From 606a96111805ff1b8f083ad15081599ee3b4ed08 Mon Sep 17 00:00:00 2001 From: AhmedEbrahim Date: Thu, 18 Apr 2024 16:41:57 +0200 Subject: [PATCH 01/77] feat(remaining_dist_eta): add initial implementation for testing remaining distance from lanelet2 library apis Signed-off-by: AhmedEbrahim --- .../mission_planner_plugin.hpp | 2 + .../src/lanelet2_plugins/default_planner.cpp | 14 ++++++ .../src/lanelet2_plugins/default_planner.hpp | 4 ++ .../src/mission_planner/mission_planner.cpp | 8 ++++ .../src/mission_planner/mission_planner.hpp | 3 ++ .../include/route_handler/route_handler.hpp | 2 +- planning/route_handler/src/route_handler.cpp | 43 +++++++++++++++++++ 7 files changed, 75 insertions(+), 1 deletion(-) diff --git a/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp b/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp index 96de30ddab592..b9b1cea21ef8b 100644 --- a/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp +++ b/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp @@ -30,6 +30,7 @@ namespace mission_planner class PlannerPlugin { public: + using Pose = geometry_msgs::msg::Pose; using RoutePoints = std::vector; using LaneletRoute = autoware_planning_msgs::msg::LaneletRoute; using HADMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; @@ -40,6 +41,7 @@ class PlannerPlugin virtual void initialize(rclcpp::Node * node, const HADMapBin::ConstSharedPtr msg) = 0; virtual bool ready() const = 0; virtual LaneletRoute plan(const RoutePoints & points) = 0; + virtual void calculateRemainingDistance(const Pose & current_vehicle_pose) = 0; virtual MarkerArray visualize(const LaneletRoute & route) const = 0; virtual void updateRoute(const LaneletRoute & route) = 0; virtual void clearRoute() = 0; diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index 4bc0f21dd947b..c24e639cee4a2 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -158,6 +158,17 @@ void DefaultPlanner::initialize_common(rclcpp::Node * node) param_.consider_no_drivable_lanes = node_->declare_parameter("consider_no_drivable_lanes"); param_.check_footprint_inside_lanes = node_->declare_parameter("check_footprint_inside_lanes"); + +} + +void DefaultPlanner::calculateRemainingDistance(const Pose & current_vehicle_pose) +{ + if (is_route_planned) { + const auto logger = node_->get_logger(); + double remaining_distance = route_handler_.getRemainingDistance(current_vehicle_pose, goal_pose_); + + RCLCPP_INFO_STREAM(logger, "Remaining Distance = " << remaining_distance); + } } void DefaultPlanner::initialize(rclcpp::Node * node) @@ -440,6 +451,9 @@ PlannerPlugin::LaneletRoute DefaultPlanner::plan(const RoutePoints & points) const auto refined_goal = refine_goal_height(goal_pose, route_sections); RCLCPP_DEBUG(logger, "Goal Pose Z : %lf", refined_goal.position.z); + is_route_planned = true; + goal_pose_ = refined_goal; + // The header is assigned by mission planner. route_msg.start_pose = points.front(); route_msg.goal_pose = refined_goal; diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp index 9f1a9d206e376..53a49b3f3a2ee 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp @@ -51,6 +51,7 @@ class DefaultPlanner : public mission_planner::PlannerPlugin MarkerArray visualize(const LaneletRoute & route) const override; MarkerArray visualize_debug_footprint(tier4_autoware_utils::LinearRing2d goal_footprint_) const; vehicle_info_util::VehicleInfo vehicle_info_; + void calculateRemainingDistance(const Pose & current_vehicle_pose) override; private: using RouteSections = std::vector; @@ -62,6 +63,8 @@ class DefaultPlanner : public mission_planner::PlannerPlugin lanelet::ConstLanelets road_lanelets_; lanelet::ConstLanelets shoulder_lanelets_; route_handler::RouteHandler route_handler_; + bool is_route_planned{false}; + Pose goal_pose_; DefaultPlannerParameters param_; @@ -71,6 +74,7 @@ class DefaultPlanner : public mission_planner::PlannerPlugin void initialize_common(rclcpp::Node * node); void map_callback(const HADMapBin::ConstSharedPtr msg); + void calculateRemainingDistance(Pose & current_vehicle_pose); /** * @brief check if the goal_footprint is within the combined lanelet of route_lanelets plus the diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index e9a0108cdaa24..bcf77821bb26c 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -84,9 +84,16 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) const auto period = rclcpp::Rate(10).period(); data_check_timer_ = create_wall_timer(period, [this] { check_initialization(); }); + remaining_distance_timer_ = this->create_wall_timer(std::chrono::milliseconds(500), std::bind(&MissionPlanner::remaining_distance_timer_callback_, this)); + logger_configure_ = std::make_unique(this); } +void MissionPlanner::remaining_distance_timer_callback_() +{ + planner_->calculateRemainingDistance(current_vehicle_pose); +} + void MissionPlanner::check_initialization() { auto logger = get_logger(); @@ -113,6 +120,7 @@ void MissionPlanner::check_initialization() void MissionPlanner::on_odometry(const Odometry::ConstSharedPtr msg) { odometry_ = msg; + current_vehicle_pose = odometry_->pose.pose; // NOTE: Do not check in the other states as goal may change. if (state_.state == RouteState::SET) { diff --git a/planning/mission_planner/src/mission_planner/mission_planner.hpp b/planning/mission_planner/src/mission_planner/mission_planner.hpp index 8016851d5a7d3..f967b6f03f3dd 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.hpp @@ -124,12 +124,15 @@ class MissionPlanner : public rclcpp::Node rclcpp::TimerBase::SharedPtr data_check_timer_; void check_initialization(); + rclcpp::TimerBase::SharedPtr remaining_distance_timer_; + void remaining_distance_timer_callback_(); double reroute_time_threshold_; double minimum_reroute_length_; bool check_reroute_safety(const LaneletRoute & original_route, const LaneletRoute & target_route); std::unique_ptr logger_configure_; + Pose current_vehicle_pose; }; } // namespace mission_planner diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index ac8e472b2f943..d24f755ae840c 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -355,7 +355,7 @@ class RouteHandler lanelet::ConstPolygon3d getIntersectionAreaById(const lanelet::Id id) const; bool isPreferredLane(const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getClosestLanelets(const geometry_msgs::msg::Pose & target_pose) const; - + double getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_); private: // MUST lanelet::routing::RoutingGraphPtr routing_graph_ptr_; diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 76763821998bd..d7b58c2493b38 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -2260,6 +2260,49 @@ bool RouteHandler::hasNoDrivableLaneInPath(const lanelet::routing::LaneletPath & return false; } +double RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_) +{ + double length = 0.0; + double first_lane_length = 0.0; + size_t counter = 0; + lanelet::ConstLanelet goal_lanelet; + getGoalLanelet(&goal_lanelet); + + lanelet::ConstLanelet current_lanelet; + getClosestLaneletWithinRoute(current_pose, ¤t_lanelet); + + const lanelet::Optional optional_route = + routing_graph_ptr_->getRoute(current_lanelet, goal_lanelet, 0); + + lanelet::routing::LaneletPath shortest_path; + shortest_path = optional_route->shortestPath(); + lanelet::ConstLanelets first_lanelets_; + lanelet::ConstLanelets last_lanelets_; + for(auto & llt : shortest_path){ + if(counter == 0){ + first_lanelets_.push_back(llt); + first_lane_length = lanelet::utils::getLaneletLength2d(llt); + } + else if(counter == (shortest_path.size() - 1)){ + last_lanelets_.push_back(llt); + } + else{ + length += lanelet::utils::getLaneletLength2d(llt); + + } + counter++; + + } + //lanelet::LaneletSequence lanelet_seq = shortest_path.getRemainingLane(shortest_path.begin()); + lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates(first_lanelets_, current_pose); + double llng = first_lane_length - arc_coord.length; + lanelet::ArcCoordinates arc_coord2 = lanelet::utils::getArcCoordinates(last_lanelets_, goal_pose_); + double llng2 = arc_coord2.length; + + + return (length + llng + llng2); +} + bool RouteHandler::findDrivableLanePath( const lanelet::ConstLanelet & start_lanelet, const lanelet::ConstLanelet & goal_lanelet, lanelet::routing::LaneletPath & drivable_lane_path) const From 235039d50530bd468e9fbb1dd074486d6ff75a20 Mon Sep 17 00:00:00 2001 From: AhmedEbrahim Date: Fri, 19 Apr 2024 13:16:25 +0200 Subject: [PATCH 02/77] feat(remaining_dist_eta): add initial implementation for ETA Signed-off-by: AhmedEbrahim --- .../mission_planner_plugin.hpp | 2 +- .../src/lanelet2_plugins/default_planner.cpp | 29 +++++- .../src/lanelet2_plugins/default_planner.hpp | 2 +- .../src/mission_planner/mission_planner.cpp | 3 +- .../src/mission_planner/mission_planner.hpp | 1 + .../include/route_handler/route_handler.hpp | 9 ++ planning/route_handler/src/route_handler.cpp | 92 ++++++++++++++----- 7 files changed, 109 insertions(+), 29 deletions(-) diff --git a/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp b/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp index b9b1cea21ef8b..f2808b58ba45a 100644 --- a/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp +++ b/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp @@ -41,7 +41,7 @@ class PlannerPlugin virtual void initialize(rclcpp::Node * node, const HADMapBin::ConstSharedPtr msg) = 0; virtual bool ready() const = 0; virtual LaneletRoute plan(const RoutePoints & points) = 0; - virtual void calculateRemainingDistance(const Pose & current_vehicle_pose) = 0; + virtual void calculateRemainingDistance(const Pose & current_vehicle_pose, const geometry_msgs::msg::Vector3 & current_vehicle_velocity) = 0; virtual MarkerArray visualize(const LaneletRoute & route) const = 0; virtual void updateRoute(const LaneletRoute & route) = 0; virtual void clearRoute() = 0; diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index c24e639cee4a2..220f557d7819e 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -161,13 +161,36 @@ void DefaultPlanner::initialize_common(rclcpp::Node * node) } -void DefaultPlanner::calculateRemainingDistance(const Pose & current_vehicle_pose) +void DefaultPlanner::calculateRemainingDistance(const Pose & current_vehicle_pose, const geometry_msgs::msg::Vector3 & current_vehicle_velocity) { if (is_route_planned) { const auto logger = node_->get_logger(); double remaining_distance = route_handler_.getRemainingDistance(current_vehicle_pose, goal_pose_); - - RCLCPP_INFO_STREAM(logger, "Remaining Distance = " << remaining_distance); + + double current_veh_vel_mag = std::sqrt(current_vehicle_velocity.x * current_vehicle_velocity.x + current_vehicle_velocity.y + current_vehicle_velocity.y); + RCLCPP_INFO_STREAM(logger, "current_vehicle_velocity.x = " << current_vehicle_velocity.x); + RCLCPP_INFO_STREAM(logger, "current_vehicle_velocity.y = " << current_vehicle_velocity.y); + RCLCPP_INFO_STREAM(logger, "current_veh_vel_mag = " << current_veh_vel_mag); + + // double eta = remaining_distance / current_veh_vel_mag; + route_handler::EstimatedTimeOfArrival eta = route_handler_.getEstimatedTimeOfArrival(remaining_distance, current_vehicle_velocity); + //uint8_t seconds = route_handler_.getEstimatedTimeOfArrival(remaining_distance, current_vehicle_velocity).seconds; + //const auto eta = route_handler_.getEsatimatedTimeOfArrival(remaining_distance, current_vehicle_velocity); + + RCLCPP_INFO_STREAM(logger, "Remaining Distance = " << remaining_distance << " m"); + // double remaining_time = remaining_distance / current_veh_vel_mag; + // RCLCPP_INFO_STREAM(logger, "remaining_time = " << remaining_time); + // double hours = static_cast(remaining_time / 3600); + // RCLCPP_INFO_STREAM(logger, "hours = " << hours); + // remaining_time = std::fmod(remaining_time, 3600); + // RCLCPP_INFO_STREAM(logger, "remaining_time = " << remaining_time); + // double minutes = static_cast(remaining_time / 60); + // RCLCPP_INFO_STREAM(logger, "minutes = " << minutes); + // double seconds = static_cast(fmod(remaining_time, 60)); + // RCLCPP_INFO_STREAM(logger, "seconds = " << seconds); + RCLCPP_INFO_STREAM(logger, "hours = " << eta.hours); + RCLCPP_INFO_STREAM(logger, "minutes = " << eta.minutes); + RCLCPP_INFO_STREAM(logger, "seconds = " << eta.seconds); } } diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp index 53a49b3f3a2ee..f5037b9c8ba8a 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp @@ -51,7 +51,7 @@ class DefaultPlanner : public mission_planner::PlannerPlugin MarkerArray visualize(const LaneletRoute & route) const override; MarkerArray visualize_debug_footprint(tier4_autoware_utils::LinearRing2d goal_footprint_) const; vehicle_info_util::VehicleInfo vehicle_info_; - void calculateRemainingDistance(const Pose & current_vehicle_pose) override; + void calculateRemainingDistance(const Pose & current_vehicle_pose, const geometry_msgs::msg::Vector3 & current_vehicle_velocity) override; private: using RouteSections = std::vector; diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index bcf77821bb26c..7de64c0fb37b6 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -91,7 +91,7 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) void MissionPlanner::remaining_distance_timer_callback_() { - planner_->calculateRemainingDistance(current_vehicle_pose); + planner_->calculateRemainingDistance(current_vehicle_pose, current_vehicle_velocity); } void MissionPlanner::check_initialization() @@ -121,6 +121,7 @@ void MissionPlanner::on_odometry(const Odometry::ConstSharedPtr msg) { odometry_ = msg; current_vehicle_pose = odometry_->pose.pose; + current_vehicle_velocity = odometry_->twist.twist.linear; // NOTE: Do not check in the other states as goal may change. if (state_.state == RouteState::SET) { diff --git a/planning/mission_planner/src/mission_planner/mission_planner.hpp b/planning/mission_planner/src/mission_planner/mission_planner.hpp index f967b6f03f3dd..1c7ead45d285d 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.hpp @@ -133,6 +133,7 @@ class MissionPlanner : public rclcpp::Node std::unique_ptr logger_configure_; Pose current_vehicle_pose; + geometry_msgs::msg::Vector3 current_vehicle_velocity; }; } // namespace mission_planner diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index d24f755ae840c..1c8efaee44edd 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -22,6 +22,7 @@ #include #include #include +#include #include #include @@ -49,6 +50,11 @@ using RouteSections = std::vector; enum class Direction { NONE, LEFT, RIGHT }; enum class PullOverDirection { NONE, LEFT, RIGHT }; enum class PullOutDirection { NONE, LEFT, RIGHT }; +struct EstimatedTimeOfArrival { + double hours; + double minutes; + double seconds; +}; class RouteHandler { @@ -356,6 +362,7 @@ class RouteHandler bool isPreferredLane(const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getClosestLanelets(const geometry_msgs::msg::Pose & target_pose) const; double getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_); + EstimatedTimeOfArrival getEstimatedTimeOfArrival(const double & remaining_distance, const geometry_msgs::msg::Vector3 & current_vehicle_velocity); private: // MUST lanelet::routing::RoutingGraphPtr routing_graph_ptr_; @@ -379,6 +386,8 @@ class RouteHandler Pose original_start_pose_; Pose original_goal_pose_; + EstimatedTimeOfArrival eta; + // non-const methods void setLaneletsFromRouteMsg(); diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index d7b58c2493b38..0ba8fe0ad6036 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -2260,11 +2260,17 @@ bool RouteHandler::hasNoDrivableLaneInPath(const lanelet::routing::LaneletPath & return false; } -double RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_) -{ +double RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_) +{/** + +double dist_to_goal = lanelet::geometry::toArcCoordinates( + lanelet::utils::to2D(lanelet.centerline()), + lanelet::utils::to2D(target_goal_position).basicPoint()) + .length; +*/ + static bool is_first_time{true}; double length = 0.0; - double first_lane_length = 0.0; - size_t counter = 0; + size_t counter = 0; lanelet::ConstLanelet goal_lanelet; getGoalLanelet(&goal_lanelet); @@ -2272,35 +2278,75 @@ double RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose getClosestLaneletWithinRoute(current_pose, ¤t_lanelet); const lanelet::Optional optional_route = - routing_graph_ptr_->getRoute(current_lanelet, goal_lanelet, 0); + routing_graph_ptr_->getRoute(current_lanelet, goal_lanelet, 0); lanelet::routing::LaneletPath shortest_path; shortest_path = optional_route->shortestPath(); - lanelet::ConstLanelets first_lanelets_; - lanelet::ConstLanelets last_lanelets_; - for(auto & llt : shortest_path){ - if(counter == 0){ - first_lanelets_.push_back(llt); - first_lane_length = lanelet::utils::getLaneletLength2d(llt); - } - else if(counter == (shortest_path.size() - 1)){ - last_lanelets_.push_back(llt); + lanelet::ConstLanelets tmp_const_lanelets; + + for (auto & llt : shortest_path) { + if (shortest_path.size() == 1 && is_first_time) { + tmp_const_lanelets.push_back(llt); + lanelet::ArcCoordinates arc_coord = + lanelet::utils::getArcCoordinates(tmp_const_lanelets, current_pose); + double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt); + length += this_lanelet_length - arc_coord.length; + break; } - else{ - length += lanelet::utils::getLaneletLength2d(llt); + if(shortest_path.size() == 1 && !is_first_time) { + length += tier4_autoware_utils::calcDistance2d(current_pose.position, goal_pose_.position); + break; + + } + + if (counter == 0) { + is_first_time = false; + tmp_const_lanelets.push_back(llt); + lanelet::ArcCoordinates arc_coord = + lanelet::utils::getArcCoordinates(tmp_const_lanelets, current_pose); + double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt); + length += this_lanelet_length - arc_coord.length; + } else if (counter == (shortest_path.size() - 1)) { + tmp_const_lanelets.push_back(llt); + lanelet::ArcCoordinates arc_coord = + lanelet::utils::getArcCoordinates(tmp_const_lanelets, goal_pose_); + length += arc_coord.length; + } else { + length += lanelet::utils::getLaneletLength2d(llt); } + counter++; - + tmp_const_lanelets.clear(); } - //lanelet::LaneletSequence lanelet_seq = shortest_path.getRemainingLane(shortest_path.begin()); - lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates(first_lanelets_, current_pose); - double llng = first_lane_length - arc_coord.length; - lanelet::ArcCoordinates arc_coord2 = lanelet::utils::getArcCoordinates(last_lanelets_, goal_pose_); - double llng2 = arc_coord2.length; + return length; +} + +EstimatedTimeOfArrival RouteHandler::getEstimatedTimeOfArrival(const double & remaining_distance, const geometry_msgs::msg::Vector3 & current_vehicle_velocity) +{ + + double current_velocity_norm = std::sqrt( + current_vehicle_velocity.x * current_vehicle_velocity.x + + current_vehicle_velocity.y * current_vehicle_velocity.y); + + if(remaining_distance < 0.0001 || current_velocity_norm < 0.0001){ + eta.hours = 0; + eta.minutes = 0; + eta.seconds = 0; + return eta; + } - return (length + llng + llng2); + double remaining_time = remaining_distance / current_velocity_norm; + eta.hours = remaining_time / 3600; + remaining_time = std::fmod(remaining_time, 3600); + eta.minutes = remaining_time / 60; + eta.seconds = fmod(remaining_time, 60); + // eta.hours = static_cast(remaining_time / 3600); + // remaining_time = std::fmod(remaining_time, 3600); + // eta.minutes = static_cast(remaining_time / 60); + // eta.seconds = static_cast(fmod(remaining_time, 60)); + return eta; } bool RouteHandler::findDrivableLanePath( From e0a9843b5a733ebbd1172e10901272b54b0f639d Mon Sep 17 00:00:00 2001 From: AhmedEbrahim Date: Fri, 19 Apr 2024 13:41:19 +0200 Subject: [PATCH 03/77] feat(remaining_dist_eta): change eta values to uint8 Signed-off-by: AhmedEbrahim --- .../src/lanelet2_plugins/default_planner.cpp | 7 ++++--- .../include/route_handler/route_handler.hpp | 6 +++--- planning/route_handler/src/route_handler.cpp | 14 +++++++------- 3 files changed, 14 insertions(+), 13 deletions(-) diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index 220f557d7819e..d75ed5e5b162f 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -178,6 +178,7 @@ void DefaultPlanner::calculateRemainingDistance(const Pose & current_vehicle_pos //const auto eta = route_handler_.getEsatimatedTimeOfArrival(remaining_distance, current_vehicle_velocity); RCLCPP_INFO_STREAM(logger, "Remaining Distance = " << remaining_distance << " m"); + RCLCPP_INFO_STREAM(logger, "ETA = " << unsigned(eta.hours) << "H : " << unsigned(eta.minutes) << "M : " << unsigned(eta.seconds) << "S"); // double remaining_time = remaining_distance / current_veh_vel_mag; // RCLCPP_INFO_STREAM(logger, "remaining_time = " << remaining_time); // double hours = static_cast(remaining_time / 3600); @@ -188,9 +189,9 @@ void DefaultPlanner::calculateRemainingDistance(const Pose & current_vehicle_pos // RCLCPP_INFO_STREAM(logger, "minutes = " << minutes); // double seconds = static_cast(fmod(remaining_time, 60)); // RCLCPP_INFO_STREAM(logger, "seconds = " << seconds); - RCLCPP_INFO_STREAM(logger, "hours = " << eta.hours); - RCLCPP_INFO_STREAM(logger, "minutes = " << eta.minutes); - RCLCPP_INFO_STREAM(logger, "seconds = " << eta.seconds); + // RCLCPP_INFO_STREAM(logger, "hours = " << eta.hours); + // RCLCPP_INFO_STREAM(logger, "minutes = " << eta.minutes); + // RCLCPP_INFO_STREAM(logger, "seconds = " << eta.seconds); } } diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index 1c8efaee44edd..01d3e879cfab3 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -51,9 +51,9 @@ enum class Direction { NONE, LEFT, RIGHT }; enum class PullOverDirection { NONE, LEFT, RIGHT }; enum class PullOutDirection { NONE, LEFT, RIGHT }; struct EstimatedTimeOfArrival { - double hours; - double minutes; - double seconds; + uint8_t hours; + uint8_t minutes; + uint8_t seconds; }; class RouteHandler diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 0ba8fe0ad6036..d97981a114518 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -2338,14 +2338,14 @@ EstimatedTimeOfArrival RouteHandler::getEstimatedTimeOfArrival(const double & re } double remaining_time = remaining_distance / current_velocity_norm; - eta.hours = remaining_time / 3600; - remaining_time = std::fmod(remaining_time, 3600); - eta.minutes = remaining_time / 60; - eta.seconds = fmod(remaining_time, 60); - // eta.hours = static_cast(remaining_time / 3600); + // eta.hours = remaining_time / 3600; // remaining_time = std::fmod(remaining_time, 3600); - // eta.minutes = static_cast(remaining_time / 60); - // eta.seconds = static_cast(fmod(remaining_time, 60)); + // eta.minutes = remaining_time / 60; + // eta.seconds = fmod(remaining_time, 60); + eta.hours = static_cast(remaining_time / 3600.0); + remaining_time = std::fmod(remaining_time, 3600); + eta.minutes = static_cast(remaining_time / 60.0); + eta.seconds = static_cast(fmod(remaining_time, 60.0)); return eta; } From 96c8ea7131fa16a4cc5c7a3ac886c54cd96b3513 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Sat, 20 Apr 2024 01:05:20 +0200 Subject: [PATCH 04/77] feat(remaining_dist_eta): add publisher and using the remaining distance and eta functions from behavior path planner run Signed-off-by: Ahmed Ebrahim --- .../behavior_planning.launch.xml | 1 + .../behavior_path_planner_node.hpp | 15 ++++++++++++ .../launch/behavior_path_planner.launch.xml | 1 + .../src/behavior_path_planner_node.cpp | 24 +++++++++++++++++++ .../src/mission_planner/mission_planner.cpp | 2 +- 5 files changed, 42 insertions(+), 1 deletion(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index aa649710836da..766101a434934 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -194,6 +194,7 @@ + diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index 5a49f4d9ab66e..e136e6b10ca81 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -32,8 +32,10 @@ #include #include #include +#include #include #include +#include #include #include #include @@ -62,8 +64,10 @@ using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand; using autoware_perception_msgs::msg::TrafficSignalArray; using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::PoseWithUuidStamped; +using autoware_planning_msgs::msg::RemainingDistanceETA; using nav_msgs::msg::OccupancyGrid; using nav_msgs::msg::Odometry; +using geometry_msgs::msg::Pose; using rcl_interfaces::msg::SetParametersResult; using steering_factor_interface::SteeringFactorInterface; using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; @@ -98,6 +102,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node rclcpp::Subscription::SharedPtr lateral_offset_subscriber_; rclcpp::Subscription::SharedPtr operation_mode_subscriber_; rclcpp::Publisher::SharedPtr path_publisher_; + rclcpp::Publisher::SharedPtr remaining_distance_eta_publisher_; rclcpp::Publisher::SharedPtr turn_signal_publisher_; rclcpp::Publisher::SharedPtr hazard_signal_publisher_; rclcpp::Publisher::SharedPtr bound_publisher_; @@ -123,6 +128,10 @@ class BehaviorPathPlannerNode : public rclcpp::Node bool has_received_map_{false}; bool has_received_route_{false}; + Pose goal_pose_; + double remaining_distance_; + route_handler::EstimatedTimeOfArrival eta_; + std::mutex mutex_pd_; // mutex for planner_data_ std::mutex mutex_manager_; // mutex for bt_manager_ or planner_manager_ std::mutex mutex_map_; // mutex for has_received_map_ and map_ptr_ @@ -177,6 +186,12 @@ class BehaviorPathPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_avoidance_msg_array_publisher_; rclcpp::Publisher::SharedPtr debug_turn_signal_info_publisher_; + /** + * @brief publish remaining distance and ETA + */ + void publishRemainingDistanceETA( + const double & remaining_distance, const route_handler::EstimatedTimeOfArrival & eta) const; + /** * @brief publish reroute availability */ diff --git a/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml b/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml index 79c590363beb5..b03706e4db770 100644 --- a/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml +++ b/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml @@ -34,6 +34,7 @@ + diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index b56d1a207f76d..162834c316eaf 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -62,6 +62,7 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod // publisher path_publisher_ = create_publisher("~/output/path", 1); + remaining_distance_eta_publisher_ = create_publisher("~/output/remaining_distance_eta", rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable()); turn_signal_publisher_ = create_publisher("~/output/turn_indicators_cmd", 1); hazard_signal_publisher_ = create_publisher("~/output/hazard_lights_cmd", 1); @@ -383,6 +384,7 @@ void BehaviorPathPlannerNode::run() planner_data_->prev_modified_goal.reset(); } planner_manager_->resetCurrentRouteLanelet(planner_data_); + goal_pose_ = route_ptr->goal_pose; } const auto controlled_by_autoware_autonomously = planner_data_->operation_mode->mode == OperationModeState::AUTONOMOUS && @@ -390,6 +392,16 @@ void BehaviorPathPlannerNode::run() if (!controlled_by_autoware_autonomously && !planner_manager_->hasApprovedModules()) planner_manager_->resetCurrentRouteLanelet(planner_data_); + if (planner_data_->route_handler->isHandlerReady()) { + remaining_distance_ = planner_data_->route_handler->getRemainingDistance( + planner_data_->self_odometry->pose.pose, goal_pose_); + + eta_ = planner_data_->route_handler->getEstimatedTimeOfArrival( + remaining_distance_, planner_data_->self_odometry->twist.twist.linear); + + publishRemainingDistanceETA(remaining_distance_, eta_); + } + // run behavior planner const auto output = planner_manager_->run(planner_data_); @@ -525,6 +537,18 @@ void BehaviorPathPlannerNode::publish_reroute_availability() const reroute_availability_publisher_->publish(is_reroute_available); } +void BehaviorPathPlannerNode::publishRemainingDistanceETA(const double & remaining_distance, const route_handler::EstimatedTimeOfArrival & eta) const +{ + RemainingDistanceETA remaining_distance_eta; + remaining_distance_eta.remaining_distance = remaining_distance; + remaining_distance_eta.hours = eta.hours; + remaining_distance_eta.minutes = eta.minutes; + remaining_distance_eta.seconds = eta.seconds; + + remaining_distance_eta_publisher_->publish(remaining_distance_eta); + +} + void BehaviorPathPlannerNode::publish_turn_signal_debug_data(const TurnSignalDebugData & debug_data) { MarkerArray marker_array; diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index 7de64c0fb37b6..87289efe88643 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -91,7 +91,7 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) void MissionPlanner::remaining_distance_timer_callback_() { - planner_->calculateRemainingDistance(current_vehicle_pose, current_vehicle_velocity); + //planner_->calculateRemainingDistance(current_vehicle_pose, current_vehicle_velocity); } void MissionPlanner::check_initialization() From 36ef21aefbbc48dd36d9d53ef896ded57e637956 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Sat, 20 Apr 2024 01:48:36 +0200 Subject: [PATCH 05/77] feat(remaining_dist_eta): removing functions usage from mission planner and default planner Signed-off-by: Ahmed Ebrahim feat(remaining_dist_eta): removing unneeded change in mission planner and default planner Signed-off-by: AhmedEbrahim feat(remaining_dist_eta): removing unneeded lines Signed-off-by: AhmedEbrahim feat(remaining_dist_eta): removing unneeded lines Signed-off-by: AhmedEbrahim --- .../mission_planner_plugin.hpp | 2 - .../src/lanelet2_plugins/default_planner.cpp | 38 ------------------- .../src/lanelet2_plugins/default_planner.hpp | 4 -- .../src/mission_planner/mission_planner.cpp | 9 ----- .../src/mission_planner/mission_planner.hpp | 4 -- 5 files changed, 57 deletions(-) diff --git a/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp b/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp index f2808b58ba45a..96de30ddab592 100644 --- a/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp +++ b/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp @@ -30,7 +30,6 @@ namespace mission_planner class PlannerPlugin { public: - using Pose = geometry_msgs::msg::Pose; using RoutePoints = std::vector; using LaneletRoute = autoware_planning_msgs::msg::LaneletRoute; using HADMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; @@ -41,7 +40,6 @@ class PlannerPlugin virtual void initialize(rclcpp::Node * node, const HADMapBin::ConstSharedPtr msg) = 0; virtual bool ready() const = 0; virtual LaneletRoute plan(const RoutePoints & points) = 0; - virtual void calculateRemainingDistance(const Pose & current_vehicle_pose, const geometry_msgs::msg::Vector3 & current_vehicle_velocity) = 0; virtual MarkerArray visualize(const LaneletRoute & route) const = 0; virtual void updateRoute(const LaneletRoute & route) = 0; virtual void clearRoute() = 0; diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index d75ed5e5b162f..4bc0f21dd947b 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -158,41 +158,6 @@ void DefaultPlanner::initialize_common(rclcpp::Node * node) param_.consider_no_drivable_lanes = node_->declare_parameter("consider_no_drivable_lanes"); param_.check_footprint_inside_lanes = node_->declare_parameter("check_footprint_inside_lanes"); - -} - -void DefaultPlanner::calculateRemainingDistance(const Pose & current_vehicle_pose, const geometry_msgs::msg::Vector3 & current_vehicle_velocity) -{ - if (is_route_planned) { - const auto logger = node_->get_logger(); - double remaining_distance = route_handler_.getRemainingDistance(current_vehicle_pose, goal_pose_); - - double current_veh_vel_mag = std::sqrt(current_vehicle_velocity.x * current_vehicle_velocity.x + current_vehicle_velocity.y + current_vehicle_velocity.y); - RCLCPP_INFO_STREAM(logger, "current_vehicle_velocity.x = " << current_vehicle_velocity.x); - RCLCPP_INFO_STREAM(logger, "current_vehicle_velocity.y = " << current_vehicle_velocity.y); - RCLCPP_INFO_STREAM(logger, "current_veh_vel_mag = " << current_veh_vel_mag); - - // double eta = remaining_distance / current_veh_vel_mag; - route_handler::EstimatedTimeOfArrival eta = route_handler_.getEstimatedTimeOfArrival(remaining_distance, current_vehicle_velocity); - //uint8_t seconds = route_handler_.getEstimatedTimeOfArrival(remaining_distance, current_vehicle_velocity).seconds; - //const auto eta = route_handler_.getEsatimatedTimeOfArrival(remaining_distance, current_vehicle_velocity); - - RCLCPP_INFO_STREAM(logger, "Remaining Distance = " << remaining_distance << " m"); - RCLCPP_INFO_STREAM(logger, "ETA = " << unsigned(eta.hours) << "H : " << unsigned(eta.minutes) << "M : " << unsigned(eta.seconds) << "S"); - // double remaining_time = remaining_distance / current_veh_vel_mag; - // RCLCPP_INFO_STREAM(logger, "remaining_time = " << remaining_time); - // double hours = static_cast(remaining_time / 3600); - // RCLCPP_INFO_STREAM(logger, "hours = " << hours); - // remaining_time = std::fmod(remaining_time, 3600); - // RCLCPP_INFO_STREAM(logger, "remaining_time = " << remaining_time); - // double minutes = static_cast(remaining_time / 60); - // RCLCPP_INFO_STREAM(logger, "minutes = " << minutes); - // double seconds = static_cast(fmod(remaining_time, 60)); - // RCLCPP_INFO_STREAM(logger, "seconds = " << seconds); - // RCLCPP_INFO_STREAM(logger, "hours = " << eta.hours); - // RCLCPP_INFO_STREAM(logger, "minutes = " << eta.minutes); - // RCLCPP_INFO_STREAM(logger, "seconds = " << eta.seconds); - } } void DefaultPlanner::initialize(rclcpp::Node * node) @@ -475,9 +440,6 @@ PlannerPlugin::LaneletRoute DefaultPlanner::plan(const RoutePoints & points) const auto refined_goal = refine_goal_height(goal_pose, route_sections); RCLCPP_DEBUG(logger, "Goal Pose Z : %lf", refined_goal.position.z); - is_route_planned = true; - goal_pose_ = refined_goal; - // The header is assigned by mission planner. route_msg.start_pose = points.front(); route_msg.goal_pose = refined_goal; diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp index f5037b9c8ba8a..9f1a9d206e376 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp @@ -51,7 +51,6 @@ class DefaultPlanner : public mission_planner::PlannerPlugin MarkerArray visualize(const LaneletRoute & route) const override; MarkerArray visualize_debug_footprint(tier4_autoware_utils::LinearRing2d goal_footprint_) const; vehicle_info_util::VehicleInfo vehicle_info_; - void calculateRemainingDistance(const Pose & current_vehicle_pose, const geometry_msgs::msg::Vector3 & current_vehicle_velocity) override; private: using RouteSections = std::vector; @@ -63,8 +62,6 @@ class DefaultPlanner : public mission_planner::PlannerPlugin lanelet::ConstLanelets road_lanelets_; lanelet::ConstLanelets shoulder_lanelets_; route_handler::RouteHandler route_handler_; - bool is_route_planned{false}; - Pose goal_pose_; DefaultPlannerParameters param_; @@ -74,7 +71,6 @@ class DefaultPlanner : public mission_planner::PlannerPlugin void initialize_common(rclcpp::Node * node); void map_callback(const HADMapBin::ConstSharedPtr msg); - void calculateRemainingDistance(Pose & current_vehicle_pose); /** * @brief check if the goal_footprint is within the combined lanelet of route_lanelets plus the diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index 87289efe88643..e9a0108cdaa24 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -84,16 +84,9 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) const auto period = rclcpp::Rate(10).period(); data_check_timer_ = create_wall_timer(period, [this] { check_initialization(); }); - remaining_distance_timer_ = this->create_wall_timer(std::chrono::milliseconds(500), std::bind(&MissionPlanner::remaining_distance_timer_callback_, this)); - logger_configure_ = std::make_unique(this); } -void MissionPlanner::remaining_distance_timer_callback_() -{ - //planner_->calculateRemainingDistance(current_vehicle_pose, current_vehicle_velocity); -} - void MissionPlanner::check_initialization() { auto logger = get_logger(); @@ -120,8 +113,6 @@ void MissionPlanner::check_initialization() void MissionPlanner::on_odometry(const Odometry::ConstSharedPtr msg) { odometry_ = msg; - current_vehicle_pose = odometry_->pose.pose; - current_vehicle_velocity = odometry_->twist.twist.linear; // NOTE: Do not check in the other states as goal may change. if (state_.state == RouteState::SET) { diff --git a/planning/mission_planner/src/mission_planner/mission_planner.hpp b/planning/mission_planner/src/mission_planner/mission_planner.hpp index 1c7ead45d285d..8016851d5a7d3 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.hpp @@ -124,16 +124,12 @@ class MissionPlanner : public rclcpp::Node rclcpp::TimerBase::SharedPtr data_check_timer_; void check_initialization(); - rclcpp::TimerBase::SharedPtr remaining_distance_timer_; - void remaining_distance_timer_callback_(); double reroute_time_threshold_; double minimum_reroute_length_; bool check_reroute_safety(const LaneletRoute & original_route, const LaneletRoute & target_route); std::unique_ptr logger_configure_; - Pose current_vehicle_pose; - geometry_msgs::msg::Vector3 current_vehicle_velocity; }; } // namespace mission_planner From 275526582a774473f6e09b257ee0dbfc1a5f990f Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 19 Apr 2024 23:56:26 +0000 Subject: [PATCH 06/77] style(pre-commit): autofix --- .../behavior_path_planner_node.hpp | 6 +++--- .../src/behavior_path_planner_node.cpp | 8 ++++--- .../include/route_handler/route_handler.hpp | 8 +++++-- planning/route_handler/src/route_handler.cpp | 21 +++++++++---------- 4 files changed, 24 insertions(+), 19 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index e136e6b10ca81..1e69ad72734c4 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -33,9 +33,9 @@ #include #include #include +#include #include #include -#include #include #include #include @@ -65,9 +65,9 @@ using autoware_perception_msgs::msg::TrafficSignalArray; using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::PoseWithUuidStamped; using autoware_planning_msgs::msg::RemainingDistanceETA; +using geometry_msgs::msg::Pose; using nav_msgs::msg::OccupancyGrid; using nav_msgs::msg::Odometry; -using geometry_msgs::msg::Pose; using rcl_interfaces::msg::SetParametersResult; using steering_factor_interface::SteeringFactorInterface; using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; @@ -191,7 +191,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node */ void publishRemainingDistanceETA( const double & remaining_distance, const route_handler::EstimatedTimeOfArrival & eta) const; - + /** * @brief publish reroute availability */ diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 162834c316eaf..1fadbd1ac6269 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -62,7 +62,9 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod // publisher path_publisher_ = create_publisher("~/output/path", 1); - remaining_distance_eta_publisher_ = create_publisher("~/output/remaining_distance_eta", rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable()); + remaining_distance_eta_publisher_ = create_publisher( + "~/output/remaining_distance_eta", + rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable()); turn_signal_publisher_ = create_publisher("~/output/turn_indicators_cmd", 1); hazard_signal_publisher_ = create_publisher("~/output/hazard_lights_cmd", 1); @@ -537,7 +539,8 @@ void BehaviorPathPlannerNode::publish_reroute_availability() const reroute_availability_publisher_->publish(is_reroute_available); } -void BehaviorPathPlannerNode::publishRemainingDistanceETA(const double & remaining_distance, const route_handler::EstimatedTimeOfArrival & eta) const +void BehaviorPathPlannerNode::publishRemainingDistanceETA( + const double & remaining_distance, const route_handler::EstimatedTimeOfArrival & eta) const { RemainingDistanceETA remaining_distance_eta; remaining_distance_eta.remaining_distance = remaining_distance; @@ -546,7 +549,6 @@ void BehaviorPathPlannerNode::publishRemainingDistanceETA(const double & remaini remaining_distance_eta.seconds = eta.seconds; remaining_distance_eta_publisher_->publish(remaining_distance_eta); - } void BehaviorPathPlannerNode::publish_turn_signal_debug_data(const TurnSignalDebugData & debug_data) diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index 01d3e879cfab3..e4c05538fa46e 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -50,7 +50,8 @@ using RouteSections = std::vector; enum class Direction { NONE, LEFT, RIGHT }; enum class PullOverDirection { NONE, LEFT, RIGHT }; enum class PullOutDirection { NONE, LEFT, RIGHT }; -struct EstimatedTimeOfArrival { +struct EstimatedTimeOfArrival +{ uint8_t hours; uint8_t minutes; uint8_t seconds; @@ -362,7 +363,10 @@ class RouteHandler bool isPreferredLane(const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getClosestLanelets(const geometry_msgs::msg::Pose & target_pose) const; double getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_); - EstimatedTimeOfArrival getEstimatedTimeOfArrival(const double & remaining_distance, const geometry_msgs::msg::Vector3 & current_vehicle_velocity); + EstimatedTimeOfArrival getEstimatedTimeOfArrival( + const double & remaining_distance, + const geometry_msgs::msg::Vector3 & current_vehicle_velocity); + private: // MUST lanelet::routing::RoutingGraphPtr routing_graph_ptr_; diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index d97981a114518..71898d2bafa5e 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -2261,13 +2261,13 @@ bool RouteHandler::hasNoDrivableLaneInPath(const lanelet::routing::LaneletPath & } double RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_) -{/** +{ /** -double dist_to_goal = lanelet::geometry::toArcCoordinates( - lanelet::utils::to2D(lanelet.centerline()), - lanelet::utils::to2D(target_goal_position).basicPoint()) - .length; -*/ + double dist_to_goal = lanelet::geometry::toArcCoordinates( + lanelet::utils::to2D(lanelet.centerline()), + lanelet::utils::to2D(target_goal_position).basicPoint()) + .length; + */ static bool is_first_time{true}; double length = 0.0; size_t counter = 0; @@ -2294,10 +2294,9 @@ double dist_to_goal = lanelet::geometry::toArcCoordinates( break; } - if(shortest_path.size() == 1 && !is_first_time) { + if (shortest_path.size() == 1 && !is_first_time) { length += tier4_autoware_utils::calcDistance2d(current_pose.position, goal_pose_.position); break; - } if (counter == 0) { @@ -2323,14 +2322,14 @@ double dist_to_goal = lanelet::geometry::toArcCoordinates( return length; } -EstimatedTimeOfArrival RouteHandler::getEstimatedTimeOfArrival(const double & remaining_distance, const geometry_msgs::msg::Vector3 & current_vehicle_velocity) +EstimatedTimeOfArrival RouteHandler::getEstimatedTimeOfArrival( + const double & remaining_distance, const geometry_msgs::msg::Vector3 & current_vehicle_velocity) { - double current_velocity_norm = std::sqrt( current_vehicle_velocity.x * current_vehicle_velocity.x + current_vehicle_velocity.y * current_vehicle_velocity.y); - if(remaining_distance < 0.0001 || current_velocity_norm < 0.0001){ + if (remaining_distance < 0.0001 || current_velocity_norm < 0.0001) { eta.hours = 0; eta.minutes = 0; eta.seconds = 0; From 7d3247c553d5d6d0fb67344fb701acf912205c45 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Mon, 22 Apr 2024 06:27:45 +0200 Subject: [PATCH 07/77] feat(remaining_dist_eta): improving and cleaning remaining dist and eta functions Signed-off-by: Ahmed Ebrahim --- planning/route_handler/src/route_handler.cpp | 65 +++++++------------- 1 file changed, 21 insertions(+), 44 deletions(-) diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 71898d2bafa5e..b63f42794af02 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -2261,65 +2261,46 @@ bool RouteHandler::hasNoDrivableLaneInPath(const lanelet::routing::LaneletPath & } double RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_) -{ /** - - double dist_to_goal = lanelet::geometry::toArcCoordinates( - lanelet::utils::to2D(lanelet.centerline()), - lanelet::utils::to2D(target_goal_position).basicPoint()) - .length; - */ - static bool is_first_time{true}; - double length = 0.0; - size_t counter = 0; - lanelet::ConstLanelet goal_lanelet; - getGoalLanelet(&goal_lanelet); +{ + double remaining_distance = 0.0; + size_t index = 0; lanelet::ConstLanelet current_lanelet; getClosestLaneletWithinRoute(current_pose, ¤t_lanelet); + + lanelet::ConstLanelet goal_lanelet; + getGoalLanelet(&goal_lanelet); const lanelet::Optional optional_route = routing_graph_ptr_->getRoute(current_lanelet, goal_lanelet, 0); - lanelet::routing::LaneletPath shortest_path; - shortest_path = optional_route->shortestPath(); - lanelet::ConstLanelets tmp_const_lanelets; + lanelet::routing::LaneletPath remaining_shortest_path; + remaining_shortest_path = optional_route->shortestPath(); - for (auto & llt : shortest_path) { - if (shortest_path.size() == 1 && is_first_time) { - tmp_const_lanelets.push_back(llt); - lanelet::ArcCoordinates arc_coord = - lanelet::utils::getArcCoordinates(tmp_const_lanelets, current_pose); - double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt); - length += this_lanelet_length - arc_coord.length; - break; - } + for (auto & llt : remaining_shortest_path) { - if (shortest_path.size() == 1 && !is_first_time) { - length += tier4_autoware_utils::calcDistance2d(current_pose.position, goal_pose_.position); + if (remaining_shortest_path.size() == 1) { + remaining_distance += tier4_autoware_utils::calcDistance2d(current_pose.position, goal_pose_.position); break; } - if (counter == 0) { - is_first_time = false; - tmp_const_lanelets.push_back(llt); + if (index == 0) { lanelet::ArcCoordinates arc_coord = - lanelet::utils::getArcCoordinates(tmp_const_lanelets, current_pose); + lanelet::utils::getArcCoordinates({llt}, current_pose); double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt); - length += this_lanelet_length - arc_coord.length; - } else if (counter == (shortest_path.size() - 1)) { - tmp_const_lanelets.push_back(llt); + remaining_distance += this_lanelet_length - arc_coord.length; + } else if (index == (remaining_shortest_path.size() - 1)) { lanelet::ArcCoordinates arc_coord = - lanelet::utils::getArcCoordinates(tmp_const_lanelets, goal_pose_); - length += arc_coord.length; + lanelet::utils::getArcCoordinates({llt}, goal_pose_); + remaining_distance += arc_coord.length; } else { - length += lanelet::utils::getLaneletLength2d(llt); + remaining_distance += lanelet::utils::getLaneletLength2d(llt); } - counter++; - tmp_const_lanelets.clear(); + index++; } - return length; + return remaining_distance; } EstimatedTimeOfArrival RouteHandler::getEstimatedTimeOfArrival( @@ -2329,7 +2310,7 @@ EstimatedTimeOfArrival RouteHandler::getEstimatedTimeOfArrival( current_vehicle_velocity.x * current_vehicle_velocity.x + current_vehicle_velocity.y * current_vehicle_velocity.y); - if (remaining_distance < 0.0001 || current_velocity_norm < 0.0001) { + if (remaining_distance < 0.01 || current_velocity_norm < 0.01) { eta.hours = 0; eta.minutes = 0; eta.seconds = 0; @@ -2337,10 +2318,6 @@ EstimatedTimeOfArrival RouteHandler::getEstimatedTimeOfArrival( } double remaining_time = remaining_distance / current_velocity_norm; - // eta.hours = remaining_time / 3600; - // remaining_time = std::fmod(remaining_time, 3600); - // eta.minutes = remaining_time / 60; - // eta.seconds = fmod(remaining_time, 60); eta.hours = static_cast(remaining_time / 3600.0); remaining_time = std::fmod(remaining_time, 3600); eta.minutes = static_cast(remaining_time / 60.0); From a0125026f8de94cdbef0cf98493f693f3e0d8af3 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 22 Apr 2024 04:30:02 +0000 Subject: [PATCH 08/77] style(pre-commit): autofix --- planning/route_handler/src/route_handler.cpp | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index b63f42794af02..23e810d2e0aa9 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -2267,7 +2267,7 @@ double RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose lanelet::ConstLanelet current_lanelet; getClosestLaneletWithinRoute(current_pose, ¤t_lanelet); - + lanelet::ConstLanelet goal_lanelet; getGoalLanelet(&goal_lanelet); @@ -2278,20 +2278,18 @@ double RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose remaining_shortest_path = optional_route->shortestPath(); for (auto & llt : remaining_shortest_path) { - if (remaining_shortest_path.size() == 1) { - remaining_distance += tier4_autoware_utils::calcDistance2d(current_pose.position, goal_pose_.position); + remaining_distance += + tier4_autoware_utils::calcDistance2d(current_pose.position, goal_pose_.position); break; } if (index == 0) { - lanelet::ArcCoordinates arc_coord = - lanelet::utils::getArcCoordinates({llt}, current_pose); + lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, current_pose); double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt); remaining_distance += this_lanelet_length - arc_coord.length; } else if (index == (remaining_shortest_path.size() - 1)) { - lanelet::ArcCoordinates arc_coord = - lanelet::utils::getArcCoordinates({llt}, goal_pose_); + lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, goal_pose_); remaining_distance += arc_coord.length; } else { remaining_distance += lanelet::utils::getLaneletLength2d(llt); From 2d57d45f54dcd2e58eadd8f555a76543488b8e81 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Tue, 23 Apr 2024 04:59:47 +0200 Subject: [PATCH 09/77] feat(remaining_dist_eta): change in remaining dist and time calculation approach, using arc length of behavior planner generated path avoiding cost of searching the graph every time getting remaining shortest path when using lanelet2 library APIs. Signed-off-by: Ahmed Ebrahim --- .../behavior_planning.launch.xml | 2 +- .../behavior_path_planner_node.hpp | 30 +++++--- .../launch/behavior_path_planner.launch.xml | 2 +- .../src/behavior_path_planner_node.cpp | 76 +++++++++++++------ .../include/route_handler/route_handler.hpp | 12 --- planning/route_handler/src/route_handler.cpp | 63 --------------- 6 files changed, 75 insertions(+), 110 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 766101a434934..dd4fef900909f 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -194,7 +194,7 @@ - + diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index 1e69ad72734c4..6a8ebb24875b9 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -32,7 +32,7 @@ #include #include #include -#include +#include #include #include #include @@ -64,7 +64,7 @@ using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand; using autoware_perception_msgs::msg::TrafficSignalArray; using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::PoseWithUuidStamped; -using autoware_planning_msgs::msg::RemainingDistanceETA; +using autoware_planning_msgs::msg::MissionRemainingDistanceTime; using geometry_msgs::msg::Pose; using nav_msgs::msg::OccupancyGrid; using nav_msgs::msg::Odometry; @@ -78,6 +78,15 @@ using tier4_planning_msgs::msg::StopReasonArray; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; +struct RemainingDistanceTime +{ + double remaining_distance; + double remaining_time; + uint32_t hours; + uint32_t minutes; + uint32_t seconds; +}; + class BehaviorPathPlannerNode : public rclcpp::Node { public: @@ -102,7 +111,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node rclcpp::Subscription::SharedPtr lateral_offset_subscriber_; rclcpp::Subscription::SharedPtr operation_mode_subscriber_; rclcpp::Publisher::SharedPtr path_publisher_; - rclcpp::Publisher::SharedPtr remaining_distance_eta_publisher_; + rclcpp::Publisher::SharedPtr mission_remaining_distance_time_publisher_; rclcpp::Publisher::SharedPtr turn_signal_publisher_; rclcpp::Publisher::SharedPtr hazard_signal_publisher_; rclcpp::Publisher::SharedPtr bound_publisher_; @@ -129,8 +138,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node bool has_received_route_{false}; Pose goal_pose_; - double remaining_distance_; - route_handler::EstimatedTimeOfArrival eta_; + RemainingDistanceTime remaining_distance_time_; std::mutex mutex_pd_; // mutex for planner_data_ std::mutex mutex_manager_; // mutex for bt_manager_ or planner_manager_ @@ -185,12 +193,11 @@ class BehaviorPathPlannerNode : public rclcpp::Node // debug rclcpp::Publisher::SharedPtr debug_avoidance_msg_array_publisher_; rclcpp::Publisher::SharedPtr debug_turn_signal_info_publisher_; - + /** - * @brief publish remaining distance and ETA + * @brief compute mission remaining distance and time */ - void publishRemainingDistanceETA( - const double & remaining_distance, const route_handler::EstimatedTimeOfArrival & eta) const; + void computeMissionRemainingDistanceTime(const behavior_path_planner::PlanResult & path); /** * @brief publish reroute availability @@ -230,6 +237,11 @@ class BehaviorPathPlannerNode : public rclcpp::Node const std::vector> & managers, const std::shared_ptr & planner_data); + /** + * @brief publish mission remaining distance and time + */ + void publishMissionRemainingDistanceTime() const; + /** * @brief convert path with lane id to path for publish path candidate */ diff --git a/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml b/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml index b03706e4db770..32f23b7d13041 100644 --- a/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml +++ b/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml @@ -34,7 +34,7 @@ - + diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 1fadbd1ac6269..21397169a935d 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -62,8 +62,8 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod // publisher path_publisher_ = create_publisher("~/output/path", 1); - remaining_distance_eta_publisher_ = create_publisher( - "~/output/remaining_distance_eta", + mission_remaining_distance_time_publisher_ = create_publisher( + "~/output/mission_remaining_distance_time", rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable()); turn_signal_publisher_ = create_publisher("~/output/turn_indicators_cmd", 1); @@ -394,21 +394,18 @@ void BehaviorPathPlannerNode::run() if (!controlled_by_autoware_autonomously && !planner_manager_->hasApprovedModules()) planner_manager_->resetCurrentRouteLanelet(planner_data_); - if (planner_data_->route_handler->isHandlerReady()) { - remaining_distance_ = planner_data_->route_handler->getRemainingDistance( - planner_data_->self_odometry->pose.pose, goal_pose_); - - eta_ = planner_data_->route_handler->getEstimatedTimeOfArrival( - remaining_distance_, planner_data_->self_odometry->twist.twist.linear); - - publishRemainingDistanceETA(remaining_distance_, eta_); - } - // run behavior planner const auto output = planner_manager_->run(planner_data_); // path handling const auto path = getPath(output, planner_data_, planner_manager_); + + // compute remaining distance and time based on generated path + computeMissionRemainingDistanceTime(path); + + // publish remaining distance and time + publishMissionRemainingDistanceTime(); + // update planner data planner_data_->prev_output_path = path; @@ -498,6 +495,36 @@ void BehaviorPathPlannerNode::computeTurnSignal( publish_steering_factor(planner_data, turn_signal); } +void BehaviorPathPlannerNode::computeMissionRemainingDistanceTime(const behavior_path_planner::PlanResult & path) +{ + remaining_distance_time_.remaining_distance = + motion_utils::calcSignedArcLength(path->points, planner_data_->self_odometry->pose.pose.position, goal_pose_.position); + + geometry_msgs::msg::Vector3 current_vehicle_velocity = planner_data_->self_odometry->twist.twist.linear; + + double current_vehicle_velocity_norm = std::sqrt( + current_vehicle_velocity.x * current_vehicle_velocity.x + + current_vehicle_velocity.y * current_vehicle_velocity.y); + + if (remaining_distance_time_.remaining_distance < 0.01 || current_vehicle_velocity_norm < 0.01) { + remaining_distance_time_.remaining_distance = 0.0; + remaining_distance_time_.remaining_time = 0.0; + remaining_distance_time_.hours = 0; + remaining_distance_time_.minutes = 0; + remaining_distance_time_.seconds = 0; + return; + } + + double remaining_time = remaining_distance_time_.remaining_distance / current_vehicle_velocity_norm; + remaining_distance_time_.remaining_time = remaining_time; + + remaining_distance_time_.hours = static_cast(remaining_time / 3600.0); + remaining_time = std::fmod(remaining_time, 3600); + remaining_distance_time_.minutes = static_cast(remaining_time / 60.0); + remaining_distance_time_.seconds = static_cast(std::fmod(remaining_time, 60)); + return ; +} + void BehaviorPathPlannerNode::publish_steering_factor( const std::shared_ptr & planner_data, const TurnIndicatorsCommand & turn_signal) { @@ -539,18 +566,6 @@ void BehaviorPathPlannerNode::publish_reroute_availability() const reroute_availability_publisher_->publish(is_reroute_available); } -void BehaviorPathPlannerNode::publishRemainingDistanceETA( - const double & remaining_distance, const route_handler::EstimatedTimeOfArrival & eta) const -{ - RemainingDistanceETA remaining_distance_eta; - remaining_distance_eta.remaining_distance = remaining_distance; - remaining_distance_eta.hours = eta.hours; - remaining_distance_eta.minutes = eta.minutes; - remaining_distance_eta.seconds = eta.seconds; - - remaining_distance_eta_publisher_->publish(remaining_distance_eta); -} - void BehaviorPathPlannerNode::publish_turn_signal_debug_data(const TurnSignalDebugData & debug_data) { MarkerArray marker_array; @@ -723,6 +738,19 @@ void BehaviorPathPlannerNode::publishPathReference( } } +void BehaviorPathPlannerNode::publishMissionRemainingDistanceTime() const +{ + MissionRemainingDistanceTime mission_remaining_distance_time; + + mission_remaining_distance_time.remaining_distance = remaining_distance_time_.remaining_distance; + mission_remaining_distance_time.remaining_time = remaining_distance_time_.remaining_time; + mission_remaining_distance_time.remaining_hours = remaining_distance_time_.hours; + mission_remaining_distance_time.remaining_minutes = remaining_distance_time_.minutes; + mission_remaining_distance_time.remaining_seconds = remaining_distance_time_.seconds; + + mission_remaining_distance_time_publisher_->publish(mission_remaining_distance_time); +} + Path BehaviorPathPlannerNode::convertToPath( const std::shared_ptr & path_candidate_ptr, const bool is_ready, const std::shared_ptr & planner_data) diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index e4c05538fa46e..fd50f44f4e1d1 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -50,12 +50,6 @@ using RouteSections = std::vector; enum class Direction { NONE, LEFT, RIGHT }; enum class PullOverDirection { NONE, LEFT, RIGHT }; enum class PullOutDirection { NONE, LEFT, RIGHT }; -struct EstimatedTimeOfArrival -{ - uint8_t hours; - uint8_t minutes; - uint8_t seconds; -}; class RouteHandler { @@ -362,10 +356,6 @@ class RouteHandler lanelet::ConstPolygon3d getIntersectionAreaById(const lanelet::Id id) const; bool isPreferredLane(const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getClosestLanelets(const geometry_msgs::msg::Pose & target_pose) const; - double getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_); - EstimatedTimeOfArrival getEstimatedTimeOfArrival( - const double & remaining_distance, - const geometry_msgs::msg::Vector3 & current_vehicle_velocity); private: // MUST @@ -390,8 +380,6 @@ class RouteHandler Pose original_start_pose_; Pose original_goal_pose_; - EstimatedTimeOfArrival eta; - // non-const methods void setLaneletsFromRouteMsg(); diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 23e810d2e0aa9..76763821998bd 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -2260,69 +2260,6 @@ bool RouteHandler::hasNoDrivableLaneInPath(const lanelet::routing::LaneletPath & return false; } -double RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_) -{ - double remaining_distance = 0.0; - size_t index = 0; - - lanelet::ConstLanelet current_lanelet; - getClosestLaneletWithinRoute(current_pose, ¤t_lanelet); - - lanelet::ConstLanelet goal_lanelet; - getGoalLanelet(&goal_lanelet); - - const lanelet::Optional optional_route = - routing_graph_ptr_->getRoute(current_lanelet, goal_lanelet, 0); - - lanelet::routing::LaneletPath remaining_shortest_path; - remaining_shortest_path = optional_route->shortestPath(); - - for (auto & llt : remaining_shortest_path) { - if (remaining_shortest_path.size() == 1) { - remaining_distance += - tier4_autoware_utils::calcDistance2d(current_pose.position, goal_pose_.position); - break; - } - - if (index == 0) { - lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, current_pose); - double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt); - remaining_distance += this_lanelet_length - arc_coord.length; - } else if (index == (remaining_shortest_path.size() - 1)) { - lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, goal_pose_); - remaining_distance += arc_coord.length; - } else { - remaining_distance += lanelet::utils::getLaneletLength2d(llt); - } - - index++; - } - - return remaining_distance; -} - -EstimatedTimeOfArrival RouteHandler::getEstimatedTimeOfArrival( - const double & remaining_distance, const geometry_msgs::msg::Vector3 & current_vehicle_velocity) -{ - double current_velocity_norm = std::sqrt( - current_vehicle_velocity.x * current_vehicle_velocity.x + - current_vehicle_velocity.y * current_vehicle_velocity.y); - - if (remaining_distance < 0.01 || current_velocity_norm < 0.01) { - eta.hours = 0; - eta.minutes = 0; - eta.seconds = 0; - return eta; - } - - double remaining_time = remaining_distance / current_velocity_norm; - eta.hours = static_cast(remaining_time / 3600.0); - remaining_time = std::fmod(remaining_time, 3600); - eta.minutes = static_cast(remaining_time / 60.0); - eta.seconds = static_cast(fmod(remaining_time, 60.0)); - return eta; -} - bool RouteHandler::findDrivableLanePath( const lanelet::ConstLanelet & start_lanelet, const lanelet::ConstLanelet & goal_lanelet, lanelet::routing::LaneletPath & drivable_lane_path) const From 8598feabf37800fce21713fa5b4df388a9007730 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Tue, 23 Apr 2024 05:00:55 +0200 Subject: [PATCH 10/77] feat(remaining_dist_eta): add visualization overlay for mission details display, remaining distance, and remaining time. Signed-off-by: Ahmed Ebrahim --- .../CMakeLists.txt | 131 +++++ .../LICENSE | 12 + .../README.md | 54 ++ .../assets/font/Quicksand/LICENSE | 93 +++ .../font/Quicksand/static/Quicksand-Bold.ttf | Bin 0 -> 78596 bytes .../font/Quicksand/static/Quicksand-Light.ttf | Bin 0 -> 78660 bytes .../Quicksand/static/Quicksand-Medium.ttf | Bin 0 -> 78948 bytes .../Quicksand/static/Quicksand-Regular.ttf | Bin 0 -> 78936 bytes .../Quicksand/static/Quicksand-SemiBold.ttf | Bin 0 -> 78820 bytes .../assets/images/arrow.png | Bin 0 -> 260 bytes .../assets/images/select_add.png | Bin 0 -> 18359 bytes .../assets/images/select_topic_name.png | Bin 0 -> 185036 bytes .../assets/images/traffic.png | Bin 0 -> 8439 bytes .../assets/images/wheel.png | Bin 0 -> 1632 bytes ...n_details_overlay_rviz_plugin-extras.cmake | 31 + .../include/mission_details_display.hpp | 84 +++ .../include/overlay_text_display.hpp | 157 +++++ .../include/overlay_utils.hpp | 141 +++++ .../remaining_distance_time_display.hpp | 52 ++ .../package.xml | 32 + .../plugins_description.xml | 5 + .../src/mission_details_display.cpp | 237 ++++++++ .../src/overlay_text_display.cpp | 556 ++++++++++++++++++ .../src/overlay_utils.cpp | 267 +++++++++ .../src/remaining_distance_time_display.cpp | 190 ++++++ 25 files changed, 2042 insertions(+) create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/LICENSE create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Light.ttf create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Medium.ttf create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-SemiBold.ttf create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/arrow.png create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/select_add.png create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/select_topic_name.png create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/traffic.png create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/wheel.png create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin-extras.cmake create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt new file mode 100644 index 0000000000000..6f7ca17f3d7b2 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt @@ -0,0 +1,131 @@ +cmake_minimum_required(VERSION 3.8) +project(autoware_mission_details_overlay_rviz_plugin) + +# find dependencies +find_package(ament_cmake_auto REQUIRED) +find_package(ament_cmake REQUIRED) +find_package(autoware_auto_vehicle_msgs REQUIRED) +find_package(tier4_planning_msgs REQUIRED) +find_package(autoware_perception_msgs REQUIRED) +find_package(autoware_planning_msgs REQUIRED) +ament_auto_find_build_dependencies() + +find_package(autoware_overlay_msgs REQUIRED) + +find_package(rviz_common REQUIRED) +find_package(rviz_rendering REQUIRED) +find_package(rviz_ogre_vendor REQUIRED) +find_package(std_msgs REQUIRED) + +set( + headers_to_moc + include/overlay_text_display.hpp + include/mission_details_display.hpp + +) + +set( + headers_to_not_moc + include/remaining_distance_time_display.hpp +) + + + +foreach(header "${headers_to_moc}") + qt5_wrap_cpp(display_moc_files "${header}") +endforeach() + +set( + display_source_files + src/overlay_text_display.cpp + src/overlay_utils.cpp + src/mission_details_display.cpp + src/remaining_distance_time_display.cpp + +) + +add_library( + ${PROJECT_NAME} SHARED + ${display_moc_files} + ${headers_to_not_moc} + ${display_source_files} +) + +set_property(TARGET ${PROJECT_NAME} PROPERTY CXX_STANDARD 17) +target_compile_options(${PROJECT_NAME} PRIVATE -Wall -Wextra -Wpedantic) + +target_include_directories( + ${PROJECT_NAME} PUBLIC + $ + $ + ${Qt5Widgets_INCLUDE_DIRS} + ${OpenCV_INCLUDE_DIRS} +) + +target_link_libraries( + ${PROJECT_NAME} PUBLIC + rviz_ogre_vendor::OgreMain + rviz_ogre_vendor::OgreOverlay +) + + +target_compile_definitions(${PROJECT_NAME} PRIVATE "${PROJECT_NAME}_BUILDING_LIBRARY") + +# prevent pluginlib from using boost +target_compile_definitions(${PROJECT_NAME} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS") + +pluginlib_export_plugin_description_file(rviz_common plugins_description.xml) + +ament_target_dependencies( + ${PROJECT_NAME} + PUBLIC + rviz_common + rviz_rendering + autoware_overlay_msgs + autoware_auto_vehicle_msgs + tier4_planning_msgs + autoware_perception_msgs +) + +ament_export_include_directories(include) +ament_export_targets(${PROJECT_NAME} HAS_LIBRARY_TARGET) +ament_export_dependencies( + rviz_common + rviz_ogre_vendor +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +install( + TARGETS ${PROJECT_NAME} + EXPORT ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin + INCLUDES DESTINATION include +) + +install( + DIRECTORY include/ + DESTINATION include +) + +install( + TARGETS + DESTINATION lib/${PROJECT_NAME} +) + +# Copy the assets directory to the installation directory +install( + DIRECTORY assets/ + DESTINATION share/${PROJECT_NAME}/assets +) + +add_definitions(-DQT_NO_KEYWORDS) + +ament_package( + CONFIG_EXTRAS "autoware_mission_details_overlay_rviz_plugin-extras.cmake" +) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE new file mode 100644 index 0000000000000..a2fe2d3d1c7ed --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE @@ -0,0 +1,12 @@ +Copyright (c) 2022, Team Spatzenhirn +Copyright (c) 2014, JSK Lab + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md new file mode 100644 index 0000000000000..0d0def1a46997 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md @@ -0,0 +1,54 @@ +# autoware_overlay_rviz_plugin + +Plugin for displaying 2D overlays over the RViz2 3D scene. + +Based on the [jsk_visualization](https://github.com/jsk-ros-pkg/jsk_visualization) +package, under the 3-Clause BSD license. + +## Purpose + +This plugin provides a visual and easy-to-understand display of vehicle speed, turn signal, steering status and gears. + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| ------------------------------------------------------- | ------------------------------------------------------- | ------------------------------------ | +| `/vehicle/status/velocity_status` | `autoware_auto_vehicle_msgs::msg::VelocityReport` | The topic is vehicle velocity | +| `/vehicle/status/turn_indicators_status` | `autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport` | The topic is status of turn signal | +| `/vehicle/status/hazard_status` | `autoware_auto_vehicle_msgs::msg::HazardReport` | The topic is status of hazard | +| `/vehicle/status/steering_status` | `autoware_auto_vehicle_msgs::msg::SteeringReport` | The topic is status of steering | +| `/vehicle/status/gear_status` | `autoware_auto_vehicle_msgs::msg::GearReport` | The topic is status of gear | +| `/planning/scenario_planning/current_max_velocity` | `tier4_planning_msgs::msg::VelocityLimit` | The topic is velocity limit | +| `/perception/traffic_light_recognition/traffic_signals` | `autoware_perception_msgs::msg::TrafficSignalArray` | The topic is status of traffic light | + +## Parameter + +### Core Parameters + +#### SignalDisplay + +| Name | Type | Default Value | Description | +| ------------------------ | ------ | -------------------- | --------------------------------- | +| `property_width_` | int | 128 | Width of the plotter window [px] | +| `property_height_` | int | 128 | Height of the plotter window [px] | +| `property_left_` | int | 128 | Left of the plotter window [px] | +| `property_top_` | int | 128 | Top of the plotter window [px] | +| `property_signal_color_` | QColor | QColor(25, 255, 240) | Turn Signal color | + +## Assumptions / Known limits + +TBD. + +## Usage + +1. Start `rviz2` and click `Add` button under the `Displays` panel. + + ![select_add](./assets/images/select_add.png) + +2. Under `By display type` tab, select `autoware_overlay_rviz_plugin/SignalDisplay` and press OK. + +3. Enter the names of the topics if necessary. + + ![select_topic_name](./assets/images/select_topic_name.png) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/LICENSE b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/LICENSE new file mode 100644 index 0000000000000..cc04d393573f0 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/LICENSE @@ -0,0 +1,93 @@ +Copyright 2011 The Quicksand Project Authors (https://github.com/andrew-paglinawan/QuicksandFamily), with Reserved Font Name “Quicksand”. + +This Font Software is licensed under the SIL Open Font License, Version 1.1. +This license is copied below, and is also available with a FAQ at: +http://scripts.sil.org/OFL + + +----------------------------------------------------------- +SIL OPEN FONT LICENSE Version 1.1 - 26 February 2007 +----------------------------------------------------------- + +PREAMBLE +The goals of the Open Font License (OFL) are to stimulate worldwide +development of collaborative font projects, to support the font creation +efforts of academic and linguistic communities, and to provide a free and +open framework in which fonts may be shared and improved in partnership +with others. + +The OFL allows the licensed fonts to be used, studied, modified and +redistributed freely as long as they are not sold by themselves. The +fonts, including any derivative works, can be bundled, embedded, +redistributed and/or sold with any software provided that any reserved +names are not used by derivative works. The fonts and derivatives, +however, cannot be released under any other type of license. The +requirement for fonts to remain under this license does not apply +to any document created using the fonts or their derivatives. + +DEFINITIONS +"Font Software" refers to the set of files released by the Copyright +Holder(s) under this license and clearly marked as such. This may +include source files, build scripts and documentation. + +"Reserved Font Name" refers to any names specified as such after the +copyright statement(s). + +"Original Version" refers to the collection of Font Software components as +distributed by the Copyright Holder(s). + +"Modified Version" refers to any derivative made by adding to, deleting, +or substituting -- in part or in whole -- any of the components of the +Original Version, by changing formats or by porting the Font Software to a +new environment. + +"Author" refers to any designer, engineer, programmer, technical +writer or other person who contributed to the Font Software. + +PERMISSION & CONDITIONS +Permission is hereby granted, free of charge, to any person obtaining +a copy of the Font Software, to use, study, copy, merge, embed, modify, +redistribute, and sell modified and unmodified copies of the Font +Software, subject to the following conditions: + +1) Neither the Font Software nor any of its individual components, +in Original or Modified Versions, may be sold by itself. + +2) Original or Modified Versions of the Font Software may be bundled, +redistributed and/or sold with any software, provided that each copy +contains the above copyright notice and this license. These can be +included either as stand-alone text files, human-readable headers or +in the appropriate machine-readable metadata fields within text or +binary files as long as those fields can be easily viewed by the user. + +3) No Modified Version of the Font Software may use the Reserved Font +Name(s) unless explicit written permission is granted by the corresponding +Copyright Holder. This restriction only applies to the primary font name as +presented to the users. + +4) The name(s) of the Copyright Holder(s) or the Author(s) of the Font +Software shall not be used to promote, endorse or advertise any +Modified Version, except to acknowledge the contribution(s) of the +Copyright Holder(s) and the Author(s) or with their explicit written +permission. + +5) The Font Software, modified or unmodified, in part or in whole, +must be distributed entirely under this license, and must not be +distributed under any other license. The requirement for fonts to +remain under this license does not apply to any document created +using the Font Software. + +TERMINATION +This license becomes null and void if any of the above conditions are +not met. + +DISCLAIMER +THE FONT SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, +EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO ANY WARRANTIES OF +MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT +OF COPYRIGHT, PATENT, TRADEMARK, OR OTHER RIGHT. IN NO EVENT SHALL THE +COPYRIGHT HOLDER BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +INCLUDING ANY GENERAL, SPECIAL, INDIRECT, INCIDENTAL, OR CONSEQUENTIAL +DAMAGES, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING +FROM, OUT OF THE USE OR INABILITY TO USE THE FONT SOFTWARE OR FROM +OTHER DEALINGS IN THE FONT SOFTWARE. diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf new file mode 100644 index 0000000000000000000000000000000000000000..07d5127c04b17a9a62121d12aeb00b701e920500 GIT binary patch literal 78596 zcmc${31C!3)<0TRx6_?{Upq;svqJ(Q>Fn%TSp_6)f+7I|34{bgSVd$I6_-KB!DSQ` z71wb<9Y+yyM+Z@HLq)~~5D^h~L`6xz-#K^b4xr=rfA9OhbgJ&Tr%s(Zb?Vf9Z(SjU z5Rvd~LJX;`tFL~!>TMxZ7O+Q#j2Yc9?bq<*LJaFKMCD^c8pcM&bk?!dBU^-6bxeqd!ke2KXC}?F6(js=gqJk~5jZB`LEIyKk<~n}bIDbkF9QFJ zF+zmi*4jR!G4#28o4~452>aN1jZ5Zh11Uo?1)jUDabD9+x4d$d5E{}9m^r_FLFbNn zAx{cX@Qo18Ve>nh<~Q4~z7+JKpm%JM-b){{{Ta7Hdc7h7SE2O~?ZP3h5rK5)_h%<6 zgdg_W!Mnj*+La$rcnXcsa+ykx8_S_7LM@)%+{w(8PA>!0Hs(x7O*d4n|0!RG|E3BSQiZ4}$PuUF0H>)m z`1h#$;6I=qfd3D*8U8=jNJ}0s9gqZ6DjHu0}c>Qb&~yADT2i&16Cp&rOR=p2AXvSY(t5yHsAnXUZh>P#4H2v5E-J@ zfCGhFWEpS}AS3TGnDceESSVV=3^7+M5RIZu%oM#vgJ=@-fUQRDX$9s?G-rWkCTJFd z@=W1l5k4ECt>D^mMv9S$JzF%xW=>7dpLcgYzBm)X-;7T@I>mhCps(nI-vZ>P1EKSQ zT>v{@0Js&`c3@{Ce6*++BgHtR-GVST?%I*_PCyNSW&v8vQa1skQ?%kb11YwFp7QNR z&PZ2H;OGW@Ga!mR41C?-Kc8v+Ig{i*4!uA%fn$?wl)76KK|*qFKgqhMYf9577C}DB zQ=^y;pVD58dy>Nq9HmC|M8b{q%U0*AB#;gYX&9zZ;rZ$Yn$JNA}j^ zwDOp3l-@#=r>Va_tW8scz0auYK4(b39`UI5wnFv-ln&WNPeB&vvk|IQWXT<{B;B5U zbzl_7r@UpHfqMqpk5aT2i_yyeRoo^1DP9n7i;u+@;ujf$);?eMlS5>KJYUY0i{&M9 zt^8CCRwLCUwC0bf6WRc6m^NN()Gp92(yq{+)Lzlv)edN1X+PTnY*DsUTW{M8Tf6N- z+vT$IXs=91lC5a_n%t?Kt50((zNE78nue49pHZFR(fA zhQK=mHw7LJJQfrelpfS8s3NE)Xmrq&pxHr-gH{DS8FV7p9^5y$K6q^K)ZjV6i-K1L zuMOT6{88|c;Nv0XA@f3(hFlu*mylaS{t@z2$ZH`VhI|?Fb7(+lTxfP^QRslsVWHzg zn?e_cUK)CR=-r_Yhdveha_IY^pNG|l-57RP*ygZj!d?&iIJ{^0)bPKC{~R$YVsgZ+ zh>nOA5m!ds5OHV3&yfLywqQj$|(K*qc=z-D0qbEeqie40bS@aFj_e4Ju{dDxs=)EyTF#}?T z#hep!S} z$6XtDOWXr-PsHtrdoS)#+;?$Z@nP|)@x9{v#gB-e5Z@R-FMetKrSaFs-;!WUh)i%N zg3es)CH+4Qm;r|pL%cVx2eCn z9Ikv|j2B(cko02vw?Qdzv+``?@J;XiMJ=NXfUg-Xl z`_Jy(?t|{H-6zrqrC*SKQTm$nb?F<@H>W?7zAOEs^smx?&ah>~WMpRa$>^6cB%>i? zM#h4SOEUhNac9P+j3+X-XS|(pAhU1g>db31Z^?Wh^NGwInY*)6vu0&&&f1rCH0#G~ zEjv6rDLX5>PxhtRf62Zh`@!rdvtP=7GyB8r&$EBX3CLNLvpHvL&PzFO=6sNIIOkZ7 zH#a!9ICoI)@Z9ma({ktLF3Me%yEgac+tH%dgBInm;jrdj7op<@s0T-<*Gc{+9d~@^|I$&Hpt2oBUsT*?V2t>-t_B zdu{HW)H|zppWc0Y*Y!TT_qn~BdoS;OQ}6qFKim6_-X9b=3+fA&7i=on-6x?>Tc6wd zd|lYTaAx7tMZrb!MO8(!ita8t=1KRodhYYQS?n%8x45aet$1@?vC5O4gLzRC0gG z){>ni|0y|I^6RO;()iM<()Q9#rB9b0DN87uQ}$HZdu893Pbq)6{H^jI%1>4VRD@N; zRiswrR1B=Bub5h~sA5IMWff~H?y1;R@mR&v6-O(bm93S}RUYme**CGTyKj%ag?%gf z4(>a&@3_9x`nLAHvG4PJclF)dPxQ;}H@e@fejWW*^t-Iz+J5i$pWc7>fP?{e42&AM zdf>i6p@U)v^%^vB(5gZE2d55h9sKd&&#H!0-C6CdzP0-Pn%J6UHJ8@>rRI~`3v2&V zmsU5w?(zEU`X%)ThBOa(V`$#c!9yE|UOn{gp?il#4;wJ-Ps1J_c3^ns@R`H!7@HSBHpwBgH!9~w@M3mBI?ZsfQ{*|bnCLW|atwJfcNR-hGWrP{NuAXkJd!IkPtcV(kh z=;JDP4RAHMrnp*M7q~7&`*4lxudW+ix4C|Hhqxo%ac-yE<<4;DxC`CI?!N9?_k8zK z_Z99t+#B8Zy6<=Y!~KZ+U+%5$r_y86Y%p@NL2j1YWX%yxZJKRSDvc?EnHt$wQI6#s;kwt#I@43)^#1{WP{s*oJ6}5-6?Lj zk&{Z!NvC@ya&njZ9^~Zj?uU_+C*0foaxw)u2|!Mwkdq`UCo_=~%&=7rW>}vhKf>Eb zs;>P6>3?1Q^s6_c>tnCPILPnM`?2>U@4MdDy}P_Sy*s=wc8&83{7vwaj00&DcwmM} za-i(My$9wTXgFZozYD(y4#0{IgdM<2fe`z@WqcF#E0PyUL_DOf&PFrYiqQ%#Et&6tF^V-wc2{^9&MA3 z@%Od+vB5m)})4sB6>`wN%YePoY-K!|1C? zO;%IXcJ-WkL7lIzM;%MWd@&ofs$LAiIJp61b$zV32qU|D#r@&|@rZav{2ODted1Gb zNPMG~t6AzI^@{3LC&dpkN=C~hnU1-AUs)yVI#`#mlcriP(l3xDIpV z%f+2yt$Idm5U-;hc}2V?J`?xJN2Eg>7hN)32FOquA>(AB%#b;(=8l_TU?(kU0o z%jHtJT;3=zQO{znV!M1wJ}aM>AE4#=NW^3Atcf2*f(#L9GDc*|1d$~Zg&QklJ!G=T zlc}Og7KEhkG1mjlF5*-wm=gTx3qP@FAm#b{YAX2^-6QH~cAM0g~v|LSU3hjN47NCAbTN$i5lvjPC4q|oa3w2a|t`4aE>PvM*eX0(N z3>h!-rAzdZX`(0A8f#>!sFo$7SZ0f}B)Mof{T#C(Z4lAJB($?0MtT8QQH z0&x*mu~y23Vwr3gcgdT?M)@~!8`iXLmDh>Qa-(=y-Xpfk&EiSu{b6_7tvVBiIss^UGs`CtO$im zB_e1A2;HJh{Dj`{1lBZv!J6i;ST+1v43K@qAXy~pu+mm4b49uADJo>1sFeAlO!g4x z%dz4-IY#_NUMBu3*N8RpB5|d>SX?DnimTM@V*Ycn`TQ#T&YOI>5E>P`i zKKkJ`>I$`5U8XKqm#PiwPBk4Xcn_(+s|VF)^)IzaJ+2!)NiP_(9b=o-bP>d zBHA)!Qv}P8u=c2G>qm~0n_3$?+n|LNBB*L|om)<>sT${&Wi?~rM~|qQ>=s|0HF~65 z>>M?+)-CQCJNhiQScS!Gx0pI^>F!jCjg76H z(leuRL6ht?W5&Gs(#?M4%+{9KGI(ZN`#foz)zLUZoB*Ox9K$|AtN4oj!|Wem{{!~l zW&aKKce1~o{ioX&&g&3c+B;^piH8=nw9OI^ELc!jBsMNsIDLV*ZNb9%3&c&!nmXFi zPmo>YuurSu64pR|F8igN3c)(ArclvKJ7(F)LrtU*binu8@`6# zDh2&6g*n;Jf=@dESjR={Nsj8cc~5kiz$m8e;jr6>2HX~a=}LgGy@X$X?IUfc^?L}T zk4|ltHVG^Af$AIl4yfIzQ;)!(qt3<8C4WUvT!0q%CG_oM!JSeF1plET9ple0#WS*KQ0;mOqR7=!FA`qjRKZ|g6Jw{y7=z~5LG3b-N7K!RxbzG#Y zpRl8ni(KilO0-70Zft5Ja^QU*= zXs?IjrNdX^63|cx?aXu!k>UrY(^DSkJ!%EBSd0l zl}d+vfu2Ol^XZ;_!7`X}sfJU!k7LyJAjVz(ISb-AWZ5S5C{Xu8+SrdmI*}q+eE|FV zLj4E+mufHkPt^PH5BgE;V~UTN;v=T`kSU-C*xTpeXmWR<#w>?L&Bw@XCPvJY&<>2m z9AGf|Nou_?szXS-xPZrWZaGVKsz|PxsE1T1Wj*}4&@JjJ`$-rRDzS)Q@SO?2h2a*} zN-$%xnI>C&XXRaC*EartRO56DPcf`A3!E?yVtx+TB0*2XQQ7Nls^nckokF*lGLeY2 z>2v-^sVZT|+@>CECLvdn>oDo`YvJHJ9LaTl^r@mJ|sN+OOd!S60fiPVI#8p{b zzd;WJTcBB*K}q)P##+QfVxz#QT3iOJ=)k_jRP1aF$L>gfk_s&Y?fX)_gWbdOL(tka z!Ag`Gs#>u7Ived?E2Qs<^_Kx^2%sLyqxvh@v&vOPs-LO@l!G;mzN!{bw(6rQRSlpl zRiG+VHK0ta-ju55nKqZ+dBN6H{>Cgm&-= z%n<%x_FZzcoUCHxCbn_y;JWWS>A_rM)ll3dX zmUHQ_R%hUricGB-a>1#Op+kp$CHQpb{Y?AL5C1*jACdO|ZTAV%BzH=>+P{ID0-4Bt z4|p@Kzvsq-=8w7~&`}`hJA~_Z-E&Cuf79I~T-s(4d8$L1_g3RX)E{zdM5a2`bs}&7 zo335wuiYkkkV9HkiuCzgj$|1Qx1DLb$!41b+^GLuhcz#kT7fiv%MFM8!@XZZM!J4Z zS8-I7!}Zmjcb7Qo{SxjQxXa+)(H+x(&ig*-B(ASvm4xnJfg}1SP^XXjJ5>prG8|g` z5$w*UtJe$IiPadw4MiVExDVitYB!52aJ=LjF=qfjM`Z(-1zZJSqPqlf z2jkj`_3{~5JAVxDg(&~?fj>|5#u~7P;s2lL@Qh!qHWKYzKe!RXqvhZ_9oGwR9SYg7 zf~0aVuA7BHJ7#orPYyc|`rpr3_m06@c$BD@IikP10QVtSeTKs-MlxKg_y{Z0=V3i& zuE=OjTMaUbm(tRUV zn@#*Rz+VIW3gA}&PqIFOIR6Ij-+<|!+#%e53w*4IVYdmh_ubeFG4a6&4@UTBB1WTj z{zcfu60`+_Ac~wE|mFtTvv)7*!>#8@o8+RA^rmB zq6W`bqHmYfek}0*tUTTmJTAM&`xV-n5VaI`NB#82-lJ-Y_Y2)&{?Zfl2&ev)`cmlJ zqsk#yHSlwxryp>StL4G~hlwQgrvup$T`h1aa1X%EfxA%TXs}Dnaw627pnVH#I{R=9 z6S?Xsgik}9sbY*)h&pmB(wc>*D@8Zw!M(rh;df7Kj3sbIaP&+x(a}BeAlRgJ118#D zaKFF}hckJa@v;n@8P|hd3XeE|d~4Wc2oNRMV=2O}0NW9l|h`G(Fzy; zdDnAV`i-BjQEFM($5K+0Htg@&r2{)D|CT{A7*D5#$}se%(`5v9#UgqCG6s8Zv3TP4 zS{Wy@k%yDmbD1gQWddq#E}mch9D9MuGDW6JmrRpxXuL_L%M6(*cE~K5ja|cB*#rA6 zJ7u2C7q7@(*hMUmeXyfgBt2Ne$`e1yVp$?fWf^v7@?{0@mi9vp?~fg>0oVh4O%B3N z%V2RrR*BbTwXBh~vJUGFy|Gd;6gzCgL?1aEyOJZZFF6Xc)G^ql9E)-*#GYA^94E)i z334K4hv&%2atd}}&%>@Eo*c){&G~W~_URh&)b$KGQ#N6jZnm5)n`H}jaOTLlvQ^H* z&SATpFE5ZCasi&pUMLq~muN9|v6f)>a~akKip7_(f>L=Q_Chbhvlkc3mDn*VldI5D zA4F^Xi@a1`hP~1?@(Ot+_KeEq)$-4H=IyIFmbYM!_*UK}-hgL0?v!`Qjo9_8M0~{VKyTBjHkL1U4pWKfT$uQXS&+-#_P=1Q1I6lKj?XdiuR@1Sr_MYgZ zHFd0xeI*v_>+0A?^jlfSjw7$Fi&3*4M=+VvGt9XZu#!Rfq~zVJaMb#S*NQ zj}=Q*6xKm5#F}s{R%+r^f=U$2Rg!Y5WU)-8;OznzucD-PU)2zIphdh0Yb*Jxmv~q- zh_A5nGahR(1z4jg#M+HV6^jX2Unmuysxt8_)@UlQcGFk&6IY0dSmPO>24Y`+u&Pqk zXp<+26{;5P;7Y9h{0U=*i?Kp9Oby3={YZ6|8l^_7G1w&>i+#dz*#Dm(&JmNbTR2Ib zgXig|h;s$nYOxi26z8d_cs^ko)|$@4n#N~p2A*iZ3cIy}kM$-s56=nEF5?BNLoLA5 z2>O~nJ@2p#&lfDmGYbCe`>U}7N&AqrBYCBGRy-$e6}O37{PzA5(aJb!ZwAj8T&@0$ zrzozmb_Ld9#pDJ&g>Vy|QMg&%f@c$M#ZwHoV^8xA>}uYnHmbYvWb3`^K0M9v0Pk=9 z1G}4>vDZoaoBzam`!TGc9aoQH*Yh##dTyb&7u1tj_t=JKGoHpC5%u{l@pr8H+=W%} zJMld2Ra1gmjV#WXwv zF&KNPuc=+?b?m6Vi8l>i6pxC3iO0m_{4B@Qc$OmoBd@ox&$?T^BksY@Qjl1Kb-$~` zmEvk~iF#L@FAj@U>OJwi+Jm<%_F~0(HP)V=!b<0d>Lc-^`dID5%FzMdS^rcW!uru+ zaVb`pZ@|v_7g+WDT6}{y8Qgf^CLL|}^>}09uXvKAQEbF0`>421tjGHGS6FTQo48xt zgq6-f>_a_)eJXt|^BAvY{;02K;+c?N)k!=7;>8ZX#O}U^{rv#!?K`wUEeJdO-S%q4 zTJeFX5r4+BDtl<(M(o#O#ec+y;(f6f{l~uF+Qq>$1Q}W;o+8M`vje$!O01`rr{!zC z@QhV~)<-MUitJU>JDL_XITp6H6xCJL>DTHq<63B3J;t?!u7yQ4wfcP(-y>d)ac{({ zsxa=WnBG%p@ToGd%&*W>=y6odYn;*1-sY%kpWWWpG&i`aqor+j*N%QYD(<2Ga88zQx|z~+tJ?0p+$9thJ1yb zzrvz=J^iAZQhOa|-(Ke**`TgAv{7T^s>YDM#?VHMt_@FNNpM{^af<4y4Fy!23Mg~b z85z~(GguatIO_C_>vC7u*oUwrAwztb)pO|a1P?hS6;GjU==8=8J*uZFWN7y|MRlGM zHEg(jm{r0kxq9a2DKrH1n0aJDi|T3^kCLf!3^N2CrVD5v*4ffJvnhlOps=K>u(+@& zWO(-k3yX?5Ur46hK9UR1KGILI#jIFRRog})E4tiP6hoq7Ly{7+jH>LTbXKGMSe59C zEh;J1xs-5O6xEd&0#vevLXc`Byh5vMn{6NMr;6GlJ*d_w)>=b=TBCSt4VJY!OOI|u zg&vPlrp2Z?80Jz_7cjcHy~D7;S|b~ECO3ns)=+p|Vc6*Ag)sGwh4We)7qT*-_BzLC ze>*8PVwZASg{WyEqZhO`E@<|v86^hi65Y5xo*MgDU14J_g%uW+8o4Mkq%JjbQDml2 zXK(OhT4rRvtSqGAltT6t8Hy@1Sd|$p$_#v^E=W;Dy=@%K(>~5m43oB8&yc6cP*a(a ziLyHTc>gjgrZOt@pq_BOsWY!-0poqTt}_y@Hw3CPb#E}Os|y={x~_}L9OM0UU0&rF zubXquZH3aiye)Ik{XQ`y3yA{H#Yg1Okrin3}5zxXIL4r z&$JAnsIJHmw9pW!P;ZcmYRc?QoKJg`Kea(sZDhN~5WmI{v&P_7qi5SwSQ^}9rE6%& z$Z55i({e|Xf3X)CEQ?AVP2HMey#?`-;mN%AJkGnPx#=;E?s`J1*>5SP*$s!IgS=13oS^^tz}aldDzzq5 zz;=H{88yXfwGAO^4GX9>Sk@XWb^AhVZ4`U4X)%UH)zk;H`&y7%BP(?#H-oCyu)DgV zu=dki5ZG?JzbTa(u}e8EwAR%j?WeWY2Imsp?meDbJDvr@aL3+ZDGaT(k&7Zj>QW;Y zX6-4hw=eLkdSyoD%gRF*oKo7JB12JS2CFhd$g)aXC$-LX14VBeb+Ltl= z;AN*&`^sW_V*x#Y7t+WC2FyBQIF!4us(Qbh>T>^^BLACW|C>_lhMIN0iEQ-czzRj@ z;3LINt$&DrT2+<)A=TCm^#Xho-e_vf3IjhqEToYYrPlafIX@Jl8NWZq25u{&gkohLU*D70qXnFMvXtU0r6##dB zi=F*BeA8+JVone}F0na}PF2te+gc2UWP2Eh^PmM+t`@j*Lx(FH9j;utaOFycD-RuTW#hz^2S2!0 z>N3-Vp)4~4Br^eq%mnH(>k!GzbR;v==`u5@%glrZ4|-);OU zF{xk1v)RdKMl%Nz213*Z&uW>y5UF9PuFI#lji_OTA4bqX0C zFP;rrLl!1ul#k55plL>X+f2@BQBiSF(}GS6P&%7TOqrum&xo#z>e8?o?XB%?^HBJm zjU7vEGuzu{+v*l}v>V|@6{xDUwYGFL8c3s{t9guo32K>re$xWPH-e4oQ_Z~zMoC8b z>jPbn(GB8S8rU>%e& z{_FGvoAd;m^aOLg#+B;;uH`}8qRwcaH$8|u4}wTGgjE~-Y6|dBxq;K`TCp)5g=_}C zDu|m;zt|;V&F$@T8>hD~Lh)EU^?^sRKC~z-)+d0tR)?Zfo8HvgzSu|X;fh>XtSbpu zy+Sl}Z^A9@_=lD7O>{Rs`G?p0-4qr1-{_J=`RmLt*rPMnGwAUb$D`-g z2=Uj0r_PT-v7Q*0tw*={LXSCzG1^^^J}m-XSHDLeKSRwGv}Z)m-vwhwXPn^oOhmZ; zo(a}r@rU;quyGF>CA7Is9c?0KUSr2x;hHyh-dsV?`(s%WlmUR~$xhmrB7XMV3fpA$ z0oLXFV?ET4r+4W@7otePkDkrMvy(Z?a+XnyoKAL#&8P2})btGTqj)Pz;vJ<>k&Rs| zJ6NBv4#IzcX;x_$0$#=N1==Nm z-_}+^vdLO6!0%vHSBj6Zk}JjKnhpMk3a9#DzhFQ7JF(MCG}pp^N*#g!4Ev8V{VMh^ zz|(TzsdmBNuU>_})u1GvUgp1t{dcfFP29f5KAp(k0`~~qgK+o2Z7|%;xUPd+3%3St z72I;TMR4=s=D^K_n+i7xZY0^91Gg>W}w8PBu}spV0)7ETtRN|-huuyPJ|_BA+M#@NfS^N$*YeJ^^S27Anz zTj3ss+XQzX+?|G7kLwL^W}a39UIDiRt^=+WZWi1$xXEzi;6}j>g(G~mkeOw0g>ZRr zS#UVpDico~XNDpi$!DB^I|la^++nx_a3ARLGu{RK2HZ~EgKx%mI6RYX^32#GWX2-~ zze426;eXl|>pg+b*hg5C-4_o8-06n) z+yxfY!-6s_2sn2N)5Tl3NDB(KAlvCs8tQ|Q210c%X{aAME)BKBfKXQq2sOrl_L&e# zYQ)`Z;?j0o&@KzwVM4yVr9E%r(zaR9V?v}ogaQ$14_MGfK({gOCP3FQbhQP+nhYF; zuCzjR$QQcIqU!|I2G>lq^q1D0X5rGNo1u(5_mohgn_%I_5Tx_y4y6speQnx6_!Sle z8#i#hEQoM9Oy|S7tx&=_IW*S7g8`axue6}mfL6dQadp6Ng`4Ff z+%(2bhOdVbZXDxA!5`|XhTk8q%vA_K&%$L{kn0RkqJ@jLpim34TM(roD2>z;CNA}u z1$|{fhfT<3NtJrQ#HD_K`0rBAQ{S+lohFpF5jwq%LJ3OU&U8P=ZqLAv%UOn2;WqaW|jBg<`B@y0!4vFmHlZF|-`eB8KK$&>Rb*(3uw9RE8#X z3mwb2k-*hkbb}e{YtfaY7Nqt_%}7m2jklmk3kp61Wb?Dm+r65M~agJeyGVU9~B_HWVchJNo>(ED_ z*aP=gvJZN-8}215^jQnqYC(@$&?biNOTIICeew-}ueG2nEok)_pcNKwi3Jgt4(8Ho z;bvLTwB$QoD>!tr1rcr>R?0Lpv#MrX}rsjGNHs@E$FxfePcmKEa;#G zeT0L4_rSfC*d2P6aW8cXeU@=s;Xj(V3I2U>cQUlzf^M*&Yc1$X3tDYKD=cV<1rcYR zA3+_=xz)nWvY=@uM7ak{vP?E{eo~FIaH9YXW!h>B>Tf}17E}l*kLd`?V#sBVK@t-a zqZ31cwT_lSifx(BTo_b{}fTj|Q_9iS(Sd=i|g63GzObeQ7 zL6a;9xP-AB*N5}P7-`YfThL$&>T5wICPcCr{0dB5LJt#4bS11xt>@G-Oo(s^DU6FZ zaX4|(qzkqnpL{lxUwoGZ{bWJknb4W^5`WYTjXz{Tmj2@RTDaW_tKxS-*Nc+&LBo4V z&+$9po+ro|No_3SwgLATLl0Td0~SP~8#(m0Zn&EmhnB{OOLSK=?lM3t8CqsRofgz) zLCqFKF{X2jbGzXtFm6mY+;9u0L$&b(<10YniT^FAmlc|0L2ibe-Qvbtq2UY##;dqr zp!F7Xg9TlS+1*ysY21~ljVMn*t1W1S1)-fZLOU#| z6|}P`MtmTkX#~Z6V?iHT&|4NX*@QU8IF9j>iHm#If;L&udJ7r_Xeh@(D{4UfEvU?b zh^~<7@-X&pi_5~j%YqUu2S?-|AP})tV9mFoj{UQqS;b;b=&zW4$>K5j|!r~iyry{OCQ}>(a zb&~XO%|4u!?tI@!-#2c@y8mjNPbQ_JvwLKoIuCvs-p7;DhByDne};SwtJpF`?PZMa zuLK+n?g*9N!;hpL0$Ht5Xe8|u0E3+aiBsH!6o+YV02ta8_>SRl+8dAwv^M~}?jJ?y zFT6K!lJ*8WN0? z@Vaz8<6&P2Jw~B&63eraWRsUOhewEmT*;wHIt|`2BMy|u9L`;iwwy7P#~hLwKIJiy z^V`L6j*%{L4rEMk=AUEul%q+UBVJ#ZIh?O0$RBZ|-0kPRf&HAvhqW<;;a!3Kyic&7 z_X%D^=>gAi7vViMDIQjr!vB_Ieao8pmSg=y=>ku?3*TyVYR$JSNv3uyQp{w%(Mg+x zr_`5m>hE)jEMsm@QZB?Y=Jr0v4dGbJIM(~DD_AhNIms&2OoG)+##d<90AHa!2!9Ui zvx4;*$*IrLE~ZennF`itFAjB)K4FKX+g_~Csa!gFjE`h|g?16e$~lDQ4x zTu7oeUf+PF6T16oan^~re8yQc(NCB zOXbx0)G?XLq1TZN*pnm6zlt&Ua@?!9^cPVs#3J6wTg0W=%vL&zbRsTh8Sc~8GY!>H zt`T^Xh|OMIWg?j7D}B77fCtBg4~ zm|Gu)8`%aN%%KlcRxn(_@Ou=hozJP<&G@?+U(EJ4OM3;Ji@BW{VBo2p$!41mVfl+W zcX13Caqfy4?#rnc8$Pv5{aHVC+@cO(4Gc0kP=1>@zaEx>&-s$YoMJ8Kx0ZH@Wi9O@ z%f+;FENhvv7T=+;tR7E#s1EWJwOGmnjwIQ%O6!vXVLUr=4BE z)Fwo;B~&t>O1!;E=hu-fRdTF+rq5^H7H}*Z)92er{(O!#)rP%GIhAFmH*kUHxRW@= zNu0+?%x4nIJcap8;<#6FtVvAIEwfz4a3u4IBpC0AQJarZ82KD}kl}+2FSiW@ez|Q5 z{LQTM<*d)UnR5qIb};2|+eoIt&Z=C_mav>pNXA+|K;pVwzayc01EtO>&B>`B{ytNmpV8*PY3vC2=*Sf>6{Q@rzHyir?^^d1s^_3Qzmg-50^zc!-6fO$wn69VV)kgkSw+h z!M5SyR6J}I9vx%DzP-${-41`9Ef2nna-kA5)IRYe*B1}V<6(K4SkL#fZD7_yX>sZU zx$FkA1_pAum#_{mprhI6sdRzfi6dLhYxcXd(X=rQS;l{jc85i-%&yAttK$0D5jw?wP}v{L*@T!?eY zwuy`QOJ0xDm%L;&-d~@F_uKI$FT8cW5SGzQU-H5m;P{dk-r&ZUyySCu3pq~yf_IM7 z58_ZZwm za1X$3gu4yyCOFuZg#F6P;8wz+4P$&Ka@mGcD}p>I-hps-2w zv=TjCRsqfj$r7sW6~Ca$JNwTl1)2vK9?kxv>|enC+w5<{`QmsQNaxA^R`O*C zr+5itu3-Od_Ag*xaBn@Cd~uTf>)HR1{ZHAyll^zte~SGr>_5u>7#i(VA0{bt+_kT|61b<`BjkksIO*Wyzr$KfVoJG&NguWEA0%u83-Sqpz z$x7Cr_YLpo-fz9%c&RM9{dwsO48eHJIdP387^g4^oNdZ~-e5^W#~tg#CzlVhX#6zhpEC;Y9@|e=zc?lzre|I2QhGo0anNZDZpbr- z7+UNuk$0c>J!s_}GcE5Slw|G4WRE~O~<_-nfy=#zW2VY z^D%K0k0{}+7LD`xBX}J5wJym0NowbOX%YvHYuT$GPi}(|pRLOKDbrf~bvin$%KSqO z|Js7P*+6%DFlqd+XQt@Z#-jd0mTs2i&*6Ur(~SH~e>6AxKl&r9B|YK~V-D-DKSn|x z{#hsnG?W01JJ6q?Opc=FuwKd6ZPGuVMq9#mqK9^8cKY3!>d@&_I_6Z4r^O98Jtk`N z5mQ1)Z}d%PpySdqDa~-R6j7c&tx=g}00F zzuEsD()DG=#nmS<+mt%@r%Tp0@*lUhrS3KjWg7WaN=m#&Z7AMDbtsfaGDanr$eWS9>qH% z-{3cZznL&l;(JPB627REBqn37m5lGtq~px6bLqq|oIO>A^T8JKSkAS0&BbShF_Ptc^8mW6j#2B^Pu)1iv8GR0wM) z2zt367}859>m`i!62N*1V7&yeUIJJz0j!q*)=L2N@-fP6AAS+g&Zj83L(q|fb>v_j zMX`<~bQC25F$;~x9E&uiSVwd!eI-sJ>nMjhr^)}{=yD=+u%6Fik-nyqJCeGWTAMw2frY;&;Yj30JhKow$K2!&;Yj30JhKoSZJLH!1-nM zuyiVea4v%gw$@0t)+nPq$XcU~Qh5M28^dK2%ViVCWn<^Ev2)qjxoqrQHg+x>JC}`} z%O;-7CV|T)k;^8K%O;S^CdnupDitS}N($R=2$v0gzoQbT2vXU&xNL&iiqp7+++0HG zTtXRKLLuEsh)N}sOC^g-C7Vknhf76qspN90^x#tI$))1pQpsbx4&w4iMp-PUK2%iV zt8ClxjkYz~3T=rtN-M!hQcE-&&boRP=W5-DlfF9DRBby>GV6g(WaX6Q698UD};MBifGDF6)3&x3m_;wfl@U<-RC0Z+LL+%y# zp*)@uAM=@l^wqRRKL73!oME?H?uEQ`b{n7DW}Mnar=uCCp{eO=2A_jAk54}9#F_5? z=bF(OWjIX?r-jj3VLNEeS;eCdv!VR3n&CZ8t14=CU zS=c6E6|kTAI8kh@nJ^F3JeJGgcz~&}HwdZmmKmiD$s9;~E2NFb>F7z6LluvJ6z>6? zcf3cPgPcg5&?!)>C|5(^E`hrrXMx7!EKbT}GShAa?E&U<6sOW63lyKYA=GJbH1tAu zps*92dJ67oxM$&Zz`cwRXWHflHznvTvTjkdPZqX zMuLnlD~&42l(E3(${c%Kk4*VUW@gu@%yNfKZcw&>u3-W4R)?*t5$lkD%gj7^WoD+j z(0=lMoEfSn1f0Ayz^*0&hOGxfqJ`>ttdF{csM75A%#57UlJc0cvII|jLQH&IEMamr ztvo$Jj@;u&jY@WEKL@7AM5j592V}-Yrv|>azFdaKsI)FyOq?q|C|FI1#bZG+Cm#z7 zNp{D_$RD~^FIYhDn{ry(CH5RxyATd7T+lqt#9wLQqj8Sq6DHo)-@xZ;j5p%x;q%l& z&5W0;ImMgIw|o4-r^OEwYyJ2yIxRdNr>AyU>7O1y7N9m|EsiRn2=Nx-t5(lr9D%j=Kr& z!i$DvRSZrJDElOpY}yrX`%$-PJX;YO*}Gp%aA;6ak^|rFF6~;D1@nHrq`YT&RzhH2 zsEV|cr6(nYg{TJI($@zD1;+=3Fv6^a2g60#gntH<-N|r1K&7IJ^zi1=TUX`G&Dt1IANNzN8$|drd z&T7w0FOSRBOCU27povBKl_sRWcrZGy>&fV(m`sJQmfjSS8Yv5$nVHV6UxI_)BVbQ( zunb_#i_XlXuD$r6olLiPxe`;7V&l}Xh>&z=Qd-a}F?5Oe(3zQ#`E ztmg%%%~BgX0>(5OGCMJLDMGpE){$B6ajCf2aFt07VN^+3aRP~p0}xP3nh(s8tEWvZ zm|Sg38#AIPzkW>i&m`TEN5VoMO)bbzek>^X>4LH>?72;z)MrR;@2LE<`d5!Dh{|-T zYG>x6$bSXpWaZ~}eHHk2a8Xh39<)Q*1AX3Poa@~Svc$*3ZgX>B7U2-arI37iS$smg z-2uTe3KZEql&MOcK`~)H;}T0#%f|Ol%N#haD7h>tu4i~`NRqR>B6aAWn);SDt{&BE zoVq!zA|cuq91@x_XhO+=$^BDL6TR?53p3W4DUnrmVt+=%ALTN=& ze^|w3gucowqZm&a%BKK@Rvwir7Z06(R&M>JjbBrdd^%`Mc3iL8KAVH>YFk<3#X}o! zpQ@L_$;Yea4(c<$DkrEb9-kuhQW^n;+DcmvEJ9!u_zg~7zI*Pb^o4euNVy=!y<8qVQ zX2^;ef!b-||E7+Zc>tdCpbl#g4pxSo;1uO;nE8tavkv}d&4l@{k)yfV9S#aSLcnJM zfii(H55rg6sKQ0P5J;E6ok4oNBNI3Dsbbj%`mkog#V4kWz*E1i8tx<|2Y=YcQTG^I!V?LU~W zfBaZmxD{^355qk0a--y9ZMUBm9*-~O-eQIKI4wLDCn4N{@B%6e?r-({CWwiC`l0?- z$A{qDVxK;#Zs_<>@tmO_8J zjG*sOdyM|zDm>3qK{~RU{DgRONKU;24{k8JDJyrBCh*9;te84kec&UnAGvyFW#!D( zBl}Fsj)-t41x5uXRivTS8#K4dH8de8s-1+`=*)--EtnTvF=N$;5vyiY#Ks0DhbQLP zY$2gl^Qx=bszQTZe~-v;Ix{kzyJMY!De2G$wbNH|9Uj7UCR%J}8`AMqr*wRjc$RJG zRD7g((P;1c;!N_FEcz4~>PJtuuJZ|%F@AWmMI9f9RR^;-r>AeiFwUYG6O<6eQy1#P z$)tRDGCeN+s>JM^q?C*-`Cdv!W-4yFrpTwe@W@D}^W@W{6l%l#;jRxCU^GYbvXe$C zJ?U!>4JdPr5e%En?v~E!sZNPcO^sLW2`MQFCy$<40(m4gJ`Uk=DR22F?+=qGWRc!F ztdLM|G>S_g4QG*?^>Q`0YC1j=HI91L5$Iw3>7Dq#yJ5jtBPGp=#g@j%h<31sQWCQV z_!NTi_Xw1{VETOIzgvtL%oJH4m^#LjS<*a}$KBAreV56vrgC~(Xl_hIYG`b35(cw` zAKWVYQ8KcY^}e_uKRPNYBRVuX0z+82k&s>I4rm^1}YDykc{%duIRxzDJfaOk-Z1RgoZ@MM$kmaoB|EXQ0H+WZKO$0PEvGqL^E9ZHZ2Ahv{;Cm-!(rC%`>a2RFM13~p>+rnr#I)$H z^8)19gswSgJ5o~8u@+N!Uf1@R_>@fbTyAV!bXWT|@~niDgZvv1F7>_&X`*aqvy3U? zd0h3;81)`8LNrn8cC7H|vkpo+SH8w}|D-cB3)L`wAx2s07Uxf+D3_>>wg?^vwh(8m zieaaY@Mx)mSu2D`9VxM}>Kn+x)asD=DOyZZ5bop)b9tOIYo{ME>?fgJ$QscC3Y!`}&eA!_xx4_xv2= zO3cYfNy*H8H7GeeEIH^IryH_ltEVDDyRKBSGdUyq*^ z?sCYBqVO=TJMrWb&di`d`F&(pR-)UTsD?N*LqfWoq4JGHw_XazZQHn17g6cJl0LRd zdmUR6<1uupuS5lA=Xm3=1NRUawf(G80v^mPfEn< z0ISL6>Q#{WqD)UnOK~_{J>u0YKdt!b?Bs#+Aw8mOx?KIW``MaFUb1HBiLKeJOU>Qn zc4Kty%je~$UbI+oCFKV-xB~k!+pycJuV$4|eo7N$g3rpV0_LpoBG!*7S?Nh}DdG06 ziz0P9jz|iYYof`}OU~Yrl9-q-Wq4ZBFqoX|8o_pkAx&s_S9+k_PPZrjIe5re6s6*p z@^y?fW2nwm(b|VK-gGHPNwugPzkk(*L7)4olniJ~yXpHM7oL;7Ys%=z#BoxO#jR#Ik1zE6B#1lw@Go23_9n8lCrkT(we zXq3VF;W;YB%hf`S{80G6IUM=r@wLvE^J~V_$QpHg820$B^mxpnxgCZ`s(j*GG}OuuB6Lhy3pXx5T(ZRZd`BaBN!W$-Ry^HRX2&O-qf7 zj!^dm2c_V8axxZvFZw+RS@)2T+msEkL26SneP!lnI!p<90{TCHA?X zNcmNC)}V2H2DRYJ@;n|ahD>oHgV(xgu!;54avF0QLr#4W6|Ft3a?93|DHRn{O11>k zNG8*HFeWQ8F)LFmqW_S6CAXnPfH|aWikJyYN@y5vU(1#OBp!4FwYf}kerC|;p>y1 zugokhEKX0(4v$I>{aw>d$xKM->5fiFO$ZCiiO&r?D}HEtoHH&uBrHxY`#mG3S@lWv z7nDx{?GgE{B(aVhJl#D#sfWokgc+CtW)K(=7?3C^U|iFpt_ekdy8c{O*~L{+46HfJnsHZ# z(HSHz21J?H|L>`~@4nYP4eR>z^XJ3de)rtEbx)l-byA(GS{QaKuJ+DIC?7UCx_u6l z$!IN1_jzIgoAT3ehFzE%N>@gb^E^RTH zLV=o|MqC0+Sm@BJ6LAVrIg=T?4RdylA2 z&y9M|Ma{RyRA`={{GHF}j`Md8;}k@SxruLCuo6mpi`zy5?$*6Ti_x`~kK%N@W_gNm zi1Kz=S^|FQiu%K?aBk^Sd5X8Ayo#5wg#Uo-o*(J9@*YE&Ky;ZFOX7XT=e}x6hh)k_ zcj|@s@`?E{-j6g#h9I%r=)zxS&sva~D;73~%*uQ^U6I=-GO4kAc6cte5UC7xXJ-eJ zQZ5$FN~NVM=4a1OO+?F~L~lG?4aY|M5>pphefg-A@GB*=CDiVU`4X9s)7d`R-8)|i z>PKCE8)I_ETvz=zl2dHY%$2*l{mxKNz-uy@UGbQl3R`|y0BV`(g%8Qa>~ zb#~cT_4@Vl@J(Bx1!@EPZ?u-TUbPs?<*vz3bYi>Hy`xim2gAX%%kAm&^%NS$Ib=1W z)_kp=StnB@1fhpscpZ9jwzZ%p8;oXe$^D79?Xz@+*qA+yU()(yIGmt=;3>5xLqYlz z#&KCPA`gssfx|gZ;U0bM(Oo6rm^a+crGkK4bbqJ92V3Fr9&b|N!>w?5kN={=FI@o- zt9EQ0^JcB}C+Wm$?rr^9x*9%yf@?wY6G>4tV=iDEE>X#w9t|hwuRrUo8|Jf7C0Cv= zmKQtX(&wOx@7#9t!otnlm{3f2_N*@!*Z0sJwRi(EYOdz;@vFSWPRtfH;pE{6xEE_u z$-@!lX#@+nr{OR1dYW)IPR6Aq{Vr?%%X}ujcwh&?`u5gthk1 zYvluC-d6OJK~doacwn#O{Y!Li%xMv4jdSTGBCY8cWG*#Gp$e-N`6-_k_Wk8nzm@Y| zG%0v5Er*kVuJ%+_UOAQ3KG~HtA7E=TBr$7Y&z6W>DXf~$;@tHOt(89b$<5X`xx$Y% zvKpM*%%T@KocFR9HZSAj{0{7n6B6UfZ=zHd=vaM2@A^!>0SQ9M_^c)6amUTi>ZOt| z@A-M=>mKR;RLJ2xeZSwwd|qkR=rG0-h0~{z3`m(`Zf;F~p65kymjgAMC?$<&%kWQd z&5mp}1ndSBJC*fYYcIa5oF_Q7hmyItARu+FHsJy#?IC5bcE5RYm`t4|-ZaQP|N_qUD9!K&}V* zf5Kd0B&IRvLiu`%$tabSl;i8Op9s{?jrrN9>_vafUte$(9CFh2&FO#jOP|a7eV+QW z=R6jZ!l(bu9f&5w(t5W)oH;$3@*`2tci?wXl93*0g?0EgWHe5{{rXl8)A&H86b~6y#sw z6#O+>40(ZkY~nNlCkhI<8yOEI_XM0MNN}UxwyRm1Y!Fe}uKTp8W%(u41`Qt8-H+Lc zMlD2dQQkpON)1j@PrzlI?n}}|e3hhu_-bHNvvi{tquxJDbVENOgPG5Ai2h=&LF&F5 zQz*I*%_?Q(va|jQJKIdesjm;`o$O{y{rhx>P;JELtNRTJ1p9Nc&&QrLsydd}&nfn_ zO0nN_+y$H{Cg2|3%`I@Ejey&A4+=Om0`Sz}VSOVj$Af0f5TSDxNx!E=~xd(a;CDevuk6evazdkV+GU~82uTTqNRwkozOjkwNVZD zcT~7hdh}fC6<%8Z1{Io@9z9~@?>wcuia*_t)-~QKNY6m8fsaFQv z@6c-gVDsrgKgIlXAK-Z$;=9*3pJL+GBs~UA@cPEP(r?tKCh3&QaiVQa_(@gL5`4Y> zuvXhiOb4Ll>>@tLQe381G~Q~o!h|@akkbN}n^wL32y76_@DxwCG@oAk2(^QaLAy1c z9#fwdQ0LWHcStQ+;`yZlHMsP+_RXi7JuQ7ggFe1f@NWTUxTlb7iP^71tJssvNt*p!o10aAtj&kE z#N(Djh2T+QB z!2vM!lQ$yVDYA-dB1Q=!ahsWEv7#2-rkbfJ12qISnLD>>s`#>OPaxBkcKgD8a}sY#|<-!S55csn`>v;;OWn0Gl*Gu ztD`wfzjJh(lyYUqs@IzKFDK{=ia@?Fmyj=P2d$aVO<@dfgtTc$ zLLPxETR7kgA?6GIicO@>Fg#iHDrzw6#gp1g?;nJXc zSm)4=&YO_r9yucU*Tr@MvhPW&i+2?mha9Y=9mmZlJD0{x_u-Yid+)M6V7^=y|%YOJcdXm(8}X z+g`3Mb(tsS%1l*>haxWb@VVWOQMbHPB(8$14D(B=MHbw^Eur@dxR>o38n_;(0t@J6~ z#f|aOQkura2TMQxrVA?A}#I(i9yrw?GQJXhZUXkRgbmsVym9aL{3SJIG!OOArQ$kBx^B!x^ z?#Y*fEAm}w9AgJpjY^MAt{QjnaGF|?j0FW#S~Sr@LCh641xzXC*?E0q+(}p*b7Q>z zCRv}=On_{)VFH{7z4-D?du~=0HU?g_lk4=_V!`1yS`t3e=_LE%owARkhk}@ABR^Hu ziQFA&c&mN1ijACQ)$wB6$+n>NGkEax7rh zdtIabyIKs(%Y+Lhbd%t3!ky&NFqc!0s%xx@$UYh45=p>M(d-H5_?7UJl&#W$>u0oj zo~Auf8gQpzn%m&uRUo>Ot+EQ#Vi;*R#C~8=^!l zcM0k-Lci#r%aZIElv3jtO)Tqpm+4ad$z*>@+(|q@`$xT}kPg84e?oi}xZwL3-G5rX zk0pTP)be)1Mui)tKa!kSew0eKHE+~(^kx8G3T2AC)XYs7c1n)foee`{VA=-lzBuSeH z=qa9+O1}Q{EzpzqQ`y^4ua(PXDr=IST)vk2hxXsXuG7R9qK=2})}Z>YsL;FwD3^wL z-9G`xHCjs0<^8(*wf5&FYQIr>#!2=4lv9BuxA@8<-vSiW(IG>YD_PQ-4ywSYK@P-1D&}11ae@1ihXJM ze7u$gt0oP4{7y{u$t%ofJq10)$cFGZ1fOqUDt?4I%pZ&STazxF>1ZOEiN-0r0u$io z68jJ8$ohrRgx4KbTJkLP1v%=A1^5M+ej1qebNMP-`PiEX|Hqd{b>HBv+=F%*rQ=}~ zf^4T8FlEq!gPRHko5ZnSGHkQftTl$i!Qs z_7fw-TlgmPaDEZclL!WhELjgmr~_HZDV;VW4QYz8$w;UoQ?`caW1&#v({8tm0hwl5 zB^|6k*!C-5G3@>HzJK+#Bc{d2Az9IqlJ^D!^~YZG3*YJA`2T(TzxzYs6!q_h`u8P# z54fGpdvuTPt;>5gJZSv<4e$`7tbV}@;Q@|BXZfM!OR>vn z^V`p1qF%z@1Ul?)d;)uQBpZ3WT5!b#GYJHt(1SW0W1(Q;$3~km6!bWMY_z|xL3JeW zI^(VjBz?~544N*`OCngx84DjEjiTQJ-HgAm1(X6t2NZK75frtr)-0>oz#KAXlYZlyo>0y>DT&`5#<%c@3#=GjkJqqh!oN0)Y|`OX8m4D2o_P51<=^VXUSW_N%YAx@_`rD zU$=4Nb?e3Tn)Y?2(zX6_pk9KP|j+TC~u_A|}=+l~iyukhA#`EjcDEbb~LtfyP7(IuF zJko3-*eB+OAkhwb{w@A|KWI!Nk?JH% z70(;*Q4C&%KcZ#|a4K_qOq72@2eVHtzh1&@ms%)S?;rPx8-9u_$ z?w6YHHJ?ADyRW6*1|H4lkKlZF?YkO2&F4?(-qw81Z79OG@f_o6zVY^g^o)k}ue2B> zaUMkl1f`#9;V`ls1@!TKS{*zpKu|;l_HjOfwb_UYEbyp6>r)io zW80d&^-~p^mjLD5cuMz$2G{F9y6Wk}xy{rX4z zrFnuu%o8+cOexj?YX%9L+Jw34M*MB&3F^;4_wpst=MXkgTgi2whCk-mp} zJ!@h_5r*Ct8ofx29$w8~7o%4Yqkku%@LWp_ga=C|Fsr<2MTnkTSL{6;qgKC0wH_#1 zltwfjvtIalgYarhwoIib6mL)aeF?uem+)cTm{6YQ&IEHIds<1woStld_6d;#1`Urd z5Z}I6<=a|;{lr?;3_&iLph|O$9rS(@xJ8f z-p-M$w>c|rtKJh!GE*olhrMQtoEfh4%;jCFh^yqW>+Nt?m5>tgn9Xu_sM5QTYo~Sz zT#1q&QYra9PDu{ezgvYDpmPAnXg{vINB14=J)$(d2TJqxkK(OQs?a<^`8zl3PV#pS z6J4}-et%gLgJw-9hd2~{)+|f*?8V%k75I`pEATz8S|maAT5I`dR=^wO$ribpx0AmI z2@{7Ua}7?xnW3y$kr%FdHjp%?0_Hq~Tt-k#?MQV#2_2^f321jAa5MaNu64u?0pRja zgwv_<-L={My{X=)zPz=6;M}pnS-0q0Ytoa*xl_ZrknD1V3i4n_s6FmZAEiNdZrJ5Q z7AX7lz^?IRbyHVnpx`h#2X~E69UM%_qNA-2tlRDw&05SMpFd)9#PY#x#+|6f>NChE zzdnUEn#oXztWC_kvX@A&fv;SEf5_F1*w_UgG7mR^IeUZ}!pMYZg{L_G1O;sAax0b% z_-uB+!>NpA0=?CEMsg&BN`n5~fI!TQ6RZ|iqFGa9u$z4;oIyXUUqm1M3+IhLS-z`6 z@6(T}P|S4cj_WoO9CMbyPb>X0_H`{^e9l0lmgc0bhyq2phfBf%^;ynyCv-m&Qi^|xY*B*42H)B&P2)g7PaR$h zdXkTs0bT=1E>ZSLK9m-_^5%B+pu1>10ypGFaf|Hd9c#D-v-*3LxeBQ89MZFC?n$H_nDu1rw(|q2rQpNjZ ztF(T4E|cx`AF(&9;(_C)x@q@5>+Q zzJRvIv5Lko1+k|W?Eu2_K*a*8Zqz-g2U_(?4vp32kM z6Yz)CY;RGXxLd#?dfe3;Cy6qUKszr&wGiV!=j}2~FOJwA0Owyn?jT zdmOotzuqR8kQ7W|d7$M} zyY8l)Y{{x7j)ihYERPfyi8?4W@FT1e2s)Zvb0RefI!+7Y3pj2`0LAQtkbmR|TA?MsV0@{ms%uA5r?ax;iNa3ktYu@Mj1P`+=esH2ZGT&GM{2 z%s#_ng%7Q0nIZ73vCM|RCayI3C5h9Ii~Leb@X?EjEiMkg4`2t>G>nMHSc+ZGNND<_nxQ0#3X`aOhwy zN|dJzR}RffkG6{p*NX=J#HToZxoDa{*ig`V6^y(_SwtQ9JY$Q;aCl3ue~WUl#6 zvjwg1Qr1fAyN}?kw?=NO$XZdK?i5kEuojgQSu5((Z6a%>%42d#&O>Cc&{M?Zd>XD? zW(w%Tw9gP)(8x|9C`HvkK3`#(sYW6N4xdQrlui)>3 zRObABU?qQR8Lb$p4QbfeSd`fPf8zIsns3qa4c7meNOSGz?o7IBQ}NoisyYxNv$=Xbzd6;2i|sDFXQg-D6sxkkk|JJO;kS4*$zN5++5U+afrj zU;$c2Xc#RHhZwgIAy756)TBU;NV5#7cvTI7%B1W`+mo1NPmUd)o<2M#uGdU-cTdp2 z>zu(h@7CA9bMtHV&0bgw$)U8{HJIt&)>YVf_3%EkY?ZO^soBi7j-Aurf6mw#ZKg5Z zJu=eWH8S!In`g1@{B6SrM$!W@egq$^@rJ_yu8}kyJ1(Fw? zPixShY0y*iYe7$L)S&uat?bhu(V(=Bg4av_^;>WvS>t=}(@H;H;82(jhxiQP5RDD& zjDIg58_3l$Bs6$Iz%gGkuRp@a&~g3cqTKRmoAiR^5aFhBG|yrf6z>_%((13C@t%pD zNA+`TNA;Upp3f6rkdVjOXGDF{t)f2Z-HrOBBWILH>#01|hk<#G_8i~g^BOJmr90nNp^eZ zQfFm-d187j;tB=bzxB$BCshg!mo``1OFiAG!Vvk<410BAT`6((i*hvEQd-|pT_}|n zsvYY~=VcP{bUL2MNV)2Kd;5H~W1(DL=tz~zsYH7_Yy>~rO6M%YI~VZ>zU!(m4M=Nd z(v657_9PcKuL(rju)HW5V4tL`yDb_3`vQG?q?}mD2d46yN_J*{(bx2f60-%_g&L}$MJUoq#l2dx;@ zp3wMoV&;N@soL$f%XlCo6!JY<+@9ze^Ckmsb4vCkJ)wM{|G;$Z_K`PQ2n)zS_PF$K zw9@_93eiN7J7LFRAB3hsM=qYJz=c*rtiiYjhaR;A9G=cZqLxkc#^hMUtAuQ}k4OH% zO}(B(!fE|P#8z;O?CPApW+}H2mR+gW8!ZlhVyKw!37aiR*(p2jQ-uBJ2wCq>x0%Nd z3@*N8*z2;#910vKMkj6|9?W;lJOIt*QB12=NeQQu(o9~3{VcxN#?I%&+7KwX*r++| z#%2-dj~}%?#REO*knCl*+8k=9Fx@0{xdGIGguonzXxNH%|0-4Tyu)GN5)-GeD_%3M z_TRbf5r+%yN9LiwYc8J|N+mk-zEsjIB@EaHKgAKM+aeBQu`e`pWNh|2t0LPnZcp52 zb!Wy)`GL4U5G%TW8;B4wEZ@vqy$&da4M)c?QhR`*5$o&tek$tTo_g*vQqMT`0u>S3 zJA>(C1G~mjuKeubjdq)oiv`m&L+#jftbL?d*ff!!I6Rf?jmLYF{A#UkKEE%$|H#3m zfIgU%QzmO+aK4>+3bE|Oj;_fgt7$2kEDsonrF92`N86hz;L?j zWT+CwlKonHsdk`C-6MUPU7&adCeuUb4dMTenGRRfnj0<*?i(1`H&`A{zbaA+g-VfP ze}8?)NC^qCk&aktgk+HDov&jxAIvYY(=@uIF^({2*J5j(k<}Sl)jJ)#Cc!1xcxU>+ zz{HVB^h&fh&HG0BdUf-G{`C2mUUXJKA4(`mlXL2v8gmz8Lx<-kj!ayZs-<(axagpU z{R7zujT_*)>Ht<*Q?3yr#Ox4uW8!ijy{1_)U?y5!p!q{z>R7Cl7Q4FFw^!D8#8XMg z{gkzD_dsoTU*GQ9!0x_1qt)st{Ue!zZ#>P8Hl$=fq@*ALMhz)449^FAVN<)wW0vL6 zexFs2hQj{Gg3&f($`x|f%u%KO-~KRaLZ${zg2A2uLf*pn(xhXf&Za1WT%y`BBKP~l zR?CJ+!SAsvW|P}2E2Ys$$52?#24;*e^(u-t?8DyW>%x5@Ka!x#Z6UXkmve)0rCRb2 zTNRH7Ow4qnpw0;P?rKN_p@)U}CMdI7K=SXekdObI=yJ-6w+)7Fz$51pK~K=X#h>m)Y00WKg^wIqa9Mo9&W5*&8bj z#|S%68D|XNKpwIx3v0bS0l%tYxquS1W>#Ogbi3he?d?y=i8kX0ZDBJfI5T_RrWA`& z+3Yoa!D#}~Pk`vCxoi1ZHqS1n7z&qyXSSQVlYc=aI1UeK(FyMfbbA!9--NATkXM+A zMLi*}HR_Z+davUHK1K2Uea4Y>_oQOIsg6w+yTcptcnn5^H4^m3E!LFd%~q%E_68%j z2g2b{f4OfAMhWri?{GrWb=U<9Ef>7Xr7k+WkT(WQLiDfVTdW_=hOpgHM=?|_jt_cg z%l$LO>4HBFGbt9ccW*BDo;4f~DgKDr)HyOgG(J%+PvsVq!9XGr2quXd)#YW@&n`tQ zOUShWESOgHp=iActoUYk#Gt>%{w|*^``#1AktdfKgIM!zvYS|25esqsDQu2odd7iD z^pFz2V@o)RIgS-s1C6#IaAI09{!9hUbkT;P(mEsy(}i%}V+fV9W4YXDwll!8rNUI+ z6ApX)!Jwa7ASaXdWIyb{klAG}CX;lWLo$;yJ6*joz<(QXdi;KmGw|V9z#qbC2(dNj zjNVt|fqtYLh*r}O#wc@2t@7d3MBw%@jlk6@BD<0HEC#LZVRdVa29O#4))2c& z_eqpN>~VPrkgnxU6Xd z;>#7h^)G0uLWiPuBYf$)g~GQ}|@14=+%2Auzhw}`!OK$#+YEpYxbAcXU4c|F$x=RW`fI1A z2}6{~NcW?L3^c+be7^;(?G`0Irq=O0soqitzOh8li%dMnh}RFUs^QhVh9W!Fs6oG; zm&h&uk!|GPxLYmpoQlQo^hsW#fHSqWP&=*=-}oNN(P{yv`#e@!fJVpE$vu)!qz|u- zB@!_QU05RKp})A$JJIE1*n#5;^7@WJa;oaA;eZHvgi3z8R!XsX?L1;gkU8M|i+`3>;p?Vx1Z%-iCK5=BGXHzX@ zVv>}jxs#_`nhz{v%kAt0<{CJbhtS^Us%aR6u*iTKNC5K{HZ~d{ES5k)<^KkC*ahiu zai)+O&P02B?hcvI+&?&bbWJpoBn~W7{jFGDGX26>GVC(*r0x^!*jgj-Vy*R0wzdoj z-ns|bD0@PEXNCR!vHVoNFp2*Qg~e_sO(+9#G@E=BYy z+TR6sC_*-LR26w1uzOVrT2fZg!_IrzWf>7V=c$B z1^af8|Me`}%PvEH4c95?0p3nyh9Ca%F&e4QVsK*zPNd_IrWECY!KILd^!{_~2gsam zzOTki`1>qR6+EZq^YHTe*%vG?y?sS_{yknlzK7VZxTp7Ve^kBa_&4#v{L34#77zIF zp5t?rBtOp&L?Qw9JYDaK`2G0frxkTQEP?jl$=@&X`xM&qR{lNp9^a$;qwq>7hhUNI zg#3q3wvM)h1kVnr!5J}Qf&qxnv8>C!@$kR^;xMjYI54y^m)STHh<(!Bd;49xcHMP* zuQ}^hJk`r@oSC`#^0F)BO`~oX>Yf*M3$9bM?)bpKjsQHH%VeBFg~JT`UFa!?^ZfIKw> z>uyZ_Pzom6E0MQokHKVEza=3l#jwE_iTI46f+Bf}^R;Ny=PDK*(r{1Du;eHf)4^{r zSO3P&3-etH3;X?HN$JX6m>KKJ+S+1%xW>*@HF@#yl-uB*8ooGDNx2;{55)ppu+VQu z`$rpnM~m1B2nhr*dN{g*5}XtqF_l*{9AT#ffrnjOeXjO`LmKJs9ue4h8i==tnuxpG z=W7Pj*HaE>0QhtyE*_b5W9x(Ai<9NFi|}F2ftDt)U}s)5fzi3fOUu*jR$!`njFe^2 zKm|vPsXuQfUVD%(f8S<*7yZ3I63~a~2YjW|U3U6Qed9-M)bFTmN;vdf+f$`{<6qut zrkqio^w~(@`CqH`N#7IofrsPE*Mmo&#HhapmM!I|U611ix_ldZJq&Fa+~3~s*YZDp-5Vm+>D0ZY4H$WC-Y za(s>b93I2#bU%S4G)k{~p4uD-{5XfdUiS=#zurcD?1Q9y8rc;HJHcu!pi7~wIir}c z=MZn&XM(O{7R$BHpeN%v|B$gQ*Aw`l)9JE*z#maO-dDNqFnP_P=*qfaDbnbK#^)os zhP|1&rdhwLE+lpYKIm{!Wl@<|hSQ#Kx(qC@1bY*sy@hRr+cwU~ygI@U2#Vi5ZJjZM zk!J1jr2cXK+rocKuj@*Lzn^OV0sm8?mZCo0zw!E3)P@=oQ5kO~lKRG5#3Q;}*w>`8 zO2;KmM`$Y0@fKLE1SdKY{Pi}1yRZ-A<5E9(?{&}93b8ou|IF`SZ`+I3_?G|7PJxHg zl=G}=fF2n(uWC*RQWx?_aWkH2c5GKlVV}ik^!eK6oJ(6>VP`lH_JdTJym{8SBSO&* zCeaB^ZGmK1HdMpx)(uONzAfqr#2CxA*I&6b#}3D2IU1E^inSD%&(*&hb3og42Qdo- z0~T{FYHkwbE$E9KsD%v#`>nY>0tA{k*b&MF@)v`kdFlc&i&M&BD+Snud36US=}oEO zxDjEW+H@+nuAH0N)l;4}L;_Mcl2O`TfTJkig#_v&RtOdS-6~(4FOvv7Vpk@v6aMNrkWfWk&BDHoriW0j1ElQ z;S49D&!^)Z8_(^UJ2E6hoDM2goO&34(6g$lC4x2N05~0;2;o4R z`3fjg=3hFMnXhf0>x|D1b#AC-j8Y&JjvFk!JFaDZyQgj8*uhF>IMaXr%(}~c%p486 zy>0SPzS>zC@+CHHo(VV{igo3vyqG!N`$7io_D02yR7-Ktgqy9xvl1?&8}FLNObDQ=0ws`tfzPxvK!?{((d-|OrOa+i_<{6)=decE?Iv~eP9(UAZbod?EE!*bZG3n^;FB*n}bH#xz zIPuibS+OWcmoUW;|M2;ueuu%g>#_)QguNccm^7NgiZzA!EalBV3GVY@-g-0f9~p8q z9LdI_xF=a&jor=SQcasT0W~ldHA?UfRyy6}*2Tu(k&CxfDqAid8M$an z6@NDlTsSp)XtY-K8|~Jl(-CuLN3!|Rlq=?RCaq43H`t4F_HJElYz9x&EYka<7g0SI zjZ%FJz58d7?-8_=-3|l3njTCS24m>gHix&}Vu!Xd==|`{euVbr`EDdgqH2xN2+NN5 ztKUQ(C3r8N;hX)dNe8sWzoNC7kGC^+qPo}SvRigUOPJboGNw10jTWEDj7W3A>>PIb ze9j)Dp*()k=;%e`I1XU!!tss`9rXXkYIP&K#O1i(>?kEYNwdMC*zE2$qrc6BqshZj zr`xjVaNU8UlAXqB<5Sw}sA{;nkypWMK`;8*cIi0w)OBF*g9*{brXi+>Wy|-g_JO-` zN-qy0G;$I8dqFr1fI^|y!+%hs=%`0gJP){o9_64nyf66eK*;*axtm;BcR;3;i;3r-p?DLpAc&lXs;NQD8l*=2sy6M`TDU~wmQi;8yx>&9* zRw|3t@?v$VH<9Y;$|QQp_E0rBe3dtF-)wUER^6xIgOV@AEvH60?57&*<|oPB((_za z;I$6rKgY|H1-9Z12qiKw$k2s_ie0YhY%J~-^1tjss)%{$`us!9-z0ykx?i*RNk0P? z!mgtV)anYt`%pc`k5CYa{w;Df>m)TR@tse^-s#_fN+q?b=7Ri={Z{%vn1w}r1i2sx z2%$?kI}f0*Yna&V<06&3c6xxg7D-#d2PmrN&J`DE$fKUzz0WAMNujF6qy!xyyCJo4 z`m7zrvo{&C$i=n?O4vf(AKrXHJnvBgo`A)E_HMILVn_!K;8<#Fo88FT+P4-5_m7-6 zUp;$oJ8PTF#qDON!Q<=p$SHP*(pmL~W4@&SN((r*s{1OtT>1s42_oP;Dz};{L?=+4 z;)+eKzOzB20iw}EM52eZU(#Jf`T9Y+E;oqvy2cOc3(AMvBW>op&k@x$&O?ZZ&frE` ztSZv@*Fh#9HZjUWM3A`z8Wz~(jvLplyK%?T%h$Itr>%ajL1M{G9TWTWW}C^?)^W*h z3zO2Ds~wvXdW&`G)!Vk;u{3wxSyq?%>yloIC;Eo%R-4H@J;JuZF4D7PB9YJ=-ft$U zwE>rpKwnZ+c|x}d+Dd3k4a?Q5%Nd3?KiaIxQ!9=>V=MT}@R5nblVgWQM-Pon9-g=+ z-kXSaMDag1^M8IPKMHNd*qtaRq1#2FpcKQv85JjOvd={*@{3ZRn^(BnbzlTjoeexPWl$Xrzrh#d-($KV8-~5*z|2;$uvwc>wSGLoyh3?ZQ z2Bqu&k|V*1r)Y-j3F&*le-ak%n)ri`_%@Y%-;=%ydtv!s(es>G?`eB51- zJMbP6H6d?wV4#gFAQO^qkg`fU_rM0^mY)$8IMJd8yU%27+CppF1vkrqbv=9=>>0eRLHi#uohzIgp#oS3?vcg14P`M_)YcJ}t}?Ca-OCGK{|73{?7 zPD-A@9M!ZgAUhMXW&WA@K&p3_sH(qjSMTM4 ztgK`MfvkeW5NOEa@~t>W1#3954wNDl@6pjZA%1c%`%g%oB)rCP9d_zF*21w$V<@Ux z3)_csHNA3U&K07DjE|LovMb|q? zo_~ricU3m`^lq+12MUoBw6eQ?F>!de#naz@zMS#+GqRlVdopsp-Uw()W{N3A`~j$1 zJz_0?koLkCCe4c(JG6N&&U){0y_C1?!Ij`UE zYjE=D;km7s^jRHNqc_xVM-~rk8#<>KD^xyCayF;TJyWmEBFtRjE<+ zbN-S;Uy0{z%a2KC!wRI{nWeMrU#x#j7@Vzgl6t5^Pu2^5k!8jgttc3?@@VG zkhVg9L)eNC@&=xr*TvHmf6OOIl63t)?Ms_7o(`u)u>?c;c3+P_IJY?IwMRo%kKf~s zMnnFdUhlb%fWsg1*DhLUUxzeAQT{D+p*P`?NwHdjPZ(pIxYKc$${-HGCcb(67)1A{)dD~oEZCa*Wq6_!V5rlW-^ zq$$ywvp+}^7^4xKf;A~5wrY<0$X|nD$9ovw8<7L2!HRqMMWEFR5JCPt(m`61nPQ{0 zio=+6$K!qbuKWobV_WY3E-#3LbXa8i5*UVxnzrU<=pO~QrIw_y^kLr zE9tXt>_3I$V?V6j^V4KWPl}UV$QnmH0G3UQJxz8B+Cm6xR$%L%RP5aigS&nTr_S(Q z@iQ@;Iy2W!r_QixJ`&&0@xppuc4Yfa3kx@Guk($G*%5I94c!3`+Hnh+40P5T5}wH~ zBteDkImP(E*=v}i)lBpi<`l6MH@Dj9OA{q_Z!eCC&4f4h*4Jg(pI_i~SyrZTVYSi- z!Et?WTGK?*3@DOYj{(EK1BP@)9HMwCj;h?kIn3Om7Y=KKh`z?8Ho2}vLP{#p_17eu7YXCVLj8LYE^*Ea zvrL7b0kK%F|2Y1e7i`M)O2`v*Iz2cW-tWK66AF3#eji4i)%t@MYZ_z_1Ene3+Kf1A zndXL$30czH3l{jF5Z9}`Bm9&LIn|5I_(Eu2MXlo#ighAA+wdZ|)t}caW^N%b!`1q% z@Cih$2C*V0dR9$l~R zuWss$cSV^$g~$@l%0rN*{?X=h<}c55(II&8a5xelNLO&gqHu|e#kp#Hyx-$-l{yqU zHP0M|H_JZUcn)dSl>P&{{TffH*#AwX{aJrw3D3s=wvt`a&hX(L(AuL5?1)(oqzS;4 z;47+)8ALDjTzEk$tvuUj8}-pZUfNjhrC*!I>ZTFtfxq;;A0e;&ev(&yKYQ!{^7J3{ zEwTpq2|1+MF_-ybdfmqd&zUFaKoy8aeSq^DpGL3$r1^V_PS$zIn~gYtLnTolun1( zo5HD77=u}%0imSONoe&A>;cKiBMze7Eqhwk_z6nr2=zpz!-2GiB|UKCz4c#uPt<>j zy#cVgBm_#ei=CxK_y+qh z>a5>Kb+UDsIHJ$hKWJhH?AFu*>NMlzGSq3d6arSC_A%nTaorqb#2!cp#Q(U2c!4HB z;I;T^Z^900?4YUsT8AU(cgEdpkHc(m*8VukWL11^cBE&E1lYyuz7|gi}%FQxVE(LcTgA#y4mriT-WO z!y~4tI;Z*?^!iIfd57uU_EIESw7tjV$cOD=)BA!SG=UzIdS4w|`@$wEnu33|Yb zbe48a&+IH!ig&{!D5X**zuD)$yI48s3*OycF72F|-c_m=?sogk;wkmF3;A=%=O?}b zB~|;1A`c={Q|&VzctEe+7OQ3QX|LNI47Z)-KW`>p%f{j|&WccMh9%#DyKJ#&tZME{ zuwP$&fgOV{Z;iAE>fx&|z?YEiB)uB(5BT!xIyyumN$o=sih&4vVDf>c9(Yfw;f#je zZ|cAS&Epc=I`z^W-HEP#C3HzBkqEur8@C#!*Z1w}@7vv%8m}0vaqrvd!Bt7Q)}8F$ zafS4ijz5TyLS%s9X!-;K%kW$B2bCU?>M)6=B3-< zvP;Om)JY$az65&}i>MCCm^{VF5rsU3jTITY{2;UjlQeCTKGJc+kBOKV>0E{6DO~6;;y~{ z{&FO9OMyoVr3IP@x-p!)CI7WtOnUCLDVEdQGm%g#6A7lD|6MMocRc^wSPoRDH5tE> z{(;)^GW0L9Q6R;%pkN9SUnCPXmfT*EE;8l2ZU3RLVwz3TH|kHDzu7dTwDfawO?cTI{bkdUNjOd;lSuvlBVE$vM>%b0g_I!;RL&u&jNV6e5F z{wJ>sy+dNK77_D$f)OGv(4uu{dL0ykYamp$+BASwrEj^S2GOnbN*!qHpi9+t+m+ z+SyMhb9HSjmp68)Cvz=fJO!~nUd=|*BiI5Kr=%60>_e(uSh~d4jg2}AbdK2TV+ls= z=`QDEm4vGiIF=0Qv5F-Tw;1AgC1N7V@ss>SE|BkuaR;G(jNF8n$y&{uT#oSDXdOr! zWjyG;(wF(1a~av!h?hbh)A%L?xXfvtd4{L_g3p9y*Ib|TrLM)&>XoDHTWc&Qt>3s} zB@dfib9rg~oHfB)SFQWenW#;Mn^v@G8=YPE|In_#eVf_q)*!@b$NvK%_WVWUf%aMc zBQ)>b*wG+KGvwS^=Jq(I6NN8bkfCyrzXScFu%58*yB5p0ag>#p{#rvGgW)Zb^cGwh zGly8p>2TRuDjcr=m)+%X)_>`6+-NZThhG1n!SEo&7ozc1X_DPY`wvNv>cq}Nui`ro zRi!z=uSCA*qdKvxP?_&4RFyUZ{y`2G`w30*{e-ap3j3J;dV+^_673{peSrvmmHs9T{s>Noq&g9pN)g(Rgf(R&E(K?^s_Vnuw=j@kbNUcq|i(OS_c_wyKe%-nbvXqH-XH zU!+e_r|#o8T}1Usn{^yj&jyipH&6aRd8AR}EQX)cx&iPpI!9H(uo)l|{t1Z&2ferPM^tAQLw%&UUR!0Ze>v4Z@0OyagVLW zecLLy|3+{juai>rNI(mVQB;d*xF6;wI_y?I4!LyL5KK+koFRmMt@e%yX*f`dhvGgD zqLpY*EEq52U>M@HJ($_m#++MG=$ z2QiCegB6fTcuEQW8|DP>#og=<=@U5d8sF*fL+4>3{K1}{XL>Ngs+CF=Ws*|A?l*eA z(rBBe*3jkX2esF^)+b(q!JQxIb7v!^DwyBu^gA5^i^=T5U%$nKT+>p<_nNqSC<63C0yqZJ=r4PqCq9KqjSc`NN+HK14B z5+y45>W$dtpZEisTez)ah7ZlcH?eBshxzdiyUp(pgq(su9N~a3V0Ba{q{mnBN20|0 z@z2r%`;>l$k3C@%5chJ!o2>tav-amTbMNnYq1^jL_GYG+4s+?(Pl;{Z+QHafEOdlJ z(LjDHd-K6~(woV-k<7;Xd3nF?GHR*MrsdMG3+JYTRx04u;a8hjqr(THRKPz z%$f+=H_zAXZ?grQF4y6|hni)&>~c4AW2OT3^)W88#i}5pVZ-1R%s4Lnyu)C3V}7Ca z#HcvmT5ZB+w&1{Dvl8{RoDn7VN#pnovT>Yd1&OvxbUB&{RsI)Cw4-YaG};MaJG&8Q zwt=^(rTyOiCr{1qCxyH<_dxA1{WEz;H5-W99DAoFP0Hdmq5wHYC< z*}101Du9RiN)uJf;{G_lSG6eaAK~|^PQ?8Qey{2`-2X~_pX&(RlVw3#dp-LBJTX;k zgKgDlY0IiMX?US&veW zs(5fIjeB+Fx{$88$DF9zZb(7gV-}Zl!vCH#!KO5_Xtmc025s`^yVU*t8tkbZ9YN=q z)v}7Yl|8jHB1p&lkzJ{$wS*XpFKR#aCt~qwvuXqj+C{ca>4O<0T`r#0x=F1@td zYIj@AcIyIUnRCHvH(T6xYd0SYC)jTN&D?&{c!VrIiqdHMO;PTl%AGh^yQOk3cK_P0 z9~iJ%+!mAFChE4?O%}Hw+oC|;NMq1t->0+d$l7h1I^sk4$PWj%`N+`WimWRj>>S@V zX{@^abfzDmC=z`{u+$iT^yfkQtV_RW**4*mR^_RW);eKY*m+Bb^F;(Ias z#)fpO)%MNukEN&C<@$Fvy#Ssl*fg7Ky#H4WuwyF+*nKN+rKeYoH|wf<;)x2z&W-xJ z{!05sf7jaf&0k}QTnbBs&N$@qa;4-UOXMvrf``WZ@`bQO9um^;e`SgM!&;UIC^5S{ ztos=-z_>>KzAziefPyj6-v@Rh1BY8wKg0H9AqCl09<$A9H5uUv=Huz=#d0|&V_8X? z%i*xdzM#TSTUM^O*37&^g6!VytfY2_-6lN7b%<=H;nr&QZx?edJT Jl2>2&{{USQh2;PM literal 0 HcmV?d00001 diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Light.ttf b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Light.ttf new file mode 100644 index 0000000000000000000000000000000000000000..800531084fa6cecc3b7ee732bc66582d0f889aed GIT binary patch literal 78660 zcmc${34ByV);C;Lx3{E|kbO_n*#m))bapn$%Dzb0L<9l}VF?L@u&T%?uH%9ZGA@XW zGA_7`-74hKmB7jSgjJmHhOOTl6hKx%8*Qk=WeN=+j!4!KSG)s(zLFa z*Ses6=UnG2Li7p|B60A%w#IogZMR+zdfW^9Ch5KY8Ov?B71HY!U2qjzj%XEjaffiw zUBJ&qR0u!nwSjk?x1nRcHT66ip=C3b9ygjplZ9H`G_#$VDV<(Q*@HO~Qj<4_*Nojb zrAyx*gr*%O{3ku9AdfF^&i=RcMfP)p~c8fwuiJ|&cP8J@S z#}tOQUI_01;lA958!>W3jo2na&nP_~mIq}ow~)V~aQUO!f{R;dkWvYh5dR|Cm%s`^ zyixinQBbIpS_0@a^@;ill6#Dhh6Jc?P z9S@f%+Tgc~U%|glY=QrpOb}8g$x`^`uqi30Nzll4NGRpq@{jPJlkda-vkDecIaLJY zh*2?syQ;46A5o9N->5die@guU{&VUj_%Ex?@JUh)lKu=$J0T6_Nr)slgz{_&f)3&} zmjO%RLa>fkB21k!U`-UMtp;ofps|WXwZXvKgiGCEzz&h78Voon0CtN0D$Br!1i+y( zOJ^wY=y`K1P$`wSWjO7a#1w!-4C zHQ)gGrCp?nsRrHw>lk3bK_WvW8*nfnAubgQ#Vj#h%n=Jjy=V~)qNk`tZE6N|v9LPP zDCQ!@zoHoqng-A;1m(qej7E49LYt9do5|^X&VgLUBgQPmnF-4qWW*HlS(J7j7 zoepVQKu@`JBOj!-MsRe4ekLG_Js5o5;6IOP138oYehxiAHI8GGY?QiN6hK09?f}U; zr|XlZUMzxql&5+z4L+s4822QH8#qe00%bsOJ9Oe^4gSwH>@sEbfuSdu*h%K3c#6oPX;{w2Z>^${bW?Gd6z z^tq_bk=Awl>1=%$rtA(#xeD^n6HD2K^w@6ULCOW99J(aCA&p;*$0)>U6|)gO9h!GT z2Mf7W$nwb2axN%|CZpUIq9lEq>&1HX>8|HRwcP6>>DMA2)zW6jo`-ysMRXHnYkun> zJ&+Bz!G?58_FMl5j!$_@y9oC*v>V0Xzf@c=?iRlnFNn9q$Kng|cX3XJ$`sjC_LGC< zSXnRU%BAvpxk?^YHR@7zg?dtL(lo7B8?8;&W^2o|8??K$?b=7$=i1-2A1%rfW=XVU zSxPJ|mSvV3EO%KRvOI0sYT0c$VENY4VGXv%TGOm~*51}y>uBp0)@JLK*1gt4wg}r) zTeEG6ZKZ9MZLRGw+h_I+d%nG|eUQE0{*e7C`zHIF_TBbR?1$~&**hFTj%bJ5k?SaN zv^bVJ9(6qDc+GJp$R3mvR1|bc(9oc9LDPa-f|do{5_EUapMpb!6M}~aUl!aLJU{sA z;G2W*4*p&67r`fk&pCsfL!2v|w>s}}Zg4*1+~(ZlJm@?TB0@q!;zM#m%0j9`MukiY znHjPqJPspbs$3xDBUKYAB^u^FOLO%#S6nZMGe^`6i<6XLRY3MSq z%T--&>ax1a`Yum)*%aO-JSjXkyd=CP{L=7A;WNYA!&ii_ick@QBU&PsMcfc^SH!xA zjS(+Kyb#h#Pei^F`F7-ok)KEYBWhq& zUDTAQ)~Iz+Uq^ix<&Abm$3>5ezB&5t==IT0M86dMX7u~fe~ms8eKICBre{ofOij$C zG55th67$EHZ87i19Edp{b0*dv8x@-t>xr$19Thtzc6RK-*k8ro7JE}lb@iXJw<5$G5ieDT5Sp2Dk%MuzB<|ka8aC5@ygbfMbB>a#l5U>PX09cX!3U{&Xm}c)RZ16r74vu!&5F#nUT_-a!txDDR-wlmhxQ6 zIhVr~K^Z&=5BE> zbzkqk)BS+^u={(rH#InQWa_U{Z%e%=bwlbisjsEJpL!tm+thPujv@}mz|Fj`# zPNok^zbk!R`s3-F(%(+sn|>&xN5-OzZ5bys z&Su&(BQsMnb21Av`)B?pb6w_BnVT}-&io+rv&?TYf5?(q5n0z|ZOM8&>%*)AS>I%R zpDnVT*|FIb*~7CZWKYj-$zGbhGJ93_+U!TOpUZwT`@`%nv%kwxIbk^oIT<;HIXC3o zmGeN(lR5jlxw>`lR?@Aq+lX$rcKf8;SKUr@JJa3XJ*s=x?%lf=cOTGwLHBFA-_m_e z_lI(2ZfI_NZgy@-ZcXl(-08V3xl40z%KdHbBe^f+zL~o__mkYOa!=%*>0#>;(PMRw z2YWo-=dJ$v>n>si%vM9+ym8+*?0d412{_55SccY1!(^Q*k{ypeg==e?A7pjT?I zCA}W+btZpM{=EEM1+fKb1;Yy#7Ci53gtWYQIPO z$M(Om|KUr*FNwb-|B}lux$%-C1JVby4mdR6SjE7K2P@+$e^dEjRZ!Kusw=B*tlD4Q zR=u|-v1Vq?Gqnk|&9!?6P8#^ypu|D>gDxF()u6iv?Ha5G_Z&Qb@b3nHFeGY7-H=s7 zP7ci+S~GOv&^Lx94;ww~iD91(4;x-PeEINqMud)7JkmC@-^jru$BvvjvU%i^kt;{8 z8hQW7w?=+8vSU=&QJ0One$;cLKD*R*sprzBOP5~y?4^Gn9Xq;m^yQ-$j9xo>!|2VU zkJlyCRo0EEYp!dryQ*$w-K}-2>(0J7b2QQsC>29Pvg2%tiW^BAQ6fYTe(;+m&-fkUGf3>JNbL{T8@^d6==oUHdm0Vi!08R;!1U8 zx^i8;&@%LM)wwQr&2r6mUFo{sbqCsr-@4Yh{^@q2O^9(Px?S!xca}TfUFh!Zu6EBu z`*5@SckT`DN8OLRpK?Fze!;!j{c37dYHVs+YF27q>f|()W=rdm7MT{4mYC*B%S{`U zHZ`p=bJrP#XI6onxG{?8E!G=3Sug(}x632)m^>waR^3&;nUh!4R<%Rz(}ZS2P9l(# zbS+EkY2?J=3UNicl3i|BhO4_P&sE~;jaF`=YqG1^wZyf;b-U{>&dGYW9XW|~$Gel= zZX+kgx)N{oX7e%{Z$2fTZ|?|XN9cX@Yu-|83>5crGWmuZK(QsANK zK9WNvhaNpN`%v8>%NM)x-+0K5(9lDeMG)ePlkDIA#qD1#{o?U279Ko#@B<+Zz5(|r z+#e1;d~n6VX+nG!X6G3Mu>u~*3w`x)mkkKvR1oEyPdevPrFsSU0bEC)gIBF z)-i#;_L#O&dq&%=ZPB)B+q5?@w%MV*r+urPu-Gi&mRO71LSrX^E2OdP!?@;<+f@UerT3~e>JGI;EmhOitEd%o)dbb3 zCaTNTcJ;b?Q%zBKqmHErm&in|sucqQIq`#xkdZP$rsBE3x2%x0a)O*Br^s1yj$9(w%60NV`6!2NN-c|!th3Zfr ztKX`6El6FWqSUX|5H(m0RZ~S2T8m)JMnqs%B1xo*{-{qy82e8aW5on9QDkF=;x4gL z+$bIrx2xC0dhtHmk$1(P#Mk06`7EB0Pm2y2Cap3=c9AhMA5ZXE7`a|52g#vwxJ;Cb zH@*nCHn5Lu5ZONcIuK@O~r)ncTq6w~E+Q7^}eadNPj zCdY|Ma-bL^$A}s7axqh0fmxzCa;j*N(?zqa7p<~EERZwB64@-Slz2jsEpo27RxTE6 z<(=YsxlG(A?+}m3`^6J-y?9DKB%YMN6VJ)V#3uQacu77fUXUBb8}dc*x_m)wlh2FK zXH+5WnqYkMr)Zf)H^_4m* z(qyd2l`hdkb`{+)4_PIPMWrkfg)&nNmjlFTStCZtDsj0SA?8UuBgrN)S56ZP(L!7$ z=ZmW`!?i*#6w73*cv#*eHpqL$I?Q)HAny`?kQ>AwUye^vruT&F>%H`Cv;|m{=(6EM4}~$7BM0gGn^Nr z>GB`Yg#8CJq5lC*$bUfN{10e?{{xz!|A5AE5t=YA9nI8XXAN2qN?O#Z{F?4e6<=T9 z+%7%S>lZZ29@D4KohRMwhc`6OYLdYXEv<87YatUi7Kbw8n1#E_9LI{_@zMj8OhP$v&YbBCaP2kfyg+$#YKZ5;W_A}vY z=&h2`?^0MI`x)?Qm4N1QgV<3W_uUg+Iw%y==GbkvLDqHFGW>;Q2mXDv1KKY0{|rVS z?b-}&0%q?W>ID9W)JLdO&%&RrCgJarXVDYqp#|Q7zI`;fQwk37A0$#S{`{LfF8?mS zmH&_@P2 zj0grGhd%xidBp5L=JR8aJ6dZYH<7Pa=-!2XJW_-xtPRL1Dja^T!n%VjS7BIfDF-fu zueAZOlR376zHO=tXve5frWpe~)*|5h@-{(qQ%!27nguO1tA%QjTCA3j*IaouPtL6$TwSbUniMm=iFsiu?YY}&2#1)A?=qnM0KItDKUY%5@MXLG< zt1a2cl`gA9YozPOLMsz;iJCyU!5p1GH(^L65~CqFU@dUhLFY@LVX~79=$W3M_QKIR z5XDP{uf%nrp%7ZN=^P@(4@{@0+~0fL;FV?YibQCh!K*7cN#$1Ea8KN*6nxxV99E?I zF|AaC0=U||U*b-x#sFMCYKbpj5;Y8~K^&88BN{W7{yQ7mXi7ImxePf-R)y4+Xp|FK zUR`>!!3;=5Ic|`oJ!nY!BoW}F>ujvSUB~#epV3L8Smd9ys&gi(!r-K;2k%&fNX)EK z>5wnblSny*?%5YCgD)=Ca7yzS!?RQ~ z!HmgdnoM!Z%)7#hZtVZ4#_1NGY*=LmIN>>n`PpHM1Z{<*ve(;G$t#9Bg>Ek;B3=%Z zm;H}YRl!VDUhA>?N#8sJG zPoRf^Eznb%K}q)P#$3cRVgpteSBV>76>V6Tn2eQ;Ay}8|OH!d_pfzEtcd&a{z7wro zBdkQJL24FOW}DFNHADJtn1AV~1_H`a9@SUDo>jIgP<>Plpe)R3^j6h?GF2~CuBrfK zs617sDgmWq_NG)-07_FmREZh@C{^XEVs#00(G{&tcU7eNL;7P%&zoMFTg2tKZ$vxz zGM*6rKlWX6q@1Xt5woJl4m1F-OzjdzwJA)YL34^-Dtq|I{Xz{hnG+` zZ{Tkcr_qaAxfgY@^<}d4W#P$siO5D9@+6)!UqnmN4VvjEx?^-b4XfNU&=VDNPgKG^ zQ7QLCW!w|>=ALK(_e9lf7d32cL)hBt*xD{bo1LR>7HR(*PJ37ckyE#b2DL_be$nj_ z4OYxfs6FU40UOSQEl-LD%TvIY{uf+L0M8d8<1abLr42S^V;RxbHK@x`zPO50-XCza z=+65wu2#d1!xfIhd*Ipu_m%h*ds|L z$OWf9h7RNOE5R2!@3-0)0r+naPayvPvQvMCj^Qpy_XzN#A>TmA6$bbo!2il+iFEa! zy63^`BzTTNoPXus1>Jwstri*DZjpYzQ^T=0C0#`SNA5b&SDo+1qh;jx4BXCVZ*#A#-m}y8*SD>$00k;+IcDUcdJq&jT|3OwZN9Cjt{uY?YtNBKOD`gAj9x^ISFX8=C~_-BCs1Mt@X zza0CNp2pfn6xKL;gQhp0EM5ohQPis~OxF|Tk;kr8^boILM%}<;RyqN$C+080wD)1_ z55SI^p`#E{pt*6)Kp$U)JePqF#oa1~Vy$T?W~4osT`s08;ug`kj^oq#P@*kagY@AK(vqLjkXzeZ7C3VDgA75$Az9)^1Z z_mB;`WrydAT8ypI5ig&d{0aCoa4&%F8e9*HKCsyYZ9eSuOO*Q~kcDKp8gXFf82hDj zKNl}XDa5ms0hfvL73^|wB}ex(V?u5)9A>MOW1zZMPEgans zF|Gvr;`!)Hd|_A#7$qJD{a=t5w-_tO<2nrPJ>U;x<)9pCy#jrY11<;dI=HLglECvH zrhLQ~!!>aU+)y}Qz6tyjhzlsXEll%vHV*kc{m7sp_y-8eZO zPluPuiSlx+z+Qn>!^zOj9?Z^6#X4O*c4SYN4YCpSyGb_5nQ|6ZaAso$rx`o+T4bx7 zC+EvHxd3~%7s^FgC0dMCtR-0eT!y)ULh*N$Ua`CqYoS+T@5ME81y+noudS{YA9XoH}O5 zz7>o0d3CHK2F$Eu#gXUM#R!^R$7=9-^XuYEv>sM*sehIod+0+{s0u@0v_yqt_HL<) zz&yy6DoRCTrY2U!sd#afN>GU^Ni0*zDn+??7A3XwtcLiV>L#wn+)6H5z&~Pa`z>aE z#$qle4|6p6n7i>{WHb)*3&r9qRU*z}j;0KAH@#IKakChYIi7y1Ki1_3s0vl7sxUrX zuBtKHvjTHJzru6cHJBk9j1~K#YM2_XMyQc$6jljGt2*pc7^}vK%fv*i7EVx?sfprp zyt{B5?d4{yQCxw&0aMge%r#wsIgPK?bnIxr47)jlkNGCdZM5(z<9yYo7N~Y(PM`KW zEW`eStFT8QaDIO!Rv>8|l2#;d5!=v*J%B#<{(!Z=c=T3@0&6qaV{ogw4ZA4rFjoau zW5#3+b|Kt@Jqq`!`>{9S0qkOU5Nn#h!>Z=PYJ>Vc-eGuDJ%-&38+m>6DXeb(0c)MK zzWE&H+rP&g+G+JXRy|+Ds^=zpvq8Orxw9?Uo3RyZL|u3%#uJzwco?(b4~aLiZy^-( ziIL(G>}1-89UE_8&&GBUj@8j;#dBEEd0XuimDoqI3;moEvvHHfRP2EmfVI>=som;* ztf>B3Y{$Ob=dnBYMa(MEUXHEkU#*x+{s8N&AL04`5s{7+r<*YE_iMaSaI3gZ?G;nR zQE{#Mi+Drr!p(K>VmaR|he3bck2hzfwmqe{@t_uf7p$u(JL) z%zFMqoDiEZt9XY)niMw zmHFj+@;&y7x%JcAT3hTDtxc^hjdOx4+Ge#h)lXm8-e|9=(XT98ewnjs`mDC;3+K*g zZd?*v)zI2rKYe;*OFO4fP*r5Bo?cIkn7Y7&+qTwv4lSt3H{{Fb{N)$a>gg9$729e! z`?i|E$Od(#p^YjdS5=1eRfaaIbZvO@i-K!9iBnKhX(*u5r+^ZBjge7ZK7(aJk-bLG zxGr~Pm2DtP;vDGDte!)UCwSm_sd(}&gQnHD=}|ou&Ox2y6x4W%)Zihu!Db1gTLU{$0mwxFn3=TgLFQBYH4 z2vE)z3PCE3@G`BYrO7rjKo!*mdQi1dtks49)kg7F8!W4JmLA=R@;x4-ObdPHV3w*-N)mp~DJZ)nF#PHFU>KXDB7-}jpGEq`v8yi?gg;YlQ z9@G=AH#NR%iFK@B*EL4MwT3`7KHVEkYidHrUa0GW68qRdU6)qa$LgkT9ZQXnZ7dtS zo^WZIZ9J>TIo_|1pz#f}8rvEd%vxX@-_%yWsL^?uKTwZXW)ydAk?k@j(b2U=X%rf& zt1YulWcI-m&#U9*9$USs5R^aHUo{xyak;IDC2}_Tb4RT63p|CvP3NWNDX`4+H_4UGnVsXHNiMd{GRrf+ zKyQ4Ye?v-7ZP2Vd+TnwpUAp|f7OaXXKv}6~&9=`nvM|eNoM)M~n(rwr)f?#&y^)^X zSp+n{r6F^g+8P^Mn(JE{W=*#>b0ONA1N2^~XTG4Y%F>J+>XH<)reIr!tcAX|wb0h0 z*Nv8XdcnD^b>7TITT1}DB3<_ddh3i<+Sh9996hC64Zzvgl$C3ZsDQ13iZW`7*=id? zR2vphZLq91SnBqL*4ilcLZ8JL7FAViZS}Vx)kaooeB2DGYQyeo3PM{iY(ZeVt%0Ug zY{V|+w9r~tI$JMjtqsmay4`y`)i&$}!*IveW-1J=wULVgL+WB97rxq4Tx(kpQ1wcT z%$Jlp7o1nxo&rNrB?hY!L&%bHOFOmB?E%U9!bC9sdYH4G6%-iYmlhn18>7?E$&8+ZZ-Tk|V6cn7C*gZ%Jr^az zwk93b42jYmq^>VAc|yZUG*wT6C~+7EWBy z30r0v49WH|5a&S)u3Rl}<%SMdHac9na^cFA3RfOF;L65{D-V8fE!SnHjiD?v10*v6 zhRg)&GV2h@%yc9()9ErZsLRZREHgp6%*N;~zmltTetxCie&_3>5Kn%oA#hJ>R3`l0cAuN({qpC*hBIFya@SwtK)E{W_^YuqeJaMvU zxK>8ZYiyg<+Ca~W7_2qq(av1ww1v&hjqMBva}&*A*tGiTbNsil=f$Lc8GEynE{P+gZ#ZyQm=@|`o6qJM1B8;JJEpt)$?e%R-Ee)+LO_rL4 zZLLPQQ3WchEzPsq>J6k((3Lz!zyoTDZC>L7#5aPC>Ql+R2}Vgq`RfB+kI@a{TI^_? zJFk5yVsgX+k8Ycue0@lsUs=qfr^5Uae#E8n)ZzR9e0cy|XuxRu(EjW61pDX-_R$l} z^%_^M1Gtt3af>>=b?&qv?mP%0*$`G~@T_5#2&85`GvZYaMgRnLXRQ5hqVp7 z{>WFTkFxR$3%TOwdwhe|DlRG?NW~xEIHFXh4S{Zob3B0KayeSF1 zso$y@xivxp_28)qU{I(h z#%1f#Z9d=QdxkOEU61})1iY?(k3N2en#*X-i1yzFV?}3-;P*^KnEsv#=3()}dknOy zg*}r(o733VBC_Vzx6Ki*xpU^u!P+6MdFk&#(3%uc>HKWj%Pei`dzFK=i!jXL(z!dd zCz*Ci>wBfKcQWh6tQRRp)-&u7n@{HPQPUpc_pk~lWeMhXGqKL(lJPPUt5-IN{4?g0 zzr{T5A2ecl5AK=g}?6+xIz|7au;g8iO!GDDPnd&g$7c?9E=hdU| zH!|nf)s28($NP8Sj9F#Ss8#SEP!GX>3}+Wf%mP0HzfIi$f4;g4{#Zr3-M6b&`0r!y z1kM=JQpv}Bu@o<12fY-JV}@6X-)ViwXZ&OE@rFg_AvnA-$!;&M*dd&`3vN5yR=7=Y z&%!+k_Xym2xclH%!`%*d6Wq0MSHUfUn+G==t^p2fisCaZY_e~JCrA(-{=ydS#=t15Z0&@{H4-+S){-9~Rc z{Oi06;E(Z=9>#hX!{5gK3toDw;t_8d{8px!=q+T-3ixBaS0D|Mfi>8S9&lN3ZUcr* zXJDs7`qTP-`eT3}f?Er>2D$j<^P#MQa)JHCSg&jc<#Oc2j&&*hpN~~lywQ=kDg8y- z%MPl|L@zhPYEFW{hMl55mJN6mhO5s?4fgND2ooHWB3qiXmz1`sOJ!8L@-yxoU zrWCI$ryqu_2Mo6l*AL*{gWCbO4Gt-%KM#jIo|iw7z6!Wo;8wydhg$;I2Gq3bWWarK#d>;rceo5V7hF7CBwPrb4GyBF{R{`0)4qi}3I{7q`&7s@yrn@r z)Aqpag4+(a6?w7;p3ueTa>envTuE52$Zg8pb-#%-^VanvAFk_e6WWRG1aCm;qU#nPq-%q5F9P=r zLmN$Kg9%aSIx|#okN+>N*boC=(iDLe(Zjxc*F6X5u_1M7SOtnq}hLCX{GG(I({Q?1xAeolBTW=P)6^ zRLX~Qoi(A;CUnAtj+xM5AzTOG_PIWQ{~qPvwZnwAnb2kvBD&|9&L8@;8TuHYhv3$_ z*1%r{cZ-W~D;c*Oz8*@rC5&r>-|U(Je=6KW*BJOCOxz$7sx+a#CRAcV{?Po3;3$pm zoJNKj>M|jJ8u2DB5>SZC1|M0~(96{;5-cVFrh3Ha+^@12~mt_juF-g=U|*a2GJ=K z$57H)93^=g?nD5DwkZI2*bF^jLi_O=yh? z`9q1zD&}&F8M@MhE|$i>jV8#xCsTD5QSRIP=*pZe4zgl;vV8%$`0 z2`w`rl11mzZsPoDw3xV=CIqW9q@QF$<4kCj2@Sz>!ywLaHE{hIDl;LE3H30cEE95@ zP@)M%0}6w4By@%p;o{E*hQ_1JfjfcYgpb7^hJV0>_LO?J%KjCbZdvo;M*s zXM&#QG#)cUA2Ok}K8SJ;m}FVw!?9GW72!qaPB^#`%%d`%a2e;(xo{uP;RHo86oPcO zGh{O%+{XP(xVZ049ML_?bb#W%<ch)!Rj-kT?NuG(oYaQ0B)NI&MNoObDT|2RU?qATIuC#(flsi`~t*orv)U zLt9MfMH70)gf^NG#n`|x)^)<&!??RT;chi?I&?$qir8hKXpj9RsKpGOX+qN&n$#)o zI5Tt?VCX#)+F?T5 zOlY$Sq3w)eJBWEqZ>e$rkO`rkq_!QnH72ymgb*X<77kr$;+C7x5)*3kLGd#XqnTs) zp{XWrq7P!aF-$iCxIr#G(rj2o#`@6oXdpbO(@cYLQKeJLWI+~_&Gxi zJ&ov}O$cqLf&116#gL>NH~OfFGdV{e^5LS+Oe+?h!PrxSuq&TE- zb_Qs0&If2hfcb*>0JEI^1Ms70%>bc28H3dV8LD1q_*u}O({PdnLI*PD41DEnVi>Cn z;PWo~YvBLL=_>YvC|z-kDQ%P&Y2$Qlylz3Qx0DI$1@@6&z#oJDB&}!2PF%y7=jLcA3rk~YvLuOWH}Ec&Cy{fMNF{<;B-##NjN|rN+^K~2Ew~*o+j`fXh103t`Yy;nL ztZ%doqG5aZM#CxsV5E*S2T3R2FrOw)eG}zHY$BOO1M}I$u{JUNCS4oscd!f{4Ck^f zigLyla_F1sm__} zm%(Qla-F~{VOMfnq@UZ?L@SQ6jO#@i>#dAhB-xkkzl^n4#^r+6lPEcrM>xMJtn(Pg z{Gd_$mZDXV&)iZtM?bKIq%h|cqoz~+%2xZCK85M2^kca!QrNCiIrUho3*bg2n8Gro zu#KH$ONeE8Qdp8aDm9tM9P+5VAx( zUCRDCSi)JZ#gR-CNh{L`B}?e1jUZT$#Ws-5a5lq#=2%}d{ntdVBANbcrumv_hA=#Y z;X5tVKFpw%a=gt&7BvGW8IVts%+OF4@JY5A8l;k=nEwoxYKBJb!wi;c2B$cK*4pKr zlp@aUp!{NV1vp5(Ofd8BPV2t1J9FqxE53lK+%vg+yEC8eax&pr&h8v5is_@6K8jNe zWBMrVEGVNmR)6hV!2LPDQ5-jl;|}B$2eNDfna@C$d?0fh$Z^{^)mVw&07K?>ErBuduv z3fA)q*7FM1^K91h3NDKkEbR*IDAON-|5pubta1hAMP+OEGoEZ?1?Oc2=ky6qcLiw@ z@9j}ptY8^#0=dga}ux944PUdil%wcY8n9m%JJBMRE$dnH<=0V1|n1hS) zF6Q9kw)Z}cYvt0!7#K2~CVJ7zv3f9N55|vW%q}k3A2?Pj<99LrQj!xRD{3K^5ne1d z@UT*`lr$!$lg7kSl0j@BO8_4B2_Kq)KZ$+VCqiML;uv$gnN#_ax$S4nQs%#u<(bJj zn#oelq@4$H#H4`7*3X}={rOWucTN+p+O zCCf0EHQd2gF@RIA+LGeBfSHUvnZMJD&}?v^IyaK?_kVk=6pX> z-a(X#wT-ur5m)J2t>HY@XqSUq4d<(d^VN&)H ztHv^bI9O)G?`4T2m?fWQNhFwaI*;U0gE*%(EL9DpQhahEM*M=l0Tz#a9*b~7;1aPM z&IO?N#6s*yW;pB7_0){1Cy`g zedQQ=25%>Km1h;c1SZeXm%wmv9livH6GrhRFq|+-@5=^>QX!NDD#6%}-A}k;+$@j7 z9f3Otw;%2!xZQ9&;ogAT0*7ZMyg4rLF1a8}lZPY`Ey{^GRG z4{ymT)F$SSlNJ=-P?dNi7Q}c@mwY^x!5_muo&SJ+TVxs7T}A#iG;$R?)vw{d!I;(T zzrg+j*gr#itfs-=!XvPOYBk^++2>Y6Ji?S~a1J{54KaV-XMpcx$P#=u9_$l=lXgrG3t>1&ckuk3`{5s=TGvx~?14zQ~29z0gdog7jWA0^tERPqr zv;P)9Wxd8UuQB`*`!C?+4eaw`{A0ib?x^~izhLLa`^E}8kW|=Iy(5{$}9nR$< zmlx2H3E$6)Zyox6-aX!LyeGXUkh}AK-ZR(%c#`qKfKH2Og1zs;!QSZSea(CL!gw6= zz4vD(>EwA&`ft65yr=zf{g9sm5OSdZyl1?h`Cz2`q4&5yHp%JxvCMi-V1F#{Y46uK zYfkv6@Xdt{-eW#`{}m}5_R{k%|8U1#{BrprlO{l8fjOh_&anez4T$68!}LZTSbiFH z860#PgB$Y9A%+$^OXNN1{R_16u`ey}5tQp@@7J(}fS(twgZFQ6n8hJV(jy0>mg*Yv z9?{7uM+p4^n)u@U+!++7`AZ%qcTlqAM(Cl7$MU6PM*F`8{HY_S=X`8nu|Ii#_I__j z5nvmH(dm${llULhX@LC^|C^A1I?38^DbNgA1ZjxNmE(eJ`w;TURtmpUF1_d#yl1`Vy#Mr~ZwUM$-^aY$5vrFt)uY|s zLxB`J430;cC#8cl;PxTJv?MRJl=O439@pY(a0IRk=va?{Efkx0z@g3XQE@CUG5F7Z z7i#Q6Odu!kT9oEZUi5(8n@DQpd%O2FP`GgC&&7uv0$P#`^d}km4%T!Ur_32Y)PV22 z??7@h9tCi2@Xa2-9Gu4=!Q-^QbwTdWQ9E~$xTd}O(g81SgAt#t3g=%^Isq*v-=pXE z{ZPaIVZxnkptC*rXacVnr|8tiqW(gbPL>tO;r|I7{(sAb?9u3jF!nHieKA7v@ZUr+ zprHh441)dyWpW%fhxJOnZj%?uCzrR+Vmq@t|L$US=zJRA{rMa(h->vx`md)lt4#Mlb zSYSEnFzOqRdwg+m^-FAwRrIin#QldamXQ+0HBu!E^kC$S^XqG$FH#Pif1jS1nLjl@ z1S)@vtS5P)uW-^7%{G$kn18@2I^o!}9*KV_dYBlzyODx_xX8pm0^dmLg^&XLqi`Zt zAt;JPZ&3BaKM5zF4Z!a8N>PP2wnhvTZk+eqfQ{cx_-Ek!^I70=9sXH33+GXs_D`qr zXzZ_e-=mPf#f0;i zFgso}hM!nbbl9VhV+PULzN-?@1X zr*8coCv4&LAbdyS3$YC+UVVip5&E9x)^A$?& z2y|p;9obn&5v(H#9YqKSo=zk2EJm7AtRp(tzFb7%Y_{Gwagj9TU>(JougWc-B_}^z|X0^*+LrX`=iXx=VuY_T!Aq zze0mH)?f-w3p<8K#R+Nx&YdMaLONI!S?Dk8kt`JN2jL&Y7HVY+wX%g;*+Q*sp;op~ zIxn&cCqUKUZ^a2{wXk$5gD@_GE^MvgY^@PSd62b68l|!kHXFrd6U}84!)0URvaxa5 z*tl$LTsAf?8ylC6jmsvM%O;M?CZ5a2!DZv%vPm$?hDs%oOC_1@*U4o=UjQi=DO@%# zE}LMs;;vjmZZ4rzE}=9oA!nx&qEbocQpw;_$>dVW;!;suD%o5rIb15;xK!+1D&5(x zgSb4BP!d;BA1cbVJ^1g?R%^FtE47K*0DK=LTnom@SRdg0t*3E5*fQ0i?ZL@s18|aB z4!*ha6V7`(DEH!>t{rk4POjU4)9+TvWtbhAh|~Ng%Klhs@ZjXYG#Sk<7-t4f#8)j& z=?=a`Yej9yqvA1?$7|wqK9vx)8u_K~tUZfU@II3JAupZ&#wWiS=f2VTYQ}kLY8uW` zqm$I;^4V$aI2AtdWHdVE4Cj&IyfHd$Y^TCJ64s%pef-?J2XpkNyZXZJutqbNB;M?FofI3NB?gN(txO0FLz5kYtZ=}Rxq>6Ol z!%n=ff#R5a*84Lkjv$2&HN(3B=in!L4+8r=u=swB_qb{VRss7p>QuDO39%33jl9os z#&RO+AE@|l2dEAq-XX}52-zhljw3GQL#iY*e8_!BSZLKvC3_F43BX(iDv7&&s9P?; z1L3ZNdmO39;v7%PX%f?J2kma+gZZfhNP}7oI^u>`mJE)>fwXfR9KS}c33?UbTj93B z?Sy*=x~80-R`r}i%KLG(23mHIM(+`Xo>lGM7eR3bsVx<$>S~1C zAe`z(v*dKI}p9d*AK^KK}ewUB=;m+p4x03#86@nH*k zp%|Q5C+dm{Q#~;e(dnsa#ZhT-GPa~Rq9|QP1Dh?gY%w|M^4awCjuGjlc8grEEY^;} zR{4P4(ov6@%6rq(&)t%quCBD5dmQJFs&UqH*IR9BJYZO98d92pGEYSRCn_|XEj=wO zJF8TdloWbmky1=FW29D^8Yc&yQ^B_2VC+wjp<0mL5sa%039>s?$C-^`vN~AZd~T)9 z9&ESR)EbA?ZaX(yvjzp*ZE9u5pqw0ff0fhIM%%Jr^+MRO?$#l4O#ICzK2og0n8~2G zxD0%@#&{#%_Z043tY&Dwc-dMa+HT_e@8XAwt%BoI{w=dF;2(>x;@xScKj4D!XtaFq z`NFmNrrZ%|4f9R>G7}#T{6rJ~kjannlpnc3ETM4Dk1w7-Kb_<6z94=m)!^eI1s&G3mvxLu1Aclyggn`Gjh0xL&8dDT`E&-yp{_{*8}?Jwtb zCOz~l-ZJTjnfQ2dPe8i02HvK{TwOp`>m7*GGq++?ff@Lkw5;Ny{;D+2F5@n0!1zR2 zOmr;XgJ+|LMcX8-S@lmX?ULXM4-V=$)8!(Dt(-wgJ=uXJ9u$+>(Vr~*Wl#6G zELXHuv#XVk^NrnxN};TU_>OOg%@Je`jSH1`!R#%D)nATwA_*hW-l%D5SrD4#p(Q)pcl^s)l0n=)+F{!O6r+t_!$|A37MHm7s){9n)zTtZen6?g6_LB6B0RM z$@y8hczrzy{l}a2^=-4f+RgGJ`=MF+Ag@=OkCv-Qh{dV)h&V~jM{yB1D5)N9PEt!F zvM&OHtT-<9FE3ai z%pce*F2tc$J3?}zI^K+s!-n=A z*s;~tvC}bdL{Vi|=+c8eq+RX6Q<$iTjfE9wXTe0mAd*YrbcfQC*tl4m9pa_sDXIZz zvDIvcvRb>?yH770&^jhRe@yFuvT5Dz;a01%#}6LeZP4_u2)(zh(H?Qjw-3YZp4V|>Ps@9GnRsNh8}`jDtwQ}#8b$p!K ztX+!`Yni&iTNXfVS3lyEThh!ga6wPt=WR#NMr#C+$@}Y0csI_;Wjuz(%hVP_Ry-}J z_f7njCO#W@&VxFtl|wr0T0X`|T zo_Se;$;FquEW(m*QO2+SVkk*~eF7-afjBRG3udnTeY&qc|0~Nx6L^0A{;uA)J31aE zyZj}K4GoFRN=l1KvRZ=ec6*eYI`_=PC~JgntrxRnDdRHZT&YgG-oKl9qMlIK50ztJ zy+W(C!00|Mnu%!J5~?1CjQ403*_Z3m8#bfTkQkPZgATenI-Ylg5O-=77ou+{BVC!z ze_X6@z)n2{4|_1~DJiuV$8k4YQiwhx1_KUsCh}gi@WsVw=}TwiSS?{zi%rX%P;kW^ zmtK0u6`uM`OV}GE$4(?}?J+mFxPIk`5i9G9lajO`YjCh8V-o9DU2(;oqq`QJvvrQ*MnsrJ;RK_N245$p_+ zU;ChrEHs=QacJCv&b0)EgaoO($oIn?+wjn4;ac>Sky1C&6KSFBF>)}9KC@F=7pA;~ zRIV-~|J-3;+80P6ztQy_HqU_W z!wTgWTyMJepHgJx5nHLLovTA0Y+9HH8o}4G1oqq0^P-N8+)lI>V2`t1>ez@+$tra$ z^#nRL{8Q+N_AW@FQTwc8H%&JPVNWH@EeW@*53Yv>U>5oa9Y+#e7p zB!l9N!|td1xy*D#O&j*an*di-`&k#xs)Me$vB{MH#hYad40|s8_lxH8hkThe!&nLg8HpYA_^)IX+$GQ;2-5u z^4aohw);ELiy*nk9KCIz2MaVJEs?;MJnBde=|xZP z8027Tbp&5c(z%q890uN|eq5qs@s$u0YuA#o-eU6hr>W|p-BB#d;!gC50<(;a?~U(Q z(D;>7&6byujF=HUq`Dd5zYd6J)7;qNsjvnmR2p;>&f{0I-_lZUOQP+t+$i%w(_dcI zP|{AD)oBmiscduYa+;|<^sjP~(-CT$pmnjrm$G9!_qx8}fZh_~9Hgyy7NA}vPNvHe z>U7a^Q3o4QDD@dMS?I$Ql`OVmeB3o!c6B%%!J&?z5NF4C%5Jp=sgA#gQ(*-o*Vc}) z@(HJsPRF@s5=b?5%(CDoA3TT0ToS+@s%vR6rH?XbC+%p7wD-@Di=MmrS;!|3?A9*^ zHMi1^imfIGK@3Zf){!6PbOZ&5*enh_YdbJG(J{XT@p|^}u z9-#v8TC$7_;6KSnuZ751gMM)*`b5GD>HXGQPI!FnNQ}2pZ&TV|8QqMo1*5;=X%%QG zOtS=sIPI}{Zc`n0zna1m)3bJP-p!TySw9frlG;xTf;tUSTp61 ztQmS@YyRGl``4Z1c4HpQuSaSfSudEEdz|uv8eE1i#%#grtUfk|jicWzjk{XN-rxq1WT{+5kow{n&s8v(hhc$6pY)v$)M6;v#?w5(D-do2EQ5L*OBA44#SqZ1VGmhZy zAptgF2{y};@kUu5^p&M0`hsw(dz*aWTE_+9WE0=$BNvVK&S%kFxqn>8BXHm2;(1f$ z>6lR0CxG$Xq^;-n`T2%l^-CMrf-joUZO3}6Z=U=;n=RRHd8209C9aYMm-DD_%7as@ zmrpOJw%^k6Ii?qaoVJeF?ZN6Qn`ivIe&cSdgIpN>;T!W?u=0qtx(W}^DA;Hk)fnR7 zQB9v*MT^gqt24{T_UbjZ{D38t9+@2{@+vYiD)K(lENV;sxbm`zMfQ%pde7nr>3F!? zpq_bES=Np>Y0o^Rm54VuL#a<$>`wsWT8%q6>Q>UT(Vx+<7gF3xGLs8EU?dZD!bm=v z)7ZjVaOtV!=;;f#&&#zG)T|85m<&SAqH(m|h0#0-PmWxoc)}m)qLyj@##}WBky_F( zxzD8))x9E9VuBnY&fiV?jqFidF(f~?EIcf#&}X;4YbX1y2y%2uNeD|yPjX_|9%3!C z{IkLflBtSS5&LkwuZn6pF*bqoa2yCvOK(5_{>?R@C za+%oN#00|S(f_@w?w%Q026q4aByLT=uC9Ld>eYL%UcGu{vn%e3qN?V$l2>g`3A-f6 z66=>Ag$tMF6D@P?$>psMYr|}JYg?&`r521q*%}(@Z|SPGJF~yAI@xw}{ZwoJYBl=+ z#sKy2DSXU*NgH#B?K9w{uLazPzof5e285Ow@JiFGT;7U$NFR#wL7d@6a(gHI75U}M zv1Y*G{JSK#Mfp>)2*zo$ZpUSUt96D%{`DHc;<#S0{#3t+Oo+4Q^F+E2R;Cs5g=9jeA`+ z$%&5SN}>|SmQ(c}K~-1>L{$NQ39Tl099~zzA+em0H=i(`6V>UtBKt1L)%K1CjS-Z; z^Ig*&{GEM78SSYm+q5+c@h!5DL|xts$gYYktSl&9iMSx@4^f)z7J;!-ld+M70|n*F z^WoexB3i=X8dky@eqH(y&IVk~b)?Z@#PeKiP>=B?v5ZO`1^=)tgo|G+lkr}pr87QI zv<`fvuDd0`uqtM@naf6MY%wM@q(zy9GBk0N*^&i2X`{>Ky9Rat|nB_dxl@G@Z^1~W@Wj-AKh~H@N0|oGMlbE?i zu%4D*f5`L^e4l1quj72r{24W=39$}Leiw*X&TBNIp0_zB&YzszKjE<3oIN{w`%dX~ z&^lOl6<`zlC)wRxEv@R?(c8PDkM6jXqA&1q{0MKco7D*E$l)~05%3~-v2*2V{0g`a zo)aN8sU8}O0`3J|cykF(Qd7W#H2Od}-ZDPA1l&RU?Ku1Zwb&?Mj;PdJd71@?@-9SA zaw*R7q*;J~2TX^>iV@(Cacf?{%dk_DW&!lw$Bg#E3MV*vI@j(4dGF<(=i{-|`}z1h z#=W8R-Q4?yc#)-7_`KNk`Mh@0EI{Dxf%c$TfS?y?69F$Z-Je&UW&r|Tf)iZ%8W^X` zUySc?INC{c#;$qPH_16`fJ-m#am7GB5p!vd3QbxSM6tlc_m+pe5u4whJY!8SZu0l)fTrZ{g!ejEyoC&EH&e##OEEn_>k-PP>0R=$N?RaivoFc8N)TT53X`0w z2jL1%W>KXF?N+mL>?{Q?KBQ!a`^w=xb{&(>$MOVpIn2E;!$Sw(IILIHuEhk&ZTb)K zl|az1`h`yCKjd3r@H`_qEC^?N!1{pfP%U=cdoUr9eye_4!i2*ieaH4&$u51@X2 zR8)9&AIsL`k0RZq$Z(t}$8KcoQ9>-+#H8~SmFUMY;(Y&vHqP%5`kFB1<5s}E@a1tW z%HgCf1>Awi@1^Q-v28qhrF!8QPDlPe{MBXjEv?mYf2Sp_NAQ8R5Y$+Cfq&GG03)fw z>a@HZIILttP76D1aakRfY$*&nIP708{gD#1YD1%5OAWHfa_5N zeV`5SG~neFT>yKa9Wu_0eb2Szfu|N|)5DGopE&Vu7gh-wE;5hC$+-yGD`FPs4Ry^l zjh^1ufBHybraR1G{>=cMcDq+KUzojP3-cuThIJs}$N!z#rA%iuCL`3B9zuN`uCvXFt%v-}#>D zPX6?4v`&8~E**vU&W`w=6TEv-C*FM;vi%OD=ILC`7e(;qi)Wu_JUcb_?2=l%`8;;F ze^Y-djJm9>gw4t;Mp_sO|8DuTUEhAGMP|r8ekq>1|m2b|Clm zUV8g!(;KGUM%`7pryqC+PhT`0GmRNfE48O_j?pV<<@2ZR(Vt4>9i^U7q?h)_4d@pQ z=#$&97>HgYEM*O<3Q8NL?>691Yx534i(ebHym;|DM(H0L(3j7lz0jiUM-Au;JK~&k zC$R%UMl9wu`CWK0U(A@y(cpu}O&MpE79moEAIH+b^G` z!Q;|%rhn38!Aqu5gFZUHq4#zm7X;NNPlG-crX4i05dm4E!fC)sq>`0_@r=b3nQUR2 z6Nl9fZH}c`#2Jix(z}{T!{^P_QVk49J(LWt zsEUjyu};AL%Wmmjm8c%+inMN@tnEvAtTxqduG!u@eLlu~Pvfe=IA%K8$nt%|bsc3* z^MlSnQU3->c2%|3UC9nKC4H5RL7M{xfLzfQI`(RKIMuy8YAfoPidJOSboK8Z2*v_< zu3GB*hW5{{xnQuOdu^}PRoT;2mnu#4mxU?@n+2Ufk#8$8<`I&GorLv9$utic7{Q3q zWguq+S`~?BxRW3^SBMYD!MwH;Ia%-MY5kCU;r{l7*X1Dp5xB$UZtNVW>0X~sukY?! z-`2KXl1KN?OkX%r9PJ3ZFXcl20j>ycQKMb4;+PPBeWwl$@9ZYMg5G0)Lhm(lsZ1E5 z$71oE=oRiQ-b1+#VyWg?_;v7kkGn0}v#q=14^i&1f}qGa1{1T2^su=F2M@mM+^?#N7x$WUo+jJ zl_$7fPh8?~l5L0-BaJOu3E8H7=dkH2T_WPW>kar*rpHiP*H(v&o_ZH;h3VW0wN*{` zOw-8e)N2jXJ+;tQ)KOepwQZ0NVX+3JyH z)w(CLP5hV(v8e--9Vd;)o5!O{=FH8*P6>ND9L%$F&$*{Z=Pz3p8`#~KIiYR=nBZikT6dy7(Ie8wrRP9-SoP?sKVx1mda4WZ{g46w8|9JF%J=2L-(n-| zWDX~NkSl)_yY|Ry(2iMp4z5UVo~_k_Sd&9$@l}d#UC+OM1oo&t8s5NYKxCevuke&` zSrmU4!NuCA_l@L+nUImB8L0D}h5}(&2N3m4F?=g5Ic6e}}AuA8<=2 z|6SM!`n#tK8{sdyjeweABj``}3mf5e-A2Gu*a-U5i@1fbO|ua2Ragl887zd;H46by zSO^;Q$&JE7cpXq0(}HqOQS6j~Imr$I=a?ImhUK8apVs_BBs1QSU^!^Dzqn7c8~}yo zpg~_gO|u*Th2@|@U)XHmC-2apF$qwuC&|~%>zB`1^pw8-fQjVtBx;mRGdd^IvR+OA zlmCu$Wk%ylBX$#u5kgom5#@Skps~_kROU68q{|B#cDKx~b&&Qxg(T?^=c?6NKPyj)%-eQBNVLxo9 zj7);ge9X=3>o%klh5Is7LVFj;fmvWtz>s>QK&!Lcl8CS#%N2`u~m22Ypfu5t}*>oaQglm~DsT6(OY8uuo zC+@TrlOwK&xkL{H`SuO$c5%z3oXLth&N_%Suj~!OEU-BS&t6u)y3=O0`vSI_rizo# zvOAN#!`0(w4Go<&*|VjiV@prZ=FZN|k{oL9tBUUA*1_D0y?rI2BC9=MlkMvMtvgtv zFX|IIDJFDK_pZ^=U0u42F6A-^>q+3~XR&%Mq!6`-w6K65F@4&Q>7`s|2>4;sO`7(l z@=qA$Uorg>nKEc(5S&J^DF2k{X>9}(oJJYJ73qZoaq!PPdhK!OMTFC0UTI7$eY*0? z^&E{0p9*uGHTTWNskbWo(uuha`bGcB>UyWxo9!DqvVSC^u)4%VW8*|Z+(}}k@N=oU zk+v$L0^*G5yTAs$2P(X^@C+mG-~7TUd2mH~V<$>eb`JJ9`EGb=_#J*qeuw#mv-8T* zY~~@Zy~a@ERh$BoyroYSEr^zyE&;z#RION^(84Y+(ObaRG}#{rd(^%h@BV=Ihp6Sy zYlO)mK!3w~Pe7l&2Ytu0hx|UT?2(^RS(=aiiT9i+d-(rALoECj(4TT?ETAvl3u(82 zl{eELxHJ~fCqD}4O~Q7luXZYNiCo+-$RmmY@vtklx~0pAn>8u<7^|M%%~5a z5_=&iI}P^k5T}WEU-$xMf(u6x`T7azda(kp$G%d89A_+qge{)rk^f8#VTz$&4)1GK zou5{M9mQ4E#fY+Sn-vF-vaovn#aILO^KgpFV#O&IM6%7!BA>saI4`h5HWj(8?jn9c zD+$xT<@MY1UqCC7W2VP+3vcB{JXfTrYQTORdL^>dVMS&=t&R)qa)E9oS0)E5;cHU^ z%{3%RdYT8YaY3?bL2Tv3R>T!l`+rDxfjXl0LlV=V&q?#vQ=89xc!Gco0*X)l|zI@RpINNiMbS=FP}e^C(oCH~${E6hS=vj7v^9oR-GL zVMEiY{icJw{foxz!GbX>8b-LI{9n18IGK7*c1Kr1QxFxMn2)cy*fxP6U5}Xmluc z*Znfw|KOJU&B{KV>TD}k-YjbnzyMt=tzlC3KI%@<4?@<;J>V6tnFB!;qXeV;U9^if z)hg6BC0yIocWv>xEUw|zvA&g2V(zN`R;V5NRne1boNd>Us;=!`#@_57w)w;DHSOy& z**_6ZtfpyMBC)I~%l9i3Y9+yhXSGE}Izpf*^a)`N&Oe<~@+dnG*16D;&q8y&KOHHs z?i`$r5@J<@ZB1)3I*Mhn0XTco>pHRs00wSJO-KHU-|-=F3RjVY4Y>AME}PEa*c>u_ zi}&l}=tk_MG{>at?*)&uGq^roT>6N%PjP;s3$>8lPPOP!Om{CkaiPU;Zf8JVBX-$H9X{8F-~9bytQW9l|D$xRZ zmDa^W4?7SNEdqech&+NY$J6e^(bkYxp;0xz(1Q#tq@4(Rj0g#ScG64INkln3zdEng znAL9O&;mNcu0Dyxrf&-)4Y~y!JPQgx6mtxkVD~YUfbDuZ_%9iH{h+sZ-;VkAE39N zHZ7R;>bS^p?J4=jFGn63iv2a4RvOP^dC#xFt{wF9*%bLJ+Wn;V6f@%kw1y<0G)ot) ze)3dW6BDg)Xi(T{{}oN4wz^~WU+2Y!d>G!EnY`g^(ON0F^5*LP$a7QX+q z7W*Y=Li72;=P#Nr(`Fsi_lv&|I-fyyqj>v11M6o{YpylF(%_2p@&!3=yupCJu*c{X z@~?9Y;1Ae?y{>5A{d_f0^v?c8Pl=j8!Wc>+2B3`rJnIpvxq=;2_BN5AfNm z0)5DhQbR*3?6v$M_0MAEK`wI}LoU6ps}ykn#Wv(rpaq9_@INQY%1NkbS0xbi4#KV`yZDmCFlATP!z3e??z)IC+!Hy{SxGmXXh5ht|5}}%Q zM@jH0BlzIh>&P+mt`dT9`U>cKvmqhOM$eMnN_>I--edG2?K;!?3Q(=DD2t2et9^@} zK507D^fTk>+@hy6&R!Ky<$sf8$awmm%EAmgSp3-ID1P*;qoP2**oa7G^X4#vU zK#H^pd5C2LC*3#i`=6~OzngC!2EFwd&rrbDEq2b|ilyX8p>JN;S35XP`7<0{sftAv z9#)8-rwV6-ucCdr)g7{16`waW&{j>x6gQvlDvz%kPawwAX^RamkGv&fzsRoH!KKqb zaxOhIL0mez2zsP~pbfB%fDQOhl-+12%Luj~pyWdp(3i~Qqr_~xpsbi@FXLs&%PGpf zEJFq^{0`Pfe!Xvg5yc>xUT6P=w!fkjllu0t#VN8`sQacrQg1Wu!Ki zQJHG-Ddnp(;r@86FB}<6RW{C~OX20RGF5R~%E#m3?m8(x+z{?glr_(`wQpPH^jIuR zjV1$4q1uL0t1TEwh2sMeXH~i4LprId%0MDqQ(x||mV{Dujs4+9v{hhA5*~B0AnCO!7K_*B3i+GnIyzU^+p%OBX($@#Zt9D8B>QUekoJ?W6ejZTBCDsG9yYodGNPzjm_*(Z7$|(Zju~UTE)`7h+e`(1|0R4l_Wet$E6oFDAu-M!N>$(*hlyo zrC*ySz9@p7p3H;(tyn@&YaKki=1<%4AB%AD z{HK{!t7hmo;md2~^65d2*&*aF%fV^Air}!ncaf*Ku(To_`G;ItvRXyi!xzv95oJkk z3Fu3^Np1-!t^Ek-lk4e6T<;A_^e@5NXtVEWk zDE$|9kXxt%PV$4`WPt*X+H?yQv+un3a?f=ORlKibk$bLNsN%VfP42mFp)UP>-9p7v z_5`3;iz7Ow>%Dvwy) zi2M98V|EE)p4oAg{m^B#BA-^a&ZR2s4_L#;h!J&5520>&^e7$<#NzR$aT(#3qHb;V z#~$j?BL} zOZ?NweSwJ6YzNzh+w4EGpYt8!Xe02r2^9FX7`aS_hj)S64)|vb_+jh}ebRv6XuzLD z7Nh44`0WP#Y11Ehe$IO2JN*t$PVpexw2tVwRE#N-@hRLJj8NEkrnBF!u+z;5Cb4F3 z!8S3~Y5rR2oeJA#x5?7iO8&*lvbJp8qFRyJ<1xgTI*(=1GRxC7f3Ql3yOmY>xyT42RBUnNUfCVrkvDhm+w+${Yt8T4oUDw09xVZfBe{y|WkR^~bP5}afp!4>K7ejx)1O43e1pIj@X9YIOwi#nb%J;ZH<`Gtt&mdO4P z@T2Tjob*Ctp30N_5%8x?2lKv3a!1tu;yFSJQfZP90{X%RAt4B=pg!cxN+K45V~YG2E#@g2KEme`0T%ac*CwAI06Df@j-j8v}2g4{yv zAuIquxm(SuoE@?NfAJOi_A?sIZsPbC!l6x0CrSz^QAd=1in47H92OLCHQ+}PhbdNL zUzeO{gM-$k4&>)oB<2vix!?%qW{{#19|4$i3lq}_*?=eUj9WT7GQVbIaNW8@`%FXE zx@Oq;F57%>a$``$trhnzi?yvrNyU zia5}DXe0gUf!xz=X*_)%r$kXabYUCNk7wpu@B^a-hj$S#i0@Fe2(=3yxh2d- z4=-Avzmsc0{=2c6`q`VDySE?5-CUCg!O!4YFmEBV$7n(6UASFW@i`6u*1(FXfsxteZwlX1 zNu;L8);bo?%r<7$r>eV?PG|jKG`U(I2VLW_)aq1_EN`o=#8Fg_?dLq;gh#uI;gA`A zTys3Bk(#pF=0N>Kb9yr73k7{Qrdz#vqoZ_aAp2Or0Ylx6pq28v!rW_uVn+?yJh$JV zu1uOs@DiZJOQu_S#^1$U`TUfEOiwuJ5IYgcr(J>A`6=j^<9%A7oLCW7AraytZiFaF z1cs={n`HT+^EBz9vU@sD>h3xMQ{hm^@ZR(PbOkK2mXs+IAv-(um zY!e~`TTa`hLaErT9;=m2W+;hgCbKq`TH8G_H#adpH+PxU5wx8$(=*=`ioy5bwYkf} zBdNNf2Ii_Avs+zu)j`n$qD8RO>4Z8O?X6^~3n*l+20gNjWUGKeOKH%;Ixa`#OpGBs72dIKhKyqZE=LV`T)?qH zGAZ3o<*-76nKzYN=s}ul{r$z|;-Va_tjK%Bd-7FA{gr$zlD@0Ir?Qi&eo?Px!LBh z^b)4*S-SRFs8N>eQ48>9Kje1;GQbP{&|=Br7uwJVJ?Q0afGv`X;S}ER#X+$wHhWrI z+iA0_PHk&Db=Aae_&0B6*z50eNn{SvS%e@Re z{VH~X3!`$3!6^87&WhUJm5HmBKU#qL?zJ3QYo za8i0`?6)?a$HC@=<)w_Ck(gXpnXJT$w`x|^a91R?uD9*N<$raO1qUzQzf0eu9qk7S zL=%LV{`HK$#|Xw8%~w>4(Gy{ER3y#?+iJ5_2@J$D8#{V7B-J7hL+%Lke<|7T@{Zc% zvdZTFEDqZ{b`6i5HI$gEk!9y5SuHJ1t;-ByX;E_8%~s11o(tAzHml|%imaqgnI1o_ zrzR{Tx3-&ThPZn6N9=~e9x}eSILPu7cZuxLVg|}iLo7-5DVcqYQ|lyf5gWBQfE9Jg zxz_BZaR1O|D655iUBUJMN~eV{3?onf6F5H|Ztw$o({elf;o8*b5~F_789AI$<64{m zM(2^lT&)>f?NMA9V1g`qMJCcBWL1oMFtfutEZd`|CCjg zkP)uE<5)k`w?0!|*)e@`23g3lEv$L{@^*W%e{eRDn(nB~Y#(l$ZH`WN_pfbE%-b8r z*Ee^ZfBva+LCN7%Y;y7R_A@(+VqG=y;nj)mU4!+>)t!hO?O5N|yt<8edLawx_bnPB z+S*S6>rj4|FTrqNUT5|*oG&hLC{p%W$$_;ToCWYfWa37eGpk}gwijC>Wg69p(|-^V zL@mUj!*Ro3$>k&M+Se^~Fs2gK_geE5>3)%Pn>q|~lI@hi`I(b@d$(q4yFyY$OLg0Z z4q#r@lKorbcsxGVI6pEvf6Mgdd;x`@@>yCR8xqG`xoQ&R@|x4`YXA8!#68?d3d6DwAhz9T(2& zU(`GOd*@u}oRv+3n_IQMndzdwnUfyoopbIvJ7$BD$BNFWIQ`1WqFAPS=HVXV{CxADYRptrWE!<= zQ&VGOQDa|DIn-Qy0H=gO3ob1SqgA>ZJR(&;gm}#64hpZIh1j3SJC8BjMgs(!u zW?LE25))(vG6!-GJ&)sbv8UFqCM=ZYE_+OPO)#r7y$vj(9ZB|L1_q(4&&f1FWe6om zC~ZnMfpKqH<8LglD6Uf(vQIinlJTmzzbxz?xA4^_h$)+La(PR+x2!a%fcG2?;Xtjw zsxji9v(gJBcbajMNfsyNLMnhlar(Yt$mvK3r1J9T1_K@`Cn&E8wD@eO9%3Qnt8R*v z+sYkwmn0*-Dvg92Xd-OgRvNYk6P2MhyVnKl%&A(;j=J*la%9?bVRb`31I}~oc17sY zR*P)+#A>UPa8WT+>B5`PEm7JfO5?5raZ7FJKivrqQV~6%pYBtgmfh^je*X_ueESOI zpn#afm;P+M!X|kU-DXzI_sU4)l6{+e>s&vW7Fd`(DJN(-5uZAPrwoRXg2P4P{Ck{% zZVaZ1kk0{gc~96IiiNBEWgvqKYZ5lcerotW)nDWahpHL_vg|F2R#w#c zirn@~DZ4S|z`HCSUsXzVHE`LcoVOc{J?OkLk9gHN3Be0)r z9#yR$an?IqD_Rm|iK<|2S$R#U%3j@4Ry#dhkB`}9_hfxEQr{mfYbc9V2ZMEyKp+fi z)PoO>B4Z&e0irW;VP1#R*Wt_C1=6y;_D@jj{>82`c0h92?N)?7y^57`=o|}D9%bK# zfP;j?=rg^_+Mv-IapHs4md?&hNx?W&5ZQuk34-?(L5D5fB)xkg%vZ{I^iTsRbBWn=QSm*+zd?AgUohJhl)*xxbC%(1DrXeR8o+?I1LDJ*4~m$3vv<=;LIV_ccQgD)Qy9vsRBPl5e^Xjn_#CDtTE$kNm+AdC zrE8=g;Qa{ByW;Opi|1Es&tI1|YwtJb)n89>nf(3Naf(^N`yKRtJ>oU>=jZbGc~295 z8S(ss#`7)wdEDe;w;A}?BcCL?lzgA2GfiuWHl!sxq@z= z&mD9X;f~AEE4I3dia-N2zG3P16nu2~l8vKY1gQ_3)*_B| z16mo!_1pNXN*mZE_^Y)YR;z=kdH@mb+zKecn)af0&$^MN#N|>g%xkp!0WbR%VVF&N zA1G*bdZ8N>eNEJg)f6q>+25JbdYJl-dOWXI>TXU_*5l14srBqv-UoQ!^STLJ#BZ<% zu=}Zze$C^3W78E>Ddu*a!a^o+pL?6VqJ%2t78J}qfZzhL?xTSMdTz#;;jWbocXe#;na@Ix%d z{;0h}MulO=eyO&rR{#GY{Rcs4th?APtQ7fchWQwP1r}3PzS$Q)+vB3+g26y1eo}>a z7{HSN#p9?-F`f|3@KC`|<>N3v6&(6Dr~0r5z_v-2H`y$R<51@$GakV0s6Ds(%oasF zS1cfi_MF|~vTc`Tsmo%vTD|53GqZ%nXT>2yT}+a<+mP3NJJx;ZF-{KRkIh~ymT$Wx znI6NlO8HOD!l-EKVbyQC{^jw08w17OqNch73iPpM$R0o^_|-sR_Z;=!X@k-IYN;g@KzZq zjkKfm*bz$R(kn5$&5NvWKa!mvajNo#m;oTMj`f`@VdL^0Fa507bSb+5Q|Il7rp4|I z(@Wr`KSS-E!s8z_Jn?)N*B{zfalf12o8WyMVV|S-ADV@GawnTz_yYU989O)@>P@SF zXCGGXrr0ccML(f}6bi=QEXB|KnJz3&>_Pv4fmR+EoCR4(BjOOw4YkwzG$L|6xSF5O zu!*jR?9kEpKkZmRdFd_WPguIVbQ3R+#6V7*@<3}LTK)LmIlM*M`?%jL?gjoid=|Dz zb2u*^^>gdN;HWvOl08S)JCNQ8|M5tlK4fB^Vjtq~r+NDVXip#ip12PI-)a86KEfaC zEnB3A#Q6j~xghLijW@J3f*?P=j~q#M`}7&znKM?{tp7)@zvk}ETkg81 zMMjndrT)YJG(Z2j568@y45IGpg#k7w{YanXwTs}am^K~7Zc$W>`ANy^kuWmwnvFwXIW7aaT;fnNm{KumYo@`Z7}T+~U})7lUH zp;-xBE08G=B@CG#q*e2kCG9N=32>#g-Cx~47WaYcN5@K&O;Ss9aD22#X0{)*qRtiR z+4xivUNU=fDn8pj+EC%JxGjihC~oX;ogUiZV9ry9r&EKCeoK*A1%@eL_-Xi6;5QXL zN6iOAA?q>eJp>(Us;UiyAgqiDDLH^heIX7J>mD{0*t8_1WHLB5RwPRZBsR0va|L+& z6U#G9{;@;gGmx4d+G%Ib9YfQt1BoI_kwsy?jNSm%K@EtuH#Ag2Ffg25Fv7M&j%jm5 ziZ0NG3}wO9e(od+aToXFc7^ZT{I1g~W9u6^CDnJn@1o!bs;wTib&J}DG4L>jH~NGp z`Q<~3MUShFvI@TQuUdWb5b6_o`TG{m0e`-Z5q}|cD$TU^f~Wq5`-}K}*}@+1!P~gM znBS*x|7qzB++V`)SK)p;)-M$413br7J?^{t{Xg*g2<*x0O({IzXeNsmwi?4;6xd1| zArAn(kf8O5cn(Pq0eU63oUYXN{1gFh=kTjI{3?PI6<}}Qgi!^13KohOPBha;H_VMj*2q!W#R)Otq(zfzuW0RYUw!w)_Zp?)5;lx)_@4MKIA6(j6l&(0D zg;-`vv+LQvW1eu0>0f!fuX&!@-3<6G9Dc3on;d@a0<|v*oAOEa@8m6my+{KZs+zM3 zTv^c67;HbYSwE^MAB7TesvpAP&1O&9b}#PKd+iXO>es#Zz-jKZFRBf8BIPiJ#wQa9 zwFY4rV9<=&)kU?jf4AKWN04<9UGqHY zx@N#{;c%iQ!LMB)ILe!T4tQQU>|>;RJclLeUburDk#0mBId({CIv~y2NXzmk3?m3X zEP%uC@C&u2ZT}w+grOOVZ0&vOD#yx6w;#?ei8&pxc{6?1S?5Z`Z#!-8&}Ey$0|#PH zlKpaQ9w*_#9)K^1b+=?&asL=u#Ad|Cf(#Ny&Q|#|kZtp(omdTm9Xp6X9`qQxiu<+T z&*NMVe1NHLpp!nShPg``Ce3AV?x+Rg8MhQIC>xL-tZpopZSKI-+C(#D-`>zZGGp@v zB|Fr(l(vNYv61$wnX9*+{*5bUVyiCQm|4*uvbeD@k=VOt*L52k=WqPs-t%ssjr7lD z?~TolHq`Vsv@CD07|H}1DppuKXB(5#O)a}Nbgt@b{)EHn@?;;Xt?pQVR%Y%46N49h zGlnz1 zX+?B4x1vY6Ft}_-!!(k(Wte}^w3@QTs1XAOeywN@9>>G)6g%hhX%QpDoipI%AvVXLHbiBGfoY=f+E)1Wn zeRNMxH5{P(d1-(ca*7S3-;AkHxGAK zPt8PIH%#{hWt@4;*R#?KKa#Nbl-2;ndKOfKA%{du(7o{Il0qiIM=}8=*kA2-|Hph4 zZIRkmvNILc=L$9W8n>O_mifTxUqDoV%Pw8%a2&g>roE=zi=%3gMl4zLe1+7sebt)H z*xz~V96L-P33*8O6+6T#72le zMi9J{W;(m|AIdRrR$r_Q(AdQ4c)$DwaRp zwWVsXwXrH$=Lt>>l{UvP6D^)-Y{-P&wZ%wB;x_xLikoBMWTn?!I(oaarlqVY9q?4O zRMf+<&-a2#FQGU5Sh2<`|8@!$=i`qoE4LKqBuHXhih-9g)=H?se6FmmHF0SordqIz zZkW1sduQkNOQ)tTr9)LOof_J^E|prhcS!p?Kd_;tWy8Q|yCPf6UbQ4uk)Eupn`o;@ z1r)CtXRVeEv~T&)%!-3s+S|7rTru;ZE$y-7{CVSJ=dDR5*PJ&te%^fY!uIvFmQ`m) z)-7gsd+W!WnkMRfE;9}g@+n?F=2vORprg_c5#LF9N3a_p-z%dTb2wC(D;usXVExf- zUvur^cRXmcn3p;(+0hIq*&_0(+;l#H2*4BA;hF$rk#a>-kS!J=Yx^gda%2U{CRi&@gzEQDX?)R6tTwAO! zASa2)j)iNiWlg4QzNKZpE3>AB`j4%V9>@B;3z-fEMf-BbmkcrPqtllB;OAfj!h@Ph z_7s1B{v&}AZ_AzVH$g_#^K`k`W{)|Z!0}917T;t>+HP@X@MYp~rVqHGtB`>}x(z9B zpc_<2_F)7oq-mox+iJGF{4#c|&`Q?#sVe6G9ZqX9Kbd`o-wolkCXB)|b~md*-|z?w z^b4tI(*HEH3eJ4KJ=zS6=2SbsD+7>o7Q$NK0W*&CYf z#_Z%eZbwbSXTA^lOlkI`wHy?JOxZ^Zuk`O5gqHjjx&kjMe?BiymRG?WTB39po4&zTVw}-TpL?80s0E1r8S156pM8ZVK*!>VgY72t{z@0= zOGM>tC0$vY1C*zKM8yuQWL_C)fR zT6aEG;Oiz&+==Kye#G~n5+~KW(CZe1aI~}TuhNv1It#wvv$;3-q~KT66{WKULl(x`;I+@w6eXs1_tRm*g;~fLkKe*5~dx6mVfA%aZuW^ z-;u+E>f>{vg&)eFksC2aZ$^vB)45GLUv9^_DkI=x-iUt5M>Acts!H;e_;cFEumCm3 z9_ejeX$9C_`dIwI`#tRY8XBipmPof1@k71NbROH|mo9%l2Y}P~gFVfDCw&!|55bCE z0(0=K(RbWvphO(VJtc(&u#cA^$9! zL1>uT>u_MjP*u8}&TiFW&E8AEewTAV`AoxDef?NNBV8Lq?KL&+Ay}<7?d(654!1j_ zDi-)ptrkV?aJ$--?A=Pc+tmT%0?T@s)v4VscbDR7oJfd_6u4H0yK5ulIgiwKhoJ={ z3)|SMSZCBu6_GxRo%i*SFZBxx?3>U-A#m;hW!yWE&!2H)UkJ$@Bk;1Ik(waZ1WKXu z`e~A~wD=YmPuGu-BlSykIj42L4Te#;qq>sS5jP)u zhJrRXTf=?PSZt)BVK^2WZm1uL^RqHwB|D^Ea_*4-6+B&rS<}^+HIZ(eFnq2SlG{oI z6D1NO+MPcqDunu5JQiULlB+Mth21P&vtQ5s?jO654hOk#EOT1DVCLwi^s38OuDpCz zdSet`eps%7k?GfsiS9>@U)jq#ahx=cmF}zy>AXAl@sqcHVy?ClZ{b~E$WO8n_JMXb zIog65{#(!f0?_orMw|kTNPTcHt-F1ebs<8`V)AR}v0CAmuRwGh#b0rar6lyOVeffH zE9-xh+W2VtY5H@NjlJuUt?VZ9Lz6!`d+Pf+y_M|ng(K4GS`UrESFy-1uJw`5QW%e1 z^J;Ptx|bw;Bu3^7=Sw(12P6tVq@!Lm>jvE^#H-Px!Z$q0d+#c`W)I|k|F&_{+S;0k zOQn6TcDXDQ3=IwrhN`*~2pOl)Qd_JmGhX4U4tk0`9ovU-Op(Rnv0=Ma#fHv~m5qP~ zqR&ujVhYvSqyNZ0S6l*!>_Uu@?DM&NF6MGclEY=eMmc+tEA6$!`l6BXsrlArXY@8S zs16z2W{xCUH}<91E*}j?`a$vmT`MLB*+1EBmm$$3Qfk4O-XcFO4I#+(3N5KZJZ#pe_~QQLFSac-W|OT2D1u5 zt%w(csr?-07{KC;dlT}}wqb7w2ttU=&+8lda$LLS*e(W5^s*X-g&Zwfxk&>-Z?Sldk`rDLm-T;>aTJ2gVS8%Ix8>9y-B}B%CG~2A9L@LA@@5?+jLISc^fB&|NoKme;3)#X7z^rU1U0!LGs;*UEp(^rN$J=pkngA zqnG3Fbs`TR^=B4K2aC27NA4{?cC%kP_I^+4$&*kx@cMn9*8^!q5esyp4cS^)m4x+} zXI(9_wYULx{E0UZ`9V7JrjujNb`bvA&(Kx;&J>=6gX9?eC>+_w$39;_$eC5_Q&`(l z{CH#-Cs2pW23m-s~LU`#o zhbpHNn{~0~}aiLS|u6=9ov zmYV(xx($A2s`^g53+?iZmjCUXsfAdKselG(Qg4r&?=;ZWXlG#MiUMZg)wE+g+^x{b$~U zPw?w&o{|y|9%b*>%6w6$i)h*J**DlXm!hzx;2VNA8>q_coxEcHn_a8dcCY?}w_+#z zhE&aKZCXs_!g~1~qH(zOLWA}MAIknG?7&|ucEx7FANFzmYsP0Urbtcp2^-DqlLyFPoS-ky*1_MB?AGa3h=60SdUsy^H8@~8Ed-67EU95bIv z#I@s;L4m<0U@(ln)G;ukUdTeuYcrR+dXsr<4*NKLPC|>b=MV<$lb{1o%bv?_!k)8D zaL!_blIq-SX8PA9#IERQfdn)nu3-;j{a-|OEgG?fQb4mXv{A8=b15IqU!1T%+kEeSXP)g8UW{(>QEynmEy>W^LXChUKfLm_Z1OMp2h8 zVH98&RSt~~mU{xKge5ndFIrVKGKPD^w9v*8e_h#<&#M*wxRIUbE%Ew;aDrGpu_|AQ zFIa3vVve$S;2#$~NDw^Q3jR#9Qg%7}AXcm28-LbToNR3_%0sWDHI*#V(Q8C7#8TfE z-!Xk!TEYIAEMANQtT@8kL)wgb0^>mHwz<675{lzvFF4$ePrGc7LeN_gC-++{Br;Pk z`vSXDdV|K1(C1osUJ%|&yl<%S6;_D67xs6C`<@#D3Uw(|~zQtzMrLtFqp!O<% z>DV+HjgD^W=-5P?xHfel$*7(k5ot%PDti(;k*sRAMpf!3Pwwj4Hd$Xkxvi_~bqi2Kigf_fY0MNEBg-sk`AXLbuaW4#FlhNhypQEL-bHK2krKNG*%C zE{{D@(pekoio`SJRc$f*ugk~6k&co_V#`}&%TkF6xXQ|ZZI888m374Z;Vtv;ixGUPf4np7JkJZLnIlv3Y6p> zogV^0J*K%1$Og-J$~@?61U>XxS2a^HM&sJ*vB zz75L->Q`~z=Mv?;^{cC(9%p+;x1}R}Nu%0Gb!x@H#8QW*)Jw9fm!DeGc zZgw`!d9qi#8O5_^Usl-}1n`wQSXVJiIZFA77sc5}RIiG&yh#k;dl8VXLHaWB)OIr3 z;ke~pC?c7RLo`XLf~VMWm&bB#h!J{7e2G9Mn3xl4q2h7Mt&Mr`gEYP90 z0W+K^mow=co7JsYRO#5wE+2YHoQw1yLLQ8BE~fF1Xhh>wBz`6mE!-C}Sm7Z^&Ze;~ zeO9Z>$&Wy)8^YO0xigURPdw_`y}H|lG(&LZdzS6kvokt)+KR@4Bac7@ijVshcCl!& zMTUJ#vHA9Acxpe(( z&%o^Jp8l2D^Ogih7VX|KsnjNnto%03n|5%0b3)wTqg^L_?|C9T zugUV)%;vjg*~cK^UCuW=o;MtBmm~WZtF6y$e#0z3DdYc?JvS|_XLT|%3E>nNkwa*d z=MbuwW>~qr29cf5zTN}h{L_eV|2)dqOWlCaa(En`{1>06oI7biSIcJ-)ES4z=XsOK z^c}$ar4jZ~xf1Zhm_>?AdzAH>;9YXefKvuNs%IJC*UMpoBS?|5_S|Ng0=x(CjdByg zAqJ7J$9gd&$13d9>5}dgGp1n(Su%8lokJ2UcgF(S@f`PPf29q@UaPlw(STADH) zkZwSo-2Tbcu~vU|DtCSdFW+eT7wK+_|HrsQrw}Uw3Eo-Cr*K%qq>QPx!zm9~6sgf} znKk2FVZ<43v0@JeeQ~W+i#W$SwHkO|^HxBNOl>lUQZ za4D*Jg@wmUq@_j{>lf7>((M^5t+Q%oC+rlGW8o3v4T^Bitz!Mf<`yv%{8XNj1W^u3}{nT%E?g z%GZ%)=RISHZo($viso|dT31(I7L7`=vP5}#qD)*v(Xw(57nshl)zUqr*TEwkxx8r; zR&4l!6rWd(VEM+DEcHg}LM}1u@JO;HSX1P#jQ~Q^CTXU~7p~OiK7LPWl~bFO@ILHh z%cYZ%eI8%xXh+v!3;RTI@hio}QfD!yAtushAKmc=lY!MdNI$7$J%$g zVxn_F6=ZNSojLPL6-0F zvhwykQAwPQ-B#rbzZCMi@C_nF?)^6wiR*)l1U0{$kIVsrJvpJ7dGG~LHB+GnC% zcMywWK9tF{smfXlj&IpiIjUZ(!W^@leI*u82>VH#Ywst!`T*~3ZTgnKOe^HifOJh5 z!o?pit1Zc8H!Z<&P~{=N%#doKtiGf=3?V7b=%rL=m6(9jH@eW`dq|qC&vEwuK$@Mm zv@m0)PMlIkSqva|L`$i+#7s3OcfPiy-1+PhVu#~;H5*#En?~*W{89Vo;^O^9em@i( z+Jh6G-(nTi;|EBoh(KnDc2mPaIX!OsMd>5CdU2*@EcF(mZ?w{uOnl8ls zA^kaNHrzj>-E-}L`@^s>V5Lhpu@6975YGyHv}w^!+WN)dPqR5BEbZH|Jqdd%fKexQ zE!>8)YZU2v5w#_B0`8CSFC_8&20Wj{Ibjc)Oy9?J7jLB{F6B|`Sq%>^qjCS7cF$!i z?qT`x@>~Mq{soR_&B8v@r;g*xksM!Q1v{TFzX!gA^+#g_Q|3&DtG$>u#&iAqF_ED! z4eec=K-xVQ0vwUF))nN(kd^ys1`ByvT8}Jxk|bj-%T3XsY1s)IZnGGNM7P|?d-riD zJC_`Y;0wf-9^f_de#q6QTTS_IqTgg#|2N8wIjc#$p(*$)uspKejkMqn^CmOGPad*J zEmp71W06Nm$#bh|5Hb(fG8Z-CL-@!y(_={O4p*Sr-BLSRA;W2{ zO3pFa*$H>9)m9rB#{hJ+A~6ctH-}8G%Xj=Q?VCd&WZhI%mcg;hjho7f68L*Ti+1T{WS}ZB zY@0CIHp>G691|6gUM?yw7IG5S&CmY_)=l^SvvuQ@USYlRCX6UC2SAq>jHw{!f&$P@ zg~M#ot@PJLqYgV5jvIw(={J}?&b+&I^JQV(*d$^7YSxWBQ<*F$>!zxvri!fJ@?<6G z`@gY54!{a|gmeJO%j0FwRXL%>`S0&*g#hQeg_SsG>SugEuQ3;bItCBo2;EvGqG)|_ zMR84$*Ns3(2Qn+zaWsO%Sr#a+II|chw_0)3y(D=(2vYE=?&1n)5lw4gDHuALw2H7; z;C_6aYn3$i{M3OH-_-_KdhT)ciEV(|C2W8n>ox$e(DwZSi|aX7+MZ76I_v>m{2bIt z!UD#;o0RYv*dY(q|*pZ`jTw7bTKQht}a(>3V!g}5~2yt^jNCO$}8~^k3~om x_$CEg?lPkDfv*TJo~(9A7mNX9!r;J-{vtV;sulG{{p{Y8f*Xn literal 0 HcmV?d00001 diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Medium.ttf b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Medium.ttf new file mode 100644 index 0000000000000000000000000000000000000000..f4634cd7c3f16e8b1ffd01f2ea4a824b3b25991d GIT binary patch literal 78948 zcmc${2YggT_dh%{ce9&bHp!-MHiaaVgk)0*H5CX|I;cQMLMOoxs)z^{^ilLtA8e?o z*c)~qMMNKLsMr-15wI(EL`BHH-*ax+4WK`N@B4rL@9t;jo_l8I%$YN1&di;eJ6A{{ zL^M2`5QA&$>Z@O>dP@kE4eZy0M~@o&PE77BA%>nNMCFx($BwU77i@S(2-hJY!d8wN z+uOV5;faYt$Q_73eeAfZamz2Cdk*fWc+-J{T(6Mal+yC4n zL?-Bj-!Q+esWJbEd-u0qQbZNecg6~S~D@Uv4a zgn#L?gZ5b8h|V!V-H(eSv|Ns*r;X##RH2s6n%%*~lpbGd67s~4kea-3b>zmvX;J-t z5t;_M3GsgZv|V)FvwiA?z7f8#pzgL+xU~yKSo~}%4HSYl!*-+W?Gf?{3YWjCt+;rE2ELRy%}C?qs{~dEqK(=| zjUtBnQA(NSz3m zEZX6Bh;!ht6$C*TvO8aO=yNr!v$rpfF3!h8~%8j;HI7F%i_v*dqWp<8Co{IFUP|*C7_7 zB$c8!{)>{*-MS$ny+6L?_gpU&SVz?LwKIS0IgS$3JpaalYKr;a?`8%UYT<)_dKu_kb8;*E0mh$3)E z&J(~{*L+QG8pRUuM`db6&Cln&m*SrI@Bl~oRzXe#cR(f{miYf(LZ)1GsV;?7mV!TB zTiTK9Qk1h15+yEM0g=>N5u*tuS^y46LV7%p7=4nMC)Q-X2(0PjB~%RBh4_~VKh#%@ zguF+JI??wen$eZs|D>OuF1gpB6br?2)+AkLJ;ICJi$ottl(dKH{KPU)S=*6zF2b82 ze-9+FnCpi0kMu3?g!-6e)ZSv$rzyYQEKO5_`6rci?~~+Tk95>h=Y#hG)DG!IcR?EG z*AbEgX>vO>N!Mq88yLyysce}ip`HobQ3~42#JS>1u~|GUc8IsdK5soE@UskTKQTVq>qyTNvs?FrjX+XuF-Oppz5HJL6d`K2Q3YHBj_W0 zn0<ae57RQs07aVUoK5`s%{2Hu+BZ8BH zvx9pF&kAl2-V}UK@Z-UULPSVLNPb8~NNvcdkW)iug)9nL8?rv+`A~bPGqgT*Oz70m zxuHu!*MzPQy*Bjy(62&&36o(}VN1i-hFuzVUD)kmkA=Mu_FmW*VZVlJ;Zfn~;l0EA zh7S%O8$K<(E&S~8OT%vrzd!uR@E5}03jZYh=ZMh}H$~hV@$ZP2BHoYqDzY?kUgV}I zd(>%Bv!gnqR!3bNb#>I{s4dZs=-BA2=z{3}(Lj?Gzn5{A2#{BLKa>h8*oZX$J&MM~!=VWJ#bFuS0=f9k{Iv;U9<9yZmzVoZt zs@M^+lVj(^UKP7P_S@LsYn#O>woj7P?lt*14{9-RQb2AvPgB zp?5-M!j6R36O$7sC$=P>k$6_(C5hK0-kSJ*(uAZLNv%mMlFm>1XVOhcpC|p4bSya} zIWaja*_&LIJUV$=@`B`L$!n7@O};Mq_T-0>w&vB#&~plvtG!0H|s!luk0n++p~Yn zKHAOE&DkxjTVA)~ZUeeq*=#_ZZM)XpfaW*7dle z$BjMi?it$C)ia}KVb6g*NA^6u=lq^ad#>sE&z_rl-rsXu&sTfy?)gd2?|UBU71S%b zS4yu2(;D+}K($}B1?;W_i781g$tvkpQd%;gWN^volF21AO6HYxl$=#^ ze#z#Nhf8*pyj}8X$)QqPY1|3_g3`&Q7nHtG`d*n*S?7gxd%OlDcm%m(oup+7= zp(4E^x1x7NdBvcLNfpy8mQ`F367q zdH-hy6b-m_pc+^(ux#MSfy)PO9;6K#G-!R5tO}``Q?;YIU-i?~FV~dSTwilX&BL{h z+8gU+U0vOVx{vCI)!#5Uc<}nczYG~YWaf|yhCDdr<)LC|#n7gqw-4Rj5Yo`l@Q;QU zhjkxz`mnQx-8byW@NvU08vew zAN9(p-J{j$u_UW-NjD2nFdt*Ny``b7%E_ht*xRh~O<9d!O9yfH{igBCA zZ5{W~IN$iP@h#)882`lh&nF~J=sBTz!i^JlPWWWP9}}}Dj-EJa;`E6ZP24zf^Tc~5 zK0NW`Nx_pmllsuG9#0wq<5MBxXq3uVo8vI9FJhc)7ehn@#%+DXD!B?h%H{HUd6V2C z-Yn31!+oavJolyUE8JJPZ*c$a3G+mI;yuY8w-Gb z#OX=&qOe+qt* zc_5tv4>Xxk4wN0Z{lMG1E(AVzJ?$WksPiR}UZQ6G2S#5{*y!MLro%VyxZi}|LY#tkpodmAn#s2$xS?{V1>Qc2#EmuwI zDYS|OYLaSEQ!obGp`KCyQPb4F(8kj6+}I7Rs$LAn_<1bG>iSr537+q77k7%g#Dn5# z@q+jmqr1<<=i&#oQq5Fnsh3rUIwpRRG14iMWCou7D`l0emy_gaa+;hY=V9EpQQjbL zl(*yge=Az)JMshhq5Mp(P&cSE)k|u;nyPMBkE=V?6Y55FwfaL{qnwx(*{NF9wOX*+ zs9sQmRF&#f@2IO(qZXnDs#x_8)u4u|VQRXFg|!I9j6@7(CQ?L(7=ZRvg7N=UF89U@ta=Uz1?t$gmD_k-ZR_a%gAj3quj1^fjL1fEB z;la#Vo=g!vWSXdw#iB@NiGG;lsg-4z>&X@kvcDK2`-P~+$(Pu_sE;XL-G#sxV%?9ChrlC$h*X|@=@`O zd_-)Q4~viFo8o=BOS~kvi9PZS@g8RFK9sMcO}r<*lpl$&#EZWa&7+r$&{e(|K-A|94^ zibv($Vk>6Do|8|A=jD^)Kk_lLSH2}az}(oU@_n&izAHYFyT#Y?V{u4+C7jYO;$$#p z-+UqhGeeP>VTz)eAasj1@f&)>Bbf9212aHJF{}8y=r4PVfwD-{VJ5Cr=8AIJT~x>( zqL1t;%4D9HCdY`=hsjw)lr!EiRVlhzsQ^@h^FixC-;SSIbMp zHFCY!ApaqD$^VGg<#Xaq`GR;`z9im}JH@;5W$~7LQ5=-}#W!-F_*Nbe-^)+cDQc{m zpvI_)>I~JU7NQ?sr!G|Is`J$a>O8ec-K=I{hHs0yTiv7XSC6Rs)MM%a^`LqbJ@xDA zP4sh5s<+VBJqKHcVv10?7ju)Uwto0HdEflTj#fxvl?bVtQsTkq}{2Os1{zjbezY!lC=OvAVZQi| z{V&-+!2TZg-(~-G_II+sgZ*u-ix;$u$J^SQTg8?|b6RJLyA~}fEE1a+EuOJR+^}fz z!bRfh6)o*;=qE@oa@eQYatUo9KbL*z1$2gHLI{_{zFxivhNIZ0^%6-dC-7;lLZa=G zAH#kq``zGc=&e%G?^0MY``PemrGVyhL)cLpH}5H47Gfxlo9D3GhXmaaRDr*+J&%7s zZLhY|`ftJLqeGjiO~MR*u=)Z21L|$GsR!ZDRj1+amPgSO7r+8PkG_2js8bHXpg%-p zVEp-wJSe}F-^uUg5AsKhMt_!vpc1oWTN-Cu^Wm7@Qt{f^@ zg^c0kekBSAjsa0e%vX-71jsjG!+fMUSaJ) z_EC{oap?nGIA7}nQm1li1$o<56ylCk5gcb6@K}$4Z&EwN_oG{;4ikSEyUD$`GzaXptCeM`N_@)MB+bEnahJ30k6-1gWNIsal%m z=Cu*ztQyq}R8EVUiFJ*6Y97{67N`Xxh%6wuTBgnt!5GzCg7t`hVZ`M`AM}}sMW6J& zNK`+n!y-fdh834wluGAS!W!wavC-;;T&5;bX)s6UFHIzJabh$C2doWlEo8n75+*&# zhMej7>0LNl3!-!x@ReALI21xFH(f)d_=V%?IS=q1G-%}*w44YnFleQNl2jhm9rr|y zYQd!D=CBggpW{k3B!H^j_X+N#Y6-v>r zUKMgzqD4+&es%6i2eZKumAF}w^dKQ=aw0%Sm)UrOx{fiWpWTHc7s^jk)hQEKk#JHq zg0>4G5;Ln*JLC)WBvMYJd-etMV5X%OPWe8DQP({fcLkO#gwv2_o3TeCb}!^@L-|~= zDxqo*^y?e-A^dOE2k<{p@5BEzAjUq9@iE8P%P~IU7?1<>?JH0;sk_l)Rzjl|V&vA0 z5%VP2f#G-t7=(V3tQSUg2x${%@R-gcXUYy0%`Fq{klLiIhd&RpMO$S*31dPfmJkfO z&G6?iJV(tZm@(ZrPB-zBRd$6{UDyAr#pxQJYG`FPDB(GX={cZ_1Z{((y4P*0PzOOzU-=3sSp7VO@9aNiyCFa6bEKzYim`YGtM%2h?Guc`x-gE@^#RST$_ z>aF^y8bH~qKvk$}Kv|f*DOXj1GF2~CrUn7ZP(4+t8VFgW!`k#vC29b;|61u~(`$39 zI2HFTu!H}`6T<(;zDtghQ&gD! ze+BFC80zL({B7bedeI>6Mcu4@-B|l_@MOJAUN1qL1PhT7c3!Q!&$KHUNOmbAMlm`1y^OzEXDOP@c3u$bumdR z7xfBP)8UD2k^bpZZ5z(-Nu|J&{Zb23p5JvkBv|zjDtb-hb0wFEX^JMe^}ZwW1vT zFmC)i?tD>*_SMzR6a}yg|L0wcL9%PeIe_~!N4!+St=H29@@A_CuK$16 zVV)^XEk+)H<_3U&^fqv~`o5#9_y}{1A7P%9o$r0|k?#k%pW*I@`&4%v2l0I0B3>k} zpJ1+#?%#x?_%F$5jINLRoyrnpOecQENDNLo>FPTQxCdr#2sc#z!nlvbA>SeGO3^?L zwpw>Bz7H+f#L>0Ew^y4K5RY(FSN}KN6!cAhlAm@6ypXQwt^jkF4FN6#a0uKWxc>5= zzPIHEm}C8$PAw8?a-N9!pBzRQ4gXb_ialh%oanG_lKOY^#Y|h?@eVrE`@iB+L~$3o zdBUy!#A%vH)Aorp+kRXR!%aiGBDWZ_pN?6~(?y&*9X53`=DwGq@9&MiEE;w;OGKz% zq6#|z%kj)!iK|z60aLuwFc;v%T*L^#gE5=gBs`c8FOmhqjoHnfau{UMAMXFBcnULx z>K&9}ugKSe!1o8D0)2;93kB|=D8X8QP&pXa&BUM`Pjqxo4l57(?-lG_`Up>`yD`50 z0wcCM+`ogB3pn{R%J(hy2E770lTpUOm?gLldXg-n;bO3#u$1ta?TChp5i@8t(KiA! zy5;2Xh*z#n@Lw5sd)F|m7UaVv$Xif9w?MX+VW#^s$aW_1GlAa({Efh$4g4z9#eR{4 zI_QR3;#9aa@im^)KSKS!ff?%85f+QOB6q3C!3s-`g~!v1ROq)nB1YQ@o*#f7wTqq@ zujFbj+&e^;mWy?hM$o0SAL0pgKh{QW7ln{RZ_Gd!;<=*0_8j_qN>AfM1zU2S$i+NU z1@-OnL*OqHAs8Qp@wn`IJfqAN>1wp_a6gUpGc^(Gl;OY!G+qlw9 z4AG$QeB(M0SDKromGrCN8sI3LoSDwd%fx%-RmkUg#Q7HW9gEe2btv0RxG#a<16`bq znEg^JfRDjls9xuccdS92FFtp|9l&nwtf@fV?Q{R_$8^ZYukqPJ-c*ZCFKPfB12^u zR{J7kBv#m>uqqbK>zA=udyB*F+{+ZUf% z+ph{W?+RSFskjOAZo8WR-YLR?8Y$E9)@dkdK*)Ay{D>iq_D8RmtI4 zmmGv!dQSf5)Y-^cjl46J1Dksryu@?*JA?#KGqQ0VjT@)P-~ z{0zG|zQD@vm+~u`O~<_2d!mEp)G<5uomi^Rt79E8U}haFjy$(6M$+s$R)de5Ux$?% zt%AfU{#kbHqYqaRDiVFbGW4fo#Bvp*oZ?K(3CCfk#-$QeqFAYtRI*ADD^#jVQ*NF` zIc`=%+yqN^7UouZqBnj3>;K9ih&i7AY5>;d2dOGmjTxOuVwI{zf3_Mn?i|bnosAiyp;)mWriQB#Y9w}mj>anC z7_1YH!}|XOFbj&rKjya7lu!EtQX4tJ6 ze9Skg1*(--8P8DdY7urL=yUqC-(dyz7p%k{g~0j!bFl(R>yWe}d6C#Io)OoJ8^m=1 zYk!Hbp2@T}gFOZpt4pwp;!;7ZJxY``vrtFcGnT6G=vCR~qQ3^!s;^Cqln-l8_E zTk#&l?dlHfX1I&jH}A#j=KWafr1i~*FyDR%b7+Uv!&vov6sw+()7uT|Nz9#X#oml< z=*Oebue!zEnDw~@R_|uZ@v(dJQY8Z(vvMbK+s~hBaC={RUfN; zm^nJYE9;-B&oO`Wr8p0>%Nww={tcdZz861;$I)wDDl#ye|1azhz5+W*8ZpCIh0)RF zVk73SzZ2JrYs9VMYRq&7qyPCg)~WQl%tJhz`Kvyki9I1l)iLY<@nMCZR`)fm?+0OR z-=PI-Az0z>vQ{J3qsOWdmte2TZd$hy`?WZXDLxYKix0$JvG31Taj=IVQ_I3Gf^OJ5 zkc(Yn-L)QCPpudBSQTi!wL-1PUNxh=Wl4);aqFC-x~e+;T3u#b3yrJSxR%hhu&Ab1 zzpvtZq^mLRjdWEN#(fpX_ZAv-s?00XEA$q69aRe&o7&r29aU|!+FD!Yg;urCX`R*B zw78?iQB|j3nYF@-u$rbh?M;gp%$(n{EVQP%t)sE2sin1pb114QvDY>=5+ROV|9si|Y0Ki)u>kbzFRVU0`A(cC{gm8lzM-2KP0FG-`BdcneEH>$>@TcdLa#S;@Nv0#3vEMYG`8zW zy;WgDx~3_r^OmTg4fdf{4Ws7jnVPrIV9;xpkr^$jt6@B9rphtYV0fs`pnYh^ocYZy zVWa?sB~^vRg+*ZvT{A2!D&}$_n{xYbt~~qj0KpcsU=gd@HXKFK`L>c692Fa!l$do? zWgn@N8W}*UL>FvPNvTeygzKWHuEb!V4{InGsW!qZw7S+=_E7<%s4dciYK>~GH5jNh zs<+l4S*w%u>Pl4T^%`|rY^sByE;V&Qqh`0Y8yZ+^6r;|hX2hyB1YTDdF>3Z=sCxV2 z1@jvhvoIj`I>)F$Jt;L(mvUZ(XlY@i7R_&5G&`VWlo*stbmjJXYwTlmfsL^QR#;SO zl%mMsy3{B|k(ooCeQW^HGNbTiWnp8Ft7LDHA*eEgRGC4d%)s~287Zo$w~d2(+Q$X3 zVa6@j3*;>_#8hS!qO8t7KCq68sg4T0XeZom>db3d(0ISB>x_)+4TkDW*&9Ub>LSLU zDC?p!$M`^5msdH)>#80!o{W%vJS)7Oae0M(B8w+%qF)>#6PxF>w6`ppv&cSiR(s=; zmaxhGKs{ZBQQh?=_Q@PYN7oy*QEZ5=zQR6*$%jrku8sHc+8Zr_p#Hi2!oZa4gsKfC zu4X|2&+P$vZ{%BLw2vy&VjJnI`snGaxP3tJ3_4Zj)ewAPv7^xtQlnv^8~ql#u_Zud z3j2gL`HLUgWEI5TY$-rdU6H|Pp}|n0Zjg#<%Iqy%PJ2sWY$H~+QS2In{ThSK8iQJm zUTkk+X=sa;uOT6$q}66g%N;F&)m~(fEGl)hbTP%c1@V^lvCm?T!e;qPN2Cjjyv3oj zj?2wkWSi|b$<<-AyQYCjF163G>a(y&H$ITR!KJr8WKIF?@WIY5oqyAU)o={NtX6a8 zI_4Nfm}3~{IhL*#dW*|-BVDE&>A785fcY&CpEs+$rKNR#V{7xACi{G@MEm>zxfkn& zFDkCF%|{7!PKsGl&@F@4V$-%3+gtUv(b`BaIk&ehoZVt?4Io#d%f3jr&al#^)z&F` z%efhVvT4ftXf0@fZGnO^T8d@04JK+04X8Cp)*2*r{erbNs=e6M7(=6K>Vw++7NpiF zN}Wl~h*fLoU0qQ`+ldwgy4x10N~K2XQqBw3x;m`w1Z!#en8FBpb9_I68P zu+~N?iVUtxjZ&Dcr?lR_D4^+;8HFz^4_kCxZF`FhL6sS#$_ysU`q(M7YEi2TV+^jgN-`#S{}66FXK9ck$QuXI#cEb(YpGG#V5*` znrEPl%aO{k(u>(jFSazlsII(^eW|XAOZ{R9S!!A7rMi_~?hn*8yTYjE`cnJyKr3z3 zLa`yT`abp*Og?nQam~I@vAwZ?HsFOdas&fr88IBr-B(q8z)f{|;7w8BO>y8&sdYnU zoo}KW{UxwM(K+~|;-)q*Brvb4K7k?C)(!Ond=uGdO3VraJv}U}kp&bO;O7<;j2olV z(4!eW2j7Hp_rYM4zbE1Qutu&*hV8R-)GWUUVSj0W&-my7Tg(WOFBxRMiSk=zD-f1f zFMu|4+RPxhX>;uC&*hu>HX!DP(2mIh@^pwcYX;-7q=12rrELs^cFczLWH4lA+v0Wu znzO`+w`k5XJ>DWbSheb4%N(4#phs+-V-O_W!$6z|Ex2;Cz?BUhuB>#pa^u348x^iR zbikFB6IUMm;Mzy$nKp(p&kPXH1Q}eGH*Ch@`SV*k7!G9< z&0yq=#-@4xTi03&{IhZP~lK=`9LXDyxs z2`p&yM~byj$3?^T;#r7m@WRm;<&S1x)Y8<}+RP;_Dk=_XS=506N=J){DRVUH1<_?u zT^iBUHovWP0V=sL^?|O}=mv2u4Q^Smuwyw=a>637uAAOMeMnwdUCN`U;=(e1#HISw z;lcoXp8&YnfMNS!|MmC;oAC)Y;}gv78dq)uxR!^oMQv(ZFe8LJ4}yp{gjE~#Y6`Ha z+`#E=t=M=R1#bqvDum5vKOEqy*I?eu(gt3C$^vhy_$JblPGDFG-#EL-DKNY~;HIc3@J8n(CQxPp z!CsxPUO;akJ6^rCMo6F>ymbKtiuKI6ZoRtB7kbTS7{l&*^~WOMb@6-k@iW9s3vRss zE)**|;{?BFA|mzoOfV0NAJ$eij-!M&ucaM(a27PS&lBzi^A^m*PE6XxslNw7Yf_Te zrLd$R?0Gg@yE>#Yv33!OIb1q>hxR1XPHBCwH1VLzM{*QuZ2KZo^NDelGU ztP~Hcx8UE#p(`*S4*KdD_)Y2-_^+rN;qS%_H05H4|D^gF{@bV&!q7hXC)FqLpGIDI zw<4zuk6gaHqjdfEx{m_2%qa zIIOQ{qv>a3U7E{jmN6OkdO1aQFkrOJtfO#;;eLRF=4I`LL+i+T6Ydqb?Ql=PJ&f=> z;BJQ72)6<5GPsN2&V^eAw+s&YnKd77Cfsy5y#10j4vuJ!gu^=uS^eP3P$oy=Do;(Z61eD4+7occ{LM_NaiJ7%mxX(gASS_7{80L{2-%wcDEuuJbe9EfwjjdY!11oO zaF<&U;V$OT^DW$J3tC}89TtQ(WaK;Bf`}KL$_xv4ngva;pwSl8U_rGOgw|(JuCO34 zpk8n}=^psWRQ~ih3yQR$U<;ynisHGCnmG4i3;F^0ui-v*?}fh`?oBu0USZtx@byr_ zZD-sQ@E>;HCq(8(KzF!rhEEXV+#4+DG7GxMg3h&|RTi|&g4!*J@|aI~xMy0p=@vA_ zg2q|UNQQ>MueNagP)f)O_hlATXhA)I&*o5q+zch+e28$|+2NdwvEw`(1Lw9v2}(Oc z@fbQ}LV8-peRmucO7SJ((hdlbwufjl^e#iM<8CKIJ1l6M1yShZR=fupx~EI%ZH(Il z+_hG`D;ZjE#`Cz+*5Q<&m1#>np(d2J(1biT6H5Qhgwp1k5aXIDElvwEsH9D@pfMIS z+=A*YXpjX}nh^7%(ad_z3z}^~lwt;_IIRnA0^>$^!8KSo9jZm>063g2 zWkFsGB3v&kG{=HG7L;s3aSTPK2B)f&qd27Uum$~KL0?ZnmI}CY6*87Ic{fU1UP3ktydInlc}5CPULLXo>}mv!Ia{1lvY^DDGk5Qu;9jyJkRz7DRdIq1hHhDcHiL zBw9G91%+FX-GV?q`3U8ae8_^nvmjV9Jv4=49N>6+P^0^jVb79buMB9X1?{jP;BZzM z#e+>V;yq|V_gK(v7PQHNuC*ZG3@TSzxb+sa&Vtrh&`Jver$*W(7H**h&9$Ir3z~`) zlbGi*7H+r&)mzXY#H&m$fnQ)jd4MumLaBgU3`JW|s0C4|%?f2GsnZNi`ptxrrzZWB zJPF%Z4|au;pc^OP_L;b(4+w($iE>CfnDjPyUY)cH@QW7otOaegAmEZ7<#<~x++7v~ zT+(I^y}`m=Z9$h?(8U&Xz6GteAn;;PSz+NiEU49jW?Rq<3p&k$CRosD3u?e9r3aU| z7I_R{sKSE07SzjvaxBPWLCF>rN0f0FnbZYJ3TB)N3{BchxWuF2;Q7SEI9T`xxUU)d z)PnX}&~6KQ(}G^Hpyw@Uy9I%=L64v(nDWCG?mi2;!-S~xfQgrzO&oKzk#QR=++~0+ z;<)Ep&?*aBW^4{#_- zq^C`I7ja)_+|Gm@sRI(WB|M(+patDyLAP1ZCKF2DVL}POC0xsCue5OMEohwut+Ak$ z7PQ2I7FrN^G3d>;aLp!^ya&)e$}RbI3j!{A8{>$c9!m6dsNRGUrUKGSImv>?SkQ0_ zq7-_(K^BBlEe%|W1r=COo&{xEP%6sdf`lKZn$az0LNx9}xjv=>H;H9$!+GtU1i5~* zpr1@AfkF>*=;vK<`xy5@7u?&7+XdW<3_WW>TP^5O3)*5ql;SQO$aBU8vMl{wV=Zm^n(R`Z9$(} z&|VALjRPp&B$>v;I>y5;!ryK|Pgu~y7IdEl-2n)e4-y&;Xd^=vCKSKHgj~rc6n~is zaf*vLMWlrbHlg^#7WAnFoeO9crHEf_{Jhq+j(*aG19|wP=1r4zv*i9p} zAD}XhS7_m2360Qf3vydfq6IlEh;TX;*hwQTtfc`F-^@!Ktfc`RG9l)a)5d*g;^Mxv zAlOYK#U2ZK7Y9|o9=8+z4hy%owF++Qy{0+VmnAMa$6i!!>-6frd@{78I{cG9pg#QQ6{{MoV?-Y6id^)WW zFy8x;GJ;kGWR7+h!$&Z?i`oQC=P*g}yV4l{IQvK8+wpd##QO;^G3GYFo$3p~F_=XL zH7%U+m@5Zm%;HKXcDWP03%&zy@PTJ78NP;H>{2HBa2kVD>OS~3TEjq0f^*cv-~==0 zfT3rM2Pfh?ijOxVZf2iWY~mHo=tGMLgZXKxl6(Vz_fQw2&T7Tmt`!PivAM&T*xpIeQP~D|Yc3!!9oMjapA& zUg6b+UA*3~i`N?-6rB{4(~eRkha1&8_}_A>Z&_9cIn~dUJMgXKYYWI{PV8J3J4^Cg zqJvZBDEBis_m>n(2bd)P1eHRxF}0UiuMTjkGdR^tEGt+)@SjZDrRd!{_>A|`ikI|i zi{KB_&LNoAqU12Haj!fEI81SA`9yq zQkE&q?*orhevs-Q`CJR-Ou@@F=v8+EKMe0kB9x?u)kBhbmC{oY|FC`VvzhZEPL)m4 zkl9SFh_xk)>qRhyiWMx|6)e?dEYB5Or*~?X zP^hdRpW=&;RR_Ubx@gW3HW+lAOy@kV(`&dER!g){yjeo2R`aS}8?O#7WK0|Bs%Ycd zoXuJ~nAiUnF%RpsQ5*_g71OzvJD74C*K!-_s#wRlwCU71_oqm1ph@kqUE2h%(s?~> zxf)FvuHXLLM*6eF`qRpytl?JBpC#6xTLG^x;q5$<%vSPc2FpB?F~4hzfvMD{GoD&p z29-i4b18o3wwA&4Gq|lexvh2M8qd&d9G`4dI@dymIsiDAc}S!h%<&m3pn2rreL9MP5n&fv6ePV1&MY{a}6{s^X!!4%v~p@RLboN6D( z+($806vy1hG52wtQ4C*U%Lkoi4Xqw;e-RJOwn)Yh56!gt4xcQ~Z1x+8D_P6*XE9e- zG38lI?Q{+u#G%a`+RQvOYwMW~@!ZU1Z`QCvEU%!n>TIsZW~QK9{$}RHORLDRKV&zG zY5f>5*@{%w6ED;8;@wfQLZl~NPL8 zbh01EtYkW)81o3%>8G6P5stZ*c*gtwWKq``80fHAOVSf7xiw8AiD5?qf&c>dvr> zHD`{EG^dg&SF+|5v$nWcTPiuPO4gG~){{!spJLl8q`F4)!S79FQ9&B@6qU?R61Sa7 z=Bko4XAVpLZPpxmLmn}ihYGIW3YJC%>qa?C@*FOE1;;Gsm>tZ?DyF}T>91n?_cG=6 z9CH=N9L(@wg4G5NeU&hH!3khf7_{<*nuN)@pws&R&gr zv70oEjU zY@{(aeSa(w`%9MKWWr@)6`4BnHDmw(``=ydEu!B@!SG5QJ_4$Q+>$Z)bLzCwnRP3b+| z5K%4!PW=#g(^_C8ER+qR>V*3Z?kBi|aClCV``|u+dm9d;U-=^3vv6DC9)-iGAMdgY zxf$*TxU1nVN4YP?xpwEnt%h3x*MZkvTXCHYHv{f8VUrUO7q(G0z(F=RH9%lQCdf{c zC6qaE9=K$jm@56a6*fplEfj^9&0B>NwiQ_-T{+&1@ z9lMs8{&Va@LcsjSJS=B;5&KWE-{gayAp-gPnTO~2>EeC)B`}*9^BTi%G5$J^`5fv7 zJI)xsPf5VHam+?~su4FczKO@Fudx3%jeEpX9Or3$kzHto*|e?Dv#&bM%*905O^B4z!2ulv68{pkC_ci2K107@-< zzcU`%hie?czL(*kdGzx=?fdk^bR2TXcZ8#K@qF~WZTx%(e24vM{g4^XSCl~i`Tp>I zWWvbzE#E%=?XH&iO*a*%cbqy7A*Ybks~d-OCu z^bfwHzGG;+=p_PwDEHUC9SAk}^gWK&a3C;-4uj&COq23KOMu&r5KEJMj~Ho!!Of4p zT_V_|2z(Ucu^a*0C^gZ5gUv8wajGu5W6=AP%ZU;@5fhlyw-L3u4t&8v5!Wd94nUZC z#GStsZ*j;*-{r&^;{WJd2k2*L(_!CUlO9^Y&%T$yxs{GWxHOnY^Yg)F{1r3~`>hK~ ze~j$hNzz*SYUTr4Y=e=WwaWJy=M!Kt`MxtC{^!2$%{$~2paX%h8Kdj<y3~i{9|!8S21GXgkZ$#kADizUmJvd^wpvUHntAu zT6yqRK{L+znT3D0n1g>eJTI-qj{Dp3&*gK0^2CGq_YhCx-&4GRC*ofCQqs$!0B07y zirikqzYynGy@x#C$KNYH6nl^}eH98PL*d&%<>Daz{qSV*1Gu2?KMaugHWW@hPQnRl zQ}9%lf^X?$$Z~ww2;YjrIa*aX>ufQfYmHOmC^BkO0 zb|y|Kn}=`i;CoW|>JGjrg%SJhIEQXCp5-3G*MPQ4oMVJ9TI?6warV|{ctWACOTUCO zr6%LO7$wSBvNo2ijU{Vi$=X=5Hb}`0nGeQ4ge4Wm(g}fF?gWP963%joV7UabT!L6G zK`fUbmP-)JC5Yt`1i5^SI@^bT6r}SRYVLE$$iXslu#93@Mp%Q9F(Mext4=(fk)#yM zh)&q=BVuv(cO}kHBuNFcjN(~F!7QU-mQgUvD3oOs3K=Z}g^iGu3zE74@QsjHD9bC6 z<&^|^y@jXCxABacEZ>3bQXsnza026pkf5CqU6LHZ9W;tG^v~r; z8j3fS@DE`P4Pp%qVhs&q4Gm%q4Pp%qVhs&~hSrH7oW)iTO{Y4D&DJ?W9PcDbKTgvZtPq)cCH&c*NuzoCV}fFk?SUy>n51% zCdsH9s+DA}l~mT>Fs>W=7D*qReo1xX=DG=GEl%ee@^B4ha1CX04TW{7A*z)uu9a-A zm2O-sIb17>YbBR!C68;RJJ*VXYo!P4bqLo-3Tk2{^`WAV_AdUfXxHMKbQfvU@vXX4 ze5)iH=W^}FDPIrcbh6cIuJ*1Pt?F@#TY<{Pms@_r33Yqqn>g+6d7PPdm)s;b$kq79 z!*rY?I2|Vs4v-bnixUl#*+t`=yyJMrXP$;8WZ>a6WzD8Etgl8cs&T$!E{v z+_M*HZCAO_^O1iLCI8s>rA+o6mT&vMSIdD{z#Ntzz;bJAxQLBL|D!ER z`I8aypzjc{oxmPeEx;;Zzd*~PF%Bpp^-sv{W8Xo{%7juZzWW5R4j>(^=q8ho7?_m- zXAb205_kp&;QIjHw{qd@2dTaTY7$B@86}svJBSwMhCdi?E!>^HgNT>UB~9VDPb2Pb zrgK;&fg7}Cotp1Qm26NX3M8Gwpm+$SCg>^5ZEb_w4)-G5OVBVX=^v_*OGsrutTsT( z!NC5mrs2fX>BzkaXUetsenx1g>cC0V8+@JMeYwa`XW{(c^Kmxo1+Wbcl=%;;Bb@6O zs+y3l#dip4{y-YcLMa<~BxxPyT<9&bP?p>EICr%P=km?ONrcPAT+nO=&1%pbsn&}D z>N?tSfD&U~2H(+3>yl~+Qne!0Dx|`f$Z+1^1-M@?W+2rP*gN8eN}zM}BRKj5-0TE@ zQ^ChHyhk1(^tE@DpBumBtn=5nd@p)PD!K|##ky+&qo7|*qL7hW`BRM7#|fClaH=E z{Mco|!Or-|2-UB1=E#v4&2w(rJbMmwUI>R4i7(g1S@?@Ayi=SlPB-zkd;_10)j{Bm zbnkI^yK2?Ubh+5Yv7hO7P2c;3^bvSVR!@)8+ZLV>?!veG)>!!uIw3p`U(WfD8Llli z!W~+SxI!da__Hj0wAdgnvhZ6idW@&?VD`6#!>K%GI)8b(rvLtg^bs;oY_RAbI3e66 zPZfu(@Izg~mm+^E&r&PgU!DZ?GV~U-UT-Z%I)@g9(sTzreziy#4ij zpM{5<#nV>&B^Evry^BBJ!3N&0#h-x@l1T9NLtn8SBMZ#S*Fj%P2B`7`2fon7>YH2A zMSbzXwD>p|-pVg4EB2B;+a+{a<#ZpIoY&i>(hs>vtK*`f)ymLn6fh#YI62xG?1*+m z#H94>JS_?Oy`#9uQ;^}ZyFyiiBvp@z4hdF^byZ*Mu!lz4Lh@4*lfpwBF_DpJvGVMZ zBWXmhOK&oIoD_^kE78s}bHFt7!wltm%SuafvNDNLqY!`E25VD`($b1jQw!bh!c7LwCm{#CJaaZHinPdF-v2xR}Ur)fVb-#l*yi{1KIa zOL*r`&cvt~S7OY0k>HxSW80IWmj>s4)0dSd!PZU(*U1>u6rpZ(9dYD(-6}pVQo-it zz}l7-CuD(l9P)sg(z4293@}HYH)&elhzga}Ffcb~;E3GL-(wOIVt#)wJZyKbft5W! za0Kt|J1lRY+Is5PUJboeYFw`&rF};9j!TSD^I{T4Ie(AnQ{gS|eAm(WM@YYcMWuKQ zmLea0%Ph46Phq0U<$?z1=0H6n!H`>lh4M02g3ImzbD0H-v>%GCM#lt&honYk4DZo* z#*n-oLmT^aAD$VR8X9hoP8w8~HDvXSK4p#P3@d3;>qD}mB9tR8p?ky30oAjI=D6Y= zw(#hz;HacX@6_|gj$AXnEEN)CE?8pd8`w(WS<}LkmC*4q7;%%;%lEYs*A_kmXWmjP zX1qlw7yF>-jc&4ff%M4g>GYz->ufFc{73@5Lo#%(`nTA>i96Md;9U! zI&^$Eo^=@y?Ln?D)AE!4o~5SC<%I)2Cs4L>fFICzNk5dAsn;UIr+9&cLRztT$>z~g)NyU?rmC`{;l zh?@JKscS-PVvm%R=s1Vn=?ITW?umXqwU@``=%(8OR}8ujQsStD5GXN}IaaeJX2c~X zn;pAZBF(IA8bQs3H1swVjIzLzEiw$!NsAC?KgUTdPUF_|oIOZJF!ZAX{T;O!S4^}k z_?NH*=3;*g?WiGpxEj0VDo9S2;ZJaxgLLX6c(8-fPFcC5G=WSaEFukiFz!J&BCi^; zwyC_lY3+#OX}O^x2~qYid-{;PQD+Sqa@MH4@oq=-H6*x4ovyHu`~{)qGu93tv35pT zLSm3JG$zreqGKCYjUIJ&16u!Ek?3O+5@WsyciPjkAQ9${+wovX!hx~+6Woql>yGlB8x z5t|?rVu_0?e1xDgUw$1Ig(%Tcv2O;l5D0@E(o5gzm`S1559Uw{>6oE0TkSHIwvLZR z?XcB>wFr!#ENRt)^;q1^r4mamsgWYx%~FDZy8C59eKKZWj&l5-kU*Cdv3P!DJ;Vd0 zi&T@IUU@8z8n8cV(rfA8l!(uv?PTnb5aIrcgF=8H>JYKuLHQ26iEt zdD#Q=NG?(vp zveuYI5;9gJYpusle3oc@0&I>(Z9~V#Z%Gmot5*F4?dHK4Wg_V+o}L`J{wjf;V6$pH zFEw=^n3&r;!Jd`mj7HMT$_2S zM(i&i&82J)pyI&D>fZ+SzW7pw$z!gZOgv%^^Z>ptqUWNCnVl3L$YLeM0|8&qSKj}bkH6X z65_Of6;DIs1oc#CaA%v8m&Hoyavu8^ThjEP&TAZ@p$<7K`PeIrnHS9?D_Cgck2>fe z>1fGVcQE-{3pwyJkjW49*3Smab%Jz22x@8!o;O3BL7n5`;$x!Y5~4$5gXC=y@oH;) z^sy^q6C8F`7JlsA==k_()#h|L9LL^_R=LsfdMzBbJiSc*_+Gf;pZ6IDtm6#i}=##C~>4eKLBYu0A_{oHa zRr|)*m+g9s*#MT$FiLRKuo-y{$F(HX;6hdR{@_}$t^zI{H zjEjzONmq}w5pI#eC&f@70=dV@lL2(*wApsph0IeG%T!=Q)v)cHe>CGk!u^v z${N>>9J6Z3kX2(&IeW;EvmqPKi!}+ee$-nA%nQ86eYcKx!fw#4upXaAlsZ0eMEM$9 zcO4%%kMNrIq!FK<%rL*e`Rw3X*L<`ve>yz*@osSR{{iz5uW2;vN_73{Bd|yJDvO_A z&2aSvtoQ?{`)~18Ez%9<*Jd}vt^DI)H!n29xy9&wC*W&6q#JrUX@sHU!^E=z_#+lQ z#-ltm@_ofh=MN7z%Ht15d3l7b)8+D7>1f2E<0CMePQ8Q92aP#&yh|M7Cqy0J%fctg zbHsC2d>V;S{9KLkUFwzOZKm^wpPUbW_{sV4hj-=c{1ftz6E|UhoLQdpEWV?#Zfrim zyvAcFy_|`#T>g5XQIwA7Ck&GgKlAG4)SopY8amcd&e`tFTI7f;re_Yiqsg*jY6y+RK;Px&xtkmf{4Cqc8sZ^c}O zkx5XSV`pz|t~lJL*zPBifl@l&AfF7WdldB<0DI<9@cgmXL# z7rJoz!fKLlByN4|#|K}%u6gnBg497jD-U?QOyl34^|~kg-cJv0D$e zo4x*EnZBxjRr#M~hewr4fwuJr`xmcWAZ?0tHrhcIA1pGfzlQa$N!D~fb)|NfET(*^=B3b_)rDt9%FHRXn~{>sDT z=;ZIpW6!8cGG(n*DRZ-s#7Y*9^=dCZMly_KSKynCy{S}h<2Tb!^zZKL+ueUuSf6j> z7T{cVq`7%0y_vs%P|)Y19Kp(Jg0EyAD~rfdh%oYyaJNVq5u-AE$9OT;nf%`@FzI)i z)jT|z99g^DB$kRr zeEtY~~`>t9(ji7PyssO0w{e2MKa{ataC0ci0^wjR8?5%-U;1b#OI> z2Tmz94m3qG{Tb};4)`^%&mE0=j8r(BX^s9@AnbXrzBfJ9`;`! zIzD9Ugwr^!k90x-PvWG*m3BzN3%F(b%XdRkuf9KllPOp3C+k<-AH(T$91g8(_5F>g zi%hz64%&?Y`WWS0H_xMSy*EYt3dK;P}D1YW&$9??jMT8mqssiu&YdI!GAINeR zeK4>Ci~L79Sg@<_PuhB|xSzClaesjJ81efrU2}h8HJp1!#8^1o?iaUqFk`n#KXq*3 zGX{6TaULa_Gad>nTR3z+2N5a@4i*yOF+PtJGJ|U)TAjiNn`Vcj44z(h&>fq}Gz~Pc z++bsRB-c2&p*3suj1+0Rn3%Vrf^aIdk7mX4_BJXV)QXTA(7BeS87`Yfd*9}C3lD%@`s#6D@DN|bS zKK7u}KE1QEZ|`iOWp;1h)Oj6&R6vup@=d#EkL)j%PCer5+I`J@#IiQ`?3ipSES^0+ zb@qI&t;^4R{;WD&9ysGw>({^Pi~-`;@PtTH;5;5j)ZsXtq(Lw2Cz(ucbc=YZJIlJw z*pAp=i4U_M65}Tq2l-2-izBeFB0-ZhNV_FxUiu5p4edp3i7#<#;Bd|t@Efxo#BM&K z(KKQ_cr&O+z`ZyvlBg#Qt7sJ*Hsq^p`1EQxJQ82C;g_y~Cy*5=+BvcY-pH*l_+60G zbQpf16`Pubg@`M1>v6?@Da{9?b60Ozx@Oi28S$PSJ-s_iVd)DH%9kx2nVUPZ#BSz- z`7$ix?ww`&MQ`SB;A{EoVlA_{;E?oYZtDoR2@XlNj<}!Juz&}lISOlS%H)_wVTu&f7sfw?MxEFNo^D1(Cx#tS~ ze2Du)*ItieU*k%@NZ(s~Jxr3IhF`J;=(-~7u-wQN5cndABH%Hc%erzu*#ZI{alFML zyfnZ&=f&bZ9FFz~&mSU>9&~-8tTE2NgwK_0A}1v-+f`xnt2MbR|JX7fZ|SlYd?6pF zy-*ai*SE6|&WmVWxg}n#PXv*-5~RphD=GLrxrBR^v6E6HQEU62MN7{V;<1F^C-PQS z#`({+afXl+z5=h}lj2@)UV(G{S&W~<`8>xRzrgrurC$dxTAXW{!br&Ga!6kjjNA%k zL;ccr1eq#-bw>jJu&eT-B-N>PfoH6v0qF~opvQOY9jeOIfOMYI>k37Z#~zSI&>TbN zhC{wX`V!BU;06ftfD}qv`{lppZ2cqsfJs)*P1OABf zCsMs0h&u1lKH>_ifr#^ifxDgX;zq-Y=h)i=c)!ZtE>{kVo?PH@hb`o}{hYlmKyKd4 zTv9%u5uSLT_&WcUz0Tjk=~cjK-3qwDdic5(a9W=N?uWgy(hjXd0auaXNLeeneGVOu~934ET@ijmB&rs8(wLg82x3QG03HW zvf})-V{|=^^6ofa4yH*AO&G zjG+ck*xpESKjB;4uR*6JU}!??Ep9EXAPd))Sw2tS)FJq`1gD4+j>V9g}8%BqhO&hEjcVEz=i_k6*B^ZL!>th~C?? z)Yi7t)4kN*wj}uw(VL@j9+0Aa9rbfZHg39RCfPMq@4gTQWq;qEf%2Z-p5223d-~8* z(W4)sr#zzww&l06kEsg(fem*{kDnc_Lgm9YG$%cNSqfgdN0B!{`5DFKvoX5rGkNJ* z$2YMvVePXASDw8hjb|TmyxZ}CTFY0jTs@p5{~vT6lF7W6@}(6*_1fRjI3TO%YgZTTt9i6}Ep}+Rr6>1YQ@tuZW?ywnzuiXb zMvQ`duQWq$>7mnz!UV2O8>$Fg*Y19x27d&8T5&&7-qSVs(~dV{hgh}s|5t1MnX{`H zN=omqL7zG`3~jc!T*is^CbBTslLv;9#8!xtb4iMWo}89#c?{KCL`GM6=5nj3_m{#8 z*K`7jn?cJT%yiWmUezT;bKAsfQm#Btsih4Ocf(C5A$u%|5`ss*7RYF~+fFX6jsC?N zR-S+^Qp1+~VH=*8o*?a+WHI(2E!Ljwt#D1?XL=5z}E3ePhw?*6Mdwe-#bcbYWjpddboaeR_G^;71hcrc161|Pb9?i`3mDd;4NXu|z zq;s)vXm_t!r+LF#P;Ka(zG~yHYbP_4dk2hYyd#xtHnTmEf!I)s;Dm$|&==DQgIHzI z3xTUeaKZs_jw&Z4QwS)6#kSgU25bcLW3shs^n_5hK-};AspiR2lP4MlZ4g`3m2B^L zTo6;whW7Rik~wqrrcFoYEQH=QB;Hx3^e%2ue8&^-Y>qDW>>e06rLXUlfq~s%$Bb4Q zdkpi}%6T(4&M;N^6&e?wE1(JF82DsJu1wrXa`2!?ug^l!Ly zeDZS1jOJo$%xAb2Paod8yD#AJg`%G3EGfl@kLF?q9dJ*-u27k_R^D20?ojfW#0#2A;(;oPn-QH2h4OOm)_Wq#;e;7V}h+CWgtjtt3 zZhMk-jzH@9&^f?esT9X z^hMW}@~-)77Rv|bTDmqCV*~r=dsJscGh&i4ciM%Q^z44s?55rwecju7ySMiB?dWAc zc6xO!ET_$+?A7$J95HNe@+0ESuw-ebej_#7GdTdB{b&vTyzNOMiE!#F_+MBrTj1@G z;#ar{pZ9R*>{W0mE@t3a#NylpFtm2pSesCj7 zrO3Yw>tchOub!GYJXYMft^giWxx!>O8qUrsVn_9z+Xu3JIaLklAtQO3Z#CL@y2FXHaUDC*B!xoFkhv@Sk+!c(*=L|aEM ztIEMJX$l;gla5{>G=5(&10@%BP75*V ziwE4gr>>)`K3a$TS3_6pYxt0$L)ch)awFAbqP1_uWq#~&c7WRHnxP?b0xK&_l z6;P&_YprN!Z!jy@8_r@)3&@tLTEJMz-M0X*c^iXPJtAgiblV{# z8a4h(AJW5~aL|bO!|Cv`pAom03R4?@9WjhZR1b!QtQnBnFwfnNNn3;B4qQ?LxO%{) zak(FiouW?2=FnvBU4*7|f{u_S+bBfJ!OZ3JsrdmI#~yEe)SK^)?bz#gHTvlmZJ z9^TZurK4j@Z{Ox(akFIB7ki?CU8GP{7Pnr|Z&(3e9C035^Y2+W)s^gOjtJqjD1;F{ zfi+IQ)N|rRL!3uF?zkGemPo%QI7x2-f6Vsw2srT$0Y3^0N~|5+FVo5t@ZUN1*(;6O zp_MG)55sFHRye_Ftr6TUJ#|qSR7A$|A0Z#H3zAb&ZMJM(ruLgFoIzzwX4C7I(iGv0 z_O`c77w8+!Uf7lCn~>DO14EVH(u^@PH`?4hniIby5k34#G*N1eQ*R{kUi1d@ht>U; zt^ls@{1DK&4UB|m9=44~$k?+!MXn=m1b8YeN zr@s%2k7u;HIL{W)XYL}p8(SV`uarImZGfPn^*q~yOmphl!-$7bzkdXTdpWg_XJ~8FBmz>UHwSd@Uc=P8|$}HAMTOYgA`gKqaoA@vQpY^>r-K*U#Lz+ zq+iH!D;|qmF>=GUr9w&_`vqT{3t{AK)YM2&{{2YUKV^fb!3tLW*I@25F> zYI)f489vHA7?)dmm{=T#ehd*6#AtR2HbcEzNq&obtYf-47zyiEqe(QC>76gY+R#m> zJKmCHPt(F6>`?1};*=#?f3)FQ8(QJiBA`cqgdO&dt$6XDu|idcMV{SiR9bL4Ml2OM zv(4~5=JRD9c{^eXLx&9;mQlG^X5m0xQ2oisj{`|CQoayLg_b;VHK$0ET2MXE8XLOI_L#Pl{?T6?8q965O5C6nxXTwYM1FIF|cHG9teO&&+ zZPiSLRe1^2Z{SIn--do4pc#|3&Jl1Kg6@QONTpoGwRsTGPphUj*ZLu?6g$`#t-a%) zGCc{e8C8v7P<88W#fL)sb?L&YS7+)6n{nCg_E>sAcRF2~Kibemv;5-n0A`sm$$KO{ z|1DZ;t;>GL=T|}ZD6g}7zmx0Obgv?vj%eH#z!$KV?^<>Dvlj8UtyqKasNGGg@7MgP zhZ*=P-u#Q@S1^6mQ-A&hWG2;7V=iFSbTqDH^K!n94J%NRLL!Q5FUK&pbAH3=bLm0V z_YIf#^;N91{+K`F+b2nuFA#L%Z{-hMLUY0r5=CAFm*sL9xt&-Yu!F1VpvV$EUa}nj zoA)R}l4f#xho&omp$#qTHbCTnM{|)wk~-4UURYNXK2c|ygwM>lne5999vH4X!$pvu zA8&3R&sTnbqCgV#w;`73YfsRuEH0l-y~bRf%Q5*ZI~y9hkdGC~{2S#X@AdlWja)uj zrDE%B>xz7A>R%_B1N(<6M|pQFTRuL{fAQro$HgP{1~XOR{Na4wn@1f#AUg(CGaM4? z<~noIEik>@?EHG(cYZf%4&v^|95-=^zqmYrR!Bo2I5NsF7bEqrf-2G;$7fLmuKG@r znWB}4iK7e5thxVL$9;sE<^aQ+HHI+yNhe*CnI6Uj3I-W=0V_>w5SA#k zHGR#}BBsmcnGnVTF(=~ggT>*dpiA^}SbBl;YwA5#goIoql1I`Zdlau&H40d^-0Bf{ zCe2!4=*j)0SrgutF*5k<`Hpv<4}2os*637>G>S~TC6NM62|zYp3X54xaW@$}}Er>~}`A3+v+)z@F* zHaGQ!eB?JSKZom2v#evO+E;m#{j|9L6xP9$2VYse%5@%k8rJb1iY5tcAXdf42Os)b z#BW7ErfdBG6z_Qo-rIX?SLbW*dDtEWUH>w_PNSrCC~(F{S$$6Wb`AarH2&J#q-SgJ zryXx~$hG@P7ZmOM9=bE_wikW=kqysF9FG32L}=*!)#p~O^QcShdD0059;?qk;&=mJ zJEDEE>DOL=+HrHuwl8rFYV~#Cc@OD};^_x#z5X@!2(OIhzihZ$dgek}$Kvi=YtX08 zsLhJ}1{(^Gz!})_it+u>@rmj)^7Y4EC2Zae4WJbs0TGKBfsIp@KFCZWKRW4`v?q%P zv4yXl*cMhA)r-Ox4G9BoDlMa+zM zx4`PN?TMQr4a1#vkx(S;uj?6af?`VaNK*bru1$T2bNWZmfi7i3Nox|&$C7k!8rBbb zQ-kiQkZ$DVEs!Tw-22<#kza0N`Rq0KKC2P;MxHC66vqJn~ zZ$tOC?&RoD)GKNJI&Wk=7b`Zf%uu#*xGUMWqq}_mR<+)*NP%>oY1#T@I^ywK*;1}! zU6a~S=Su}Vk~dzbrR(c55uYcLDHV!S*;c}g=qpK?J8d5DM($hZaQQSFo(ES39P9mI zWO03__8j4vo^wl&P1IWBUR;9a2+E&%J+cbuT^A8vYR^2!HCNFC(mg~=N5@ING-1Y8 z?j?Qp2-j!D-K5Wo{yuESx0^6)tM7jnaGEy(uij6(2;g>~Xg$|M7h9126SY2(7fV*S zo$V^51#-hlYG6(Pp+?nVYNL5Ov#qOkpmZ)LC zr6FODiG$5buZOjqhlOabKa7d`&m9hYRMmBfBw*Nz{ZGtivm64K4MGum5ZM|q_Z`;C~Tf8^Bh7w@x+d;GxgucGG3i^CXK>cg(-LscgGJhZK(&q0|q=%Lt1iexlXRo>Y z+4G4ef>^a@tZMns%d~12mtSDdNiIb1S7+wbyjY}I5MtPO&FCeE&b)+J*6jG?j3v2% zgl7&NK75FAr)lMx>Dk$7`cC~7t9pa$XRmPR;;n#JM@hOU;C!?qn+We;_1wz!s;(;9t@dN(dR12y z*Q@|eT4vA`s+CtD9)uDIJM-$|bfT>{ zw&=40tLTdyj%|^)R66W~Ta;&|wtaP^tFgCG=UJ4b6UmOqvAnxJP@k)hrxe#pwu=}q zvR(KX6lAr$#Qz@!yIiX{Jw_e-BNEGE6zWvN!+mElYAwwUt+ax@eO zJO3_ng|AKvI*-Kv4iYqKI=#-y3|@%Rv?Frm>v%hoGw<su@YjQ-iy!A&j1BS*#ylliEGSYTzt z_QU;#>aEjFO;O^7rNOy)Low04YmgPWcKhh`Ow)LdC99m1dPY12{xLy$Hs>TbaYKT; zr7AZhDDgc3eQ3MjoCGE5FWPw6-j7O_h42ds__OR^mVd=L0^Lu1NWdSlD@6$`5&seJ zr;#%wI0)TOyn^6}zS+EjptPO@lvWNSUnBdxvv2;w_ROxv6|Bc zJKI9c7Ag@Is;y(#u40QvfvRdoE??H9%HZtm;K1CRRo>V#ytk`svCG{x*VVkqLPlH6 z=?S9DUwL;Q(>>mx>Q(zQ4LK#Q_stHMik*FZoyF2j$NKj2hJ4d-rs?Yb-iAgU^_X-| zG#|@snD}!r=-0GZV|y}K-@(_h=sofKCv1xPBx=vyJwB7; zRQPeeW4#j+EiP4`A-(dSfgwCQy7KIKE6+}~;MqqUXFKkwwS2?M)yXDYecG|t@z&Z^ z%7ma^;=Qxv6?qc-Flk4c7z5enbQSY>nx_W+X$^Yx0QqA0z4BD8rK7v}Izpw>gZwIu zp!&?p2v$G4ZROc*^z0*!-@rRmZFy|v>ORVCdD>Co)k?&Bx30SS3?IQLw20~merI2W zhpvw*C5mxxg_&PJR; z%%QV}pC>M@VOS=uRnR7&nAu0ML;H8tXShE}%*vBPGHSP`mP@E%PTuZ1oNh1=Idh_~ z3*17)h-uSFUMLd8J;+2M@xEeqg&_L~1ocW`KNvhXHhOSq=-}ws!NE-%M@E*GMn*Qi zSBtsS4L7}c{f*n!?dvoRBjMMk^TYc}Z3iw&FM5JL9rE7eVH=R1)4O|Uh-z+(4$sXE z56{ki)Tebx2R99!(w8oV42yObC(HTzo<z9X}H@@V3d2t^_UF09y&mm(& zyjQ-1$0_N()%F#3fZ7-B;!wA0zwln_7qs$+8D*kU6lb$&Pr9Jmo|Hb}e)N;>x5tTd zpljniz}u4?CQc(9MMcgAs%W%LPz%up-#kHop*WHVLZ<$5qnm&8-8;%vej;FtQMh z5b`xcda4x2cDLu!T{-r5#ie5VeCxzSZ!Tb(ffo=#541JK%lV;!p6-F6){b@H6k+x{ zwt#)6MAa`#(QKhG*U>gxD9pBX%oWykwG=u#3oTtzbH`ju%UnlszO8M(*fu!WRu~w7 zmVjIU_+(|W)J0A}HL;461DD`52&+z;0RNDL+1GmUV19JUDoG+qT041BbVj7IL|T zQfVQdU-0d}{j76t+rR&|bI!Vb|CZ_NcJ8`vYU;XOJFkO^z>wYGz-jScpuc=P&|?d5EdWUHR9`5N~7_IAX*E~V59t-#)Lv z#q{b)^j5`0+toBrCv()2SC{wVb-rn(U>ev}LCbi?$*$zc+NQ^SY#gnid<5nr>#lqw zK&ocU(EaSaUd5giykT+Yc~8H!wr*Xk4#+QjK`IzFJP&`aO;NN z;!F;8!4iHZt6`M=jCdc8_`=%oS?d-q!Zb;aGUjX-WxTzPGCOc6Zs&A&HeZx?C_|Rm_WG*w_jtv)0Q@*yvecf&6 z9X@MIRD$0u;?f6~_H=pbx>C7`Z5^X$kFU?qw71N*wa&E_rdx@oVfzvGus-aV&>GUA zN-&={;y5NCQ28RKi*rrOS^2#yB1cdUO@h-2h_W(P37v9U9Un+F?QiOy92{(-@L<;Knz z(u3(tIWyDWKXdKarrbn6H<8=KPS^ClseJ$5e*Ej0?$Qi@+i1R@glvDyXv>?L`WqVh zoBF1vDzW)e^I$qX*j$1-K(q54X6GB&h1pA1C`|*Vq`H<6$6KXwosi~f9XC7uXDkF_ zM&C^9?lvnDV%>G2LeH_|u6x*ovE>N#_g$Too#8IYi*h0 zzHysBLh44iygD8G+1k+G6sTzo**To|W7dx6n>DTR)9n*Y*@=$gM5bw?y(yn-Zp!C< zU7NdmHg|Px?&;p#H9pbPy>4B1&jctTjng;2$Tn0dArDR|Pyqgh)fB;M_@HJorRWN{ zbi>@H`tZw?L)w#Sz3htmO<%XdSjeb6uZ4(DAzXzscTOSMNSqfuvBoE>Ew9i4I25q~ z2$*eJ$fInsTCAv%Qk<$s4>p$4&0SV3V@|t{sHUl!s5#`>n&?hoCt^_X1pUE$5>=BD z?YZ!*7fuFp#yU#CQ9avK;|i-4Ie{Pead@Yy)-T>~p>EzPPWi#QPL#=1-5!rS5lpnC z<7!+F1ZCGb+U3-bw`2UwcQ7bNlyq03dB~^weP#gV=A404ofY#+Ea-Qu&Qm>R0GV8x z?%OHLZmXlAsV_-AY{beNW?Ss)naCwp%DupVEpG`~He>vi8j4*de?FD^xgK>o->H~x zBV@{^_I%(LgC*1 zt!gp<-=lIB_8teXR3njiSGKhuDhg5UbIf47P%8^ozo1&qfidZMNKQqJ_c%@I-T87d z)ic&umoyTE33r!1l_ZP-8Z5zk3!JuYJ@^DXov3INmX3IcBESgS7 ztTeFE296YF3-E0T4oA{ah)G^nStO~wA`q6P%l+?Ck&t(rX-U#$&Y(+IU0&ylmZ7Oe zOsB72101e^abz%#6!vNLS4RRjin3-MDtQs`U#<38t5m={GJ~0D+K{5ThEij?ub~iO zsg}$@Hr$YkMC((LcsgrY*|Z)H~Dwz^c#;|X-u1OA{D3ddsMkoEqQ z6-^{i69rhN-X+-18kRxg7CMJi1TkhJDo~jwl~;A+jsf_(wYL%64HxtE04Ij)x6K_ zVziTHmpQ&D-46)*%&r8ahh50(q^|>lKC=q}DdDMl=}Um1&-|%IoZU8zo#?#J>@e=> zW@odk^m#zgXLbo7^ezKFT;696X=4|$F!pHkKC{blPk|j`8U8NxnYT=k1pI-#&m59s z_pmWJ1xO?A`5K-|vu`@SD8~SyK2!C;9`+ShC)Wc)ef|m{C7e!HkI0wkGv!M(visOD zhXBv)tAKRlB(W?kLeb~@0ZFmDQ8hUU2=L6`)yBTa!g2r*;F-5vKz}m)UDRi4nIH-N z6!6R*zzVcbo7aI#2eA5V9Ybh7P%eg5%gt^J1XW9^><>t$;SEUF1Wm)|KlWOKY_ASH z`!VT$)SXG=T&64GkD6Z~8!}_tW*y7Nq|dIs&b>@cxR;*q!S$a@U&8ZQobq)sJ%1TJ z-^4z^uMglHs889?TcZ6ET`#aV+Rr0$v-bG|;`*of^$tA$3x2&Bdgvw8{)OT?qBnSd zAFh9iU(Y+dI29h(XT^2AAGo2j4d03S2f)o$WGcenKs=cw;lYSyMX(lwH{x)- zUsBK$SYxne*Yrg`?)N#hzIkfj*t_Eq^bmcG#4G2ldR=!1Q^#(#>g%n_fx7Rk8Tat=6592OcDMCd zp(u?Mh6u&IX^x30)104o(stQsUFASDm5Q=k>%PPB%3G%%1CQ+c@Xxf8Rk{r=)HY>7 zxq=ZS)CbP#l}vwiPqTI0aPGE(?XxXNW^SIa{PlWJR?`Q|qi2pZ3@oAgvWT2hLd6zBrhHfv}Y_jvrbzeDtz_xa4=FdeO^67;kN_ zIr;~s5`6^*poc-p?ssFeI!Al{IOMPqE7&&I(mauGo{aiZy5UsQrw@!C8g3X^pl(t! zG|SOK;l%hLirO_zh;I74et%leQ#aez4`yV>2&u=bU6tBDwJ92daNBfrJ;q+^Mba|O>Mq_ zjw?0>KC!}D&OrDT)tNF%Ngu;Adgk8_>q0k9{Y_NbXB&=lBMdp zn|;a^e~spo_d$2mP1XP6?Ow0WYrB_N3+V0LPPcSA-=9`+JOo;L!tIt0^7w+?Ph3C5 zrHK7j{633*BlbP(ID`E&J^$^^__@U9mOsP(#fcpr%W=nMjI_*jwgo#x;C~@r4lI*c z!3sP;vFk<9{Q6zJvcxVm#;Y_le(WyzgTEz8>_yV|kjLB7K>x zF`OMBoD{Z$rdo24(8mUR-mMo63?1I&^%P%MZ<2zJ!qKv6g4=bhjhH=!hylV zn?3i&0zrSnio}1}A=xEw*pgz=Vv|b?g*10_M})@ELM2S1Oz`x>c35En|BMrCiV( z^99k%Mri(T0S2IBh}k0)YKq?$BpVQrwwQP1F4Sr4TC> zSyvx3`}?Uw0d#+9^KsobTj$HN>l;z8Pj?2J`wM%A7B zg)}vUQS5CR=*WfXeB{l`>)55>XSTgaIS19w@H6B1D!P8H?7hjU!OF&*|C`u7#U|DJ1De@`b%01p}Voa3|7S4h8twj!7= zXuevF2dV%tlgVXPZ;UfsD308UeR0x!YM{0o&JSOMy&Deg;(d-!+U=fHkA$Lu>HFmB zc2_psNr&qPnghWgWMfoUX`3Ai#x-_h9AQ{dpJWfhZg`{PD;R-WdgC8y+&RGSdh}2F z0|DPBba?&M_Zc5>2izgq59*VMDyf0@>AX2Q_dCZv#?Ir~Eqb?&lQVCQdWbHH@8iyNgQ>bEJ@JVAOa9$G z>4_n2>V4@*@F($x2gM&6E825>gtxb*HMG!Zs(1=5RG;FQyqbMdO4yj3<(Qo1n7o?Z z%i)Acg5T^Sc-V2B<3A;Y7l85g{J!fPzvaJgcCE)~g3I4SotV3jm5-fNwk+t0B0JJn zEJ#6uODUHD?|=qhRX{{gH@jpto0`}3WDD-~flV89_$_rfEs?d+(d}7Ox3~?Q(X>n- zJqDBpcV83x`1}?o%VCw=eZ}_5DT^D}hr_xNl0t@#HBMUYe)$843vF|piO3N2Sxizj zM$cVbaP4s_M0e29s-{l5aEj^(^mFwNi(%!21|k?uYR0|L4|8^nCh5+`p18}SnG@@C zEmMW&$z8qWId?QFnK%H$+2N`WWkxy@bFbQc=BHk@(6s)l?d6T54XDHDYizrC`=K}O zY2Eg=`!Bxq{hPAuPN_W5INH-7`6GSV+*q5{TShI4(Ln!9W83=9&O^KVXZy=HtD$JL z@@OX2v*oPb4VO)hTz1EKgNOH&jHK>%t1%>R!3jFE|S|72s= zL_^#3#%y;#@B%-z^lsp#!Ley2zE?&$DOj@{4>ndb8Hylet}S*!l48Mt;6dw{M!FyA z=>p2kxr@fLbLH~-;oPR-;oT!S=&>kND|>pjUdf^!zjN}k3(DESOxK>#xidq|6$;{5 z*YH@+z)*8J(Y$^8`Z{cj@lBpRSll`p9xyib6c&rE^Se6&S~4_n!LB~PODgR@G+vmW zZAMX@UQ~|q1|nWpeP*CNH8ok^vSnd3;xYU_q#lxY@hegcYoWuguZx|j;PJFp(RGXu zeZ~yKyGx>(7$5Njigvw#qQ#eJ>49urhewfoN*D#1{K-sYV*7br<*N_ehrm+MlrG1a zVxKCM>w^JL4Ckggok}kKcq41uzqsktmY{mFfNj_~)M}NucS}e70 zn+l4HK9C>_4%5zjy>z}2haxIPmY+x`dT$dUfboHP1s`VRgJgvX~ zv>P|9$5E{V9a}D(n7EMYfQY}R_3a%Q*jG*|DZfv4`~0xbTgI~iuiNSK*LyUWoK8m; z#~nWk%`eBRm244uK53LhVM5D8##?PL00GMYL9vU-R1GP9;!UUf3>T8RVLYc*bHWf$LU~&k=X9X?9lYA z$p`sN>r_5J)!IIl%TKj6cXl>6b#}7%pbSdObW6)rOJSyExZH%nHD}9Q2NCidw#%Ei zZZ*5S-|2;EPU+d zwi_d9E8R|(eq{?aRw3z1nK5X!6Y-2MNgqXI7XA`gIPjKXQWfDaA<0?l>$A~HSXJC` zs}aW)lz>}h&hfY%5eZ|f^d`4Qa~lncOVhOm-I<&moSpC9JLYW7Sy@#}1~e%Uow_tr zO4X-g^?v`(%{fJOd1V|TuEiC_^f6c8xqZd0z1zmR&N@(#oZH(wf>@+}wJ{J*voq@^ z*EQA`5-rg?J)qq#L{typEMMUpISwmCyS3$-B~RnZuUl(4+DJHhj8ODg?VEH5N7DqM zjK!LuzlP_4);m$!t)JR9G3 zWP19@wvAWMIhj9D+3S`XcXW)M(X4pA0ax+d)4=@GJ3BgdG)Nx*#@BAydeg?~Yc?x} z`wJ3E+GYAieSWXvnHpy6o$q9FwxJ;-$?r!7i_-xgtn*EfndE66cPv3-35i+jT|T%8v1g+Y50uMk<*8UP9GUPV|X)oXKu8qX*7qj4KGgeW7F20 z6Gr(OmUKI9H)8Yr^FJmJ4I`~$@~okuvnJc8^ZDs^{>jwZv1+SN5UU-!cI=x)Ll(nsp2-0&@@w7bb#Bo|wEv*t+8kmvVw!Tti%~vSOgEbsohR<(a;15d$_-S=(hT5WO1&f9y{U+* zSov1n08-7K9lSQmL<9RwW`u?@oUBaMS)zC))wYa#QMJd@w|97WZwX#c9FT|FmRN!L z<*TI6!Cx0db_cTlxV^CEoFm9U*lKG|KKdJHVZ9M{vJct*!h>$}ZF}9y~ItR<72DJ&`EBX($WF)DVhRPAC9Os8(@PXBTN3U7eeX zvvr-x`eI#Ou|C;ZM>ZqsUmJ3p+djKQ`XJ&xVQ?ObQGN@YrxBcajH>xvwTfb`RVS!| zbfL2gF}-HkHk-Cx)@xb#{e`(U93zt*Xm%y2nheo)C_NNPw#DLYb;(xCYQ2C28|$af zn~9x&mOfrr+|q;cZw;kvk~ukN&(Y@`ix1?dQ$6(!bU;%>vN!b|C{ZCeI87-XhF=Ko zPIwDshZlC%WzaK7${@IiF%eI}JkuJ)q^|lET45qJ&5+ARk%v`dHa%R-Pta%O%PZeU zr?1&p>e+i_u5(XQ&>iq5wd7Ru{N?MWFQ08*m(=RLs$xV3$9_YV%_Tbj`j*S| zzh>J;XuHWom6qqO+qUcasc1xT28^snkMp|welQzk3}Wsu7I+2z^6ylQp=0?noHgAJ z=p3Mm^g*UUAEb&g;@npcR(Kuq>v|zgxI}ZeRVRo2w`ak!?cb*{e*cXhBscX(*_AJM zG%R~Rxv92?lhSzmgQ!S0SsSp zL3-leTn$8!M>41k28~l|SePxVa8!pvl4tDH^ZwB^O*ZTec=V9pSNWR9o5$}EYw-pY z!;DmZ?(zDNd3rgK#Ibjzf>}E3iAhO4KU;3RFX0b)f21hUfH&y=vD^KQxIgT@Us0?; z*#8wbJo9v(Hl5>=#+<`901by`&K?BmEBH$DR@G#X#=LD~DNEdK?wZZ0q=iuZx^;do3mr*Z-S(yCuwa*H2Q97wRgX zifp10Y!9(bjWYxrZ>Zd5J^PYFc`K6Cf{LPrbZ7@xYsk*>`E+FLxm=%n`LW>~C~;Px z2ia?F6f@c;_(^YX=)do{E&6P_xr_^kiRWLcmlx4M?lckaV|9djw*BS$_8Th9$~9+D zENDP-Vg|Tva5|S*@Y7U#D(pG?mrW$uDwV99rU!Pg)-1qj$qn_PNV+Y01!4P*a7az{ z+{{Z)V9=1XQdYD+y0hg-^)wC`dd#168y^NBYx%cv1|TE=LBJ9 zp@Q+VbV#-%zWK7+7gxznJZlGnfbS&le>L@=P19%Po|W$-bOz6_HJoA>bN|xq(xTo- z;Jcv*+~&=YzF{d0G5m(wH}=VspUmSA`9hVS%dE-ggWtM`F~?`w4aiKY@;BbMOB1j_ zJEaI}=Mj#o@2k@OidckYzn!}@-b&Gj zJC*;$E=8-ywRs9(wU_fx`)M7k5Ic?>H?zC2yNTzx@tImx1FOtWTf$Tz!HdN8Zruv7 zR;0j01C^hu%avdFElpQhCJ4RyMSTX1NJ)vZmysvD{tTp^Y83Nfn_~<4~7O-tXq5(TiNr{C~vj> zcr34Nm;XWt4&p&9-IsV#uN7{ zsmxKXkyu~lW~-U|8W7gATwLaos&_gn#RS;ta^<~VpQU;XFWco;eSyjy9%FA@^J~gi z`@ZYe{YH#=TwisE18PXQ->J|WQjTrNryHj?90JP`jn~vjXqI{L7M$V~^j7YIi#Wix zVlyTVcy5-m(h_E~+JhQZfDVrzb8X1yaVmKWiE_UuoPjnDodQ;`BD~XF5$Azek#UE`kGG%nj@k_<9Wp&X5z&H7 zHUoMjQEaH2o*R#7I+KH{7LB*nuely8rup@h#4q=f z#NGUYZX^;`O9J1Ub@&iEX=i4Sqr(1`y$Nyem+XIuXAF|&volf}>c++l9N&iSMT^-; ze;L1Z{`yXII%?`cEf|l+TVnVg)af#WFwcCrv04{CbFLrP-CcZ!BxZ(ctONR?;(UZNth4yREwL>D`@ z$T}ns9#>3}Q{G$iaa1FHJcyaA`Z;FwsK$PzgK=t=qW;U$sdI(=?Ee0~Q|AzA!Qagt z2toC1DRyr5S&03x2ehbWXq6$obpfHe)8fTI ztm~|AD8`~KS@quTDPmUkhxEb8+8NiZ37U+%;8ynkEBZfMN|bmazU{= znS#%lFic4sI}pVwlTqyV$+fw+7&~WTg+wHxhSa*|uxqov`)nl?3e~yGdG;Tt?uFA2 zX}PXMd!o{O>Rx&mvB5XM3j&MY-em_b2A{QRQWP*knQ_&bvYi@L&0i_vOy@C)ZJoY! zduKz>KwP_#;v%=HQIBhS>+reLQ|FH4*0sBQ5%nYFVS8;jKG5CJx&1QffsU<*r~1x3 zWvL!4(}-cqb-=y-quYdszkJa}18y9K6XIurrh=W5dgZZ}Qj&T2&y8f-j(WmfO=c!8f8K=F>p~>zd1OL-jmM$ekl70l zDmZhMJJAwf6OD%1{F2v%mbb!d?=DVev+Ih*$xPE^d#)+hoNLaruXRi|0oX~vj(k%t z2Vmv;Kup0-9|IeHu+xX(SSp;i+>1lA@o#dbuQWT?TbikyeNynyar=TC3XRD*wPsA) z9B2Hm#`S+cW_Ha<5OFNOX3Nw63=xxm6ME<*z!#;c^h(4$8YyZH9t8U7>FNls(~YXL350+C4Nk2pnEtvv4c zpXzk}#wq_l8ULIV?d*~^uq{-rNO~L@DO8i?OkSs`O zZ>zx{K?NzQ5Hu!@u@A`u1P?sR+y69bjbWFYG|aA-w-UTbR0VQ6ZUhgR#9pAC(mh-= zg?>eO2AoR?jb+s@)@;QRmKBSA&!U4tVlioVG@@GJNE9FV2K=G`9Or~Rs5A0*=`(1P zYeFk6o`GW^@nl@u9FAxa92|lVaEwN&2fGg+puGiHpO_pXNufWW8@J=Q-5q{Zl|#nL zqF0l86z4hxo1a4gWrxp4b~ba&z*hSibT82Y=3J;4RMiVQ$6iHukGQeHB8*-A8by4)xZnw;Hq)02X_0jwnwtLlpH{f(l z8g-Ty^o-%~VIM5VUDEBd9dCcE0I>SO=SGi`l_aS zqGg~f`{6o$+>2_1;f2%sSLR@$;e25!$F@j! zi#92E&ZnPik76c~!vE#$aNh0GvDHEG6zYfZ|qHx z7SkhjF}L(0=l?XPFUjfNpX^Gdx{}H6`ugsqm1>Aa8yci8Y&Awy6%kf^=}kqfWYUVD zUFa3S?zNy5NP4u&JIKu_VTPcql(Hb~tS!i-a+TU5`D~-gt&k8*6RVIibNLKP&B9EP zmg?e-ttJ#0q+Qink!;koOepEdq@sD8W9K5r9P0nJOsNkkZrCWlBb)twHY?4g8yjh# z_c**Qzn7lj6%1>NH6|Uze>^?8-N5Vyy*ZZ6L%~z?)7<_9=$melMKhT1S zCL>s3ieHJR4URSRcCcttq*UJZS3f2Ae z1Zl%7T=QTIj2EXdeQ*`iB`;yzP}g}mFlN4;j+daVj2Fa>g>D zSfW-zl@1tgq`g+OkG_5ROT^W7i7Ce*!RjgV^Kas6m&_`@0JikG7bD)lg5q^6I4NMB zx4f5aTYiRUi$;1<{&W9J@}E0WAg$xr5B2sH?9AnRXzlJ=y>_3`6_mUHwN0I(gix6RkY-x=ddWi2vu_Y~jKg@sIk`%um;lFLUh~JOe z_j4(S-@mqhb2)+EM;+9kN$D`VlSd?pvr&Jl-ndZIGFgOtVbWpvO~T<|C_?&A8}>we z3}@)LrCa#PF}8HT@5lHX>^&3CIq4S1H*hQ(j9@%v^LyO&xZMxVsqy;>{@doT`2D1P zo%2Ebev0?AW%(kV*_G!+O`pqEu{AiWTYYP5>+ftmAzAOD-YXGMn+ zPuR=i18%?TjJT!yOl7y*tw}#|$~_vkGI-tdSPepl>V>}WD|r|Bzr@^El_;SAZB#Y4 zYq!VrY0$(Dx&qRVH9YB>cY7m7AnfjeIxImJ{fJ#8ALLnQTw<+lqZjL7Eo5uR)8|4? zGGd2g-pIQ`Ui?zEIydyCi1Z`VuWs^cVU$|LRTSDG^+`89D*eKkTcvZbqxcWBzi``X zesBUq`1~%v;endto=2jUs)fAsZWq*s9PVya+G(T4}xE)-*%+s)hQYm$3-;d9GzV{AA?kLIy7AD8GAL5)7X7b;UR;!8idZsUG#{(EgHP1oSAsp@El_-Ga zTq4GqbzKLHL-c7{U>w&8t%`41cNoX24q%+(LO*BA{QYe{&>JVD@Oeq%tS6uYcQx;!9hc^A5Kx^=|&F2 zjZvKO5_^5WimESYm`t6F>LwqT6*Ic@D`AobhN$|LBu|k!IW>LL6>%^g8A7;1V{>`b{BJKCoZ*A3ki<@OA%k2{CYp5WVj2KWa>kx?Q|A(;x#)6zJv=_c*93xv>+o^}5G z)&=b^&2v60L=OZf51ilDG=G-u>dQfoJPP|$(s%j8mTPb;q|YZJa1~mOJ)-Bsr?S6JeTDOB4yfTGR>kBd|ZIUxYQYiLeC3 zPJ~MqZSdR0W$@RC9q^x*NkYmLSpmN%>`Kb15;U?M5=!}J`3U^SSNsT@Kor;36c zaVidQx=M$?Row%ByV?%_0re34$JCSXpH|PnCrLF(dJ39$LK-R&A(Et*@@xr(4idFo z1C}BhmZamA2-j=|tcgms&wwo=Q{8XCR*|f(H((p^^9?uz@K6H|4T7DbuZlGAt{^x} zW{PhNe7GnVPZ@AhKpvQlOBm@&DIDSsokj-9DK*e+H1HOb*g6BY!n#)&uuZtd6a%&g zWR@YqBl;QmP?0TC4cGxlh!J9;m@TG>xnhB66fI)9=q_qdbD9C2D{Pc#67vw_-_e{8 zn(3ff2+DKu7=o~wViv5$&*e<6!5jkA3@_ zp%6J~Ls~t=Fwr1}h|x%OHo`o(YejC`0gVDQ1JGjRzYQsP42ou4r{TT@^pqbD@!W#y!d50glqGhPDZAhfX}K-~YXa{Cd^3x)^CJhJ3nZkaiX$pN-HcN!bF3wAKQO zX~@w$NI)9W={#ciIVjI%4@jychxy;Be z$qw_+DyNx7sV+o0`}Nv`wd~hy_j8s(k8`BofOu3}n<0B4bWHZrMUW*1Y=`nr7TyL6 z)9pM^H->V2%3J0+xM!mMC??I_q%jh1NONrPjBshinnHNwzt*MYh$p z4Yr$YTW$ZcXW9$xz3dJ4$@VSw`|MBH|7L&H{*L{K{kZ+N5PL{;h&!Z9NNGrO$l{Q@ zLmmlvF65U`YiMq$H?&Xaz|hg5Q$m|VmxQhl{Zr^G4woa*F~l+6G2JoWvD~rVaf4%v z<0Hqnj$fU2=K$vl=T**)&O4kBI(ItvIS)F&adx;Iu6S3jtK3!N8tR(hn&DdHTIbs6 z+Uk13^@3}k>wVXku2W&-!tM!sJZx9k{;)$~--Y)MZwucR5f(8uq9tNk#JY&%c zcQL=khQ!9kj*PuL_PW?jvD;!Fi+w)!mDqP;kHmf*mloG0t}L!P?)2cgGjT_lX}8e_{NL_>1E&jlVMf&+%L0?@NeH@FWx^R3+?A*q@l3 zctK)Q;>C%VCSH?xQ{vr;-zJSsnwr#-v@B^|(sfCC~G-YJUMJacte305JwIOw6>ZH^;sf$uCOMNc& z<7^<-LjT2fkeT933|Y4vHt(|nfY?&TbUncp2!-Mbwk#ctoyQ_$$B~K-K-$$cmHNbc9UKj&HUBJz^+>hnhA zP0X8_*Oqr_-uk>7^0wsNm-l4ei+S(l9nJeG-J><^B>Ots7r1a zZKG*e?t_Qjv?)r7tpSx+@!n-AP+th7awp@_tcLS<+r|Y00{hKbG8Ba(l`4lE+GRl>DP)U&%Wq zhf2OEIZ^U!siicmG`=*wG{3aCv{z|u>5$SfrISi$md-C-TDrP)OXEw#D!r9em7^*z ztXxp}hsr-y-cosI<+GK4uY9HQ&7QJnkDjZ09_V?xS5B|)y~=v^=~dtB{9a>vUDRuK zuZ6uX>-9jd_j-NW>v&aS)p=Djt5#P1q3SPHw^ePcI^O%z-rx4|_IajnLEp`Ne?2en zydLNEKdzS5sE=RL$<%9<>{5Z?AozPSpLS?w9&L^&9FB zG}JfT*kAR(qW?Do1`e1!VAX*82J9a2%fRA+69;Y?_|HLVQ0<_#gZ?%+WAK>43kPo< z{QZ#ghpZX$!TDk5pLhP^^B+3@)X=^|?-^DxZ2qw2!`2VGVc3>o_YZq&*zRGk5Bp_! z)Nt?cQNuS3e`fgSBcez288Lgr<`EB%_+n)C$YCQd8F|CV`$xV#^23qekIES}a@6us z8%Av%_28%{M(rH6XVkt?2S$B6>Zeh@(T>s4qmxHxjxHG8Z}i2ZZyEjA=(k3n9MgTw z#4%Tmd1TCoVvxI4yeANTgSj`8v1 z>G2K^8gMk4=Mg(!E%uYRz9d%RxoLn1!+5TzSRq%SN4Z|!DsPt$%eUlF`IS7OQdD)RrR4}(Og=D7Okad*;>9J2;jVD^ zagTCe=$`Gq*nNrna`zwIe{%oDz1jVX$LWdm#CeiEZcnBs*Hh#v@$~Z4dFFeTdam@` z?zzje&2z8k0nekJzj~hWJeLuZ5ucHnk(*JNF)34J+A^Mi-SRW}r92@|sRC7G=HywmQ|(djYC^LiCsD{rmX@n^ zH*yk!mMz+y>h`#^-39JKce%TlyT(1iJ;~kdUgBQm-r&BTbF#%_M^2(WiJnxC$H+-f z&Plsx6>@T?XDf1YpXU+e52-p1 z6Qut-s`RTbv*RP5#5gGE=ljTa(09Q1x^JIvukR(_KRQMS1^zDhapsY93Oq8+PjaOE z$hISMj*L2DIlK@5?MLhg4LgF_3Ly?3XMe-t4TqN=zW4CLL&p!jA;h5<;I_d%bm-1Q zs}4;S;=^z|&l-q5pg$rFIW>=#35%)I8eotO+InpRaigDhwYC9cmQC7L?Li$A>}&UE z+qH+aXS5yKPHh)PHoLVw+N;_(+IJS4CDIaa@mOf=Byfc^mUk@&Ek`V$1#{40%ezc< z!16w*-nV?vnZmLkSi>3gd-battu9g<)O3uq4ycXlk7|ips-~&uP%GxC@v2Epz!+?| z`kVT@nymheXZ18ZJLaHPHHiKgGmpX;ULPwi!n6D~aj)1e9u?1v7sW>y-F+%P6W^)j zYKFR0y`tLHY4M|slF>3rX5cx$m#mfza=e@^7FRL+XlG>)8QunH7)NSfU^{cu`MPmkJuWC^@YawcrdQtUL)v80it^T4K zwNQ1Qicx=1gVaDZSWOWzXe}I=eTc#=M2g4|eNmrEG3K8n#)$D^g2=;+#Pt}TUV-Q8 z4eEKZMZAu7A>(9`%#^vZyBvX$>tK1lOqPq}6>_Ou zF8?Ces9l)1*e#!vyW|V<1GGE`MZ9#Nt@=qMNT*1bF(OMQh-{fCJeVoVmnot^rip4< zB8p{}=#BZDI$4f+ooq2k_7MYQl^7z=6N6=6F+$dfVX{U{ljB6A93#fcfnus0D<;bR zVzeABX2=W0EO`-Th33jBqD4*<&9YIn%IRW(oF$gXW^swc6N+q+^TcYoSZtEliOc0O zakKoR*eY)k_sK2d0eOeGU*0YrllO?Hs17O%>`iFf5|;%WJy*e#zDf0S#*-STE}t-M@(BR@tR z&CqgCPcads<>9$Pp}o)5tm-$kl@86WeClKM31*7EQpeO6>WDh5zE)qVPu1rlQ^t#~ z(k;5lbkPNKkF~N))W}j%B6Gy~vY!|!>&0+cD=w5n#e9ipBso*elT*b)v=GbX#o|)g zCRWLXVwr3ecgh>ZUGgTe8S`7W%In2L@-Fd++$x@t4~b{x!{TvyuXsYmTwN zu}3~D{w|*s2j!dMeawS>BHt5-qSHzo`KRzZ8i?8G%@wGf6zLlS-5o(kgt46AE>SEQZ=A$28 zudY;U)jD;Bx?F8hcc`hD&3jngr|wq|slTcR)syNG^{9FRJ@tO|2Ku>Y)tl(+{(-g( z*%S_W5c80#u3^Y%`CxNndkeI%LWEXNsQ1VTwbi3Nvb=UA{OG~e6FlOZ^M?)bh`mFH z)Op0#k;BgSh}D?f_J~QNM-KL&rxiRuOq?;V37y%Xzeuzm(P&9xMVyGojOMv$BK`xK z@c)1&>_4D!{RcG8|A5BvAJByU2Q(q)pb6*F(M%n7)}RHUq(z-7py|$3iH(iT?b17~ zaY2*pHf`Fx`O?FFCoBf?F3+J_or&`;lw}^)q%x;+>wl7#vR4ndVuyE=Ev3bG5`3uC2%bMC+(NBmw2tMLw-fNYq{Oqu6(_p95b*Z~vzsOVaSHwRpJETw1GKf-|vM8&vDZ2_$p_tDH8sh@!2P1-h z$f2LVL>@8QkNNvJJykeXS9${H;%h@t z>{O1epl_Rs0PScM#x$dW$JzsYf8NH6E^4NlrDj75&1#`qq!z0cYNcAGE>o-38g;F@ zPF=75r0&Lwf=dh2!ZFs4#ArKOi_v1WI4xdF&=R#IXf;Jk)zUOKuY(|E)u^VTaGKN% ztYOSmbFpSJPt6lnY5^hD5_PEv!KmgM5w8A>5mz+&pie~%`lN3~qB^cliVXELR#)X!98)KQt)$gb6BbB!?aQj z2;yqFXSrt-OqDf9*d3EW@ z2D2d%<#@Uz?LkA*FNpvjU1wtq?mEV={p?N>#UuZuRh=_Q6%Hp=BY4LnL}F%@N{4)b zo06U>+# zrpXZ}%)BeC;>Q24YMgH2sfJZ%gA<;En4cZCNYG9=Dto<6mApczQ|R_mE)r#bdBOiG zRV8eAwrK#H@yM0rI!rqKR@k`?M{*q|d!Uwk74%sEJE6J}TyLmNCtLXeRQ@o3z0nY6 zVZO8m`z_iJY8%3tFU^Kf4hDfHmP?3IL2f{ELVd4(R40j!)>ifyL~GXsD^Y5I znvIp%nP~T#A$=Fjzw}Z40p%;N>aAeUDo+)wDpe0C7jqiDR2`rk)kF1EwScl!p{i6h zfU+=qQ=zH>WvXtfT=fH#p}MLvbslt)j@G6?m8!mw{!69jO)t$I;zHavp&fi0PYC}X z`z|?5PEaxOLHQKY%YYmi6$U_@)Kb|w6KugjEn&~47FuI;9O7V0)LzHn(RL(t71@}ai z+!OWUo~R%9M0IQz^=xf}*xE+1wOxQVJ6~NPQvWM%J^1<^($M}QLddBJJhyQfw!rD1$t{JX9a@>hy5I9z?- z(G}zAYPj=t=le(;Kz%;o`vLCnaL07VG@$dH1YInyU&{{&=X)ED==aNT&>jysm4G(G zaF}5o!|nuKeWw8Tkfn?phKWW#BVdT(v>Ta^{LlgGn=vwRhNE;qRN4SZ| z_y0{dN_79d^tA6G3)zb9iZK&4%y133=EEhz)xg!t%Y5(1w=u8!A3E?%!<=H&|KwCp zr2pS^QD}$0JKM=mP^Wb}BU}5o4zq&Y&vYsoy8CZ9r|8*I z4G?Z|P`EKq?!_~FvFwF;<2u0cz-3{!wh(je-Jp;EpXe~&OjI`^4-df|MqBr|I8W`x z^&Q+lCrTw|d{i#Rbu%z%#}gghlf%k`{`)J|DPF)6>a(IkyePV%O)tghwVWL4xEJk3 zcky@3-j2l#bs1(1HXuC*#z;;)ncjmLUBYAL7tSe05=-BB% zge}4h@gk9o8RXc)(GO{HsDtRzXEelFJiP=C2~-fnQ$p+*K#0# z3TA{88?Ny8^x518DMWKol-Lw?637CP`%8-{K zNR#5eh8d{+SRc6oWquHPxB~V)RTNvEMt@K7X?&;32ma#teSvLOm~`aP+US)R$sS$O~I^f>#mxDlcZ^y{ZJxZn$XJ zs1tKEBaq$*^s7$Lg&A~LfyRcqG9KgDX4vCzcxJg8FJ$>^7ju9POtAki!Y$sR0UH{6qq#81x`>7Ko$%RM$5K+07Od~tq#Y|MFUnBqkWQ@jh2gnss*J#@ zSfr%&%NVS^#fk^9suYJ5b78YS%p1ka1gz%eK`UR#Wb9^6m1)u~(4{40fVqAIRxvHL-CY49IKQg zQD#Nx+lsNzZj2l&$KmPl0y#lmh!xn2uxf~1?dt`R%1r^)HE3H5uXoGE9? z*;v7ugBhG=IS(s`t#ZD+ShmRp*rUA=ZNqg~M|=p+nM>s|%ng)?uTgqs@)E3tUW&aJ zE9ENm$K`UhT!Xc%wc=NKxm<^}()IF6c@@@-D&*Dj8o2>G8?KetVLhx8D@T7qt$rKU zGYhMK2e6`gqr6GpEN{UY@vXc{yajtX?vQuNyRhol6YbSjtQ+5hb+anWL41Xk%4g+$ zc;bBk&*l$dMXe83(mul)?qi}3^GuJ+zv4OgN%@p~8mnt_<+E6CeopR`&!cr}#tPyb ztl9n@tGEBa>ggWrirj)0s$Mi;^;cjW^(FZ-*0lO#41=F~Ae_KjGq&#Pk{F=%ET^^WJ(#Za1E#|Y?*`E~KJ7_O{hL|~R3d*)p# zOogNET7tRqkz%QeLceqg=7eK0QxmTe&|@!GNh(>Th-E5Or71VhqMR|SA#PV)#HE;9 z>8iSkN3j0?4W2{CU@oQ*b2LSmyP?)_Ean%=#HVOuf5RM2CFX8=p?$qljKdsHAJrG@ z^8Hk`szEz9UaU}cnC)4Gxu4506SNXDL<6y6KUfV>=c}RE0XiJ3gd?#|I2!B!W5oqx z0#*yhV|T&?aUtGSIHoQX&tQ$>BJ2&AtfpYD=_2$1N3nxpI?b?~Gx(TqQuDA+fL0kV zR&8nlb|dI>`n2C+8TJ<}#~y{?`Tez6fuwavT9Ld;>_WS8tJo}VK@Z?x`%A>iPBN{{ zV2{Do>Kg2#_@lWha06ycHewgTjo71bv$_R)6K=&WhTE{Fc{^4$?^JiGyYbG#Hgykn zGi>Me%?Gf$`4HARX?^oC%(wr5Ikc1NajbeifmP3^=uHOoEauL3U~k4wtPw@vJb&!S6u-e+A~{Y?#M84?CH5VaLV`*t4-)L}GRHQSlg7bY4_1VP4>6?3Z{2;{X@t z7p7njL_e&hzNYr6*Ri7dPwdM5hj?84RXl+)l=J=7B$%yw#+WBuddgxHRZ;&$hdlqYbjleifili`)a;NyjtVl zh*w={+*dQbx5(gA?Y}a=B5#q`UOlgIT3c(2y}ET~YfIByM|IommYI#y7PdFptLybE zi&j+WterNyZQ8x&He zia38o#SMD;#kFO&dd|MBJ~*;LU1MmY*2q<@A$_f(japqB-l9@ReJ62>>uU@J)c6%p zZm%~os>^4vEH1Uz>lxSOuBo;4XGxs>1DVxx==D1KpOK2U$TDDRW1Ak;TkRasIZkoC zw^R)rWE*IfFiNh0xp|8W0loe_vY^HFwTwr}RNDs{0uR&$v<+;Z-8{X?Nd{0}l>xQa z+lK|)NtqG5jMFMYO>+)g(A>CSR#43-H8_{*#_jdi+D7UM8)+)6sJP6?MX@1unURZP ze+u=sQ9(@0jm(#qJ4c;S$lhW@QRN1!a)U*=f$ymcQe4?!84dHajSdpSPg|j9$Xjfv zsocm!dA)5+a2b_Q85Ma^Pq^OH`>*BJF#%oI8wocU0@eF~#= zaW|COE?^QJ-C&ePiJ`iNO4|fx@0f5#9q;M2HJS=R`E&h615=?hsxgeXh7|=o*9X|W zk#4n7KdSvLwh^zoryjqW>jwAghHd~r#wr5QQY zB`IM|!L|%pOZ;tXiLFJi8!e6WQgd7D{8>%5mLPVey6%hh))}p|ztz?`dMmgZfV00T z>!~%N0=5P#%BU%3t8EBTXIMa;!LrU^soNJ?Yopjp{1#(aRBeN`HPC|88Cj|Kb2F&w z47;l@4r@KT1%d6h2Afiu5xb1jLTg>)Y(1;BHaM5+cJKAp*{~N3!yQ|jsW7zGMlOmC zsmqL9_-jvDgKa@j)hjnLUtZx{a7Jl+iw#AU8?4F=A)c>k-w?L&Y#mee4AyZ4 zVi~RULT;rOnwDQ&U(wUHShvK*0X2j!He2b%dMmv&5U5*rrBTccWwxckt+Y`JC5Flx zdfJvTd&jafs(sHATVo+@z;iY-fdR9Q7E9_DOh1qBBLqy-1##^^M3GNb3< z8wYnE3`PWc625mfa#1pDo2jE_22_almj?KZj|^&y8A1A`2AOXn0M}DS%S@0ivoU%rs^KbKR8*t4 z-$nW;#9LHh$XsE_Tw%yuVaQxz$XwAg6x!uMJVr_-|{25Zv`X=ko;>cZycrgnxM+(a`NKDBY$ z+`w)888N9}#@_6dbEBC92?HVO95ZImT!_>#RM+Lx+eXx|BIm57=pS2jIhtCC#DM3S zaQOVjHuTR;GjtIn__mF0h{O+{iaw($5X`rM;7Gck+th9nL>Y(xN%YKxv!Q``tpTDK z6Lkg|winL?tsx7OF)Bc2ThKJEwPiZzw79q=v}r**1}N=KeoVQ&QO}63i<+{qX|2tz zE%Q+L?Tu|qEz?_DW?JeOwzV4JMir>8voz0cYc!BXLD%pY0S~Cmrw$hd;d=(b zB?gSP5ADBBPq3e!U_U*tOsv>5Q7puF)mxLZu3Q6|1*ry?t1mdBH(rPd-d@%)LcnxMzsIVffb$6 zg5NU{;re?fn1{s=`?K^Nl}c!Ho7!4L?!3mfxxzhf?!38}H>O>j`g;(xCWW1qzz{!M zex_xKI;HZlb`g#_Tsmim_9W9zX??FW_D<$a%9}(n^2W16Y(9y{PfdG>U&R|(QkG+G zHwWuXZkdR+Di>C>1a^u2fSLNwu>$k~R%7>zy_o6UiCNc2#r>Gm-GbTG8!#KXUaZD` z&NFxUO7Wz&0kZ7W*1*3^eFFbAtr-3*+H&|eYWv|or_t`{ZQ4NiTeT?oPifWg7hxxv z6brRl_!G4m@E>9SZtPa2SfqjH)zk2AXU;F-G#x4SVy+sT8S|XF7VzCzC6(eq#^0uP z0bZoGz+b5Dg+EbU4gV!|1^lp{w>z; zMDA5^YvESFErDx;Ylg#meC`yu32>v~uwt5v^~Bs7xZZGBb}Wo`i+RwHwe#!!1WSpX+=je_4~x?#G|@ z_`5Lcf98(tQmmWiV^x4`=Mmpk@c-(g_a@f(E{5NTw`&Q%4E{vlLijJT|D5jv!1wv+ zEr@oeoZ(9b{D^M}{E5CvNJ(VB1-B3GCAb&ho`8E8Zadr{I0~zS>kEgKW8Bj|<=;CM z$_ne}o$^?=k^Fh~c-qkp+x{2P%YVTxRPr0yH3;`0ma*d< zyNw^GaIB)h8nEk!Xx{{^lDB5_o_K`u+c+vo{)Bk?Nm9HboxKjSu7XYDMJeJoi?yG1wda(uW-Q0sDNfJlLU@jN@CLExfC=q4p}i(V zxZO+#+csjr!VL&^Za}bh0}60~^#|c}E?Z0->Vy$`g9!!VZZL5qsUCN|i9`J{;x0F# zMJ5!;+k6u@$AqQ>nk4Y^j5nc?fQB%x0Z>1NdYMqE2~lXF8LC71W@x4fr2>kFizHh5 zc_KX~&g1ZhGR|^FDCp8V{J8X=3DS9VhSE=f?pXR~@DG{L`zG|32@!4|(*;6b>J<6{ zhwdrLot6Iy3Nt4wH_3AF=ift!^+75+rh zMEY108g4=X9MKJ8x;itouL)HG^1^jX&xP-SOHL!E}TVVuGSn%~?f;eQAB zrTY{32Tk0&CiI301#kiARWo#t37NQbN@EwN@r)VzxCuRILid=^9e_5uH^RTx#9akw zE#=(3!i1KXP#d6T4kc&?LsM`j#Aw_Ng`2>bq3!{GoZAd#sD|hm>TNEvY8NtQlM}HN;^eR+7H2@Y2PsJbKs8<#B?7p?tq^zZGYO{ zwB2bt)1FFu)P(Lgp{*tqz-{S-yP4zOVB$8I(0UUJ#9eLTmY)M6S#*Aj%+UEJbS_E% zeT+F~-03DX$%Mw6&`1*+VnTt`8i4D^x$I>^r6ygW3FVtmrU|7&_wlUpNI(uaOKOJ@ zsXsGrFQ5|yr5=O(jG;p&^u7sE=vy4RuM-aK6YgK=gxkTmCxCmHq3tGgmkDh)p&Lzz zVqDKLuI_|e$GBCUaLY`b4z(k+1#VVq0GiqfH_;3oYeK_KXpjljG1ND;GS!>f4REdr zc}ytTgaWt#6l;bOmvH71V&aq^O8G6dGUX(NrhI2Yg!__lpP0CVCiJceyMxO&hj1;tK@CTToH73;Cgvw2*2($$p18tQ7p%F5mL=z%9Zn;uifNUv< zl6=a9elQ`lP(~%iZ#JPDOlX4%tw)U2Ec0>`x5$L%o6sE4O;4T#f4m8egicXsa1SVX2ty4f)X#({ zw3ivGL#1YDp$V-|&QD&AyUgUyQ0h5w@g^>kAh>)^Av4(l*pk$N17UwQp%W%_%!GhT z`i$ugnYi~&2)LxTICP(hLtABVe!+xxn9vg@^spZySqv`Q{kWvNOlY$S-DpDBo6yxJ zw9bT9nb0yJGQXr8C$+((hWmvJ8W z$uveviiHbjD8z)6A4>eqgie~!cP4~9=y4N?lg@=Wn^59G;+*)dAD8%s3BBrvNDmkd z5ZxX>j-_Jx5_kD=iO+xv@__Df6ME2u?lGY|K(UGG2-?WdwScZ-Xl>$(#3i_EOKdhF z!p&eDK~qdfrz6}1!ojUz9&L$)8+``dP}~pTaDr+W>J6xzpyUQWlvo6)fJ3uQ9MQSW z7>Nu;cM5fxp*Du#>6{ZzA?Irem+(WvH>oWNpC=qi_`rk?_@UHxKa{ZFg!Y;ca5(po z;_ftYPnpo8CUn0EZ8f1SCUmn2K^BAG4JK}bA4*gjA}@r19kS zaI0DO@t}!h$YDaDF>nZt@1W55pF81BFz#3<+-HnC1lso*ddr0Nnb1on^nwXdj2#@~ ziB7nO8MnO??k*FjL!0AojK3ZfSI7Szw9X7&WkSmsYVQ=c#SERr(A4;e?$PmM0S`B! zK_*mZLVZoB(uBMw1TOL2m`kpS^Z22}YvU&-UPYk^>-`Yn5>_*AxgVFX$b{zmq4;D! zm-tu{3OAt;6H! z;kanw4Cp}@IxG96UW%-$HiT1LRXp4S`$JG7Po|Bw3$$|3C%DeqMO2W69A2l zLz@;iz=Uc{2rZWpS`Mg)=?Y9-wh6gSDA9zXO$e=zDHHm^gud}Z zaU?0njs4t@i#=jOADGYq6WWhfbW`kJ99p^C#O*Ypr%dQkP~1=2h}~*JTTJL?6S~2K zHki<;u((lzZj>E-=v04F zPmAcLuaCVqwZsWJ^M6|e*!z; z3I8zrH2?i67y~1}M=Ym$6@G$-^#j0|YsGtl9I9}31~7;#otg!{U44yMAFIDIp6E4o z1b#HF9DoM%=AcK4@Ue0rBe7$i;9c;Q77gE~6_Kw_zz_2^F}#C)Jr=PT1#*?pTt{ElwyH46@D70 zn?~y{GEM8t7?L4P{mlMz@RM1dA4wjW#(7C&N#fN3U@}>rG|pEVr&vI;K@Bv2ze1j- zSd^mJ&8rT(iG$dPxoIh0;Pr;xyaKVCS0L^Ym^;T>73r|IJVli1O88%KtglFi;tP)T z9ihk z3u#qaSgYMwt3A0)yRrq^)FT{gF#Gl7<1J4q^YDg+lx6G}k`96YihSl!$o5>KUS#}J z@T+Le4DZ82t9XN!O5{8V7;^gHXK;?XvpgB3ADO{?y0fjOlV*Uy`jG6-<=dCbWe~^8 zV7NQOFLSJy8S^q>!~)j#0>X=nS;Gssl(%S?Q7GO@gHQD04Mp{O0b5`<=Fp9KIyiL~ zV_eL0CCMq)k%i+_MJmT-Y!7o8KbPu`n9JomlP$KER|@B`42$v3ABCa@iD_K!^Vxpp za=Fjt7G^P*{#=%7E~hw8hgln`%x9i<4YZNUD`(5pP=c9ep4tPritBF`(^n~KqwsDH zwbHtp8NT{G>I4vYSS&Vmfn6=bD(xIr@pMC0#Eau7inO2XpZ@ z4(PQ=jzw)+GM7j?-pi3Pn`KC*ngX6ANjgi?jqU9hwu)qyDxKx=vL$$#gO^MHeKiC2 zqnCRjr|xB*Hs)E#JbN)W^rzro$b9xwd#DX#{84&UHTL*Tebk!THVS{N}UG=W|ZGvsC$d9yJ^I7iih=yQ$CMXK{|Y8uZjQ zmXgeP%RGcaS%!R;p_VmJOY7FMR+|TZzIFk@OjE0N08Z4Fvp*JooVFEq^(&WMlCPcd z6gN>@1HYc*CUPu#e^tsJ4DVt3k2#f(iBd%}<;P6(G1ClTcnHJSTc|!Zak@>k29I~e zNRlQC@odsak|tWYhfj5RCR0u$+2kNjYbNLG22N!rbDqf@8kuGQ(=;(n6HC>^d2ixe zTu-soWn7v~6c-0aQSZ>i913aG8Lbed+k@7d0aLr-(Jh4e6yl9j;5pqwj+MmpNt{+P z$4cU~TpTOO5)b+$j@w{CPbwQ&a$eCzFG+bH%;^s1Tn}b$gPFq+<~Eq)F5y^%Io-h= zYc0c}x=$FfO56i(7*mqZG{+b|#_&p(WThn+q4#qstYqEZ$eg*wkaL-Gs`e|<;M58! zS8|E0WZ717iCm(s0)9Dbdn#*tC70bw*1%;Pccu0=Xb$6?9dMu=sS=H3TgiD@$+^3q z(_KmWL_a~T`bw5|tu8J5%`9Ov>*qoay->%qmYO-md90;oE~#ebe-m?VX8LBP-^}!z z8MB!&Y0NW?@owgj#%=rU9M{36%%@kvLP)pm9IKQmOPJ3{#yrn?ImWRtaz`$nXZjT+ zxj0Pu5}Yr*r%HTQkUrtl-jror;~F)zmSP1-BJLv#K`81SeAHR^s8ixT;*U31iQDOF8?Z=C4jG9F(!rM_T@6_#&8Cg{#>@4zRa^PTTT^QONNG=%D$XRU#6_G zP`k8A`x1U7Oa7~N7vKV}JAGM(zAVFB*6CzYIfUrw=<%dwQ>ma+|0vfkLPaHb4N zUdfb8INf#3?F#0@pYWXI?iJ? z=P{4-SjTDAX&-?8eeD4JE!rXYC$#O%fpT4Ese@n58pyNc6NYnfu_c3PQ10?#N(FBi zquga3OH~IM6rb%#<2m{&St9nJEW#OvOT-F5t8gCpB{*Ykhq#o#Q1&E!p$t2!@P#tG ztB)^~;SKtQcu##6eW46*v*Qb8cpDvGD3gD~8`W|0SG+%+E`OtMlgZQcZ8F$DzD=h1 z+hjNcmEPzL#fct5IpC<`cfkD&cLEOWjr{~V2U#Wr;#{H7qX86~$ zKanXPVSkIn6B^Efpmd*O|33D=Wf|HT<{FDufM_QAeu0ng;1NBIgK^&W`|$5(d0t|8 zFXL}CXfV1$DAC``_}iFr4#T%Hej<-YUt<3?e(KxFG|w~qH2W_}^bI&u;uQSt>^}^A z@XoJO{AE24-iuara%uP!zuE z^?m4vk?xzmV}aNtr~k(?|H5~$LYDWW?)e#qslDdLs`k|Iq*koyOpXJadSl#m*A>4*A}JR^Ilf<@*ff z`i$==Y$539LmT1y3ho1v5r2ax?8eZL53LFPC`SnW5t=xBX6_7%li0@^^aCYJZiF5= zcPxK8K@t66CrSOt-@gV@M@~=s>0rx0`%dBXH2(QZ-3(;Sp;9HE*$3&v~2#L?{hzd(4z?doze|Z5%ha{=}dL@o$o8k6;e4ydxTMce%7rN zeozfS2>J%!Z@$yMUwr5xf`7>Om%iNyHRSaD1GV8uFoh0-+kbG;A!pzkh{ z8u{Msdma>S+y!#+CWmbDT|<(A{FpzmQ#Cvh5{@k0&x-uE&jH{($N=LR!q0XaC2 zKY_=|KQ95?|#02>1BY}7=f6--WVr&`EQ~a&`<&-1Nswa z>KJMcx1r?gHW{2xqg~Ll0gFXT=8qe=2IC+@kR1kSf+61zR1eO|onPNZ z3S?uT`U}UTlGA_ajr>2ZX@(V|-v@MN{!B_gm2vgs&%Ppuej2oJ_~q*~z7FR9d;RZc zy1x8zaScdpj8*io;4;=>-?#o)MoJXdNR=?u&+0kj{QBGHbCd&9`Srxi0;vTcP#HY* z^v>xkfw>m^N%l}&o!C8Z$H_p^B8*Qj3dh+&X~5;+AB8j2dLX12{}`OyRRW4KoGTY6 z`rw};&J+Das;CjQXk+Vf>Xip?8%)P3Kr`{r7PIls!86ht?8M)Oe;%J2lrJ8|zW`?k zJ&!T!i{d4m#r6vRg*cJzHKg`B{zc*){ENkV_!?vSVvcw=PBFU#XPC{!7kTitDSVR$-ya!J?=j(zQxWmEvV~gNLal6}R<=+pTd0*S)Cvo&2W12PVO$2` zTm}(rt&wc4QAT-?wMHAIvK=Q~#c~C6(>h$z?-dD(Q){PpNF&Ts982;&d({50_8|mry2` zkh4<>QK@8csbq7h)ZwP%e)Yl*DqB1T8hKjU1wL-GLLJ=-I9 z;e@@ra7y2`avA1GCg9Y;39>IvFZAM{k24X;MdB2_3HbWP&u}Lgl4z}{4cUe{*L$J= zkNEUN`aWDEpY-=APV0M1z7KinlsZ14&N!cr&Ve(|eN$6$<{O>(HjmGEYscyJ!6&%U zX>2$*4dA4^NN#y(^-v?MDIVs=reWsS8M^wNZm+yl@Q%SzvD#iCt z<;EyV;qG0AB-$9Okn&d4Ns9kC;vd9a2zb1V_<8u2OT6!&oWef^?8NsvD87`B`c8r3 zYw-4|85qS{fjtE555S%V_PA;SRsnkybqe38Ax?<>73Nhw@*TlEjDx87?rl&VK|Ith zK*v#vkQ#Bv<1HXcTfsj7iI3n7tazLUo9a8F#zX!K&=+C-5BN~w2HYQR4cxuHW1uVI zJf<-13!r_I`TUAEry>w*Je~!?&G(B+HaHRo(#vsh{2I9?=sC=2?S$I}_Yxef1yW9b zQH`8K%KLG(5&8`Q_D3}tC#p_Ciqk{{^8YnLPpfv{%b=h$QkUXv)Jt*x>N-$efmXqe zJpV$aqZ)BG-84wuY9B z3~Ba4zDdaGWSq)7#rG<5e?(37eTC515&F3LGfoQMi11s`4^x`>ei5|zGQy7H%WZE# zJH+=Q;)49^{FBsF=wupl+k~>5fi#hhy2XdtH{__^6_)JBUuoi_aVlb=A8*Mu@Ojw7 z0lX3KQx0FK=4k$Sd0H~wl_kEN=;_XYn z+zX9xJKmq&EV51fauXjZZWC=L{vnee<0(IKxoG8Z%8x%@AU~bsA3Q65nCvQUHTfSn zD?A=&{hlzx-|G}U2I*6NrkLTgjBvY_0DaTj(R#Txns_J9derfdS3PgyS^p;eWD`&N z4wUm&6AwLO_sH4&6LGp@Al(Lo-loMZ&S9Ia!6~25V@!cr`1;J;veLe)A_3B#(|qwE zwYb=LysghB4STjp*s}8GRK;fGMcdJdr@j?s>>b{<_J%Ykn5|eXe_U5 zZvxuk6pTZAp`K;tLTHwUDwr+LTV7V0o0Um|o;wp%EA={9mr|IPR+y5~BQ>>0N>WB< zVnSwS%Kua^Hzs#aN$H-f`vn;ZNuG?vgp3jYQEmMd+D|lV>$7HQEj3G#tcPagLwp?? zt)`U-)!M_+31Rn zc6IzU#4ghqIvi@3gBaQz79G>E?c;cPNA&3j!y>~Rq3SZbEh;Q5($Vp?E6PRJ_rjxb zjdtA_Mz+M#aodxk=SJnB&C_t6s=!IKJJ15=V5};tSx}oj&+ArkvEd4BZZ2Be@)Bzn zWG^YFlF}IDLd%txkDi>}P-@BPUzwRzHKa?&_avW`U%8xLmiF&g`jyr8O~0`PSWCNb zM8S|AT5McleR1jF!uV*HTIGtaithL{Le^AQoY%3})^Rwry1%z~GIUvlUa$pcz+x?@ zIzApYoRn4aps_VroVClvM+J&Qa?_l3bz6nv~jgL`zLw>+piqM0`lqnPiVljVhhI zcEr#%Q_4Ni8B4)BL+`-tR3EO#I-c4+9Up~}G_`w0zKcm}6Ca8`hIG$(lTV(;__O#? zyQlMu#JVxHmwGxAO}vZu=_oF<+fZgv)H_ylNulQ=Yon5i@lq)jsw^rddC8#G0a@o= zHr+?%^5d9U#VI{6Jnvt2o7z!1ZAJZ*+a~J;aeC#@%ZK-xJ)%eG>1_^@8FpdK(H3I2 zKo0Vrhc6=28YtR$Z7%0E3U&h-ARC3-)Txh#=&{so8fk{G)FWKS)RTObLDY79gXT)s z%T|6tq?4@2 zQ0OrmV~lfD%b?1tt9H3;<=S_T!zsHlbRg6!M=^9Ae6@pWU{uG^FsgZujzc!R29l*4 z@~BX@gC4A%aPcGC6Lbwc_2W7|8f&=J|Lb_trjCyie=)RqaS%Q12~Qz`9Lo ziBpKlo`~N?+Pwxo4?B;5XFI%H%wqj61YdtV>VL5=gYe+^q1xwX#Sg=J>o&i^fXi3E6QeY0eP6dpGk$ zJ)y2QDo204LIXps*#e_cI%g(gZI^~eLB{5=sHm`xhb&f^!_a$nV5!nTj3`^j$x!Oh zLOS-M78!lRCD^H0NxCwd|Act|V4Zpj9`s<;Q(j>&OWnJ=$RnwPX(OK6c%ZA?wC=zc9lZ@jzH~blCG@Q6ctj^BhD-5t5RuVfOGS zO~u3yT|aj0`k~43ai5`+4UdcpJ022lb!R~*)Mj78b-6!uL1Xdfxi0H?s>?b)O1y3K z8AMNYPRB>$q#M2MABgka_n7!pna8%R^C6qp>0QzjgeRNS@p0lIw847+-iERW!|02i zrJ#f;e$1i1f=VTDCo}9BD_k)$#)VRmABSUFE}X_0C76Ke$W%L`!%nXzy{HxB2jGqu zF{rcPt4#u5?$lH2f^WNsQ7C)#M@G@-P+I&rb?%fec11?I)Fkpx!|-BU5s?rg4D(N6 zrVttOizp`ooUX_>gCz)tNgA?E-)x+izXSRh%H@zQ9y8mLHrBU}kHi`D+%}@m38qh$ zF2v(LLfp!^5{pf}ktyA(>nYq7lO9kCRDhIE%3nAJdYMt3;>6I?CFukYm+@qt^dw7n zq#4_G8SRRQiiXY?o;NMU660`$*<$*4?@^y09UdN8F-1&Uv|$JVh?@6bqw zo=<;aE$P_EccCME%MZI~G-{u9Y{D*R8q`9Z=GIxqI$txe5(6@WHdh0dTf;K(5@L)- zoNXFeu^z{jNo6(~`=7RPndw-(@Cx=PKzpl3t+tL0J4S6bY6H%5+G=3!8qJI0S&CN3 z@hC%WwoaY+BJubHShq&CL&wHFl7l>2eKpvXvxCMe2~$ z7*B4jjEg}Tg}PFU-7!&-VWAFJ0=1v~Y!u^Am+Q5|;j%iqds5QE!ue^4q`;n7>;$Fu zQkNq3F(5<@?ByV&NaMEu-`Iz=oHsq$8Vj?q#ti6Q*pL?!79LeO)$wmE0ld{vwuI@> z7d>e&;vSFiy|{dJd?aR?+Nibg{f2K$?7$3L4EFD!ea*w>F=|*f*l4UBUw|o>MvG2H zYqP15VWAzL^pI|QLcA*~w4+yuyvxy1g9ZdDlF=5YZ0gam(cz4YR6C=cuF#Hgb@Cd= z>4xA|1f@C2H;~eWW@fUSsp3ssx%NpPv>us(JDPk`c3^M-*1p zINs`@cs9+`Ozlh|JlcUA$>UeD---%uOJeP?+!*sgGf-Xw!^5Hu+3n%3=tC-Gg4@QxGBj%Mn2PD>2o)7}8XZ2m{aV#=naz&Z zoosSV*y#ru=N~_#jfMm$g?7@9mW;Va!%8s2ze9f-@=FBE4G2OFuC$|St4U!IF)mxU zrK2V)(iIjF?F1~Jc0{Qi=yz5{L|Lusg3!|s!C;+gO+*2jvA6<-gt-PYIGCCSv3r3Ga(<-E;aLpMW72%4{Pcqcu zjB>dm4K+o_x^r{(M7km(lr^!yt^OXQlwg(3$SBT?ce1rsX_uHG6$$4oU(Oj#D#?T47(NzzW2CL4x0Ov9 zgEvj?VYAK}@=^pI)nsyy^kM0$L7je8x3lob5bNnDLsTESJ$>Eq9)k-|(`d}K4?KI#lSNn=5TrzOrB@>GM*M9ZOh7Y@>zW$P7!vIv1nOk@r zA1U59=M?s74;Xyt84Y+&=Q%Nt(_a`A56^(GWs;+F{EyFyA10f{9j5%>`oq;xwB*mC z^uNY;xyU;7e9$u>$rVUH7GLjKVTRKfLzg?js2h4b>eqF=Q|Qn5I{rJ8ALAi!9Ohj2 znfwCbE+an_{yK*vzdX*?`Eq{Ecr@zJ@nPcYpmLybhmMcO96rtA>T+~5@kw&6_=kz7 zIe((h(-_~WTuI;lc!BV9%Ml1aw>*LH&T?IPR{F8{;+e&iuicb80{b4yOngA!iNI5v zqvw-GQhNSLkM#7b>~PhsRygePFCW2x9<(a)&qG_P$u z;9|;8@7qwb|Az`F@4?)*Cod*1xoe6$CN#`qi?q`aO-A@Dr2pEfV)6*i9cN2ZNx68; z)vTco9=NGge?|3QgDR|G$-jW)2QV9#gB5;#Bx$T5(U9qX7Wg7ZgiZCaxk4O~A*Wxo zhO3!=0sYrbf+k=|DO5ckVhwX*jcK^uAs6~3^IwA{WZgqTZd10v2B}TS46)Bp zB+ZO+ScR2V+MK=FtkdFk!r2DnY_KtK*!T>_a3&r(hXYKq$s7iA2S>8k_N}wQKd`a! zj{e_Q-4nFC2JZK}zdv3{{kprl>eZ{4>y>=MeWHoSh@S#&p9DuwkgvR~*KrNJXf7V- zDv!gVZaaWsH;LqIGmd@x)T_titIt`mxpm<)vcj6_M&Wmg)TK&aoY*;B+k0s92r>V? zcki2d{i%8SQz0KUn7>+hSk{H@YS)G{ht^-a7X2c>PCNP)b~STPI4PX)t5)g}wsRF6 zpF3C2%x}$Pw&ov%e6iqZeJmZZkDCI^CJ<^LfK9MZzuqUO~Wlui=l?dQkw$&;w>b z9uu=xRa13TRm1G|A_*6NSCX1!KEoi!(v zbi%`2UfXa#&W9s;O%@PFhBafu>s*uQ;8+HB_E2QlzE9pax-W_T^9ko1>NXr`f}s4Juc3M{-93*m)k^iU#^H=$F9nLu>yxUKc?r!(kpxr$je&LGeYbxPf*SAN);ZCo( ztpi>3ZICt_xQr}KSjnH%C2+zg(Mj_J@hRHOC1{7q_#{&346cnxasGbXGCmMtO2G7( zo~l*NiP2V}CD#}mNi^oy_IN`BqpcIC4Auxfuh%Cu&Yizu@U*5n-LK~sll48dHT~(D z%yuo9s1v-Z5%Nf}w)%m1TYrl$*gnzII^0n$Hu$4P^Vo)TVXx)$S?rGN!Hqq25r0_I zJc1JIZfxp|Syp4`M0d}I3}}*ch3|qUAt%Vgo8(@^Xj20iBQ0Z2e=u=DtXwOwBbDs( ziHmmSgpet0_8hy<-LvSs0Lk+^%eXSI$Rqu)=|b zOXlV-SzzzsF8u>TyK=c*Lv%$w+Ov!=@OAuMK4J@zP40i;aI$i2cmUaTJQBv?w0>>4 z-}QBlA-f$~i#FT`OxfOCYM;2K4UbZUtn^*tjy7C(G@d=+rWkPvUc=Oi=gA7NpEqI6 zl>7O?5}a}=$qJzU{6~ zUHQI=C_=G6zv14{mG>ivh?VI$A=kT0?H>}!3ZVP4h*P7v6=37HjIS!3A6>@d zZ0Y&1>ke)O*w0hWg#8^3M|*_lJIRLxEuScBjB_vBx`t31w+mc|)$R+K%?B0edD=*}`;xaMq+pTqe)*I{odBVA9p79Q#*c zdk8Hf)+T-!-nq_V%T6{>DJ@8}zYvKAF9?N2{8ojl6zENwdh82~eMZ$$Z%8ey zcMD6Z2CC+L;;Z~2XO-W{snv$ls20{&);$ zGv5nubv5_QkY+23$spod#oRq$7Hk@E7kEd5a8U}4hF|{greA4=9-qp7Er)aj7F%SP ziI)7|vHwzqd%e1*7QWld+DzlvWvXf+D0RJ}nf_yAeiZ{8%oKiU0^jgRtl7)|Q!LhcA4SIBs z>9-2M7FgT@2KiSw25BE8_ysb$X}#NU!XUvV(RTrHJsV2+v!VLwM8h_8mjfl8$o5hP zmtRLCD8Y*wi2Xca+y18My1wF@A1uKm&@73!*w4>8a74q`kUzkN(h9Nr5?Uh30)s@@ ziuGS#q*7Mtrbez*l%n2{tHOXcAQc7$#-rGUCd)6e`=r9@Buo&AG&JSd2NWNo(;;0` zgspCJSmLX^eU7g`IQV**_uYn*{IKDE@I8{SHk@!{!wuI_PH|bt1N5^5uOT>efnI1P zK0$}X24&K`J1*vd9JiVHw8KvUjf9jIk!RwR-Gl6Ta;RenjoJCs^r6wQvsQJi$v1}m z--g=Ty>Xy_6MnMgfLRzLg1A_z8_G1!UbeXQ;^~I|RW05(n1MofZvV*eo_u!C=m?MX z***FidJ69<{A`c9zK)%i%T7;!>cA!8i9@j>RNUu46T%ahwDWg<=z15wdkCW|zLON5 z2Nze6+f(`Oj`F(~cjDbgkdyMBQp*R*cVE|tH=nuU^`(2SE#Eu025&y)Iu+-36npw* z=dLU~?r1ai$nGt{kGkG~opR3eV!YJa(To2?W5BMOz5FhXq4-vD3^M$Xm2dZy-#(At ze#Euxx~SB4s(knI7jX9(R6?6A-R*PkCeh~Wk>M^0Pwl7GXZQCZ=dL6?d!W7q{d5WX z@IC|r@htUHcc8M3>C)5xR)Rl*6U%80+igEwfvH z5XsV9C`VhnDhc_yzI1J>E+mC+JqgWYJq*ZxNln$%)_Y`Rm#S6`kH^?pAz!mi`%k*w zTE>=mg9A?rumK%z@N{_|g|C$G^VFV~fS(K^g%SUEGcr?vyXx{y>>?$$iDnWke;HLdE)tw|c8?y2UgzIEB*efdyR zK=o;c+A=V8(Yh^{Og4^gA2R$k{jIT7IGKxf){Jz3x@?SmUrI2q&0Dbh#RE*O0~btV z%@nyH_r6d}B$?wLg0eD~9227zV<&X7sp&Jv#?G3GkN3AxhL7p@AuMTW$^NnWEV04t zz=ocl4T3&>@!G}9W+Sbcdh}kyJ?9Xf;ZtL^~k@#YQA+I@aeBuH@54VK1 zpy87xEx&hoWM9rw^|06QCF^G|U7WvU-d>0JI=C=)OW9obJ4G%GICz@_f86mQ^e&%A zy)D82?0UOHxdbn^lN30dxEtyYIx8FZ!QGtpj=HWZ@@ z3c=A=l~)b9`P8aIn6*{y3xiFNSJ@3kd9_J+6rtPgTwYmqqy4ejOO_Tdo#FC|9W(;R z7IJ$>NA~7&dq;pd@<;YUYcnvS7I=SWZ7+tC!W)Ug*@P)01t1e`aMMg7Ih=BiON>e+ zCslS_*C_-OIBxh&n3I&Q{Mb*HVqo07dbY9cg?|bUfa3l>eWModvXIi z^Y}lvXOKND%DUkfTfI$gh5o2D9S;0y${1kK=`mCPEkN_(@H{yDqb2x@PVOM_tfdP0 z%WRl!=FgKvC_n!^^1u`hzqSG{2`?RTS|l~2%z{ZOg!RmCquQnbE zgnFuvBiXY(?0SnxwrhQc%TJ)zI}Cp36<^*iAZwgQusqP(3Ca%GcedV&sP8BB=|}rd*gp zEIblXsZ~IkDnPQAmYv^VZ#N1TnV!BiNk<829_+AGgDU}oj^1v*Yyu*C&KqRiq6mPu7r)drTa09YhP5+wxl#uyn z-S5{yv|cZ~zQK6)v2PK-7se*0pMnkM^Xn!Q1d=v+p$RkH>zZ^lDDJwo%_J^!!MbVh z29Gph&x<7%1@Q@5LQ8saFa~4K@=cw$I=++>6{cvBh}PU)v-4D4ZO>1}W)4qIp1qjc zMlrA)1>yv~u{T#;wVM*~3hUM%9t_lZRlg+bs%WUEZ{8=iWLtx_e9GJMD7$xTZ0~@* zMyT(^jfOavdIHtdY<@&=;zu_8ao6o7{@%p7hYdgKdb=Zu>G_vR&;P-7yQ8TSoYu1a z{1NQ*wAV7hX}u9#5}v-G9(1%0bN3`dbKeI?j2!>`60hr4SD3#R>D^aeAC75?(_ zuh|IT>z4OYe;l|Z{ADkm#@fjK_XBVNig zgql{P7 z%ci-rp^x8Bz5WxRkMWtap+~<3S+V?WK>v&LWgGhJ2f+8RN7&_hlJjL7`tUsf+E8)P zX*VGN%DEwP-H0BZWSj(DK7=aJH2>66LZH#361N{Rp4Y~>Ng%#$f8~*%&|HM@+*btR z+BWo=`@yxbSJ~xyk#lVu`rIdoYfml@v-5=aLLVr%p2V(4Bn1$&~B;!rgW>zLW=BN`ti!;v@5>Z1RyejjL!ppMC>uzLt(iJ#mXreM5++ zT*zLYav_Gp(NHiPAqQ+*eNYauBSeISVPDuEtf|bh5Y=En_XmT1JrG1se+tTyId`>t z`qcYqmY-f8cHP5AxdS7Sgd=diQMTK#>kd@tjv)8KR_&>G<&?MZ9qFki6Hdx#vWhy{ z)w8O_r@IZy&S!H|j|e-|&JoHk1m39iM}5U_{)xO~4)o{)*j-P#?(7+?Ptz5pJlP9? zkrKirMl6-*$_AU0u%?K?UO=`B{;@edpcg(RvQ9N*s*k3RsI(J~FGEtI1s2pzt#D+H z3EHt`{rUDkYT$rG4O^Dm=!@vbE4LyVMi*ztNK_u!nE(`I$I*PrTsrjK=PI z8z1{|EB0-)V(DK+J_7X|FEP#~_7Yx2D>VyQLC{{|Y4jUeiYr$>EM^iGG>KgIhs2Vh z!}0{6(l_24OGgzefK39(fww%8EHsB};}u_y*Y-7OmL)1mmCv-?ZjYh*t2;5zFE8g^ zPjO80{s=FAkMP^Q+~)d71$2jgx6}7L*R$za8T;fv?%DwOJXZ6&E1rHnO1k`&jj*#ZC8RMLs1Ia@mq(!e7Y6* zhFf*(rmlR`t-PU#bGCr=U3t48_>i~c-X;iz2Wcv8(y}FrIE6}$;7*VzNcZ5ICjW+H zaZIk2k|s=&W?*c)&yvj1wQb`|aiZ#)e0TerZu+Y#+togwE()Jou_-$vh?5iUK*K;R zd&;0AgR0u6+uEkv3y)I|S4t$C0C%@GjP#J+xo-Io^%_)vCddEt>}=@hwtV~(G>v~u zKJs2qOs$Jk$7+UqI+l8hU5pB?Lvw;Ya7wQ5U%WT*wy8G!U-&J*;>%%kOAO+XdIOsM z6PG=QcyAo5oa&SbNFa76gj+uc3TKDviK6VMN&47NKkmAbYYyv{^Js;%cY-6A{38A| z)^`~yqu$Jymx%)HR!DBxtsHSZ07~MRS@HbyuKNfx%fAN=5@z6^p0n2w^i79$2oKN~ zPB!V5C>dVMh$O3N8aY;4Rv@f8k!rfnr+Y1tX90_Z9vd+y;_hwjxn`fo9@Vh$80Xm3 zd#ngyiev7Gu+PE8wH2d)b-S~SInu3d3_W!!>DCV3?5qIJ9mqBCDk@RsP$f3yg+|!Z zA3Dk0(7_>902bG|W5fd|=Y@JAh*^kC0cmlL)ydUE?qJUt#p)}B%`Bya=AU2U;7*10S+$V7<&}+OSrM& zzjWZRn$K%1K}ky4Pm`aCIFkMJcS~^c7ZLSvxY*&qVHv;v71Cf3hdZ6$J%sTU-y+NS zXP_)@#~E-l^_ zjyiW?AD_`$f_|w4efV^_2o;kK6nfa{GQRV)>onKrN_P>9=Qv413;G#y_U-#$=J#oo zv<_{Y@lh7v6TVe~KY~5XWn4a9fyJ6>%XyX?5Tgw1;)|I_da zB>5T|fkZ0WHI64;B+dmlfh5T#@0Fbg33>pg8@~>R#(acc2%sj!W;U!>pPM5>#LT_EAjL>zur|>*PyDZy?Kkg zmXBe!>iL@QE@%0Y`9)ED_IJ3zR^2bN&nqT=6&4is{a57)wLV=}*fQ*FT`4e))xHXg zuxEw(M63R`B9B0A#v(<2vou>zy{0sW;w`250MwbS?-$<@-+0{Jhh3+;epNir*4+SRX`bGHYUA$8U-g`&9ObziOZS|Eqlx&!wIfK6R2#*?yCg zMV0;kv#9dl^wMJ+?XlN!oo4)aH~kwCR!*<<(%Tx=`Bvp6?FhXoL3go_i@W@9CP#BqU4C#Sjy`n07WS zFq2W3p@h}irGdI!OUq!ad7`(WYh9*#C?8QZB`jA>CF=W{h1StTY&c!pyD^hJxWS0Z zvY^I0g2{%)L_|@e@k~o6ni6TsBswRWQ-l}0rzB%OC#WeDu2ssI;@{pY+%cYK8Cjj() zo#kWE-nF^m#YCvRk@c+Y9zHPA(C<^-m_gl$1={C2d)Ks?mZrtpgQMAGzRAaYJCF-+ z%$NoW7Fg_owoNms_Q^yj)2X|yiQQv!uN^Z@)Tq&zDr;SvvJ)H9su<9a=A|~Z`&$PZ z`$l7hE`0c_l+OaUst;rIgCzTK{+Y>lUUGp`^w;LNYn6}6frGh{w%_#xxow|7XW)47 zRvC(^sAeppwj`?k?3mxs(YWEe1sqAMt5ZFeZUx0)Pnx}C1b|oPi|egix9(pZ2HgLyXPEYSWDA0 zYklk$AmP7HJ>!g1Sq*2=|Gj$6n$`3-^_REGc@%P{xU~EnUtczyyu}2E7QQc5dYV?1 z4SoEQavS%SphsUvE5vSrc$fX`vpmjXLqA=DKD-6X1J53!u{luksD6{L4*O}+5bfSQ z;=0PQs(=gbIkek;<`Q@g>5IZn;q21We`K$BNhLV(5PF*QP{8?EZ9NrVuXwL~zo@6$ z?G}4czF*W+?fVa((0)-*weOR)SNZ*-o{GB|3wh=2F+PTz8)r0t6F;}d_}o5{9`@63 zD?y*$LK1;P#WNi!^wcdBy?Pivs4sHLnc|d#Vr9i@YS1#l#fxUMpZh<{SEYDVg-?`S z(mol9ry~7komD|y$ZSZa!fn+pQNwaeD5gfGR`Oj9-Ocd8h{B0PN5nX^t=gz*X{c+G zJ(8_|7RMkU*TuoZlgP>|Q&$mtz}lt~9z^oY6Lt~=wW$}oMrqH-GJJ`etH$2RO?jYp z7)TZ+8S!;HeQ}lIbAQtOtP<7&BKwXKRQ>MzaJrX(?9;+Ng?%{0OhZDI#r^Vfi3ZKw}0=pCGrvderz?Jw~ zKzxtrM`b$kEx|V`A#Z`(Xp*KsVs;D&aW`` z(GcOs?#(BFiC+K{WaC<>US5QMssulZ-JnmD;QvyBKa2?HA4>3#mEe!KevSA7bX(Lv z{T9x_@gfJch46W@%u{Tyvc1A^=p}R6Nw3NdU}KS`7w(dRh8C1R()4bXZ8p84`y-8a z>Vn%WWEBk=qwEK=j?~kaEO`5V)$>C`kWpSzbN{aACzOLq9+4*zJLxa+JR;kbvJOEu zYy*L`Tfqu#Uic%^Kk?d`j`^rzcsya{WOY?zPi^nkA=by)=6}pCwy#RCRFQ8|&xoh|+Qz!;vku=RIPpS) zOTy6$Y+guE;(9i;$n^+Hvfpmw2<h=WdnY z#DDD8i`=CE^>H?HtbZ=kxu2L)cB18d#mI>#8@d8_XtSC^O~Jq?-1s z*z9QGFX6C>t${UdHQ|PIghorggrGo~Xiqx0d0)v}5fpyoz#)g%!ozPrEs|%2o=yl) zY#QL)??b#w8Tnnx?~qRUX-Dh0eTyHAf zy`+41Qv!FNf=%p5EQ-2A4*g=1jCAx1M4h@%x`u4yZYx7HR*cwx~}d(#pt$mr2$@G98M*-bW`57`$ew(D52djWZJnIjym@MJ>%V%d-1@>*Z<>Go+R1I5 zNGb_y=6nj}tkS2R8Jbiq%?L3?VGD!U@w{~qj=s#c;mO6t$%)0qcc?~-=fK*bZQZey zg;HUv5p5Xh#O7XRw5`*WfCb}+c!)iwA4v&1wT{+%Z(Rxc`4aT;`BzF%$P(w-qceXh zLH}HW{$ZYUExX-!IZ(2(-;Og;ig5VboHm|LR0E2v9O0|NL-3Ui(#k*`{WG|f0$hAe z37)j!h?vX?h=pUmjtIZw{Jnm8*gg5G&%w)0&rzgBe2@K}_;025_wm>yeYe=Y%=S|I z)UV}X;a3&y&QZT$4IE(?+wBQRv*rB&JF&-sQv!?QKtK8O=qEkz+<&R`J$#4X$H|2_ zbFg3d0c2?hk9HEZaLH0k6|#Lx1IR;%)>t8@{wbBOi;pIICcIwM?V&Po-o{)wmCdxb zWK-;ht~Fhqv#H7PuC(g&YJb%&uhtW*9%$_u%MJ{Ur+X>p9A!7+RLA?FtJVH(ie|HI zGo2mN$>elL=S*9Ft}8t-knYL}t?9Y;_PKP|>JI2dJ>%m&>G5&s2T9E75d56@ZD#@$ z)2VE=09VDlThuMLFWzo=Jv~%p2-`(rsrP!kNJ93!>>m3A=_- z*~t)gYCEKm;Zx6X3yk?uP06m;IE>a_M314dlxsckVpUGrXQ&&;=^Nk^a+3WQSEX(; zgUZodZvAxQXt#;l(?$Rl8zLI(6=J`}zjdWj@_4N1~nU`iAD>qT6rE zy8K%od3eGaRKeexqTIiKZuZQfx;n{_j4*m@q06XRM!U=Sj$>5Ya%hR~k1CcI!9=ig zQ2x2_lE|*&*xCm4uqlrhyU1ut)+mMdqxKdRbApNX0U3oV__Q!&3>DZDIMqGRV;T0) zR_yzC@RG=3w_v#_hn#fs27r<$+c(7|*@rSDHKUEg+j}}U2^it_I^%-pZ_YNMMnm-%UB)En! zXMYtQaPhh-POVQd$GHV4#1dthI%7NeP9Xipp>2b;Rhjwyqq4^gntE#EY_Apx3@&t} z7jun+r%raQZjaCO4J@^{t#2QaQ(t3Za%1Q4Y2!nw zHNEMj-kx=oTZj1>hSm2ds0k~CXG|Su2~gFS&mh~JX?o!koG#8m;Jok*P9>oooWiLV zQLPW9(2iZF>aZen@Nztc`EEkSHikY~_FQuQn3JiPMVS~|oj94Ttp_=mOwfcuAhXws z&H3iR10$pR2jhc{Vr_Q=Lf5$+0}VaPuEbbt%UJ8;@aW=A(_2!r?d`Lv&1|1)_RX|s zxA*sN&vwrAn3|a$Ph=^fGMgMrzrAgwxp|~*cwyn#OKXSQCR$o1+J>oG%FyzkF+1PI z&dWZsKlv_vvBGl5Rp?tMq<4mgx8>`qd*=^~pvF83M+}~|WQP4i^BohrGnkuh%*|{j zyO?TQ5WdSN=j?M{vpynVpNQ98wfD+ZW~{${{EQK2YC6|;cdza4Sm+|jU*46H=KUQbjg2E6ox}7q+1{SSKP|n~-MyGjFLrk? zrF&Nm^i5Cq4XgqsG~ld{_d}LDlrR8ZSz?wBuY9v%Nxg2xqnYNCrs+sV^6F2?je_V? zEw#(TnAa%0tb2(|A!~!_Y&FS7k|eOez;cT=nZu?^ED1c)G0Bz;uOw{@w^vmMVv2x5 zLRL+0OLIrKs@XR!U8Q-w__VA`J8F7r{87X!6+^Mw8?Z^JF4Y=b#CB(m7!KJ@%tQ`A zktb9ta>Y*AovN&<8}SNd%DkB{B^138ok=o;np}yxfm*|{&xJW?GLd! zr7m6DoYlPOi0+j^!ZK?1dSUxWPxNZry5Z6_0zV0%+jF9bHjNdkXm4Q!Zn zC|Y&Eb*>My=SbUP))biH4>hlKn0>aY>L>7Bx!>ZpB*W+Rc=czsHybQc<+*+7r-qH0w5F{)X0AU9j4ZLluN7 zK{u|_A)YR`0uie0+PX%Q4c&F| zY(sK!qV?0w;i_0;G(xqa8YIC4j`8x9XPrP)FhdK;VIN-s-}cYG(t|>OdNnyIg;9T?t46kU_NEzTCq^*I_`Q zxAM2*%Uw+4&w$=IB)yzwvg-;w18**eG_XrqO85aFL@L)%pV=FcKYTAB=rg;X`pn+Q zba-ocpV=D$>BXsRCNdRxpBecf>e!X60e%DCXAa4rWxw!6K+tEW^@-!o0@0)+ZZkTlwn`CHUyoQ&nFf`;)|)HZ-vAYMnuh;YsW z)uLbbd)UWR>_^FM-O(`ohjUlIx|hK0J|O@u+_a}yEWrf zL6VR?IECpAEAJ!JjZrapPjEkj`=1fMf%oG`-MyOL$BT6T9sK?{Y!IA4!`pAR+sDu_ z8l0VOzyE@8=gRkCSJ3^pI^Tam_z-`;6Lc>lotwwLV>V9f;U>0Z^9WwlVtZ5bHw=? zcchwANGNi5tSh2;gQ#9iNyT6wOlXSK#+8$%5_4+|J-HT^AI}8bbX;G=`o=rR zf3Ww3(a$jc_lFC6(OK#E5?bWV23%C6@=m_4*Me!zeEl7oqRki zKDzCsg98-+%j~bN1ITLKj!`D@^DFo*3)^Xy(LeGBTmzkzc1*i2Zcd8a?IR<|bKJOh z!|#k@tX^m~5lZow0)BtsJ7M;fKr|XC%!a>HF>Gpgd6nxLwrsbHcuFwBWp5C5U+p<2 zrc86bJBSv&el)BJ5o%MS*4ap;Fc+w*3a~FnzRhvTo2MR=c6Fcd5M&U@eG^(JZN-Ap z1``OV1RX)6umrg|>+EIDMUNZK_X9@P>Qr(n)xNq)2^)r6jUC7h?ajyX3mu~7p~y08 zD2GU-gpr}|YTE*W&hzq;PccGDWX_&5aZ@rT1$gZS}R z42*sgL1PtmxE^AijLrk4cSw_T@GVInjSt27|1B*;58;oNq2^|k=Np2EW8h(LWv!@f zGs!(h(83Zj1rm{(lgsue?TL#SwW=R@UFtYB3y)(LuWFy(7w&|)vZ7h`>gAc7A$B=oCr zrx^^I>_xg$Fk^@hcMf$7f$L0FJkuk)v5#AQ<#t)oEs`mNs0DO0dxu*>HT4{>J6uOWOOK-h z{Q(|XaQcb+2e}M!zKZM9__d2IxHhtn(fi+92M6VLwr2UG?Bj0i=~#}r)}x<8INx-M zZNsd%h?8RmxWI)>Aq)POJa?`(fMS>Q4?S?6M-R>hC&c@%C)j-~PVdu-D9_*y%kQ_? z5-p-9uoZ=B4G?DWyhtbKocwv=HvT*n4FX4@tQ@C(eD54SBIkWvpKD*+{V(@tc^}4h zJGIYeu0&B=O)t)Sdyf2$@5NCX@TclNKAtrg|MmR+9)4Yo@oePZv#(?5?{5CR9Qr@7 zJi$&8zD3p;&Izy`6pnMISYD7!Yc?q>o6j8_K7WHO8D z-rVE%!xCwK!yW6^-T8*3?9*_jq^o9ml1&QVE?Rp1cA^%RJfRh(0eD`Q3{A*uIt`j| zrflJ#k?w^DN3k2cDhcBBxjWwc(Oo+~@}?d*{uy$X^6XmpBjE?1Y33czQC=TO6`FI% z1eBr>z(3G=8VI%{al=HWf{7HvV21>^xOQVbi}a>EbLaS`j^QLW z$tgN|*@j-;E_?^k7iabe1?XTd3dRYw1-P)qRUeQ6J1J76R_+GkB1~$YG;!p@$Y?mz zDRlRS&>aEJ0nx+OZLAAt+9l2B)2Q!()IyHAzvn|~74&DQbL03aIzxXprU%>oa#+zZ zgr(js7=jO5|Jx^%TUv6dwkk&0T)#ZU&H^uUY(>g4aFz{K$aVfaL|A&1e*9Qfenh{& z?$gC--3N?#M$C-+o+F*)<*5tCLz!$OSm{MyZ|ttBGz2docu$&K=pq8m9IMO zi7jXkc0Fi#VEKH|=%29aFM(FO47$RZ+rpo5eJQ^VFP{Zk_zSKtoQF^sMIa1RbJEUaeGYFSKUeY#rIsdIqjZQgS2n-(BnhSOhmy-BU!@Zhns7?SOxT!*4;hAi-}D zs2@q_Vvn&0$ZH18k(Ms-*|iONA>?H!Wj)N<~)uCrvOc z?SsA#qr8p1Be9}2=!>-95^|r@4ICFx53p=zEY)evuUsl#DSE=}0pnAOp{d2@K7?)l zXik8=_E|`8CQi=0IqG2_R0(Q2H!Ie}OvODeMSS8fEB+S#rN(FcGFpytRrJnoL=opce3!^Ek)l1?(;%;NWtS<8qSY@&e?@5}a^J@LL3eM{!=l zgF*;2c=L19{JD!eyRiFh$B0uns@6->J&wBlLlhZqajnuSj{bVc2&6<)QWtz#d)^TD_5NNxJ3Z=HMoyVu3X zw-vq?pB-vto|;^uW4fnmFjtkXpAoVPt?7lX?t|O2YqFWQ>b^jr@L+R8-m~ZazXnZc$ zv34T0d3193L_!rz=>LM+v+;E-3a{npdFPDA^UYnGhgRs zI`=MZ+?Did$1byAevoy2A>v=(0iNO7n1nYqXB&RNAfeFagS=3MO?;esA{ii%D_XLUM>jF!rv4GZ(d8ZS6o*-t|KJ*8tk$wN@J+GlKn=5 zF0v1YOtX9zC4kvm=C9hH%k95vezpC3_1NJp-Q8ObkBuMR+}*wT@P?67`ZK#mCo&qO zS4atVR&`Ccv`lwZb%Ye?U2e5{SQyxI^_r!t_6`i}y=rOA)q4iI(;Ls7nmT7wSJ$R< zrl!u_n0{^F&U|*~K$E9R#nGyUm7Gj`zc7i1g}oA!PfD) z!UyVdG(4J9XE5X#ijxPxarxr!WVAG9E}%{*P4(}Jp~~}#j>bB{SI0cEBr*|s3PE3> zTQjnu+N#j7rS^=TJ~DFp=-9#0(Su_dl+oId>7#mQ?2xYf$fGyKs~aRmY>IfXrc@7( z{$+J_{)oCo(XS2q5yspqKRtBX#Kghj;e!(srww&OOJ7hYcvhGJNj@Mf=O;6Ke<__B7%7FWVz2Pd=$3&SmO_ACP^_ ztY3LNlKbJpll%%{AX$Yc_U-d^_p zw#h`>WHLFK!~qDsL#?etgUJ?t5}+f`VYj@6+i9zp*SM}ljcu}vIL9oe#$HRV8&rPt zy_0M`@l9lTp$ta10uP?q&ZE!cxKXapTCpGlSMfTtHlSbR? z`X)OS{D*u1+!y7jyRi0Ymda}M$9y>a5C8mZFWGG`(+}Z8JhYxA6OL8mBqNJ*V$doo z_OTBLA4EhJz7km5uoN(&^9g&NTQ5vVtA*+k`gim z_t5JQJnvqc?>lRMo8aEloejeTQM4*G6k{72=9gMyX~^hrD4^Y5*O#Gr**Jk8oIG@| zh86NLmT~l<5{`BfdY&bl_Sw>3sDS`H6}m`AVF|(%LX_4!N@%0mz$ple$Z(>Xbc8o* zoIW0b@fSzkrcflzrBYEzg_Z=zTOw&IO~7K3jc>ek)v8N3E?qS1R?NaqnKka{8a>z| zshTFG&%}WTtZ8RwdPgHu^`&dpZ@6Y@`jT}Xzw{-jNbz{zxQcb8ObxR+>7SUuS{h?< zq{D+!+;ozJ8{T^EV;-maHz&!(BavTZzFCIF%?~>(V{gS_Xw1f)<6m;WA-`_~wXX8} zP}(p*lAP&G&9t@6q&jDkujKjRXe&+wL*jxrAl%858s<1ge>YCdXnf+d;o;LJdKWu8 z7kj(uCo@Zjr&XR4Rytbk*!?JrZy^-Q>zlMKe@naz71bo+Ht2+O=GGycpV5o6Sf(%| z_BtDYMM<*`q6otr3>KNSt?Y5d(2+c(OBMxKgngJ6q<|yls1Wn#|IuT@FQ#RCd6RHq z6+egl)bOzz>x4J{BS(kR`i6GHeuw;;uxkPu?n(Q9+}>tz5{ICQGl^A6W5q&cqju-* zfkYNim-752l&t-@APKc3DN4_$P1y&*06i4RuRXU3>7jVzg@19 zSF=RfYgNtf9YuzvS2x1&6ejDj0#i6~;4@+j-o7||VkhzVK?d?zl-)7Pb7BABEX$#?ik$9K3v^0Ev5(TO=bpevHN;CLB7uWQYIU6sU57P1^P^_7nq zsu=x;rb)tiO&75*vPU=?;gp=ImiZokhx zq219j-+}+r^QqK)XMJ~VZFfEY$sW-L-GP8OgfnX_Y$T-fn*s2PgKFU&T3!tJ-Gdt4 z(r`x`b^HDJN+7+E?po;VTl16k=UI4f76Y;)IVAR%SpJ&5!) zfb+oPfk?zxT`^dWV^qKI;!4g~aZ)M?!D7NDX}=|Qw6X_>HH#XIin-hA5i2Z{vAo_V9pYz$0uNL!6_7lu1>Y{TM zEHjakW>~>#OU$N+e6?(j{Je!Pm;WA{ro%>dUOJoEpD;xQ8$X-Yb}U`Kdj9goj-@6& zBCBpAGB*7z_#jMU{CE?kh2by5U%0k^@3kA&Ub8P7t1r?rP6<5a#)Y~nN!0Xe*;mI; z(x5u)IBp7ahq1sX@bbf7!;JPUpN3PV(}2#|Gs@!7GdwQMIp0;m3a>?89c6CWET*HV zb+EsC<|~{3cN*!x@BJnX^+#;?-#h}A-2tWrPHOoJulYw#gXMJhgm4MG;a zx(c^)@pcZ0x*w*tZECJdn6l}yu%jiKjWkS7jn`FY5}H*d8>VSCXS3a%W*x$~zJXI$ z4V>Db8DT@x-PKDyy|W2Gqb_)qh%vqUw7YQ(0-Mzh z1@2m<@D)`_SYGJ!ECv6v?)4S^Lsc{!>3bs)#IY-?Ly2rN&V~>oMq<@K{dYpDDZi|$ zh^d>>%ZhSyK(&-33a-7{BZ^GY(mqckh8c(4gnmN|#Tf)?EBKQpt!%0kSq!-at|R6_ zg(3?tn7-MI=k2p-f>|Uz?#_FWhz$A1{z#9!@@K5l_bgDgorS^yzE0mWv@4t4HAGj` z4;4Rt3|xlkB)?)52!%Us(!zOcO)@K~q$`vvqA9L)wNbm1VfJ9{B(0L!nnG_7h5t`} z>MYyD*FInTg22u^siIU;qlkM^56Rz7=f=UG=k(E83kU*pb%D+~D_N zk*P)}0xFP)9TYLzM3hN}NAT}=-4T8c?OeKs$YISNUag;Jk(GB3J;PFjezyH@_U=DX ztqZ0OxBB{!t`8Xidmq-pK`yhv0E<1fEjs7QA(VKLQp#uMfgP?i4A@7M+S&jehj%#< z!_D#G#M0O;gmA`VllSFt{9r8K(i|Uaqcik0Me!HzD&J>D%c?w`j)$K5#8w=Qw@?)G z&7F%qskw})iK*FMI!@06hog`Ews@a&wW18jy7rZ*>i-v>zwp1z=h>S7MgA^O9Z>OK zk^R6ep_8vJ;z=R$-D8&dK5P3APO0EaD^L9Cqbb@`EnHBwmHs-T;n-*Dg=hcKQ-Exa z(8nJXS-UL5 zXPrR~=3VR}#Dt3cjrZ-0NGui!$6`$9zrv9ip4FGHKzz9ATzusWMP8isQA4i<(CB`IQ$Yf!|$S>|850>*cKIFJ>c73 zY|8NeGGMU}q41qm*ly9j{0!@152B8uSsH`W<_3L92h<2qMh$V{b}8!{;!&kq-2jvB!KcBF{Y?17J_H*f_(y%xe_wDP~oe$5_*jyVH;+%~6>`C=;(AX?kk#4! zSA2k7Q@d(ryvho>ade6|oNB0BH9J-Xmo`EInlIc|%Wr#w{B|hS$Zt0Y{B9RJ6sQUW zLps6>p;UdaDu{~7me;CDRec;ckcAKS7ig=)jW)oIj(*PTba1Zgse0Mp?LC_gWd^$a zPUk}Hv2cH1kB>SBbIjL?4AY3uA4IUj7fRM5H#daTNw3ik)0y_`+=hJE_mfn^IzY@4 zP9c(KM2$d{+Zxioxah`)* z-)i_h;+=BP@&;rg6x3Mo{FC=Kc+GAO7#@_92&1oN;Yrj`(1W_hysYpC4Z=#qo|zYf zVN_%BVlL5TvJNYA$)j9br1*I;&d0--iK3Td5ap`b!#MQ-%(_v3d|=m1A~ADHcHk8J zo<0RdOnZ8_qWWScvt178hQ=P$u%fj>Ck{$py*HQNKiA$iw|_9VZ*^Nfzk6t8PY%1k zhxX)1x};s*;yC*}G;8d5!wM(F5kI7SO&IhgKN1oyDAbm-y`h8_ju(W!i=F%tY7Y0T zY3rL$d^OVF*w7b?_f=PSwHWs|Ot;4R!(UCz_qDC*>6}k>P1k={Z|SP3>W|0zyHney zR&7mnw%v!LWygDa#~VU*#siJ515MHU+B#EPS50k8B^n+u>O%Hins4{=7qBn$XGB-P zB%kWaR0`^x<4_=NY)vp0LMC}YPiK_%*2dXTQ^*gaSC4g8d)8T-7Ce?|1wDf)_KOYM zJeCi2znEClRafX(zYX6)MwM_gydbdYo!xbCVmQWxy%2$sN@ttn)3ERL^~qg0xOq%q zn`SQ9)D`O+tWj@)?PGjc4alCEZ4>9MSv+q%InyC&e(l2)<-66Y9YmSB&F2gEr#GCl zYT%6B>l?wNjDUqHm9~Cz%iQ7d@xycZ^Itb8L&{s^uQM9g?K&+tdCo?d?bu(9AO9?T z)8(VeLI;t3ODA8!!N3q*f}S8@S)jI1vn<@^_Q)PDPLYuPDvPVa3j1lY_g|K=q*f-bYyigy{&F zrX2Foamb`|c}ge>H;BLr$4pigWc*u&4;afTQ;tb&6MZ_09ZO9iR&T|k5TV{c;UP7w z79LY6?UHCJ39QWspCp>vPwIOPXydDt2b=hbptLMNT0~Q*66BZOR(}?JDQ4hwRaN}% zH(U3*y*Q|nvG02V$n4zf&U<{C4_;wiD||%Q2!X1(74g`+EUwkj`AY%eL7N}Ua4NR* zXQH4OP%oAtKYPhS(0?U?v8JiR6N$;K-2+S6KvYdlZp(rUd^2aQ>5j%HcJ$+nZun+1 zn|gXTiK{Q2&+eIRORr7|`GXtsy4$B=lbAle|Ln8V!>6xH=Lh!<4(u94QE>bLEUaHX z13PL-=B@Bx@r|yqV9Sz@a8oR5l*DF6>9B<|Iw(D!OE(UtYi$z}xh-1HbbIY!N-}+S z_$*;Bd4UQKq40Qh$3Pv6@k^Ya5-`@PRejCTj+pWT6x#P758^MvuMvZ!D0Byp2oPs3 z@+QuGDtFt#WPa6qwvJccxAXZl_LYvM)1!^C(aw(6_V!e3JNs7WSYwQU4YARVR06<6 zs_=#tJABwSpfs~NliA$cvpLhhkQ-W9%ni;L&ORx)`?&o;sCkSrxm#9@X%n4s_x~`i z|NSwub54SYV^@)ThpyyI8md(5}QM<5)^@+QX4f@1O-GD!WodQ&?vt1Yi{2+%n z1OAK)`=0>M2&f(+o=b3FJuJqjz#%^g_>eHi?i9NLKdMkX=TX=9c-L?#WcbFR448k*F8Al0H>o0H9_q4HnE12e*+>pJ1RXp`$f$rhP>iR)T``d6Ye?b zZZAFqb1W`=k87gnDVIQ`b5S-oX=L{7CX=7rChLlDMzhJz_NCQTO!2hQ6@Pccm{W8dL%rGBsF<>% zxjn1(h%o3|tEjSSP7AX#u;o@gYq`|y73$cq@F}}Z3Y_!l=bEE4la}y>=D}7`FlooV z)KOp80XHKGCy8Q9UZ`uz$8`8P;>lzjr&k%VJj6ZCX$MZ|c#d;_n$uV1b9dBs*VR!_ zmVQ<>H&;cQn}v>=bZu?A#{QXVidM&(s-kEY)klOSb{c2}G9In+4px{@*k#~^tmKF^ z?^8u7(;R4RX++G7j1a#jxT7sq-qw~T%M5v#S6GUKo8kfN6%6PWxD?LGiunB@&EWGm z&UOl~BftEn=7D}pA2!IZt*iS(U7avqQ(H?J$!mpP*Pp-@TJVe$SOLja#>=?eCwh`3 zV0OE=HQE^W22f;xp|G)r5`=~y8ER1#iNTT}+-C-=;$DBPPcje(GGtiSlnU(EWtl0m zA9!sLvMh_eB7CiYXB@v`L2k!`SbXIwey3!4*2-Aas4p@tYeH6W&%j7;DB}QsEXP z=VO1Ao6e;%5SMV9bS@3rU0~mI{YE&Q^S}YxXznl$X`#Ct&Q>ix!M-^VPg#*FBRLFF z1+KY#Do$khBE3PH@Jg-;h8w=Cf@uE{Ckb-Ezn$Z%a<7w<@sz z<+I-ma~XOz&Yd~}>kkX$VxCb^thGk$%vN}9HZ&%@w*|x*X|HJrI%QN*#y^VsYfWtp z9?^q>Dnb>NLMzovrD|#oA>N-ni!XnPxY{;*T7abg30FIhn3@O7Y`sqcQ&W(43}J$n z`*9-L7|yK#ZP7?i%74E6s{H4DO}Ur>_S2GV1N-sm#C`~S*RqYvU!b+St#a)?QCoXO zRZR`H4dNNsi!8vpY0fVu0mB(IG3WIZKYBm?c(D{3!VEdm8Z-1T--+T#T3jFD*N!B` z^&|Y+k&C!~)OnsuIb1*HTyr^r>!Z*@7}|d$dpj&LM{=V-j%9Q@>{*K$*q!1P-WV_u z-nP6v)2j#jA>NDAawOqaUYE_04!C}te<6kY|BU-{!mX%Q>-vUk!q%BMzsFNgIQ`(9 z8rM(qYlp+)`YGo==YzO@n)kB>l=3d;OB_MTyp(Ym7DU@Hi; zOrN*54hNeOpMximLfkoOBx&0bl~$|VJ8 zQBysh9g?M@GOv2TqYFRMW$ZPWam#)a{;OWp#S>gJ!spllv_TnXTw*zjSV@U0sb&sj zvscceKpGq;?itztcAq>*<~=39Lk-D8%AyB)4$6=16n-`1v01`Kq|hlFI8TtJNwnS}{Dd`& z8@LWtq7lLb#bQhHEgF5#cE$22DjJuNn56q;-nj1DDHLX9NrevO*{CXtN^MK3v5IE5 zNBAXM5Ko~~?ttqGc4L1CANg9}YRj!b!;#I7*jSAOF{ZiA)xs|adXQzQ*EJwx%<}di zv4QlQqppJZ(f><5=V(p3rmnNLwzCd@w3D6_t9JApQDmo!m(t29>N&Pb#?>>f=h)&m zA}yGxd)C`noq_As4_7bz^`aPUid6OWz!wWG2Up=(yuLmHe=D56F@Jqs(AIJKh3DAW zV)IHJXG4Aca(%tTfu|mTU_d``B4To?>8ctmrj=TRm zP2@soB0nMCLmbl{BzeHeej`of&7q(k4DlbF{+2I;Ch~JU4?E_6q={T#Zm9eh`rNrZ z?|S$01ANDD$u5Ex!KWDtUtHqCG81`sBpwR-RLNuNl$tH8hE-P;jU5Wbk(jP(9)bDb zL1F*jgt!DnOM%LrI21NqQa3vfvC8@OIE{GZ7PJPi(SI{@MhzQDA-70p_E~gTe1*|fx)#3covwlk_50*!^I0MH94e2WFB%z4f;&ph+YGtZPWGiQ#F zLWpR179sjp*VI?k*Pa08IQFqDBGrz(8B;0qJJg0tM|LYn)5hC)a5W%6->gUe`J{sZi zxCT#~eaY0{2Yr+&#LDZ1cy!G4#`-BqEtcL0$Gs?-4n**npq;qyf%~lKb6OTJ7>J^P1+j z?3okxtPouxv$Oxa=Eix`t=C@x`f$+Owo2a>k6LcPt&l#Sh{9E99Ym9`i5o>Q-39!t zM1}D0eOB-u;j3uv9n|?O8lmMfl^!>qLsNuWG;MkdGgCUfw5T!6nUI>i=D{sdyDp0A z@vG3Z?+O1&my6z_>t{PBUW0TF2X(fr#;sK-!s2I9so)TVa=Vr}4b-o4qVURmokaK7 z3*qY{+~fVY!9xbuh@B$hl+yEIxmR{|3wbkz%iq*?T--u~luAr6;>7Y*0xJaZh9*&> zpin<+NublzCkhszzEejKBD_P`|0)g++5}slukEX>JjQumr?Tgma2! z_$}fx_$$SB_|MBEA!V{Ggc5G;PFfwu~m zFl3fCks*2*_+VH^iUEhT7lgJO_9F80Shx{94331ZMFV_FdlBwQ4mWU=ZUyvDa0_(eW{v;vHRRW;uGK|IV-e)jEu|T$ zEv__zMLeoIvmtvvN{Vcxqaf>R zvlr3^S#>k4O1JH{`Y@Q|Q{FPp!#x9SNHJQEMd%G~7WawA#f##7@rC$NoRVSa74l?v z*;kH`7s*+2kz6TP%WqU4HAsz7e^>uhr?g($0Bw}kpfzjDwQIHQ+8f$O+E>~U?WDzO ziM6;a`Iae`d6uP?t1Wj}Hd>yr?6&N+d~G=vB!a?&5`(gWJV8Bz`UQ;$Y6!YG==GqF ztQPAC>qXXC)?XZRxfywsPBW+s(Fhw#~LDZ7cJN)n_Xj@~{8RAnA{#5v`@VCPEg&&R>7_l~DQ^XSyyCe2Sd>xq|IVJMW zNMBT4)TF4{QH!HiMXiZi8?`CQ7abOz9Gw$g99-QV%lmXw5u3}do*Fe`w*Nv`MTwk~jrsbx2(|V;1NE?~fm^Lr%zO+_%sJq5J%ss(9-96v^ z7x#7U+ui%zhuy!YThjZdUz&bZ`c3KU(l@6+lm2S@$LZgvpUBWMA~RAmx@44R)MO0H zxG-Z*#?$gRvBoI5smN^Vo`lH4nD|C)PG?t{5c=Dw8sLGCxXzjm;6i0+WwA*VxehpRi> z(&63?TRME+F{`7eV~>vgI@Wc(spA(Nf9!a?lk61HDXCL-r-DvBI`!?eq|=q1{@UrD zP7me<=f&rx<>lw~%o~(9K5u5;g1i-ZH|DL&dpK`<-s^cE=6#v>Q{IWrTIa~lNuBTM zys7ikop*KV+@-WjWtR)OjOj9^OH-FiyWH62A6=g9@_v`Ex*W;xl0P>8#{3uZzw6qm z>t$UZ^Jt!-p2eQ`3S0%93Pu)OTCmL<>MiwN?%m=2uCS!Ax$x4$RfRVc-d1>T;ikfW z7H%tivG9$;4+{4ceph(3@b@BB6jl^plv17?u3d*{b4KEv4)?9XN*-d44m2D{7R<^6`wX*lhMR|VtW#u20w|2|vmfx+UTd!`l z-3E6X)oo(8ncWt4yS&?$Zl84frrXcm6T0{6KDGO@?$>m`wfjBY|K9y@k0m`0_3Ya7 znO+@x-P7x2@0{NGy=!}4++%T-E1fg{o+%c&@Uza%<)8s{E>3tJYUNRMlF2 zTlH@>-D|F|*;`v#duy$)?-hN2>esK|#D0J2x4GYo{Z91v^dH~<-u`b75CbX(Tt49W zf$o7L2F@S2ap2E`1`b*==#vXVFX(Z>ybB(@;Mm}@!5fAY44FA(;gHLRtR8aLko$)` zHe|<;*M=M$8a}kk&>=&w9s1PJuZKkrD<9T4?5<%C4f|%ed-%ZNi-xZmzG?Wo!#^E< zbVSC8AtNpsaovdfM*L&M<0GCO@#2WrN4!7c(1>FrPS@G$qUsXr(&}>Sde+UYyQA*W zx_9gTJ+jltu_LbKM{d3T)9{-m&+UFP4XW3H~FaC zE5DOJ%3oBn>Y@r&sT!-A@eHwDJ+IzSpKBH^T#M3TwPY!9Up1zNGT(-q>1awWJ@ zUFoiDSDve@tJKxgHNrLCHN$nW>r&ShXd!NP-R@fF`rRGoj&|GKPPfaQ;m&b;+=cFL z?rQfu_a*LY+<$X#bU)yJ(EYIcG53@1ZSLpNZNb$IQvIYKMAReXI%1 zik!qCCz)D~*2Tz4uq)gZ>q>FCU0JS9u6$RCtDCFRHO@8BHQTk=wZgU9bra`gz1xPI z#JUsRDQ>rslXA{Ui+crfa-aKtbgq*}6CrM^brXVMH5?57t z62mhk9$vdj)%qnt`meRSe)VOve&LfC2L=3mU-lqd&~ElZ;$V#*1CYeKLo$Z zIFLqx2PXST4wM{t;K0lSBMw-;d<*~02W$w9IDi=iA-?>X{ncNt{_>J9AN+E`{-5{1 zC&d0;a1X#evj4vQEA}@C@p+_;XA{KBpg$lDIW@PI0gI{DYGIJI+SM98)$>ogUR$lL z(bj7BYg_!dwyU;D+pImRZNr#mhqhDOrR~;U#^~m-b`&FalA2Zd5mQO+TspT_2UcXx20oHH^<~9AQ>ePj5wVHzG>JQaz>PEF#U7{wd z=TIx=VD#0f#;NgYw|YUns4h~sqK>8F`7s-{s#f&HIC=!e?fO`8Ax3r&hzG@H@tAmC zyn?aae({a?RvcAJ)l{`iy{=l+8S$%(k+CvKrehAEo2-zva*UjSQQr)V`xeW!a-FwzyPN_RpEM`YuQ*+f_TCiHH zUcs2LLba+7)a|NX3sJpQoVrd8Q2o_FHA%#wwFt$`L=0vql0~}ch5A&4=YWY~q!=T{ ziCoN9+=S=ntHcJeT0Jk;i?`8^ye{4p--%7~F+43F7p*c<2FY+4CGFB9Gh~kJB8SO- za-h6GI^{xnmAphQmAA{4YA5D2cFX7FPPt2dhL&faaNt>56TgWB879(XoXC_3B1%rD@w5C^{9Ar6ev#jaTjVw3 zUHP)e5&6=M+I_K{il>3U$QBVI&WO>Nr@2yIDqfS%i~g7)yjR{Ll4OKPkhkpl3oR@cAr<3l+;Uu1MV(ugR1Jq8JFsG$ zTO7V%$RM|PZSbIKx43`!kPF=6a!h)=#l*Vd1KsFp1u0w}@8tUVjk5FP$#dpOH~Z03X3v-=L#NDbnj*4Je#OH5Ka{v(zlCr_51vL=d%rkZQ47CW0}lxdH1Ew_?NDfThN=S%@Tz}|iUM?ZHLYRpnt)I5ybreMT8 z2JOHgJOlJWKS`|@Ms)~j5*PEB&Ml|P78T7k6ZMelq^yNM3%W&JWj_gHLM0Xw48Bv~ z&tQ0lnoTfcvY94Z{9@)^VRhH>zp8P%g{K%+nFUUG4q|>b*djqY;Hd2NHdXTKp-!RO zONmIt-1ON0RjNu@@oZBIHe--0$#s}?dPLZ`4o7nxCVQZkdj<5_33fttBe333n@+ZJ z3{?Iwf4$KVW?{axK6?c12el1Y%S78ivmum&0icQJ5~5U)8_@is{;hsh$BB;CN|`PL zVY&v0t1`JBMGpg8pr%&y< zVE3^6Ftm1!uo9*EsTo+MorZRAHl*)}`InxmFQ5*}t9mHdv&vNks=KNIl!G~qZmJqk zw(6?NRTZEtm9NTFC7?{q-ju2eKpCpDDp7p^rK>zuta?KiX=rUasUp=2(jQcM-t^Mk zF2>`&5$)hJctZI9*>}kya-52jTjW-xmkvoXAz?No&qaQtpY$xF_nyJy9R-iK^KyYS`Kau(gd~Ya5F;yMwx1ME_UZ6(UAm0p8@0 zhPFZkkyES1Ftt?V{h@n93=0|onm1r?fDLEDmMvnK%I?tl#O z9mVwn)m0Rj?l$lv*8%w*tzQW?U8)Xi z$nXDc_XW}ly#pueK)k95WSXE(S$y7TQ7-}ny0{S0>(+~>Mu8qi^^ z`weCozVUsG86CQR3y$btkTJePGPupDd@i?#jBy#>JJ?%JTAzRU19_A@)16+dK;QJl- zJ>g0KzlV8O*PnH$11`)bM*mL^qm$bIs>>B_b?RJ)*;M`wSN_0hz*~}qE69N>VC_=Su7Fz$-PdEjZX(*Ok=SoHNp!(%qg@q=GCcq1sWOZr zOGJgr!dN8*>VEr%SU1s^9IbT&%iu-U*HE|#&#Nb4aR)?|06oc zYuBPho)!+*L3lCf_Gn#k?S*?MW{@#=q;fE>n~Fg@p6KYF99ACm-vLpE8C*A>11h8y zc^{AaqoOxCg}ENtis#@Dgh!4?zQ>AG?31Kt?F4e-4IK}?C6E)%w3_Ivz|3tiIi*Cg zM&m!@%D5-mhsjwY2QCit=#g*dQjp=;qbV$Oae zX0CjANC!FloLGHJ3@5ftt7CS>}B363^W6Eb?7YooQ=ZFj~2KoG5 zq-cp4?<@c>ihEF0iJwJZ%#P=)5X{csit9p=hn22j9G}LA8rqVjA`?8iQ{Rr6avG~j zRfwk%8kgPX`weZ0T}^?0sGt7acU+D2{i-{RGxJer5KjFo^`%(9@v2UkiRp>B{b6t4 z<9-a>0K-LLJQprfAV+t&KFR|+FTxbuy>R_8;%*X|S_AC23vBv6k)-w@pRXWJIQs0r zBM+kx=K?WQ%M_WGRgirY&!o_73axsR^THJyt_;^MaG0@XJXuZ;xB@sg9MKX?@d?f| zu3d4BgDZr46>b0=g_Cm|*AB*&XgN&Yi*)t^K7sYDaI90UM?GtX9*zV5G3p@d9m+JF z%0l)59y-QKh8N@1F0vE$u(hRu89&Yo$=?ai0~aVG$%Xk(-!}$6P(I2Z<(c^DabQQV zyEL*V@j0&K$Udq-LGu{+`POnC^qT-5brL($v5uvrCM{Usvq~FQQeKfEG8DVh!exYv z#0py!R>h)u{W1<~Z}DOaR+a3KFbC^bKFk|AWCB+6a%GbE0c(NDGDW6Jv`dn9?lsDE znISX99+@Sxv1*trJIIb$?dpWpme*xxtRm*iu2@klkY3Rd+BhK#WsxkFC0L!wlV!YG z+8r%f53F$Y#2Vn6vNu**`iPUVLcA?2WtFU!HL?~u?koF2^Zi9vIRLAYgRm|+7*DA~ zu}V2y96(zz0_9aFN6JxhG@cH}%5ic$R$wp0sv&lmW98-|ISK1@_1K*~Sx%9SSf!gL zr^)Fk*Z1X2%;3zHbL3pvBF)ERl%avHWT7^A-SI8@|R(iF(MqZ0Gqf&Xjya9XuZj@`}U$GumhLxk6 z(ZYNHE1HhgzYnpZdWXDI-X-tG8u2~6O1vI>IX1}q^*#3`L zseD%c15dmU8wr%D1p4*AJ_H z@5pztCfY3D=hf>Ekths(7KgDY2zpx7Yx!fneko)DA=$ZSYzWpx0l3&Yju#4k6 ztn7X-f1ufP%&UDQT4+ukvtx(FB7I&R>xcm}>sWE*xpj>1FuRT?!L#Pq#aCje3PNjU z&az`aeYlEHk(l*fjJfjR;t~~ud5}vnCmfHN8iz_yiDIcrQcjgDmZ%iGh2Y{@l(S|v z#NW`XEW_MN9(w$LV*URxW`0IuE+!vyG#<>|c+s+s!u&$9_y+y;Y0S}-VeY0Io`>VzDlwxoMl4s=7}Ko4xcxHB1pNgwME$X1KM;FAFHnQk5H%F5gu}5; zSf@s!9ULphVYP4!b|;JzP5p?RQv${RK<0M&s$?svEb+7sWZzg1l z5OFo;{jL+&itEKn^`W>(d@n9nABkP+W4wj&DQ28kVea`k%yfRP_KDxr7ivFdjt=n3 z`ZwxZ%pZL(uE6Z_ZCF|V5wo60Fpk-Z9_L1pjyC&NaSL_`KY-oD8!_5Dgq60nn7=-Z z*~UA?-^Cr6=?um?)H7J8(&sXd@oeUA`g|t#gq&7qumi-06@H1;eGTjTL0H?jX~9|u zR`}bk)ri&NGxQHPV6V!@v~DB5)Z)dz&~tnuJ{9}K{y$p9!5)GPEfc#4vaxp{7rVqd zYMrz^tuyvm54?ZhdlsWcQ& z=~qCBt;WcxE}y}&pvYFEXIz)NvdY?*B?;@>mRUWAUT_&IbTSo)H;X@&pIeTv4yNyP*qw6AuGDvW)wrBLPL@we;HL+2kWc` z2e2yA6ny#x5qZ2`qf86^=3tmhRZY;4=}pas1y&o`sPS_%sHzQx*LWg^OkV&~Z(cBGcKrfY z2Gm|-8xm+I#YXI6PRoOu7B*!5?E3lB18PQ*!MR8`Zm+k>I$T%Sa8qHPf?^{V1%}kc zMlK5cDb!d;1TZZzGG9^>HsY*8_7)h5Dlu4<7%WN*e7P=2L0PS(4(4gC3lPIkTdHTs zTVSZE#K=TRjdf&T85L3)dAz76TyJXp*OH)-ZMv>860S7_s`2aIU|LfXG4fnp7nImW z2I{)B!ZuPj^`Mc|2w6w6!RrZ^mRU!$dcsDxsUu|clo^f9jq_*Bw~n6HT)(g}Y;0Sg z9jSSHcYwMJV2Dd6b+g?v` zXrq~~p&=uumHwQT+8P6ky})2uP;6^#*A(k5h_|@hI*la?o7R>)V(lsL7KTncD>ZL{ zWqMnaTp2dKeH=8&#nu^Sd3p-;#s~U0r1aK?%*dx5KG@l%%kOW&s+a7=}C6W>aBk zt&Ln17*ZD-x$xJX;#%wcfT~wwWWJ;{Z2noL?JY1ARbsFzF@!8Bx3o~}+!BziKde;G zfVaRA1!aq}C9m#;vdC zN}39}Dfa#po3FSOR@(+0e-dL}Sn))B+u+4ftE#041~5!N9)O8$ke6< z%?31Mp+Pr)#$ugrJ|3**>R{sxoW7tF&YfW}B-_J4oChtqa<#yf8#-Ls=y2uAg)3Jo zTzTk#D;p=SJov%2T$h2T* zC0A*Wr&4dfJ^Cob>nSy4E;VE>HDoR|WG*#iE-ep%b~&Bt;jC31o*y<9k{NI~i)7rW zs^Pi_9)lGgR9KDr1C7U{KVssElSRX|GHzaD^Ngk`^sI=%+LV0SnH$!yVD{|B7KTH) ziDodep?>nLwp+(pF{xk1-t6S_qnQH<10kwIr_PwR0I6Z9uFI#lji_Osu<4hef1In! z(Kwe#40w(SN6xEnM*rM6RTnXeZ=2bMNc_kK^cjt9!F<~m98LGL8e2?)7z5Ep5<6|d z3}|3ZQyWp7i8_l6+l!}x){uqC7}Z8*o!>aQY3>xxX+c3@NaOq#3{YAc{g@J4y`B+W z7nQ{klbdEY&7Fh7Z>ev-#4@F6?leoyg61Y8+^7N-)t1>an(GauQP7nnVC5Xup3%t5*dOiA(+*4W1qo+bo2|wae zdFrqy0AC&e7aB0yKD7TjJ;8o@g8lRabG^ou>j18$A>5))Zkp2&!kq^}Bpbpi4SrSm z*i>%d^tx7PJdQ#(178us&1XRDqKN5DO|$A7niisXOrH9{qfj4Ocnb9gKwK-s(Wx~w z&Td-NM(pK^>?zchgsa{o7J3cgy{v8E^+&!!eU#-XEaZys@%jg?Ra|(uujGarnP-zX zZc6zk(o}cLwRz@Si1jLX)m+q}o?e}*yIU9bLF1iY?(uReZ;nrWem z_uqwLMW;^idnO`Mf6oN-u=rtZRbv_@v{{YKb4AXa`sP`}HD}hGS=fn5yEygtAZSfW z^12k36ofT*on^5)i9K08Fdu5g?p-?Jg(y<+r@fijJDKxo4tDVhk+YW_V)H3Ierno7 z{082@lClKU*;r?C$wV28)hjEKIEne>!NXz<*MG z4F4JI^OE9W_LpNm8k`wFQ#}LtZAH7JKUaIBB= z-2%57?rOL}aJ6uK;IKlQT?B^}%WSMUW@o^qz+uHU8}ET+hr+>*vRYBj=R14JU)Gd^ zhw!I8{^6MQKYK@Z5!OUIU{!!@XOC|_<Z~8_7 ze$q!fx|cKMvexeb@A1)I^_jklkdnw63Wt^0tZKudQek4}sV5|kJ0D#og13v#_2`LSVjO8AL8k!O!10z7HU@JX}IHXN8t{_eGNyr zeQ+Pcy$6Rpn)%xX70*6v92lJrVvG6B=$pgG`8UwM^H? z#KFRixJ4!eYd3JPc>~HYA;RfgQcN7`gFzQ=t6 zmbbKT{kXLKCiJNgX?vkyk@l7e?E$olaoYhs#n7WBwAq9xbfX!nL+i}YJ51;%K-a@v zNwoA!yE4thrLFLXGH%IPp+whW;^q>>ESO6hlr|k94QUhLk20a5CN#i=2v^N?y-Zx0 z2@%fAp`A@!jtRL<$Z10H=YdETolB${8f-$!54ld8&~XzwYC;E1=xY<&Cxq)`xc6Ld zz<-(Y@7ifX+f3*Q6C%1TOt;CzZ7`v=fNq0ZnM*`j8)&YK9V&dOy)IwB8Tt zaT#~lSzIW_Eljr>{?*KzpvxIr3TPoi^Gs-_2~p@2lWrnIW7>rdXWSs*YE8O640SW< zic<4aJEUf$rldMdDB6TVO~~ShQd<2`DsU+$C~nFxeq72S6Z+PK_M6bBCbail2LXt@mNH4{QhX5iW&im`)ZY&An4Gogn} z=zbGg59ltAaf=C|y)tlDn-I})8|GXJXrUABmvg2GO);T~CPcU~OgG%b4Kkrx6Y66^ z-At&+gb1f|$v1JRVTJ@5CX`}A4ih3t^|;X{F4Tl9ekiHcgiZ*N^b5(HbjZYgYeM@? z=u=SaO?nId9uwMy5=5N=4bn~8PEgWQe#qI!gbB& zY7gCU9^6eP?s|gYHgfvwlCA{2B54Wy789ClLeou%a1Bg1!NiR+A;Jyi&;cf{+Jt(U zP?-sNO{lX8kt{lw924g@A*Tt&n^2?)1)GraLy4zN2>MJsN;ytE2>l;m=xY<&XF@0+ zBlJBJdc%ZXHldy1v<>cw#P-k@#%*dBx`Ah;K z&|?H8?V=Gf;~p}h`%!LpF>bvdM|25{V+d^^GrLO=zzPy=6jsOlX%0Z8xE(Oz2S) z+H67_A=Nr)cp~XuZ!sNrV1)BAm&XZ|$u9&sZi2g>p({;jg$YsU5)MVXX3!CCF5{-R z!?C?MCIE*P4gOFQ8el?b&5Y1qCPXpHIEJ?!t~29u+Tq+LPKTU06EqSO!Hz$Ilt0vd z+Jw-KIfCs+1LN8cnxSaX9KlIf+V>@`utQr(EhaSAgr=L&1QRMVA+HG$m!Zrh$Hck) zP@=H!OE^iP2^K#@I7cht94GuZ$1f&y$Pd}y^K(gZnoztSvcF+MFZ-dy(|!nNsv3E- zZ^JPZPmoUSTl`~c`z90GU_xt6=r$8V%V)oq;!^KtU&UOO`=KP1s*X!SsTvSU)PN|) zVvdXQHR3k=p(ON7I*$4tBXl;Pshq|n6B=hibtXh~gPE=$BwJyx#C;DFDls9n&qin` zKtq`>%fz`%DA9ysO(@)itR_S_oeL7zIme$gp<^a=*o40KLw1ssWTSI-Z#t;3l-;%yj1^L(j(e9vX5& zH~2}s333#^qLY1OCp8v+S3V8p3{JC=;*5Hjd@TZaO})dIH`u=sek*YhXCzh;WTg5O zev!6|V9W$d8KlUMR8O#v8B=Ldr$PTM&He+w4e$xV;PjM(L50uB4W~6!__+^T|lduZA?WMerc;fvU%m&MNPBES- z`)juXlSykQGEnZ> z`q`$wBbd3p%PTs^Io1M>^)BbjNu{g?5=ISVOtE$?_!nzy;E$u#DOpVGMmUq>d4{PJ zBDCuXqhYQbp^vjq)>5p#gx?wOFG!g|`iE_NOc;_!4(C$n#P$%uc2%q)cSvg{d>7tc zz&e|Hk1%8v@G%cBi#cvFTU2+v`#|`Av40Qzaq0zvNvl}tqq3;Ro2^8n;G@-opR4DK zrOGw9Q7Pw;W@Ijv4(LhF;Y>N6<$QxF-(U`J5MHcc4X+@)SixFd!6o|`ui>r0Nt3`6 zz4!@l=19DI^EG&OW)7X1a{{NBz}&9q^8E*C6(>a!|2sME6>QbbB(0dwm}d1T;ASq_ z>AV6rfJ^fdmgEj?0f#;Xe*%~ICCs^*X`0pDz~8~;j{bxwIjudUE1XKt7`FKg=C)X) z(#+shtHo*r?hJT z_t)kzp15UFzGM>T>lE|JWd517?kFQDM>31rC{X^!KD8~GTsoO-GaXrmOsXlMp>oV* zN%~W+RWMrxE%5-)@|06K%5vsV&ZWOkVLeri<fZ8H$9P`}3 z_(!-s?8eDmH9{9~DO58}wb~9$ z7Og$Qp9J5jJqZi>oiQDJO^m;U{afLWSMH8{WWqZ_t(??#&bnZ!%N6fgTqA5xm(2m{TvNRbI3|WG!X1z6+Sz ziUhW_V!Yc449Ci5nru!hmnpM3EgMs2TLywMo6{X-=>m8ZON&))>vVdSEt26#g7J>p-@u37+=b7f-!c3h!^u8OyxN;^tUSz&~uk8EtYI zeVmSGubQa#M2u#Dwdu3n_LEL9Vy)x=ur!J$2LJnO27Q@@yX z)x@RK#QfJY=O(6aV*0z8{%*$H%@`;1bTU4bIXJmJe}v=4vsCd!iTw~{;Z;mi!5juM zW;5sLUrbNuQ%bp+>8~Q0#lI;>*#7~%xJrXQ;lqZ-GOk$@nC2=d3 zY7Jo2Q~0n|v6WI0eTXMcJwYpt_u5IeW1PxWdMYf{bk5OqmTfxiQNWwNWUIHcgtzN7 zjKRnf`00$fj3ktou|EIGIlYWIT*msmjLYjrroW8ST`8#Nbuz}u97?#PvKbCzTbjnU zRKlD~*p@o8{e&@P38z)UmQ!NM05|$>7v!|q;pb8=RHXJC;1ZT3m}^rB%TvPgOk>UO zV9Uv6NlG~N?p(6nSr6UWDvDW?t2o!)nX;HE=dlb63|&zVvVi&D&zxDSasgBJN8tJo& zC8=T=s<_=KvrsFP$Z!?ssKt`cl&}ifLXxOz)<6|YSOs|$pRPzFX8LAWB6fi+#3_P{ z#d1I^a3c4mIOS}+SjOKEdz!u)`Hyy9w@kIEMVWHJZN4F~(BaX!u>5Hc7}2_a7F{Kawbq5U&Q z;SQod#r_z)!Adyn{Q;d6uW;Sl!0;0GXR`k~*@SqP{WV~TyM{5avOkk4_ptxC>;ODH-(mL_`%jV&iK&%Y&KPJB@JwGTd^8gX zb#dx%(r6fO@c#<`F2;Pw@Mny_mnd=i!7=zxGWA7;w2{A_bS<7cw}Hv6CPli2g@ zKga%0Ouw7`XW4%N_`qFPC;5waZoHGMus=yfPJ-+zG>i7kgufiN9H(fwkb{7q?~}G0 z-#fk^d_Vh+`i{5ZbjXJ%JKt%>hXOh-;tBS>4hNf~pYM6!*XPFLkYm1+Ow!K7c~a)j zcffbNEp8iR5)gnK=s({noIz#&eDC`XwZ$em{XdqumG5AGEbnpOcfJn*8&vo%!$#jh zKYiO3DSYkw&3}(O)<>IMZIDS5ps~Q5QF!~<0kQ_f@$+GNzjUPY@7g%%GzK^1nL`XM zwwK7a-}e!;@_|1s-?u2&ZQzBnYy0`oI{1Es!Wvhqi=%lp}=x3Qc@@ zcJ2&{<8(ex+Ygj1xe&;XCO&rr-NZ-3(3|ov!HCaR#b*fx@Ym_k z2bn+A@FV^kq!eHSfv}&V{q_75?b=w>U&s=`wLORb)m_jZP)Gj({(nSM-8Fh4j6KX> z4~&p-g4H=^Cut}Fbe+_nKvRcMbGY2d*KIN|pN5XPy!{qyrf^>1e0Au&gg~Cn@tnBl z(G_a*LBE8M-sqdoO+lyeQ~JaGrHJxGT{pBw?bQK4Oj7yV3Ro;!GJo8*Yak9X{N5IF ze#m!>>cKg=^XuD4fou#^H!zR3azk(A|8Y$-tPuS^wIqLFlYYGa>gRCo6*=_tKnsUo z2c5>(O87tQf4|lB<&TSNo5aRgMGp%sV;%M#@y9Y!qPRw?gh2@#Iph5L+voF?1Lr@` z<^wG1+;sKS{=io_jY{HAvWMUrCZe&UJr@56^e}e3-;s)cG~PSN#wkAZ4cb_om{x#u zg$nVH$Ej}JK-ClfWSsEV2YcHqMHSlE8qrs{vD1GFwt!E=KTFKOKbud1&JhpbpDXCZ zo(_1Y<1w5d_B{T181?VL8EdcOpO2CFn@H_#{5_b}{|IS*g1=Y%3-5#!3i@6X&TJAt zptc{vzXzTrjzS9hGD9zkuQrJ>_-<2@7>8%DWPIf&9Ve4bpmWJ^!c_%MAzQ#FPUAdx zIRTD;0sSP@ZF(VI7e_Ped!6`!@;+n#0H$&^#Hzw^EgiC z`a4eH!U;q8*2I@$Cr-us25)K5_n%+IX-{ME6r)55Yu3V=wXkL_tXT_d)&ecLp!2@? zhp?u?SUVxm%Y(p>Ucy-~5v-RW)=LoUC5ZJB#Ci#0y#%pdf}oc#P-gq_kAil-LCJj! z9obk%Hr7!L>qtUJF(MdGr?GhMB26jQ5uJTsjx!RwK~wRpsbJQToplt(A}pvAMsz% zpp`Y4iW9{S;!$yo8iVrePv4sY)g$A*O2C;<(v4sY) zg$BVwYj9RnE&dT)29aC_QEaWzY^^ayd62cn8l|!sHXFxf6VGL1=d!VK*;u)3tXwu$ zE*mSCjg`yB%4Or=vPs~wN#wE#=CTRqvPm+^hDycBrINz-8^&crUkNG4S&~#XE-sr; zw&FA{Avc#$I+suemrz){5~5PcCB_Tq?O-Djm2~I&!JlxKui^U59Xa zB%>sjQXeYHwRiA;S-S;axLu`<)B4~WBGFnXPS1J|XLN1B8DdM+6zv_Hj@AdKt#!b6 zSx(?gxc%}&y!Z98+=iLwt$8b{KUim5Hr4!=#bU5Q|I68yPICD)k;Jh_D zZEX&puhya#;~P$Gr>D_LXgISBXOhv0WP8-Butx{_G4c-}=U@1aNvH3)+>4VqFF}u} zfH@^U#fU*uNxt1G+4rGxq5n|0`xIJ)mwkPGZRn=1tftiZyZP0Hpu&32U;5iAWo=(PTr;Wao2=%EJ-(gVr z5ORq~SIa~^R(`|ORcIA#$a5=|4$j&ORg)ogqwg4VY{B?mDhp&}ZRt4ZC6x7ckLZCE zQm}e83Or|m=M?a)1kb^0wdjRauyKez7SEg#-?qc^PC%@Fh&30nmLnFv4u&%TufqLm z(STSB(bADLlOTyM(a(_RE9Brc$Ttx=y$E`ltKqr$)k0{HjNE7L(yM35KGgkyz)o8%5(rA?8#aLZ-qW=>W zn$?<_k&|0g8dp-1;B_R#IqdO_(X`U^1Uc|aYhskcA+=Upa&(l_ddiX-8fSCg zIYxCm^L2D=Qk*SBO^rdL8GYuy&`?KmT$D;`T`*}9EP~V07FlypvO?IjNX$Kkn)qu? zd@M@lIzQf0Y~XV>#vAeWaQHlRvF4ALi?>2)9?hoHneofci60^E!kdYPJeK+Aggfx< z!X;*SpL4?F#Z$E`({SQ5Mz{WQn`y+e zX7+RAjBe5rAMuUsP?iu86@u@&M>$-c)>&z=?pF(ovI;XDHg}lnqLHCH;=|B} z>4v^0*cKXV3G0N-h~c3&dt8*;E@ARCj@NB|3|ggRj6u7hj%DOPWR`}-$@P{L7v*GT zkeCVoL;b5t^`@nHQ+3~-oEm3ONlE>Wb#hgzC&lGSP4&1^JgGgC;t~>*9C1lk{i&L2 ziGt=6&6?`B;ET1(&5|O^p}F`V-)U_m+N&ZV78TlJ5~R_LNaQn})t;GNYR}b6ATtx7 zAB*xUPDtNzIySC#U6dm_RfWmFhbBhI-uBc~d+S%BAx8)}8X6)~7_-%pn$Y^{akm^4 zdgerYqCF-?jgJUPvD=*?U&YWR;p8&*w)DlaVQ66|Lt-b! zFa;T;*RHVjchQ)-~lX~=W_ggWgytw}I3q0f1En)d_QI?RX z*zB5#<-O~x(xan8f}-qsVUh9So(Wfux?tr+#fi`uOTijLkHD=Hb{v^_YVCAy|n%>ee3U?sF%Z; zjkWV@3di^D7;@(4P?8x|5!6{*YRQ3B2#f`f;@dx@gBWcT=T(CskO8t$xK*8ew?vPn zHgG>cSn3BZW$IzRvH)ru_Pkuln)w4RzIlPv=*`|`>S4Z%+u_}`UrJBavRZ97WX00~ z&gS*wZ&aW9^8h^OL4A+@maL2{KN@<>!nnd;3)?E>S#=XtV3i!lHSaytLBWvCCi57$ zAL>=xsn*5p4^45P4t^J`S3a_GLo?BA16^4&k$CG&8t z-%yV_3^o>R(vvM+!Tj3CBU{qrMT-?|OT=%nw%fqx;!6s^vkk5hqnYnK@b$-|9v35E zga^itw#akhN5~{`lV4uT>T|*!;sJT98J>7fcsx#{rZMsWDho4T)Z;e#%Mf_#arOL! ziMauIsv9~!9N%c*GKcM;OieuJ!=JuJJ+V$7ffI|{^iMspj)%P56YKh?o><2xidg~a zQcp~H^u!anR7iSDvVqMZEa?_yyv3ik#dTIFNw9^i5WP5AVV{6L+~4N@C#yvBcXoe% zC;IZjZca<Wcn6&6Am6%hy|i6nkt+%$Km?7#D2V z>99M3tO@QoyFDyS@6U~zg;Js3PuC8WqQ6FkATMag<{QmXKo-nSFDBl4WnwBM9PUU> zb+mqFv!bg?b({!x`DKVp3H>5G#U7Uu+UNxv-LUu%Wa=b0dn$jn$UrSY0OTWy)$-&Vp zNr;E-snMZb=7g3`zI@Q2%O{sQ?6!n3dzwXyjH+4Kzu%&on8@TEktq%b-h18`?Xaa} zpoCdEw%)#6YhrQ!H`QVtPqkRb$B0*qo&vey+NR^9F;hdMiacL$%B4x4f^Q>`zI8ri z?K*w9ObEb}HR^af=7I3NR&G6L4^srjTJ+QeCB*Op4fPOIA}9f)zmVy+^sD02WSTu8 z)g}Lxn39@kccrxs#tHqc=(STFXEu{ss2K}{TR)tHF&)O8I2S`trz3q!VuY@BqtLV4 zrF3?>_Vk9>q@-9iGcGYP?##jXG`Bq=1tKIs1l+VEB9)F_*th?Oti7Bpx__Vt2lT$;} zqazYSC$i?}lz5^d>?u)U&gAs+4EZ=ATQBH2wWpCsnZdow z2;{-4MRr5mMyqu)m#vbpcpCI=BdeqpX&J}8v`!uKCfYEX<(ILnC!IRl_b%zlcQ^2f zCKs!g@Dx&{H5r-8?Xu1zY^NWaVJSoz5H?2xmfOK@;uUCo2yoA9WW{=%aD3DTSnP3n zp36+6wbq2SX%5UX;JJy`bFhn*T5Fv;aXazAnv(3Q zQSH#N_D939N#>}p6tm&mY1}fJtd*Xba@z{U|CnSxB~9v5mFg)?jwnb=OmKxp<(4Nz zMnuO(MA=h4{zoB?Q_bW;x-&E`D7*uP0g+Ms>_bv~04ch0Td7MCzZnQo0GpxRL8&ao zf3T5XyEnK(+|iK}E?Ge6+OIXK8W5?nK zYArBV)r@`VA(%r>r}i~hE9LnP4Hg`4!+!b_X|(24p{-U09sGVlYj{?4yfdnGm{rb= zZM_i9M`A(>KG+f`D+aed86B6HqISAtVxwB8EtCy$XDR|45lAx(Z5>iY=}coOQ?SZH znxUQ-!&As28Yz9N`2<3V=gPf2;Cj@7R$v8@xs;I{2HvWEYt*s51F$wN1$%K#-fd~Bdg&EI znajL(^iF}DZjA4tzERI(Y)Yx-%CRIPW<3um?CRt2iv!|WH8+fh=46Gcfo`IC%u3c< znyo+0+k&jtgurJ>!=i^f?8!1RECgC={lyZx&MLD_{n;JKGQ$<=3||zK7LgpjNU1%c zsg5>v`b*<$%!VRm^dbpyumx(@{QU<#r{`L8U@(46QOOnIPFri9)S{E((^3)=Q{A80 z9N}RJw!MkT5GGAM7arESOv%d<(1<_CE!-(v>pw#xu=zhk4(M>^2g0e*c9*V)c?#*H z6k13>no}0ws$0o*&;&mL`Q^!#0b)SR1ZjgB)WrCtR7YrnwY4$98E;Q=*~5~o@~=_Y z#F`v`=6*+Nuua(`&YX!$PL5OK6H-D#&K!@Fr{a_K^p9K68=#yPQu?r^&&~3_j%|tY zn7PU@$CKA_+p6PZ@Es6+++Kz+oRBp!9#25qjB@TBh=)D>8o;00N}W%*3^M5FwWD_u z9Fkh~^-@Zl zGr?+2>6oal2vAC(%AWD`&WW??)~wyd)=bipHA72m%_j`0FK#Eb8>4L2F6{X_ZX5Mn z#^XyRT)KE(ycfCYWQ>VRN~z~8O^}6cW@eTz=ZxpGjwHHL?5?aRX>FYro@%#ah#6rI zmTRM2F!lT)dlKX0Q)Fy*^1u{%x;35648xkRursZ}@(?%Rn`(Lw&7zt{Bd)hG-i*Ua zv8bSV5OdV&QnsRY!_5-)ws-u}0sWVbFDMwlwEuvm<{M=hAwx4c!;e-&ksHO>G&|zC9)cw zpJwu7Jmj_G+cvM7;TAJI+{h1wzsBLnFORZyzMNlwJRWoC_y~NXjd}=O4jOgnc!xO5 z&xks{vx!f_cl&mm^fbFq^tl@2+m$Qn+aIqj{QPpXg`Z!Zw($0H(X)8_^yBeOpf)?X z&6GO|Ys0ao+%$^P^O=Z|vZ-$#N9lOdqsfP#di8V|Z{(And-Zan=ic_=l#eYKcjV#8 zm+Dvw_EPj|d-_c<9&9nqr}u4`ss0}-puDF`m8)x+GbO8wBO%fjZVAR@AO>jC@gFND zjo(VL6N8I`Q_}H-8x#~4%)>U7>#wN(Ye0n+Ecw@v{2R=`{eP^z2Y_Tnoj>07Ug!9_ zU%%HmrK38)0EtKvRaDjRRu)y1;?$EiQBkv`_Mh5U-=_zs7YUD3p>`R_^$`Pc(P&Qspc z*Rq%8R?sq8?qV*3CX~14YN0h(9B$0z&s*igFDa+B_g}4Y^6!YbZoW@6f%q%kmneS# z9KA@M@nyY^>)$Wq7|+3dE}XuwoaBp0Z8`qnf$P>3He9e)N^&jcK8N!~`r}2Xb;g`jDa-xd zq-?^ES|^>;(07G172KXXQ_t;x#lXNT`oC%?MJA~oi&kQ>O7v?^xIBhV9~(PkMEOlq zs5Cy29n53~GQP&|VMvN^bz*<0hvdntmp=f4k-1q&A|*$00RxNABs4uva?5q6_{^8v zjt%S@sPF23LYSXd)2AAH(gW#CfAS#zK7uN=s-|QGt11s)$pTgtk)#k`ok}LC#EYRHdBd)! zLzUQ2>2a5^CHnV_wyhoXs;>5WF4Z2jIolMs&0=vDrUxSVkSqAKp1`$^xzS?RRJ8Fk z&_BnNuQ!-?eBIcDK1e;_vRc6XhyV(GaDsY<^&;SL+?K{QB3_?lzJP~lJ@NLBtg0Wy z4wdEl#Ir^HFe0x4e&MS6X+&O0vnoNaNr5`XIKM?$g`8wPP2U8FuvC?epj?PXIhV!2 zHeG9>q)bbMwJjX!b-Ci2;w^3)Y+KXTzHy*u^I&rF{Mm`~v*Cp5bt(g6@y^L?X|A)r zV>CT;fwQe@54qK(E0>RUB=WVC%aQJ$=^WeHRmy1LK+5iq1tOJ1wj<_pCu?(kqp#?p zUT|#rs6rCasN!~1lE@s+qjCf<2{_8#$Xfbzvz(7Qm0M;1xiseDtxk*;L5l?C@BF*z z2fXw=8X2S12G9EI`A7;JNUIV!D5eXzR#k%iy0U)U&{{-&(%eOTH=;wLFGp6@kFJDs zuL#vA&pYZHcnMwjkGRe7C&aA~p;1XfB)UiLugHCNoyd4XrKqM{2{J)%EqHl#F13l{Q|qZt`HJ zSI-4YBbit=8XxLTj-KvRi*YHcs5zTG)*dW`v+Z%8(mvT$TT_Y1JwDBil%Bq|wZ`Sd zr`Y-97o6H1QbKKh#cHu@`9!o3b-Ut~HNE{i`$3naE8GXV?4n+xOGK8LP$miHNK2X1 zAY3!(J=Y3EY?8fh;ib{v1mUY^`k={{w;P@LM)J#?_cS5W+NVCb6d^H=Q~ z=-+pxv%3A&YeUK8!H#uro=}Z|n(|RjPy*7BpHS5=3a|RsD5?PhFJ@XFi zS<+3W10)N`@Q}&iZiR7Ke>ib&>d)NM{!J1>WVDh&EA57Oh{iNM3aT<%GMA)3Vy(>p|cSVSw}upeJ*z$aG1VLxI=9kmagenovy zm57O@5JOuDPg6XF>}ljIT?9KHcufiWoMiUj7fsjoZ|>~ej0>( zUdbb19DXH6LcsmVt`nS->eG4@a0Tm5_;Xjc6EeMxkA(OxSrMYX3-^x-e2!3$Tkxo< zX{%B@6e$w*J+Rc5@gyriz;)9PMWhILJ|b6J@CbX_^bMoGkF@$rS~}pEX)iK=MSDk9 zytiD={m`xVn|LgjdrV(x;qwUhg%Uo?*(@)kQE^M<3r4X ztN<}yBvAxBY@%H#O*nZ|1zbZrt@$u}4R{Gw7~tq9jWeA+L-8%5tZ~l2gugZWvc$!W zdB~WPM7KW6b^O?FXVA%MFBB8B7gzOYxVJq~jfA{LR7<#KhbwXW7IspCBw{V^+87Cx zN{A0NLtCw0ex=n*)pXa2-jm)edLN{?YqP$Y^k#yWkU<1EpJfgCwG7$jCg~bv5=O+j z3fd^K1zcQiN?tXm4oI7|q~*9h=JiHw$0aGNq? z%^ZI~N~2K(prP#D3a@R)ik58%H^@A9hJS*~b~x?uiGdJuCR7{#kk1Qd5e%Vsjqc+p7uhAg0Auj*-ei}U!hNqCD^B&lHpbybPOSn?t5(1jR^Y2vz-e^~xQlk@Vq68B zs9(T6te0o2l#!)(3ink}4-|Tk4JZ^AMr<097fOJ_U`WMa%=LqzFZ&yt z!+!QPSJod^8l$eXTaCJZRR5|X-HFcl8pk#-g_(BzR*yd%)ucUMMNb?bi~0S2mRfB5 zcL*aMz+4XE+lX!wk3>qYR$9e#|cZui+6 zcZ@W?$HiiMf|XpVLyw0VPsz+nSttA}d<1_ZMi4pM#4iM#Mo_>NaBkvz0!|}HaI5Uv zP2(q^q=ksuZo}UgSh|4v(1J%Pf3H=a##_|)Aai5+tHkvLTnBe1?jqVJZXmv@Z6IDC zptMQ^G&oO`3ZJC3AJP=D4nA&(C{QdAS_;Lv`|2#j{~hR+%4*KlIP75ObL(zIPr2Dm z_69<-2@TF#T~UrdZAEHXJf(sR{Z^8*_$qIokJ#^w5qqBFF5o0V1iYD*DBv_U0`4|+ z?{>&c;Msyl2~M^vbdwUYg|pb_(Ugv4NA-ue<-}JqlxXNAHV~f7^KW3y8S!ZLoE}F; z2=s%VnbPd}lasGpQ&~HZNF_d3TWD)rs8#3N+vg=1M2#&(5({#mqdhi%<>tksbMcOD zT|P}qHb%R)_4aM;>e|}ZyR8d778v~om_A26hFy6t_F*;Q-!tG=>9NyYO(>U`RJ$lW zc0qu@^N{HpUV0F{Yra#Gp202=85un*-#yo85$|3U!n+T_iuuP@%Qr5U9uAY=4-$iN zJ~)cgX^EBMM6efvcVe#~?wc7BQ0`sA&xZymezMd}6H zVLFAEQZJfsHG5%$FLL?ql6>a!+ZWT@4>9)&OxG-zUV+^y@LzVC);2Mf_Zy`pw0SvV zi`0`-O|NT~OTRbDtM0iFGs7;J^tM>O>@P}|SxTsIG z_d*N)B;nht|4^&-r%!LRpdV^Mf4hrz7gm;PQZMM&XIf9b7oNh`B2UgIDF%9SYBuC? zD=NCeC)d7$e!nODZv!tOayT(uO4|UOavn1hPRJ>@btN%3?(gd@^kj8g<%*LKJ{Cp4 zL$kO`5ly#Rkx&{?(ps~hvZFOBj~lw4ptvs@@RIa6xD}Viremg!&G)4HTjTS@Ho7II zbLo%rxfq|A=?q%mSjV)G#R|5Orh-+Ca0*6>{(=Eu>nD3eSXAV^sT+lUNOfaZzANMQ zdDXBU+t;`4==8#clifRK+LOWKKk2MTqb0R-y5j8gjc%8szU*-2D$D7mqDRXF1G;MW z+haYMsvd0y3-Ny>w#$7?B$zwUbUt)yQdzEhDxDu%9rX; zXZ3oCs7{Q?NdxExy1cN$K%dG3{y zljqG8XZkYc7`eBIEh=)ldm_{|-_|zYRhw&XpOd0!YkP0sB8)|DIkG1)du7g>g$lsU%BDe%krmRxDc88gsAMaA9|IFI z&;9jDEH`^(P1~ANItI3MJNl$p&$=Eptmz*2_~~<1ea(^C@^o8iO}TxhRGO))3A0%Z zTr_x|_+x#$ec|Z(!2@gCySMhHhfkd-dn~a)ASL_PoObRd!@I7TJJ`9YR$JfMvA(Oe zsgr$Cb_N2PIj)6dmp_0FWqyN~JVSW{$bh7o|BVDqoWlpfu^(>1pEvwS#GB4v0sk}W zVB@?#NrdJ4&mbBjbNHnz;8y8R2Mu{(?vfrhi?5d0BhoAR*B_PsAO017lo(b6^76=A z#Q7C?5dyinOzAH$E;h35iZ$~WfyK5=nCswxG?ua$h0(t7-4dNdH&T;3X^hdy-nLwe*LW^pF8Z{>!ON{UIhnf8e#P z(r-7mFqGeIK#K$wv)R%CW8`Px?=(y4`=2xsJ=O_d(}pHJlB%)HhDmE)MVl+cr4Xto z^90`lk31F_Lyhjt>_>g;lz$hJINt~RMw3)#KVT0&QR4z7bFyS^3b%;mbXVSCN$ zSVhfh6x5vCyhg}MXUb;}I`ncUm_BzBc+>jws6vl0#_5T9I)RB+xUu$N=Pb)cQW-+n z^+9_VcwB<>G()q1Ld9IviHj$@cFnXgDG_9^4>zt?&F$lvu8Hlnu0!iqEN55Ntukkr|ozl;W{Mli}H z&Y;wXneH}C8Cn!sLrs4UITOL)(OY`rd9GGA)|H+nN-^bO`;~|lW-@Fgg6su`!Vb+5Il+CB*g{%QNwpufj72~ za}WVPhFxQV?*J~BTlIfu${MSU>eFf#^&g~jz4)pnIITB=W4)b2XL~_5vL$d!WQ6gV zYt5G-3|r4)bZz4@+dR7=MKh+>%JAbib*q3a(>*GMMh=cPp6BicM{YQq9nOg-NkkBz zcIwq)2-wi+JoH^)gBipq{CVjctQ}a+E$v(Zw@NRZLbacu+VaiK+Oo3rRnu2^?Sm_7 zlZEqnF3+fkALC;HrvUo;pdAfR+~4#8iOzL6Au9R-QVyvjJle@_C;ZVm)&C=xDWa8! zqp*8%KB5UH$I|=>=wlzm>_KCtx-@$N`skMk@81LZET208J@#eH+|qji{WIsy0{YbT z;CyuI46}3IET9kEMlEnC?>Rw>5}=$PMos?=3{TQef-W62eX`a2BJaIbdd3Gyzw{7V z`2gqL;wuk*2VX(1naOlFS$+ogPu_>BblMRMaK0_-KK()B+rvwv?C&Z6iq{pbm)I`T zchLrN3b7A?@WvC)ktS*r@Ba3Eunw1=LO$#_;nm`i`Bp}3Da##FqbS? zp&nC+GG?2RX)=6*Rz^$}KCU`^kfl zq)AIkS_%3ak6!$^a{TxHAI|;IkN7{)!luSk^gZCVo6qPj(|eXKY~i8&-{8SMA|~hM z@W5(CzfJ$f`+dS{{Wp_xVr*KLNjV?iLINw8By3oM>60U0t_yOGcOF6v@Sj(Sp z)yFE~Fw-w66zo;Z+hzP~eCQ0*O4~b4v#aYs|}GK9bL{ z(?RpRHQiCv^y8{;PO1Gqzu+ygHq+!moW zyJ}@SLOd&2Imz5pFKb&`dBJSQ%gsM^^L9!N7M>Ll4ZNu-=x2go8Fn@@k(w(BxfbLZ zl*Z>STfhFY`FZ-CJJ_+lTHVmmv7uUB-@$BKj?Tf=wRm)X{^(+Tu~u8G_iwFMw_;?- zk{FjB!x&s<(AqB`iJI{LGT^YB&-S#SWY3D)L~Fu>K&||;1wUrG#?U$em$w^mSjR`9 zZNQVh$F!5Tc5ua8WF3DSv_+oum2V$fe*1EI`yrg$)b#3)%d z#8p0HMfufB52O4E(`h)trP;$j80D~$*HK(ajK?=y&hvNj`g&qY3Yx1J(5ao$Ys5LMQ@r|!!K|)tx3_Bj~Z>kPTAL*75Tje6qf%!#Qo8~ zUzl!gz9YZ>gi;#KPh%d6@Cyv{RWyoKbi%434U_g|Aq@a#qwrw~dm0k)#7(b1=~!Q@ zuJ7zzU#+e0I9#1gb`M1(_4vBW=jSh9hozUF>L~R`eO^a1C)l=Ptu@XZ7;GOdMeX6L zw!9V(%m>vJPB%rt(x{oDZhDnH7A)H8Ks^`;-}3P<=382N-OOlQ7V61io*Kfw8S!Wnm6W{c=j~3j*~V*&D zMvl`;>xL$ZlRPP1Tn{l2)Wb>w03=t7}8Qi*rvgK;eu@#vM| z{O?3Q7<3zUBiE;H0kv4AhcAOR#eE+*vjLPQppV9hc99){y2Psq3jGMDB11!`vpxYQ zkE*Es)Nf$5o5q$7uBZ+D+(rC!fY&9Dr>Oh1nQY1*Kr3Hv89K=ONncK4cjo8Od)V@? zF2WSiDM41a?w0do3239B1V%!*Esg9-j7`ZQ1-&V6e6~ASPNw^k>8ZX<|0z9*$x+=Y z2i#egI$BiQ$C!2 z(rKwS;UhAsl9;uX^`8Np=1stx^+_KAy!jqhG}^+a2sn`m2?ALbAt#YBZ(>qt}2d zbp>>glp0Q2!~I?CNBq1JkXAZ3YxEFXUqn6C88_{93i2;}S=K zwY?Jhe3qz10bMLZi7s|=y5L`wH?-P*0Cxerk+*$tMSZO1R}xhyShtt0_~M@=TDNmJ z{Sem-AdhK29)$wM6Fubk)B9xP;QQh{D@Y_e<Vz{P*k%6Sr?UyxB|AHvva` zO?{QVzx>{Ec~f5%?KbgPE^q3qqP&UEa(Po<73HL_5?;;nroKw0Ch36|){mI5bF$TY z;_CEPGma%{f2ai&aV!p%Uu8g>k*Wtw+j*pF4jL)Z&IpfGi9A&vs3MA?rRC>-(B-FA zWQu%MV(nSkt9uqwJ)`jh*xI#%zCdTG4y~Grt9I;73yO1B#(Oh^ooV|XTtV{^vLkZr z-<9^HN(n8-GhgT^wPt@Q^Tn9G#|`c&dfXg6jM_YD`J%^PYW0}nR5YXCrn`JhY3wzz zNvbJo?CnN&s0aulNtFbfNNL>ai&<}0Z}FyrF|&N9C+SPrza*JslBy_;cRJX`85Rjz zJ=Vtdq$D9(@^-Vw;Y%8={~WEu$A>5em@uWjme49vGDYjciHtqvDh(gcPL)2cCM4-S z)})f~UKl#toA9Nq?={ClO2qQo(Al0$AZR@&_ByAeCPEgcxv?FGp5X}B4yo}IsUzSI;3S{_ zZo$9ZffKa*BVRCxd+k_v2!fi-dg2Y=z%z_(!M~|<$a6Z2f3I}brY`{O5@1Dsi zO5c2?zPU_1a(JjXm`+FmQ03O0=l6Qt9BG?PPtOd@hBF=E?j3`a@`3VarpMAlMdodC zPQvUr7_Fa+QOD?VEstYN+>qc_smTqgHt{_HZSp;W(oBdpnvrm_E)Ge77W^6Z4V>*k zG*9)34~hEA{E*r-Qr#nJead3Q9Z#!^1F>Sm|ANf0MAhu_t> zmG(=Euh6JHVvO1?eAEP-Bn!czu}u?Y3n-0`sQn<$mEv&dQ^2(ae+GU7x}B#3`cfLY zt;;mSvjMsG!_Qn?VQYs<0&F8n5?T_LsIG-L4;0LfXsnKuHgo^@L|@O*naN2o701 zmJiBt(M=uT-p;y z>65UC-_t5Rx?DQwLFp6Vg_Jcb`tVDm6!W;t+=7zTE_!h6G}eU5r?y%;ww+}B!)yRr z6SYJ=Xuh-DgO%?dUVeA0&<~zif#dvg>8>ZK2grz}Oi7NTd~msR=Wloq`c2n0OQq+G zQh4d|-WC+6x*9!rU_$hZa3q^S%ve)z5u@;pow?j!K!kGYetcaA9 zM3=E1+Hn*nov@nG?d9%@Gf~#6n|kUSN}Y3UBj*-6f-BZXVR7~e#ba0edfaJG6_n+T zEVTZ`40>9l^Z1e0_{z=oQ(MpPKr-QyG&^-#Wafp6Lk(5@DBJjdW+D9WmzWJLt5xf?nbX{oSwr(1c2#GN5GLz8&|CG+TaetM+e8 zq@N*6NA8p!g6C|AxEW5;|3}Wd3I0F}UJ`IbQ08TvxQ6+9P@WL=mPXBYy==Xbs7H|( zvqijTPPf{BjK?bJyUq4(Y#+7Hu^p9*E83kWyr7dmNcZ#cNREieJt$q*Y!BxWHTwZP zd41qX^+i9WO|9?YJG@*nd2!$1tn^=yrxhOkZ2EdNh##&}gNjH1_18g7E6)dhOJyjY zov73Xd|_1$Mf_^m7wfeo%f(!>oMUgSZK`!FlqaSJGag;@{!vkbzG5jd)Hc)GS?%jD zRK~z30_=LW0Xt5Ks{bNIvkmPFot>1L+}XL%zSy46wYTT;?NXtWc5ZZ57b=y7YO$xM znD6R>HU@24>c%~Iu+&9f06&=(-GORA-N|K}xwtsFTs+(m2qFJ891gIr(QnKW4gm5) z3qfATA2^`#8eZph77P7FegWiZBeS3S0F7ih-&6R?PfVa?UE41i8M$Qp_KQbHFWz2T zQz)#d)n@Yf8Rwqc&OUtG?%lT?KKr&kXO3R7ZTlsoqnB*ocF8E&)Ea&=*u4`n`U4%7 z>jcd>HPp?=LrKpbw?CMQzT2TWLh%%0&*8w7Glk<&&$ODwVSUurAbuLaw{xZbgdITO z2twZg13p3HfHGw(vF~wZ>Yw$f_g9tL^gyWA?sEnmYAWE>C+4!#2l}Um|IxK4M%ie3 zQ2BlJ71{cXmJ509v4A(~ja9;ZdnX63o%pDeus}3}JuH2W_Q1b-6>B0to}us5n|qSP ztN{nkw3=+K#C=C++XJpZZ>BKWRvgW!(XdxVdi@vl#`9d)8;wR>_Af^4MfcEYz0;R& zD6WtB-LcnN?249~?C2ayAegGU1Fmlb$r+Ojx`K{-VrKjBfw8sc4r@VY$fah1tqT*K z!1#kF9KcfWhvXA>PYL4_)4;CQ;(_}t>^weLn*(VN8^_UGI7R}VsN>egZ$0#(L{Rmy zw>WXq7oF@#<1w}LC*1P+Ihq~BHAL4|oe5x!OOa2xLB<)JnrCDYU~N8K+Lmx(JGr6- zJHve&+KW?dnVvR(G-{J_GW6a8N9kEt+UKa$`{6XV>-Z;pelUHk=mvWhvz#sMQX{x{UalL2h&}@OZKFaJ&EyJ z_xJ?^YmpI%yubx^dcfB|ogds&ukRV`oT>VBS823_14sII)ypHrH>JAb@vc;DbhI%r z)s^W>Ci^m7Q^bYD?A(L>n7w3y(llU7nkxx$JXi@>R=fi*N%f4JFgx9QXWS8Ab+SCQ zzfa6fa=1iuGc4WHv3_4~>CE%bTGS;yqDHNO^@m2xT1R5!>^0+OPwdWPY9{i9$zpM= zKvKuxj*z+FVUU^!ut&EHe8~g7$j%X*AG6k!I(%`jlro?1oNX)4Rco__(rjlYpUdKZ z&YtakecOA)?}qWN+W2^_YaEnNz!&eueZvMN^n*{f7$vz?ut5J+(XAD$*A`HKf~-kP_w7{VtzYHEXAHk+o;p+bZI_KvY6db?6Pn&rh06Od51Nqc!RoMb#ApwmUt~y zs>gv}9&2PLJ7k=l3D<_L-ix_2`>%RL;3nXNZFbQ^Y4Ng@A|@9jaB z&4vRupY0B}6~q3xAJaysaz4-ckz)r>3g?6`?Kw>;|AH~(xM*ZWum4f&_N%^t)opbo zgVB649*6`SVXqXF6wkYrU{JXs?oBJ5nM8N8ea_+Y`a)g>-Y|DE5=^_?arX@lZ_uj* z_1E}uJwZ=fbr`A%(d%=p9XU{O%6Jm=$~iBziBb{bQ3!w&G^7udN7M1HsbV1$%(qR* zeg273-&kQZk24wda5CZQm@8EmM>1Lvp$FDKFy1>fQ7MjOr&3`plh#9Nj7G=Oah7MN z!J{R3+W@vx3-QR0RVK-7wZ73ClI2&q-s4wQ|1Ek-l8;z4IiO&(Ivk9uUkSuDtIPUF zHzj{94=3H0`P})?Bme`e*M;@ zu0^oBFo|)_;SQtfigCv5hjc8xrcyxi26X0?a2jC?v7?2omTMoE`xF{rU?IlciZKoc z(+Rh(`a>3}e_*0-aJ*6)$#%|`YFkD#-%M-abULi1xwc(ri>8lTZBiQA@)RHi^YXf5jl%250S;PzN}(J%HqKgVs*mnZR*o zrvcKAU(LTtIQ#U^FIMH$llF5WC?W$=UV~Eqs~qU zIDzx~0qMs5>HX64fDq2_10>1b#oA>jAcQl0tAo7O2 z0I6~a;d~p`ApFXb8Rtj%j5W9-=VZ#8bg*~(R5;`tXZxg3!0nX|2X)ouJAPA;(jS}qR1JsAzqJ__)9$6F&CtqDfl@e zH8g+H-mLoO#V79?<`JU|>c0v(t~=4o5`MqLXK5$99REtV!O(==4RlKvjVaELE^-eK zMB54dzAS+o@RHF;O4g+;_1qc7|NS`4-W1K}qm5Umf4r*S6H7bLt}5Ey)`MHPxcpUl z)LR(SV$N5!OHDedaW;`@To%jcW9<6OkN8;f)(K-;%l9ExTBaP2ZJ?Ug#w^G*m_Wiu z#ksxB+S5zlLRUg3bm!vt!2Pe;+NY&R7l9aj4k>pF|2U>z9 z$2tomz|rIM_{#oL$LOKy+Iqr~0ZXJ-J-T8j88UL8!QG?hpKJx5Nz}&){25NwoW5xV z=AkLq*<;2#tMu-j^A4tFSL#4^W$y!gWgN9*RyeOL##Ed0_b5ys31jb z3&x*)B{6Lw$ZY({3D9QMQKHjjK~Q#4LS9D{TJfj#cDKUpxCU;{8MfIS?oG11$!)jU z!p=F#i~_&Mqev*1XI&_Fx;M)5Mh}&{W@VI1e)jr+cN^GSkKN+->XsZcv%DqjcAITI zk|b~Q2B=t)x>4-WEqN5@tRc7CV(*b;Du!n@4N|-w>xS-WXs6p0pzYI*b6{Z^Q>Hin7A0vVYVg^4W4&2}R9kOOZM^H6NzmPZ2~8`$G{Fgd6YXC6CZ=HZ1M&Z*u`ZM%2U``^QEj-@F!z4RG8!#-T{o3;SYekQY1*;$yC=6x21vVVxy z=pFpTH*8qaakW-3jxQSZfx#=m2l2k?S@vDFo!%#zv^;}n^8~zJYT((Jrp4%gqQ2b2 zPI;O7(oMWR&bg=h{ClE(eD4C@Lwt|k$MX^KEbw2(XKBCmnx#)t`_Q;o;IlUn3I*5; z^!xshpZ@VvCP+WD;8WS#`1=+9oJ4=F=HC;~8GP>={=H7%UtF4p4tFQnW3zNzB)%|U zIA@y24w7ljsvhU&bL;i-rDu+;!{qJ+>sQpN>o3I6r^= zrR^TwN4B1dwr54#9Cwkfg(Xkj=)qo6G;Fn5$Ed+=<+g2TFyMCKGlS=Da(*G{)jXoX zSGBv*ptT#H+Ibs3Mf2o^zD)P$!3RE@<%ri2pC}RIMB^k8N}RP4^3)OR#j*9n0Mu zv!mc=hQ&y^2FB8%^K*?qFDF9#sXrX{f5hs%o&LQu6p-5l`Pq*L-9(1eS_G}lh}Ncr z1H~}$d+BC9W14UyAzJt;z5NlJ>vsBAx+4^L@jjzH>9?Xi&~b6;a?t7Tu<|d1X1WC0 zx*W7c&zJLO@6ut=!yoW`1%D3V`OVVr@qCm&Z&^AAy?YqXSDM=Jegw}m{P`;WoPn11 zP1ETp-^ED##WTAW&qdtwOFHW=(wYF**nRBv(w6|g{*V6+`1Q!gq}-AOyPsVn-39oY zz(;KO{R-zNDRw`0g5E{C6*LtR4n&aL$4478L6KaEP37tdr_Q&8qJSRT@o? zVKQazic-9_-;6iFTQ8G%V_uHIwY+z{jQU3x0B9*vWU0}tRT(j5}WK|#eVc6 z02}Iy>^@ixZ|3_?t@>@?Tj{s#KJuGEbEJh0kJcfFJb-mDPE8#kaz0zVyv-<)cg*N8;Fj$9Ad8_hvo7WZ!K}XEu=J2byRtwy= zaZ={Z5q>~W{5@oDONRW`HO^Q}{tf@zHtmc@W$EqhQSC>G{15p*Tzf%#rcdzpR<(u} z(jmWXjWZr=y~W4zD)vPwXN==|jMtlASkK4tD)v1Nr*S0s4R(SDkO}s%R0j3E`Gsw~ z-gVgLOwTvix1l$IrH9$0@Kk4M50xPYdUPTnp>WVplj@s=lVyeSVd2!4+oHGWe!FUm zC9DhH&6~Xuw;o`6z^2&SI_z`aZGO7S32r-F)fC575~`&u#co==D9PrqFA!p^z0x?c zaUHuZ5>UhNa|Up;JJ!rz`DR3ew&9L*)0xm@F-c8NF?VpmvDegvfM`=gCoMQhX9z&Z z5FaMuC!xb%!IXQY0_s9HEE;DtN$*P!#4Qf5e`G#inrSag?da{AwS;jUcPOEn%a)j$ z9;}3Cu0G}TkG^IhyY`aB`lj)uH)M5|Do3`T`IcSfZEwHp$VKnloL{rA@%=eGp~skNDoD#nE}ns3Fpr0B+^W>l|^ zV=~|ezy0%Sf zGs;{oH&w38@2Glx+3@fMr}aB6^3cIE2HR$)3tfvn-39n?ePO318Sg8mCPyNL%?qO% zGN)Z>TJ@!+yO0%f2Sox!R0{$^@F1X${sCvqFnqh{3@uwBNGQnlXLrnZ(48B}>m4q) z!)XuWZe>>_8D78nU~TZy)4rnw;oO$ajrfm$zGFD%cG?p@w^=q@vzfx=n(3XvG8mFVj`R?vg76l^e z0$o7YEg_wI6Ufq_Ny92QeELjZU$Aq_X#1%PP>C6ft2WK;Ee=)ug_PR4sSD>?q{n*P z1LgLq^_ihl5Uz>YY>~-)yfYT>sHuB*Hy+*}DQKzG1!`L~#q_oFmf_S`e`tKTq-AwC zjxUN>y}o3?>Wc@%*{EAxoK(8H3+7sAuDy3{XOPJqMSC!il&sN2AQK9ub+0+N^@(+{Y*N&dE*x9*w&gj@-{JZ6xO@pV84V^wZTvMzrd))2I zs-^KfY{5WQamVd$n=jIDs~@;_-GDKSUo#?U0YtW>BcVXR?+*m9btmX!xyJpzAlvKo{pwdiE1ebF_$9T+%s;g{ zoR$X~&+@0N!dGR2-2gr9Zg>Ys<9X>=w|wtkG%_$K52Kpz?9AsnJJ}7D`SyPi|^MBz4Vqf8wA5W2e@r&Gm=V=EpW{ z>NsuAjPv_5ZhubkOG2D#QDN={EWJm?8V2y6L5kW zPB|pzz{iO&g8FM!;dmuU zxniarPUiPPYEr(>glXeR^Og)j#IYP;&l(;+YkHb8`lj2)ve~gV zoDGp3WA4_aYAf##YhAf^{GX#5HK0XlowhCACEtuwl&sP_p&1e_zg9XRSCEN>;KHm} zY5lM#Y2Gmj8jL}8S@yKlLqqnEG;gVg?1Qu5ic=F%Fy{}U2=khB;9Is0Ufd1 zJNQYJ8wa*^g+lIt&*dwpI_Apdwbfjk*MnifVV3-4lwoXp>>QwO)U%E4`M5a1lFqkG zIgny)>pEp<=+thH$E7Cdd`qqeTrGW4&cWZ8gIDY%K0io7*lMe8J^CAGVRImAVef$c z<4af@ue53JqUX08&*$4THv6|u%sElN(<%2De#Y;5ykR&~oN|W&_@T!m>wnWUS+Vcu zG|ZA@@SHks)ZGEj11l096tYSO24D)&l1B=TakdXML9YK;^tjikF$+d$E z1A%F0H0+-CD-pKAgVeqmXC&-i<5vTLDHnE~Px^h4#;06Se_$4m&Y8elyXoxb?jHUd z$pwSCNTi^u1xdmS$TFJ>1YFSo7_cYcp9a7=tu#&xOv0h>obGmwIR$_Gx0l%vz3my_Do;F#*b;CO($Av&>7BaT0R`k z1p>MAdG2E`{r&^lnxCPccXV#&wM{{D3kTFBX zlMRbg=r5uhG)GmL^cVaEeu@|2IHjCLx=jX8M6j4k!EIa9DICh{c$j34JnoGzbICSB zzn>~^-JA<{cpR!-3#L+9uNIw|pVa)hgj3NyZ~$xJzCQCtPY9Ras`WGHI~U_xB!$FI zt5(mK2IFc-4d=fZ36eq*j2w*y1K}u?kne=UK8M8`3uq~q)6QTscr8}h?1h2?4)3;% zX|`NnrnqiyCOdt`P&njC;NEt-RgdI{bBXEM=|pJ~31c!m#gq+v2S%$(l4b`w-IV-f zwUGz`?RsUdR^sAVL!!{tu>>l%Km>WZR!BhKbSBq~cYCZcZzRmjL%T1yTh}A3+vc_g zb+4!KeVenW>nzGjHaA?)vBpnrlvpb5C$c#HiM%(}llOWUY`KMz?42oZ*!?lHCE;~x zR{VQQ5?-WR={f4T)odn7DefN0V8-DWz%B!tH=_%rso+n-xv3xH*)Y4wFYr#GbOVVe zb(}@K35P-?=zf}w)f(=nfg%Ky*c}`(H~u=hc;&*vm5Yt*IQ*!%tA?I{$I>71^Atu> zquc$OmJ^Qf6r_cF+A=mYXsGF{6e=Pru5fYvej>-dQkkVMtgAG}lkA0;xrvqy(#p5l zXz62L!|P9~B(+p1%=OZ9!0=jNNcYLXpJ(7`tOeZLOmvN0^OeVPtH!=}x)rU|Mo39* zv~C}Hxm)enCy4=ZPUQN__uH8{K9}$jtH9!b-{9n<#z_ypoYiBA?IM2@zB@u}DnCa! zugf&<3~#4Cyh3L~#dQRmEi}Fwd+KF7^Tr@D3|%e-29nQru@cn$KA&IHaAV9}f3b6B zlLcc<_XOIJw^pHO(Kf+PdVAHsj<_NA49Yo=D`UM&FNfttWXFA+lca|a{N}%e+j9{e zYzbEy13|h6Mv{Rgw+jw%c?B;`6H{T$8BYe8YU(-W3=0&h~kY$F8U1MUI zYVl(GLNzvnJBwjBrqzI%M&?bHJ{K);P| zapLQz-wC>f=hsRy98TJPYPYH}cSQMm=!>@SYaxFThJYZxfuu1bam+q_^1FF_A$O?p zbJ*c-H~iK;rsqv}BR|g7!kFWBWwN6qnXFWv=fBA$79%r-mySxRoH=>M#2ogw+sBuA_4$cyo|ws^Fyt??ONr&Rjq)jhjI3bT7pHo_K+@Uphq92+#;xY`&e z`p6Z{*6xgB7dP@{;-Kvw(^@GkZRD+j6jqP&>UQ}PLU0feV)4GrhZwvAgb;4E zKH+0WU-H>Y6vgglpNrVwdv-V0LMAX|6zyPtkk%t}+*n`rLa4w!4Wy@7IQJ)I?@T{- z@31}A#`|23xX+=v*e18zm`a0Qc2+gEK+{B+x$RtMUTn>Mi@ zOViZ;nP54hX|6^N@D*z*iEprvIW%|UQ)tr7*5ke_f70b_+-70>JH?YKWXuew0CZ%`RY5#fmN%a@L@TtAqXoyTH=8*5%gx z?y!d)!l4D8#!W~@<8#MJn!{di$a1~e_IBEqLp$_=!K7(D z&gkBTxol$4vOqwEEBnm3Z?nr6lCc94#INECdmHa@dt4rN*d2DMfn?(!tn4a}OIzQh znYZEVmXOyQHsk9tU&;lv%$i4`jiBHHJEVYgA*UwthOVMZ>UUGi2ajA;wwts!_6GX> zS}2tYgDc$68O4?S_f^<95W^|{(b=`*0k224Xg)O->q_x* zk5`n(dUL!yY30Rrwp&l?enr(&(L_%&lnALlRZl15UGaPH5KvUDkc*b1p=2l<)KlU9 z5#n{G-?8trchM;cXA10alhDiH&kkur<9+a<;d6mlq`RaI4flH89%czDYP9Ql zs-8SQ(u5r5+aM*zp5;FfTQ+<4aMAR5Xo{XyCwDd6CImloNE`Px*EhkjZyVS{d?Dz+t%V%)xGP=?eqHvyVtc<7P>mu zRXWyr;(U@q1-lq`fwdLuI%pKT~pVJ|!eyP$>-y9~T6_n@IkoV`EqMrb>OG_@Pi& z6waSmIi%*(zK`bTI-=eBhl&gJj*Z>5jh+2-xsQ3%`Ji5jMJu)Pj_Eb0mOI-1B@zmE z7mM9tWQzS;p}ajD{+ISj`P4PjJIa;(zxi~xC?&q?TDl4+_B}yVg^}c9Vr43YF=yQQ zfLXgJ(v?id6vdayS{DPS%|t=xk$|Rzl0M7k!0u}u;ZQhl8_2Q;4)1ed|4PyxD~B8D z!~5_hQtkf^J`mXR#?CtUF!-#|PGb5p#-lkzlpkQYG(;H^rK-5jd0b*!r!U&xmFljC z)mPDemz#Z2hk4DW!TqD72kO|3YIa7Ho9QZttE1t;?o`()7fIi!E?&5%cmIxcu{62k zu*uqM-g@)m$lig0y(0r>pHsKs=I;yd_n;c)PX zo;)voPbw_?Uwk^8lGBNh76UIyy!dOt(l7oxoWi)5G0hK1x0y0LCzmo)z{OgOKLfun z9Kp?vxaTCYO#QX_VU=YQYy*9%aj)aYZud`QmZzs|O?y^-POoLd*lp!`%9HXu=?WoA zitki0T37R|9Mb{#{N)w9t4Y4m*+^oMLjA=E9CB;6_oQ~Y96>#P(Cu-m)@$7VVGVlJ zsDz`%L(GSJGNrO5u0%aGtK@Mv{vb(VFZSMwM6 z_9pGv*%K5yd)PwnseJ>d_Vu0G-?yW8!&Fz#g&L2!d>&8ZVYmBy zv-y5m{)yTA6Ywwi8fG`imk~VV#Oiqh9;$Z(-Y;!sUzJY<{22Hpwf_h|Er{S} z$%k9;hj4;5#RvwaQT8EuhTv8@A@oU{gR~CtPHB+6O+HBQf;jz0GF=A_GA!+6XM&!1 z#=;cXtg$+Urn2IRb;cv{C@ui`c{~z}CZjQFryhaJ06)lsi}>IaisCPls6Enl6WwNP z*rdxX9!^B#ae8&T7E$Pi5G5K!eO($beOvlIc@eNaF*!t%LTdmTAF+5WxWPB6cy#*~ zw<---E&vcXc%Zw!<(>6kGX2L zkWWe2?E~)MO)kY%v#N?eWwQ^u@ENbu9hiq705=8O>PSpQ;^KnK?bmQ|Fdl(r%Y#Q>Blt!3JB0)oq`NxV$rVm(AgEIoHx?cT1btkn}Us zXSRtfUs_?fiJ~RmpeKAVqxQQ3iZ8UF&$v~eTd~^v)r_<$GU4&MJnASLaXLLttJg8X zt=p>9#m+{i8gG*V=9~by)@aP7SNe8-tm3f4Ho(ao`B*fMedYmw!0xDwN?kY*L5ui( zlt$z8hl8maBmit4sh{CO1Zc{CCHv_8iJnxdCn0{dcv20<<5GX3D~>at5?wG$5@QkM zFh5@`y;zS;?Ilr%UHYRjiQ!u-&}lHQqD+uL#&X=c%+ zO{sXMI~e9hNGhh5qKG(oJON#-r7i4o>1GoY|83d+KIAH6bNrr4<@c3}w1w6R=A$O{ znVyvX#Lp_^Q$VweNyn~+6X^+RcX41+$w!N2pWEedF&rctu-hGq=JjX}JF*$=(l0zp zwB+|kyiUd8L@u=>=ydDYKIXDn7|sQuaaE;_>|)#pz}E`6#))edpFI)8wya*q|Bj9I zdywSlGnVy6vw6f3atA{mENhp?f5Ib;MK5^XD{)RO(Fm*tVZ4G{V4wwwBPjU&!f4sy z09oixXFeLsJDj?z1Z>XonDm=SEfpjh(REHE=_+W1nZ6~>vkQ=sA~Lp!?8N9nU!fQz zqHKH^zr{21qb?u6s77Su7dxd7rAOO+Dl+ozL7xjqo8d++BGAN4>)5ThvFdEj1^a1} zxzV(BUAd~`a-_m~cI){0{)-$2I;}8`DQE?jorf8W-vl*lc*be z8ul)U%qk-yNLdorQN50g!t)$)&AB)>?0Sb2X0+#=f56}|{s(#ismV6#L&dJ3W6M$zFDz2J@L*sPW8bds<=y7Pj}$9g z?J(}Q0CiDMPs)M*^JO{EM2m;b(q z|Kqc6dXY_IuRmt})tvh`x7nOYIxUX%N$4-OVndiCLts z;?IU`#Ph@a*^qO1e#Cg6OA0(6GZ8++(r)%8SY(Fu2H6^ZIG&ftl7x`7n_`?0{`^L( z0`@}uKiryQm2TuZks%-O{3!oI2Ia8v%=6NXw2R~`Fo4kygX5#tV+J0aSL69{{%r7A zJU?NSb54lo-*P-VL78{Igfb5~V!CT_lqgemucS=Ve}gii71GM0onWg7beTTi4I-=! zMr#(ACtgj2ydIlfv--4nC*6BS2l?5tzZB#NCy=Hg-BnY)i6ECW$Jt)_9E=*4!e7** zim@27?S;?N~Xg^h;Up_2Z5=mwhc*vCyMBq@SA}m0wA|FUU2qvW%5W z`p#xWwOMyKbQiQS-$9F8`nlhOch}lop`a&X?={202o3aUc7=Q$&o$#R%TUIMtD=ow ztb^5%En!#H7W4%ZcH5x)|Lg4hU84x1IDWh9?e6W){{HFx+Qg7VJ-sC6Cm0b)h+r%t zVz9E%MvI{7QYl!8DH70Du(L=Z*b6o(MEnCRVk5yOq!Db_@0;EGl}jwr95>wU?Cj2) zd7t-q?@jzJ22gpnHON~y{K~LzG90170ZI=H@RQ;CB^x-Ub9&b>XBnP5nE7;7Id4rD!!dlbyHO|^)@7iEte3n3BUU+dLI|}geAOD^5wN< zgr0)@HEj(SMLVmeUt(raUC?94bYgu`LFZ0+RT`QvsVEYumzE8{D*BdHs8!t9^ya-ajP{#MYvLMckC9~sH zy#jt$ALVj`(fYu(DK`V1gTdOsL{dkk+;FhsjZ~7lNti>L{ZM!zUG1fu2aU#GP|hJV z{3!l2EY1~v9YZ-;!W_wJo0>W0OmoVy83W~b7LHMGQI6s>4aWd>Q;wz`LpkX_>ZU)G zUUw`49y$m`manK;E(1M_?0N4Z`-E~ikCIxx=3L|-ic?O_i*)6dtSg429J2bvHzUeHxIR8&zuw^am#3kTXP}Wi+I?ux%pQ}9agY^9G_pk6XK&h>pX@`f`=her4}%=mnIy|A19%5$!G*F{Vp>tKOr{Ef9fo-=F|Ikz$gm8u7-h~a zvMeH22={HKcZA33{(ni}WLxB8x!Grm5J#;GPt(tRB=Eb@*a8TQ&^Yp(LX2aJk1Nj= zg~ofu+daQyoC#`o>`0gR?nI2*4u!)cp~=&gAgw!==_0bfK3O#!W=L9SR|4jU8_c&V zqcIE|msxaboa04qSFc$9JXSw5MO!vG!7)Kx;%h;<;!6hebX35qPu46;+%OTn9fgu< ynRaG1aen~M%_w~3l9ZVwxiIwRX8a+tp!dHZtQ9`+Six3i#?k)^?XmdKI;Vst E0R8`9>Hq)$ literal 0 HcmV?d00001 diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/select_add.png b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/select_add.png new file mode 100644 index 0000000000000000000000000000000000000000..c5130b6092384e5477ca0c52e856eee862f69431 GIT binary patch literal 18359 zcmX|p2Rzm7`~R`YmXJM8k?e#dG7eFQP&V0nM|O6E;z1EY2q8OroFWNHcIK(j$;#fp z>m1+z|9SO1Pvf}VpZmV9_w|0iuj|v}+gfVWr&v!R5D04Z8!Ea81fekkK|nxG3csT* zV-W=ZBlc2K*CU620?Dmo;MZrpQTM#>xY>I9T6)?b>|EVkY=ph6JZ)@Tz3kn*SBP5W z5eROCx{9Kn-^;&~hEJ{cP5HN03_Yj&l8jwUCxgyiXIQu&|6Yll;E{C)O$-Y!mCER) zSz$j3Oti;yU$rl%YqS5-(LI`Pm*VUg^&{*;obniWf-qzdKq5_FUo2Z*S}uNjF0Jb4 zmHL-*C0v!4-1L2Ye3$CKZ=W6*nAER75Y#sKEq&axLav^K_J?q`ZW_1x%wqEg9Ry-enU2s$@r*A?$+z$u9rLQ!a*TZ13mWe{B) z%Te6q7U}1ch`;)97#mNBX%asT!wYF-Y9u+%M8LOyNA61SC{o5t{{7VASRxA8O zRoO4AZszks?QRQgkHj;ixZs&HoBl-C341E(h}&x>wd+kDm0_R$Vnj31)0c`W(mn0@ z^~ymOR+y6svt)TEW~JDF4d7I&tnA28~kUw<=_ar?hhw+2;8 zhLn;%m=J4=4msAmDjqZ~-VNkT)fkZ=I?qLf<+czUKF&-6FL61E!kC^ae}R!uCD_VOl=d9v&_BgwtdM#n{X>t}Q?RZ&%J_ zB+|x^C9%tHN(6riLWZe2MFQFxdZa8=r0y@}&nI{1-po65nGy~>cfkIYnHz6%cSo)8 zt@FwASzZa4rhiwu@ZbAFX5aNeZ-Lk_fmjQ}-(GxlDrpdQw+62#At7KI%9I&V@5|zD zou@V}S4us%;cqIVb)3?FB}$l=*GN55iJ-=a13gQZ$kkf6;A!6rSBhS+lz3s`R%M*tdnIi$1Dkg>#fuB+yIuv^KnE2V1M8=Yw=L;DP}#7Bv;|GJNh-;~P}xuWFPONT?t zun3m-3vnshKI#zevKH@J@IKj%h z(G*E>yIlGeRv)SES$3qR(pGI}TyGKup^2i18i;gYEpM8VbfNXUmqzD`*mf4vMe?=MIhF1sfJc5)u!4gz@2?wceZJ| zZgyYZu|~FdXz`OHr1+45Y zhK7eTMWNgC)fAJF?S66{vzC;pHuvr3Ii;kf2V7y*)3w3efB_6Bdglq%LN9b`B0pvG;*r)76uR73tc1IR37z@TB$RnU(Wp_g})nz#avf z?l2gKE4c!%2JCq=dPN$9jNU2bkZTS;>$aYc*N8^9*ChD&N!fWfa>V4yTyxm0nUsaE zWOz|Jl4L_sTns>TFLn2amUshOK_j*PjU+(*85xM$mCoh<%3F{m`ug}|3+f$LA`c4% zAm%2A3=f<(_jd5UsawPdc+474jTkg78T1K~E}yOg5XPTVt5#vSjMgg$Ru!EOYinzP zg)F7~fWKOH@LO;zqqUJ*h4HiQekDFK33zbvRW2VvC4G2f;50fl)t=0s$Yjbe`N~8j zdTEJ6Pw*6{LNM{5B-8NERLY-^V;1_}xv({x(H8ypWPh7Wq=CJGCtvq0K!2`)Wk?8Z zs*Ui5Ga>sJ1nX7I;rT)eJ^ilbWg>`!m%1jW>rFUQG)TsrX%uJjMzEF=YkhL&vo3R= zphiqysH&xl8c>$XP^=nLk%i(!ef1ke(QB}IrmiE-gE zh(W3gq-eY`z{X%$3LM%z_HK%&`!L{6and1EiwyBfKyX6oEx95cq%TxHfRdSg`K|42 zA=6Lk_=0k^d~lIFmbW(Y9{p}0L4z5p;$EnWv5btpaKr1gIl_m$yu651n;iI1ibjR- z2ZoXn?E8>odAK_oT3V05!0Lr0v&XpHA|JeLQig4-r214DF*!;06sd&}PIjz`(m=KQ z{cRWXXQBELxz#T#Di5EH$x5$@L=Z!?N@i$6fQh7=iy3O=7?kAc3AX!iyf35dXXB%~ zYvsa$dy)YPOBO(NM0b;LgahmITj%3MminF{DWF>Y@+5(iD#O10`S=6wh+?wnQS?;k zQ0|!9`e)RWpw2^)U--8C1mMoI{)q-kQ8qKo=EcH;#u&`6Y^gvd{Q8uD_%XQ%)Bv|S z!-Ue0B!`ttBsE6V9xrERUXhIWFqsbLdpweZjokE><+zvn=zc}a(o!ZW&5Iw(K3rec z{OpWHNPaj|+cT&bxpyU~h%8wYM@rzJcp&!N2F{go=rHPt+|5d`{kY(rFe}ri@mDJF zOai1LeX|mK7t}JUJW9h<_v0g?7~W~6@;ITM+l*(nmzR`q<^0;leo%xZTs4#FRLa^5 zB^4EK8Xd-V4-=NCNAO^!r7qSIFHmVU|2*s20e7HGV`S{>67Lp-3_tW>eFl;9GFKo1 zvjN4z+cdgh(V5bN1gctbF%%06F%|%bCtZ0pEWNV$i(DWqaN+TXG7p7Ko#9?;cbgAE zk>06AZ_abVOQk?B@MQGPO*QYwiP$;VNSt+ccIM3%omp6*gSA>hqzlZhR075DCh=g;o310c zRmiw99TM8y%+EgSFPPDrtCybjKrKl{&VPe5Fr-q-g`+PVR~c3AGDh+29UcwV(p}Ii zxqO46>k@=@@sO-{bF9EAi0z13_fT%~1H{twKZTMn4P-zeHh!sPT-JgC{0=OwMq82v& z-?{Af2}Oj^;|NMF+tB~6rN*+cy*`j|*PKxL0Hp8Y*;^_)DpDB$I7&r&oqlp*!1ZXz;zV2=a7>kc zGE9sLYCo~!%eqK+Q{VhO_wLFkxin+3O*&Y;5+Y5EDyNtgGJ=~tPGs>MaZGLu z07Q+EGULb5i2%ZhT9)d*$M`^@{OVW(g&)cfvEse)TDo7JX8|dJ_q4iUW?n@i)rTF` zera0a?%XI8`FH^9128118O@DY+LEY=q`NJWR?*xX4u7&(ZE1LZPR7jJ@?ta&HSHBU z#8g_{`U@B5WFA?vP@1F9sY~FKbXATvVK5r=_V;qPO&gB{tr z(<`R!!?X~mH(w8pclpUh6&K&ur%pmnE*$py2M;;=yw;VtHE8{{!4_9Pd5t8ZqoYSh zM?(u7=um5&I2sTG@&`^Yyq&JV0VKlIr=Uq2d=TBV9e2zL7l{3RC!niqgzde=3##SG z#zZ~A$hNobnxHlZXMz?=FvLY2-s1-WIw06e*sNKr<^7 zv@F%6c(U;4?V!OFyK=l<1#(w0L>xT?sNmP^8yPWx9G6r`DBC)(c`k){It4@g}G?btA zdn{D=w4eEQ$q=xpuPfWY+Rj$H(yQT+(%{3?)M;lI7iE2YpzvrhvxcaPc#yPDr$NZb zIp<8TOdHg1FrIw)Q@bK1oDzgtsX@T(FWn+Z@8&2nT25Z_K)^AP@Zm6bYh3(%1n~Xf z5ut&)QYEZXaZjar>bksnTQa{kFip@$Va4b0(QxLH6D7gSVt2{38|6vR3uvqlE}J~q z<~5}~`NYqCd7&N^P(+d(Nk}La5Gp&th^|FTNmg-tVSA zuJVyz4!)`6_&kgS@&a`NQ$eQAKyU+|vZa61uqOh4XCxqhb&Dd5N@)zWX7{H<*nkv4 z1urgct`sJo(Oln}_pgEnq@_)4^L|VgwW;nFLG2-;|=-(sB4FP*+ciaF&V#lB};U z&O#*yKiFx^&b|zsj<#e0*umG!jr}bzK1=U)d~r;Dilb+rfs4Gj#e`X7=>qV%H-9FI z0AloAO${|l2Z1;Y&W_h|JFBgt2`O%^qN7xCFQV+Oj!^21j8vA~L+_kdKHne~6zSlB z-xQzH`LC@0zW-VL6P~+MGW4!7fU8mn)1BM}=-u?s#VD1+F!igmlupS|S&oLRs1_e+ zQQ>F6baQVDw0Zm}yh@YlRBt-sSrYE+uw-`rkHS9gK{?OJ91Nl1#WE;Z2C^ z5-(^vD!)X&6q8M`+SsR=lW89wmU66NB_QrPf*Qeh*bG0^Ev|I^?M&_$38R|n&7(^c_&a{Ja64d4>l2*=Fo>dg4KtjUnY z%-q5Pd5eN#vzc1nz&&qur^rDZJV*!f_>U z*`@p2dWFo>Fd%1@fUu; zx|M8Qc#^ESCMK=|g+$>ozJYY`RZ5prc@P~)BZwThq>IeeQ)wVY>}$5hnC4!#3_z;}z;WgCleBDPvJz|=t4_lf$2BSnDR0^v=DQ})?10ii8 zcAdS8vdncCf7qs9-|pIhySJhZmLZskVHQCXd|$?u5Z6l$)bc6_W_BEAVwsG8B;gCX zEWZvTfH}B-IS#T=1T0y=&VaKpP|+do@}NV}*VfkFF4gkAKtoETLQgaj=iZCcELR}- z1LbK=%X7@i!3_bjy4puv`eO0F+&DB^8L$=nO+XSI>(_qtSIEOqBiF0-!nm)qM9r*_ z4(u=QHLxqu%UQj?hQ@iq@E!j$Kl+vH z#BC&~NM|AOVkXmf%Fz3Q%1w~ylC1Hlv3 zHId;&V(yuWN6)x+pW%0rgj7sIvNQ1ecbdwX-Yn9KDp>q9zwT~IHt9;H_>S|is!RSt7rij2Nwm+3}-Yu}kxazk~cUeoccXoCTY8UO>OR|2lmH@(PGQA$e z1$jdV3+S4}_8Hg6@y-1=AU-z; z7rj}Fi$Sg{rrLla-q@Ft>$m#azyokpE6k$GoP@mZ<;4cVJP8Sm+Zc^g#SN!HXfUD_ z!7pS)fj?j10FQi?hn(`gU>sOS5;6~Pnn<4&y9n#4yBy zKXpxd46=QE`w}jtb8C=27wprcY`y%;TDlUs+CBEb$wL63)9Eng4cJ>)S)EpAP`LJR z(;x3y)+7TLEEa@NqKYPB=i;)IoU5Ld5P!l+Oz^c@P)e#6!CvO_zs+CF*QEf?CY2Fx zxnYq$=z#XgDlkHUF{B=LI_Ui{uoGhiI@t2_TAw$3kl14GCx|w@+#6s@{0KS`mg${E zwRG5Fl{CD2`wgJ@e6pfQT6A$S6s0Ij3mJCEaiIn|f0F5KOXztZ!ESoFqGwWAONS#z z)s^rSvY9v?12oNEGRo3hoSlZ*l-2Y)-46I~Kd#eXcANcvjAPF36#>cB8 z@0Fjihk9f8sq%?H>{{Q|>1dl5R7Os(2OTgwJ1mt#mQGG&`MM7W&Y4o+IIjIUYEor5 zP98wNG^G(CoS%3?)4^vZKwg|+3On(y!`iy+KSZu#|9BgdQ-BqZi>kLb@%$h+U($)v zGX2`?!Lxv;dV)|1MSvT+<4lj3)RAi82!iXO#g1T3*1D8_*zk}y4=uZkH;U}*BQ0^3 zeG*b>q~u1Db&)g*;KeYtqN0L8kq%$)?JqY?Gv&gn@p*aSsI(1s9Y&ze%U~_Ew|yKK zpdZ1>)PX+>-s2F@AMXXDMrLttAAM;8G#}DQfsW=1 z;DmfhP3uDCZ2?Bm3PAS0x^h7&_nTq?^uh7^7z1zsz!qZfQk2SoLR|5+mJa+myk*no zV+ynvESuej9C+hHZje(XAK*qa>t^ynGaQ46s8`cn*lhvz0G9Xb->AT1m3bt*#>S1{Qv$wN_}r zhhtoI3I|o$yFj8pwK+>hR_fGz=q(GR2hJ3n6JW&RoQdWSuPsBL15#AXiE>~Cx)7dl zR`so7wIzbG>}zqqRi+ zR~NhiGB8dN2IeQg{F`D~w+R0!+{tlg^g?$MIs>D%)Ps^D?9~VyYVjJ~!Jq3ZgA%Y0 zyg>646V(6M&s>CkI`15P1aAZ@ADsgO1c1ok2}7d| zdOuWozD1F%q8<2M`bMqnueaqF3#xdq0ojDqm0|CYjQ8@1Y$eAFih<0zeR(KyVpJ8N zKfw0Ml70kz7rFjfo0F5vG*?AsX znK-2f{Njy4NjZ>8Lwpc=+kr{(-O&fSYHmT;47|6EYw($rHB}3Lu)%wpG0VjI`XKRU z_D_Qdhul?9f@UNn#=X?X&}IdL)~VV2)y%nQ^(1PRww-2C( zhrFZahjbzRV}K;#-ae0eLaDa}QvfreRYIFnHKljzZjjvcA^M@iI@16ip4Uj7! z)_*o-0gU&8C<`1cB_8fRqzS^I9$bELamP0Q!ZwG>z^{|;4}IwwD5c9{Z*z2YzAn`c zEMV72*MXG!iDyc}9rNveZ zED%homHik@Picj}0ZSCLQaspm?gpcp+8excut_(20Bi zO_V?^%oD`eR#AXeP0qU)#O4vWbw6+mXI15Ic!c>k z)9CA)`(44i^#dCAQW;-2SwW=h8&mbdrmSl)j%*Ms-Ori8+yiIYKOPa7%-u; z)8-$7qCtS~n1qb7FR9iTk(C9FTK@AP=lGJ9wZwJ~7HqLjiy2RxY@rushTALA^xe6V z5N_ZUGH@=_m?g?@rI`y_0pA@jLt38Pg~;~uBuL5#%MFphZ}T>5%Z&=p>mp|)d2wsJ zgo{qQ2*CXa(AHaaVS5SM1?K_+65&8jif@Irp=!mw4iM9L6X_9F_GUfZ5pRbWEO>H( z9*~@R`pVD>2WJ=z9Co`RqpK#7^AAr>fMv{?33wKWzLkA=q7FYfKxt5AMtFrcP}*ZH z0fz}qj_`H_a3)Ds5WQ@8%SWY7BMAv)0it7~7W`Od({J&3U7c%O1C3pSCn8%2TtCCz%LoXyZf(=PZpAf)@_bS*(+TgIuvx+rBw35~dx{v#VNVL`JH>vU`7%LMvixi*ve&BU%(s(~Z<20KsbCj z^@Q&*!|)3*0ZSHMjAKiYg=lVXD1Ss*|)8#msnP6 z`Kb7r8{@T(y~)v2myVB1w%u0qwvmjLZDgzxoKokSg0)q}1G?v63?gSv1_!@Lb$~W- zWB@Z6QROWXrq8*_Zxj~xYWSFT*-JwF&NNUNiB>*+=kp_R?KnuGtu8BK=d;3(BT;l+ zHfcrj_TfMPL-3zyn?Ucoon)-vN=JYe+#Ou3u7LR+oZ&>wqMA5pD9xSL18jy8f?;Sp z+HwPClHdUx>zHbfmepg*0~J1`9rIi-Yz@>ta$7-ZD~}Ry#)gjg+8lhREnF?)GKy_i z;N_K#HYkY%jlIx7qn-p5Qxw!9j8DOE)?<*YM@O8X8(Admn?J|%KNbz_>0)l-_@b6< zpjena)8ER0`}dU@{c3iwY?`zrE$Qb00n;DKCv?4^Cb{hCEGb{Cy z?OgW>3lwZu{n+*3T%d@xY3J2us=v>utdO&0%~YL_BKYPHj3b(FcbH!j#FTTUtgU4d z9EHtPzVo12?? z4|TH-;$X|1VxfMX)@|22EKvaw?0vCaTaNMerx=8U_OVHMRq&TtWV>;6+jI+M;5K4` zy6^7($adV0Yh$Q+5MR4!OK@)_kRW^WxdQqUpO2iq7;crIDi(qVa_xWa1$mm&0ueL)fafVfE*PvjpA6u*+9W>0b4|ZU;5H*QOfggn-Anyggm#jo zHHLBq0Nt|E`p&nLE4VSijs3s=12cn!)uMf=qeEJwHex8&85jJ{9@v!=xw$Z|g@lwm zu#JloZ59UEcrdPZb-f%KG0?_c;%84{!KZiVf3ucpiatk9sF4r-N;Lppq0{Kur;6D0ZgB2s zfcSyZNmd^9q#FNc#^^iiH-dVQXyWq(QXGAvh~3Oup-qG zIl;37W42YynL1h-EKHChMS8B42Umrul)(~%2^Pat^Bvm`jK@_iPFfwthjL7Ro4Tyd zXcDDS8>YhiDtp%>Y(osD@$`EzWa>>6!E1*xS@87w*+d)O)|?{@oqq@rn=X}E9<RL+jM>Vx*BW{?fqZ(~ zeD4CZKL6{n`LE|!$zF*XCSg*tnjwL zPas64^u#cPM8U?E0fZkWLhpZVu;fL&FWdj-#eTRF6125_v@2?}W|WEE`6#qHefVc= z-s0e{InBTWEi(Ns53>d|dR?wexgG`jKYuo@3-cgemG3B6=-FM4M13aIY*URQcu+;& zTe>fNpdMu{fBFIADFco*bSUh@z_ji_PNyx0--d22XL1Kaj<5<1d^3ge+*uDZ8{e1_ z9wlpc@7y&HK2qP0blcr2R5(0($YQ?vJoCU?T{^MLs(#f^D9tD2B}S$brY!G+=>$v( z#@wdO`@N3OoI>HwAh{co3OBaWy%%pJl6NOAs&6k}wzBW&!}0XNecPoF3ei7Y$9arL z2NOIE%Zue90ix*&2FzF1q`9Uux-bt| z`$=CKBLftwNY7E&{7u@f-w%`=r?;ssf2j!5O;FX)Ab)n_OJ71&a zH@>~w4CgvPWbb~la}{zX0Ez^Uw0t&kw#39X-5M-{b-4&j+^iXSN0YghNE!@ejIf60 zf@+;qtucZ@59mO_D96zMW2 z$)b%WtSl$k*E*6M53`ou_t;i_vaNEy=+SlS{Ardb0{l=F2p;?>i_f_vWPdmlH+WPq zHahZvdP*W-dFXJA`CV052N|n$qXD*8diul4;na#{Kmc3oZbs{4?ZCOyqRj^=wRqRc zt^Lg^qRzT4-azm9IngQRqM=G57_fqo1iqU|$lf~Xv>uz+gNt{kzn*ivl|&5u8R80@ zaPXUUJvgaIVWtIUc%j)bqPH|;^2_d27y{hu0*5{})l*@i&Qg?`gRcZWUpDZUHu>eZ z(~{WSd=1&{UHDEQ7C;L>WK3QEV=TkWK4|v{?8;u{&(&kw?&s8Q7xEe9-?MrebWyW` z8yM?D7|NC7M0*ryzXjK=f4%SEY`O6)$%`4(V6~{%3#0X2IX(Tz;$m_%UDkZgq-)-g zBlxwH#l=dDA9oFwlbgM4vme;<2~{0uzn!&i&9qZ46NrU}EetbALKfC0^b^j!jT+0g zYn5&^V??cEgktBKYGo4U`53C`o8q%_12#kQ5JY9-r8&elBR%9Vd!|3;hM)b=ziVF+d% zta|pES}n>)!d)id1dWYXvc3NPT&I41G$ps+cqu?6%Q=%fcJ9E5pKE(8C_C`SoQx_< z)Vh`5Kk@9zF2j+Gpq01Nc_r@?Xm6F+gRDsa&r(y)Z&`SSSMv4K9#lPCz zS!2!qW`k<-X03Rt{#2X4Khtk_%z$)caj9;)6GkmoJK5Y|JaRT;`T#d`5oir3jWIvQ zhQurEgezPJ*%(enyIQ5NU$x#wa!bvxWg}m7)+>9T9lCI=M@%dm6MI)#sd=>q2i_ztnye;W*ucNGNKBO2VN3Ose)E21NplhMqza6yDkYH3w+T{T@6J3|M zp8m(Jt*wIx*I>9NeVzU*jO+rdW{ks);|I6mrhj^Sdmm=Pv@W!Cgkt7wlimOacc02%$)aYwu*ugF%Y+ zV29yk(-AN};IZMp4y0g$0}yB48G7D~D0frlM9ynUc>|#?6VS6?WGjf3Nx*$uZgTLL z(tE+QB!s359WhwnS;q;#)*pf~A`t7D-{$iSQ{f8EP(otjyZQ@YSi%L^=MTHVU=%pF zxOkTZCq!9B4I547Ll818dswsbw@W(pU+Ze5D2yv(E@kghfj~Z*6Fnj{-ya`YUDOU? zMXaiYY^d%0OKW|i9kMsLQ=h$m1v)S+t%nn>*N(rR?GkT+FQ3sq-q2p7Y+a??`D>>T zw>=d=+q&P_8s}K!kKr@!I;=tuqof&43i_&4`)#v5DI*EN^o1Xu^*;_O{2!>S{v5&C zKw{VP2Cjpmntuq#Kt@J3Iyo8SYV9O7C%%8|E~8R->6*gNzCIf8pE|@|lJSD=hLwf! z!6YQGnbGO#E~s74dTn(?v;(HTsA6ri7bcdZ;6wydPSw`o#^T{4`AD7x_18 z)|Ii}ZN=Cn4&KQDb>LQ~6twtV>)<2r8XGAs#xs_>llfr}C}@EJs$iFvmmyDKoE`WD zFq2R*77xP9av%aYir^iVjq70{vBvt3e|P0IRL7~JC^`?M>)274^!Nm4G@xL z*j)TH^Xx1-8gdC@E7hjAKhKw~Y~Al=;BsHsu+S%jUqfI1aW%zHQec%1>EJLal^Q4~ zApspNS)f@q(;iL+KMx2900>-v_7PHm_Dj}$FIQJGUlNSztv5Zqq|;OB4pDQzLPnvl zs|#j)7w<2_NMrhWI1k(i2`KWF?O7QbV#S&78)t4wn=fJD9T>0|7am-_=<)3jba}0- zu8eMN_=a$>eJjhoEAq6}{LJch>7aSYcXhGV0zUH*n=Oi^IP(Ku`GZ+n44Ugm42LM2 z~tw4xCO6gAVOX1;#PuI0)WD{ z{=3*37O=f+X=g`felW)@{^FLaoO969?T_rjAd%tL`|{ahA% zq%fKDwAU5~I3lbreB@!wW_DXE$$1j_x(@Orm-j!&8E=TFe+!(vRX&1-A?0$1B;?|E z!d-Y10B}dEFsE4X+v3I`hYAW_Tll%Y%VumJZ0fe0fSGCDo(hK!`KAvfPw?4^+WGnZ zm+?#>UAPWr$X4atj@ID?GGGw9F-y+hFJ|=iNyE0Rs7Q$fVkO+BWGO4Fq;~;92J9oC z;6TNj-UbtH{_3r8ZV2ym^9M|%wmCsi5ZC3XqS3~apWIEm@+Mu;l|qQ;iCY(9Jsn>M zJ|Nu1-K)XUgMcF*MB9M`#1D+iB)#74uC&Yh!Y_@INq{|S1tACv2ETl~?{W0#p{Vm-4=zAyv0rb_3>+NvL9Oi#wm~}K95#b zr2EakckK$RG-u-M{*fFp!Ag0C?CvP^iQ#+|XsSYG*@WS>5>}c*%0T{P3SvbWAG1Et zr_dSzUD~x4__@c&l<^b^An2z`Ia)eMu1Myrtxj)O8 zf26H90sU7z!-Q_9A*{>F0r=s(c>keE~kA$_Me9cu) zg9)Jx&?!`;;k)1GoqGkDcgz#pE%q8gK87wjeeHJmjmqdVVT2AbZp3csfyIPW*vv<} z$efAo&yz83f!Eu(0)OrL7$48yJ$-PX#_+wo_Lh|^P=WrVzx^`}B2)fYVZ`91{YvvT zC+9W)2pm46vE{8ah(abEq7~7FtY(?MDSIuERk?bLjq|FtQKtz)R)?yHI{HI?&QWTb zp9$*=I2>!e)_>KjV&m^hl`7io@*kgJo9yOE!}tDMvV*~*hw}wrZKngIoUa8;@QaF) z6M~M1=@@InmS>oNA&ker1}MZ(!z+c*9xr#R`-MU?QH&^11-qogi1m1ael51_z^QDL zcZbE<{OSeR-vCx7BbjxoKy3?$7p@s&gnnkSXVyE6c*un=_UnqIwXqwwFvVFY@2o{PXjdUAZxTd4Q)?$KRH$!+JaOjBEU{ALmLr z6MaTjCT`>x2phrFy;(Wgw0Yo+M&TgLnG2*94t@j%ooeH$;zV&xI)3M`s9h=f!M9fa z8QRvZgOuaKezhIuR?khH3}{=eY_I*!aLXNYp5r>2<$70FM`qDr22*V_>)FS0^8cPC zLX!r3gkI)biK=`}>wQ<(`S0fILU$ciHvw(Q zj&d)2K)$FAgE?*}3<{2wH0aa0m8}idVBH@Yc{u= z%zN2wb>0(V0`&b&nOimXH}JGFY!fi+_*NBtlAUirivUt#e`V~=PiM!Qz|C*WzTJe$ zxAmeA@Kz z<1k({SzA@qG4|h{VcnJeaeK)QsPaGo@^xRBht$Tcp}PLQrM<#`tUy_hgY?UR!(?0y zto`fI4Am(g$q^6?oK`FM?Ud{kPOsS**o67`>m@a`BR+m#(!Sp`R`_!8EirCKdiqHg z+vMIp(MgXJE()7+DAy)Od4FG zF~)t|?f1_-npezg2)D@g3>DO1?rb{@BfmukQXs0OjN+Bbx$!qAG(xc5GQi@l-sEJeM)L;kt3nNZ?FrLb z{@0vOjXuZMrWu%4PntbY{Nre-tM4+FFW7kQHn&W~(+{@J{14buWwtgfvMm2T3Ax2E zk-QoxqScvY-hb)R%B7WkxoPPXcx!W{|3y+=bX1gMU%7tbYmc$EworL*^+(Gc9br>> zHeX1RZO&FzRr#-?F-lMTE%-=C8BaTIS9pAnsIk*LsAjV^G?=!)G-XG;p=>{CXU;p`B^Dozc zS8A@LJPR5f(7W3?3>FglvVALZa@M_Lg_fIz3L3puuC7eG2g5J>JxabBoUfSswi=Em z1m62+h4T%eTXSnm=uLh7C-L!?{aM#!Jb&JZKP7kVOJCNtxQRM9%!kLP>6B*XKE}Ow zpCycnj`sLFDsEEmi3)kcp%BatGt)ony<|d;^3|?u#FmzD)9AW@Z)_7l(PM4McHEPC?Z9OfBq?CK`?2+kGDNZJLOPh&)mW z=;n>{$^K@v-BW2&%SrSYc;6t9)8dBt!?4wDOTSKe>b($gthrhi{5wU%WVr z7*geDc)Xx&wDgra4FmDkMaKl#~>P+(^mD=&49~BEDXvyO?syM1+~}(e*o5 z&gOA3q6W+b9o}aUNB0t9R40nfRh7TN_L7s68{S5AVFqf@!y4rWmUbYHV5TH@fMsi$ zqrKD^^G2^Bn;#g*>^7O0LTl*Qn40Odf)xkw#%ktA8Wi6wQBG`GU_{L*E8Jg zZlDueh2LGYKIAqqFt{zmR8d_WaRXWTr#I8v`bOr<&%cV;vNei|WJ^s%uo5JQ4NitX zsL_}Y19NvCnIG0X=}-QRe&cG077YW21ynLBPl(2vO-&;vKnrI>n2Gbz*{H)Wa+BIu0S%W;$1v&NI=`XIT z6NB&SJ+7(_+&uNtfo)T&oVg9T&z2bdlj~1nN*~&ua(v!DQnH(C!_&G`buYZk9OGlv zRQt)*yZpJSTibdEm6aCq%rlk{}Igu$CxZiVJ%#nCkd5WUYY6t=U|h z`aL9(!XcmgKf2ZNo(^5nG^G0KZeW4UXT57RR$VkfXE$S6#LI3r=w>pAAFh(F7KRwS ztNtPLRrc`rpX()q-%E_7(Jb$uTT+eM3v@fPbqdN>b=DdZ{peeh+KW%|s-cW`)}qc^ z3p64Tv7IO~uT5Q&GV0&qAR*7l+{31cRq2#qd%tjPPPjs4>TfXEFFkG@YX0IZ^k2C2 zwQDfQnM)qc*H4_9?d=UO1V{KCIJwIZOPoEkdq7BLlo3-4KsokzTrE)P2d&P3yC&Wg2FI*uZP9 zwwU8D;Xc}Ibh3qyk59(ukDm6HaKv?Py1-Oz!w>&F?edw}6aKs<8VYQ^-~aF9^O}K5 z)(TGewi{SNw~((gGrE+7g$jr*)aAgHr?rdWWv@>KdMnTTS^AB>13@@Z?sS9LlGUDI zNug<+BKYcKIzrAwwGrpaeP!QLXQq%Qfp-djBPW+KZXloDK>7!{viV8mn|NL^87Wx& zsEk_S`o8+-(H7^9}6SL<={6WS`2n4AGluc48F?8VGF8w|R8a{FKRFCF^VUAJl<-#j`W6P86GLy*01f zb|l?}AJ-BJ-Ip}#)hs#RA#JWbSUi}2>(;IBx3rv8&CR*M{sw0uP@bz*{{f=dGw5K) zqo-JSOKsjVWR&vakp)Y^W!|(Nhl>|4-Y6Vwh}|@@lL~pifbO~@nsd8S{;Z3=1-<#U zE%()%e(VspEzZ%M(l-4hx^3k@5Uuu+r)T0R$GN7;b&)Nist+F})0q8#F3 zn2~igFw9&x+>G}4M#Jhh#aZ9Ml3#>xE2VXnu3zAjyEn0ZX1%;kxO|zqF{4v8~qLpu7ati+-CnkI;=W^l6qbQq1DyEjh~j zjbvufc&M$!kheM0y=Ul8cXD)1SzNLN6}-e*<+Gsi&IW0Ukk5FtilUcmzLZw6!G`*(^3dST2x4AN>Z|DMA1FCl@k?pA`bsl1>x@h`{O}H7+xO5 zT3O)s88udUL)vXBqQE0T4!@&Y{B*2pM!03rVjP&`pFOPq8p(pIWxIF93coZ_`Lm5K0a@DT(dQn{_Diy)Yn5d_^27ajg)`&YUz z{DI*kucD8Oi~D6!YXQEc_Ej?W)$?%h4Y2XHM;zTf?%H$t-0`-zclUAf@ZHAfkVX(D zL`6|fKk(_#X931!1AjYLn^adz@!8p#u3fu@B}azE;Y3Eu`as8afGxfso4qTNs4pSD zsP+nZ?|f0MBJ-5B92p*yv8>Jy&G%hi0e}DAX&>^Kdn-XK$~<-~DJ}is*Uupd0g1-# z*1dLt%G6X6S*FXlnCKCxKi-czyP*C14Q6)-r7iD&|Av_{Ib+Sn#^y9tNiCTtx?T?Qd0Uavv6?@_xG>-`q~;15%K8Jqf+hv-9J3WsQ%=y)ZS%pETI}>&N&vm)t$v2 z1_p*VZ{DDxp#=p69bAqXcGwGSgP*+@94sAjbQ!4$KG@KFCf?vQR%BFd3ID|m9{&0& z;r-*?=%_Xi4^KeApY(LH!1Li;5z-r)zMh_*US2b8K>}QR2?+`Dq&H?~W*VF)`UeI| zDl01)NZ5;8T7qX@+jDbs6B85HISiMVmKLzAjTZK7e5&~SXM1~notlEe(7>R$stE7@ zEPQnTEeW}i`{&22MM{Zb$IF>>b8`_GIGS0!h4a!%Bl$8N_x`+k_KY6s?CM%fmN|bn zGLkQRcee3c7{}w=+Fqor>bEsCEZRekhq4702X~hS%uGy*OG@%30^Bdo&m2EK?W+6Q z8c?lxZSdW@cY}lRNlDAz%|xZYa4Id|o~#V#Qu0`a>@3Kcn9TfM{*dkL{SX~}Hz+e73Q%@!p}XL@VFY*!XCF zeWE4d`{w56!otGJ%2dbwi-iSir1Qa*>zrI%Gj4~UYwsjIe3&O0gs#`p+}zySih-OQ zZv8zy_Ng^~nw=d47ls(Y$3&;4%`MX_VUX}A9C`X-xjkraCI9}pO|9`WiGY>8V?Xlk zcaN|83pF)27w)wNY(IMVu)e;2^3x}a8f&yF^LIZ6)0)k>bBFVU@0xmhds`&3{u^64 z3A1;ox_f#s&>>st9=-2HtukC4mVGq4sHo`8-7ixr>Ak(ZhE=B7IXN3^ry~zlR8>!o zSM#mj2KPDCS#^Y2n41%hmF95enBqS#e}8{#>w=03j`~PJWg{cX28^77 z(NCYq@ni1&`Q_*DZ|LI@78W-B$^s36)PeY~)@%Mh5sN8LTJ(%67Sd58SGc&iSclBO z)HL|?$ZN&uutnF@w7jCi)x+Zwa<|C<^fYb@^fEEYmM?tw{(XzjDsdhY z3k!>cL~aqAo}M0eW<}pWm)zOe$>gy@M=ak49}F3u}M;_;FpGkKPCQfA2vMZNoqK)`Pz9kXx^fIkVNLKBJ#i zSl7)!b%q-7|18m{pp)PoCX#qxU*8|zL3h;lJQTPyH`mre+#ebL``PI76I8JybmOZ3 z{6)wtUF(yKFe&5oi6?{it!?3o%gcst^Ao2?Sy zRJ{3 z#|0Vzyqpxr&h_jZQ7@4OvS_Wip14Z`y}isVEJFXR)6TjN*I8doz2nA&dCQ;Ek-sA{ zkN$VD&5+AI3(Lz`NC6u@eQ6696Vt-SXA(&GC-B+Ms&ns zD9gst@lS2^N$>IZL>{-hcPY8en_NDzBb^YT`t(D2Qun4RO#-&(@0vz5s2Lb!R9A05 zS5CftN?15JI6l~c!+^t%jk>3d6loV+Z>$FOy5!*xhgN@njz0ZRww%ab=zNuamI`hv z+)$&+?^vH9+0oekIr*Q(0_`TI%{fXcm7D0+G+#_ZX=G_=uMilZC5#K))bO zDEDJaVCUe#K+>N)(IxA%t<5pL*6pZ@R^cS}CsX3}L$ib^4K4yXu@}iSn%#ZMO4kPa z{Hz*lcysCx)m2X}?)$ladta%3Ep+!K*?G1eTl>j^(l_om8q7E4uHTLm#%63{{@NCl z*0Z>P<6>P4ak(jA?n;hhLf{6)*P&+#7V71bO+9P4m+(Fu&a2j~$eY9s45Lne<0elV zy$=;a43dGDDJiGhg7#pYzkL3Ddb&4qiBa0kr4Tote%tu_%$(527POM`SLUf(ZZ2N9 zs!X9T$QA7~Xj3opBwpV8`{ZRYi^r7a-m=%lpSLqZxBm>i?|kNi^SoO4Zf@>=K%Uv}PV4Zz+eZ=XDbIGOX$YfmE?KtvL#=Vm_X*33@;C*PO*#eF&EiD`C>&-1KAG7$bOGx~M zpVZ)@S@bDL;&E>Rzt@V3|Z;AHDTGiYgY`(5zfl z&5RokPTb+vmwd?}ekLXa@%;Ij&o?|ZC^-1nY{Q4aK^13KFE1~>63r^1p%%@#W*=qt zjKj4t1&-#$s!0F@@7~>RHb4JlWM$Fp-S_@II|~bzB|b6nuTK@z0pCI?uUzp0@L_!2 z*W=5ZyJB=7mj;p-kD)?qnC#KeN&r%2)zS=0Qs=R=_zs7`pyHSHd3PLGX^(X8A*J2`m& zUX_uNk!WHX7M$V7@^TW5kV{W2(f0gXT7J8C062z*hkLraNk~cU`AwjQI5*bc{qm%U zjXRS7+1cF%gl0vf@?4Ck=f6m?db%NOoIHV)Yx9ciek5fBh4bbRq! zUg(PY_3PK&FK?DgQJbTPc|Y|m4O;-Oz`{S3x_20-6Pk8DRGIpo^`tdVI&}8a zr-Qh$Uzyudn_IKq1!i9!Jb0iGM?CyYf^tNWW2yV|=RgSgyu3W3$}vE`73JkmI8BP! z<^22(;0Z3#i87@P`uh1P2n`VtBdd#x;mM<;qX!Rg)zs8tw$>`6?!KRLm&g#c!cPvk=V;85Y%tlG^=y~yQaiK8F zz7K75|LQ*9mYtGP1Bmu5V4AP3lnl`2mG^|w-?)D@b)Cdi+`~)ixHy*(5;ExN^;2R^ ztDX6&lE%tq)qZ;R_s`LT{rb|{*z;ALt_$~5WBeEG);Pa@TLgX^^Eg%t%~w1cVO#)ADgb6VrX$a$09H}A){F~ieS zjqV24)gwoMWKY8-xC?Y;Sb&Gel(c@xoL}mn9Ywv?At0Vb1 zNN<0?p^=eR7O&0E&$YmgK7IOBVOT}OXWN@;71r#z*j-)@9U1QE`Sa(FLs_+udEdW( z_gd=5!o)oK`}evsS(!c!J^j}9_65|Ck59z}WMnQNX>Vxd(MkCKY!CfQGcKzRZB#*C zzWsQGmXb2_^XJbNt^Qqun8LZCu-+&lXV&os|)08b9wm_BoSP@t5+eG&;+176lln0Nss?L^I64eXiAxTbR$igeF) zQBhG5kw1_|8tUqFf=($@2fu&(_sCxm%>A>2 z%-hWG2M3*JUN1vmgJR_QD!B8pg zB|}Gs{_^%-fT*w+Uc-?SpV>Y5-m@(Px`Kg$f!<5?^-mRb0vlDva8E zI+r0ei2C!X!bna|Zhn3qGzqgeZV@-KpD(RXlt8J8J1}kbX3-uasDG(_G3WAZRZ7i- zG-lx`F2cKf{7$9cif;lpraL?wVMrdZtqlnY$&)GJQFU^1YVzMQmCnC^v}0p{MMNXG z2J{#WF>mrjla@I@KlikEaZo6`_^OA`MLK&F`uhi-{)bmq9rM7Iq5t@=j~7FHWM^l? zT>+zJ5O$*q=@Q7_xij$SYqO6daMdVmqL#3;U@1FSrleWr!NEa*A!?c21dK2AkPCjClta&jP>xHvc}+S)>(JwqpQcXtOFA;xIB%53%5ulYJhEg-v2#k^Ju zNfA{UI=621Ll0ZbhdY4fz}xrAk*@qOQ|Gun*G$UDcmV-HFLNUCMle?*;8knuUx)zb zY$tp3{jD#5`VuL3vcv>G=1KkiWOT9lD?L5^szPk%QfX-^z`H+NUqr;kgGUQ4xY7z6Z?NnO)GNtmUkz3Gfy39=+tnHe2L~evcjlLu z8nkP~auV80lantsa-rw~@qYyI))|f_bGoAt5^@SHtdN_8k`ihvjzN(@g&_)7p6st9 z;p5}FN8TB##WEMCb?xo#=G>Qvh~9cHt3r+f-#P?g2a1JH^BhQih1y2|#@^n)$P*rT zL9PiZ%=ccrJ9m~cIE=(4B(!pchlhp;Er0LquyJ#1YHEh zqs9CCzGh}-O`|MC4js_-1?~?|>N6tRIyzpU(>$dkFBcPwq&?v#EWUCvWvcuquL z9z-MLp`InnMrH|n384m&JqLl8K+XXG0+@XrtP-khDJ%C3IDqI>?oc{f{c3#reY4N1 zX1?^ZoE*^HXvxShJ#5Z*!Y=oC0*Zvv@y?Flx093nEFJW40f9O|BGlB>XowSz3o9Qq zXEX!_qM%}zmq+@efB)W>NT$@~ybSzkpJr{knvp#KxCXR{Ph(>@IXOdq|4@N?^2)rK zgn@yWi=y)pTBuMWRs1(GKXUfIu&H2N<25oyn9ko;;Bb++kv4dr-uttUSQee)JvMf>qeDJ?P3% z;Uz#wgEWRLNG~b{2%}Ag^;hfK_uk#OH*ff?52;cSA$w zjqVl@wsAe6n2(Cay@eER zn8G^S-r71l`|~ZCim!Wmdb+Q#_%Q=laTO5)o0u=l6h3f6^QmayPJw(O8xK!oeZ5=v zGd36cw&msJva&Lu#h&MHD=RrABwAtRhQ=1x*Tp>M+n{2jB-r%{Wdk0h@}_=6#+1r) z{@C@{_|L`I&69kG)yroer0&kSaJfRAaTC4=30`k1o1Q0^6AEerYLM}z(WAAgsor(^ zQBf%<;n3PM)6;or%cs6c0h@UEknr?jY?X#iIw*yZifjqMZZ{$7-Q3*ZYan!*n#4*v z<$0dz8NoC4@02&M3y%NU{stLx^7{2_m=F+C^DC~aC5Y)~2gyU5Y4+PRjF9Dp68gV- zN*9|=Lq+wFT3`jLBS4wgjg5>lVIhDiafs=hASTzxSyo(20bdijtFefRi=%2Ls1Q3^ zwZ;#nKPjL>yWgs|@ z9G-c4c9xWsbTeTCTAI5%x8=2;wt=YD1emI-ynF*16O7KFil}c=%E-tRZwHrSxBY?% z%+Jw6jNIX0W6uXbp#l}UFNAT-Qm{NseseyKakQSke1&k{Y0Y?;mh|I6614#K`7Pk8 z@R+(}%PT8Sva)XL=tFKo-u&5FREUsG$n3#C?xGZ*91Aw zakhA79b0Ia$&8z0yx=LyRvHsjfM4$y_2?1tgqBgEHjI)=fFafI?Mz%pn66$etf}#Y zE17ds-a0Jh(cCmPGkd-Swag#HAQl!SW)d`nRV#0o0?9ky>~jMtfG+Pe zPM7WCCQK`xUhq?rQGvEv;wz>@jF+K#%~jqULq!H}(3H8IvU>T>gyd z&d#ol1p`F`uyk>{rv)(U?{PP#4Ezv)8-P^lhv=O--1Jh@s+O&oV3p^4w!QSrsA34I zm-hDa`}*cCE!{c6x0&LS`?1EEx(bn`oV%p8m7Yb@7c*asBUu!y-IlVu$l+ zml)Qc+6K<)hfJkgMz}26evr{+5Na^JyL$Dix>)u%z4Ug&1)Kl`c^`4SbSOs{rOp~v zhrcF!)6-Tiad#WotkWa7bN~Pp&mvScMy*Wmwa29(wV87pU3+Za7I@`r!@WQ5pV4-X zJNMiqAuk@Mrba#;2c0-2HPw45w&e_KYikQq^I@bf8UmLDq(3Tk0=W$RBZjfI{q*+- zP!NC!Kps#$5(E{Oh*ns3)f8r!85uFFlD54MK&)X=d(zoxYGZTtR9_ngL+zpW5LrV* z3K9dUom@?Pl6z-)hEZtcfYof=RAizLqn*jspI=>xr|7n z`fLGCZ$j8XeU%RQMHliL%0)0l_%=Xg=-h&4`Zr;YrlO+a+1dzXuv^F`%MXen*VC(2 zuU_4XXoD6CFfd=-&*k=Q+^YEcBd4-$f~=B^4DzQpCQqIV`Al7+6?9msWOQm2z^R7O zd`Zb_xk1Ik^*_Lc04K52)59jLtgKkwKl9VqC#!52x9luysG|8u_OWRD;0~Mfa=~A# zITydS>~<0!ELK32BOgC%-o9Nhd`STSHVDfAQ*J$^DwJk~p*$$Jowq(WdgQ02rPbE* z)fG-&{JI&Ft#a01J${33q@3aPr;OwoWx!FKJUjpq`9iRajEodIe2RI>VhIfx8S_!H z%1A!+o!`5=Wu>Ko2OAl1%MkZp=jH%9>2JE;Zq3Tdf>~*)R-Nafyikr7#sF4aj|oiL zQNw0>iI=`kAPft0aHth(BZzig;Jtf*2h^BJV&n_^dHaFE4cFN8yj0KD)z(HvI@bvb zDy?XKzcM7n+9Y$~!#jC+y=NpgWLpnfXS>8K_<#-C70H|iMml!|V);5{{dMf7QR51;* zN9e`bA8;br*3FC#(jut#2znv3&gh=S&tJZH%+?Q1PmA#Jc>xdsdFPp+b1Fq~AB>|x zW7~hBlC}_>>D>(8k@l&#l&qRhZ%fnx1ps~eE{Ll=iy*Vm)9j*0Sc6dm?%g#wSX^Bg zWTtq!A}l^o($dcE2gqyd3k##bkhi$w2}~MX47PuqhZhrs6OYznC%_DU zFZ}Lh)mAS+y)ZCX0IM9vN6qApHLawIi#Pi2{s{xx+Nkwb`+94Tpa&rZg2L{t_ zEVi*F_C=0GtKLH^nR?^GbSF?IZ`tDc{JWz0*pKcaN(~mBCOxOJAeLkcrAf^sSFH7N>XxX zd&=bq+!@oACIT?yfYB99tf_i1(hmrbg8A*>;_d4ziLu9|#S1aSbOlZS*4#eK~UjQ3GL93P)8hTz2)G&mOjxPOIZTNMP zcxg0OIR)%X41`9nSf>{PFFHn6^EsfeDZwtxGB7~KL=j#%SYH%@{?H# z#GDAo(d9T`L;;W4;PR=w4C^X9idG5~wS%>>p5b94Zoy^{j^SZoItQ}6Iwu7RK=#=} zcYg@$*B;Ugy7=MYAxKB9@D)4~w9;9S*ycLUPQt1cS|{vZ`t^K`ozFTwEM# zKbU;}b5?9IWvGH^goZdcH~_H|zjs&}7Z+DoCjceoge89jdiw^b^k1P100Gg+=3j;a z26GV@7&*Zx3UbZHrZ6rJ$J{%8^hXNuT{q(#PL0s>(;%|_(`K}&JRCx*(aFevEmpW1 z;hI}2|5;MHSMileJ-F`Nxf3JbHD`UA7B}p`L52_Cf1kMZe>@^bl8cjhm8R#uc8>LT~=XGXu2 z(~J7gBEu9C>qOS`p8@8ww3aB4b|)9=f8P$4M>0b&|LA@Azi&D(_Jr|Aj_E&EnUF`m zusJoTlN=f?i-%m!WN>_)1D2^Uc;0FSZ1z;smmt0k0f(Z+*ruHG3i5zt!^;mpV zsCQ}Khj-m|aoGThW^)3P1{pc|m0Z+2&J|8Ox_H691>~5>!v`j$Z-f1o9w?&H?Sc@5 zE3jncRF7^!p8`eb7I{4CUT2pth+;u3IJ+}&zRekzwlp*nfY1@g^(?{=Mb2G0WxLa% zZZTUau|@cCC(7e;M5&{%|3aH>G@n2Iho!puShG)f(Spog*jbCBqNlIlt{FH?a^;Ot z2BAru;L$pug_$3gcLUe%<8G--sp8||4Gs-ePH@%M)&f*1S2p?Qs#)4(N;>*}N_{;| zqUSwvR`qV{wk{jCF0(WJxBhfR#hJa)H`4DE)Zn^_den^}96mx%ezcEQJ%c2<|6Djy zHJNkwEql9YXIQ{w1ITk?AEf$Ss7;VxvBdP?FGNG20M)&I?Xr)51r~B~DUvgy)pcsk z-XZ6AAjstj5&?+P?$c))dwbs?Q5!2O&Ft*-)KpQ+cd`?)F|zFaxT|w%x5*rznoyD< z`TK5)QX%UAs!W2T57IB0Q3mLzV{q_EDvKI|fRvtOMvhtrL9BPyZ0AeK6jM{=x;O9j z;=ZX9$m}EW-DI_For>;LmGO!+ef^@01?7U34?U7SSltaAWdM7VB==MOqkOyw2PzjK zDzG$tb_2Up5ZGe@{qTY42vc1NF|nBF=pnEmLIVUR;>0T?_5rpr6b({Xw& zZ4k^uk5f`SVNL+!Nk}fn`=?`I+xU`%%Dd=`)r-(1GW?(*F#~-?da)u}n)j=F-#oss z4i5dGp@L4D{4?3^&YeBJL|1l@5TLCJiK$?`Np5HmLS&7M8e#Z~AZysCzn9e;|SrAv24YuxY7)Ua zp;4P`8T>mSuzd^rJKWuE3$i|fzyK7eMEm^<2Bbin4HT?#xLF|gklSF1X1Q?#1mEXZ z)KL3$E3zEz91RoQa^R7qaBlVUJ3D=p_zYU6`Y+hH&X}kRyO@-SoE>nB%fpkBG$1Kq zRst7ld;7NPpBDi>>h;RgS4{Ki8o#fGgyy{9`1wc5-4n zC9UR^jOQLJrz0heY9uG)VP#zbmvYaC$h+XT{IfDli^xJ+r&DJ{nwejFjEjJA^`^ew zBonMfR5$d)?tKu1chuqA-4&FmuA#97Ds-^nqD3j1j?m_dx-R14Pm~^vD^1$?T+~%o zg7v%z)NuUQFLQ^FRQMuE*|hJX&Gr8&t{6&0`Ud1Fw~b%El*GZ=eW{^TVYoi~1w%?|rZpg4 zJvLRSp^Y(DybP;dsb zntuU9@!-z(vS_J^|Mq+ptAcrin!0*)jy7zPzPOFvLTogM0M+bUe zD`>9T+Lztsy0TeBEy7(ezg)d}6VLgA_ib{rmXp&O%uKFbzplf|D+kQ5%H_7C=t%ep zw}?pQA=Bb5bOD?K^}mj9jQ#zE=gZkd(p3}~OeGyP_-!6}g~Td5)4VJz!-pId5orXK zq7`-oG}9Y5a7OSw%=S|%Xnb9E_V=HHu>|FgXS#6%W%!-0wo*0%J+I6zHbU&JtQm`n za$NhHR2mr85fKsX3QWAzNc*t-E%eVseHk{2BtLjb}yzYrX3~T7QDY+teGtKN{hQPC$0qF!adW@@{ZZvVkny7#_gF$_l)A8R7^W9Q|s9goJcb!Gdl@(43w-3+Zfp1hxy*%=Y(h zFgZMmEQfyqlGqP*z{tRWg_(I$#rmJ5Bmd$0ga3Y5aq`GL4i4!=mdp59{rz*ly`RJ= znOvNIovOOdts;70=#?Vwdgo3QXY_XaUt$wnV1h~%-LO78Vwk0ig?A*)N*_#{UBM$F z>N|^cdN018Jk89gk%M*Oy^tWS;r4qM(os=lUg*LweDjbZ%3;MHmfB%jQ#qa3tp}2Q?#HV^` z6>XsyNIT!EqjkKeFl#NVVB{0z<{7AMpsm4&rR|^Ih z!!o0+k5lwjbq)e26++_*oarXpHdf1=^7M~_OjV0-@gLQENPj8kR}0h9hK9Zy6oREG zBs=|u)X@l{rKJU6T(s5`;B|HT3BCqrr>aJtV*RjZ#=TDR5^;vUC=g4-}PeXfXw{ zUjE@FTKx82E2n8MCB95hRN=g7Vk`&~m^e5J1YKXgeEIm1c=##=Hkk=77$ObD9!9&C5fl>ik^z&=0NS>LkZIL=FhR`{? z%L+czyMcH^0?Z*C|6z#B-I+qUDD18%Xvh=nG53y_zWvM)Mt?6LDJjXxNf^rwsdfFW zSS_|MVT@cA4lUh^fd5b9xyZQ*7?x2u}{oiAgEfJX!I5cWtQtYY09zL zqFr*3b>3N|priyJ_xktmwjjA7aB^tiIz`q3dO=>_{X{3t(4$>ABZDep$mMuNV8DH$ zDNN8G!*>b6Sz!ap6LH=%nfvW4OU=NRRq0Y9#jHUpcuveMENrZcf{pGNV*$ei$qi^&ydpY6CFnHz%A!?v*z}f*Eman# zOU=#dp1X(bF@N*PO)k4Fobw%>HPMzt9!k z8NC1ZunGnsuvIj;M_Z-K*;*E73^I4+XeCm>ll%C#9V7_dyBtop;`&>Fsi5Ax1>Xwb zLtynZq9^)bGsG3GfP)bX(jo5z$q@vC_*G>kS-j$C%+CuVY*t8~Z!p_I7N9-10ZtXS-lRUV`GJE8z5r=tVPSO z=qg~KrKPpIiju+LxE73xZELfHox>}9kJ$5v1arvBeQ#>LSRWS@3t#uIHwgD!b^xOg zRL57Y2hRKz<1K>b4rC(~)}|77vvmRs9KIS8nUOfOg3<&=4~`5UC{`eS#bJk!f48-@ zh4vI@C|aD6co9$F;qHFkM`;Bnwk}91_UihN@?vbE`qso74Z1?9Y*J;DRK!F?e!jkh z1OzB!JvfhU-3xRgDyqk-C$6_rBM%FN6(Gck!6>9p29@yo`WB|+1;PDVyn>di4O zp0lRVpc%VRI=!;AwB+OC^Jz6U@x}ffnbKN2PYp_j>A@%A;&U*h%5G_;ANH)=HLr~U=S(V|oj9G+B+VQwNr$ zg6T(?+MdCYJT&k+orAszCYVbI6Yw&4F5U>;du6ZunX1~=UGeX`k9k!InBErV%He1* z90o@z0A~ocSW*Jhn`DvG=$bSLqIm7`t5?6kji&!KMxJu?eYtN`VO!fN9NPqE7$jzs zfR>8NAly1=<13q+9G7wHjY+kwq6*;@B-|HB!Qf@8fnn;a+o+`*O#xr93Ny*9OR_4T zh{*KBMAQ`ekt89uf$9x1kN4>}VG2@N@mM=qYI4Ju@)rlXJsjx+^qsWw>WYj0XK`oi zjSodPcMBYXu9-$-aKF(VAUQZ*qK>@uJdM<~sB~A`qHPW=5?fzer-A!)cXxxg0nQ45 zYQtmIK3Q`;%W9_30`j&5Ml*#1x2ZH%(6aoZaYi+8KRupuhm||n+XIc!1g3TKb%GPP zp^7++{n?$E&_Tg{Mlf$ESp6dSxk}%rP12})*M+`|;FN*p0|1|dM%o?pxvW9uWzWmE zKBuG8KXDpd!&Wdb_ym@El%=QR11CkPNh&U4edi7-HFepbBQq)mFHi0{QxW?8Hi80~ z&2NuChev?&x?QHHmkK)#G&NMUI`tb5JZ}`ZrI9WsFlTPCFSh?c7H0!^G`S?Nqb(-LsWDr7XYrz6mYtHTXi5Em*T$E8n&!X&K zIi|}y$01HvWk1MexUEq{gZK(FSxGztAN{AbwYy*!GEj+WyirMMS)`k&Y48>fQaU@A zfijlZX9_|xoZZzILNCp3M})!-oepKo8ZT{e8=UKShBJ|3DZMEeau)0SGImX72#>-b zwG_|M$W+fRtaK)cHX^Rj71x}fOl0Bv zat1?qT)t>J`QQJigd#`*fAqPcG_z-1H0%%fxWN|+r+!}*6j%c;_VlrL;^H;hv*UJ1 zcpZZiXtLAVpwAAV!vminda{_t?vk~OW+ zEK6xgy!K>SWrtSCD{RG66y_G%x7lvNviL@hPEW@jcanHf?>rsj)0kGiZ)j*J?+S}p zT1x?1q>~teK-|UkL?|tAy{xXjbS6rMk5!k09)XOMzkW@Uf$P&_kHL7zQx^n&g%C}! zufa(Wu)cqR;bfWKjTm{ffPmN!FXZ7A4iL~3n<%ni7_O$Tz?OS%#&_lj`H;E_>xNTz zFC85PHbtgYRBVFj3y*xFpn%DVD>^n-o}9wg!z1}2rf5h3)lh*WtdF^A+sh_3JEl9w z7LqJ^CFNUB#<+G03|-NRjo8R^%hEqAgSXsElunRg41qZUNa*I=nJAq)0n{8PF2r7e zJPaMu24$JZ$j~j*-#b{7hx6c;C};s4i1k1U|~d!nQK3cvdbns(A`)ihz{rG&UsPUz?9RYTlJ@iXIHyR zcROf%66aqp!0B^5Rf|+7^iB-etdAJES*kMV&Rb% zh=Cx9^JlA<={Nl)Rj)27xsmyy@M`qPm(udY985${MU3u|Irlb9eZh|q*HhT%3@&z1 zTo1qo1A}GI(jv=O0c(NL9!ysrK!xtF;4sE=uvy5dWqe5<$7_Km2dPPdE@W`2nA!SZf?>TFkzbI3W@1(OthCHW#i z_1#1i;jf#~4cLe*WNV}srF?NObarCMa51~@Cj!DbIXW6OUv=)>16FaN6BR+-`V-7< zD7En?|DMGw8#;CYnEymE5U;5}t3;oxwag&akVp=3TL{{h`CT`#=qU=bm8RFOkgMz= zX*b1wk-d0n34sjbB85BHy!Cd1S0c!SB4i67Mlq0HTfWNYg@rbLenPLlSCG(#e6GQz ziU`kqw3@t8^gfl3mlqHzoGjs_$j#1%*(vC*2X9D+uO_TBVs%M9_bix59DnQXEcXLR zr7DW*}L2r_CA-?KPsp5e*JY)Tgyto;;qoiUZRu?JnUN7HhI*yxKL1n#`05q-92 z0YunYVsrM?c<|mJ-AU1|fAT2Sed4l~)(BXO^a{11xaI7{v-^?i+(<+}p5XXo z?G!Zb?U1LR6P`_8I##0dkZ0H%DYqz}G`f6==GH>eOZ_n;)1sV~&RYsI@~#O3OII(k zl{QUWE6ivjoL!a8ND8(O&c#Ky+v=I~mVuNWNAih*vQd7d9XoSk2~^uBwu_a@?6cmmNnJ zvSo4W_pMj_@ZGUL6DEV_1x{at&#ph{=cmF}G>^quH98W!bsnung*v@_VIgf3g+_x1 z1ul+38T4B?t)TixFKXb(_Rz(bsdyIe6uV5nw&3Qz;IpWgI1}ALLPpx@{fr7{fWQxjr2w!xy1QGN zn5az5X0LDJKQy*}HHn$t5U%T5HGjh98%zyM1CXwBX2GS@)>a7t1{xf$N9pfAqoq8_ z&GFobB`xi0cRNr>!XT-dvGEk>WTl{KPo*NFNJJq9o1R#_7Ly;X9G)^b3(Z~QH6JqkoUc7={UR@KW%URjk z5jiRL>Eqz?J|^Q+)7N7IY2{Aj;#U32cTdrG?efjL$03E$Nli=pToh;RX0$&~*HRwb|AIl=uMp{usX^*Crdeu$KA_Vsdcsiw zsKd)!TlA!)7++JM4#R8$UT_{6i?l~d99b%h?dtUuZE9*N=-okBfiyHUHYUf%<6XLh z!}y3kJ>37+Fy9_B8SOPai;K$^9}EW+Fk6vVO8x5LIrLZ}7zi{acoou;%=7rYrqGvC z14eP}F`Jm!F%)mMCTb5YjY=#e{A8HAUaW_g>HF`~$Ha}VRk=$#8X6`K+&uiH>O?zk ze_yiwHLuwuew-gXBCMVxI5_0*nRdSisR8%`izqAo^KH85gJImhr0M9D*DeA0WHDW0_i3bXXC_`rO2K|s6fWr zN=h+MuGJb`ym=zul+~3xGqRv@r+^s+&d5!c-9|dADoHpB7dW;lcCWYwEQAiqof}_1s1YnwFt%mkl(0kv}6nLqY7Iq29^IVux6*e zO(|zX2&c!i86&46&ADX)emzyZ7Qx8mtn=_4PYm8Tui%AwOm&*xr2&TeP^z3tkiG;N zsRS`P&Htpmk$0*(h;)&<%P3MzGX8P&T+x-HP#oQDi?!5)udKYh=vm33W0%v z4i2pK6r*dMU(jR>v%iAp3cPZLt~R23ry4vZ9axBDs72Um|K7I=OU91fQ~O#>#8d2S zOY*+nK_eWK@&Wk>w%WQrg#5&&^NO@reSDTo*%|GZpLuT40v1jle-T+;KEBx}9UwrjsY8-G{` zr1vUFWEjkXR+pAW8qx}4bFJ~|`PscvtL_w&eRSKfDjcNrA`eS?-%?xk>}9Vr{wrfn zZVnDTb{G3$OMGyCH%ac$;0k=!KJadm_;&{ zuiA;$Aszc!bi19PvrZe1z)v|M*jP3;y0c^tG;HKDevGy?nRQaGF)w3;Y&h7;6`+l|`IUUm3tQvPFcq1j=IMwnqEv$6M zYzw=IQqZ(G?JVekG0c5teDOjak33g{}bw1vT3{ z9&l>i`)FrsWkt{iQ2b(%9RMu2uD<@l6D~njPzYJmbWn7hx@_uPcRdw##0Qa;l?{*G zBji;@3%*9*vD;SHP~?b{xL?vIlDAH{;ervG7QR8X2F(d}4i4u4ap$l8&aDDe>>G4R zkoQAFLO_9ZaCaxRNQHqX$~W&&2fiEv$6+wSm8fT@=H-1{+6CKu7J2M_)68Tx-(e>uhPs;O%3y0i$4xCcQ|dQlRJwUZVK0 zz!2m5!puA&!nCma|1tI5;auHlVO=ebB_R7u{vUm1YM#{>bB`aA; zA$!Xvl<~ct&-J^m-}&d9uA}1pdcN-GeLvRi=keX^ZDVbezge_lzxyB=;`X-NO~YN z3W9*j@3l8IQE)w`CqzX>y|K_BA}=m?Z%{^pTHQu z*x3VEy4UV3B_vYN(RD(tgq{stWtT%-osPs7`#-GV>>mOR6dDTmT2E%U-`-pK7=3x7 z^e^6qK<6Hd*Vfbk&Ta+C3Sc>guaq1fqHW)E`$hCzU0%Q0q&g{y2%0dRo`k+HGeq_; z5e7M&%F!kysdG_gp_!xUGN4;>9VWYZx|&A144f>qcX1zB{T+DINS3Pp7Sleo?hf}O zii%#CC1G}tFk7Bqu=o*NSa=7U0}z3JF3dS+0ExmLnm_vTSt|&gEMx?+kddg7q00s$ zJ)fb4(xQ^aNq&q(yUp!mY`^+y;oAw^Ux^oq+eG_)@Lo?^Y%Jp&-*6&PvP5dKvKh)of?b zH7EkXV|Oc|59m!$a!hvyNwksB(BSF|gBDgpMFj=nDg>%)cfh$oirMnaL1_I3ISYRQ zNC67a$w@HaCd7uroAA_*iS;o*npuxr`BJEQ(OwxGw+Q1Ov_h^owq@67U>05eI`Ik&_cgS^|?{0%ti1~to$vqLAt9q7Hl7jbi#?(WFOPVwqWlJ1UTsMD{$&P zAQ-P;Ev_SKLi+Y-2=sb)zS)1$G-50pmYjGqT0MXW1|A=-G69*cY@#^`4yzb6zWog~ z2h;w$iFV5h3CY0htV!_w7}RaFw`Fk4HA$1?lv)g$L?hYLv@FypGFjFbD27OB#1x=6 zy(b+c`;PWjrZ<)B)SH)&&+5aS)XXB*Ow|uhCzyp$g7-GjLt+@au~7Nq%|qY6=eB#y zm`m%sU5FBukwH!)dtyLEDyLKMpvf$yLM}WJ0gaPS)Prf`F!YO;1dL?zp1T)To8zyv ziXBtM(D6!2HJiLXMfo4C6L`6^adAz#_98c%;5(tOCF=l}(b(8HGB6Or;_z6noGeVr zBctSqJz(uTdyQPl@xEuSai&#!@@KRA!}q=)Y<|NK!1pf6mM_+E3a;hJ>=WU^uY6 zKyi<)-GTvIE6+~&ft`NWMH<)+zHpSg781@PZO{R_4Rz^x-b7A z%6f;E@L4v3O0IZMP@3|HHOsaqBx76{?BiTDv2`UEd3KG$Fzzg@BOxGPtvw(qKE|K3 z@E%&}3n^&cib&#S2R1L>@*OB@l6(N3Zdz%w zk5?9a@Sw7)DgcH>7#Xjx+BI2a{}9__2q6`fu@7G-v~v+86b(*GwCnrrsZS{VAl1^; zl0`)`A=G!ZAVg-^ZBjMqI+qRPEn4Oriuz(V>zb)S$rHHrFjR<*A*!gqf)LG$1?!hm z%Y;(J={%k7-!B7iE7Zf9hQIyW-`CZLOsVZh&;I84&zm>#L&R7yIMg2pc|S%n1ZJd(fgRI;3ALkl9W5R+rRy^B z>ZW@amG7=x4_BP2*qE>Q4ssRpL$2Flc$elK2Md@PCM8zVhz0AcvE-M4cY${KUGbN1 zBh!R9g~}(IFO@mPn`362k%9}KBR`n09Pw}lS|UJv-r-&Q3%bj|Ai&3X-K3yZ_x}AO zWTv5^;f)vqaly891-B-{jV-+#Kk^Ak$3$Qd0!?BbYAs8SYv}ymI#(jckPD=hz&*CV zOdxR)Or4}y($PWtPv3fPaqre8&op?RuD%88oBFPjn+4QBJQ3VA|8`rsG*oUs1QUgp z5dO5%!orgJ#hWy0+8Y7O%86eM(u*V_;9`_sPaOE<1S*F&aM#ldYl#z}L~@a`lcH64 z7m{GJXQVfa-A~0?upNt5e|<|$DKpx;965OFE~Zb>#O8`Dy*33#n3M%V86)@s^5H*~ z0437~q&duUL|0kTJdT+eO9mGOF0qU9v%`a`wKW?i@kI(FW8(&)gNxf;O8b88O+?rc ziCo`iXI15d?U+7^5|!OXAzuknPX1J`)^ks`4}2yR_|V(R7ZY)jgNHmbc79Kx9A%}g z*j31}#$f5d=V7k=*n`M%KK)^xPo+4s_3&X(%x|dnqv$%k}Z}XOhsMh1hzsASmi&BXgkl&w~}2 z+*gtmrg#1Tm2aE>T;O^VbhC>hyG_e!`livc3?S(M3g^#xz?7-~eStR>6-J<4=FPnE zB>}BGG&qQ$r@$?;id=45j)&~TAuufGD>8v^_k583T`Zl1>2?b^6O7=t)Mk3jsUPU{ z67mK;FFu%$O5QoY3Y5}(L00-+`whxn8o5GgYwK08?>r?yKt2&thWUUh$(d-s5KCpe zqnqX#qT8JC*1d}9;~cyZEk)6g?Dr9v8Bb~`remzyq&W}N^XlI7ye-q|@d0|`@j$JK zzP>`|i^2COM(zEWnv=Q<-;y*!XGmhY_}#1Zx-d~z>6bb}Dhv~}pUkQ=ryvu>JS3No zP)9ROdbvb2dR3-Ud>S=OMNN%1jOA;WI-g!0ABsI!r@4a9l4H}*)MOAvb>}t?+JsQv zix=n>0=Hv&x3;&Dg3stncDufaR{RmGfBdg=JF^nfi=R-yzyVwy@?9JAGEF2kVun70eKUUXDsyjAqrGH3cB-?_ zY4mHtr-RSbE;mtvAoR&pEd!gQ;4jY!c(_jmvhS&A3uNa)5Ez`6v2Wk_;Jt-HRzJ<7 zGX9Z3!jU)Ax%2YRjB_g<0%rkFaRw3KKk)i~ zN#=vo3BS{v<%W8OTslMmxN#u}7mUP1`ex6c0R!#=N&}m^T(9Y;BceyDt(k{c)CIOm zh=6O?F#3 zf$`PQAhss5L}Ya-N5dm}I-}7kTGm8zCXPRqWPUn$!N7A>aPJ(QkJ_yI2G;u#?q-xl z%=_f&%7GSY(bYg(#q|?i{&z%)$vv!o>Su*i_Vr`Vg|X(`2KxGa3hJe#sg$LMv-G(! z5ANM_XIQ2DaL7vh3?B2E6mc@WTWUr|zQ zfslNd`^Q(53jz~EwO_H2G?a#FTft#&p`mCTTXQ;F?at3P^} z0%{l;!_@maKEGiq+!u1xg7JQTH=B&c(62oA(I6_qrp_10cm%h@_o@q>I}3y&xTwc8 z1>6#g`uNV<+h>#oBDnBkdevC=zSL0{MjH}Fk$i;Lbggf^NolaEZ$~X(AXbr%K_#h@ z&e6S6(Nq$7%5HE(7K66)3(_o9nTt94<@#OriNfS!EK5vszHgZgTus>zaE&>y@=r=7 zF9T5Bk~el*UFAd7K$fZEF3Eun=JZBm9>E>d69USURllY%bx8~F#R$?{XIK1WQ=y$8vyz5QZQH=3E8-y!^G>=+b1dU=g`0xLt?v`CWNiWX`m4cX?||Z>Eu@{?eoJr)Yuy zX`#aHXJZF_r+eSyP7B;ZI4E$t!^}i)*G0 z{Es8Jzbr=KxZ><`uXJ-6L@pLcv6r0@v9sCzlzG+q_}Qf~sdA+ee?#Y}=?@gdqe@ci z2EZ_8Kd+7&kxy-%(-(MBxU#vLH^p)I<|UveRLoInl$9Lg9nObpzl@_p2| zR80*}K;E8^%QLtdpSF~m$-8&`XwhR`p8&M1n*E!eS*px!4i+|t23yMeg4kRv$1kLn z3*BgK6FPm4d(4qsDvpBD*f)fi?pQa5(v3p`0C6t1T!!9lmq{nufYE7jAy@AR`k~rk zn_F!Pv<8aIDd0u4so}W%NQX}AWsr9@HmXsgt-)yD6(G4Wbsl=fMgp+(GV4Z|qVteK)0Ik71&mAYUBV*;!cFz3KVl zqlGA2jbmPcB4PR6ko%}chjvo+_mzl^ayAGGNF8`H!+Twh@1oM;XPp#kV#fLFxgfcu z>}oZk(I9>?pU`1P*kzX`CCo0m7W@gmz@8;sS^I`He%UOIa9_pLJiHSwbS8w84HQ@sIl}ZrgiMj!G%AE=Y(92Z!tZX$J+!!c@r*nyb$7gY$a7ZSjTIs)a!IeX6()D5~`edM#b~Xlkju z-1P}ywlyT+x^V;d1+g@})d95tIEbH+;StL(qo=*STuIS@PKRU2Zj+dfN=@GU&t0n8 z3MR_?GA7)q0Jq*tU`aAg6q7EaH3~PngO<=&EN9Dx>f0|pORzX?Z8Cr!>?7*jI1^FL zkQBAR9WH%Go8^cBy~OB`U%OCEg_71lXAw8rUjA-71YCbDy;WL?DXbkK-rU)Ds&oA& zpn$=l%e@~xOv-Wj=-ektvLP1baeM{e!Znnaf8FC>oAPTFq&el1iG9LkBbLNaf(NXY z?n?PwiU(8{I&nTWbs+FwdShj%&P2RX?@Htp*qZ-af3|DLt+PlH)4G5EUp7m7;KN+9 z!ZTPOP_XAY)r^jM+%)?Y<>W$%_ zoJ5xq$ZkKVpO8P@eofUZ{eg64(4Pf|o(pUAHu`_Hp-|?QXe6T%Ek*Hb&%_Na*JdWl z0;6Zd+}GvF!o>~ULpfUh-Q@+CDAlMqa>Hz62hG!o>jQlq5-kq3NC=wShm=^FZB z9+h3_R*d@TD37AmPr$B3JodQ%$K4LR-IdD;QO)a$r}i}=@8iFsAa8oMG&GPJDp7D1 z)w!Z5Nm&Ux45ty6OX|?7G!#vQI*0KF>2l~>P_^GX4nnQYVp7UfWhRSBI!1n8ft*j( zO9>bUZ|0{N?}xcC2t&{vS&Y_|eBDpzRLSupbJcBmGns0{@u>5W$1+_%!>kA`lA?fM zXjQ;;fn!D6bTsd3uzOI5^tx!l3M#^!kE-32%RLdas6p>qFpx*oUj;W8>ivsmNm*VW z&i=EOz4<}VUor8k)o#FY+)$psy2_hilx*+wRU`giLQn65BI%Sem0)AtgTnIQhd(vh zr2KZ^2lg$f5TNswKo@Nb*5q`mHmF&u9paSHW8YnGbH&%=#btfN(G!SN|B17zAS_En zN+B%?wL4QQ*#dQQy&EY;RiRi*Sbqn{Lxd_$p3k-UR_|1sp1zXrN{Cm>FK5HI^nCex zEzc(jQ8^cjAFGeV*Y#@37FyX`pyaJ67n~ejdcL*`N-36(&nMh15P>0#IYr3^?eGk5 zDVPU6RE(a8E?52vTPqEn)&UYxWY6wIV_wlE^x>h0F)5Lh6VmAKYLDX`Rt-`}ft*8e z4^kV+5%k3g@Co|twV&E0RLCy&iJ%w!x$Lb{(5`lWV6)fT6)I`r=iGxT$iB}~z)W?U z*Wo)mbY06BnHWK44fg$2hWyh+)ZSWSZ9`o8oTxt>1&YTg68Z)v)L&0zs>-uJDh`m8 zNcp(m`#~>5{Q1xE;d~N9{&gex4B-Mh(?dF!qvr$qD_ zZU!)pxQn~Ud*$)g;jN_qsEMm>L%3j3mG%j}LCX9V%KT4(Ax&9pOQVV>b}`hBZ|lVG z?IU*EE=JvLA`3i>>dloL|Jky%XOkCo0VuW!*$XS~m~BBcc@=!pY4_B<-vY2n3?HXe zD0;z{G}-M-rsBvP2bNV{4$8RC&=2xaDVffH`xf5tktbQ^-K`gHO({zEG&f)7=tVru zrSE&?-ujC(Bc|uxqsp`wR&_sp8u_GGn300J%@s?vVdhkOJprvGQZNjLaT-JexcJBw z%;3Y?TPaD{b*(v&T<>R<5Zzg<7%9D>_Ov;-FW$z2U1gDI=IOVx+ujs zoRHS2tdQw*A@AI*uNX9m>&f%qZC;=A-&@5yWO8QNZ?GzNdZ{rEEN;F{_+p|#DVW;2EA(9g%9n~d$jO%Ox1D@92Hmt&$XHhh zO1|$}Ci0NRmCsEuDujSM^c#V6g}<;70%-x%-J*MKM~C?airFY~Ad zBg!O?CiWV*$C(yJI3 z{h6XBrsLDo*oZ|}3Ku;7J3lzmln=hV9~DRqsYP`$rp`cpcV5vIJfmp=oNWuJlqE zzqt{CpnHCtRMBMEbzdg3!Vd>wj_|QMSjzutj0o<0XT-mJdD`%e>dK^bUd!o30^-S)UMBAE6uvZwV}V}fCB;e3@kxh1jr98$Z2ha;2Rji zk*{A~lK8+&Q4QfQ_jJm@{mTKU9T20odA@5dd`v|*S41b4W(}IfHIV|1lme)%hjCPL zz2|)UKM|6&_?~gw@uai_W3Ed3>usl`WU)3A+HKzj(aO~y_Vdd@Iw2ZhyRn4KSIu<` zw_ehRJKt53uB`8>sxs=DfH&k^Z$Fw|0%MPaA6=25hu7*yM|E}l_*dl0hN{%i#3jlQ z{gTZ=4|0>1;O`IoxKcNxx(ta;6zTT^zSz{!^Z)S??Z@w-z#m3@SR{K--}WNsqNThX zi{*7q&Di=;@3LDPnOary`R6bSSsTWmVuo)5cn1g|3>-|@AsDm>xtEjR#zK+=IcTk7 zk5q6Q(duanEPA29o%5P;0^e=FRM8AkM;g?BOWt2ze|{S2pEtGqt!|wAdr&Nfc>(Ym z&r}5)GXb^DKzYS}?)n_sFLO1uVE}7x_B%kJG*I5+|9;o~k7fGazj|%2{BFE>_qMM_Yuxg|*=_Gx9w@ij&MoC|1k_)9K-4F&-h;0Wixb5C z&K4svkVC+EzTc1!!&G`&+B0Au#dHxrAb9TS>s&~HR#sMaZd!aH8gz0)OkzhsvfJ+i zAHa$sU?pg){52e_lRq;q*Dwe`z;qx0Q%GIZE^Th`AHX-l;kaJq3PM6yXCHkP*@KL= z&(1e?%M=Z9N?1I#*8yq}zxFxC1W|X$lR*G%`~tvW4PgRM?&m^|D@dN&O zt*Oy!SV4X>%ynBKJo z^d@DIeaG*sB8*4d~D(X1WOD~&^vnZ(%w%5;h%6S(}R zzI{9XZtOz(6z9*g{{~knD5%Ki#GukH)P!^zeu7x7m&y=v|8&z(OX@kOfO=een#;QNo4xH^N3W$Sw;zYPb}80tTK7<`EyU86f znB5^2QT8LiSFlQq3IY7JcQ+cjW*x*=&ASiX2U!MsFg*2)w6w)T4dxWz{ca2=fti{< zTK|(t{m#QdcH0~`dEh*2tPKr+Le!Y)^OH&76J$=d9#uZ;eMt&u@TREQHXfjp0GwN0;?gtu=q5HB{6`f>^ojUDJoHlo z&egn86axu2$G_`FJ{Y5z{IAJib-jn7c56~@^d>6aQNS5j${3HcK{r`aQ*JPhm^iw~ zJhh75G6YBBeD*^7Ww7s%=r?9{FY>QNfx4t0jWn5Obsv94MF5QulS@KKNcQ&VnCnY+ zmtRi;0Mio7u@B;f*Iq$EWDmM=1B0gT1|)BsgWH^y4*&1{T8>r|PLfhkcoA!`?_o}( zGn}a}1t-ayBr|>U?X%>G{3xYMH|g)WHmLQaAUGas$}wJ)MMN%WB6NHm5BoHYzX;pZ z7<^ejx=W1J#;BAG@<28E0aGQ}xzW)D0HoR1@~G1zKiW|6Nw((Wke)eeJ{Q9m6-ycT zw0r>gIVNSw;X)tk-Oz4xB_%BJ28g_X3!K%#dm%h=>ox*LMHGAy)t|;>^qIt3%AGv74I=FP1812`aNDFI61$Ym5mh<}qm*8I8-_u@IdB zi6lGtf=TLahrOXM)?TC;O9Y*@Q%37v%(TzvxqaK5%JWleU1tD;{_=rPM*(7gT!rf{ zaWwE%dS`*~;br_jgAlXq;SZ3^25r;opbWAkv^Hd1rnm^;DIsCvA6%F)KN}-N4m8o<5of@Pf4Nw%n{$ z0qg5cXj!_CE-c!DkLc!$9{iqZOxSe>l?UAC5b-+Nj&?Jyu@XW?hn$~h2qfw%ob-sD z&enn62l5_4{h-MTu-zochQQYAp`J9gEmtjJM(fr3D_S-*uxB(Dw1v<=dhAIWPvk%H za2w0`Vz+f`gyAUWi#4zFXtKlUciox&FA^lXqr}1P=J<5Gfh*0}bL77o2s^r}T@xy< z=~woNXzC0&ybcFg%zRhV6zHCN<{^pD#Q!hb1GaZuz*V0m5p)HKqK`SrDWd?&T0tHB zrixhbYIQq#d_vnyAWvBevq_6-G80jP$t3AY6?b8f9}QoeL3ZYYDxcV>C4`l_`I~T2 z`7iG5L%e=3&KM5flZqQ!Fe#dWz&Egyj*`+hPZyG@4y>DwWCZgDtgfz3JB>NWR#mTj z_N$cPAjp&f!2+KdWb(*fah#>jaa%=g{cT5Dh%Qy}t}ku8iKGPA?-cJo;mOGfB=?P~MR;fmTPnxDH@dgrm*Otjc=M^JCC09^Xo#v+XKp#ytqD|G;|N3EBww>R1Q^6(N~kn8tEG^40FEi z=h;lA`fIpgx8XLpXF2Lb|1X(qBl!!$eY?Xh>EGp*B2y2!Wwfib$U!3k3jXoL3tKq` zBBqg10*TAff`+%fu?qXe0WgS6Qw~k;FVSQB1B;@aFj}_K__0;)g&6niD10~eTN;b9 zTV7&xg;K!wL7*XoCm;Ib&^)RGr56f9@7AF7@V1pulukE%}KMdRlvR~e#Iz8dX zgdb}_v4j--oh03wcfIe0ky5NK=yFcOv;(~Fr%Y;rfO_$ zrgi93wa7wO7bFXTEcO>y9sNeBig%aF&+uNGO%3=Xgx|xZ2JP$(ef~Pn&mNq`pbY_= zI~XYmdF3DbZI)_?9>@Za2T5QMIszG{A=Pzbc900@$B=Xeu_~qjB7;mCS(1rZ_^_XG z$IIWrf&CHLw;p(XA$(#N)QJPNZ6KUr$qyiImhU#dN!~x!=b(!FvpLac#k(`xoKkXI zIva#(oQAci2qPmSn7$}yn{Sp#us<@NLkIhnnY!Ls-LQ>6T&8=#z=IqEiYzFCz*IB6 zesnNZSyZ$HJ(Sqdmj|c6f9jm!ZvV#s2#8y9CuC1rX@3tgs*Q(eIfrT6a zIKtaG>k3QXUzlGPPDXquO{*oA{6og8>S}BdlFkHs9~Rh1sfv}e^^{-*sDj=->{-uc zE0$@QWa}z&bf^0SA*~6fx8A=&>m>j3Q@L1sj$@8%XUx(7Mw0Uga#Q-R`$*l+jq@-} z-2mphc$CNeU)KkbNZ43~Z2}hCKxOhvRD8jJ)9r1QX5&$GDXMZ4-KAtHV@SH+yL=j_YY=azm|3yebiyNAVo|skgKcH$<}~1L%%gSzfYo@DD$=;Pec;rHnr#nll}c3X26(C2$bh{Ubo`;IuOIpEL1wHwk)g13Yp;92 z`d79~DqORjA6jn}mkrG=HB6~Qr}8Zzbt}WfJ^K4ScyxzP62#<9D}#sm`76DDBN|95 zpFez-%#rS;!)R4!SUS>m%>*XOH4loz)9O!MA2DcVHVqI$WfMH)G!oM6B2{EJLpEpw z4oWjjfmhJyrfAzN%ck|)D1;2{SB;e5QU~BF0H*Pq)h?x_5$+f;k3oq0vz_Ua9FMQf zFpu4k;fN+URBI442IdEFzvsJsru609ac>5L1;q2azMB#O7cIoUgE|qZD-#BJI5H62 zPEW8kz>?qgyLJe?6khAO-g%IL?NdFvmTv3}rXWBAZd$C3BJd$K&br6U@9lxr8jd`O z3Z-O@V~_S>Ui=E%>nLy`e3pp<7bXN1+lq`% z`vWFH$50z~;OUy0xD}=hxq+r*dCLfJS0ebSyrE0Vl6Z-l!!0ch806qo(1OgJ` zM$5YfI3P@(4b8TCmNsZ&BOUFTP&;uOZ}e7e`@&rdr{&pT?v2S0PC=6a(p54{aU+=z6olNM1qS$q z)C-#|076tCZl~&5r;EeNubRx^u$jv6m_4SiSl$ESd^(X$<4490bEan})DPq(Ot$Wc zh5y<*dlzcDX&4zl&lxz8mZul-wSQIa8AoQXodqNdnsYaK@0soj+iiLaE6_=yd15J> zip)pzqVxSy{J7v~tda3m`@W(oqb^$o455FupIh6pC!;^|%REh7f9YF>rnY!78Q%as zDhv$@R1!TPe7q^rAWhnZe#3MVGWyOUk5wmE3h0g3^of(YbojvqunX?_nwK;a>*8X%tw&V z@mq#(73$ay8+BN#+*!VP(bNQgh2J=1p_$)4oevtJZu+$gD$cLIu&iho@Xjpd(wkWj z;32n|jTh9;go6rK4x(cIoUNB$lSrZvb`lh@j5k}RP<$Z{xLx*eS(VrI9y;3WZzS_G zw~y_GMzxZ0!SZZaH6!G^90SZja>}1J|Y{tMYW-J zx+QW_A6|8v7ZhQWP;?)wkt7tA{+*sSYTqB5gxM2tnTdfHBAs8h?3FvvF#de}j?=I!2qT zNa@VSw+?yLJQf*XTXP9mysB zyZ_doAU>bpQJJ>lO-oHZ3+MpNxNo~D4E72|s&}I$D<50xttVp1puH&PLlrzg!z7cK zu9`K6#T(7X#k2_+Y6hh`QlIWKEKQvC0SfZYOkz%mI9fGN)E5T-O-~~VtONV~C!)01 z6Zu!iTb1vyGqOc}-66yb2>g-t6ay_$_afAPc`xOcJqnMT5|`b^I0~PHokj^plrZXT zK3Fj&R;`a{ArI^BGE0DANOd>-%Uz{p8hni8n9%NmzGc|N%A7I)XNfDqL<%?flly9W zbpCg+??b;42W9tBPdZa{#i!&eB#FZ=D!e>C0u1cRN#!!pQw$$rfzZU$TfM`9ok1|e zvpO^Ph9dNk!r1&gHws#UAUL%sI5Zl{S1#mYIKQ6Qgwd^%>^IeCVw!dsqC*vk;^g!F zcZL57S@jc63V}y$x+SP{i@SaodHUgnG9^m>pMWCU|Ixq85-4^71t`J9{Ikpwh2EUx z$}pdSCK3935$I-)?}GA6AiI|)wF@=o6Mv-190d#e5SlQ~9P}?Q`R^BbR14esPyFR^ z&j(yO1DQBNKHZwO3Is(~O2v#2MA~NhZorB+d$`*ijK~Gp@%`LZ4YwR35|F}(bu$gh z74cD#o0io5eSU{(_&=W%W{=v5`@k zdTxu`vb=aE>K&nAm1V%Oq@NlA%pm;dZ2GX4uaLu zhp!ch1Y6Udlx2js#g~;a4~onBb0fpx=Okb(BLnM;J(^8y>V8`BLMS5;XeJA%=K(9F zqx&!o`elP8Bzt&i5<0*MX!9o;Km-WkQM96k1G2*p-)B6Eu`0bQrS*$0rk6DW_Y?!0 ztM8GS+08b?iWcl+>-9P0p!4RDuv6orJA8jlKaws|{LfWzFq1lLL+7_~XY$({uhz?c z#)OiD7_$4?AI>+56E@H|+1QqLggYh@O)^#(YziK=<}w1J6~+GlKf^}+i%Xehl-mf^ zpzs-4-6lXCH#6J;C4!)WED>)`1TGaH=2PNNW-Pv}+MbDIp^xxK5>bRJIcXD~h*PTm zlhM|7lp(gQU9e7%&HtkFZYsvpiy_^0`9&5#A74SHqSC;yO&#c&RSBZ?$Ye0T72EN> z3?OwjKD!L0@?a$?BK7Y7Ie$J$j_Is(cxiOEve`wZirQ1fx$QvSIUc18Zl=VU`>0Oz z3Oq%ZO;+&_xS^{E$>uZf3Whv|Be9AalBy6%i(7uXCgR{<=6P=}kUhX%DreGSE%hOu zPKk5mojOB^Id_!*_$FVOQ=BY=>AOZyccka5G3(G1N@mb!s$y#hlf}ptYkiXo|7cP5 zrt9@>TdaAF#fWZw%#Tz|&1)_=os18)wo6G9)nDUikrT4Mmt0!&s$)C2ImQ1iqk)8 zR`Rg5PCx!cV%>%Wn_E|s(zfx#{zqFU0D+g*Wvi)H{qnvql~h8XN8fGlfa5U*#TU`5 zTf_zT=ccEX+1~-+u_M4&ayG)viMS<2qho>X;Ggr9an-)@06oYEnH8Hof ztQ<~%#{}~A)tt|A++bDtj*T9h=+A`5%MRnIr}DqO{)G{UvkKLlzB{d-PzSpM%>x_U z`H^jb-+-|V8BVwR3p%B=vc@YHr+W|;bKmQ{O>=Hrma9C1wgh=kM0mzgI>mls8`RHsb(SKjF;Q*-e8G5Nv-CZiMDkGtH;B! z_92c-*4no4XLbO%&I*YS0OXP&{@0Gy?Y^0K?EaHV+z+8#vfZw8&yzu84}s;DB&93{&PSmqJhk?DFKz#4WXot4TIREPNr2 zB7C9n0cUkpRthce>tiatoe*B%H&ffCY)_II8jA^0Ak{$`;E@`G8~DA$7FKVBHYP@D zYbYowLc}w)t^77$C^}dJ2kvG7&Z3i<5pdw%DXwrpY(4CE%0mMexj+uPeSC)=2*hI-sFM@OLd&+ebYTfNcXB}5PRSu;Fm3S8_t>4&+n)RoH*r{MGCBmVNE9}!K{ zYAS2WqlgugLHZC(CS1g{I=v~?PY$0UbvYz#!*s5e4F+|4kWB^so0$(kU{{EGcFlWfeaUV*Z1RSoDob?X9H1QbPM?ex!}ZjLEQ)rD zc`M=@v$htjrp?NtGF?IX_03ht1k%I!sALKg7sNn8oIe6NN+5BG-j~_(;N(ZQ(Q!Y0 z!Rj&CMHHlZoK@bT7?62=NJOC(CWkZ zAdk_rSyz?;j_FX*NwMm*(JY>o@z;muXhxBcPE=AN```El?hNQb{ctJ{QQBxuRZ$s7 zGTDcM!zpWnBj#8apVH=k%4An7ct~MX*yl89b@7cic)>p-Jff_fCtYvp%aXdkfLzP{S?Gm=ra%+SB(K(v+vs zX|M!MH$Q{^FbE01hn5u5vo_SASkb#30l*h!s3T=uJzAZTNQWPZg2QN+6rjwnC>0KW z2kf<^jrs>M_RY2`lp*I1<#JY`A7Wk`{ca_W(`sNMmbh~3Djer7nb_22yZpowy(aX0 z9$b}ZlnZ8NhmPMd>BUZZFVt_FxQP2C)uv>dO>T5nRVvlak)40+hj}2 z`<3T~;Bxz|Ld>;T!-|B zBt2xtE9Lys5I+z1mR6~dSh=5Uo#M_^rm4dUa!Nje3o zj=WAu4vn}Y&}QqzZ!0*vCOi~+2yO$?{?jp?mQw(F6;MBNW(=8gGXaB$(>ODn`S*gf zN1M8*6{wt1ByqtaxiV00#W_{d>_CLIct-86h%T`Z}`JDwzrH)iJfP zb`n-C&4{jd%U1*)GdC~=&~%7`j*cs6BgHpxNO_5wF5rQ|PABSUPu*hS<8O(#*ZaV; zqsXR{#g5gN{}d!3se{jCVM4VtR(bEnG@;?~?Y5&KE)pC5M=%84vtmXMh8>x(nNhp) ze-?AggWs{nUq9E6UH_Sw;VmLA|9#9Nq5Eg_NAll}54~1=Z63yE1D2@4Ep|oy_J1vc zw)YjLe0J6}Uguf~Q2r74964+dM<+3>dwnM1y@NeOmQtuvZV`BBH( zoOhrNFO`6}&&!-IqL&A|r{5$02;RltGw(e4&H4KFDoSwW`tzgn@BMJ3+Lr$Hd-D(5 z-d@fRP;YECov-z>oj7=GQuq1f_rmxlXD5SIUGTd{4^u9;MW~r#Hvf7gIPWptjH$t} zS*}=faZG^@Ef{!2NSr$)qi@6&_SrXI@yP+o8)EU7)AJ|oC`sq?>*0lk6}aNj~}lFteP05#B6yfIYrjS zk;U0M_|zE}6{3TriE$iNaem}@Gp)Xi8F0GgiM^0goWpLI4*V(meo~Wz!s|q~+?0sv z20KXa9KQVmScYU28Q*kWCBq&CKZX@ett^gyy#(ek>dS{&w<;$A&KeWD#dMgO8tolF zV`Vw61HqIANYguBM^lKpZqU7@r;`!eE?36iE~>jBgXqu<9}IK9+q^T|FiKp%id}Jw zb#xLy262+}uHNC%^ki8OnJ9lw{ptAOr=yU*0R<}J!|r^L^i=hra{?y%TN{r%4KqSM zR>5Ts@EJjn)zgb)rW3FSf@nmj=FOW8DCz|XgXjoz{_LaF%wi|K`Pf7={OVfCO7O$@ z<0MXSBdpZq4LZeY1O2T&#`nLtofId+KLbd-d7 zBYz1Sg_Tl_@j{`uNPUtPAQA%pxuJo=U=MB>F0KwsQ^^KxkPo{)#6M7v)DvlO0VZ957d4FaH_QK_=!%ken69*5qxUEgH zl&6xXyJ)kr)TwD{V*=J9Fb1z0%ERJ^YSDwLy01mePR`C`%2JHrUV2sPRFd?*x$H$p za7Bkn{c&6W z&6ZUZ<-C^KQ#lq-M6kN}<|_4HRpCx*L_lk!p|IlZPR!o|N7GJ)omWp}p6i(WXZ%^F z--nS>;&@c1jUMH7Euk3=;&UwJ#Q1nFI-*;2Nxv91>+E{?$fL8w1-NjT< z=A=V`&g(0GaTfHjkU_@*;ozQT=>pm;3WqkMOigd;_a*lN!sULBN9f^pSg&^P5z;~^4kw|hd*cj9p7baB;PrgNtTXr^ z@1580GoEmsP-e6MCYjcDxGk-Cv3^#KnZJLfdqs&L9sr<|pGpq}a@fQC{3M!+=Vwy> z%{?2lcpOto_oq?(V389c)TmLT!W-09ZejN1qH+Cc(N_N=hbNO1vN3 zKNetgnAGxA{q}H?p+VFdQXFh#Nf88`ulI@|%>6g!Z+UwvV1TF51{lbckLC#dBua!4 zFfAjl8-Pn*jabOECvCi?cRZ%H1Dn0!pchqq*Js}T1NwL3n7N*3}(P0173KJkIGJ;K7wDU(I zRXyjx8vy(QsGC;GCIV>;=n3gP5@&H=8zJ#0TOYY%(=L51whMOGGJHBrKa6tgJcXZG z)#ZvF!M~>Jj3_8Iq^aPh&>PB|W`B;``s=2p?05};X8mx+k<_99VLQfSM$V5nWAodX zvu$J;iRCC(Ocor^%c*Y(9bMc2rOaWV)==!Bf4G*%8zCMe=k=?LqB}w zF3at$Oi4z?vf1!hYW6K_A>5w;>=r~=9S`8~4_Ilt(l>;nV-&i4?g|~YDeekQ{IZar zEpYc6(;31Q9HEuFouI6r3%b69zOrZ|lp7M>m2YJYSczYqJ$YDfH^wmDZOoAlqS&10 ze||Paxh_Ss!2enfkXvq;GS#6QaqBDJ1%QUG{%uMb_7!Hm$-988G30i%vy2Vlr`!}P zveTFdL&ehC1FJIrJm++sxEibayObJbNVNyD^87uCs zMmh+3!&vfTyiYortz^z>rFD$)1m+l1dEYmO{LwkvR?ny-y`1A;=U;nrAzr~b%%s7q zEFM8e$fJk``o3F#Cx(9gi>FQG@st%G0=pjR3-f(5`97{#t=BYOj{4UZrSlqoHqErA zH|m0J3z)Bg zxXn}}$fvn|7-zO;)hNVl$HjS2I-b= zq`Nyr8bnY!1f&(DOS-$HK|s1eKw4Tr1SQn(V&3)5AG2IDYtT98dG7m)y?=Xjz^Aa@ z-JoHck0munW6=OxvDfW>IFriVZE2tlvpT0M=6e?#Xv+#$bG$w9*DmtmLO@g(s-`d0 z57XRr_3l0-%2%t<{o!9KEnbz#8K%v16P8b%rYuyK^lC=~6M-mAB7oj|M9)Mcn;pf*hlfZ1P zXGq-lDkYe%UHH4)LYa?G_Iz)8H}z=+6Em~WTFBkM=Zzh(wSEOYSU@QG9#r?kB0+J4 znB8b#S9`+F19Y`NCl0+JTl*EvXm0QgkP_R%{e9|&UX6y^rl_RqxSxeTd-RpJsg!^E$IEcQP#8ALPO| z7%Q5g1Z`;%N@3DJDVm&g6Uu06AH5~boDr2oSNCT`wgPh#+kUM9yyiYQQ1d{;*5003 zVpKf)0zYoWi^S2X=5J^M@@ptRxI&rq<0kLLGhj{meCwc_XucoiugmJ>V80xwV zS;A}-?x1(d3>E%FLN^KTo2)t+ zSxmz?lb;l^8aDOhuGeX0*o2)3s8*c-=K`FCiuVTa^n(ube)?~aXq>)BIqQ7v2VP*1 zK5A2baAWvKgU3v+}qeQBE?_B!mI);ypq zW#3pF{uF6$9K%?BR1#acLd0_V#n0bnyEM$BHxDYB0m?msx?jxh2r!Nb)J*?{S~}Lh z>FG?v4q4kv|BuI<2!W4M6Co1TGQ^fMC10M;g&|f|>3x?3>fAr@UQGA5u9(!W7+Z;L zVU8#_3i;Iw6x$xxaQmDydhV~?h&Cx0?fMALMi4IN3%081U^XrRryWITM^hXbF1mta zK%tp@U?uTJn1FuSf=|_T=tCg^1(C=ZgGGf7aJCVmbbXr{yA1s z8kg0C#VywRS}KN_hjIxFpEIxp7s3{ypr7uZY-b&cke1wa#?+Pe)tV_-OI1g_mdz_6 zx@R{W7j-SqYREzyu)+2MIV-h+PWOk4{Hws4TM7x|iUsZy#tbUR??%OYbUFR+D|By< z_QyJ7hT(CRNaf-!!K}|2)O)Tx1MlAHtvRIjz_UnuSUlqZF=dKQ34In!EG(y2e}3=_TMJTXolM5JbWXn{n=~r&_3#5YhNp&- zOKtEzBQJS;B3u6QWEA8uAh3N_j>nxcd}H!}0)~a9(z}(Q&J&6i6#Gq08<}K=%jzENHT7MGWDbjgL*ad@%7s68}Sv4 z+P}B`GBFbz9W0X`dVerV%JM4;Hy^k^iGzgTlz!R!1yiqgZp{UDYmnwWe#h6m<^ zdY4GE9Zk-~cNc*jw9X$hdR1gck~X}5cidq72VS)ydb4m3^{rAmg@k1%)lF#L$4hVq##G% z<7YSdNV+dyvi=v;unsQ^+n3s3$?3_gC=F<)`+`?8$?9C#B2M zOjtK2uvH;0(RJz>Gf}6VsYWOU*DTPB5_8|YH7iyV7w6On^~MYpc)R`M)=PFSmiA9l z*wsb~s0fh10KjxR8E`9j;ZlODq%6Ik3JKqLBN-z@!)ublt&4-K@(-TQvd?k~_V!X1 z^@*?uXqPP3!rmYfIDFeoR5=6wYiT-y2a9=yT z^4fJ<2tZm$C)Vv8DsAt*Ro(o~%x2%^K*aPQuuPURyq#e@(Tt zrlI5b@}*>YlwpQ>dX@ zZ@q-vw+07ZgMIL`hO1TOhNQqz_%FxC#S8tNQP=&fG0tb%joBYv{jlzcve?3+@Lsg6 zlP(s?y6}Z}2%l9B9i_}DlPD}47k<6`bl~O7{I2_2zUgicR2r$H_a8@JQ{30im}@C; zUB72yWHh{i%a>MORyJ(LiMi0?ooQs0naD8cP(NA5th*Jupff7+z#a{u#VU>jFO0li z(9#^)uTu`*!|kW2pbolAJfV0ISm6KaZ|&Ikmersq*k@5l2;4Bitu5Qf=X#e2>xFRC z2YDwGk1Vygv5-2yhlO>#Itd-oftTgSW4xICidH;hv{ZH>4?Bvm#fK{|uV{DWZwblC z|F^rMpcv0oOC^9gIYbE3;GpbEff=JykNrPCih1a=9gjop0)qlJi{!NiyZRkdhHtXW zuORsga*3&8A7(t+@Tr~J^$?)&HvTIWgIgp`2TM&1#pl7|4>TAF*OeKl6!3q`2L-af z8Bbw}9PVc#z4V9`AYwEdXP)bn_<2u^vrO(&@_BXih>cWWAZ!83AF~ak5OlpG7D@1j zC&2Y_hg=Jz7>?b&6?nxK9Mc@sp)N6_Ru9j%p?-Se6|#2m$4_f`NRX1R@+>Smes~ss z`wuTSzC1oMazU@_%n~S>oZ9^fi;hR5*+0nw-T}C?OeR`a;<@_n%BsaiXJ9i~Tux*Dk;(JGE%fU$`N zpAGX|cDg&#`&#N{wsegd!ld`1#8`qQuD5B2gIJ~nwlx+RlxkQlnKjm^UX)4c*%XvD zbqDd^S9<5BpFs1_l{j*oHe|X&AWPmdZ?oB^wi#@>RMa-T-2p@qeJ8{W3IH(mXMU$K znR{&T^UY3lAJtB?ny4GFhmWWlB$CC8-}SrM2aUOlvrAB!iRlpX!zY|-SgwSrT6Mfx zVpP63Ki~B7!tE!qcZ>G-6GaEfm){x1TC4`0qV5>9ABB(xMS=3O0|lzr%S1@yUI=4x0(P|1WI0jbZBZ;h6@# z*(($$YWEtk@4e&>?;oN6lVc{R+=bs>{&A;=pkfeKvq)M3gZi^daJ%KUDRr!WWHtii zDi1l4BXaG+8+(5H84A50)I8lE8WuS1hxMEURbymmr3hkER((Vah`{%v!M@M(gh1$V zT08!^ z2ZDDZ)MjbEvelE&DgFK#j|}Ldt!O`ek%Ke4%N&d-VDayLxW~ zvT0M+lGeb6d=J``*904 z6oG7PNvAF$ak|X@S@2~0S6QTXi}!m^tP3nqGh%JsGcE{*YNY%<9_h~KRa2RJyCZoyrU-ZH=ivS7UMJj?!=HJA5) zB_}yum{N1;;tX|S`!`G~lO2i{4!r^yf@K+&eL?f`y{lxVDLWHnL#q`shW%5;1Bgvl z?k7`sh80sH(yR|1MI`TNC-7hjIS18HuRq9Xs}RYruh*8}eC>yJg#F9T+O}IMn^6Yy zDJD^rF?+Jc#*-&BK5|XZ>J2XL1vx^-c~BSrj4s{}@~#91&x831r$%@8yF_EKe7S4E zYM_v>r68@if+Z;b`v9AOe;X;`C)_+qVQb*5#toI+k!u5b6UJwW&#`klmF*|fn&Ibr z`99M&)gRqYM@V2+q$})2(H&Ki>)+^fwDhu8MG4u7^JUYE)2F4n!C_6WL4-CDg_6X_ z99wfex6g@7j;d=!VAqim^UnyJxsoD*@J;O5lD>f>$S?1I8WYKi4ugk54xfmxXYL=nEdSj%dAd~nkU6nG6VvA{>Etbk|>$}#suHK6Y1KssM ztI>(?V%g~s*++8ha!N{3W}Hm6s*L3{OEGc1#ClDGYc6K9^diX&WS}daYzDWaQ5b)U z@{VtIW9OjO&cZhZw^aW&fMa+a%oD6o13;^Ltx6-Pj3|~lq_DSd#Hczuq@)P_OABM2 zrgje`k})buKPd9Njrk%y_o<1GJy1BCqaw9bSv^~mRa4wX{{1~#(JdEhQX&aDK|vRR z2S4>IvUpv+=eiO{{bDTKOEJ{MGoPe8JvK_%7b=qzrgKnwH!}5$YL+w6iwgd_gX^w)^W?r z3u=t8)9i!90Ds?z&tv-9r19A`{oN6pN%A+Qia045oC`_IcDX7wI9;kH$vC@-90VB@ z);sVL7|fRfuCvq_0fh?03_%-&8CMEw494EaT}DPa1_Li{lZ?#?1Vo@Ji{ye9E8VM$ zp}e%TCq*tc=JnMkG)}ZX%tHp%Un$omQr-VV?0pZna!t6vhXVsCZ(_$o$n{gg;D-^L zjY}JAU#enFAu|fae(fTTbLda8zal4dPH-V%P-{>X+Q|vLTpr@Et<`7S3K+3S@jtA; z{qOtp2lYXgkMBSs6R)24&D6I%sWA=>>Y=%@tgMdnpasW*-lxEj?H0TKq-|W2)obp3 zI>PV&@*&^7^yiuOpWjxV@`EE2o%bWS4ig`$e)FYzu^CVOnE8LV?xGCj+6cJPIqB-? zP16H6bj8gg{rz|eiK@37af=X34TE%GU6rUYvl)0cSut2$M*M(2)K=@$wX7S zO}Ib+U&($qmZeT=&CVnvioFJgM@C-J20?TFA80#x$hC>Z#)7jxn+q_A^_c#1@ZMwcMZR;L zHU7zwuko9jhQ<%zO>CTl%oq;=n9uAy%>w0%6RFAn08|}% zaZipHl${Bl8gb#7uNf2old;my_s)F62pDO-7ZQ^M)Kq5yznp3p#+m3a6yAftci=HN z{iod!Qwr|YktMOccRyH&1P)Lw(dHy~t+^cEt?otAG2e(qF=hLE;Qdo7qvjAu^HbLHT%5J0|7} z&6&F8TAClG>rfC{RL2E6PYLzvPdw4RqRM~2`;#l03k;vo`H%0I7+p{D&b|E8|JVXu zySxO)jFa_C)5*WKs|p9Sr#HQ-yth)}6ad^X2vjbM85J%3h@G9Y{_h1RS;A8Z}VkmhLPHgXi(FXDI3&8=`QK0bQ2 zH3a^e(`K7)v9awJ9a-V-q~p4@SQt9auer46=O+p@iqFrzawj%^4xUSLAS0jzn`h@# zB4T@hN5rjC-Fii#H;S9=`dWIME|EF%S{0WyZZFk15dIqvESH$yuZvGUP8&_L6+p`Anh>XS#-ZMT>8S&)zS?QQmNp9`p$r+n(-MsLtGv0PhO4$f%Gu7f zt0|mJ8U97}%40cG^aVL@icOYF_qp)*-y0X(u~w4qp_W!JE~vpvb}Ib+{i|-Q7aV^6 zzrIIh`C!-6E$IS5>V;hmE6DsLKWszohKH9ImeVR0yo^UlnPKXe^!y=4Ox?1toTS1) zB*j>-Wr|*%k>R=}1g1cTShbokNu!sGZ1tQ)zm_UT48_>~5|t1~vcct^{LRRzB8+n9c z$+Dp%&fbt|Jss2o}SWAH7)9D_6G_#EOEJogt zzyiPR4}hV-WPG$oo$x+!6c`7pghxal;G~S$v@XYN%`-k_<~(}#bsRNnsRxwQf#L{3 zc`Y+q{wC8l9|oTiEa*T6H_7}jr%1$t@#HW?xl3t`_+MSlE;^fnS-*Tc-TggQEHRc2+7V1zZHyPXy95F>hub`aP-lsxgPh@}4v*>Lv&glQHe2SG^%` zk--mvxeySb!+W~Esr>L3iOl7J4`WbOMw@_rWNku$ZVY(l@(grV1S2|czOifa2ki$N z?y~xZkBCCxh+U8c)C@=dlA($dV%RMq`!Cj>|41%I)Mg zMB)4(fohPOl`+qv)EViaK__m583Hu5l<4Q7-vmxVi>Ap{vObAR)h{>((SVNa`JB(9 zfMjHmU6PySwxlR{YD-e&PrN@uf+PkNa^v(32~CtS%X;P3ELy&y&q0zJ`8X)?zzgF> zG(TM8=tCW35>U`%+x9Y{Ak6+iUt)&zd%Zzt91>cyWby{(i&)01Iqw*cLsvcJjb_+6R zX0V#7*1F$zZP4sWN*VU$zrVUGZ=)m8Q$_x8pV~0o7mM^4cB@LZ{QdoT$5r^_YoyqP zR|GfT8mAdpFkI{@BvzWbR9x$ht7Ov{6zm#z?*}ocb<3SIIEg4FNV9qke0DDu=irom z{InES=x0YOS*K*2XUqkN?!@UbAe22roa_!d%J>>2FqF7OPf4RtvRTeL&gAjDR{lhL zhOBXv-iR<(G7+CEs|>N?0@J^iv9XHnjd>j}xL}I}7rojE-LLnY>1B?M69U1!iZw4# zMc$L!8;_$q2LV?mq0{`4n7jRXFG)ArO0 zk-TEV*Zmvdk8egpPv6HeTLhT=a;N=Bs2^vtoAIMv>a=to zQo2;8q$~Tu1jQ*$$_GcJ3A?v7 z1-Yf;X+KCpdSn##Dgd#@PQqLPBJ)Ct{@rgEr!uc%%mQ76GG_GO-Z`R}uKnGTw7 zOa%cO4^A-B!x|J44|TVt8k?_Lh45U zhQlon=pPA;<<+{H@pBn#>%rfM;xvuBoiqNK5NOf$l_KYMnFkxrw&6jIDg=u&j)D zR3ZxEszs--q`27pvD-%yY*cf5G{>w2t~L20M{aD&E6)+fT8N`Clcw1_alvv}FjpIo z=)FCU>BBnk6m%D-KJab?o3Nd~dTM89c4YmGbX_wiHk^=aU4Lx~wEqLr8ooF%cb?N4 ztR1)91sg!^jDvOGNGK!m^mra~b$?`T)rVAY^(jokfw2<&J$t_cD^+w4OOVGDmbIr- z+nKG$&i+x^2xE>=^%Y5V1kIgT)8pS8k6(QkJo^kdo0siPM$K(#ZPvOQRrBMb$Hdv? zhpPUrOP3p#isp06Rb&+%?JLI5DPyY1IKdkg_>aKlB?DgQdjX4v7PuUumYw*&z1K~~ zjAMvk8&3;nR3?7^!1Qq{+g};J$f@1lSr_Ltt-GmW!E^h!AcOLLVs?-+5}+VYFBlYZ z-%20?&~Bj;wWbRELInYd0h^G7wqkKD7#4dA)m=d6`Q2MBUMG+ z|Aq`jNZF(215$Qgp41q&RqYBaS*y^n31u!oeQaNl+HK*rl2PL2LdZJ$rC>*qkx&TE zBS;J7-ZZOf$MEGyyQ}bQzFH}|GiL0E>23UTgT5vPB+@TF6+7U(xt?k20?ip{pr&I9;J(zm=WIyD_la=@}93+{6s^1hB<$2R1ac)lO@w}ml+x@gFw>K>|;SGP_h0%S;=7S+GO zRBPZ*3V+%NEIzs zMX)_c$sV1gXhBE*k+7cKpayY*1F&*c33y%cFZ{a<@Sz4 zUk!ZVVX`p$)(Ym+5#QUT&f?>~ z8JV!WJ-)t}<1p|LSPJ`dc=*qGt-I@V+dUAC4-W-VtyiYX>{VMqQjj8qUBmEagSs4t zBu4N^H*#Qg6>26_GruTY;#|iwR z9nf{-NJFPN1T}l^do3j;4)ay!2W`N`sQ9vCW*lVKFdb~e5I)o`O@qRdIJoK#W*)+a z6Sdt6@8DHhgp(9(fUqRAq=WbnQ&VSn&zicwj<)Cfpb}X%nWz5C93+~@7&#x!PwLKa z8*YBvb38&ob+8aOO;&N-)cQo7E937*n)6@lvpp7o!~D3bn$BaV#-XoBCUfC(^tBKe zvqwj5$y!Wj3QKR!e)!CW+E}Tw!Ooc?jLlG%dY6_|K&Y!g;=dEL9nIF=&H&x+R-Ws| zna|w_RI+_eygr8C8@>}|Tc z3}ZY2?>)Tm8%?+nF5vyx+1TD$>rV;IZCbiCm*B%Ps4SimFZ}W44!r@A2q-M9^=;;W zH*dlIK&v5cqhF^hxZ)FI+mo^b0pcjyr%D|9B}L3)QR_BdvtUTrK7|!TeIxAXIu&WM zpYDcH8M!w0Fj_>oJuGR z&rcraZKv&C*r#ex@G8Gr&nM#?51$8=7a(n8e=ZlnK2nq?8|H2!pmIwj}%Uh)-=tz$JGBj>%W19{lljGIF{4GR%) zdTISgvH1cvYr~CHVw9nce)i*12rGo0@3mrERykhgxY28ao+sEi!d3L!k-9D__I_Jl ztw8t$O6#y<9E?$1!OvNAZ}65E17JSEHOTsOA2L>&VJ1x5D$qpEx)3}P^;z0`CL+@L7I?Dq)|Gd-LLO+;zA0$9$T6b|Oz-%lzLTK!jS2i$tT6lI^Q z{jz^Fk?R0EwHZxUSOF;*4%CQKw_TzN1PQut`~U8_K}d)(N4hOoC&Q^TLFS{Or6u8h z>2o-x(6JJ$#Z#Y$Y4DMr*UiYR-k`Lk#O1y#G1x<4ilnu#Qb{=))k9c8s<(3sqZq%c z0+~c_;LskF6b>_5#@jL`;S$ad+vEIi`5Z~xpUYze(EwK8D1UVH$*ld6dw5_#W{*0J z4kyIY|M$%0o;Ek>zO{W==vV-batK}`x z77G64M?Fkr{MTsdMgOk_fI|x6zA^A9;;hLi0T>6W`A<&H`+;m$vLv+*_Vw+=THoRs z6kw$MJ}X=czlq$hBMVc0lUq#_&R}etr$PCxB7mPQs|8}7-&v`t>zuogrKm$YVWKP~Ntv8!moJWcZ$aL;+KaiNbGnfrKy=%lh`uTU;9tSbPC5~!Re ziAkTk;38dM`>$)_$8O}C=A#Q-KF`yV>~wVA2opN7oi}!AKyW^lb(a-4G)%i3YyL7F z$8fV=8UpV#n6n@w6pUJc^vmvgXzl)C{Zj`GCOm%vete3ZFEG7YDWf#<=B1LhKqHYg zCRdLpppQ)3Xe?v+(W2om&n=Dr`ecAIokH7Pu>VjcmB;ea8wl&R+(L@n+zt)EjqiN!ZMPNF+M<(JCvG+lZu<-iROsDIZupRAei`(xveO3lsCaDBuOLRdvO z7Mk2dc%ml=U$M%&r4f>-RIEyz&SngazZIiZ#TM)ZaM5E-LVDI<^8>qOf3)C7W}Th? z1g2*nq7e&JS1vn&$Imeu6w*cp28xsBEy<438iUssHR|9v@C^duIN36K2^$y^? zEY?y~ksCCZ+IUgBFigHbkLKoyfuabDHZ|%R|>^5M?qO4OYnsSg^FtATp9Y{Z`dvHr3LeDUW z24J1~NoQeQeYT7S?-cXrH>lpMeM|GN^*OteqrYzt1SxO?v;wA2AKl#4944Rt{v7!? zCnhjJqL$dichVih-`Jh;R5t^dcE14v^YJTPnNw%fg2{)K0gh<1O>$E?Aolu$G`tmi zkv+2*P52Cf04M#6S>_QX+RjT{J>$T(&|0^qh2~|a%DJ>bt2p_dRG%d(&d(b8j@J7C zt&qv9zUf2=IYG$AJSE$X&;O+1hXL(d4+?)v%MEZ2e#(UU1rS|B0MWJgk`J;lw5i7* zwE6+*Ul7(tz6g+2A!I%Z3oSP=3H2@9Y4;7r#8?-CE@>VU~UVCOY1OPMQb75^)$+njPJ6Zm92;iU$v!Gz4^_wo$Hta`xU zSOP0^QgSi?v9@nelhgY})gHT(z<9#K$xe6a#)=g^e_ud>VkvB`d(KohN` zsBkvfMUL=?L**}v#3)f_f2E7)AT`aIWD5%?;3(g9-|-%3kUSz3z2(6-kW32U3uXGX zKn+($!9gE7UUd<~6+I?PV%6tz|2BMsYi;cKa|n}ZK&N~H<3oi}v)i}f6dV%v;a5ix zFXsx}MiY+-nHyL%R3_iS=5up^!j$cRH!>F-G5vkZy2`fPn_Bi^?^AH7ZI6j zNB+lxm?98$#G{4kbbHmRZ&3FRcS!;0{;~>KeKB9k2BilcWP`R1}ix zj$ppj@%OCqH(L})AfGKYske1JkqEZqfz9~Izp}C*wy|L!yPr)`Irw4pO(YMVTl0?> z*6grl*tjSkMbP(Pv&rix`7$}pCLYoe;4}_e>&v>jXT7Df>2gS&xgS}m`uORmH%F8L zE_Mg=Co?lB)`DQH;!Gw?e#De9YQ;tNgLv936lu?SkamnfkcojJkXQtr7+%7uT^>QK z9a@n3Dzb&fR@TRweW0wYfs652QGthy!B`{-T|`$)^TvB|O|W0fGL1PqTo1 zdV};&U|=(BIDoN97LWa;@$+TtdIRUSvss{^6+0(eH`mm-0hEBVw0eC*$+YhM^m^TK9594F(qRx-z(8BEl?dZ zJ#OtBf@}SlXmvk9M?2wzeuohckJSI98pslH=&L*`Etj6`ds; z&B1^!LK;~`s4O=wt@a7BodLxeZ)jNnxd1QU74!4J0j+qH05i_t$33?}X7#iIKBg~= ziK}5A~7vqg7xr$T(eWq<52NCQDodCDc-z!@QpqLlF34i^>TXp|IWm3!F3;-B|Z?Eu_`5H zP}D` zgHZqH$58OdiTqv-PEGqvDw1RAg|liwZj=N(vpsuqGv}RuuB-HxRY{m?z1!cXDcn zLT1H#9`jfkU zldTA$iu=Pq&5wXDje#}hf<}zLtg^qry{h8|RR}}^7d#QgQmv`LiA3dW7@s}Q&q@mJ z*Y-Y2H3@(4Jj(D;}4z9}{Q0X#9f7%M+PR*J#p5P8UBKpC3BtwR)X? zsZUGh@c+Xpgd3`v0OXn^c4MDDBHinor3oZQ+%O}dg#`}(`AI+Z?NG_vV!v0R_XAc4 z(=cm}EQl4XQ__!sacTpGDNx#FO3TQEURJ;YQseP$Dv_qeDenJ1a8tvd?_)~scd|8z ziF$srrG8`0L1S~Qe=+^#%N}GscSrSESncJ^>O8v)c5qI}j{?aHA0_@iLmXp@_r)~k zR}BbuX?0GIjwvyXOoH>5L3_%~N`Ll>JK90FPVMa6DMDH1?wS?pgdGI)q9Y?o;9Kc` zsvH*v9?joFXMf+GTl|g-H8QoXyjJ=qz$d-!cN`3`Ok!^wVehOlT|jLtDD4_vzvi=J zeg{YgX#7$ee^FVjRkxst{*j`KuQDjN3O+X%q%BBn-nWaxL0e)7P|CNh~T@4Q}Z}pT` z;mmmQfu+@wcAo-GBG zFfjP_9DdY~OCg}9QU(x?8wd!XHR_;xq-ZE(jD&HdhFNhI?~JmUt+Xq8%NuMoweI_B zSohq5GsHMKZkPLi4JrK1jEq1h#y-%keeQ%iJ`?c$;DA9^B@m4mJH%$K_PfPg1tsVZ zx1TUa!iTQGS3keW8rtZr^#~Xa8?mp6dY!ee35*Zn|lmcccDV~PRpBlIms10D)-ai^8^&ZE6|M&os(gO*zEi$5eam&z8R zz6Ndbira67zD`@npDGnAh;Y(h^O8z&o%b3|?aOI=MUrCvTs(AKEQc zt69(ydRuB!(X8p6vOYT$Vwol(ff>R{pPd|+t^k{PJ;JXmoIw@d)9kpgA3kKhGja&P zK_5sMeiSVm*l6TAqYcKq8w&)Op|S?8;0%Js!v!GB-NTL*W~s%mNKYT+R7Y{=|3EI*illqEgDI0Y0V=#r zyXt5&h5KzXHf)l!O$0KJ5(l%@gu`bB7EbEkLkdfHMFr(1kLpa#t#tau))swgp zjS~+KkL)zmg&NXyH)B!UHns~!&Bp@#^Fy%DX{ZuU{ydV}_VW{6|E356=3l_rZKzDK zj>?dXeZGYi`u?@u)%poga!mbR^nq&>S$|iOj@uSl$;Ko;?8Ctw0X@|_oJNk475dePT~U| z9SwNRec*IWQO#kQdmY74)XKuno>XVm6pA~)eX8CY>;qYiWsTW`JvrPv+;%2|j|#8@ zGtnvq5kQFud)gGW@O9A4Vy;7c=w3@wsLu0{Xb2}6tf7E%SRW&}OOI8S>rPu?&;6dQ zb~ese%)eOYE2}8(A?$2a4j)Y~kxJmhAHF4Mc_j6VFHC=LCWU2-5PJn9VZI~dslqY6 zw#yYnobm(gVw`mTOQhvtZY6zKz!FCvF7KZeOxZ6L0Mh&B5uw@q`arISPz4E>tI9&U4wH$Wv2{=`ZG4jrpCDA5>visc(^_dx zMO>%Tqsex9r;v?DkSG#BfKu-{fK97cBld7p`?Q?bn10qvj+wA@TlNp4)$V}RO$~Gc zKYZG}%lP_S5JvA%MEk{6?ntc`xs-$8LkFd^UF~Dc*pu3rka=FyTdkP#=s4j$>5bWq zN-7v-TXGZ(YG}l6Qn552n5g1v6mg^a666^MBo80`h(!G<{uLQPxXy;?1m;i)qayP= zEnl3}o`JP51lVL%sljh8Cz`T?ZC(Z(X0(O1jBCBB3QGF!lW;Tp-Rb*%@=rN_bkPLU~6(o(?tm}XY6U^TdR`b&>VQ6|5jBgOp1H$G*3 z!#Et)O}5qoIsD0&D|Trg#a-Qf1;Vy_C;j}?7kYlz~ zQK;G7wba)q)1AXLMRcriC?tR|q+HM@8&*U+>=qq*dT{qlDbQ>_Ay5F2>CJc+=8QDhswG{>SZqsVAM(`ttOx$S zkiCk)uFhFw^c>MgMK}f@9v*riJ@v~81^91urU4K6$TPc|>^q~5`Y3Kn^W~;VuRx&; z#4@E^@n-H(c2e9sY$dQOSkBJpt3F4jlk?LUcSV_Rd&xkqK4fieYV*2qc3#naC&`Q+ zk}IjO(fG$BEJ#8cF78Hz3}|_a|HF=@-A7-=9w&wSDVMR!Y#cbv$;o+1lo+abV5W#E ze83gjvfw%8kv@+ifqy3gwLmh#T97Js-*ZCg_n*HM@6vKgC-i?`>C;Sq14OVz25K2q zz&Q5{ci}tBp(fQ1J`am2423eBpzTpP;l=ZDM!RRS+JH4}J$i%WGRGTN=yCaLX~cqGs+@FtFNW#8I?vIJlIc z5TaK-++`UK?#+NCUf}g*aPT&!ZPBdB!8q2dkYDmrkvkrbGOy%bGUiy3T*Vw0K*4c> z@UcUuBW-mqRLoS}wpg2DX!ifXQB^nL+N>uT_28jcmNH zPK!wdN+Bbn`ntn{vE}fx6l;Gu4Km~J5#5!3+TncrjM|V@r-^loFVPgys!$y`=%A4h z$%I71qR9BpNl`w!I!1NzSNp{a#r0CDs>okVSf8M;V_#|Nr5O*g0R3IpdwaxK;bS8VaL()z zSG$+NAPpqynllh_1A(T<`C+2L)G-?anbO+aQz5=|+uYsAfS44ek-dv2tW^?soC)nh zA{OdCzzF-Z zN%#JOxU;wN3`KUqz0#1wS<;Km{QUCy!IfVXeth31oDT@L=&{wuz&-25UV zk@%rf_#sY*@rjfavHi_*<0#2A7>r|%LKzK2!k~xh=B6#etqLl?r>>%j{I<>QXI{fH z$4g?txW`Y4ktxx?E4Y3Qn%X^pF%F>jmcM?5Af6q4iW&U`v5U<_D6#IHec5RP>oN=+ zHJ_o%s6$kir)PbORbHSoAFRu1GdqC~*b&qPui$E02r`p`gMGoWQ{#f8-8_LN=6hsA zNR@ZE3a+0VV6^&`P_9#&Njdx_-a9(;GNse{H?1HN%lv(0+%I?UXez+*PWdoY8W;;H zK4sK&k#v_>CY2;A#7<0ZjtdFDfL-!GCh4|9;S|r4k|`q{9a)XL zd>;c=VA8VGh6l3D0Jy>(fUI6jG<>w<`tCud(OZ`8y06 zUrjt1kD#3}n!lf46HFWx`YLM>vN&PjzPBxz*%!~>_2`Zdpx+A$3PAn?4P^Q`Oj|A? z0q7$no!$6oxW`0lE&3wG4m>oCzal5q`hhuok77(50Bq|h;isCc^U zcoZuzx&FEi*LB63R?{;)My>3ct&&LnvNMslJ(i^^Ws!yaY_c};)LUd!jKoN}&eXN$ zK*-F+{$RekC;YZ)wM8gnBn+l*K%&y>z4uPoQ?*{a5R4R`XFHUpTl;kd{Axx*X4nPF zK_EG>A^SJFESJ*yD;B?e$u3=#1xeh&l&vWhpK}vfH68(+%!(^wGDeI9AEl=Q1My+3 zIR62rm-*=fpS?#-)Pz?4-3&@*o;YQh5~_>YUefO3Q7F#N^z z$n1|$SQc?PCrx}dsx*^cI{zf<_q{ebi)$kKR4Dru*)E^-Z_SHZeeQ{%Z{jhWkn#-- zPzYDlk*cubBrPi{A{Fx3fyon8^OwJlVioCCu2)Y~Z@wB;mi?XK*)To${-T>N{xpz| zA%>#5?#EbOy@)hgo(dxU%^W|<_}JHRgshQW>BD6KRWy_~e+yj}pEYjb>DLwnjBT@w zugBk@vdo7ZxHFzoM-zb&;sM7T8bP}J${<0wfQwDhJa1tfoFH#x$7fuiq}`!GA9P{t=QqOEiZ0xn*J|-G2=)UCioRidw2(wP@ZN{u4-*XQS7?!NF z&?;zvBt(Qt&N=Y?NiL&?C(cjhYrl^FEp^Xw!uv`}Y4-(O-E(Si2RgfO22;Zle}cQIQ#0H3Z|TsEH01H)o+l?P64Wdn7CmIj z)bbqO&_r>^uwwRbPdg_~!B#T+9^k5~T$;+I<}4rgY714uEV1aD17G5rm+E||MQp6d zeSo$VYV3x8ebQ@%{pCGE90_YRDm;hL25~asIi~Z@J89|6xFYn3O82_!`*Gw5+g#=Z z^%(1-HzuM0_w-li_m16k3DNY3z)EZuzUf0p+jZMB=YpWbYju{ zpB7+9u%}`dt=4b58DrjGh4Q@?>!iPHO*X4;4L#ZEU#w^1eX6eu=nWCVN z>x;)f_-f5VyM->&3Bpra6;!J$JW&*$n~l;iojmvMIWyE{vS?z}-oX@6>kj^PGdgah z<&eDFvWPN+bRoqwwiT6|oW7~4?S)YNuX)vOBfN$ADTfTRB_*`NNg7VRPxAMFky*t2 zGHNa?*Pd$?_j3?$$m@(5Dnq#JyD}gukMgBd%bv|llXD)=aX|iASPJXV*VTaaw$B~q zVmZveyERM7MVjs+)JW2VDy|OWz@`lChnq0>PV$Qm?PTb2iZ(zd{5~z zgD|voZW-EVpy?-CRu)U&0iRSsf%HhT`JnpB48%t`rnv{2y$$jBEcWj9F+#33XD2ED zHqJOEC@m53*0sUvSaE`SiF`x)4R0mo<8!>t>I|N(rrf)mGZ&O#9b4x*m@P-2Xe;^s zA7QPe5p?-+f?J%8c-2YihQhn+4-Fgi!52>p$^8 ze#&^XrRxj<%_raY8kX=_mx4Rhll|s}KSA`KQMnfDS_LNF#c`vO?~*K0tr_wlOSZEp z|LURP6tA;gaJe``=1`hS;Z|WE9VAtBoBa{wy*?O|qH!KA1{vlevL!DtalJU1r;+@> zaGhsK7OOcg`rCgqdEPm5HVlkHj$z!IxNqz^%dbud4spmDzJ}yJV{_o>I zU2N}KnH1f(Mr+mj`^HtLMZ6}A6}DJ|s;$Q2rC(=>6&FwE76aKYzPoRHTX-Ji{#;S^ zhpg{8l67hvTM$RiGBqEZW@_{6s&3Bb$uHTSP3_(e}f>thE&FdQO z1I-^E1u)>)**&wEv3#_WXj@1b6_s!I>{-`x^o{>(e#K>(kL!4FF4kcteEk-JG!`t} z0_b10S>?ZhC<3ShwAyK~rd2?FAn+Q{tK$#CEeK@#yQTV^^+ule1|U=z6%K)zxzP?( zl$9}fzc5a`iM^#3Jp*p^(@R3rs_%Qy;I;=j_o(+)Bnoo zK7E~B6ql@ibQSo{*9a5QTHnN*AF#sr_8}v)!O%#lBWm!@@UFPO+rNv9FvRj!Ir^pe zbCLCant1A``&xuEQxgmvWGUmZ{5&X~7P@f;E{mg492CCY`Y4S-hxN`mr!I35@hyf| ztpSRLQ4ZlG@aRW%H+9xUmF7@pJBCU_VsqlXhN~qL)g)8IhJ$*u`>5=Ha3yb0k! z^_*|+3%li+tn%I@uR&v)NzlJFkn$nGPym{hvmxi8LkQ6_aqDN8hGJxpUi^pb1YQpQ z{!RTcfU=>`jOzdqDg;a_U@m;+g-O$QBj>Xn%S%YWOT(tW^$B1`Dy#@#%iUKZNN&Py zfRIV=TZOI$twf}a$;CzLTc~n}2z~GtVZEVZ>9_;M8ThxB8$jl1*&|0KX@gSHBO>QR ztt>kA<-VZ8%dT>69jDJ)azE251p>r^KZGJ{iQ}S@#BEE?DRC_4Obd&moy@uxnabmd z{l>6Bp2pGe)4Xb?n&Ln=p1_F#@=nDt0@;O}KgbwcR;y-|)w zLC{`2|Kd&SUS$?Y8Qeh?1UT8r8(#aF0#cwjq1z4Ek*8^c;Js>n`YVR$!D7InvdAHH zA^1uBK(0)MNkA1U?R#X$$1uMjmLL|z6s*vqBzGr`6;86@bbC+;l^ zgjV-D(BjoS1^MVJK|g@NLXU`?2n|85`EWw&hlPb)m@_I;fiXl=!H63z+E2Z6Tuz27 zg>R3I059&4CqeIAa;ubRD_6*Ab#e5f=Je7rAL8|pwYdRn%nuKt<10apca}7X)^
*Dca)H()zk0qyTlM5|9tPxDzYEh6z8))V$vYXT*L0u`clOA5o<=7QH^k>y2HZZ z`EA5|?wEod_NMRrqhLey9TnFJyxKJs&JMJXy7LsUBZ+skr;H2*my*MnGKj=C$-DZ?`FV9)vWb^N_4V(f)qz)bEu zQyD@?MI39@9f@nZVRj$%@}Po)>T@Wd1+p=kDf>&^b5ON#7&Rs`KCmK~fj73aKUhqI zixmFcU0NFLY2;65BfBFFdU;@)e5&Z>0gw7l4uiiId8kfUcFz0c;*>@*1aon)uDPIK zf@?X`Ei)P+Di=lN-d;a8Cu>J#A?ud?^590pzr)_`HEwGPo7*TjR6<&T3_Fhrvo)eo z3_(;@GUm=i_^LORLg;S^w2(P@E+16%mKi1JOEc(J5AXNUH>5IXgu34`2}Y%E(ITm7{J5XQwS}BFZ-hJhiAMQ73vGc6yODn zlkyO@aB}d|!g(ukzbm{D0X0EmGJOqs1qBQ#{ov_GKo4}`3yfj)0iCP7%X8=_*&L+{ zAbu~z@DRmg(xGyf*W-lCz8HEDN{dPx5VN)~*ZqoLy7ys$4L>9T1i+%sA!SRlOik%( zf%8meSoI{H)us>&q_oK{p-W>5vYEDD#<*R+>h zbR{aj_w)AuJ5V_Ygk%etrqW-?&@F4&Bgzn)O05ycR1_^poGpomJ2q z6nc}Kdcs3`htAYmFzboy+>M@oQBgiG@T6^_H11^z80d~KX1tYXfP!O5{P7|W}c zo#^kHrF=gsJBZRSrp#m;B<1|(U%-ok2I1D(w{vD&p4x_{hV6L1(w!Bt8X!DQJc{fa z=mOc+^?+cH;Un)aD=P2i9AD>H?k9e$N<{>x4q>r;LKttTbSQg~-4;qr4Lbb( zxbbpf>XiP847s(dzQDEk)k!A%zVxXC&NY>Uy!gG>R-@;nZW44kQs+;E{6Slh z-zC3Rm8P~Oo$+5Zu<)@G$||p@=m28bN+06)Z<@k5pZ^;K{}5*AvWL(?S1yHhok8>g zgY}@YsWMLewh<3G70~D5m;{icamRxdEDs=sbbU*E9#B;tN-xh$EuHJdOn6VSi8%(; zWN?Iaym}BlML>n(Mkvn{YX9j`EEtc;`Se{ zy~;K$(;0X(H#;jIcr2*@B1iup(hwU~py>N4*ym(W#Q?VJ{iv z`!P(A@M=JipO7N1@i6=(Hcc}S{bXaLUD{3(`(CO-?!?oS7SEql=+f#Zwbn|EGp!{L zPgAR2^Z1#L>2kB8$f6*JbQWuqr}9sv2mV(UJx#dr?s+@4Ztm|}C=HqkeQ(L4^y7F! z7@Cjf5egq)(qPZ`t;Mk`T#uwh)2_#@v*+{{%bMyx{8G$0;okSjanw_mxW&3|dN&TM z0Z*PRj$aI_pTWk`u~+}SylI^rVe8~1qe+cTPM-o^23-@A+XxWv`7 zU4C~{6Yil;HlX>mt`W={-rlwY;20_cpe6v&bQmyz@^?c!A^=mefuZ4TN`cD%R+~cz zao_5}d|S=v_(S{l?@=Q}4>N}#i9_&sLX(6|uTuyGenauc?|}2m9TQnH6hoU2E!A$kuwS`+b?xi;oq-`Cs5brfeBfS%z^Q+V zyNLyW(Fd!%k7aIdZKLczxkzT--)qWkqAQG?b2E>ZYs+hWUotF;t`ma$HI0s9r*hW8 zNYK(Q4NKkP-u+Dj#tb=4AJIrWiCBVAv^W-F0*^X#_X_myXtsCKTsYXOsGFoZ{tY=p zF-bf8Jcr4=?=U9s2Ks6kvnA}s5x_CRg^z*eVbdrGPgMn0!f7Bdg9qUjgDTnCqgKr( zOo?~2kLUy%D|MP){*%W?AlMXiO85(_ep8;Qhe*&;zZ|y`FwvR+3YNv_vI#%e^4}S~ z<_A7EY#q!A6j0F8=(-A?-RM6($Q2$I*!QxX6jI!h05r{S@1zc#!(r-d14?C zO*U-~iAL4;e{s#bEVNQ29Q}V(8$am&Lq^$k?#?>CI^l8Nm*cR)r~dfs+xIBzkY3b} zca+~??N?|P0*3fZ5Yo+_(prA0RHlnB#IF}3+blH=`|j}J`!iBDs!&hoM*Y>czu-~L z)eE7$WnJ^{L#C78atOxf1gaK@>H;*r<%$pqLe@zSZlQ;Pa{{2^|8_1kG~{1;gRYd* zxVbhrH)MbhDtRe=SyN+V@?l@Foz*>*Ri>|82!q|QQWD|fSW~YymBMC#PT}p zaqFVz+nowZVD~-Nh3%p28l>%BJpkIu#4$g3U@>Un-gyY}A>D4LhVy`S30g>W`iO#o z7jOY`jDX*g#>Q0DJu6&)5vXn9Dr`I^(pZH@A5MX3T7p8v?Iek`Fw2_R9|w&>Bc-!; zWEa<;sXV`-@hWls-B{foS&GGbxrjwDlTJ_+JdgG>nW(nLyt7j`8baXkCUEyOf!dkgEt9tqPvz*Gh5g3R_mOLJq4^y$ zCoDe*?whkatGvybrjm6X?3-e zHb{VmQu;C&bfF4rVIhr!zRTXE%dXCDd;N~D;zI<1=>5tNv^J3%Uh&uXZ}~rNtX|oT zou!L<#@5pj#Vb#zd0QY$IldA2qn`|~_sto0A8q*WW?BO@LLc>X`Ke=jCRupOs1FpP z&f-49u`+!$PPw|WDM~3<8GBvGCKJ>FL3wIf)(N>ib*cfEK*Ert)DBM?Yj$Bd{g}7S zpMB%%ldNE?DQ!u~#FubpZTdxP%=QT0WFA&>I;%L(mIXLce)L4cj1H%ptSi?(P0EW5 z4Fk+jiKj@G53ufsl|X-bnj9D&U83A>HB(O`$wGTYq-J+8&iZ%Q_8|H&9<5pZa4RL; zAW&IezP}3Y?jZVszBG3*2SNZls8E=(V(yKOm}QwMzgA)_nKaPS@_WL<}eO?Klvl^n^>kc|1r}h*ruaiwibVgG5{^_2t?BiT?K8+A-4+!Pk`!H_ByeCcl zoKDoO?p>8Rl~Z2HuYyC$``CyXy>Ou?-JUV;?~mTQERhT$|4Ik`EuiE8s1(W~MuiLS zE*cs&bY=|d=aASy85JKzFaAtU{Gxl887RLB$Ds?InHHH?4HgFTa z6u)ZB&86#;JEIiL7BB zo_wXGk34)jf=rl9MuQpuf4nJ{Qi#dl<2N7T=6cNBX;vCuPe!#Vjd0~1dI*yp`I&1r zqm>||tX4^+F?AE^Ef-V8&I%1sO1^_0jQ9-mJ9*4M+J$%6X&+)XEcP3A&eGenKjsK%!uSVVYLOYIh8njB$PdPgx;f(g zPxs+%lC;wAw=RD?AGWYzuG_WfelE#Xko7M)->mJylD4_<^*h-S&glRinBG;{ToKL-rC=`%U7y{U$W&<_p0;c z^~!Nz-KyfRt9BWrL$N-Fmrnm|P5LfL@UDmT7TnxS4icNO>+A2tI$}H~l2&CpX!%fm{11ePh~f+mut4JF=hzyH}s)fUJ7I`X@NWJ|%gQbyy^51ie> zw^H3M6M{Iv1QnH)?d=;kEcu>Jkm>q9NVp6bDK8?}e*Q0I9J}=ZSxfpr<9yOX! zM?YbfWwJDW0mcQiIM~AkC>h;j$Yrkr6GB|a!eGTiclI!aSs70`3tPk2tisnQ)>s7zq8eJ+BtpTS;;~FmYT4Nvl)h^+7^irB?+s zle$f8c|gs3Qc18w9$fc#$JX3dz=|K;hkzpwRZ^nj}$17S$oHx*#9~7 z1DxQ{F!+;uSRlW;`YsF47h0$mf}|Yi6+Hm>&}(llb^4@Nj=cFHut3<4cITT84Z%PI z)V+KOByfU{piuQ4Fic{iBlxf zQpN1S=I6(53~Rk$`bvURRkPm6=B)S?nk;n-AMBgQ zNY=O@`$~j3NZ96Iu5wtw?XSJ^{wuo)!idq6=Zn_*1i07Ee3?n>;m@yJ3n_<;beNQL z-sU_R~;ngVZ&ei{VVvZg-%5d_EvdKg@uh-0Dq`4x|84WxIs z(v~g`spro4AeSQ^mckPaTePcN$KA4hG%$ntBcyLt5Ikc*>wE<{02lxWrQwK4OG|@I z_i97@dbajiiUCOy#fWq3j0`<; z#EZaJg0G%L(P=XkY`=F9CVoAhg4EbYVul9F>_y|Kkbs*06ej5Pyg3Fu@lZU*ZEWrB zAycTR_S@*pu8RN^xs@|xwGsHbet!K!IDNm!K9%p+OX}|fbjkIk5Rz5HH*J0h{_Sj|Jm71f+?K=PaJ||+3M!2ID?}uxLnzT~ zEtG%pZ<0N4(rq#$|7KVs<#IW?cWO=Fa4zSicUvfr{Q^jIJ_bX4Tm)F`Cmf z&@b=ehSHj@zRm5|_F!z8Up)XdeZG9pBRw8RKY7`=@q%7QuNptne@@1G^(%ESubWsd zvi$umzH?j>d6y<5xPssLYP}^%K~9B&)tjTIj}M_*TgQGx(p#IGzz_y?(9oc6iAk&X zu*nOMQlh93XmUZpgB#AMd_DtmsuRT^=kk0JB}Ggoiye|aFLu06%8@jUpjXPI9TlI$ z%qtd6ctvP$A^T!O1T0){y1*p|%JUB@5$|oTid&$(6X&Yf_G@W+xg#XLgn0j(=^OEwVnSXBX7i&_8<-bp(5B=w~ybzVjn`U(a;}R{j zLI1vwoas6V1ga_Q?d*VF zDM!O5CR|LCtyQ8TLjux5pLfkM ze#0|!x@5ef>}kR}vai>CJ~oMQp|TQ_Qu5~0AJy!|X5Z@-*6)iAw$XCpL4UJ4%I0He z9{!J#E<(YD%MYUViGS0Wh5Hjn)Rf`IygX#^BQR%_c|;l^+l93EzAb+Ll$nD=$5}CD za>qkxRy1hdwr^i8_N(u$_xMuSMC=xihGrAdq`4ZC2(F{D2;T%c1WONWzi!e_rpILZ zvX%Wz4(8`Zavnsj6;e)HTN_j#k>Wr)vLrruuV1sHzCwb;%~OjmghbLW?wWxt@VnB&_lYr!uHC7&U7$bfKVk<$a5P`94b5v zUu+Ny-uPlc`POVRLS4P8-=HvZF)8&ZV;-)?Kx~1*^BNEh1cN9{kk&Qvl!AYt?S5ye zqodiJ{QS|!@pZS+xa_U0JKFt*lj0*VKbi#IfUWyK;dD_E+M;JGXn?W@5Hou3+&MZw zQG@sc`My(yqjm+yohMMe_=A&XfX>-vVw*3SA_kXLm0FHyzWG>3DOe z-y#aP4%wn^HCk{}HG6CU8;i7@BuiaXUJjLpa7+Jmb&1!5h5rip$o7GADZ+U}v_?^#5R5_gE8J}NO>?QeZ z=Q(RvnuwkU-A7#f5JveWf&pX{mJe9(8?me*i;fzk&JmNFp};(UZ!TMataVLdA61QJqBQajl+n?bU!{rh@v{-v-~zt zx{QDO^cTT+RcKZdHle5xMwKgdBl}s}lmP}zE#$$RrIJ6g?A0O*jqYZjP+6rUH_Ht* z1ZL7)FUQPGFOjCc=C8uv{C3mE?9TWLv=mDVNrX^^Q(VBS1$GJa zLIfrk-0Hhk+89p|5=Byl^AQ&YOC0wj)@OoDP?J%yO;km^&k{dUq&mpl zSHBii(YfKOBrK|khl2rzxwXkz8#n56RLm7 zf&VaT!j;I9cCCH2f{e8Lu;8%h2y>U732h8s!~ z4+2EV~YB_r0!86>j0?#uaGSHOIm_UdKFGDZRn4 zwtct|s+Ym^2gP{9A1vTOBT#_Otp_s3 z#tSzwDBq!sDKC}-aw417(hT=o4^>(l+uEqEJy&VBcI5L)SasZ{GfFXY+);WgizaRNcVL_j1sCKBxL^mfEZ8| zF9cWSa@XwrEIw>yktJjr_WvtgA2Ry2ueNS$zV!y=-|~=FAb$9jTUBuF6-1o?Q2)nB6!1+s z`foEce{Vp2@GaX4+5cI0HT6N-BB0kE(E8%$qsFZ~ODd?$Z5i8gNBG5#0iiS-Qy=bY z?I)vv$pf_{MEw#B5HI_lIqb&xwmqGDz{bk@Y1<-{HYb~c1iwZRq6m}whgI0`Mgwe; z#DayynjuSzuSN(-LHXt(4&GB2lROfWy8)trm_Y2v$*(07_%E7(k%hsz9jdZmhuJtG zp2@Yd4xGfs@bvQ9U+TC9O%GK3P>TB1!gpr=4S?gw+cfQPdio^@=4=sGNtyRa^$EUy zTzZR%Q?C~oG(f!sJT40*xDQGeL-hvEY5iM#6eL6#Mh^;w2zl-+snnc)2-&)<{+3Zs z-B&``!yRjst|d`n#?k#^xO!l{%pn*{MvQ@K$v@57A87Au#5H7=wcX@U>1*?z|PxZWicZ;sv_KJGv zTX9gti;G4+%h6&r6|RAJefV=KlVq>;WOn42zax#eGTq+w-|v&puUBlfw7i?V-2@Rg zgIa~j+`sOQ=U50EDgvD5GEfpA!GLE#9gx3I!s#GBaS+kHTo0VINwWHKRl_#_lxJ&8 z+hrI3cDqbQ`d7wrc9J0V<4Y7en71#EnG)ia+i<_XU-RDf5un_8fDTw^lwn znjGS4^qb$WL)Wzfy2g*ShWh&Cl3+*kMeU2URx}6^b!&n+(`e=xx4pV)4ue`-Fn9nX z!@|KayvL3R9Fh}g}#mlP4)WXqC% zC#eU~>C|xj{G?q(toYCTwIH{Pgu*yLSR0@7m9wl}5-XRd*5%Z8NA}J594yIWu5StrV`oj1PGSqFRcFVBBBz zJ5iNPm-(dc&t5sa6~TjJ^}#@N_0(W$NGrvFCkTWQR_ESZ^fT`o*0oUfREkgD*O z|EL96n(1Mh%W2s3ySl zvG8ArB2sBd>Tq;>cl~DUHX`!$p@{2V4vE<1dX_P+yNs~R39q^QUBpF)J^H!<&(5jv z^@VS|d3MC43jmf|fs~r>FN9 zWMc}9U&m2L4zY>Z8h5J)Ar!$tU!UcfTArh%C3;vFKCu5Gv?s|7`Co3O{R?({*_$3Y z4BekcJ|ebR7M}Pz#L$J1y)lN{Y4oJh*y=^zl>=s4-)inQOYx(;kQH*CyNQm;>FK(L zhS-QNui$oT>$1wi#Tkwv*=3ZyAxeFlx7)m*LR7bf>GjY$s97sT=YAag1?U)$T7-F% zdX$c`Tx)%8Z75sRALu1mWP?#^=h*z+e-B{S1W$MkNL}d(#QyvX0GqOGs&?@fxqyo) zfHTU<@eN~&HZM+ADt|Kz~mU1)*w zlqy)%S7R^NIrX@H0bMvUG;{@tSRd3nA?2nC_Hy{9*i70l!fuN}qA1f-DDj4+9XKtO zHYNz7Ua*YZMo{oOwO;%g6kZS;8iI?iD|IErxF#njKe1UBaQa^F2rhCV@B96OJEPk# z91@^tZvhrRix;%|=>4MOT4GQX&dEn&r^OuQfRMS86_yp+8Fj=#)9>^kXuSg&hD71N za2^2fZ=gWn;tCp>4dkYtD<>-6ImFc~eEfZ}64{u=1MzWw(18yM&cB%!++Tk4_3KxF zI~63gNWnh$Q0K+iK2T?@^0q`!YO%`={fGe3FNV^N@37y$kMgXiw6UyvrPIIXjZTl= zs9oLD3Vt{t%XuPH7+MM%Uxu4n@GQHzxjD7$)q^16#dZ=DH7xmVWPzHB-k$%17ArOu z7F^amf#kKZw7iw~=dWBo*k1m%!{>5y#J~-qKL9=A@k78M4V{`8I5}@)+>BBXM*}fY zEf7!>c!ug9ze~ulGe<`)Bjm8aLxz3p=uMAQGG+fyM{LQ3z<0T8<@a6RjYdt3j66Q3 zKXq0ytw9?id{A$VU2123i5kvoV(;rWlmfe~NSjfCsWUPP=x1O6Wo~&<5j4L;%n?EReUQDFK$UW%_phgjnR>@e znf#jwYi|)FGUM+g-O7DAa>QC%R!UOm6{hk*HU#+)Gnk*W~kYFi(AD|tLeKR@G` z7y-0FE>Wm;iB1VaiIyoBX3TN#22eV%;vmg~l=TV@Uici<6<_U1^c@C>P#3P72nq_q z>W1JSKS&gJ%F!vI@!QP(Zvg*+G*Y+p@X!$S?Sv(~La9A3A_{|~vP`3+JLiuRWkXsZ ziDbgt+;EIe&r3ktMxQMWB(JC_ySyR!V87XvV~j~zEU~w-enEwJa#Z=wpeCZe*3R1cH=0mC`=q9y+U-y89G73L1#FU% z#zQK1hP|Fsc{~AA zOIcdXaK`YBe^2g7wpzAwfZ4lVEZe{(9xv)XC1kwW{e0z4Da#!+4&nk_FZ}1=kD9jI?qU#loSv?7$QKfJg4`?l*7Qj{z0!4f>$aDj}-CZQi*uUIf{;-{}du} zUtMg2Swd(eED7>IaL7mqN6-4KrsPePW5Ana1Oaog#O$9^8%0MBwXU)md)9;;5Y$6D zSjT4Jw_|_Jk`q0$!2~qR_R~$8)+^=Xe*rfY{Xrb)!H&&WMz|dj>bp#A*<1@4iGzY1*iw29VaQ8 zd94R``Va)@Gg=yuu@p_f#N5`I4Lv0g<>`EN z@eiUk8IWxXC6Zp>p!^dP;Fr#}T21878?%M`E%7bX7i9^kN7-MRKHSzC?zM8A_9~SG zNLaBDo#m4ITTe0;7fEC`kCPM&{YZ+o`8&zfib<6!w1!$luv41xqqdxZY4TrN)0g8Y z5}Uh2_ZU%v-k)srt3gnxP(6HfP0L!z@ZP|)faBX2o0iC%zU)0b14&sjhHulVxH@F$ zhLu34U>)Q+ck;PeJ3f++mhZ1OA^n*x?9EZ;3n^w_41>MYKfHZQdC)#FfIA`=29LuJ z9>cR5h!NB<A(}6Q}MP8!M~a#XDz224#H2v5-gE@Ew5hcoeD0`#&956Xhf)fvKwnWth2k z^7KwwMFo>FEj_=537+MX#6PK|Jq;>%7Hm$f(yO?$Wb!eix&g>)dt=M<=H0syomEgU zH5+kM6$~Fil zRU&+&e`X{ul|QBHrdISi`+uv$MdTP$yvXLcc;QU!DE*S-+$M3)uL^R=XkK;WCp1B+O$PyC_!Q23|9ds>;6*nHaUI;orwowpCH z_g+0+wqcxqs8qC)B4dQcIw>`3n3$Kdb8ej6^CO>AmCbKks%xO*((dGKEJh&HYSNf{ z0Hh9Wy%I5COT#2!d>eJ}pGhN@P&}Nl{7=)h#%n0yfsb;ED@@4KOZ)6_YBunXU zX2Yq+eX1X(LaoOE*RoBA+$9`r=Pz<-Nl#SO-s{ju4z8U+8WTG1*$I=|_C(PS7B?^y z&2)du(QoFvN+q7SHtmgVjLw|iA^L8~;}g~;L3nGIyVunSd~6`H&$ypIMjHJjPR4?Z zw0713J^?)}9@aX81$dGcs{(k@xFFB-Hes}=XnH68 zCog)&qSx-~bUYr;4?>!v4+%8lLC`#oJgIdurY!Tlz)=q`Y?(I~)^Blf*u-GaqEcOkL{_oeHwV?{Qz}9y z!U-uwbD+UQM*7UFCN931$_lD$T}e7QRki_zXZo5FWpCymsdv(@txTyoqBH1oQyJOmdTe@#X_=*$R@q5r8jYJg zeAhAZr**tc_n}CJ?MyzdKQ977d^Ap}fkrs>NF5W`a5_8;2fEKQGHg}hF8wv0HbUrb z^m11bJNmG=!G@2_gd!T^NQPEEORpg$LYuTk7Dc5se%8S{|1W|IwtFBTa#j+qfp;&^ zfHAV_ZuCN9aq%{Ml>nwZZS^_0;e>uiiMRg#gbk1;AL54e>o}XN;Aq~=J6P@5i-@5- zxVX50xKP-q&8Up&?@G2mp~e3)G-M@uvmyq*BuebOKgf4Lu zuw`?=yATzJ=2bqkGR8I2g|QQWzWG)*8>gQ>8Gk=Ym9|0h;EuDu7uUJ=Up2$OqYWwj zTd50Pq@O&4l+2P$$gv{0zSAy}+C&!kR}G5eN3B%Y50q>(T#@VW`&?C9kBpEg?JkVR z2l?0tkY68N9r)I}7qn`r@3pNITn3iDiN76365x6G?(~=7-sL+A^bzVkxxmD9{zEmp%CS~(}wa3x+V8~jE@bYZK>-xpK;-YNt6uFr9i|U~pB#m6q(*0di z>{G?3B|Fbxm`2a|jJ$ap0{lVcsWH>Te()TM-I=G8c6${WCb~|nU5>OpJ$X6srAVlN zueH8~94<0)<5mI_OEWBwhq}SMn3lJxMEzdzeb9WNNo@N)iI8Ph@0Ftj$qP~5lLC+p z!EH}3DO46R<6#DJ_(HaU!Ng98HRe`n9FaC0@t{fvV|sNAYRr>y6W>ds;Gu`X6@@sq zpuS!QHtl_6%*{>qM7@-!6@4vno|63r1Rg{`POzEP2wwK}2dC^FGw#=fY`x$CUzJni zN+f{U#swN^$RS{kBS1hKg^Y|0l$k;)phRZsszAJqrk>u5aBDX?1Y&_{s`01q(`vmJ zXb++X%WXJymZiSA85&YVb{{zQ_8>cr0`-(!&)Mgiyg=83$AzffcPB3&+W#hx`Sxip zwKaWBzvcD5w@?TEzz;wjEvY)FVCkB`i|J1U0x7vst3>YrV% zX3-b!;gco0-bJ(A2%h@Ci{IUTE-#T(%(`B5rHf+(i$rZD|7ic^B!r5faS%T-Ib?eO zrN-!LVxPNgNyREMgl2Zc=T~WH-tPWVHsOrnUf^2nT-)SRRoXXZ%TXr}=RI79C+O~4 z*`dd~X^CroC`y@jo813ga4m#~z{0~Jx9Y&z+Z{_V074dsW?B1j8XZ{6X-Rb^9EV_ra^*Ye4M}C*z3KYR%6X#%ngc9P_ zqj?MYWc1p2wcDHJ@q8=YeX+GJGkkc9q4Lf5}We@?1M zb`Jkl5~2z*64To+e%sYa!|`efJowSuI6pcXJXA9{FaS#1Y@jsljyA`@f>&iq@)HMN zQiOMgg1zVk!|d|yWTR4q!$Xb2y&1jd5`PNPF0h0B+WTd&sk)Jt0)kqdeV#N#Bzqik zrwHO8>uX1dJ!6k+Z`nfQz&ZY2tZzfjDME;~qHJl;l50_e_mD%t!X7eROLQytzj3IR z&m0WyFt(ix{COZN{Q34UQtGu^dU1N{ZHKVOjp|Jd5Lwa?H+60H2lHs7JwUD3Z-%l zs)S`V(1RG15jWwN7PBCB=jv`sL;%L|27`Gj)4PB_0D2(>!*~SOd!?}Dq%s}*M_1*h z@sM|(RzGG-?~D|pWLx^^+s-kV21_RMB4U(he;X>?l2dupW!ecRR!hgqXBYvL^(-BK zkixUCXZ!sx;3G?TlrsHYEe;4Ya9Q2mbuf)Hm{0~F1oU&O2eeIOh{XBbV?X`xcQ&Hj z1b(n6IC@mm4m@KcK0Lonwvt2jIMHxO6a)VRzr&0R0K6y?Dk{UUleD?54Zz*{!?=@e zQAmVgBb$pb!`K!&>JOpxS8yfN?Re~L1{eZo$Aw!*(B194{*TyM+0t&J3u}1cyQcK& zsoOyXk#--SikmbmNx>9dL5QAuwf@%9PVVfVeldMUluFV^EJ+@yqtXwgM->YXOM8!*QKO)_^A3vQ+gS(Ce4GM8{^{17$J!?b{W}?3(9R|{ z>3OeBbjmBnRd^k&L{*#4F3QvJyROW}{GcbQgYvv(lF8zrXRVt%yS-hmPzO1fpHy@T zAMpY4Y$d$(xkE*!(2SS6Jf30lk)-eV;k$rUye9)319$pfQOX4MX5B|JwXixAb*7qi zpF1Bek2F+tpG|(Be|*&^Cg8gn$4RbgX*e-$^2+`Em6*?>QOUZj1^3d@IH_ubA}NQ{Hus}$tc@`Dvn9T!+lY&^h1HT%o||tX zum976KUy^EatdWEQ?^Ns$>4+MervzoUGLqTdY!?!vaj@%B?E7|g=z&yU(i)Qvoj?$ zQ8HnSrmO!O!Yf*5z}`=pJA?Ny6K#Xxfsspq7s__jja`YtsSybQk|@9*Vo(t!lLL6k z5jmTbeG+VruHmm4>aA^TV4QJq4KD25b9Zz5{S6Y{x>s)1W7FJ;Ajzy-DS~86;#-io zVkv?WJibM5R^TI|viB2O(-i$d6W6_}+1de$-MJxJfLXAL!LZU(F2h34m#1`?SZe)2 z(e!&&(r#O$R&-VXr6XW?F3$IoY$0YI6}b_8C@`*PJmQ7Aq2W0Mw-OT)&iky!H_GIy zRet)gfZ|oKxgv>AxcC7rdjp(F`+(Obn5WNGNhU|ep>7X^x@o-5v5>#$O3*;Esd4mw z6CdWDLRGK1xo#7xa%X<|ZiD&g(1?}e zgIE?&d242R$VZabjW9kUyIRU)0gN+c>DP0(Vx+U_|2c79Z#z5Hy&26Y1^oiHKL&L) z+K;8Eie(JD{=ocL>X@!O&Z^3XM%?DcMHz3R@8Df8Ehe@sq_<;u82iwmy*oVH;YgLj zZm`O>z5I`Z*f+NiytV5ceWMLf7sKmli(c`gU2N?DJsVvW`yC)& zwLYO+D8irqa}KANAU=e3WA^Un=Bd%EH}yM=)*a1jU&nWfv8d(-Bdt7IKX?8Xi}bbN z-kD!HZFlp(n73p_F+Ka({zHW^m*4aJ>l)zXS z_KdM7$!VqU80Q|octo+Q`(uvutiLZ+%QCbU3!zq|rMG|kp1N*YTf99gN#<8487ewU zHq`Ge`s1HL(<=*bEuKW^T7@mh8hZ zAo>t+e#B24>o{9o(Ar8_ct?L&C`+Yc8YBnooSdqZq)yMCHNiTBxFAhc(Nq;rf_0nL zr_OA|_oGm+H+-|L)LvL2lC{U>r|heC&;rm?6+FSWYxb+jsn&vEln7x8*Q#BG`Uis_ z)$>_dS!pqyB`X8|yi3g=aP!wl%Fnc#9;)_F*N*b`m;66modr2JP>;$n%6 zQ`6c8)}&x|h1u)lHTq7azhCaPpQ0v{A~RTZPBVL0qa=|dtkchV(F&oy6WAGD^fen4 zzh0yFts_KaT_0zho$+H*MJRr_ldZ?Piisg_S(J|4TqgFTsI^u>=XZc6#pu& z>}t9Bo(A6?p1a-B%i#pIdZyLUMF0wBS>=feRMi$7}yX zG1`QF9c*!;_vD?WhbbZKEOwm~G%;@9_q<*q^*#*bUAu$OV#HAXY*)glO5U!^LOgp5 zQtx_UK7Cvyi5BcC6#J7Pf9fBx@gP%Nx>0^=Xx(}T^imF=flUM??DZ5KSnTCFUDz|w zzRcuGQkt5XfqwX_;2tB!zczUF*nifxJDx>e-y7t*3O#Ils@x&04c0!e+j;0#-ssY>4UIh^ef-fI-``qM_O8m znVFnQe2`ysi^eCrzTOL1Dqy?&V#g0%0X6L`5W>Sq8YKCk<$=-s1iiGAN$oc=xTeC~ z@k?5cR#a+SuA;se=129S%mF0G?d3H3h(SbW%J3k?ll@QI8glp`>!2$@{`eE{5LxM@ zLKLAn;v|jQw*|7hJJ{&%hVhxt5rJ}tP_aAfyUVrN;~@g!vjMkz3@~ltCC7oTFGL;F z=357Ga%)Adq&s}rB0TwXgW?9GAWBFFd}ok$5@_-V=21`UzJqhxBc6wUCecdU_~dVK zU>_P$4KdYJJt~rgMIkPNn2Ole-oYqTEIh|&cFu2~ zdGrf2mI*$MlY zG`L#$Cba_0{VTe$8M(@Fk{y;-AOeEXV;)2xN!s&M4B=T=w?d;F6NmiIOF4#5NDjkT zK3~RZ(h50{{1%~k{CLft6lM*ihY``dvCa6;5YmR&u|ui~@pnTSu^C8pRBf9K!a7}l ze!c@%UBs`{q$D?h=Kzun20=dsl(Uh6#@C%S!n979(C;=&lW)=5E zSfXEbAn`QaW6ZYof@n`GJKLVZD(ewKgXe@HaEd0>pWheyYk3 zNZ?RNpy6~Sr=Xyyy1N8|LOg`nSOTr2#QpmuZi4t2R1*F^AfYZ6Q+=J1l2YrsBJ=ez zSehVwjk!o4t07ilO*8P2=wIb3g*GIeJCS|=ro;A56E7p7A*{nrXUinut3 z(%J}8&)?e^-&yPT^}LTgvL`up|9sE#c5*OzW>gg+hI%ZoU5fqu`aI}f-u6oHC|c7t zCqfD=n>V=#&@fZ0x*}^omxuYBh@uoON;C6VAzE;XI*9S^We?p!MSRA?|N8q`Yhx?d z(uaV*-=&!=+$Y#?99=jFl{p-h}ICuC)CDXXg;}!0elw%2D5^FuVjr+1!W)YcPI!~|6 zu$d?t%UZ3-R(~?ywibl;Isrj7dl25$Y(LEw))_22GBmXMoF-M_8>u^tH}K?tO!ybs z`C?s%q;_^@p-0QfROqD`CMfuWFpY`O;2?L}zWU-WMO(4Xa@E;RMog`a`iPW)nn<$THewq8F7|2fiMbThj7aZDy5Y z0|Rv8Vc?1>9c#(Hmbyu2fer#$c?+oTn#Gf$^s1QEZg75opHx$5j$w)a){$fS zQ(4h-e_}Vh7gia#5ArCInU3v$xCA~r-|ZQYX-04itp3nRx+|-tryIS`VCK6)Z z`QrKsDWPjLZIAz+1pP%t1p0ro_@6L`pPonH3;q3Z!PU6v&%v~Yl<5_vMSFv|dL@tS zvQ~X#YOFY@)(#A!5~i=Mdzs77Wc*$`T?Oy_7w9sa#0M#PP=%L=Ilb z;uCR>-v`*&CTF&IjLBoB2f($Wpw9^1v>!}d$I-HsE_w8YsdfydSq*!)gtZZ-PZ9r8 zmD2@bq|40>XHS;8c(_asES+Bq%@0IHDXEK`W5tq`U>k$qqY-kI+9x>_zc?0VwX6IY^{i^mO@_0#3 z=J&}dX%YAhieyzM?NX%c*dEJjXx~C-D!aR{rg8Rd`|=~!=5w4fdPS4op+P3@e(glhZJwqdSBVadMk;X$%W!O-BK^lQvkI;tRkin_Ty@cyuL zzPL3wGE#twOURV?eF6+`dSw&K3i=_w)hie&!jgl>3g7m6SF4KCODF8K1X4KjK04V%^u~tK*s;iJcnBW0rDf4-3V#@=B zUrc=%jijM^5y|$ACBir`xVy6gV{m}2`hYm7xyQx!N5WRG8gum!m$#klS9zyzjO?fG z)8d{SV|bq?CuCiAHCk^MQfR&6pojwsqAw&OfvJVntMNwd*G1{ll9Z9r4C)DhKiu@M zz&6sp8pHlh;|ZK~yzIW9GV>7&gl6ID>MHyPq;AmCddo_a6k~aTK!{)#Bg8|N}3~3_ItK#(CDNGr~6Ntfg?t=M5fNqVNS4{s&N}9e5G#BDOOsAl3*+p{Xr8d2*4QsA!kIB zV~~I7qc$u>zaXS5ozGsqOF_7`h(Nq;BtKDXAJ{m8b1Ynj00R}ME!xW%I=9!+U>a4* z(Y203LmOuWb2NSZds+O)BSP`A(vW7aK_7tlR;xoCoGTj(DrZkOJ8)3*-|Fu zsA(5XiROm=M$GX{xzXox$Qlw259EDAI)2{SR{_WXTGrf|l%9aPPwOIhm)8JN%f-z- zHZ+vZXA=X-=)T8xEW{#SyAb2u4IjH04L29p2Nks7ZtX$2b0++N_Gw%X;RCaG zsj z=J5m9w;nQv>}fck02_xJIdLB%E>~R1Gg0#Ai3O7&0!f&L49>NhdnK%|WUPC-cZdA*#YbdQ(Q}-`IblPYy7SFLF5+#MCA* zJWN$77hQdBrpAt7lyYF)J$p5`WzzuKZ zaW}d&U+2z=^S7E_+uD)0_hEd5}UGCD0-*w`op9m#2K zPhu;^Q$0SqXNnfBhy-}(Oc3mXwmE`UM~k@UPW!Rn$AXR&0m7keC>oDdACO6#}F zt9PUrZ2glCt=3RL_oF_l2ZqIGm4yB^SATX{$R?icb9&Qeq3b&kulP?(M6`|-fpA>> zoJJ1lD=JEo*5&0re)s%kOIkRKo7o zu)7Qh{}dWsaaGF{se?B8A)7~EVPPR;jR6Hn^DW5z%?=5-B}9MpuOu7DK#6j1};K|vgwOyeRJ3nIMkBM z@tc>0a9Yv)b*)|K1*-O0<+b(f|2`WW_?M8{;(zIy_Y*nb`OWT>w~;OKvh`#flJfv9T2tvV+SmLGJXR~ zdtN#S0dkz&g7~k33O)U?!gIDCKYYLy7RWnK$zIJ{#wOZDc+xt3Jxg%DMMlsTx2*3|X3)%}MJ&eq=U>5kYRx+&gK)LAYnY zzAGpopq-Q;^!G+8lJeLCl+3VO%2pxOi{*8Zml8uE(3yS(_g~O9_VvN?dTG65z)=qf zVd*gR6|S480@#}eA|ZwjEO!om#b2X-kfVy8YNKnL!f!%x;iE7_j*zmoEi|ft{dHt` z_+|fEadXTFOYqal2pxKs)R6ehE(Ekr9^WNI6i;tY9sDNFHcrWX>wQsLVj8+m-H%)k zeVfsY2MNBy!1e=GLi^dGA4obAKWp!cy?_56R{4IVwpn}DOKu)N&y=73)`;Ly|2If9g5;Bn@t-skwG(&_dtzadd= zZPSDiEIO~Md?a)RDsWq$m#<}okdeNnM;f)chuf~ZIQ20(wyWy+kH8`uB0bE?HJvyh$v7h7*$K&YpVpfS>=`@(&;Sk~u?)iyxM7z;nfGrJz005HK`OAnvtmU}Iw=^5`~l zjN)TUq&@fewJH;p7B{}QyhXH(_zoMU)~Xb#N4doAWsys4-q(4jRJUvV_FJ^sw>ZaX z?+&(WK+V`Q2W`1{7^O|3=UbqEuF(GZ`ESA^&8auK1gXX@_w``h{hH%Ix5GJIs&@8urDHPf66_)rnFIY^d34hiipKVuDxWQ)zBR5aGM8}!DNHWl19U> zAgE5inMvA$IvHMOi;;_+7{U`Fvm!|Yfq)Xn+S|U)sOGa$0v{|N-~j-)VfR*~f*>L> zB#IJvM3plT>sp*L1B4}bHX}YyX|c$07;un9E96ZfIxVY#Df+TEG+ac8CR}C$Ub3Gy z=v~y5!_0?;s>djN48=L*G(Zn;cBnI2$F$G}8C*y3M}@pjfmu~95Q+Z|xk7J3qKHEm zpn~NNVcA9%VD8^UTS=PO%Xz9@HVqUk=Z0IzNFO~D2||cS68d%7NQ`pD#u%$bX%b+^ zgqcFe+S-uwN3*YX{34mSHkV^wHl)eXD27PLV#aRuZ-kA4lGCTXe`y(yqwwT zJ$3b9m?wKumz`|^;zl?iJ~1NT{^!#6=SJyVR$PpaQOX>qQUI7?v9UZWDh$-F6`r4@ z4?hx-wwNp+{9Ztn;SZzSP#dFeu4h#JhXa$u#ZG@~nAzEN1U`zUy0peGZxEdTCW-_PIQQY@)`+(gY>0d zS;3chEtVHq==F-AM`K}@mD~p+Cj8iNNB~M{_DZcnZ|t4$QHD#~jX0RHzvCEJhb?u* z_09H^alf}G5rgJ9ENYf`5( zLS(yi9gg;j3Uxw^3@#x* zu7nu83;jX1B!en$vet;*%Yh4&r^pjN~Bn#^gC4U!_Jzq|Kx&C&tlrr?2bIaZ z)O`_?s}KDwFq@;rZ8E~`6pYs`o3{IMCr*KFv;Ts@B+N#&+90+ks!A}}I;!eias1)! zxO4Dt7pT5YZnWhg2X1K+s7l->azVTrOYiyA-XmBsULg-Itcb*n3{gmz0--20QGA@33r;Epp(w$qc8}Ns%)HjF+ymEVqaJ2jp0(-iadUH$XFU0O zg!Nj|{o~+uWZb=-)|I~c{i~*W7bDT%S(8NN#$sGERw6q z(#BCzAPdi~ay17lS1q5)F^Rpmo}S)K7B-&vF@7rHZ3_MmPL<4Y2fsSDXCf4KUmt)ju9M&# z=vjH|av!nX=i^gRQ2{Og4fF>{@}<9#ZJEDa(B{?!5B$<+AqHPkhJeFY*y@0k>*a2d zAw?_Vp`;acH~7uG8rjRYcTWW#zgAUMJ@8chiE}LSUiuI%2--1K1jh2xxB8BQ-~hnc3WZRuAix={mZH(4abb^X?yQq^WYe{s<}5( zivgP~OgG1%N~sQ^i2n-RuWgi(fC{}~HxnLmh*SV+5un|DQLh!Lbzeo@4wnIT!S6Fh zA`zHQPEP}c044;?LKIx&KZ~r<0(%(ldNhm+Kc1to*lQE2?ieM!BuG#gembh0zHTeH z&%v^dA7-OnWEC6(_aw-y{RbJ!kI^W;;3YnheEKE-#-b1CnhYVg+!5REW7YJTGB8~G z{)20{bL+|1Ip=04AW%Y#@I@O0w!#kF0vHPzSE`6RI+CcBmh=$PyC8|QG4CD%$frqy zR;H>1^FU>Dz*FNils$Eb_;1XVUAa*0Q6HXFMyqRJZZl?-)9J64gKqv-G<Hzh!a{K?SS?QkKN_iHkL<@kf0e8BF!lC- zn?i`sG(QaU2)-};{0~ctym;u&H4zd z1Ji49<%&n2pFbbFqq#Y%dNIO2>Q3%s&f?YeBgkTpw}?CTNsxp0!amj7vf95Dg(a66 zTFJF7sqJK{=IpC5{~TlM2+ZESpgJ6UNid2En4ob>*^OT*md*>6Z4c7sOje}rdh3{9P0GWXtx(sbc(0#%P+S*RNXoxR%{YJ*;m{0G#b#VU!xQ{^B z!j}MkgzXF5fEt#G(va5)$0_G#S)KO_B1X$nJKNV$BBU7oAb)Q*i#`Wjwq>>sTS$xmNL7cC@*+D)geV4VIIsBl#W(7a6 z=eR3@n{t=OyU|tWrl*CPy_uISYK(;uXs7?dB-*CUgQeURXpHE6Kebc%iLszUnL0v3 z)Tqwl3q)+AWrj`sbasfG+jF+JH-bBQC>pjIsJLOoCYm{_QBn-h&n*v_+900d!Nncx z0%g{Vj7&?Dl^h3(nTYPkxhz_dsA(EfVz>2*U(F+q@7lEvTDuETDe*{gp?(+}9WDGY zouu?4mXbJ7-i3+uB}Dtc{pAiO5~^~<6#gX1jae4@M=Bi0mI>j+iRG!9%s(J-@uz#^ zjUf{Bu(ZPNJsU^WOr~L-JWv#6I5%yb!mhVfm;p{FeIujqP>~ZI0tQN!i1-=U6 zop*&&HT?3G0LvssOxX)m|Dk`*#%efJ;AK3Wwxicl=y!hpsV?+8yjm4y0K+dde-rO6?E;jVoJc*WTG+fJAR;#)AFgq-7N$SQJRj@ z?sKiA`z&~2cY6gF*J6!#CV-Yomz{+27nRF|*PEtPzn%A2E%w`pxtc$+k+ydb%dz)9 z?$@;*pcd=Kpm;iQb5VI|2W}kCyBNu0B5*qjclHane9#c6j0f9k%Y|#4V*%Q|6sIn~ zORkSjUHI90H&mH%hXrvy?tBYKiL;)*>T?Sic^2^`&@I>IyA&m&TylNa1Uq+<8?eH(1@*qL<(cWnx4Ka>+Q? zY(i%01Z!6=>pUMmhL#isW$sGbYT*FK<1n`D(9UeLN-$;tePH7V+Om&w)NKp2+0b?F zu-f9}bGWN$O zrnfw%aw%;pLCtaB;VTC?g^t7sGfA+}=1RpN|D(R1M$E?*FzWyZ8hpr~9E&F7<>lqz z!2a+ZnjxB7@?&t+(tasCVmuDSh}OBs)Qsl<`8mA@s9`+jxK z#E+(D;Drf@$9{h1rbKo7!3W`hV{?*3lR;&^w{(3_vz3*WW(R1baTr26PA@Bk$<0VB z=%mb?S~8FdJB5oQ66t#Yx)(i~OiMhiFlj)jv zH3|#d$ zh9TXozjgD}BICAzS36?#2n_i(&XB118S9KGGiK#vN2d2wo(qz#*99n!!nPxy+J5@F zd}{e=QX+MX`u{6>E`2gD($wpJg>1Yy43AQhJ@_{zcjA9a$KEfNyAp*+?Acu;{){4NR(R~Voqi*l`l&482{YDKG&^rh5%np@g(ebF zDKauLb5~rH{0%mI1{HxnIJfZLuMod$=geQ0LW=QdK{Fdv=dK9~EdK)s=ls^p!O(ln z!3PfElV8S3(Sxt=7p%;S(qa1gxYZ-uX?QU0f%nXhxsP}wv!bTNn4;DQ9 z{NSJGAf3EvZV#`xVu;-q!9_dCX^p{bcr1QPOq4Hm;#cIU1hjR-?=sO%LPS(FHKB(~ zRR})$;W%6HknaoG*QJ*_Lqk5UbOY6rg0gqO zs+#FH@m-GKQJl#Eb*;n9eZ8#{yz+_r#j^?C!K zrHHWv`1x-%V&H*-nL`Q0*eK+QjZG?p1Qxci3;oTr7#-f(-p0bh2;E=51(ScE+KD%J zLi^TE(aR7=&|8{%2pbgYAgrT!=OG_JB#vtE88FM!ta@tp4NI@ zI|8QKll0FokJP%IwoO|36uS*yWh0HV1mB86yjaB#eIZI(hKDxxvF_Kiz}hW2ejhQ%2=f^F6toZIw|4D9Xomt0cOkQ`Ap!P%0nMluJw+%ptlJ zi}pzo!TKy$JVgU!@tO9x@Ih-gG9%7QjW$15R5&)-$h>DqpSwOw&k<&>Q=Sw~r8zMb z#{FzGtt(4i^1#gG%UK#`z+r_^oeDwRJ(|mPYoV|7NBq1?hexb`{OnsRLX_&2ZzDLb zYBj&q<<&a*whiRyvy((p_}??VvW&1vvShkmTrv=3zU5HO_1Tx{#s8!9u|B=gi+zz! ze~$P(tg7(+i?ED6+r4R2AmM^B9t`I1??Pw5TKpi0LHK4Nzz_0D0a~eZWN*EmIAKV8 z+-dKPi|&sV|2|ubO+L#pV~7x;;Im1x>LAt2DcEsu9FOU}PBOZ^=Wiz+kEW}`%SRn8 zXGbVSjHy98h|vSk?~RZOY0H4%MR(O6rL=U5*Ms5lo)=piKZX zD4?%Hz>#!)j*c8d5(q8;8$u)D{|P_>An)Om=V)(%sf-0rb`S{$YR^JVs>r(inWhIEDA znjbN?e3_&$=_QMT1iI%v)SpO7r;nIanF{~-gVm>+QSk$Es-eo4A!VBrWCrmwRDyzZ zO5sx|rbJw&3fnnbe0AiloKPOPJ3d;7wz&guLQ~$){NbgUTj^2-*JOqTrIOs?kz zBQ34lLj7vTMt}I!hr)VS7K-bMsL#z@TN^z4zxDY4K660{xNI=3GgR=*lCLf5dv=|k z7b+(mlSK9OnA(0HsY6+R*)9c-%R-G~sOh=UL zIvcyJIPZFI+LU||jIS6mRI`h&uqQj2XKf@cK@@zF+Lo(O;$H-HV~dA96{jfT)uc8H zG5H?p@jS_cF_r3wR;+5%aA*UZY80k_cd9~3S?5G4`fB7(~L;5=t`b6`TudRen-&8I>=n_m)$^;tW?STOm*BB+?`Xu z(($*V@WT)&@BAJ0BiSB?NFk11cw9or(}H0Xz{M_V|J_u&XJb8Jjh2;deVj%6T}Xim;O0JD70SL$xH4wsmln#=Izol zy-G9Ar^VIT?}NU!6;;l5F)3?Jnp@;2CTE74q98Wu6D1SB%aQu4n#K9>920aG1Hd7G zrn4_uL*^{eXj)P1ic1&;IXhf29_d3)v)Tfu)H*u;EcWkGomV)Uu{rsK5rb|_LRHqx z+z(Zl)Xmf)s+=`{hX!Q$F5KGORsydGXUG>ftSUU?A~j#-DD@!UVpn*GEdq#>{GlbE zvuoiDgR87Dn#EAs^lsN*`?I=XD%eiGb-5FiSF3Wv=H6d@LN`o`8g-6)9)HSjKj{tc zHfbBUpHV6y;*Uf?KJXZJlfEAud3VcWJEf|w;dp9eIk7) zISV3+w@Ia6H%!5^U4EQ6`_X0+4VhMId@N);9@ROPX<*)Z=P{`4DR$(Qm~R74>laNz ze~It*e4H5Cmz8(NsH{W3(9o2UzZZVwQ2zdSf@m&NT&S62P-5GY!>r{TPz}Ud6p6YV z8Uy+JA(PVS4R7`yhBkwQ3lxspV3)3`Z@buL|B}+%7Ffk_YT0_maOEtXkIe7KUrmeZGZEXJhyCRNzTU1*P|HCJx?}YxePr_1e7BSv1JPSCQi1t&j)IhPO3t4mZfHk zf9&BhA$tP&3u|mqKU60DZI~X2N{&j^JdTQ#vw1PjOF!8yxRSj2@M|%!031T`w)aX-`-I)A*wSbGVj`?V zdbwUsEW|LZrb#H$!8&a8!tpIIDAph4`jGMZxKb#-yZHI8N$SA5+bwatUp?x*!*8DfF@eA zSq)i+MZjws!WJ8`F;xvun82tj!M~ik1xu9Tpvc&RyD)r^HQk9=H$#442K4NJ>UR}z z+A%X{dviB2O&ftGFvx+23|ncEBauJ&-RN&AIb5f7nDxWL1`!hfGK7PF;;hyyyAAh~ z*qv`uRt+I92CO4gVJ^ieGwt7EQ%ZGSYgtb%=}_6UQyR<%MbV3n>ylVVh25`V>b|@h9=y+De`2d9w0a_ z5*h$eCG(c{z$Pc;e+!t1ZaS5em1T%}J9~Kv_PaSY905z!4JYR1%l16&VW?hYY^KC2@$;eW?V6($B8v@aKJK2;*iUYr4Vp30Xknc& zNCU_7*ipm0`%9tL6b8KDO3j)NgQjTIMU(4NHF`bblAbj-MxceY`svfW)~&v}Wvx$) zZ%!&tSM1vPNXt)lYF?}Pt=pcb`UFp$$pELU`T&Fa2W76O$?h%`Cr!`P?+a+tbH2_< zpS%4^UK<}1^+cC6DCqN8F_QcKe4a1w` zvi9~Mxb++)=4Xm}qu;va=i~GFoiI_>;P7w;w6RvYBT&74k&VO!>m>OD zXDY|ueha4E-Q9QZ-YxrKjQKo&uKtz}lonj?lC*{+dFw!Bwbq~TK(rPI2S*Rf5DTGZ zv}_)A3#kk{-RH&d!>E+mSs;6fdTu`w6>XNh{(A(kr1iWCgrIeG0)3xZ3FHjh;lTj{ zYPblBN;_$>bI+fY;s}H)d1F(P3}quo$1^hl@xB1xwq2T!(RrKYG9eAGJGG>q8ue(b zh(C5MJyo-fmDSPyiY&YYmXa!P~Q zS_x_J#i0?@nT?ElEg5?$H$vCd4&9CR3{^u)^~Drw7A56!;SjyDe`=- zU;hGb?o%eh2_F)4QBlzfJ-_t<0z?Pg>KPar{Z4nI1NWxO$Rs|2ehS)=AQOXmHaK>F z0Im-SAuTP<%E}7+?daH;q~9qA)!U?`8%4+b{5(84HrCc}{?%v6Fx|cT=g*&$y}2`R zXApA#nQ6Z|`J&1#4zP4)o7j+$oScp~q*zq#FM9Ae|GJlL7LIRu2;Hk}yI{Lwf5o=D zx0i$T<=eMACHPgBAyAK2R&vvPWDRHG3`*zTnVXyIHu@kSAb?!x%Q7Kzhs>;Z0-uVC zDlx*s%Bnkon~xla<(#IEPPvgF8h^y>2h;5%&C=YoWff%Y$5KPVad9KS)?GnT+YZ*G z;wpzvFeOC?N>0#v0$W5(T>R+pFp8m)n6B{%3?&qIZoc6Chu@HJhjo6#-G@+;%*+L_ zZ*pset^PY(Iy*UWnl9D#@HhrTxq1M$rZ}@^){XB4CUVfl^MON-@Y&GypRu66o}M>v z1klkV&{0APhnWjlGCvgC)1Q?kJi=fJ7Znld;#0wZRqsvO4Jw`f1X^yf8c;gIV`Kth zBp{W;t|fbynR%cJ@LV*!@4!)|p#g;E^1#5r`T04J^1;>)?}mDo*d4J`9&mYe-GRRj zYt2;#zVA$+hr%~aOG|shaPJ~_o-kgnUD@3Q*p{V7Y;6p4kFuoyxt0hCYX@tt)n6u! z%vubgcUh>fR91*0+n5mul`rAw?k+Aat7$}m1j|Z+ZRNc9BgK8+?rRnkj`lry9}w}C zQ$Qew<=m5Db(z=m`iJg#U@F7!EvwRb^<1j?vK%AX)k- z{FvJrAq9{5h`IRQ){XP1yQ@n^M&@SxV>g}+eBrxvGT~ zPToQ7crA$9L&p#~K5wTMMLZf7%tXHoaiIJQO`en@9>tv&O6uy=yq2h9v;+i5+?cQt zVPl6W{DNxl{PMCLlJB6G3SR(?0rC)hH37*VR;YaA4~#Z{q6p|^Lt-`jQHA8#%hK;fBHcs%7QExN^OX~U;6ztOU~Q)z z{vnt~vPRHE~uQV@L4&;q@IULGXD z$pFob%^5IZ`eZw65}`lt;1HR3ytTD8F)`s&NR0wt$ciEpJ13ts%}HNydbzJ9**PxX zot_xX&u5xgRHHIf@2HSwFPBR>O-@Mx3H-l*|6m&e*xPeZ{6S|B46DWTvvYHdw~-K4 zutGyaLt&A^g`&c&_2NGwk{O9bhOBAXG?#fBm2OdWLxUnRRYg_dR=%qVR?mAfx12|n zTx@qk$QdAFh?yCEOP?iOo>ypP|>t0N&cPcBwhEq%=LCWwiNtJZCaR^Wkw2n{waE>Mr3_Qg@&zkmPww4uFI5`_KG zKt&+5mUQ4+F;nZqgpQ8B)o~PUBYjTEJ@ZtGpB;+_JwtP{?bzQ_2HvfV7sX|$XlQ%0 z)hLA)5Z|ygGIG207M##w6v)T)Qny#&>YPh~%xR@tIU|eo3tnrW+Tsh7(F6;%2^RmN zy0i{Kfd^&wLbG03=KUucT3TAp&L5CbgtG@;Qysjv`zUCdsgoY0Ag@W#A0F=4DtE%q znt$MrXA|}EW%mjH)zxQExk}*HeP0)_4@W|bLjeJw6AY5N%o!OOLG$$oOIAv%T}R!O5==dA5m5Lm1S28I zBU9&n8*jxXYug10R(s&TuI_Ggu=ocDBmDgQia)}qVbbD5FoTbdNAtNzCgc5^`!S`H z2>B#>IlBA8>hio#`*{N!Le|%BY2%S2PBUMSa0G2}oH;(n4fqC+}y2FAwlFfgk4 z$>7OWNlZz}o3^Ko?(FMhzIU$(Y_ElD`2Y<1a;uw9C0AM^H!3PBF_lmyKWfG!x0;xM z;Ghee`^^W9yQpf5NBjGm5ZD32g~umn;11b=gJ9sP#ot^vD4)T>fT0^66N43kbL$;{ zpre{LhfU()fLhGvrX9;62jBBRE_--NJw-t*?++VpBFphTMGR@Jh`}G{Kwws?-6;l~X=OUXOnvrH>FxvSa5S1&Wpt}ZSDOpq)`*1{KlWY9oj?_tKY*V zygg=AaS9#dRq}xlm6yRwLT1&seA7@ZvQDvc?+^!H32E(;YHfGr_Bs#)7T7 zm@nNVMVqwTJ<3R4ipbC19TuJzG;q*GyhPuA+(AG_rmv@G8_39;MATMQklRZ7mJl`} zD@#jUYLWHTRYF2Scd$W&&0glQI6ptJ;9V9l@eL2_gmWdOz}^kh7IZYUg|+}uZtjFx zwV5fN_6(UO&UYBPIP3VBn3z0wJ46Bm*eHIwk)?HLFdEGlRMF3jut=qQ#nPl1(Jhi~ zFdgyy@9Qs~k3SEs|1i}EgPs5923G+R#tl3i95K+TzzK#fjtRRQkIqfl9QaC%poA+= z--d<9Lym=owQdhKF_DjTr4<$7@!>5kVwTg7dhrE@R<#z?L-b3NQhDgGTI|^>s400R zvNp@0BcX)ob-0}|r7t_*!EYXS@Ey5@b+Zc#4^Q#wao2NEtXceNQaK$JI+F8yQ_Ofp zT=K?=sgHXbD_^}L?l@xP#X||34tY*aPENs7^*_pSSTO$zX zVdM;_&(%p~kXs?Z31F;8=*1zm-AAc&H{I_~{t7Rr-s0zIR3YK}yQJ|}IZ$Ai-os%r zkkW4c^i3-NgGJFDyp<`mX=X)Ri9%VdP;cKVgg1-dL@X664Dp!`M;hson~~r{ z!tuAz!ayLZr=H5m^}uQu7ZXDu(8F@z)DRRTO?afOPm#s{lu*U_r{a`>pdfl=O|zau z#lGM5emCClC7@l{LD32ya%?5lUFxq#Ld15A_Px#%18;-e_7{3rV#f0K*_5r{gfqb@ z4PQ~RZkS$lwf^+Cv^avp%?qBW<<8s8(jc8GNR6aMe-Bm21B&Y?cq|^{5IXj!Wn^Gq zV=0#vaLOqv-n`<#{L2O_SsqQA`%XU&j)s1v2c^1-QSOm1ipENZewUG#?}fyz*cnpW z&u>EFZBmVO|GDAk6-A*0eyK977 z%>J8hPFPX~)NkOS%vs5;eoh{h=wP`XOZLehsvIz8Emv=L+#w|=--KOudmD=}9u^Sv zmMb96L}`Vdg~bkP6gZOY?><=b4pHP%u1qf_ReR0GriNSm#7EDTuE?gw*Vor*NRrNi z>;YPKsq5vb(;C@!`MJ+C z_mkrg_%v~DlW7)o(Jdd`i!p!t^l5c<^2V zx7}|P@$Cn>}^EhmO=&NE|nBvk6mMwfngpF})SXf#bHbY9dLru-eeS;)%W8#;*WD*v($84*YRfK(&L&(DD zi?J~Q%qVALXZKThJvut}Fod3P+w%$C#s(T5xh^$w^1ad2usiC>vIx+ zjUtN-9(MU1NW2TgPVz+I8!~e8u2jDGec~+%qD_OfpK4m+3N%L+MsssB8VrQZA3P{F z!qsx2J~yGv%9@Rz#xO47W$J`7voK4phekr6(v0r|0?~Axflrm;;;OL0j8S5|b+sIg z-C}%;VC3mK%F(Hamfdc%A3siPy~Sz8%GvR&Yi-I(-=*b7p`_Bj_@Ji!RDEn`RBTR? z-6_~x?7%ZUiCG4VqxDs#4}4sgzJE72GsAQzm9QYdOFsog(Zwk#)#4E>St5{CH=K^1 z{w~EcQu|9yNhVLwzV)j8meOp{L3sEtXzXt6Jq>5XP~bi z*_9Rxz_LiO@>Mp+cntXq7go`vz`(#FsU{U2c7eU*4_t3tVs_PpbB8?rl$5ol@_uGI zp-*m8wst@64Y@kmoQ#!yaA5guqyTl6H07Z6>IxBDvEgvT*%ieZ_M^xz3}YHYQ=erpu4pxl*+4r>ufw9UTZSoov)lr!Ayd-3$y(NTIbhSQSGB^ z{j;$F@a7)ek{i;G+(@b3B(-}(!}yrslG@idgM)!>F|-(Bt@`1rib+X%ISJ8=A4R>d zq(th|0UzORFgGz-N1ZG8OaQ-R2VrM3>)Us_G~v!3%oN(STTHn}DLmzHPT+&QC69f$ z+e*bimmz$efnM*@M1KCZCTakvJXfQ`Zt{+FBt(O%}h-5GO z{M(fL`QIdR>)E=t9aI}n&uVFD{Z-gEtsd1Pa6ur~(1pVKK&r9V{e-i%6%{nQxG?u? znRLC_Bs~(LIcDd*89rbS%}_z)CxuqiTRrm_iIG@ zJjLTd6Bd2I-qkf_>|meF!spNQ%z3JQNt4+;W<(&iuRbq_mfXI58yGw_HFfiHCm-hi z>cEZivBAsT{WjM)S*o_pHbblNXN+}Agt;Id3F^vI`&mw)$Ppi<3tN)93AB^j z<%;t{Im>x&D)>gm5K9jHT3ajR5i45Vw(d%Ca8FYfTPFLY*o?8vB{tcP=2IFclbeT2 zqRZk~z3vA*-On+<<=(d>K^3Y%wP;fjY1@Llv!U!ORqYyZYUiH+P8y-qbQI z3xr!xGx0}sKVLI?;;C-EkqVqCF;S=WXNLfNnM{djo-xA+OZYCw>)pP5ak+ZQX`oz? zE}zs?u3lnx`fb+WjfP!J zMn(q4-@1d{SvYK-v&kweC}{Xa6qtFJ<_K9WDg|$&nU-HkhAl~Ab)p~1F&4~42cs*? z$Ot{pp6Oq>;(LZw-SULtr|)N`oe;x*ktbS=yU4h%?Q#d5c1kbK6ZX`7nUa5{CFk~D zK!&%bJSCmsjT>ank9j%mIU0uD1BmZ@B?tEUCq3{K(p}?gb!M@fp|PHRwLPmZE0~+Q zW?NQN(Bb@MrPxRUAKw+25nyBljc`IhKtNGZ5hxM&9uho?OhIf`F|iVmOauaU!00h~ zd3iJmSR;WaPS|F6ynMQhmJ6LM0(7J`HQ%GR4SC)OUpc(K0Nv7=NvR>=BzN$dA3OF1 z!u8ZD(lyM$&+>$xSVOq~Fj8VKjnB#ytD%*#wlA&YEjLciy9p73VS@youorer$Cn5N z)ce$h1MZL~@~WJQnXKHS#<}upN1IOFgGnj6&@E@DOrH;#tS8L8rJ>2|QOopx= zG*-MXN{I9GboYgg*K$*D#+w{eELem$QpaU!+-8i_6SkKrT*$xBwrB6)<~}mn9rM!0 zmE%~M$jTwHFDjyz%ueNp(Q(m#zLB*`f;i2*y(#@-OqokdN;aUs-?-V!g7&fEyHZVO zCc)Iep;_nZ6(S)sGZSPbccHh~QstifJstc-4o*XcT&5kA*|nADq%n>R;bJJ`_MHA! zGI{b9ozS{`ZnNB-RXS6$t+%`*om_e~C>wl~>8&^p8E`rzHj3=n!5NaU*PSk!4XbPs zTmy0uu~-2U`JwQ0bINNqQivrL&248msP;MA=jBSS`%!uRXq%p%E(lvsye09J&1`CN zk~Eh2!do@7Z-<%a=y=tGeQ@QUKE11}s!%?F*f%_k^ZjbYmq(YMIZMAJ9(*o)RAWKc z+1}PWvh2#`*}&X9_3Avj?3c4U`bEa)xgOJ?#*iG-*-xqca;>2Ox;UlBwPIV%JglOy zNxzk{gT${NvB;6)*j;72v5mAmXK@M>ysRDS0dm#+5L-&@3Pt=?zeNGm?5|Q zrvt1u@n}gs(n)SWTio9itf}Kfmhrcgn`a9zFZ$DwyNCO6`bnixKAEH}-+Cn=gx7jp z#_L)r4{!F9ZljoB@&~6qy{ZMRbYt(hXs2G?wzaN&dnI{=g>_Hp1BFAjcS;VUZla1S zX9o>TEbj*4=BF@k^y zzpPI4tH+nuI$9rcV=0&7EzSFi2+sGEa60Awkz@+o-f zjI36?ew@HhPnyAun$cY^^_SPjKuL?kj+rVfy`*vXJGOnhMm1_s>%Q+n0O3mYjg*x4 zZBzBVUkh3jF^_`hrM10cmqDxf^)8Q%C@f!m1-u*5X0ztmci&%5b9!I-FeNp$goMQB z;D;!|U@&E+Q6ncGZ1o;nAujQ<5gm1n^dj54o-TkeOB4(F{&5Ct*Z{I&{ zQ&qy8$++^#x9+kz_hs@F3x5YH%A-ayk_U@a*!t>5|AxVvXiXe@Da7iOBNp8au5Bj(cZVa6TK z?78{u8H~*h9XT%Na@4>qk#XzxUfs=o&#Qg+PEj4=`LBWA#&uFktO{!aN9b)v?{p_! z3G@w*`-q`Nc(r)<-5g!~BDb}fk&!mXu45;-sQ*g4?jRbS4d}QUk*0tA zw)I&a^;3)df`ZI^DfGpF)=@1XnZ5a1L4hC}n#E_#qsFEI7C@9OTI2qLMg zQ&HKbtc(GLmoY6mJtYML;EHS46R|8S+mC26s1@#DdNU1_7s8`Y0JwO0D_?!~U_O-0 zT`{qwfWHP9pNxPaA3?Qgm1TKtVkwU1oIc#{Z|rSe?eH)wNwp}Kk(QoE*%ulbipiJhuMKM?dzop`F~!sIxYhZvR#Vq_21>kZZR4Oari;FRpJZV+ zGNQ5N=_R;&yncMX5u6oDXi#~XZB|ZBJZx;W2=D-D1nLOZ{_1L3)4*pfEfMYOoK&l{ z_#IePIANzcwg&dR71h(zBaLFIsIH7)DO79Tl0~o_rC;uQUgqD0VT`MA4YrSy;_J=x z)dqv>gtEU6D)W^*b(uF9n{uu!J9<}$vcreJUhKH{_tSE3x93-o=U)F4Tdi33Rzg;6 zjuz9FdJD8ZeE4vnc(9|h6O}7B0gYZf3NFkjy9FMT6uJXRGub~M%vy9u;~NH`2L(&^ zF!xumvGmN$f{LCoSFX6Ag#mT?ZDmESLkM;M#VB^A7$%E+waCe|)iat}i$=FzvBzd% zTv(_;SUTn79xE4ZVd~J7)*}7nHHlwhEMPO-8M2UsB`IlDC^ujt`E6=vQE~Csty`_- zOhf7^H^NFs5>)nw+L)NoEo-p0jgm3E1EA#QHU@az+n2t>q&Pw3uwb5rOW}(maf7J} zky}&WPd{pE%D5-A@2?YA$b`ssmJZ3SlLT$r0(Nt`!as>TN)jKX=+iSFTe6TB(Nn(h zqHAY2GBH6c&#&*V4y>%Kz)J*4CV`+9{I@i!_J6ex`_cp4gZ;qBoA<%CP#2ZN-Q z*?w4`w+Q@RUq7Ofhd;UGh~sEKO1|;1`1l4MZRxB8VF%rdsXO03y-o3?+E;%>UzD!B z^dE3UQZ^QG$pL5wK&Q*NM|0Jr3Gzv;1!<2k`kbb(jLy};wADz9N#Dgzy`upSZCVt> z_V{9U#aW7cCypnwtP-qOS$@V{9u4dFHM6_X5SLaKN(VLUBL<1?A&%UAl2G++q_nWoI5e zE-N#L_yj`3Drf~grirO30)r~lO3g-4!Z(aR6BNz3(-UtTLO!XPlo$EJd+)!D)x4v^ zgDvxpHcE-UWRm+{fOWRRnCa8a1zZe)r#Mj@MXC>YcrKR1Xdh9i5-p`*u z%RT2N=YF2Iqw&Nn(|Ubv?GUUWQ5!%&orDXoE%ojGDiq!Z=C)sui;s^!^h40&dYbct zsoZMNR9lokd;a`Mf1%g3(|CuF@txov&K+2*9$N1)D${3iVW^Zouw;&IZa`y~3Nbr0 zy)x!A%SDmLYH62No$npHyzdd&K;`64qZ1tCKdbzAYV&vGZaJqDaASX{BhOS@k#Dq` zPqLTB(&a?@s9Rc#lH<|Gqgl>hgn&`8HnX3qD*_{c{zw#`+~{#<4gNGRfr@o$4YbmI|M&9)*Q33iJ<*e@YHNC6&4sEe z`zg$RPPj5juso8@#?(sPL^rzN^HB*DETwUXVWdytR>do1?#ad4S`&@8^-2TyZ8!)| zlB0L?EKhSy_I6NOcN$=R_MY4yd7rb(;>SLJXx3VE z!VwVlynL5zqCrVO3++gpYS8PZE$J1RG;_`)E!j6|nN0QORiyGiJkaF{b)@qkf8e?N zDmaWU&*q@IYQUpl;7PYRY*03PdyBj7bhc^moX@YN?s!G5&LfOnYs8eiV(LL;1QC30Z?oeI59xT0pzF8oWZb+ z_?Q?B2E&1jvmb>tZZ!m7?@Rez&K>IfqN77ESCj_KzN`=V)85{5DAlY4<5c}donq`s zPoTQFT3V1SmWEqyUoeR8IrB^oBMtm3_MBSG&#t`D$!(Tx^DN70`_RS?&E=uGP(Rzj zZ$By>$Mo!NH8nMH%F*h(O>uYSikH^+sBR7LPpqlkbwB#6innH)cTM_|NX27IwVf8# zZPi@6=2AIQjy(`cGN{3>k_bTm5qaICb(DiD@q@3$EQP4dReA=%(FTB{22cGVMKoa8 zI3|TePe6CJBsT3FvgPWqe9Oz1Ig*)IsBKn>Q`en7#dKNCFTA?-0kLn{#*cd3|N4{9 zA4!~7En|uBWGZcL3%XL6*eCmWVlsMoXeb~&A*sbBoaJ)-vHz?ekJ|E-Xy17)ytFXe z+x=6k<>WCSryGlnUy<}-HG9a`y(e1=p^gLZ-eN4|2z^_y!rd#nJ-rQe65dS@ZMKg} zt3=nG=A!;^r)+>Nb}N0ybD>l56^&M%Uo7ViQH~mo7ArRIWsY3YVw{Zu7x3TAj*40= zk?Lx)iADb3#t80()ID`J)3-@=s=JN@Lzd4$%5Z`Nm2t?4Tfe-#Vy?3vZIh#1EAl>k z_}M;1=Rw=b_Tb07Qcev4*IV5Q1k?}6iKD!Eh4K{T&C)3WIZkJ`d(YXw6IZ@aB#P%A zlrlxNdRzV9p0B7?ih(R*NZZ6DDd|lHZ))d<4}t{vkGEtG#$iTo1g+m*p?XrZj@ zGB9s^;h5RPc?Sp|t2#Ol%d(Vne(VSyr3pNA)qTSi{as6C`C{Xe4t6CVDgF) zCU%jT4=5_z(RNxnstq5h2c+=e!2@h|ub}%VF3bFEZ<-|!`)b6 zTIx^3eUd_c54-M%E>D7E-6keBJu}0*MPKUF8#J-GZ6qd?4wOZ^e!D%7Plikz6TceE z$8AOZ%1Js1ig*A(7TgPvx|{UX*D6G`i51NH0Q}bm2;=nz5Nq!j$)3ZUxR-kfQ@4JhL1jHyPCKOISE3vmt%*YxmUiX@0 zS9*Jw<-0lU8bvmzPZ_5pp4|VuNqrA1{>R&0D{204?jq^ZtMjDu@(XjtIku3Asc}`8 z-^_gXi6bO(wF*S;NnEpsa?Y^IzKu$4kf0QZ&y<&SW**g`Rppm1%G_1?)qW*3iR1Iz zwMTC&pIVXY`uWu`(t?i5Ih2a>V_$tGaI+sje&mOVgAc}g!76~dwJGe+!_wD4QGE(q zN+||Y$d=TG2uoSlCh7-Ls0k6Aj{j<9uIA^%zWeg#{@pxr6zqAwlnwRtmYlO_pjY%A z65}wucJ=DQ!ou^}E#=9{C1vcEgXV!1Q?rAAf^xDOOll=NpFFwlwK37Q5-?bJ52Gvo z0KBQHkc0eC$3jR>Z|mW1jdb$zsO@BrM?djMm|xgdTwDy^WNv1L>Qr8^U*wNP8fH~D zmzG!j8V`g3dnC|3Rzu-&&Y@J6spyGt5ApEvt|w1~`#HnhIQ@vTF>3>*t_er)roL(? zR8f)>P-4GCV2FDQfe`WN(RlzsvOV1G>;iFs+}^%<15MTQv9UdJa*Wpy?#Dn&`vwEf z?dWPl#rS)FL`tOa1{#*4_zd?itg~{a_ zX2sjQjcOUkll7C!)VlUwRC4HSACY?{%?*=L$5bieNrv18Dv>5tJ7>+Za4Y_J|Hv0Z-^G zQDGgmR^6hF>u+V|`QR-mhbt;8YlXD%n_tov#qtOU#p=+F+duuAy6Fox==$~R;H~!6 z+=EUQxHw42HsbR$kK6)-l<6KDMr}XL(09!>({YR1Q2LVlyF_7c-6#2lQ~g?-{Bw>l zQ%mL>Jc-#yq~$!oQlt^DC2H@)cAj62({=ktl`@w1zHQnilrg@Ke^d<5r8v6oa%`;= zp=nTC>u+dKtMklv+`Bd?IaW%D7$0{JmR;I2xp^{%=zOsuJmH49o@T1oJ$JhH%_(TQ z5x%GJgM$EGGs4CfJ>h`D@#9~iN~2%uin#84_YkTYoo2M|FyHRW5F|lNWNBMm9)4#{ z?f95pSXij_cdZyuDt;(#CCVNrZM(JWophmbCD&8W!CTNKRbIK9I>AOQwJ6w6Prjf| z<4|4{ViB&7&}+S^EphwnH+dL~GsZ&qrrO!WdqVT`Cy=#UEUrp)RETptsZ| z`T9{2ecLPTr2_O(nOBas9=5mpHlyv?me|oH;TWQmKlR%o=~^dx8bj1eS9TtEv$7(D zKkx51T)qV~T)+LM>x0S9pN|s%@+kbjYkngsM>4I{bHwaT#+evKOvWAhW!-&&~Oq4CJphSr5>2 z##riTKFC=r)G|A?mhJ+d)J-57`w8NP*>Z86x+$XB6ts2soB^_00uN9N~)Q`gZ z(Xwx)4MHl8Qp2|^&YW9iDeC~<1zg*+tjilRxG6l|-LRwSCTn;WMx0DtC?u;V`+2iG zI5?9gQgY8@=!vHx~4K@PfjPC?Y$z@ckVsSK}(@hSQJmk z`?9U_26R0CR)pBXIhCa}*JPI}uMx7Fdz{K=N_ zk=gytVUNgEdzsH!COI_Q-!a+V{QAzSXGi5~kJUMPx_ytAq?7<-;Ip@wpvbnDCqOJn z7G(K(Q2Drc*&eZ+_fD+c{(Kksy^Pcia6<#{j@mq{^P!@Y|5(AtoA!bGG0j?1BG-8` zODg{@&O_8z{M#gVCI;lSXVqrOHZvy|| z6~iyBA}ws2oxc?0hu+88)KM1o(}i;-6*Rni=P#m95`p2PB5$<02yFtV_|C?M55a@n zD=N};n4|YxB3OSxrHo@)p)5zdKtxe&pC?sprqGPsK-6ttOTBFNeL;79nsPX#T)$5f z2fK8#{p~%-%ay!)I3_A@RQeUG#+A_CA2|l8ioLioyscQUy>w~=n$%{@*tKb=N}Q|u7A1^huro;p(V%S!Ipa(|FA_R z&{k32A{{LS;eQ`!PZqllQd52)Cmi$h18&lD*rm0OuF(IS29rjFi-QfdTr`Bzyu44n z^~dXcQqs_$*HLy?@}A>lPnOl zRW?3r@JVB|E~sGJf5{*o~k4N$e$?7q}1tgrIstj;Q;rMq{(GD+v zx)t7&s>|%^=!odDx6Qmq=(Qi%e{n5zP~>7=1M8r?U0eeNK0m_pCTuyL8ZZ%__Vqd3sbo&oT#4{ub4X^a^C_YV8a*));7N6*&RdW= z^h+BZ6I0*w=O4eStlSo>y2%=tqG;J8@=Ts?l8e*Z-hFGyhq78q4*}RT2z<1+RnkeX zkf7p6yyx{Bb`PjlA>}LdB7VIQ(8_K$KIJiPp+8)DHQ&mT)2Vaq zokqCQZe=YWYjGn!y)(YBAlEBVQ^yg{&iQ$d@tooHo3E2xJ|&JUuUq4M6^1RMw)^-U_(@svaOwrsn1l$BS+ZV}qj1_Eq44 zpypA~M-xcEuk#&tzpdo-AU-kyB@TdpGJ=w_vd4DSVIuQm!v(SgDy@4vic19h8}m*%Nk~>sLIM(2xGQ92^Tf8@v!ilW!4; zYSX8=|rc&G(V>fsU~nZe$_C&ie;0lGXmR2|*Y?8)~xi!5f~-XM2?WSAO?x5Ybl;jgUl;za`l6^_-^3{ zH5N29G~_v5aP69Z(> z0mTt6g7|4|k@&S{O3!Vy1)8o}t>HmWyN9@zf+?+;X$N(L=UX!Ai;}CC&+s6a<~1q~ zjG#BWqKd%mzgRJVzmro^>@Lv_?jiyGkItULLx2}JCME{Y_&inC!q4G zzkAm%o#0WXJ5L{G@Y+!r`^EG@Uo$Q*_18gAyjy1G8fFb*N4D-0>( zYu$LIQ1g?5PS#iF3J~><6`Ib!i;N&CFYiBG_8eg@XoBzgzefW$g7TKFJoO*hT<4!? z8gvzIZf>X#;riODbkHa?bj?ukJOzRDRsm~YDk#_rF9PD%e*JQmK3A|Q+dFr!?S{-v`hzy(RUYRAeV!amZhS`ZdhKWP=KD}h z26*An>@P1b<6eeb3L;8{5iaytDn0{3YKI_=1DXNJ3^)z=JGilw840B80z$6D#5tH$ zkThF(fQ*m<4LS?U`276ngA<3HZeEFl6w<-b5&LAfhDH+_74%ITNW&)HfB=?}Uv1$1 zdre3mL`9>+7ruRbMzWMZfCSSOITsz&Kp`hixI7H@_3`)k8_DlE4c-!S3lNdS+1uUH(n5V^FSH6+aa6l^BGnZ26>Aru z{=AyZ19pa+cpL8w_8jixw|iz2xLft_enJv=Tgk_Z2@Bjy6wLXWPvR__N|=+HE=@KT zUf!Q*Ra%kusrkJ9hN>P*vOoM^A7^HYt{zhVl{=HCJ;wI;uGM|3?Hc18cXeBCth_x? zak0C_*i@T3bo~OysZu4s$eHxE{VE;Y?9D8vE)Bk3gB1@*FIZn=BS!(P)W35Aae~#9luVPTZ49%p;2=OLNHWd}hOJ${eS6?vMdi{t#LSV* zq*r&}_Z{B$g#Mcfk?sw&{_)NCdsM20$RPfD1-T&4C#DbPP1EC;p z<$=pM8S~Xcj^NlK)fM@-A@Y5mVkyAOyN&@(J>K=01@!*Z2Xk|C$kINVjTPzB2XDtM z+v$a4fH(CJwk4J*Ap+mx7V6Eqy6jvn0<#s-aGyJ^&QaLzO)fn2A_Z^J%+0pT5`G$^_qRTJ`T#gu}EQUC4uloY=!#LQShU|)X#cLnb61CQ9>e;gDP z%(*z{w&e3ampvaO;{UE;usM7a<5tpmchCi<-A!EtA=1jz(tiZAa+{ksF<%37+^`fW zOx8@9x0Ij%j_*K4sYZynbcs7imgNcSNLZJ1;3Vs8^jx}3 z+)p{lPw1Jl(p1TRDeaOiGOJN77;8rv8N$vq%+0wZM7MMik^1OgC7$g?(J-gj|w!n}24 z?(1#b!r5NYk9;#Z0j6ZneR(Rrp2v?f`?cWY#uIBSC^(?4t&PEBV@@&H5H4KY+$;SE zJp@5sRH;TJ5<^?}s1fe5lMzDCo+X)ZiCFH(N9%6%HiqX7VplpkzCvf)b^zlXhOh6X zo-jp{MKUSoRwFdSsfHOdtOkqmtq275;7<{U9;51kJ5x_WqNuK}4kI&2sqDK>Y*SCP z48y$H@bGX_U&WIS!A0)7V+uU(FYGuaW=Aq(RD*m@MX>H@cwoIhTE(2M>mzfKSjm}A zX@9D1`}W4xeA`#^5(0@kk@-F`Ge$)f*^FV==T?b%#yng33M!Hu%`tPQs=9i*%RjJV zPq6Hus9th7J5L<>hqDRneK)O6e%+{omzrqI%0|^w<&eKij^2k=jn%f{-l3WKgDOEA zOC{jOgiz#}<*Crp9{F?-PfX+Hty{BC7x|%y-hrzTlXox@38xa;eX=*xus46etpHiZ z(gm36zJ32Lhv8~BZbTl2_F|XuS)5u=8EtHAzKyq%tD#C)^BF4X# z_(+{?3@9io4*XyeShu2Zul1QT^Xs!&r#rl!ZAUr6HlN11uy{J*YEG2sR=xa zo^bw1K-_DMbZYn3sHabja*G~?e0C_R{a<+4acoa~{j(^ZV4n6y>N^$rI|aO&-#CCF z@CwCIg)%Gep*$b?UN1thtlF+!7cX6Er=s6bwAuG)sI%~RxP=8%dBM%h^9lMj-&Cad zFKKa@Y82g390(^Pc>#rjRE|or^53|0T&U}K{-KK!yw~kdWhK1aA!0IJ*_a}v-!M#a zU)sqQee*gfU2}WMWJF(|Q>;GQzK@T1dR#`g?HaZB&@MlVyoXU?v6ny4Ne&6|TRxqz zeaIe{&{?Ix!NnB@a0(Akg@*wJ^e+h8cYRj}*^g7F;NnGlN5}g}XY;&9-iCS|3i^Vx zi@OLdI0$gYTSm6pmYMmE*3E(Y!njw|y61m=`v||fAc91puffIw2pt9!9`?SHl9F1z znqew$Jp^pqY8LShU%qU>RYFd{rmTfs6fi7g0WUULn{ro3HrQ=ZjDLyDLMJo0U`w z$QS#qWpj(VNs0ii?$bNO{C6cX8zmi+uWNW?#3$N0f# zHfwL0a#lq~aI$ z)(m=bg=*6#%059--oJfKSbJzN*KzXFs&(lgG3+jC>9#L}0+Bcaou$NS__=ecU(4lv z+soe`$W(aP{H?Iw2d2k+eHvqjEw>6VAS^oEM*r$%udU;C#+@=8Q|&1q7;4q`54f2P zhG;v#@5vV5Gp?>OwuhnC%F%IlVc|S}2{aAPd6&usr}r>;y6?Um*~;s#d7cL%Kn#OH z(N**%|FyVU)qn$Nj^ ziISJEGJCU&&lV!fWqV5Ho#$8z{fD0Y5-oiv8yHrvev-YQ(I=hbu8!fnehtCQgQX2G z<@f5G*YV?U~5k2Y>~ge;hcm#*5-;}cXqgH;jjx!Wb>TW-8fV~pGu zk;jxzX>B^9t)0B>p{L$yQ#sX=b`v|+rsV_P-lb9-0&J(a56DfpR=rf#mFX>DxyCAf zaLBQf!DVox@hVM;gW|Fy4VX_{WIw)rBaK(X#hH5#wRFpXl@;8+pN~g~FmiOc6hCDl zLy+Sr{iD`J5t>as(ptuOPCrZtNe8w_$#l-r>3Z&_mtqL;XL)Y+ z?687T`Q@kN1R)6t>c_eNVKJuvysQvV**l@oxhl!Kh3vXRU9^%B?JGs*kkINEN5G73 z;pfNPS!3HqPoG)2Ph~9Li8P73pRW^-+xn+)4L%X$-bmH)iZ;^yUK3?$6l@bHS^52V zjHPL7jpBt}|6sFIQJ&XN|K0dCVDR_L-TtC%ThDEGjO!@}O^WL{-0Y9t)Jtmc;4Eh{ zU2jPV2zh&lcx-b;z>#dd@Qxb9a)SyH;8p@ zc}qM7aT@2=SV-&cC%81xR>zPlk9=|?=cH4IxP)P^%oVY&&6N2*wEmt=oG0x@Zhw|^ zMiIlnw1szm;kxyB_j*&(l^_}dBRiKF^fxhSzLla;9ihVKZtE>|FJIi-#7NWPZ`FEN zsFJ1a()h*2<;6#Ji-SF9l*Z@dvxll!*rGpC%)hA35Q9LS-q@2Ql%L5E^Cs?^-?p>L zO~X(z#5p8&I*P}_>y6SLy#Xhs{^E)Fj+S+6l(t5c4lQ2f6go&Usn;yGTv&K*V{6OV;crZ9)e7GHs}yHz^MR*VZi|{ad?xU3 zNLP`$>TKuAWcS>Dgcw$`W|LsM{J~u65!o^wX8esX(dB%qdq zfMU5Hh7zRI<)6H`bO0wdFTdI{ZEb|eUXVtd7KJOBISMx+11!#;^ZVdK6cnX5gz zL0-a3SDuLOU0PvfW%U`fG8TNXP?(@zz9FOTuv6QJ&S&V_>Ji6^FphV=wRV(~Q32X! z{)wrnoYyYjH6FNCx9CMSaUx%ZO6pc(ZNOHhHMw?=rHhK!O<2etN?LCf@wW~Zs;p-F zye&{W`IG1#?tMe7nezPaUUSC5vhW>xJ2dP5{{GOukeW?QFS5V<3+;@m*!1kI>4SIg z-=BYy#97o1d1;G;u;MidP0jNIg*r9{`$)*yo;`aiJNm>C(LqJUs~jC6s30VyZTBHV z$$;pq+%j^itHs?SAubw#5g=l1qP(W&)*amKA9O;7^GZ9qM0qxEMdXP0ZgP?}JHOiz z*>|*l6ouH{8;(gb1{^AL1^ zkr5ySXdQo~qanhN#V<*c=(v~)CFmGBAH;qf?#m|(_x{yi;$Gv=C65E1!Yv*>5u6SQd&1@=^s_>&U5B;&i~;#)Fi1^qPA{FVXo<5 z#`O2>^e4Lp<)pi6sg53i1zMp~yCmoG12EM3@83JYo?(0&X!x1#7ypa6IsgJqw?}6l zG&Y_^@YXerH|`28H!!yDF3exB4&ogZ|MK(mgOCLubi4!td~U!$Nm}=$q@Yu$m}zOd zpFWKc1w;B90@YQhv{9d+Bfu~QGRrtI&Cn$wfTaowx6uxfqW>TsVdaG9%IFECGytOo z3bexaC@BpAHd0Xu#v2Kk2DNl8{O@TDr3dtfVhwlX^J|*FQH`KUyQ&_d^!*55G;(H; zwJ0VoPMNNR{+H|AX^47BY3PGK8-M=T+Sm+4fI5dF4*?|_YHDk!cbCNI)Y+VDv`?=S zB0!g_?cPmILGca9h_pBf;t<;s<}=wzS+0(jMbAYibus-^}e zK@3_1fr|Pq%0k&|F)gxH58*-=cL=02WJ<2-CiM7i z^0TAL7Hg9>Lf6T@E!%{Kx)~YEpL>Z>*q9V1eFtA#bhS)2TDQloNSt9HNFZA-!BvZs zNowc;+4vmYQm$pf56{W7>G!OL4jkMN%;cE8=;Np2T)69V!luA-k7@oB-zK_tWJ4Ex z`xZ31=YLh3hhhjQ8aQ9yxv$NeVL)Z@CdpD!g{=c{jxqoJ{rh*IOu&^~jE%c7zCiQz zw`l|=wrP1EI^;jr^oumjz|L+2(vI#2NMz8`2>xURZ3ChgFip0QN_Q^?Y+`qQIREoK zFj>U+1&vf#qnjs003d;>*U`?-6)Hne6aQDrS#=EMT?QOwkpHWoI012w^~J1S3^8>x zrey&;Bqu;pxHvUs3q<4U)kiqHaT>PLBYg4|Xl=OC`tx>tuDL%pX(rQD(oxP#c#V=* z=2jCK2@P$;5rIM)sx|yHgofQl!Z#pPRMnyY`_Z^|)U<8c+vweQVKM`b?GpwDozUxS z-~TYCPG?ko;N-FY4~Vvh+-7mH{*_xJn%Ka=JMfik%zE~|S5(NQ8Ctj{sYIb+;s0Z0 zWp6m=#i!=we}+2f=L~!zy|lUGVs`1+Y^QtI)7OU%RdG{#%1hU0NUXe0BT&b#--|0G zC81J0H0Z7;cTUH~p*?(+vNVB~L%m}~-cFIMes>eUib@xzl*_budB;#xie2}b?9`SB zbS&q18@YUzb2gQ$Qm-*awQO0M0cAP%Hx}s9D@V7}PY~$#_ASo8_k;+5hUYN|W^8N> zCQ67-T<#qs66%h=TEqglcmMv+<>kx39r3&ej}4bwo(c};U;^0j{{ylz8&rd)jgTFt zW@%y3hxTxZ9+FrrE$msGGwto|=twCm&TanriTVJI&9R{pV>lep>fa~vBoQ#L0IotT z7-H=(&b`9@iEI>(CLC1YfzVPuM6$rZ_^Gue4=BL^?!)(h2)Q#*5a75$bBnzlZAnKU zdF@GKULjypRR!%U$b6R4)70b~P6oiBL@LTRZ{J?Z$w7o%H*$bvWqSt)Gu!XAIIvPK z8w(Gec@%~OWC-9w0t1~9e6S(ox0T{GB6j2n5e;7YU;D%6RSo*uGlHo?+&71EQ}I;ymE zayULM)s83#O}y`LQItFsz4qnclM&+*$uq`iInf&aLOL4mNBV!R$PHM2!2?3yj0OX* z|9^2Mn3|Z3fxv=V59eH8-VXW?bf^Z3IFOup{``3e7$R0Il4*`((_{M(B#c4YafZNm^>b8fd!NG5Qom4)~0^$EFKpLH%>J9r)OtF{rCavDld^*8|JWMudh+zBbJ_v`%#mV&X9 z1k$Mr`6`U&4M_0dNkUeeGp8b*{^p;OP9?Ldt4YyJACE4~rlEJo5dR4+r`}Myr;@bFyrWZE@ z$f@z2%zf2g7I}DN$y_6Bt)69(C&u>v>Z*)*xunxjQXJ(jtPwz;v)W32KY+$Zh(9p( z1b5PR;=YeEo{U@e`6Nl}hpgRK#q>pxj)j#sfHUfcXN5JhMRyI{j)|cNJC?H8J?1eV zH#Au1S>!JLQ?4+TJH%>u$@_sL3Pi;uCr(v?h)}e|jD4Yf<-DMdg4< zSS>LjWm^<}XqLDsmdstO^r9k=C6!R>A;{!_RZbpMFPLOTO<9Y#0e*#yfVfo>LdVU0 z3E;`f(SpRH{{@CC9HA!+eEtrstMbMTV-)ypPoI!PMAWxTH6WK84m#d(Oj26dI7`?Dm((A?gq(Th93ZO7B3ISMpgFZ*h|@KtJYR5gmDyAq`VDahaEg$P#0o#&#Uy^)%5gq zgJL2EHE8sZs-lf?y*QQ+OxEREOvB=RlZD*|D$BYxS!o19jYA{QO}ioLIY+uf29vy* zE~7Td4sE6OmP%JY7?=zx*xbQHFr&A=Y*I;F&t@4+Ei7hcgDUEI^j;rw)P#zCvrldLWDD3n5Voin)7W)t28@sF>9CHZJM^(KqTH02}@|L z%gf8dF&hKbEUY;s*2=;n3}739fa~xP08#*HRaHj;j3K^+nLx_zKR+cT1kbNpbFQT)zO)vsk#TL8Uyw3NZgLAfrZ z|E#m~5Eyct^?*wA*g$2hd8n5MehhpqHnt&P#)OFIXmY=; z*$YmCjTm?8iE9JmCWQQ9=!T2eqJ;?5%aua%@=Uw9zy`-ee|>IiWN63KDg1s>Qc>R3 zq?K#Qsrg~xRNT8sYc}JlrPWoj+7go;_SP19--&aTH1B+ko@8as=$P?jWR)IKFHOiP zOKI#&VABW}<1c$1FM94Se>zu@$Wd7QXFTJCfhrKOMxEGsf z$x?a!PiU5@vZow!0plOd#xZThK#kpa2Bs${EDH8)<>NcMzUo^gLSkQu!9_5}@WSi#jVvr22BOVY9}to(wL_$~SjQ~9j;Si6`${4Dinyi5_h*HF z6W1VH|1K%T-%;%sUB@UAf=nU<4;j$kbaE;D<>AA~axixHWX9udb(sx@MkbW18@Z=> zWSM6?#tDeITSLyxX-xJ5=Dd}kpNfG8Ww(hPuM-h-#=GByqWIXR)TpGw=5!^Vct0~) zovZf?3k$*Geelauyi5P+MImRJ?kh~Xlk-EZchg7AhU27cf^Lra`;9*0J6k&khtBdo zk8TDx(Mgd3hUt9edHF)u=G5g8{Y~c^e|!GZl~rZKlR=;+Ny$){-(@==A!&Nqjv`xr zpLw3j4Ln~Q$Tpe*$)a}9cW#y9oZ${nj4Jj_Wp%t$d-v}1Lnp1RB_-q&eobBS;dpW0 zqg3xp0^5$cO_q`%`p;TrRAK4=;fO*CMjVWCk}U|z0c|`S93zzQA!xYUrR=unk@|hP zCG;a1XMoUw@Ta(@Vsu5z>>a~R+H5}2{F&>a%DMitxjs4^3e_()i*`?bRTG}s8-Mqx{F+E9|fDStSj%#TqwM6yy$GHm1;72(snA( z_*B9tOH5sZJgrMFp2fB)g6H}1y$|ALXiB@#PNBsI`8tL{H< z$s`df6xpr)-&z2J9X+{XWfr_r2}>8QEbFt>$R`O_70D&!UD6kA_?ajlfT>HN9Wu9lsJQI?Tu}le}3>nItkjz6- zGG!JKGL(5*=8RFu*gz?Th*VMh!o=!?MUD_qJC-5A=@Nt{$EE2^C`%Ou0(yS{@BZq z7nXh}X^|^8=>b2|V$}Fjt&WgHQz9aWyZL_CtU!${pYr%FUE`x2Q2$O-M&uQ%E> z-}rvF;^y}-lIIg$xyjvfaV$D8!qu1&e^!08-CgG)hBfG-5;AAMi$ zY~R+L^)nfy6ViOKZ>!-UA=#1 zr^O~cVRs{XI#DiB$5+SimdOoWSlqVz?6-5pxBQcJ1s9*n?239RQH|#Pq&_-B6{z`Bg3Vsi!R;W1ye7v`VqvI75oO!S)Ju z#FFR9y$j8v@}C8d%JyyNq*O2zct?uK6v#ie+hh8yN6A$eR^JA@dXiTf=mty&$OQ5T_iX05PD#!yLNuPV|d@ceS0-%VGPh8^p|h$T|7~_4d$+`ThFDX`Hz;xLtlsH5n9jw%p-iz8=?f+ ziyDD6^#pIsJ-IvoG=M-rbjO2(nP_PtkJ$cQ^)tqv|5#t|?C2n+H1Tg``y=S>?fv5P zI{`E^c#5DF(@~d2l07naP=7EpFuWhDxQC+Y<(m-0F?4F^^QX|WrKhLkfAe<#QfvaG ziS%tEkvMyRL|Veq1855RNoa<8d$qkz(G%d($p2e-gh0&FOd4kqRa{o&rXdm62Z$7= zOu@|HTi{}1GW_eu7hu1Cr#z7o=zsjbfP)EuJ3*}8gJksHJ#P%t4iF0*;Ma}>=E%*) z#KQ6iWiA;3cw#67TF;+73y+8xeadV!IWh4sm?k-a5o6u^c^=zw5l;bNw~oMUp`Zf`vpzp3f-$`ZK@J^uYaw3jsqB9QXs! z&249Mq$l+Ks}e7QYUNN`@7r7Uvt7)PxWLVgE4~l&8D=7X`Vw>i$LQ!pp_WBKhfV1i zDXB;Bm^D@qkXh<21%O`vGJCM|I5+9uVHens41Tr#Z5MB`X!JhKS}7Uq2hue9+F8 zY3y}bqy+$;9)J1r<-?Ib-rx%pqK1Zy34MToaTaT@&zIL7YJ4RI;p6*v?^F@<3k5-Q zS66|yHOf&4Eb)S}gtX3D_vSyDm{>!W2y`^haB)yhATs$-_*IA{vBUocW`f6*qyx)W z`7=0^ouD7=_Q7Q@?Z|WPlIWa+JbHS!btuV2WoTUnDq^ck*r+aYCm96pDUab$rr>bh zFD^NsZZ_Uta-rnxfG`_>>W#AuC2T&Ml32x=Jhry1ek&LBmbv!nF`sk$CzhgnA3B54 z^*xO+Ev(>QplN|>1+-aKcD7^3@i(aErrNwWcb$28BOa~8W-cx`dyU1}bN44`XJ=-T z1`?vj9CB+x7eXJe`}o2mPNbJ0@)YJI+{Tm0lX1ITSN9$(1~oh(YI!-J)Z7LTxVd=~ z8h1#OzB>cU2EI2pn0Bb%j*Ek1&-_WOQoIEOC|P&iuu|ijn-w-ZU0htCVTKy2!ot(r z`#rJ(UjD}A+K(9og!G&o)XG<;r>6%72JnGUPeVWYbaZqDMiz^jAP6n!<3$w|noCPx z;x7XDU8YGGN$|P@^v=x8?BZQFsBM8UsV$(Pts)Xr1a=*i$p+w>Y2Y_JJbb)^q>T)S zc5Dwgg3Mhk=>0}U2Xd&TvxK7eeM8I>;vwvCwf_8m@rO+iLloJQZVe4B;)#h^oo9QN z;wF}ijRm1sI2gm_22JGiEse=E%6~ z23ZU#($7Ken6$MDW59gjNT`xLv%}s4J#(+w1ky5lemma=@h|X`S=_P82wN}Oa)u!aic?Ed3g1f-69<9+ zrKY3+4XLn@?x)1t?lUq1Z4wjH*3{IejV=8Xn%WObOE3sS856Uv5wWhsNDrxtmxl)e z#wQ;=f^bGjK|!QR6E;QcpzyHK#oxgBSNA$oK}ktgS{ip+L-67A=Y=|XnvXBrQb42p zcyjU^hy!v$AC*x$X|Z+SZvww0>BaZ#xrr2oH@|W~FaQxC4TR3g$-(L$xi(%jUNvCpxoLqg)~sej#+un>6PJPLIu_cQ|jTv#Z4E1Lu}!sXJTYDcU>GkU%+?%e-?F46dQDHrYsUaKy7%B%aGoA)3c+lRyMHs=B?~OLHD91#)2E-RWHBE2Tjcjx46nwmmZ zv=cY(8w#{X;ur7b=jBx!;8)Z+V3i!F-l4JscQT5{du;4DLPoy-WaHrAz{CMTK|gw{(E7*BPdmlf3 zynF*{7^n_UkIL-%k%3gv48u6lBDm7^LeSt3^!G=bD#ne(s#K*45NC6+{{C zc%3$i+Uqw1fubbuzuf!#ga4i8zINT9&G!xD^|QXvM}7UJ62M7(7gPq!k_+U&mf&;a^i@Yp19Y}MGtCI zPMlJmHvR@2But)s0OMB+5&xxUV1Qu-R@TZEFVafU(-K$(1z{G3!=n(j`CJBO701Wx z!>^Bn1uxKM-(H+~I8_Ddk&bW)FWWDr9XmL_o(2__kU$*~@f-Uy4TK0hJYe=$eI??2rp*sYaSReMi=aYx_|Ajr|nFMXHSsGB6-y?>t%72DJlB;1UT z2mxauEK#AOUJ`o?FoohL-hZ{RWv3i_65J_gS?HTM;=8*w?Q*a%Ku~!cEsIVca^M+i zq%fVwVMOA(-{$)x6^Lk2lbOl!Ix*GCR_l{+`yXx1YDjv(TJ%C*z@36Mg_hZT$mw6L%ciz()GgOZ1* zCy!Qmdo(bu;58Iaw8c5u*~kGn859Jd884l}3)HA5W&lL)mkdKIh0PUX%P2nmfx;6Q z_NS#KD3StTf-AlC8WG!o2EY9I^-h~U9!U5iBo~+6N=Z3Nc6N5=Hs^JOY3b=HDm@nO8}hbVmUN6(%u!Bg+fvB4vVxwu^>~K6Xb@6X$s77Hes&;dqW_o ztE(?}$>>N z(y5Tl#4WGWZHf*Mw+lUDhz7zCi=nS~YUd@8LLTvW=H}jg_vM=JQ|MQB3o#aA598ue zK5`=tp1?Ue7FKACQ<3;fONk*|xX|TkT4l$!tE)dj#42g#BicPCCK%e(yM%aoLl?#* zqIH@8Xrnw`{t^DG1`QBNn1Bo(oSp#Qp)PmX$~+tZ{PjjU4wEy#R`$+2VNTb=LZMn< zS#$H~?c4gotjGf_AJbfgl;QKYZ;8E3aOLgE6TJmh7VKQJM|e@p_MUimUbhs6B>nq_ z73g>6w{ES2X=Z<};!$*2fAQTC;^NC8U5F$^pNYEzHBDk-B6gj!q7@Z)cX#LsF%%kJ z8xl8#CyhWr4Xdm?(ciyYn3d$U!?{m6h94z_oB&+2l$VG;4nudb~rGxDY{Y@7vY%DrO(oiOReB#*|G ziAUw7oYzx|l<0*xCQpZ5gZ+_7x|5l;(L1f|*T6JQ3{BCgT8GXlS@o~D(OJyQr*)Sf zOCaz*P3Ylan!1x*v{kddAo2EYU#u_`ct{a%q&W?p#XVScPaa<7#3pJZOHIICkN~Cz zLAT~G8@zbuQ&Zt6_-IK~4=|^IuMPVpy(I2Ab|rTHrfDjAABr8vRzu3ZcVg2i_bDi|HrJ`QE#&5==Z}qVQdL0KlrRt+inmr-z(*XRf>q4?7MS8 z)=k>W(O=|O2^(PQwup;soY{CbGqWM|=ldY4u&|tBr}sx@OT;unS7`-T5}<1l%9dID z{hfjFWn=Qp!jTattX;3#6rHv?@J2huw6ARQvs17@f}l?9 zu)qOdOYJvmwsV2H=##$U8>5c zJy}onCSCo(&A!q}TzGtj#aG*BkC=1GRET)>Y(@cm?tGwx&Ip|myE%*XX{i1L`Y{eFfoeVy%kMen=eeGTwPqgcWRc6fYPC8+jhFJ{h-nyCT4#dZ)CFAixl!Pgxrgn7yiNpfV+X(vs`3+e2!u>ROu% zEvZtl0&W1tShcp~>A%!!a+5t@+FX!);-gyju9#J=mz5`3!i6PLcW%kDxos;^@!)L` z?OI<;nba%u>yOFH^U0e6oN6fZGIg?^I3JF}v4Ja1`Ygu<7}BizCup;+=v9VzykaeH zVKgr`aCvGv0-?>x_l>G$%~fJDvo&MF<7;&p{M_DmMlAO>+hg5$(K4Bk4X5m&Ph`q^ zsB-Y})oc^mf$}ZYYp#~OBCFDMmCTSSuQhlsAG2D(YS3rv?qAWAv`w!>Ax?>< zr)<5YEV1@0_v_3Z+(FDjLd8oW+1)mFap6eK>{UEwpD)v|kXkuEVpeV-orhPAaY@wBweHlMC0>EF&q zr^^E$%!bXR>^=I3;(@SJ{Ux^cebKAl(OTE^cxoFc*T4E)u;%W)Jbu+EYw&3mQv%A@ z{zu_I!Z$$2!+lFZ4&Ed z@Jgv%hT-yS_nenXKAh%Xt!J#`jXmGkB|@jB)LinBR)9e?gI3vDBP*84YG+yWikpXZ zRg_m`#%rSwJl0!i2NpUzOfIAI z5gv@0?o?zRlaiLn88;O>LNPXO9cARiksP3x!Y*c*G@h!XrbynK7FQGeQdrk&<-oGm z>%&zY{In^L&l>wQ(P@@_UQC~+AP!Q=lz-x7MB9nAgJQ9%rRCL^AMkwh?r>)$2xEY& znwlEquZXdS>q?Z*6Ns zVZ;cdH}nXDgYN)PtKCLI9%wIE<)DE@HVb53oHN^zAu-uljP@RSQG6k2v$nI+Lcw5X zZ;vEE5HYaG%56Fa*V8*hE+uGKkAeYDW7`O2>JURP{O6ukTuLW4p9vm4cuK{pwjZF%-VHTu4K9n2YluBDA;9 zw~^g+jua>czY?&9<#KE?K|1yp78lSXrVXA53>;lsu;O2*wW8l-5xmbvLLxgrN-?GD z+vm@^FO{suCz$g@rBtg+v^w`3rB!ghT+1}T&A6T(p*vyK_DG|8AZD*ohFz@BxYj^* zgn@TlkiX5jmyHjzQC4Rt=~AgQYD@%q zw3x0p^aHjaWEi%>2#Fp|MOpc!5D6B=g$0KIs}y^Zo@6E&0fQIODgo%-y}KVB*_D`YD8d_1V-*T!25l5wyspPX0s&|vLjLY0oYvJQ z5EvNFed_ty(9!V&ohKNWp3pTJ!YsgWK+hI6Rx;Tj%QC(?U|r?pAim@8z+ zj?YH*wQqlLX-DlgYD3kkK;cF9Bw}~BfTZfXw{N|Qp6wsGk&&E4vsc7JQzL1dy2PSL zsr0 zvh18GUjiR|f~ItE4zrHQ=i8p0F_YM_!?nUPTUR0LQ zH#j&rJiKko7LZ4~t{!G@`ll8Es6K=-@ZNGH>0x>nctQ$7IAS>Pd;hML1o+OAxwZmx zv4Md!Hy3jI??6zo7eXoua7jV&1iTIH?d=GK$;-{fC=<71$My_!6PkRUD54WY1UTSY zF%z~|;3T0Je2dVUl+@JI8bx4gbB>NPpjw}Q`*vV%1uh2UMwXsX*VcZ4{_^3&G%s|J zXzzjhDJv=_r=|krH!NaB#QcR8a`X8d3*Se&wz@Wg<48Wj~E#x?U$Te3GomU$~d2r zLdy6p(F~X$5%EyYXxP*B5N65BY+lgy4VHvfRY%~o4TwXOvmf_ z2NOd2)^-qGyfn{Hq!uciu)D4=p7E??1Qy+qy|oAHNBOPjrE0e7ByyKBiVkXBk4@7Q5=`+2bz%QrU7A*ksm06gwbngyf(HfSP6N?ct$@ zjm*Fle-6hWt3I}wL>3|TOVI_hW-zk!73cKIJ8Q6a;R41VJJQDnb3T~+~`cTdg;<7aNc0R z00IKMICb(Q`_7ui#$pUkMY>%S83jCy`kk43NetsZ;b7Y5mTC*=`k*Zb4>bAsu@i{i z!c#M3obOqKzyA$#xAxs~QE+gSsV~Ni1>8Fr$S`sZ3h+d)*u%M}$w5~B3u^xL0s`S} zV4emOMmnB=fUmEI=CB-}EurRiuYMNlF7jO-^dhn8e;T=FtWE#ayPL3{#(z z?b%$Gc_+kM{T^ZrVV1kQQ3O@(CcY7YpjJuGPU{7}6zYg+XC2nR5aBox4nh?8i;^_x zRsmY-|0m#>$D}h%r@DVXZr6LOFS;ziNTPLgBzAuHba$6r`T~9&4;!9J zNc&l!MNw2FC*bD!Jnvk?QHJ9kTTATqsP*+fVWhkaZ$H0C?8I0|=+w&yB3-E+9qRjy zqjgSm;#>jL;92fWeP< zXh=&ZCF6rs_}>WepZ%2lhyDILB|_&u@B zu6=GqXKYycUG!qRK~73Djq7m+X{()c`o61c=|o%*2(R&>G%-p7j69&Lr%(AJ zS0M_-*y>)ad0Yd08I(E!EW5O{dJxe95E;s=0jKS@E#m6xKOo}=s9RC-2B#Q&8|+E1 zfi26g0BkC!yhf15Bl#OzQJlYr$v92g5)-%Cn~Q5182P+`q%bQC?2mYUMl17>U!eOM#NM}N5>N!P51AonE#>wAL7G= zC_I#)8jiZT>D1AgU)~e0_n!dqOOMl1Q<;KhOLpO~|5#NVX@`lH&v}Q0j~0!XVc)^^ z1#^aN67@Wl|5r@L#W*Cyhi<%o`7#ja{nSg6qSyc5;P<`<*wzzkrMnhAxvcWTt;Saz zPrtTlM?ZRrE#f!q`!~^YOqM{zpB!`S^B_pW^ES!lu75I{^CiL0H)fzH>Up^2a zEs}oz+-S1%!fUssMAp5N*zHlrAnYGq7YN&T?~ZwU=jY^5YXgDo4qCXNBTNeSLN>?u z@SdWg8T2 zCV6o$5HdpY%x9GCSKglTPiXiNn&z7mE(DUTorDeZ2>kzu4HF0uH)s`a&o<8Z6dxq; zO3c{Q^dx8yMYlV6f>2l;IemP6Z3ikL%+?}JHnph)9|QUV%tdzk=jf9AUB|Ui(?gxW zA-SI<8RN|Yp{%QW17v%M#thCisB1_RMELh*m|BGwG(mjJ$(ahXqAtJl=5w0X`q^Q< z6Z3N;p7h&eKF`Q#2DfiDgCz6h@h?zRj4HP<1z?q=Djh!fUU)(~>tSiEdDvuTfP8#Q z((M7MvY61j?LPF2b3gcqTlIXSo9K*7$rdbqtbAp@Tw1=Iu(Z4S^_?4AGRA`qDk|U0 z#TKOQpo~^Xiw~@63Oa7Fw#WL1vDwylM}B8RACgm8nEF*KY!iAmu;1p{OS{sID_okn z3GzpWve4k-WMqgI;qX~HU-H^{l`21;J?5`Bn2Dl$+-;!K+tOqBh#bAX4!e3ie|iDSB;OjE#=RStG>@-7Y`Z#3Ra8y5!!J2)e9GO{)^O_# zW9TB0fkJuYmR-py*(RQhhHXj@oM%VE*o1`q{rqMgftVtNJ0<^F*hLJaq@ub#F!1ro z6&eXCFdxZ(QeeqjmCfW=lcM;YV_ET`mNLgSjWy1Yi!=5$5Q)sY7cw)UD&6hM*mT+9 zZe^r~>mfV3O)f-3>*)(cJ4?N4jXec@E+nvxGqaZ2ni8*)8K(=IA2_JfMiu_N?7>Q( z>Dpx%nL3^BJ958lrR0cvc6=>2I&fg%VxHF#55c~KJ$oDIc#~;;diIElijpASZe}U* zBoc7U@6?elZeXsyj^i-B@(wqnaE9Rs8N-l*p;yyx-i^}hXK7{TchXbc_Co@fR6f0$ ze)!H-t_<>@Rg0-gyon06CLHrS#|&=v6$vutmXm8SypM~IQY7iM zU^aW!Gat;GzAup=Ea#h?y9MFyk*=dt{4_on(A%3QN~P=I}!cRe7yM z7SB6c<2#(+;Zay7H**$FA9!+bS4_N&oxt<)h8`-Z$|zR(*!`Em(28;FJC(!_%#!1t zo^#ai+(Fqi!<+Y{YR0vhbsc5LN~HB1pA__^QciI>1sc9LlC=^ZX6lQ7yR>xKdn`)y zH(hVil`5|CLgU&L|4w6tOqqT(Q4B_}M&9?uiw6SkF1r>l?kTvXy!M+=_G&a&bLr!{ z+Z3AuWQM+FyShgC-Ef_{QZ>fuA$Yw)FzC<`>f6Sn`(M|}+gVOZ%HJ%o)!+nwKJTtUtEY)6 zi6x$s>N+P(j5FSF&NkbF@KI{ECq@!fJ`hc?#XS^kP&dFd5RUv%Jhn652XCLSIM+bWq#kvg_&cyUxwMOlwWa6 z9~Y!{MAG-;Cr^F={m{IvgANepU(ml{$z*M%2rylgX99MHU@I8f#(*||U;vE`U5V2* zKS#42H(qiX_oQ6IIvg#QX;C~D@BrkGx{TD=f_XWs0+iihf{+@7a?^9~ZLo-CxcdDgQh zTx;b1x`Jp+xF-+fTZx^nh1 zRS74XDSdb>|3Q=A56^7etaK6~AOA9Yb*sqeCf&^E4i-&E%&ybt9)H`~*hs314@_9O zZ6jDebO3PeTbgm%Aw z925FvfVZ=%y0hX_!SA4IyT#5LU9NGz-#Z$6^b(Edj{41^7DeQog)IIU2hUJ-{<^GERf7f< zF*Bx0dG79TRH(Jb(Rkt50-0ue^>F4!ni7VfJ*8WeJ1cA%zn7Jf{Wc09M#!8x_vh&; zrUaD1(3f#-J!oTVyYl0gQKn=n&kop*MB$gw);=t|DUDl!oG>yo(}P3N~UoS_x zyH{Shaz#hjrsH@;TACSTY!6B?6AC2>UTChOqsh8Z{eLUj9ZPcNx(+age7^@+`m}}< z(haX&y9V@PU2^Eo9i4^?Xcy5?f%QlG4UyUVgDukofb*a_00s^bc!FPpT^oImDOx`$ zzFV4`A@DOcGTP0Adx5+QcL>0jmKY=U5(r3NYL9-72~Fwg*tB(^xBwdj8h(zmMzZ_w zC_b0w?s5r;RMaLC#>tEN6Rt{Rj9SkGS!clG0$8 z=~(~;$wxvF|9{Zvh+xq%KtH%BfNZ9xLxCX@qVV?D+S>ZdA3=>scKemAoSYy4|Kf*2 zTH)WZW4ttJSKNXE0df?;f4FbB+!Q38>?RDo77)xtk`p8@=D#Ov%S% zA+57i>J>vtKJktHl^e3&;?l6eDJ5x?eq(+)ae&VH@Cx;F3b*ttfkOR(HAiml=)4f% z@%|3;fOn4Yl>d?L+FO#LI!#O zt5spfyMI^dnjfYlD570T?Q)sNfm622(JiAu22u08Dby>q9OL zY!mbaCdg^SJ4qmvGEJld(Lma=T;^S@8p!c!iKO`x;5Ag0l}Ypl=B5e$H<(xsDJlbK zu6jTS;wR$C!l_AsHAssc;7jP^0Xy~vEwKL- z;p62+Hv1hnMYQ4{KQ`>|L?;3D>C_amTSkY{GUXoNmWG6eBESLDU6HnU29t6Cbwz&w zLJf|Lj1Z@fhvg@72Vujm6Un?wN{0p0g1*4n8DnbXF|w*wB&Zh$ehFFk`o8ZIZimNc z3}z^%19)Xz2?s<9TBBYZ%9aS79nZ*&OC2b86ql3~AVFdvvy_2F*=<66s^Tr1(d_PUD3oC!EKJQ_bCcztPnQ291 z&`T-CH8!_0WPxDd`F>@a|U zNbdFTuNWpT5(p%biM~GtfNdkgSP|t? zvIAV+5a@xu0;vQ$^HLF|3xB{EUC@f^E7V=&+Y=ivpQ;TMy<}{?H?Vmw@p7FpXUw<;HRpq^ z_3z|Iiuakgey({pE=rlNK<-~-q5oFPS6&!$V+fCLaEnL${&V*h26_pz0%XMuD!g7` z8!au}efaQUarSz|LI09~{ekj~M%0+fHq8TB_o2C>vOW_!_4KKjsv+*By*;1Ojw0gpO0u>6;CO3jmoCUJFj6(cesQ`=_KGz&^Kq}W_?=$xfEI}Qcr=a*}0Z1KN* z8po12Ev6+pTJ#ec0ecz>8Hd4lRqDL!a8#6)k+AE+@{E^TAz~WM|V<{{C9td@>i*H(s8Hd<%*A_P4qLSRDv~Fr>F5SOBxjF4IDQOYyD#$d!KpvgWD)I$`^WR>hu(M7BzEDKtLk zg|ufTCMsko{>F~sDIz7sV&c*PK`N&IgdZ=T+J~$QY=7W(5%X$nW(N1of5wkx>NMkl zPNJsbJSoabi$n?>x?um1T*6F<>WK&64J-}EKY~Rd)ooc&hvpES7IqYX*`Ui&^^*?v z^D!|50z~QH{w$?9@mFx(nrB~YZtghqN6TmApAusODWCXjJQ^VZa6ci0ii`kn_yyw% z0-?hJ2wq@^gP)5FK8Eu{wFO{|s!B=_FhVXd|NcE656{~F27eVAyVQWhLWRaGqy?cK z77?7G5@XoAFvG#d-X8v^AheO4K}m1Vrv3deo9|lQ{O4t&M1(mbd->ygP7DW(#6BS= zUPWg6zP_n#14=9djIJuTC6pi9_w7RF0^dS{(gQkAe%d0p{kLn4OX$MOK3Q(9)BiAX zX050!)S=?@VLLJ|{V{=v^|Raa%obRToLvPU?fJ5FCJsFo^g7rP(G9JHXh4K+Z~qiz zIiU|606Y(F5YWV)fy;&+mi#ntZcMYoNk|}oVfnK@*^3FW9(cOmz6GdVVKDj-nz72N zDntf$ZLGh?u1zXCnAaqoAw>Z)i}}cGNqWaS!f_OP$bvV-V}#QcW)hOYawDt0-q+9X zBO2uADA$1=AF6)v8-+Jr^k;0k7?36w1U3-Q8D@UtB*XZ1Tz_=De~?O|qPayv0?gD+ zfkwc}B0pJmPmgiY>%$P|Vjz>95Fd{XHx=2^(4ZoYg^GYl)N&#s(Svi)PDx5g2xx?i zAg~z6IX2|Alxqq*c09duEKN@ou`>6exuraD9`EMmRf{TAN0_9JgPNC?2shwm^wS8HOl?En`TF_+FFt**E5-q~=>{Jj9kaxg5-SO7Gv9-rf^JW$K2Pu2nt8zT z5Z6*-lBHh1qtAt_!H38%4Jo=g6tDL1=9x_d>>ANFoYylGS(iTVk4Meub-N{=-{QiDOU15%|)AULTRbx$5<8(cGPi=5#Q@&-rjSi ziRb!6gZz_Tmx#%mBYe=3eE}c<>>1a)8!K^70^@?``OwXv1SI!g8X*h$V&0gy+#6Qe*J~{jc<{BJg9~^Qg3i#_D;Ku)fpWp_|YZ%wSProg>5Z z8;lNU<&}5-U%H-}pKCAXFFG@n4scO%j z(_X4Y#45w;=#OW_3~SySs&!kw^&x#AcC;XfYDdfT;NinV5A86le%G!)*_Wx9yLsT- z`Gez(G}!{zZ-23t06`ujNfwIxZ5jAO=?pVzxW667h;PMQS#|Z?iZ-38F7f)@J)K+4 z>~8CG$P4x-SdJfD5PWSD-dSvJ07$(ae~ES zzWOUZ)o1C%SdMsN%eqy`3GkO*Y_(B|&Jo20Pz z9UFGu^ESeS7qR2728ty6RMpxbSZeXAJzsr=j7vRF+}}iPNptu1?nDlL%7)fUHkTJS zX?cd#GnjB(WZ-je{l0c%L*k7F@Z`x#^=s!h9y!H)EI#$O{C6x3O|9;pJ!I$Jz#bM+of$Yg;_GZBhI)73 z;0-w5R|=iSQoMd$I|xy8{&XdAWIgbZRL7G?k1|J_OM(}P&KiPz&NI}cPt2U`{zKOF z^EG3=Xp5s0uoaMRnKsTj`l&>CxMNGe?MpWI1>+|9jV>)_i~P1T&t@7pJ$~!W4G&L3 zW#i^-$->|JrmL8!Sy<8_!d?9Y90Z$Y7{wL>6qqD9wr12Cz#*Sz54!C%MoJYAR+wlo z(n49yiVKPa-BR{sbLj!juKCvOYl`&6##?+KOQe{ za})7ld*Iwi6)M%CYxJUhS1o*je*-xlM)Z)fP0X z*OAen`^pu%A)urj5-pIuiNIColT4f8)g4zN{bob?utGIMHvv-)dBxW_%EIP7( zlsa_7y6v&dZ=&T2MX|-fC)a7LBDs&A;dM#*{XX_7Atfee>+am-gPSNcJ@dZuUT~#T z>5<-6S;J}*Kdv4d&5x8Xm*y$pkvDJ70YWAxK*Il|TMwnl5w`;<4|Q}1#Sek`0T^1r zHurK4$H}gfO9-n9I&lJpBTx&7lm+CS!4**Nqh97tL+20qEjU4_Zh=}sICt|W)&&Zm zE3K`l@g9(1dwz|OWt3L<#z{7^$dY6uV3hOSnVF)&xsLXBR{p`t?PLTfnxWqy=^Jqv zpn~QX5C9KW^6?UiUsSw2JPkVXQi|5Q^y^nFOnR8jeg zGiEsw0yX8^4=|6Bf{^tzE+L`pqQb6SPm$M2DAB0*8F)}SseAeyn_s%Bib`$$n#`UG zySF=^uen+69j}DU(!(X4wpn3l@;Qgi!w~A*XzQ|1tk}B1v`i5QV!C0o5jvjS+IQX`sdn1J%ap#&z^EV_}`~-Xm369;tg9cm- zrm>);li;~EM1O>uGclk4-(gOIFlcZMjd1A1Eow-bAUSDiBLw0igl)ehj_v|Lshaf& zXU6ix;Fcwfx6}T$d=mj7v%evq$E?_P1Z68LTZ?9}K1f2}XNxZYxaO$h6Tl^)m}*^# zyFtr1In7{v3zYta`S}b+r~bDRm}C%^G)kst@3Rm*Rv9od1QxA4r4YI6y^;9<~bt-DVpfKR*ma za<^9R3Y;?l6oR-zIE;04`bcBK_WqmtcIchv&GvE(7Xuz}_O?rgp`O`$^cIi|DHK1% zWB&|#A9Rkhzag(q71*_jFgrIl_x5c%8jo{@0? zTAkCUJD~i99R-+Sv~ON~KP~pp3l|W@0?jcBb2{u`23K52W6Y2hi3j&{hz3GBq3Z4a zI_(Wv^wX}>I~J0M@83sn8xCbJvQVI}19(5R!|aL!7yWH~HUwDAgv>EvpdQ}&P4pGp z2IA*_HcrmhZ{JcM`wHQyw3L+dU5&Zc<01OdduKrBar5$)r5T=Cs<}Wp68bpwhnP(K zg}>I#ICV{QT)qvw6L)U8oKaNTohqgrLhH=P*3Z{8=`pJABKtJ6g*Y(h6(-M`o{+d# zqO@D1L_)uSeu+tt-|lcGEx3m7y{l~IGR>t%+2T2oT#iu@e|(;Crp#mUSXhjuUhJc= zLlmc4=&A>JhE3-X>oB5-;oyG;wKoD`vYm7aVak`~o5`S%;EJKdfKLFL{<0}s5#};xgWcR-L*z+DfKWS6Gwfy!V)8oItRlhuDmN<$=svWVXP{%KZ1q1lC;x~0q4UPSKc z#Ee*`h_Hy?+QSR~9xovX!Vma4;O>||#uXMpri&!!{1rq!5u0?+>Xm{2Iaz*yCq&8= za2fK{04hN>oU#|j7fASF-9d$c7j&-}kEiKc3_giGIx6|t|BJXdlEvY(6$1qc<2|2+ zJdmOC<+U}W0(v5NfSI{S)nAZ6*kVFo%k>ob;&6yV_zk?LFNfsS1ZqIa07Aq`q{yq( zAQUXH)^O`5k1*Y{w$+L=g|JCfObjzbKwG#!D4?S;^oV5;GAatPQ}62RtE+@i;9Q`t zb**!`MeN5K{{%h_q946V16{VuwE%fZmf4ZV54MhXJkhJ2edn5PC%pQE$}4JR_cM_w zvq6~aZWSdzu6M{jFD%Z*Tk|!^elMkmYC@`lu(AC}x;4`|0nf=(yVr+H_IEe(F%ppk zu>c3xxpOe(z|R4kjfw#Ga5#)V7z3c?R8#p+?JP-6VfEt#YRG5UBEdfr2uc-OKx!2C z>S2~%=cku1k;_nsX^~H!oJPTUY4bh`=no)8y7?X_DT?az=aKtHdhw=mxImqOgZ{!@ zHzY+r18{~J!?VAkg%3utjRF})fQIU7;jAjm1b7M7ccb{vuf3(_h$InN%tP!kW-(C3 z7t&J3K+k{a5;w4RJm(aI5`U5ZqGDcx_QWR?&hmeamgxRxw1m}3>^#o2{~=m}>fF8} zuOqX*r2JaY{ct4z6*A_$(d-}xxU=0sPE|pHjh3?MSb>tX;UQUqGv=ybL%2Cng3KE* zF#yI1eU^R!5dEQ105L&MKn9F)fYj)o$$QyWq(u6W$vC0{LNs7&0UZSdQbad|5A7p7 zD*enzVfGHm{O5ug^XMMZ?xvJr{M|bDZ9?vH4SPUxO0CF7W!)hAM;lO4SFc>zBa|T{ zW#vb2usB^CNEz%WbDa3iI`!$OF){fgy;F^VTUlvE|CmW!!vyU`3*{Mu+|Js5|3>=I zMIWsP&cgkO2Ll_giUtCP891?kHjxuR50YJp%-Bor7bEyz(9rbOYY<06ebNoS6sT_# zC6n}~ZFb|IBruXK?IRyIH~1X9KL7XyuuWf2ZzS>Hb}%5=FvGR9Wn>m{sKOFN9^Ho^ z1-XkmKH7_K*|JMb4H1KGU@`&!-ucAyKg^0KtGXcwfy+SbEE(Z{jtCbI01E(>%fggyTld!XRn$EbDP64%b$FRWJ;&ywrvE%UGVScyC>l#J2v*w33Y!eK zz6q@sJz?m7GHp|XOpcsm?d`%y4P$yI4sL{WJqlm?e%ys$tu*?4t8WZrw)Gk7N58F^ zB4bNd(nh}Xq=aSQVasTO0>I^$#n zH9pODnW@Z=HP7FCEIr3im48@h)u5Wp;HCV@2MIgxNt*{(PTk>e8RTJXB+xT3U=srW zgy@GY8HSK*SP$))VAb@HM^H!?GA*PmuhInKfro7;%Vcz~VO?U8V*`IEfA^5H`KR3~ zdGs4~P?wFwZt3+ZJ7grzeyKqiZ2OCzVMWL2ETz=EGO=N^y;pO29oYt$!$wBrorz<< zg-x8a*)vH}uT+&sA6yq|+;pvzV)KPn`dL(^e?`;$A&pgm-08)EUgYP5#kLU$kToqz zXLr*W&DmV@EByZOJ92A`?7adzFvE%ctf2aFy$>@W^J$z)<7K{Mfuzsv;(by@) zocG$@V3A1l95>%)$6ysL<&|kJxcOd##{*)lriase%X1HFC+Sl9L>S|0Z^>A*GkDr{ zNQV88c|OT6Wt~t-HnG>|RZOdeoKc0lS1h!%^T9em3i;K#j?cFVQn&U$vD_`d+P;gt z_u~Tsizjp@7t~#%B_PJATHr$>zHY&axJCfA0mpr%#Fa{rA-L|3{9p#*l zY_jFC=e+`399nmNj#v}C7JINVDNqfp$G^a=b&Lrg4@rcXRkM>f(97Dk5HTp+o`=Eb zf3fu?&{Xbk+mCt9m@#AKsBH|HXEKG9p%6kUgp!bXE;3if425H;XjG<3sO(Zi5>li@ z6O#C@eg5CO*89HSXPtG{Ivv^evwy>VU-vaUNWb~X;Au%(vvkMA+#ac^{F5D@h)MMXv;`>FH3D4a@H-5oaz5#V5q?cA>~-=w5@=Uw*Y^2Y+Kn<9iY z;{Stu_Ii*bN-Jj(CL{HwW*b~ZE-)*fvStM+9Jb<2**3mf!#PYpcPe5&x2Y2QMH z#riF(n3uuOJcM$WxTKdw(#jAXpd~dORoj^%w0-NgZMJHrRJcU9Z-2jjZAu0DpaRy8 zCmxcuE=A{dBxu;9A(abm^c`9+vyWu5X94FFt?0TcX}! z%cZ5m8v~-0^!-0aG<|tWxLq}!UB)Dm61ubgr){0)v{Oy+jp5`OKmI52)iH;*nioja z(28Ao!s@e2?3w@JjQxJ>egP)I^fbx)89*6tpLk^wsKRfa-W;mOkG9jizpUm$@3lwg z&XWKB7V^u`;fiVqW2&2CE>orJ5HlM;_%vQwNDP5T?U-cGp}LB!{i5+VyzgZo!v__O4rI5uXqG z1@ywe0lRUi-u3dvhUPay3_e$`A`dtKe}-VG2A1fEiybi)7g^Sq{<+@*XItpeI<(AD zXCf7|*2!9GE}xm!{fyw&3u8Cb-mo2H_3{&V>5Reexg^VZ=H)l<){>49=KH7|kGm|1 zUN2+Wx!r@WUJ>T9SNItELG^7SJV8g4_hQB>` z9rI4+$|>)6xSEgz7d~j0ts#ztEfKIud_ne!FUU~X1XURcyWd=9?vqb;wxV-Q+=lF| z{cBv6QhwjaJgt#UBLN%P&V=q~^ia6j%eZn4bBMU$jwZKu4)ZlXd!)x+2mMqd0QL73 zsUkOx=YV+aYfv4$+$nYWfW?nRyC#g}7T_j{vh71(LHEOlsNgAHrwC3GQaPA0$aF4( zA6zdGlwg{mHm|3pHS+3JUQ_&=SFe8IuMzD4yb!Q0m(zoO>|eqLM7bBZU&%3wBmt2C zC&<31c4?V*=J!iE@LYjPx4d$l|HcHGYWs3c3Ux5kf;70E;oL%oDvwI@T*OX_VnXA3MU1;d6?q8 zg)JvIXgD8qOZC9J@>8rtP0PSwW@?HzLka8Ny$0{fLbZT=wBb294wjb8v(tb`AQy(R z7;VqvSOLzBo82IB0Y%l^=q6ZEgS^?7z1ZmyUd8`#M(^YtFbyDm(Q3tBBfpp{hq_AW92RZ_@3CEGg=c5Y` zLcjzkwM)>qtky{9c?Ji6L;dBk2h*g>6Zwby{yQ#D^EwyfrT^_0Q5l!$MZvEiMGOgf z1B2aigZ~NeE2VkFh5}KBnr#fnC%%t@F}uKC8rvGi5y*^4TMff_JE*Rt*1+Gt23%(( zGw;drlg7v~8>3cVfSWg#5rsLvi1OaIO)+5{f<` zqBWIEh~5S-1+X0z0n(H=#E*#T`S1)mc@%E-+P;=U8%Jq23sav(M{){06KCgpIJ+no z857nYJ^-vo$I48k{7;JXI#Ptu&!$EQp-9D0%OZK5+2A+7vKuEYAr?U8_bWw7UY&6$ zVkoO{}SUtqVrDGkJLyZL4n+%=oIjdxz&bC-u{WYfBFP zox}l}6PE3HG1^?_SO2+kMPGzzCbwOOi!4{3-J(C91?!+yic)|T)^?Iy6z&z8SKt-P zW^hN@+ZrB>vKYJ#fa4T$@c(Ow{90L8cMVD)%srz2%-zKLE4PzHuMRjA^4&VvN8&jn z1+lJU4E~UKI={hSZVUg``R2_IS=kvpC78dsfZ8>t@V^lD>Q7AoosjPW`+|cY0b)h- zZrh*1zgc)&Cq5)7SdmXIo6|!fGy27b3gPg=pV?XU;h3ZlOMsW+%m+~YUJ+;^J{lY! z=wTtQUb_L%(%0J?e1-0zp%aigFG#BnBYGOxI{p^gH+?bd5f6C2U{j*!)`r*;yEymv z>gmM>ZQbg+zoqAUyz_LfnMv47q=@C09XGjR>gSkHnUZZka*5Vt;}Mg4uk!O>)}4U? zZ%e+@5sTf4gM#}lylW0i{Ly_gpE*$S?o;vIqT3<9$`jFgy1Ls>Jky!hoF3cpBeMTG zfbq=`6C;=bppI6^$Bdgdx0ktg;l1(g51#2rPrgghwYhkzfv z&)(*G;|m%a@O3~fe?$4c^MtM$XhR=*^KjTB67CmN$+=SdAiQyQ9tK=+616#c&vJ@q zNl{5jG)9r|aWU3~djf^j0YW|)K5%DuJ*6>6f2c(Z!!>2)YnLt^0DC@#racdCE{G<< zm_S%3A`~z=U=q-iyE;1yt1IqFg9sCH`0y9pLP%0=!pno%jw=`;mKZ`%Gz^N=%S&gZ zBkKWGZ{2q%6t9kS1r!m1$VA7q0&(|694u(VTTYdL*NPT- z;^GyjI!q+^g@xG&j|tXD za&sKs9QaRosYv`ebWyjkS;xRqxZG>>cB0d+vRCnmCXtb=po*iJ!pcU9(U-4Z&+2xz zsb*Qme&%g8Ij|B@K9}Xs8M@ole+$RJ1~b>_LjP+E+U&OG%t|q%6ml^j9F6Vz4aP8S zOyOU+AsIBLTs+#WG0&&h^iSnlAno0#n1P_~vD<63sowTQ2ij#SF(OIXDORd_WWE|+ zLi!T1w`e7}61eP3xGm#-3rK}H>%F~i-M&qk7bC_NT{*DiWKnqU2Y`c1!~j1AmloLr zvv_luz)KzF^K}Q&&gUL^6(o4HOnu(UxB3c!@8{>MLu-LK0*oy0{dl$` zTvbOCH=LoNA-c_KtMikyv-pXQI9P!sH3wYT0@!00+|iHEx!})G5Sf^nZHD>Y{pCbV zKP@aQFfg#M!6E(<0+do>71IIW^Ry0;1cBusR?vq57@lla3A1=XALbyqU3`6fT7Zy3 zjar_GmxjSMLBMUC5~wGG??(C=B=d;o8on;WYTjw^ModjD3^YZ|nRp%w_rMcj5Hl?> zBGDv)jt9A!{>>y@m0t!fQ*taNa(Vz%X&;+HF7+a_JL7^eLlM>R0jn((z7=R~}blzQ$;Asjn9#9xR3#@kZbBshx zAa~-)7wXHf{^{%MD^PI8>md$;dX9+$7V|N@7g09gAfvF(@y3wbcXO6Z?Vf`bnn95x zL8W;gAsdiXAc7V*6~-gH_d8?8Ej&75JB3V&d3g1MV-2XkoR9Z@rB&S$%!rPE9;Adt zUk*#jGJPsbDSCg!k(?_|)CZIg^kk380?*r0+?_i4D>~^lL69Qkv zIw84~nxJ&+cx`gtRqObrk5Wf&QI82V1if#Vi1X#E(s}gB64y0IB8VUYdE#P8$%X(0 z@@#Lbk{?-Ygw7e0_?{1~O97nR1N%?jqHexvIs{fM(|~X#KO5+13`-Fx>wJt^QO}%v zPJzXnP2+LO6hH9dE0hb5Nz7*A7cv!M==6R%(B`|z>ZXP5o48===}_i7Wl^W)Jh^1; zskd9&bxLZ`NWN~9rTua0XgaLZW52S2HwS>V1d+F)>@l-~35f26V-AWD!}6K2dpop; z;i-}dK!$Qa;++e&Y=e!Byu9Jn%Rt?PwL-_mg+?}AyK&=Drhj^6R@s#+j|T=Ewia~h zLB~odMKW8a)7L0^)hkzG=)XEqeg6@wf60D|mbl_ri%NJ2Cke)yFkM1b0;zKC4q4|| z7zDetLyKKr@3g8NcRU`f`;ieB7?cn*M8S2;9k4M#D!2m^CU6oTjfJqIUAX0RHOZT zO_Kj+UiqgA&JMp~kBd>g-03IfNqzsN_N-=mo`H^^8K?e9*_-t0&1VT0S0bo=fR0=CDO3EBTfKPQ|>?DH#FS0;!ntb{6$=SsvEkbt77L_Xt_Hxgy z(O99JiTnDIh(YoQ59bvf_n()sOwgLx*qjaeKAVKo2V`%Nzp2JmkC_N_3k#&fKEXYX z52gG~!#LGnFb%G^v?K=85k#o|ITf%-z$pMN0iP8`_cSMnj)GNGcax4Lv~WDWDxEd{ z$xUw{VH_S74-ts2Xn77&a>?#Fsi^7V6F9t~b8^N(9roGDNYWf{6h5*}HI56m&6WRQ zCeFXPxsBphW%h@u`RY{z1BKjMf|1r_rB)V9+JZVj$aY6i*!Qm-_nj0xT<&2(;^6ec zy@uarKeT}Z9{^BV*xJIa26kidYvx4`3qOAvF9{P_rKR&9K0N%*>~Ii{7nBTP!1lOb zI_%w#2%?bBeR}YSqVYnjspRhvS^*tpIz(&xu11kw z#&7#W&Fx9QEm$n5M?0MFMTB9jg@e!8`8<+tMjI)zJ5@o@E%>(!F1$XY9z8>{m`SlY z$UI^)D5J=3kt8KzWY_Q^Ql0j;T2Vz-YmCq2RDa1yU9%Okq7>@NHS81#l6Wy}(V7ry#=5e+#=0o4m!PI4>^@+#RAF zqdL?Ikq8z&W9s1G5CTi9nVi1^wt5{G&t14+Im~EgSL0~C9>djE#|^m6;tORy0DuS8 za-hHeZFpp%=q%$k+~L03iPfRtdgGt6GW~id_q)g0=tBh=@VP^O^SFtIc#X746nsd< zNn#VKwkb~Aj>BjXB~Mrw9Wg$(*g1)%PElG@Of)>jSB`ajcmgx=$B*sg^U$Q?i(FZ8 zFA1eSh*3b{?PPhdi(!D?xm$-hv=}w`0Oe7j_yJx7z+FySI;p10Q66p5Ze05?*1$Tb zxK{~kJAT&D!-o@WHpFd~lzcEetO=e>l|AY@rm7Xqu-TU^+ggdRVH~EA7$8Ju=wBCf zW|v2(FaUqxmVBm(t_Fps4nP=je8o>}Q_k2Sw^C3u09-86b& z)W~)y;LP#N@e5fBjW#!9wD(fa^JZSHrZu5uV0gbub+iXLUw?`w6#$fc*3y~ zWgUvBg$fk$l;mX$R8gq|qPPd)rm@6t_|>AuK#7ig3B-Twfl`^^*NONE?-oGbXpa$3 zLUH0tHJ+TFzKLEJkQE9TiY>j>)*)OlEh`Kw%d0rcx2UKLz+4T3OogZ3%ES03NKpZM zftR)f>etfep-g{NblB-*$h(@*9fW8z>r5vjo-ys$mm7$bvuDvX1?lVS<1UlkaF!y# zse1(tsvt$0u${z(z+w~W9PHD?TD}?6UUGj0%Vwsx7F7N`y)?Ot}#d15DA4) zNn|U10aJ2r?jGnd&3z4Q`!3%AU1r<1Mzjb&KMw^0m{zcPgvEwV19r>Un_no=>38)y zF+9P{^*)+S%yxXB&i39?Ddeq;0~%i!AUg%3T5;*pc=lw2Ur;@K1V2qqa-k$uF;H~7 z)r5V6B@S(*WbP51z#y8%R_!s(;18aDCY=8$p>ZRN-=29ewD3)TzxRP^h?^WQ_edC- zerM03>n!EGI$ab8iIa=V2n_rHGeJ#%5kF90k9l!VI9etUCt?1MUpU4W1MQQ@-ry}6 zPAcoqmt14(YBoEnu}5lC?(=fb@>{p~1$dX~IJmcN@XaE8ILka^$)yQ7GG!Bf55-zH ziIYeRz(g@bYpkn#)8t7ba*mZ~7og55it#ik7UBa23?*$- z#MloPIkfoNl9H8biCsmYCpV!J)G%zdgV#xGCkqT`Cz_9e#q`?nZ2jGhKpcjm>=p9Z%|3UR$7AFmE+w%Y)Fl|OEovAlV zeH>&==(&p??x|IzUV5r8!*+AMx0$JwGzj_H!E17q?fov4H4H8cvdU-7W(=}!nWx1>=O2kQ?_8wZt!7h7&niIsGV z{VSQNJ~AFEap03c>f1YqsW|%gwfpc4HpS5BXg7bn0N>hkq!iLV%xHiHR<~3w^PxHf zJCF7APehDx-}jJ~m7y~`yXo7X?HY9g{A?hdt>g3r>O~2?MehuwMK}Uc6h!rkL+@ne zSvQ%Fp#`Ls7}O7zycl zo?=rodI5w!osaY)pOodg`=YDnL)p&&o+Kj29M*&+AMHB1xk*3KAe)?h(a$2wl4u_K z8ND%m9eJ0hsgd=F4hOS_sGg0CMA;HA(X*wj&a8B8p8?01vPi5zQM&XU$yAc2Sb-#` zgmJTG;kBJy+#37xGUl(-nkDF(0~iK6$wvyPwNV~VCuUw;JmlW#rI5x)D|kU!;;Rqs zK1dJAeJLmCRC$}iKV^A;QIlcRGcIa{8HFDz3`HfTj z?vi{uJygZc#FoyAIcloMA2Kg0KK;E%M%F~=wq!GFIqDzCu_|m>V+XY!Jb3yuxkO7M z`t~`+ji$uFAtAG?ytDgR_}?AYB3rmn)`DhAf zu}1IPLnl46?jX#|y9gSR;f<`4lCuR~6~ZP#9|&8w_>X6|G48)ud9xkh%BW;cu#w+(WK`XEQ@tI#%!IxEOk;0In!Lty z3Fl44hSUB5(@c!7+syex9|3ronxCJanJGMfp5iNuRSMTFP*y1C7!au>5gjqHm=n>V zoN?pm)2^Y5S-S->C$7AZ(9l(Qry%ZXlc3-sI5eaE1yK;1*ZfuxTR%oFbTAMxXgKU^ zBOGv!ZQ|rCzx>*iet_kL{I;`}Re;Hk9Y0>8?2~3%fzD(P@NkM<3EumxGo$V6xT28%gI%Yfhcf9c`VMVgP3W6mtV~u$Mvt~daDJ+Vw{P2)Y4;r%1=1nUHGLb11)Uy1#o({v z^z`(2OLc;%{j$1Z5b_P&gx#nAe!1R{;T7CXZo_k&0({|MhgugPAx_fO=6leBf9umL(93L$tAA<^1~k_7uYFRuf{$ z)8dizv2_m1{Y}BW+sM_f4>Qp#*~QY0{8J-2{=~{wE+&Syte&>ffqt*_92*-aKfj-^ zZ?btOisme-ay0bK`Ly3%X{LAX2vGI0`I~)Bn%)E+JL-DRlg8QQb1sQ*p1#7xX(e+6EMOKDubdDj|(=wlq9xkVyR{+lQ+umq@_2ebQ#D`0QhE-W zcQToShv&h|n7{cjc!5E|Yg;H|pFDj^MWB4fB4uXx7dWfMufbUA8BV$Ed_Xsd^{E>n$WgwMVw)RMJK+(0p;_ex08`jalVhp$UvS0QZ{a z(~fqP9Otni+c1|H7hiPb02ijVVKw2?Bc(jra-EvGXsfZ32g+TcA{OTMQAG~&oAL5I0hSs?xD&2W&{w|G9`@Ei^gzx8{}d02s3RMhSJ`XGz7&Gb15DLL zbs|)el@6gNemG!;_IyO$U;-nGcs}siVX2In5o7=6e&+mLCCWu`^3&GdL?9UN9x~<% z^(4V(0|cY~8qx|Bq8>_W{PGM!r*S#}0FJF41JH?H4UAW1!4#cTb0Q%F@P#K$dUB1w76&kL-{*i z$Buo+Xzf2!J4(bUOe=fcpz&P>R}cx=NRbZ&*&c-n3P9vFc~bIwyu9)(VVqfsmIK8p z+R5@?{^+LgkX(U6M!v>534)Vp_~C$nbhm6snY6qgbAZ_Z(ld_K+$hgrvs_A|-~79G zU{`8uuVOIldd-_jyV1S|5UU5?Eu_aXhR$qrN96`Q?-(>+iiYtc?0Mi{w5@Gb`Fp+% zXuXV#n50E~uD^-TB?$WLe3PVYDL1la9+uzpG5-jB5^1Xxds5Q@P0HsPe(QL0E(1Jf z!xr{q#tGbT8xez@RPT2CJKn>Bx}x*7DKK(lyD@+<+iD?s^9!Cn>O}zekn%)B8_?0V zFWYZkcp$^CZ7_(!69Qix&jp)+S3UDGQ{13gN>8wP&<8OXdu&%|cQn8C$jCKuk4$C_ z908P{^V3S74pu!O$<-Hh#dqc?a_ctKDPW;U0;Iv(58q3zNdEIoQ%<(8~YFaVe5>Q|)p$UUr(+c1d*N{1}NeeCkzya+l z5mgEBDjba1Rm=}yD+oT?ab%Fm$uS)V3XYi(o*qhWbUs&f_yA>wi>e7e#gZThiut=~ z#jd(n$bW!QeGP={nC9b5hDOBWI%Yxhu!9moc2*Q+R=1259=~&!z5Ri}!1Y&q+!1Ss zGX9cGP8>d!uG_$|f!CW>JO@CFZjn+PSXO<<&;w@_;6wGI6t}JG2&qFmi1&R~I<7HE zU3Q@S9ySJrxQXEqz&@x9vHMF&p45^20MBriUv`uSCIL%F&{Q5>dptu|&Y1daU`$!| z2LeUQp8KK5KwUvG@J|Gbh(dflp1e#`{oD^UFFQ9kSVB=O_a`Uq-Q63X`|1AuIe_)l zxrk#z5N(yVZqPUpS-}+O4Ch}=H(wqK1F!;%E!EdXk3;7R4;uezNh(RehY3LPGF&+t zA`J|v2KF7KihK^)j$t{-$>75u#p#Y;7ijgrXBy0Apc2L7{0klG7PeH7T`*L@7YvIZ ztcX5%_|RF1Z+T{ca#$m`+68?(fL*M@428_`nYVW-XeY9{xcK9y?0t72Sfjh3vfRQLO~yRI*gBV2nt$;PXOw7 z-oO98cMo(l>fVpDzp$ca|L91a9-ZypZBm@^wo!-8E68gr4%)MWQ=Q3Wm4VE>2#6gW+ z27k54$Vl^pp4arxE+?gX(X-xHwW?0V#n3f=FwN6IW`^fm507)X3^ff6l2GjSc2c(e zUPFYFAGIKhD59X2zxae5+;a54M z8s{^n6B9Uj64=>&RXR2^u+DC(`mAELw&3Tg_Phlw841s2K5cDn@;3@!AB6_ygCO(Z z^x0r5(;bKU8Wez;9LqSk1VVU=aJluL(4Qa_S=)5$5J*9|p1??MHS@o#zh=(iXAK?G zMBLQ$^y$T6-`I76u(P+Pep7bWdGB6xXHXxKFtew4_SHedfamb?keV*7F0&%43<|!u z$`n0MVIjr-JE3V>9MGAg3AU?x- z?sK;;z%hl1ed-v70-8mPG7F!`V`475Kw}^uxP$58-o3DQ0?^9XvpLW5+mjW1z#H;i zDRie9Sw;fEJ8}1L*J6GWjoza9-h?|J9L0b=mu6;Wg3AY-cw&fdLh;R=usV#=a2led zA}3MP_T8%}=KM3{g8u|r0x1Bmu*@(PLcfvito?92!;AjTl_>DoaO)+y(vxnTAN`a* zsFO<9Z2ze;RDxYJl!Q1L6nLP}8)e&}uQ^bFENwcAP9Sp@tG9w=M1eu1$#Bihc?e$E zZb42y@O&kL)3WnY+qJ2Y7rGX=7*}8VEZ%@{}L>6GH7>v)4{$U`!V>}%HwK_AC z-KTz>8ZwKHI#|VHOd^d3F21m9+>8fxG6pgqrl-5~zMbmU;f{vX*`XQ4QK=3>#4z7ZwyC&2`Hc#UJ0lk6ib)1;0b4G*UTWP{BAg_UqEw9|4O0 zdydqjFv6?xOL3F-WTAiTwQ6btDld;gM``-b^I!5fas_s+O^s3|Hkx{PjH6J%%WM=8 z8H0Ju{5<9A?Rf3OpI;Uw-ZQEHo_(Tnfx|PDX>N|Ah=1YupR;Lcm%J}XOo>8DR)6BFs9eJ-5$_g20neBzmvgdoCCl%2AAmD0DXzK1p&fCF|`HG)OD}WrQ@da@drQS%lr4&(Yiv5 zjY%jx7R9u*1fz2=T!@$(QTsRIMg!yO$Q=$tyGCR|o&t*tL)f#=fKOLp&;w2jx@#Qh zbOb^Q0#R&`f8VXH{s<-^*)C?Yu5L6s9CD%#&W#;Ag!V6^iZG5}0hErmHYPt*M6+j&RZ3dg9Y`V3D!@?{%_j;? z({N97^OWn?Ly&x9S#<||T?C0g9xE{kKl1NhzifSR5s>q{w$p6@&@oiUIz15-lmcsa z)TPf#_0R+8f>DdL+!_3<&1d|bsd&Eg(94(LvxR*f6(G>h%JJ*zQ+K)^2WbSU2bdMi z&O$eQ&VXwsdLE}ZZQ+V=?1xH=}FspJ|#M3v;{JB)~vlTXjTLPixMX-96+S zi9~55aVVkUp90Pv)bC+K=^;=~Chf0##6JLPJ5=7{5RVmD!cZ%n2-k#zF=G*11dz(C-6e7P~ z7vp1ei}VBn$%AphgE|4FMHB@+FVPwHdC!x*nvao+EeH@J_Ft~U>f9F>61rf7)t^G6 z1N~06Ib%xTFe)fi>Yvc@p!GvRCiMFN)!TVt+zX)Uq1eU*2g)dD`J5W}TWfF*B*aFy z%C(=i`)2(VCeXQRzfkZ|@LgBpi)-b`_4igk6ZGp&)6&zA-3q2@yo=$JWzF3uFU5WQ znx!#gSr8K!H;~;Pe5C$d4N0_Jp8WjiC6(PGWOwaIRDOJ+PbwqdkJPV?h!4=j@G`hd z{Y^H~8Bd~1(G1zoK$utQzfrPq)waoMeZEkyRAYQcBQ)yK@=l>2q0BqJPGH#U5 z>wWw7FIL%=#%)_XnB9=#;now)2rL}hY0&||__sn@o zg2)iwkv|~OD|Aay@WXdg(pp78FFD$waL`PWRhs!6i6C&lQ&ei5zHd}L%bq-ZNnvks zaEyQacpUc^bO%^Tv)-d5S$IsS!DZ>T+kJS^0Jnii@uEtKA;%`I&?}fb0wqxC+`H2L z@@w%YZhDtQSAAjX!L-@|U`K%#Id$fla{p z_4!Memp1w-2_44bT=a84j$9x$GvgKMKi?OpWT}uAaV$@kgko}N+_rV2+(7ng7= zLlU`xo|e0tVC|z$<-RKyFPd>XO8?KelFpfbMyDh#2_hIBfhC9UH+=<+i9a@@#n(Ckf< z{)QGoRkdB*In7!LQN*|+ip9A5_Lwkh6tr7!&wbSC?#x=6>3OMX!H`q1d{Q&y zChxbG29kJS&HDaZIj28qdF0T_73Dw?(YeRpvI2J)ZyQq zpReFdZ6d#I+q6|xpw&!G>{SK}p-JAX&;M9GVETPC1ELEpMuU3JC9jFg%CisjEO--M zlvhcKib}dP?U2@?BmX*y%X1hABXwr^#hgV4DpG}UU29Xd2|tJHt))HwE26{BL-XlH z69TjntN{GM{Q@Zn^Jmrn{F3b|hWxrKGZnBZr+It5`a6An8p)4bhDm792sbV5Lt4&_ z8$UoG@q}6{%;ZXB&QFDZUYU!I=NRtjeLV0MrvcE4Jq>PDtr_%Rx+e5*rrzvfY_pT5 z;pL_NoCe;bl!9gbz+2U<%p%UX{eH1RQsWLk5!qOwuv=lwx|tjjY?VS1yOFieZR@!h zncZP}KBM)^b;eVy{enTA`kl0l7gIUJI~o046JooQRFCe3<S z?U0u&jaEl9n~KeF?~*V=NQeim*^6Y2mN?awFTHxnQbZA zB2}lbgM2>DC7ocTvzf0(<%Wx9W?GtuHTzkSnUm!M-tWEgQwQyDThXhw_l}M>?(D7! z$^I^)eIu)gxq_4S6sZj;N{6n@mzT#0`xDVsCILH1_fQItsQ|k zho-B3ygf7fz>V0{48Mz%Ipo7axDr~_JjjTty*KIO{>`g3Md3)tzDNVVfbK~)#+{3u z2a8%jh&jm8to+#}=z=}Z@H@(v9_Ya^kpEA{7$7%8fC+%FU|2$kq0-jVTgP+>4I3a- zkX_tB+x)8MagKv2skD+mB#U3mI+m$Rn4_Oni*s) zS!bNLcvZ z!KZ?RKJ0Me*93DOa9oHw0U)##%o~svc%NE8(-96pjDx|BQWb0~wD4I)z}~iO-u(Xd zbjgnBRgJNAr0xOl`HiQ3c9SM*)$edR0&eqtaq(lDsiA(2BZ41W8d#HJ{5(0tFU@sU zDzH)?UA{`Y{e1=h1QdTO5tUT z05t`S_I9tpzK7Zu4K{Z*O>djn4&rG-5UC=7*R-}9`yFsR#ql>4^uV- z#sFfoUxWf%DJdDlaj+oATaZnni{y#i;kN!f_*5s@QRj3#F+&{D+r1oQ)y=4_uF=x? z;bv*tVw1ljp+)s8WVXtTK3XDU@;vAa~tg7DRnsGu5%6Z^LCW2LS<_mtTV zW`|SRu1P|?Vj9*Ak~Wqjhp7k;|KCd`YDILvCue>TIWcZre?`4)W>kj381YVzNn-Sa zFE8BgUR)3>{CHHhlSt8|@n-p;_A5*NvCp-S2YpVO?CWpP71l0pcqgAlof>$`w{5HN zw8Bb8Rq1resb|P;`Pb3{IN|tNQ${RR6!^g>P6Q4$2y1DAFM=dwq8&pA=+O=a1~x`{ zf&oksX&ic0i)I_1{J}QNl*|VB^HyP_;^$bQPW?Ps50?@AH2hHl8@OFM;NIg9w<^;3 zR#mXS_t~>(?0jr(SSo1xXqEn(TvT+FHJ`v0P(1w->tCEgWwXO?M>qE zgEPtw6rBKPxxN`wjw{-Bw+()OjQ{~FDkzk(+ebvKpnRz5=TK-jqj-Wf|2@ma&3$gS zCvYx>3!zLTAk__^%`Q5pww&2<~|brIuCg zqnn7ymdUvSAB~nV#w11&SN7&+fw)f5W;xm%mK-W38u4sB=Y_>PZ?_&-KXXPg?3cCX zNuS?|wrOc~g0mOX)9Rj9+6S=wSnam`{#8%A>4)NC1LYdY&ZZ<8pdt$cAhSLLKeBvt zNx05J=b#-r!*Mi{!UIGf2QUym{X#Ams0cv$-I!Zq#6fYchrtl;fRGnS@OEekd^d*4 zBme+h8}Jy0P7lmEW@W~o80TZ)4I&=Kus~j*j{s~Kf&HZ>XpQj$;Q^aoh%5gUc!a`U zj8x4Wwt;~ECVm8kMq2lZh`|wnJ=L^Rib6i=-%!Y7?IvJybTXGe36Iiy@8h1H=jsYs z@p9H|TgM<2IHyzI)Rd*88_UbH&+?6ou9DKZOX}h#w3+|JtQ#fLsKul@|BgML=>ID^ zoNGhcHbLKTrX2Z)EL2M382{buz$DWmA-XUw7zk-`__xuX6~QZ^TaJ zxmm{68APY=5lK=RXrfioU--y0Lq#%n_Ve7q!>eVoW+!Wmc6j3CDD72P&C_tvcaoAs zitlZZ-gffT+oOSdx_2z4i4+V0PheQSb9^E6&|$x;H%M)83?Ghbvpu!g0QM~epc7M5 z-be1~sjE9xJg1DoFgpdfxooC<{xBXW>Z03N$$$BE87q!p)=$aMY}k91TJ9YO%%zd37=Tfu1#2)s3J?{;!G0iO&YZCh2~p8rpJFnT zm)VCxaig$sG2~69rFu{=@symsXhslNq$m-sEi4d)NRgR2(SwYZ5?;;0%X5# z0v`%)BsC~Vf66_SCfGxN*(J}x{2tccm^j-^Fy%gK?kV;-;H0|AC%MFq^;vGsa_OzD z5AUC3@+o_p$0u2tFwnLI*u_P0Lg6&$0mj@E+p)ogm zbMs!}=$FZ2hLcO8U;i9XVsednedEX*1O`BbS11T(G3JFou-ZColm0WK-{SO-#~rLd z2OP!|Ok4?y|B_u$oZXe0norLwlHvac54BW!G`pIZn5FCG zfkI}S(r$3~4@*=Q#1E_lwy=S-L$I15$5ZwTJP`PRdJM;Saa)gGRm*RJFLe7)X8YF( znc-uSa-$kNV8r$~OwJ|q^0~qX7uy7m&b#l~&}GCGb(kgT z_+4cl&+*`mldSiQv>f-SN4L)V7Fw&d51nbv0hyxA(Zp&mpj42i&K|pDz$&Ev1bX>T zTmaR8o`UM!KQR!;%m zBhjhRQJ#)ZpTe;l(b8aHZ1+lIe}M{tb`vKZw^7c&)Fum0;A~B7795HbLCaCO&`xYT8F9v@h>zYoRZt{OVzTJ4SE!5Lr*&*_KSwMHwX}@PWp>@=vKBf{`UApP{v%thYB$hWsI(pnv9Z|z2^e)- z!b+|@b6l?Xqu5!hn@7KgXJ31Jwr#7`SyIet4WsWeED@p7 zD|b#mLV^tcrcKaHyo!m58O%4~7wZfH0}ys*&lW++K~bsxpYBlqjRb4%vBTh)cZNh= ziV7AP5ou+%hgc@CM4yvptu!kO4kgbvd$B4umaW!&j%4e$2U_th%|A+~w@H3@fauj<8DAw$?}a|x)wj!ROYK6 zw`OB0nLU2i;?d7L9iF#>tq06Isb!li1h4#C$0aZt#QIv-*VY<3J5c4D=E!l&I?xL( z*q(K4%{L4RBIz;t|KRKJ%JpUPCuz8j7o6T#N_)21r_iE#%jwgn_li(etM~TzQ}j&o z8T$TDLRmtoGoPsE?hKXhsCL-3p|?^aeQ%CrxXHBt^=eaND<4mms6QJH^6@uS@05^x z9&^+C9BqGL<>hp}`2egMmqf*x(x%<~EJhgNIyv!1n{F)thvDs;H?Hf?Otb^^d6Qs6 z331*tM0qd5hk>4NCzb;($(n_R^{9yY;nz4Q%Gk3@-XxDm(}{TIHqXi>G)$H+MwpVW z>z|5CDE{;3&kjvZ1lo2sC16xe=)+N~p8Z6?5t)p&0B8oq2n%Ba$AGTo?C~v6x;liJ ztb|6NY~Z>Z8*_t>3)?A$(M$6B*!F&`lm8udG zE?R?k_v3;4PajSyWIFjsl2&JEASm|nqn@dqEalQtte$(ZZ!zQ-(To1azDCR!b}#7T zFygwh4hLS$7;Fkj2I~{X+Hb{bx`O5#<=JHdP6dQ49>mQ&&h%-cZvz@3qspMNb>`FmHu zzCEiWVGkRfO@1vr5&hk=V71(RI*Vm98bizalU}|nEb}6PyJ}rsd2vS;%2KdgSKN-E zP4Tg~mW8pIjm?hiVt(8dv!|{6*8v$SK}NpKNO8DJ^-ov(3!0vpa4#+?rUKeCXMGKR zEiIi!&kJ=al6yS&QvcIpC6wPzJF!(tE|zh6UjpUTekO~|DmG3)ExXWqXWTYQ|9I#Qgmy5O>Fw+i85>3;LqxnhFo+n}qlIPFE~ zcP~20yqh(VNKLs+6!9i`?fJnsXI1*caOgq7sq3oTV48pP)Z$HAU!B(D>7w?{kJ=O` zse53AYw)^!QG*f721^Syp8WRcyiX5gh>8Mdau45586`h9mZY=WNe8uQ*t;b;lL#SC zg5WrobaO1?b0U~+OF<8lSlpJ$`o2j zgM|Rc9 zB;UD|Dd^((>P&Cyy^(&=uSa~g>V#MQ)bsuREnq;oZ$GfDmYmb4>%Ziv&=nm>_v4mr z^uKWP?}6{<+XjM)Tb+P>3ahlLc(YKt2?LgW!_=WVBaj*W)YXDT49b|6Vd}4!;sX@3 z6bZuK!6EU*!7>M`uP!kR+mKJ?Fj67LylSgM#a)ig?1>T{;^$yhME{JAx*gAjZ*5;A0Mp^fmY-n#cDIOiNo>9!7T7ImCk$Y4PKN)j-|JK>d$xUJeDn{_2-(D zli7fV?zr zQnTPZvrNO`gjnqvXE?3oF{c{8czG!sQ3U!mFIBg^JoB`6McQX~@ug~m=l|GImH8jt zb={SpAaefPxp2`!@xu#?sFC;6dVgyc+?-7GPXAed_UVRnrzoM%)V}O)K|_oi;9u>} zO^+UxeniriN@4x{`d<9N{U7YSb5?v$Df@!VG@`edC67)EZbOtIifv>i_k!X{{mcKT zRNZoh&7cj<^B2U(l)3f|{&F4hEn8S_%8)*2TslKe{K(fVI5MeJwKTz&{qvgDv}>PP zQP1uSJCTqOQrID$BM+!A2gf{=E~}e-M$Pqxy8Jvf)yC3~PtY5Fzdtj7%yff@*QfW{ z4B}rL&YVc(-ea0~p-3^N&5PfWiz(b~z|HY_?)t5XT_#=@J`T=dAt$YOhQ(jHv5RS4 zr{U=2Bujgb>HVdauczEU9}VzND&13qFrqW`j@#vJN6S`@QWJy1J^R+)#&1l%Mn!O+ zY8g5zcIk|v{JDRktJt-9|9$V{Y(?^w)zt^Rz47){)T*BzNuyc21~$RIHzybaiH<36 z!yU9fIqbHL3C}9B4oH8~p!$1u?-wQ>@=+ZqsttdzxUjv>&gT!>O3gx^^Kg;nJ*{Z) zL~x`c$kc9p-1?ZeGI70H`N)`x0K@B4+Lv!FsLPmyvR?CselJW*DNN&wfN1rxw=v(W zh2`@zV)JIArBZ+E3*wsSo}I`!L&{>WaH?~4afva_+2{7Bvf=g(3xhw6)w_1tTRSFH zB%io@bpM>JjJxQEf$sjVOQW;>(OWn1kC#Qgnp6^Ad)&BN_7&&7eSB@?Shr}->dgE7 zw{1ih-DFPec-|@oAWJ01(eqJ;K$d*F7CGkYP2RtYFchlDS(#6VDGT|~&6yMM!JTWq zNcPLgbYii!wtgr;$JG3u8!#uIpkSIH$$!eqHIv6rCP3nLTFsWwjGyw=VpO~>siixa zj_}hANRX`0^D3<7Q1f2g`XCwxVbik3)bOEIy%CHzP*is?ECx2?RQ!Bw>lVo&*C^smo5V)8!PxH zpxq=jbgcHslq$G1KQ1$BA{w}S&V8%mCaKBv2|vHAantHiwdm)Zo4G0hwMu;oGijGM z_tnZ>w)Kf4C5Wr552}#994IfYlS$re7Zv3o!&fI9nEB$g-6jdo@Cz}FU6^{ns7dq9 z4lOOXF1#5(fH7MfA#K8MXF@lI#Q51m9eTSGX)9{Bg(_-B-O}CNNJvXJBGMt<-AH$LigY(f zBaM_OprmvO(%oHW^1Ns7^Pbq}jBkvOaSzA(1B5l#9rOBK)zUud87UkF*F8ilYY89e z_ow;D@HMhF!?B?lCZ_7u(aakM`)Eb6DwKb-5Tg91L}dsIgljRbc-kc2Mf;A}yA1kn z3T?2|^?HooiLwWINuIprB+9!8HVbMw`XsCdd+a5Ps7XeIr$vRWCCs^z0MipFi{h*> zfmF5O3mSELzjkzZWB(gB|4fLI$LtgLeQXW=eI)yCBaKSJ+L|euRJuFxJS1^StVGIi zV$iaG?G?**AHsQLEYHI#BEQ4}nlihhr7&d(B`Q#|1NX!=VXN-5?F3Z9JP6{Se1^jO zcbw%RE(*5Tja2gtMk}sz6LN5q*!v;}G?%b`-CIGE2FQf$u-eACFYR7=?%gIMZa0}) zl}E1pDL{WF8g-In{akQO!`K3yMxJG7OI_5>@??? zrUFIk$@x>51LW;=>J*YO1i4(YS#?k9a6aO>rhvR>Aw~>GLSnA^@49(P#KNzj`nFi* z*`W@qZ^7seWED?N!b14Kpa~3v05b9d0&*}%2ir_!P7;xCPgnLcxLsslHKwCDBgSwq zQ5mYIAg#Es?d=EwO*Q^0z%L9bMZ}pkP=%1F4QqVbI5X<#%_*c$Ok_d2c*V4mv#vttF(5?}*TuEvBD z1u6o;?Gcy}!A$2l;_KO1AN~TcLM+)hudUuEI6JJ|X-a53@c@KXa)TSL??%31S zsa_jjl^mc8m z@jacsVpB zw3!pwT!n^8Gi^-QreAkw@z*3rmb;81h8g1Af1^7IOZxf5GdY%YrV%I{BPGgepyeRP z(5mEEakBEpA=j4WlNnAn@9x$0-A{rM@de+=b3NZ$ z*c7tgb>V(Us|CSBG5wM2E|j}!iMGghJ7dcwabV<78fg-GQHL8azkx-Q?Wg8mT7%{pO+wAGNh4IrF1a-O6Q-e7t zo8D;=GGTjINRcTH3p&4HRRwNaJu`|J(yqJXpG=B>%-akW`cPX3L;;T$-IZ#wV{?e-Pkfaq`K+$WGlUL zrYHGSJRSZebS}4bBR8i-U3uZNijA<4+fNm?OhLM`FB@0@LzPQltO=`dB$9!t0i3_2 zHjXY`3Xww-$ew#GADB!p`dxgS)i4|f4!?~@nQg0+$jf?^;d=&8Q6|RxZ&M>1j9V?# z*_kND>r5*6bFuo`v2F4XdFZmz^piW3>J;=4_~A_0tZ))R&rtc z`+HkT$jU!Mp^g0gz$1g$n^PW0-sh6y{0)bn$!`Q(3u8$jkYP-;VJ2pmIUN(9Oq^YH zt2x!?KSbA$Q(VotV{zA6ncR@>dGJ0#kEld+TVoqYDcZ9&qe}*(oiELQv)U0Q`sRCW zcRC+uE9Je}yjapcM#5xEBSg5)w+s&P|mX(PSA`0_S{%wQ! z((LC72NjJeMr$IRVPsrL#wH$jRj640L{^9La)Fx2mbsA7FBADPVn|+_G6*enu7yBY zyz=`F=ayEwUK+P&{Cxa$?_l=yCr#+v-fqU@pO^dm4lVA!4c1r1R0llQUu0?AyUx5z%Vo(tGvt`BKD??JGpff=io_Yq^P~-=c(~ zmF4B)!cNBlgBg&^pPHUtt{UE$Z4+!oPbMPmf{utNO7G-=EaV9tN(}`cC2qrz$M*rT z{qCnJI}q_HECv+w$~!g)55~#fM`($1ew(V?$+Gh}#_MaPWYud++E5iDO}_3C75h$u zF`XJo+bjmiJ!&Hg3zU^30{9e3XtJ4C`0B4VMC?7(#zG zW?H^QMNYXraCqW9ey9ZJMpo(-Br8{`-i6@$KA=blidk>|!0>jv&<07m2U|0^(R(7({DkikAd-#y$`TX17;lpP-2 ze~-EB6f6WvI(&6`J4sdy?V9L2E&psJ(SL|?>aq2HjTKqc(0(!3j+>j!dN0&$u9deo zgfEDt_^nsrR!VmUK-)*n2}8ORh21q|i0CvbW>v)hieM#R82`4&1-f~YK@u`DkU!WT zk2ueV;2BM;Pzc=C{$Dm^hp~v2ycqEN&EF2bliTV^0 zP<1_P#Lr~f$0dSv)M7~Gfk08xcjvS-Iyb}qwTE3Ya+m}JV(h+jBh>75A^Eh;el?x4 zn+|RFUL7yON?j^~oixq-y*izeiVt#``ZeHBZf~I>ASDOX1i21*0lUu-^;9`!-d=`f z^e{hW3H z3n!dC31Z9$cHJ(&&ieYK29VKZ0&EdzY@eRbJwug{9z@RvMvyKzIx@ne_`JFmtqRz@ zi$MvFkoj>qe54PuJKEg}H=CP~_qgx%ROvBA%Xn@Zd0%{#mqYQD_I(^n{+_AGP2h(S z#!mCF)e!6+$(bN9rw!PYgVh?H#WaqSx6&s$=LM(pc=W`cqc57G^|x1EZpw4AVSt&n zxMXIq9436vovE^m)m!8aT-AfXG^XhMPc-u}CusQJ^Jx_}W>I;muA7YlNm-b_P`>h5 z-d=ELmqTqF7nu1?@q3YlBT>bk4w0-T@_z!YIWKwxo-*p6>cw*c6p#UxFlDc>OiZ6= z&JuxVkF5VL1RL|43JuE#u`swiUh*;Q5D9`FVtLVRYF1;qAU-;z(~ND0aZb3s5P}ir zXN3?|j-sRV9;f;S6cxb~wt)sE_$4jx zN?OmDTSawNji%Lbg5OluxZv^QRb&uTQexH;1!H!{vvzwpnf@3n|457t z>-qNl%HQTg6GRdv7!f<d?u2)4-G_=mi2eQ05+*oA`4Bm~=oi z#B`Sn<|q+{5un*VS66S^0zeD;IjtS*p2z9|rD^Qo1Rl*5c><=HMyO%m|j%q!J=d@nQNy8`B`-BobB<-CYYDh<7=^#s_V}>TK`VRM`t%v;0*1C ztchZ5vc%k00}Lc@20%No>3~ZcScz0s!R#EQK>Pz;&$mH*9l*7qPn2=M@%5O?g#%#G zZp-S^ommWz@LMZivwT?w6bD+Lr*QzF%9^@@S2nz3gMTq zca12Qb=RS-2qqea{VuP{YdlNMa!+*mQo?UfJL zF1{^cu%_b?=V0kxF%Re;p9qqS-#X`{I$6RW>-ytp-N}K5xo)DoIEcDcOCK>MUUuaU zCX&#%a`l+-&Lep$CmNL2UZ-IhNwiC^gM5O`_rNR6zBR$(RUsCD|~9q$%p zH9q+G%6VzLqNkM6G5kqJSIP`$6l(+o{|EtKPy^(*%lePEGhK=quXes<^G?4ONu+>4 z9=FdgAK&6R&xPN``<}O$&|lRsmRY~5_T#(kSzSG!amUlWJ5^HeN0ZR9$c=<)f6bd; znj4P?8PT=#bT^PPQn$$*oEPbRI*SRklU_K>G?$&r{|_xd^w92tPRw-ei11ZELf5Ne z_kbEaNEpjcE^S+pmxN@v1%+`E0-k6FejkOWi^TGegfXvn0*CfZzRYAOyhp?QJ$2NI zB=qBZ=)H^Pj(;5JG&(vUKKJ}C>ebBcwbs_T@k2fn)!gPOLeW1RN2uT(1?2U`&5Z;; z@oyP-5rZkO>UvtX-lr;=J9qTyljSKvJTFuj+$_Ub_K>qPJ{Ti};x4Sgq#-6t%Qus1;zB47 z$IHBNex!YY9kTW*50O5_Sye&~J4CgM^EGiJ^Z}S)g0>**71#7fa457sAGY9-!oJW{ zn^S<6i#Yi+m*~%G<9(7s{QYBlFCw(Cpw`7u92SJ3(jm9~#P+cGyS~xa-(jv(%{npW zI+=qN4$Z#^<}c<>gzkM_>BLWeZK%mAbaALMw|8D&Tp!>sr1I_L1|7WHFp%Pzc?8#^ z^GRQ2#^AmYjV6|PpL}VD4thFErT7sD2Kk&7_!+S1=hZQI3(2`ze_SfQ%HS_;KT`hq znVEBcz8IRpQ_-_YJ@wFbbA>og`qIJA-5@kV$MJ{iA5)LbV3^$f_Vh56bo|YjqxeQR zRQO;_#I@=L5Hf;+jeQ34Pk}ZH#AQNhccMp9xX*jEnJr@x){n#_368T zCYFcFeD@_~&9mb2-#+PLkgfH!x5xM-gjk|P<9GEgNHbb#p3%{Z&VkQwjXmM0S_Xv`Y1>eHAtQdJmuHGJT29v$157(x(h^fS>K zqQ&{;sv_J(BwGXmxy-5VS~eaL*05n;NV$How5#?t0bS^}M;6Fa`IUh(ksvXWkfH{)>NXOy9?AoK0K@h=QTfWM+xSqjA@(6 z9{Q+Gt~)VnMz+sV2Rk7vKI)anf&nKpp4luQ>v!u{ta;&-boC$K?=w2>hNlqsQIy~w z4}!RNs_OxhAe$B))Hgr(`2uHet2c(twgrxb=4Y+I7ax7*L`0l0Iux&e_5zO=5&Je_D-)u&3M6p_GqDaI!<> zMJIU|(IH+T*Sj6BAWBn~9bSEi5Qzd9dwqB)B53=@jNApaSGJz|f9pHoa&r*^h^z3H zDTPI}F4XNm)Uf|S-}+81C^2%LtRa6js-N%o9t{doxB564 z9pSfh4+XiA`9hd&h_%;pz1Q)`!(3Oqbbnc`I@=M@V~7)|g1bLK&OtTTOc05K1q&_D z*(9jxH$h`HtH-DJD*qcDSeYBBl1cT24^lJaAr|V;pH|Fi3SEBi{=|%9EZ3a7Hm97A z77f(-TqRoamxg3;6Y&SijAb{QNs?oT)rNP)oGTW-6`VdEGkRy04cNM zWc{P9GG(cIp|rnQim)_Q$OTCdg@&lW+bZZ4cz!bA)v}|3eAKlm)tAh3;h0EEnY2)H zO=a!U_cB_ewAJr6WOt5;jPwM_G7RcH)w3wH*dTzP5jU9O*tPBYjof#)tqCckCI!h} znSA&DvMG?J%FLF*{^HyAX^%&0NO#MVJRx3ys`OS$QK;;?cm>t58&y>uSTF4>`kMhl z#O$9QtHz|sSr$DmsgEyV&r^#0FSKysSLdM@V~lFCU?;f=EA0t}_U4%!8fRV+RPV%I zyruKaY;9c%dfYvSxA$G`GpH6m?IApOZ&Z7dRDp$je#qaSBJDpD5k!Ef9wMV1>}R{V z^BOn|_e96K2n*cJH`8)0^XEHoQ5$8`i2bpjbE(L2pP!2Tp4yC?O!F=5&OuoB;rmr8 zc&IhZ$pXcig2qC6C2Q!Ee+#-4>}MEfVFlnWmLL8ONiI9 zno@+T3@>?5$V?1FA^$4X+&pnbgJv#=%X!`M(8ZH9dG@dMM=A4B#VKAAe~cC!_|=Db zTb|@WSQ>5JC7;gzSzC6lNA53~Hs`N#+iDisv%XHmJQ6LipvP`sj%xcBio1F%PU(DJ z?-*aw6vjb;boSkUeb3I&YT#(4cXyclA=~wRcC-0vNKT(O0vYpE*V9>wa$Qfy@9Ab8 zC90>w;@cYM%C4cR$1i1+oLX0>jmv?4`cJoY_daHO1Hyr7cUBT@bp7x<3oM!Fnp+0; z1@6UX6FxlthC?g0QN&@v_(WmS2tES-qCTedt5+C(!vlV+?_&05c&RWl@!1Jt7(k(< z3@Dla>Sa*D@-a0P5GO#}rV<&jJ-lsEXV-T2cf0;bOCYxT6XH>N;bj)XwqQvICqkh@ zpShi(T2u&*P(u7ts8S)f`b=$itcuxW$eW1*Y1hCP6v)a%ali85?7KK2W0u|F zT;yM6)B@a+==v@fdNVZCaX`*5@UPwemE4LnLCF04nG^^GF`9y9qF#K~d_(v;2H8lV zatKPXGODKx;Y+bPDTlEn_yR^Q5HIhZ7o_lU$QrqM>pffmNKLcwpl_hO#L7xlO*-h^ zSOmie|c=IdqJ3n#uWIl6?5^xLpQ(+Ck#lOLF^qP8=E~alyz_ns~Ob; z(+WPlTv7Z8bGhKlQGraH!wizM0{fs>jqi^yzgnp$1Sj+&4&lAqE-NM=(C)a#P3>1% zur*vc@lqxz7G8GqMy?hk3^iI3JaP~srz$c_75(!e{b~spo9@5=G2mnRkxv$C1RVBk zm0e+ZrZ&xQ-H<&e+6xE1Vxr-AiH{%Mq!<-0&SCuO zap&mNYjgGkt-ofH-Ml^HAPYud7#yW>9l~Hw)QYjXSO%rkV}aohnm`8C7PR0VLw14> zz09;I?=mCabHXD>N11F|N?4IjGP_m<_)G(*{M6Tk5vKM{@?t`{d?lH=c*!@xQ| z@ZdjRG3QZoWN$8uGIqp8(!~p!buAc*Q=}C0No8q2+vHa9k=!lu^cHmbqdOd_+8@M< zN-z}&{)yQt5J!PoV+Mq1K5R|;R!l}ttT-)$Q zizQ^RNNdZQr)BVYv4La(WaXc0c64^;di;$9eCogviA$*%BP#HJdUfVB`+}q;y&YOq z_%*i4LiP@jou}w!dv-evs%UWW@m*pL>(ivHDQ1|FTw8OAvLy&H_Kf<&n0*s)+*O=& zW|D~}aRt>j{uZ16pfTgd80=&$WdE#HM@389Z{9Fx%QI;Nif!cN27!H3877Gac&7lR z`|6Yn$524vys<+3RUlCPW@+FCD?tq2&50prXi5lj=uCPu+R-Xxh3H1NB!O7QEVjV!H#AIyx_H)Kkq{qVc^W#^V~fkpwa|<=wpg2R*uV*p; zxQaB{@qE*&T&vEeDdJoq1RdU+kep22fgjy(T$jd*7Y&9QS}b504cUQ7Qd(LXctyX1 z)DvKJmXVp6o_2P1e#!_6DGnbuI34LfFV-UIv< z>h{Fo0_$1NtkIXmXdbeR^ZBbXC0_X8o?4?TNzKybI~vWSMey`lsUg$qCf*ia7?Isms8}j{MOGpw&bnd2{`l zL2^zy3kNkep`?yQ|2}HnB|A11zkKSH*Q8Rn+PrKDmOs0;jiwl6-2n|$NeS|f*DJr@yjV^RyS+oy z5`{#koKG;BC<=JgIrVI9tx*de=)RIne8Ew$Qgz;OcXf)-LpGH5F@f8gK!yvP++LHL zNw9~<$(Y-l>)K+o#!ka_nnfg;w@cn?+!FZjzNhr@3()1iEMM?Fn1sxvve47Zebq0<@G-d&C}&CcPe+4!_=O~T-3=E=w)z`e5gx7Ra6;CsLxxzS^<-}}ka z7JP$D)D4Uq2XsD;Vr8su*Ii6avs=$PlzlcPeDDb>&PlS^4-y{V+wc5(Xe)eh+^XLy z1D7Mu7HK47du_Z|1L^{oq6ZMpevlY~mBFp%=8?j6ntaHKmwA9LV{qT8(j<1yHz z6)u=rSv~_#)$;BA%1+%G;iEMd03yjq$b^e5L@(>+yL?>|t#zw-?fF%>+6)|z*#Feu zUbYgCZt7d_<8BJt$!hwx_ggkO<-ULjp4JE@5a5w*KiKtralcYON51Iv7sZDl?yL*( z@}G_tQXP~u`&bNqH>jDnWw(>n`cUX}Gm_*GH?4GZDB|B|N*R8E{JF(mQ~*_)?&58j zg)rao;MYv67C(kEhU)22!apJ`V>6xDeTM9$SVP6(kH4gUki2th8h~0x=%SK__o6Ql zFipPO@q7DmmeLMKrabg2hn=Su#a=^F9U}rGUHzjjb5WgXtHGp#a)pJ72(ejvS}VxXAN`3U8rnmfWHb=wc3dia;5s@=_x(I= z*hG7U@;J)nUgcAEgzis@w|+G2eOpiHn?v?z?PBsPN%83H z%Bpkcw+)Y$dv+O2KD1xQ@HFXGxE;dQM5YqAsqu8*+=ky z#*xPa1b?XoW24dKNbw%$f2F;9bO;Cw7=ovU><`qCemT7wuk@3l^3e7bwEk0^>~72J z@9J|Ah6xFiL|E+Lf%X6cuR}_K-7d5$^FzM*3Tf)yR`)b=2-yEaEs{Ww*JO%7uJ0_l zVIiWKNHQBk{RUeX&DxQy2b<0A*}a=!mO+iSTr0w_vw2RrZO0b^x%ogqV8iO-AyHS( za7v5Iqe*M6VQZET-m*)f0j8N229`g|j}txF8w+|$vDsopOuxYqH=QJr5Sv37>IQQm zDt42kAcnGBzCp&sH%1s_=eA$ov*K}yVZbM=!$4@XSc=ANZFt}7pndv|=c1Z9XW0au zAe|h$(8~@^`94o1hhK5NV2F^N3J)m|cZINTRF92rqD%Ud7t^EejuU>7vBMB*+lH+C zN-;lwM~uXiwB-tE(fSP!NwuDbP!uIM$EU*gD=wt<_Ov7HDUEK-EI{S0zZc||`1V!` zD&UTjqu~Dl4Y3kdZj#f}cgkS858~b081~bwCKVC$qHrU!k*IC4;B|H>iwgLVu?uK$ zmvJiHuF}T`C~9?XBgN}Wf*_fY8r9gp6+v2Dp|D0X+@&qHh=FruI3(kBrOWO9}5ZZ~D0%2ysHWt^7^=4S51R zet&bV_~uL5YHBYr{ZOWJoPkb~FXQZ=pLJ&QO91z9BfR7px!K;g`SaP<#bjM7=Z_Cc&e{4+|*!$i`$CkI}?4$Wn5c_JKHiVg-r(rJ~ z*?x2B!zS*zXSQ`n8FB$nSLhy@@zrFpr$YIkrj_qLO6M!K>uKxIAM0897Q&;z39%eK zY|fRgAez)aH9VseGYrqQW}w>MD*du8N&k;y*Go=#I%$M`VePBIz#*3uR<3Y2vvb>B z(#@->ATfYa-|Wr1=YHNR`n}u1-BJ2v=6oJ`YTnTQNr2`4WpV)&MM>qKEagPM!i`eenMsecc#_ie)Py_kmPsVj?1sh47G&XFu-F?_NW8=wm*x6BhefN#F8y zg{b+}3bb|)oW$5sMLfFFDl(X2QnB*K?}ci9ke{8f&tpEy$*MCQNxpLZp<-|B^j$be zM~SX#S5HFb(TBg=l(I%cckPk-SII8~Y+OQ|->Zbcm-hhOJr8cctD(*?d4ecVq9Bq* zATOMaFGnhz8a3cfQhDsINVk+Akz$BTF~0AE`~U{$OTs1f_7!u(c!8DS@`{KK=AjuW zaZm2R(gCN|#1i|~61A-LYx9KNAGB_kvG6{=q4u8_9-1g#tLZr2b1QxC4d`J&G&2J8 zA+qoxR#e3$M)%H*z&KUX5WX;%5I^!Va}wTgYYAQ!Nc&MN3OK>rAAllwo>hG?E5y`0 zu9V`SuWv7Hefj9CjiY+HB$y3@>3S^ec>26mL#4?|nvvYsZxl3~X{>LsK3IJWu)k`f zI^O&QS8`t8?dbxrzp^8jo(`lWPk&j@h*D=sd>#=U3!|7-b~dtf>%eJObQ>qt3WZH} z`dh>+b=A_fIUV=Trj-tH2U{T%03ZSEb7wf0Sp$)xK`*vd1bxYu*sf<4MKw)1-Ih^+ zWH&BH4G?AGAE9orP`Q!yR14x64Cv+Fypa%=b%Q3%d^N~?fP{(Ay1@6Pt%1P`cUbbH zxcJ*;ZYk7t#0N5b;HFgUrq^!po0?{&US+2!&p z8-63{V{UHE%%0~00vuc{0Y~q@P8g-CH&|E?z=sObUb9HM_PoB)xjKtsG+^xeB+&Hj zi50crtIEhDtp7z-%kkb*OX3*xG|)fHNl||8PfturGJXbY#Jix=p{}UN6yWbND7hq} z*b+cv5}`F&8G7WEs^bE5Fx-kyYd&fI7rXVlU=(YO85bK_{#N86*k>Fu}T z2n)y2kzjB5YmcSY+k$Z8|3qPQ(ZfqF;M{6fHZTBDagTpMk2J_o1^FR-pbQ?AE`V}j zP{Qm3GRi@sB+x@|0+HdyMyq#8v(Z+Bu7SZjQeGaO0vNC3fHPx~hWh&Lkv|(<+8&d2@@9-M7sRoQ-Dcx9u32j&ja$ zyhs*u(&mq-gq8-5#i z&md%U=OO`Fd7r%FW5)cjbZdTQLY^acyH(e&FU0vc95mx1pMj>)ve9&2$_;n);VT6QwEfk>O_ z9&JMkECgV&=4PMCp+7&m(!2H~NjU>1c{4*7@nV9MkW2ravuPed4DKm=E~}R2NX7c- z`30_t)O}ED=s9xqt=#@)hvRI?TXNZtQN5L{wM!(f`)e?dkErv|wGOWZ-$~G%b2l0qImN#x*m|DVL;u_t8i zKLJ~D*OYnv?gA@Un47Pg54s5X@O0sqqkZPm#dRb$UURzy6xbIHnHrB%t*^&CB@^>{P0 zNBui#xECH2_1F3#>*S#i+ILBi0~P-FYW}WhFsc>tMfXF9xld|UFN}kRjF}0+thp3< z#=&Oo4Fy#D@et*tvut3ml+h}3fL6Zl=cF|+?7;QK@`pn*%hb4@48H6V_K9hn-&-CE)tHno)rde5HIY(<$?S*IrbJCIf3PgzXInqA) zc;utKTEyWUemGn9vc;pXGT`r^0t#vUiBVu=uYKCLvwwKds^2;{S_ay&U?3Df% z7Epqp6b>F%jvXO<22;q8KcqD<0jVYD?;jlZ1>=9nbxIKI0Io{$({#-rmrdyg%zq}{ z^-5yUZYS-?c)}7wj#m=?smKlHEM5?nl<|+yXd$pD(m%tF`5ef}0T7k0<^SRmVcC)S z&{0s!K&UpU*s;!Jg%cSm2M$I?^x~q|uPjD__+9W=bX!7hC2BtF-tbrlJdQCM|40dl z-s7S$jk=3U!*6-H_%nLantwSp2xXCa19i3kp{bi49+*pbG6QM2VOOin#t>LECM=t@ z?TV!PObjF9_i-@SvGwj%{RZ~>AWZHfa73#(NxxxLJn?gLE zf)>qG(rx?uA6kGDbo_>A#;*I1OeJNvw0Pzqo^vLhvrYrV;3dS8YaWu8cC?R$XA zbKpzWWcx1nFGkO4a7$)+`NQtv<5E=R1z|E)ttWWI9|tX-C+wxK+s!~b&PSo<@aFj zO({56V5&r^!ig(Ip<4v{aWaJNR)Otx51CUsID4ULZCN911#H4cb7JqwwQ?^6ad)`A%5ZX^IZ*c+S! zQV#l!|2sWsOQZF4y+i&dk5(U8C8($#qj3O4+mG5Xl-f>BOER(EWsf$P-B1kTvq~DPZVt%*Xz~83k#H%ie3)Q98doWx# zczR#_o1!QijIP7r~u?4{7v3CQF?)d)JSu;J8LVkgi}((|&46zB}(4GV;+jD>|H z!TPqFjh1^YU!JD(H}1_aoVRbl+M>~ zX)>gDEA&V9H~cN-sq7iM9?n*)NBs~r+ZYN`F~9>?wA5raNkST8^+Jlo;p7lj@TDvy z_6;MvTYWn<2kWl2K*CCrRz4=)lh$Hs?$an8ecr>?KFN z-HHvjWUPMNR|pFIIZKy4pGHNE^(#eEl287va?%z-9{bA?M4eVLeg{XzZ%5zl-|PaB zNOv)@?&!amvs6vB=;7zLOLtDs;Gk@Z6tB~MDXwTiEahDEg~6jH@lLOZ$>(woUZxKk zi>er|>vZUIl&K2VUw?5%c+evi9fchDJ0)V=xYnreJ(3GHbC;L5jj}6ep*}E@ND>Nx zW|ML9v5w5`u!wrjaczAX{7@wcKdr$*7dQbr4nI%5WCiW=F~t8DpmX^x#Rz^0HN*!< z1CH-DKwRT!nCq$V{jRM0XeD)@PI%7?-Ecqwp;uJ&LH66ANcG8ym5<{F@cO!EgKbJ^ zJOPamkIud+_P5*9xZpk~(F;Va>QSh0By`EW+>%7Hm@CJKLj#}7x}?}5r4|cpp-Ix- z&kjCZGo0rpz7O&51RQDEJG?ayKUGzQeKqnU|N2VoF|RuRZ`eKmiz$_iiWOTAI3*^Qp7Es!WjUp9Cvu2nGyGdL)!;w ztVD-oBZ)6@a!~>Qvz!95r+MMs^0`KMDt{9GlAO);Q9$=TOTi9}5fk`Vb=V zU!270e71nQ}t=O-NX~4ZuBU@g9Cb%GPijk}CDeoc%s|~`=K(Bfo0CkyYAAoyVOGV{5 z{dO{dMlM$RccBb=>^y2Z!G+knN+wC{fzi<)R_YuCDS14hJ%otpY34SfGb&kEFl^Af;f~P2%@Taq}@)?Pp?+( zfnHAc7bumMQSXF<>|(BX0IpTn%BWVtS&|}iP@MJ?veYEHeP7U-N{I^M$CyNp9_42n z8pwVRJzf>~{;7*NKb&{_A{NwFsQCalo9|$Lp#WXo;nnl@|L7TYvX}!T_dF+!1}j5= z3KEMzVK%_LK)ValgT}|lL00GD0}0TjUH522)Wg?VC>uARN<7(XR5OX<7DqEq9Vn zSr5ipW7u)ubhP}o%fg_3eqd~58Em*JiDNbG3F2701iNS6tn@2^g=<+kJ3C3tc4H&@ zd(9>n6iYK_&1i@cys-L(egCoZJ~TF*laAJOnC$yFYH&|W4yXr+Cl|?C52lC!sVV3m zyyj>VDq7{-56d99l_k+4t@g(zqUB#mXg9{o!2a?HH`ajjjYGB)cqgX;nH!}F6w zNol(1Yy#39dAjL-sg9%ZWw#@8wG$fu-2o|X0Zahp&r=1wg{1OMp!%t_e--y`yMA|d z)&SYz-s~qFgrUOzt(KQoCFMx9yts9Dkdx43+HZmY&<5D{GSti0uq}G!hQBH#xl4$JB&|@4 zB^U`73a$8VDUfjHP3h#Z{%(G&VnR$0+e_S+ElhG1#VVi!jm;6RK*xbMFiAMskb!kr z+RSV9#jC>v>tQB_9+n?aoDmL5|6CT3A`O_*pXcDP7`k{qeqLBGXOwjn44Gre2JOIa z8i01SW=MCERcB%o1OgO1w;opVd-K0V_}xFNi7@e$X_o!*AJu>Nbe+|6AO3P^3!zf_ z3jJ~dtNq>dfq+w$X4%mLOdAAf%#K<-XisH&+V09KH_0V4lsnU%$^$y#Ry* z_$hw<<@5E@Ew;(V6Me?-7n8h%IX5fa^mq0ptGD@i1ugGIEPS47MGdYL!HMDli}l)t zAtanusc<%19DkTGMRbnAVtIL=sP@a%2~->U#NYm!0C90*2l~Z%ad6WDsfJ=NWC!jn z&o*P-=AkoKc_(yL*F7d>$M8&--CpSwOWIj+OoLm<2rY*3OvGV5Q*zI*S|3Jj>k@gA3?~SHDiKPwl9DRe)y?6V ziqp1L4G-x&lU&q9fxkdJ>6|ybHdsZg=sBHCqgC~$MlU#1uL9QxSt~s>qz&$tC3|`6 z=(m?DD?K{$gLO~dh0EWcyQpB-jwvRbiHCYSWAb2udSG3b1SGo*&b;hHe{0SJwBL96 zjiwV1OFs|VUx$Jlk3DGR05PcG3+Rt0L3cgq#jN!PCi+pydRN6A2=Fe%#PzzWf8*9x z+Mym&4%r{G?wLs~QlX^GS2Z_n5arL5c%`7AAYK8D`}SuU6Gg}`jnA{;-`>*W-WW@4 z+PR{aFvh=TX4B=fD;&^F;-xRWG|h>NiQE#>xRh)536YX`1GFs`m_DIyWUSB4lBc0YPrUUyOD(5d)B}D0^0uN z3w3@T*+cwA=3mXy4q5Fd`vzTKua_ci-lHV~VQ1h>v=awWkk;k)Fip&}rq=_5%YM~s zA!wGqx)II$hs(|n+ud+etAMwYdEW0h6n`ClSPu?q5`l{vkoEhEYfT%i?Ut_6Z1+>z zN`+qyj&dlV`)1(d^Lj8L9i-G$v$KVZW{c5I<2v>#ydtV~QE;y74?qiijJ+2d?fnAa z>zplJGLme4OWTcCblsex`Mr%b@65J#rS`K5|7R(DY%B_g_5e2SFipa{xShkTssrM~ zC(rNQtDP_|FS+%rZE{~RoC9ZspRlf<5s>$6#zdW;O`DQeK0KOsn!seIZZ_P&sKSS< zFS3(#jIqBGSowVe1E_DLF4LH3!nv3Ckxmb{(y-42{F-))luiPw3N8unKEE2Gg$F@{ z(9Z)&v>&G^wiSpEABGT+`e#n@gjTYv5&}#NQ;&8kg7p8)wl@3;L$hf`fk&Ae$EUrK zOP*h1-eme4UA#hDyCgv=5KJ|VD^=Z3=tfqQ-u~GzNOZP|e^#kv0<^o{mMIs0 zJKIBdsbT{(kRb;vi3KowxF}P-uCGJXyh?)ifK+d{CwP~AtRcFsS&@qyJ1~?KmdAx< zvs*d)K?U5Sd6yg5GSv^&Kt5Wl{LAZxB9MCsB! z;|d%iq9HxC9!#?-0{p@e?N%(AY%%d{1Q|6ylk%PNhL6M-zk42jegcN%nBLmM?5pOS zEo7#=ZLIBfwzIG8#=Yz4Q9ETy0MP`W@Tpa^QzT};&D#p7O80(?Z96-x(PGpCM^TPR zx_1%#_~=K>`;~cJl6xTZFgy6{vP&;a-~g3PM?-TLReXp$O8nnsk0^Q|OiC2E}R+N_v-Cs8ONU$W9{yZ^+6d4l?ili?cnAMcFeejxs~Y%HFf=aWWHy zWM@<|5*gWh?+9fco9qx76;6^p%3hhj>wI6|@6Uhr;ymYh?)$m!`@XKv^?5(+LC%6U z+2epoFnQ{sgTqBqQjY^ZI6#iNHhz-p`vr-5Aow-~;794=jF7kdyZ$Xue&Y=^2!t4K z$5m+lFr~qlWV4P}xYW%cx&4>ap^-f}+SC;Ei}R@~T%=b!Rhj-Hw;T#A7gQsmCvVIc zqAkznbE?X1EoWiP@9fN8%_kw$XrJ-uZShz%kJ z(sFfdwd~b7HD93$QuA`z=RJBu+TLk2(u@S(Pw9&NZB%IXZ!&N;%<@6WoiQ3{U(2hm z?rawQnQqLHe&xxNx-Q(!GfFq77%LJyLJs151n@?6iPqDF2;J@Hn&=6;en+9mqrxwd zFr^K8up-|I^P#_&WGlqq^bjY!A6h9~JUor7XTLz&gS5YH)kaH5szMH7gBy{18J_QC z_N{Gmebv4%&e7@Ve-3HQQP~4@Hd&{|ZdEFC7fW#`>+E>T0Dgp<&kx6;Ce9zoxu)Dl zu{8uw|C&evtxWP}y?BUoI9%l}3h}OLdz-!H-rnni?9kda>!nWY{A;(8ycW@b!&lL?edQ@o(DQhh7em8_K-sw`xdsYkHwNS>Cdv51JcoXzW=?4VfzHP{`g8) zlrFv$L}){f^vFPlIQr5WF8UuY&0_^&vpw3LGc~&+5k((Fv|PcP%P)Au_wnDwQB~V3 z=A{IdmU>o^1nY!MH&e)qs3A5YASq;Kw)q4(JvbWL%OShsqpr$gnAw%)h> zT<_;{1r3zz$(?I=mADCae_bNz$o>eGaJc2D3wxmjvZ50MTO;=(ei%?R7GF@^lXH4S zw3?hLnm~6;A`CSvU&&V&@qi8krCHFgUcJjl#rdS5P=@`Umq!V;j%Rr&U#Z%42P1Q2 z?{fSX$cx5yb|UQuG$^PIWJMUQ`rDlk@&aCT{uv|W2@5QyzKkm@J{9oa8^y79SEqcC zXD__oFSP3}&ggo~c3~)W)oIC_$I-#oc7Ffw1dDO4Y0YIGX1tWTq$7`oMV9!TuiM#% zb{<-8CovQzSEtpZ;>Bn}0QnA-1i+W@${*PR znl+yGbxdfqw|-kGroo*dZ<>B!{b8cbiVZy_-Z+3Opah9hS63l
%WF&fOLa1s8KF z{I7LSEE~UXF}}lZl3OLJi1}=dV(W6%{C!I$Ja}MN12-t`frhXGw2tupDlac5Tp|(+ zS9n|>!lauMT9N&ybmp{ZNTc#g_Sp~~he0VFKi(yz z8KUzl2;&?0Gd=y@HL0(U>zEgAa3>3?6WjQsMG!A9?Un?(N^CN|Bl_=GcbzZ`^<~o2 z4cZNrI}$>ju{T1VEn0nIY!bgBlZ2O<)ieX^e`FQ&d5V^LkO! z*>mdEZl*lrW*tWZXE*Kn+f=mg3nnR`64qbEBa*1t zd>Kd;0+)*PM*G+8B=a~kqIwdzEP9`<>ioMCO$}SbD5mUKo=Zi$Iu76XeL-?_kMnP3 zq1&Ii?G{cS)s#%pn(As>$d%}9Ux*P@Oi_L(K`-G}9p{@EqUWr(EroONz*5;0V`Fnv z$!WIN8A=d5$G^8-`HTC5VhfHwHS4oYoV`(x9kITjcgVXAH~i22HkuD4TVz1b0jx3f z3mHl))UBsOnv!>9Pj_KAqaKT?e9#ZvRE#upy+;$lsyFug>akknx~_I4Sa=4wDmA?M zls1ioCZJLRe}6*50L9$ceOdwcMLxNOAKuTSktBH|Iv%xGVs{KEesit$m+V8HyTb{3-Kfuhljo0=)W=#vmbgiw_3zt?2QX%>9cN6F=7^_K z>%AFaHzb*%Q#AVT_!tm_&w&mAej$kyOQ94TnLdjQx<&B`2|&R5%w%k8P$}p23^3sj zo54Xkgp^@>Q0y1_sm!|aD@Ud0Ie@|jx_Tl%3KZ=aan=L&t#(cpT~KobAWj@HAwD;w7N$5St|u>|_2n5hqJ+VnJ6d^NREV7hh(<7cGN zVtjYrGj^BnnJ2W_>zSG1B8rJcUI||d!S@C4pBgmSi<`y9?E^)}RuPWQ~RqK~&;Top^;4}NTh?to1%==)lV7T@k z-Q>{Q-`@y$3n1k*1Aj57{iTJIgF~vYy^fL+AeuOUTB$6Gh1!GK1Y|5pe5SL7|9o$o zl^GR{c6E2RY!|sE-85glrP1#w8TU^ z5k?Ttzz@)fajXEA1PmT9=T4UNTm>$lx##uUcme_f{{H9K2DtCv5B^M4A*^ntB?(wg zgIETv(q)eSQ~@i-#j)U)GY0TuKS3c=(Ry|SR2g7)0J&^;a16k>0#~nI<>6Tc6shW? z$999M%9h^%&;+S?L>rJ;H(JkM>@s73BU~ylX0&;AU}koBk7mdC}0L8cG_fFNA(H@J($#TrI6IGB98Q_7c!SfR@Cj?gk?&nNbb~$>4e>BXgEy`2stEAkd9M zq$$kLzYTci@`JUzeYiq85lHpCuZIvYs;jGaS4LkW`wUBsm;rDM6BL%B!NEZoSV;%q z^npp_v)`XyL49>OGWuW$fuJzPG6JwJ=@451qm-1CbkId-Nli^1jjVruybm|Kfqf6W zw{mrg{8rx;sl{q(Y69DxcNIPdOTYr->b<=^fb94ktrP)E=LmB4U{_lQb|TVsGqgPS zI2>?|O7{SU?&ISFpU9~m`HGPa}w8KKf}0w6`GQv-U&XZNcr zXxdOlM&B?PES1_VV)lkNtIkDs*}@4|Su*JlE42PcR7twRt_He)NJ-Sh-SxC^E39!A z0)v;?X)Bol0~3Y$)c+rc(kc` zOnZ35v#HN5+{$zMeJGAP1dt3c$D#Z7QO%@jmEGg%CWhvg$5XY&me0rkL*qDlSCpxc zR0WX>iWE=4ao?Y$`3Bkd1jt_#_F0kP;X6A! zDA=?>sJn9I3c%BhOiV)8|9vY%0fl;fZLJZW2gvMXPBuFjBd>9DKZ2(qdv=)D=!~n7 z;fRlbsu0|sj)sPYx_XM(6PCWS7?svBi~s!iAB|?glB4eSLe=8gRu_mEssnp({NC8e zN=<#EW6(kO`tlTRJ#)7UK?AOw|IrBlS?(AmHO9%fX@Y-xACA)(NS$fJZ8tdjDC-@a zvjg2qBoBHsBzgZ$%K)1xG<2Dfn%aqOAX}&SPI&d(NEJM%DD_XH61^Cqobw}}*iV}P z#hP-e<<>8ZMy4bt?gP^my25Iqx+EqB%xsdH73g$pNC!N}s&bjp6kvu9w9IZh^)Du- z44<2#P>vr>09d3>OM-_*=Xn7Wy?MF}RR_P{(~VTOsCVPMc~h@wbYf4||LjCQh!D>5 z%_rOa01SSbuA;2m)p~xq(TPIHJ$_u4OE>t|m$o+w#sDmUz*7tcjdH@v427z&Y|V^` z32-(xGfVBWtu!k`kOM_|W8=_>?ypJ5bT$g zEG;doxtM-Y99{H+z%A+g`0)aLm-(h_VSG>>)0NY&{b|mIi=*F#(58XHb#mVQADj0l z8F?Ie(#T?Mw{$BH*Ta4jji?xx(56)u`!BtisO*YrCyjOePIs3LMxlHt0Y9@q&tJEgw>_atnAmbok*C%a&m~hP0+G3Hl%}tC}5yi@DlvS-fXx4ORKWF`i1+n=0&-g1a9dx>ak~MXHS~8y1_x$|7hhp zyf*;2g3rjF@|^7q17IQi_031FUOlix0v~J{U0eI@p$K#s#v&yEdlqmA!qpm98&Y(47$Nvc@Bg?TM0m+}t*lOM|E}K$2Yrj zIA$jD>Br&{_?-g|zVdb!3glnM-Q#lQ9g$y@ybt?)=wkbMvfv&)?KI-1SOvm&}| zgy>1Zg%=hoZ@?qMu5@v3PBC^Kb`IDl7K`lv{CWS+gyNuf-q({k)^kV>0Hznpsykrr zuSWDZ0NEED91K*>lhY0VC(h2d7$bYD6e_;=bax;9`v+_8b07s4yFPqaJmJ*hyT>Ex z3Lz3(j**uS7_mbC5=?#GwHI2I*$(JfO2-rCxyD7tD8%L_PT> zGe&5lq_vubwdGJ{eeMC|Pe3z6Bzyqa!QP4u*n3sHduRI5rVEzu;;#?YVxK`z$y?y2 zKAwX9eOp0#P!V%$ckmZ`MK0&H?v7}(KHvQcUgHxoBN5@B4w3W=fGYQNa zt#C=XgmOP4BqWN-V;0(Cm4*QHIXDSF~}g7jP>i-&GY zC(D}|>+Ch@)wBrk&_eAA4TO0>L;;)F)Yw?e zZXg+ZLjYx4cJtl;QxDj=9u_|=CJ=Pz;J04fSRu#dq`8ooLdtM69~Kfg-=D*ts}U@} zin3lXHrM#>tqQcBxB-X^l8xXIU8u7H=TilRPq1yUA55)*%fZ}@tsZ<5OFQrZhtw z`(P#S;NbA=*)tUC3XSF3!h)##;s8WX|0??-l?w2L_JkgL%V%54z+Z&(_xCcC{YR7Z z=N~b}?vcw>YFb(VlV3jCTY~}f3J;88Xyu5CWF|7~fFUy~3H05qls09UV+fAU$iONQ z=`OECqSoho^MgrAuvM#<7QcEaFnmUs82vzPHwGfQ^uW7@2j@#=;bQLOu~+fN^UkBb&e zZj`Tc{{4o`cS!nvU=Y}tiVzmd{;Qb1 zdc5Bz1bY<}K7P0IFNdiL3^U_GHfnB`(~87A+HyQp7xfZ#?9`8m??OdTXi|<8GGHWu7KdF2ty^lz9WQb4;F#F6zn;KL1HVQ=5d$`XrDbI*0>Cv6 zl;K@P!%|;d+TFc2*R5S#)~wRpReGOTenPnpFTwv-ig&7RBh42CFX`&1ya&wh1wH;a z9#BJih)Glc=O@1W`Sm^eTE{l;^0#Ee9W-bHS0s_U2swL?@Vdr`A%R6lAXkim!l~%L z?ed*KedZVm)C2vB#d#+~BNTZ#;c&rYH0PEj+9lwO-F)mz-$dceZ3;L%2|vZNm3DkA zDj22HY9bZMdE-WuWZ@dU%kitcDhJ03&ox>Ll%F=mcpzRB+1n(#M>Uj2rKfAVtejUT z18wJ4wUhE8PiCXp%sBi|1orw=d13?>9HKAj)K0Of3@4I&@m|ib%X4wDibUk$CalOM zY;ei4mKQI7`oZ<|OM{DWxZd@f?B_-t^7W`Xm;4LJ>uLYpt^)Kh7x0~Zx z|B-nJPA%R0G$OcafFNgLQuto@XFZc-J0jve<1PkdBfZqZ6 z&EM%yj`@WDOWNHJpa#jCQpyVF8ktuJfwMQWlXn5rE!Q{BCd-qefA+p75vNlUQO+BS zHEcBY2lVjYeS?Fkq+|=DeMAr$c}XpiS=3>mD9dZ!uM$+Lh~7cz<;uhK;NW(zeTLO9 z{RT+1Y#S{}`&x2m$Uqx^E}Rq5=pVK>yLx)^(humL%E#J5dxK62qBjvGXolMxt-*4j13&^lRXwAOc z8M{@)6HMvsWMiY}woUIc%y94AboMTC#w#w$Haz%i?+o+?!b2fMpgmT=7MDu08yyaN zg6wRz+9fUvj=G@#4iAPTpYIb5p$4l}xV4od8T%y?3^9fC4=pN>4g~{)gZJ-Sxo&cP z#OO92zX_uK{w0mrB!ZA>c9A(DBMkRZzwdLb>ZsjNOdg%7UPpja^ptAj^JiDBSSlLr z8T;%1DJ!rp!+=Ef+hBIDS?7vm;0=$bC3*%V=nc|>}=jq?iuJ=DuC?`va zLGu(TVq}D6s9$QnSQh<5h?}4P5-%wf27*>za?y9lsmik=B|<-^z9DC4Z-zX_&7)BklR6!tzUhh5Mfps-_>0Y;eZ79^H*HzO#mHP=lKOegqqSpvv& zCUg|6pka$~>+vK$0*;+h&nLOF zME-XH1#VJomzrTpR|Ag(BQ1u~jHk)1DlXb<{7q=c_7n81W_Qk2@e(4I>N^|q`UQ$* z71s%c)q>o#7;k&KczcT@V7r5lj}J!+j;%~%fATZU|F5>d;YV3HmyUWMl}E{H;h`dd z7>NiUF_Uh#$8tADYE|eV+a(;D3yb6AZI8tGLBk0)GI!!vGJ=0Tx9hJgv7>JdY5Jw@ z+l_2keo`chc!$YwpWg6DLav*Os8Hcc!j`%$ssuNU znoGZYf&4NT4lx23SF-irq9exKGr2SM&0%MVQ;tF5;n8J3K7=P*s8^l();wCs-AmaLvt8E#=-B#;PwuI8cgkp^rFQdsZ zd`u~{WP2Re+Yz^d;XM1&p71Jh4;4h+n3d%D)H^NgdBeijE|5M@Il{}^ZX+}TAuZIC zaB`>#Yu%ij?tBAD_>jyL+h?LMMV48b1bjPf(KOg!xA5BNWJZK{&@5}<;yxk<9imN9 z&inY4uak_-MHa*rbXiWGbOzik&*(bBBU4^ zJWCm>3M(a2dMO0Z&!f3I6rMdhU&dHDw*=V|P_a@0000_I4HW~z zFYx4{AR~Mu)Tvtlfb+zDMy4JHC~qzoH)mU%BbLj<*9FUk^}*Q!06yczX*jP*L`Cp1 znz518MuWGEJ!)a+-1OH2tuiAqO+Kpw&%z?0Y7nzqSQKDw`1r`b;m%gPn}%3;(slP& z-!?+$jl0cEYUt1O`vnVK9S_CdUcM}MM;JCP`C+G~U!YXB z@9za(ib#!qO5d7X9pt);?qX`|W49sPyGF$6vO8*gtC(&}=y&pb)ScqTl@_} z5_Oj*1y7rMxe5(D%KoR;?$%}dBG>jHaEGgZ#3vc1JE6rRE_PKdZwCh@d=Qni-&bM| zCdhYdjG9}%;6&ybgIFHnQWjPp+4{6?+}HoY{C#%&TgM^m*5i~!kg9O#nm3c>A(%I; zqdzXRWlM*tbi1F3-^LyVmH$liaz6L_DwyU6a`;mn;*e>;f=f+Ck*OHub4}Rvk6K*NK22f zy#_L`PBb-$dl;Eya1#d~qOiZ(d(GilbxnK9gG@GEDb}iCEBwK{C50cLLY_&cb`lvo?Q(1Anx;PhGly zf23tA0X~#JQuq8ve~6Sc-8RcPYB68gl6hicL`q-DXG5xaneDM_Bxc-qH6!*N{kEAo zw7bd2eztmxO>)5dj!bU5r^)Yw4)4e<^myJ`da-faf1w(OwP%l+GP74}1deqaT{9Q# zjhL#d=;W+M&US5<>45<_vBVoIaR$C7-^1nWi^y67Ik_cNpZ+doTxO#Z>GZRNP z!?`6KPK#@E+W6qvZPy1S3%bols~V`x@A1tJ5|-tX-wN})&uib?0UUuk?R~IAXqQ|&nsjfL zb|yLYpjm=ta<`mL5w1m%QNSx$NJ4+60TnUi&sTzG5%J2UnFWUBXSsrec~LjrMIO~J zT66|EP$hL6=h%8A3UvLTuB{!a{$2yc*@bxYASxu?oO)UVd6N+VH-d>BRxekGW-VtX zl6KJdX(g9Vn6JFkEQ>5D>u|BF|2$LGR$E_&2%Th z-zvE>Us4a?nc*h+?)My2`LKU18B#9bxEQWnl7)F9W<@I9n|L9>Ac z%(@^rwR!M^U2su&*fY}?qm(Lh>xE=fkOua@Owjym;bB>rw&nj2`!_d3_WOQT7rV~hNDiIy zDN59_*T)+?K*zkCGnhelFE1u?QBt*k=2OJVbKJbXET7fGi2;^X=EORCZcKXLyjQrx zYOLqysqK4Jdg@_Ll8v0apO0@Q!dAri=8Q%j`jz&;w8%O$#&)kajQL4GM3-(yp2a!& zI9t(IqZ&}KzWOR`U6Ar4i>t-{E7s=OL7s$}OJ}mwVUUm{&nW1JJdt}Ge3(dK+IBb5 zz%fsKJ%K#$`!a*9Shy{(X`N+5V)1-hGE0N5VGQrVTCdf+BI)O=DMw)S45iM5u7tz> z=>XYS0ir5z;-cN<>Py{_=TD82H@}3>is@~~V-9jTuCSVRez?T_(I1IjO{&B)K>4Dl z>4lbg%B!9YfQl(%Y0d&G21!fHt5*#GQJH67sB@TKWVE(Tganb23S zE@_z)HPa_~?M1GLS%{)K1-@y&apYEXR-F}ey?d069iUk1iE^Qpx=&J_04JfJ95^BC|LNT2= zu5@?FwOy%nolb|MflPB8=P}>#IpxvUd|!jcIw!%SgO6`5SUsRCXZmVhX{uH3poLs?B7`iq4b1F zKX!?m53YA5@EFBDe;^Tb?dmY41-lh-TLuNrm{a%+Il|RZjXUrfm7id5?C@8Wb4M3; zwv42kBcE6l@{KY9S0XlZ#Ze!eb9cW9R$Cd3>9kPMk}pk|boq^{JtBQ#0I_Rb^M~}2 zGd)*!ci5E`P~ipM9AW@1P+IVE}u^?9w^Oh+Mt%GP=mZI-lbyX@ZEZV`bgiFD^b z-)A+7Z(_DFXwiJM{}A}&lBk71^DAW$_#TyuuU>`=L*e&c_z*7iiT)C3$2wuVrzKZD zS&l@&SNq3cLiaY2cAsTe|55NpkQlSdBq0ASewfC>v@Bnl#wq5W7^Wz`@5P-feB`2< zWa-D*X=Sn6XQ>?6!WwM*ROT>dl#!`D%c+PLVH;?^|dN!L*oOP+Dr!Q^HgzJuHAisMc`b`dj1=5JEPxnl>P$E%_zbr|`UbpN8kf}A#$||p(K8>ajW^u>Ii^FLmS)-OR zRO-f$&%CZm0&CXUNOmP%=1YCaQmoxRRAppSfE}S)!PcOn&|)2L1ASfLU6Kdm_?JVt zm&OmAKU-x$H4TKXlq$W8PfBfn$|bm|Qg)E4Jn9N#D;DupfD*f}dd!k4HGK<;znmzH zxl@t#%)rmFUvA#>?cKDNJmZ#~F774<93@Gfp`D%W%{L=Ss!QN4*@ahfbwsMb$hkWo z%G$@Nw>*PX`L??Ua@Xc3dE35Fg>ha~s-?bYfaLmlfjVwBcjUcWzOktwJH}B8x_&Q; zMWni@ZB5bcPNjj+Da zIymzNvYr{0crD8K_R@uk+UrzWT18)iKIPm!*IM1#u0B`S_w@`7V|h6)TfDKnHL!90 zQba*h{N;6ITmbrlb%_G>T=aLHs(J;JV)d%w=mHYXA<`Au{+kG_m)#c&Hb2o=6E_{tU7$7db;VBkkbHlW>;$eE*B$G} z`odh6w073<<0TSh@Yyjv?wJDdr)W({A|fweM}?G&kVRz%<+t3=p0WoEE1CI%gk{xk zS{%c2fY##N6}wNlHXGwEOlCP&80A4w|3 z2k>o8j)%KbQD>TyOp`NB+%S9%?-n?_Q@~yG!77})v389sCE00WESeh^bN$W~^p=$v ze+#VlA@V8p)%PCtXE!2c=B<5o26QbAsefb(kOhBzFi%s^tE4-BBQrSX!VE_83t%6& z>0z|nulrc<8ad#$L&W9DMSl5oz$i%}gJZH`HdK_@XqV0I=Ih~pw*-}MaP^ef4N9V`w_9txqTuM>M zhO`Gp5F+1~k5X5*@MICr4C`B;?G$bt&XEMZ<(RNp1ulGxGB0^uivA%R=2`>mS-li#)S z&CyP?e4`wwQQUoN&5^VE==?Ni{c$Jt+Zpd*#uGv%CK5h_?#ClU5{RdXjlZ|CS!yi_YhSvBIWvzGf38l3{2{; zt3Q71u=()%jhP9#$rai|fUB2_fkzzuaq>m;HXoPC81Fp}?+rkB7}FXL-vrQ#0r?KR03p{ zxu_RPHumk_@#_tI@noA1j}QY1!is$X%}lXM{O$SdEzZk2N2HqyBqn~{RwYERtS2TG z=5rK_Q)FT#7HJja*Vh3@x}lC;C3E>gb8gKCECGgOiw$S$M_3!-d#*nKPYMd#Xk1(< zqUMDBr)H;K?@s@e8(iHWck6b`4@bh0gj)+%9N~7t6se6sJ3EP?FwQnuF&`%v!tDhB zAgkcxfjcdvzr|lA|oRM7KehNP!K@^2|1?mQs-J4=j4J!{sE77|BVF#A7CGp z3m76M4t8<^|5d}?L)D7_@|#2dQN!JcaLEHUz`8qox}mYEURb;b&tD-h=s)ybJlz~m z!@;1zSVycALDZdK74kQe>Y7NsKQvA#u){gIoN5us{+px+&h}5T{^r}s%4s-%b%db) z2kzgbe~`8jB2=8wo+s{Us>lIP>?1JFXdDLdYbcG85Qo@Efuzwg5+DhvBnl*B zgT;W*a5x+#DS?rZhDiMdN)zwyfx@G)Cr|`%F&qKM28*(R!C?>(R0a(LNl0TbAZckC zC`b|tk%HSwp|BV@>MszwZa6|!q8$I~)d>`a0ENOrq@if6BnT!UEk%HWNrF(~Xd4g; zDlI9F!osmqaG6sm3>u;4?B;|bq!Z_avcrO1@OGyQCxj!e=xNFUp3o}>jq z2!=o`>ZDEy0H+#+SP;r?Sd@pen~}4#qa5(WC9V_A)AHt${go6AoI63n_oU)~t9e7L z>#w(8Tfh-_y2QnGTDAxj`j-)Rlou9rYKWlsYYA=ipgq=aY)1#}t>m*6Rt zLVx$g+a7zulQ>iYBn}0MOBz9-2&fc793~r7~c$ZWLKRZg2Cz`kK z8nHUHwc4}SdyD$zn8MAu`uBTB>z_V-Qb%iloJ$eZ8T6$FVH%jI7XZB% z<%3HYhYe`)w-^K~8=8#J)ksfhP#mzpi=huA5hJHtMHr&3-RP+bjj5$)HiCY8E zd|5s43;eFFCyU4@koSIbp`wniZb04;cqIBw&t1sV!s-&VdEGlfy6oWr`(oILq4+j? z^L3$b8L3TmH34=}rVbs^JD~H;{hghfD~eUaI_V@!9tbI?>e8Ijdsxq&XJ?5JiX-~6QiJ2K0-qj=#nXga=)(OFY z0}0`&!+!OU0BRPO7sJ%V4o<~4NdgxZ7M!mM@aGW0nwG~)Xh7GM{W7f6*wD8CdRHxp zq)V(jAHRovnP;v}B7{7tO2$BNPi7|W)s_xckuhLzch_9#=<8Sdbt5tc0FBA^6I@%e z*6llYj@@&!1%UdcBL_&8WY3lt085A6FhQyIU?jA83Guqe%ETrm>~lRLIn^MLVR(GY z?M2jh34;!_*_`b{e_806Yb)Ky@flMNyL)^2DhZAd3;JZ+n*PMf_rg4RLviSf+x*%u d$L^r-0J=2sY1U6W_fM){Q&mT$M9Dhne*kRXJrn={ literal 0 HcmV?d00001 diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/wheel.png b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/wheel.png new file mode 100644 index 0000000000000000000000000000000000000000..07b1e33132e430476307b9d5f57d35b9da9f0097 GIT binary patch literal 1632 zcmV-m2A}zfP)92ut1VzFk$_)z#&eG=!_GtF`6j<#qh~zSU~2zr4KgTEpk0R5Zi;5%0L} za19oI4fJ6fr!CXFVZ*QMT4OAvf^@W|D z&ugRef;NuH?PFDGS0a3KbJGRU3sFiHWjO=)aqmOzzpk#Xe(!WT-zLiphr{2Vo}LoU z;+)O#s4KHGxeFQU{tnW2%JO=`*VorQ+|Ct6xtyf9F1NO}22umiqV=Vvr2|othi&&Z zHa7kc1yqD#uP4S{eHfw48Px1^tToh_&pxEzlK^pJ*C!G{kg!s+mr$*vnCs;vNE{O9 zfcJdmG?H!wzKE*zr>6*|da}8>`B@eKvof6e%3$C>_-xuq*o^9xxK*k0gb@SEe(kul zt?j5Ja43!yjV_cdK_dKadG)<*$d^r5eJf$wt;c)vj^H8?B26EG>Ti2DqtXGD85tYN zX0R{I;6L^xBC^VQOb0FtWt*N?iL@$gdxRUM_ZRw zC#t$+3)CTPB$(RX8DBg{PMDDkhtbnjtK>G$OSV8A(&+0K+jDL`$&vr(giUnOhOCM= z1+pBpxycqFX>_!!EswtT#i7=?a*l;cZ#&xPixPAKBqG@YSSBw_+ghZKc5;&~2zMQo zFGYcX$1^Y1*mecdUmedA{wWAsI|`flCIK`|wt$*6`rLQC`d6iC)V2~K`&|&(0xHs; z6(!-H7H2Os^j&@eK>EK@!i$b8|1cnG`b%4WGW<{YzYY>^<$ZFF3O`1`>xHK~aF&HH-s``*cqOn#c$3xikCb%1|hC znj-9r?fQ-&%b>ksRNoo9&b0L~uskd3v2K;%q36UT1E;BFbLRBW6Tw&KQIr8!ZyO`c z44^}qRl7Vlgv&;qBp6@*iS5M1c3iq<(i{?7BXy5L2**)Qt_@NHfs_nuyEEHEE>XTE z1~cJV#jt53FdLT(*L##?@B9Z z63hnlnVh`N@Xn>tN!X}1^C+AyBU6ZAm!}%XBnCLZ&^%vQcx3WVoPG9&cqWoZd^qHY z*E!Nop%a5nr!($^W?8E7GXkpbo^}ma6E>X*&5kx?X7hdLaXjceted@TB6?KL8LLE? z&?b5=0IAtFR@#SGCR_l-dxm%-i$!LL2Dgkh)Fw{d%h`K*CC_Z3q*RO&%y7@RABLv% e%RdB(iGKhQFK?{O$+Euy0000 +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#endif + +namespace autoware_mission_details_overlay_rviz_plugin +{ +class MissionDetailsDisplay : public rviz_common::Display +{ + Q_OBJECT +public: + MissionDetailsDisplay(); + ~MissionDetailsDisplay() override; + +protected: + void onInitialize() override; + void update(float wall_dt, float ros_dt) override; + void reset() override; + void onEnable() override; + void onDisable() override; + +private Q_SLOTS: + void updateOverlaySize(); + void updateSmallOverlaySize(); + void updateOverlayPosition(); + void updateOverlayColor(); + void topic_updated_remaining_distance_time(); + +private: + std::mutex mutex_; + autoware_mission_details_overlay_rviz_plugin::OverlayObject::SharedPtr overlay_; + rviz_common::properties::IntProperty * property_width_; + rviz_common::properties::IntProperty * property_height_; + rviz_common::properties::IntProperty * property_left_; + rviz_common::properties::IntProperty * property_top_; + std::unique_ptr remaining_distance_time_topic_property_; + + void drawHorizontalRoundedRectangle(QPainter & painter, const QRectF & backgroundRect); + void drawVerticalRoundedRectangle(QPainter & painter, const QRectF & backgroundRect); + void setupRosSubscriptions(); + + std::unique_ptr remaining_distance_time_display_; + + rclcpp::Subscription::SharedPtr remaining_distance_time_sub_; + + std::mutex property_mutex_; + + void updateRemainingDistanceTimeData(const autoware_planning_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); + void drawWidget(QImage & hud); +}; +} // namespace autoware_mission_details_overlay_rviz_plugin + +#endif // SIGNAL_DISPLAY_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp new file mode 100644 index 0000000000000..822a1e2bbc18d --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp @@ -0,0 +1,157 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// -*- mode: c++; -*- +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Team Spatzenhirn + * Copyright (c) 2014, JSK Lab + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/o2r other materials provided + * with the distribution. + * * Neither the name of the JSK Lab nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ +#ifndef OVERLAY_TEXT_DISPLAY_HPP_ +#define OVERLAY_TEXT_DISPLAY_HPP_ + +#include "autoware_overlay_msgs/msg/overlay_text.hpp" +#ifndef Q_MOC_RUN +#include "overlay_utils.hpp" + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#endif + +namespace autoware_mission_details_overlay_rviz_plugin +{ +class OverlayTextDisplay +: public rviz_common::RosTopicDisplay +{ + Q_OBJECT +public: + OverlayTextDisplay(); + virtual ~OverlayTextDisplay(); + +protected: + autoware_mission_details_overlay_rviz_plugin::OverlayObject::SharedPtr overlay_; + + int texture_width_; + int texture_height_; + + bool overtake_fg_color_properties_; + bool overtake_bg_color_properties_; + bool overtake_position_properties_; + bool align_bottom_; + bool invert_shadow_; + QColor bg_color_; + QColor fg_color_; + int text_size_; + int line_width_; + std::string text_; + QStringList font_families_; + std::string font_; + int horizontal_dist_; + int vertical_dist_; + HorizontalAlignment horizontal_alignment_; + VerticalAlignment vertical_alignment_; + + void onInitialize() override; + void onEnable() override; + void onDisable() override; + void update(float wall_dt, float ros_dt) override; + void reset() override; + + bool require_update_texture_; + // properties are raw pointers since they are owned by Qt + rviz_common::properties::BoolProperty * overtake_position_properties_property_; + rviz_common::properties::BoolProperty * overtake_fg_color_properties_property_; + rviz_common::properties::BoolProperty * overtake_bg_color_properties_property_; + rviz_common::properties::BoolProperty * align_bottom_property_; + rviz_common::properties::BoolProperty * invert_shadow_property_; + rviz_common::properties::IntProperty * hor_dist_property_; + rviz_common::properties::IntProperty * ver_dist_property_; + rviz_common::properties::EnumProperty * hor_alignment_property_; + rviz_common::properties::EnumProperty * ver_alignment_property_; + rviz_common::properties::IntProperty * width_property_; + rviz_common::properties::IntProperty * height_property_; + rviz_common::properties::IntProperty * text_size_property_; + rviz_common::properties::IntProperty * line_width_property_; + rviz_common::properties::ColorProperty * bg_color_property_; + rviz_common::properties::FloatProperty * bg_alpha_property_; + rviz_common::properties::ColorProperty * fg_color_property_; + rviz_common::properties::FloatProperty * fg_alpha_property_; + rviz_common::properties::EnumProperty * font_property_; + +protected Q_SLOTS: + void updateOvertakePositionProperties(); + void updateOvertakeFGColorProperties(); + void updateOvertakeBGColorProperties(); + void updateAlignBottom(); + void updateInvertShadow(); + void updateHorizontalDistance(); + void updateVerticalDistance(); + void updateHorizontalAlignment(); + void updateVerticalAlignment(); + void updateWidth(); + void updateHeight(); + void updateTextSize(); + void updateFGColor(); + void updateFGAlpha(); + void updateBGColor(); + void updateBGAlpha(); + void updateFont(); + void updateLineWidth(); + +private: + void processMessage(autoware_overlay_msgs::msg::OverlayText::ConstSharedPtr msg) override; +}; +} // namespace autoware_mission_details_overlay_rviz_plugin + +#endif // OVERLAY_TEXT_DISPLAY_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp new file mode 100644 index 0000000000000..4d27655dd33b7 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp @@ -0,0 +1,141 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// -*- mode: c++ -*- +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Team Spatzenhirn + * Copyright (c) 2014, JSK Lab + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/o2r other materials provided + * with the distribution. + * * Neither the name of the JSK Lab nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +#ifndef OVERLAY_UTILS_HPP_ +#define OVERLAY_UTILS_HPP_ + +#include +#include + +#include "autoware_overlay_msgs/msg/overlay_text.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +namespace autoware_mission_details_overlay_rviz_plugin +{ +class OverlayObject; + +class ScopedPixelBuffer +{ +public: + explicit ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr pixel_buffer); + virtual ~ScopedPixelBuffer(); + virtual Ogre::HardwarePixelBufferSharedPtr getPixelBuffer(); + virtual QImage getQImage(unsigned int width, unsigned int height); + virtual QImage getQImage(OverlayObject & overlay); + virtual QImage getQImage(unsigned int width, unsigned int height, QColor & bg_color); + virtual QImage getQImage(OverlayObject & overlay, QColor & bg_color); + +protected: + Ogre::HardwarePixelBufferSharedPtr pixel_buffer_; +}; + +enum class VerticalAlignment : uint8_t { + CENTER = autoware_overlay_msgs::msg::OverlayText::CENTER, + TOP = autoware_overlay_msgs::msg::OverlayText::TOP, + BOTTOM = autoware_overlay_msgs::msg::OverlayText::BOTTOM, +}; + +enum class HorizontalAlignment : uint8_t { + LEFT = autoware_overlay_msgs::msg::OverlayText::LEFT, + RIGHT = autoware_overlay_msgs::msg::OverlayText::RIGHT, + CENTER = autoware_overlay_msgs::msg::OverlayText::CENTER +}; + +/** + * Helper class for realizing an overlay object on top of the rviz 3D panel. + * + * This class is supposed to be instantiated in the onInitialize method of the + * rviz_common::Display class. + */ +class OverlayObject +{ +public: + using SharedPtr = std::shared_ptr; + + explicit OverlayObject(const std::string & name); + virtual ~OverlayObject(); + + virtual std::string getName() const; + virtual void hide(); + virtual void show(); + virtual bool isTextureReady() const; + virtual void updateTextureSize(unsigned int width, unsigned int height); + virtual ScopedPixelBuffer getBuffer(); + virtual void setPosition( + double hor_dist, double ver_dist, HorizontalAlignment hor_alignment = HorizontalAlignment::LEFT, + VerticalAlignment ver_alignment = VerticalAlignment::TOP); + virtual void setDimensions(double width, double height); + virtual bool isVisible() const; + virtual unsigned int getTextureWidth() const; + virtual unsigned int getTextureHeight() const; + +protected: + const std::string name_; + Ogre::Overlay * overlay_; + Ogre::PanelOverlayElement * panel_; + Ogre::MaterialPtr panel_material_; + Ogre::TexturePtr texture_; +}; +} // namespace autoware_mission_details_overlay_rviz_plugin + +#endif // OVERLAY_UTILS_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp new file mode 100644 index 0000000000000..6ccc319aad158 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp @@ -0,0 +1,52 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef REMAINING_DISTANCE_TIME_HPP_ +#define REMAINING_DISTANCE_TIME_HPP_ +#include "overlay_utils.hpp" + +#include +#include +#include +#include +#include +#include + +#include "autoware_planning_msgs/msg/mission_remaining_distance_time.hpp" + +#include +#include +#include + +namespace autoware_mission_details_overlay_rviz_plugin +{ + +class RemainingDistanceTimeDisplay +{ +public: + RemainingDistanceTimeDisplay(); + void drawRemainingDistanceTimeDisplay(QPainter & painter, const QRectF & backgroundRect); + void updateRemainingDistanceTimeData(const autoware_planning_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); + +private: + double remaining_distance_; // Internal variable to store remaining distance + uint32_t hours_; // Internal variable to store remaining time hours + uint32_t minutes_; // Internal variable to store remaining time minutes + uint32_t seconds_; // Internal variable to store remaining time seconds + QColor gray = QColor(194, 194, 194); +}; + +} // namespace autoware_mission_details_overlay_rviz_plugin + +#endif // REMAINING_DISTANCE_TIME_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml new file mode 100644 index 0000000000000..4b072b6379e5b --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml @@ -0,0 +1,32 @@ + + + + autoware_mission_details_overlay_rviz_plugin + 0.0.1 + + RViz2 plugin for 2D overlays for mission details in the 3D view. Mainly a port of the JSK overlay plugin + (https://github.com/jsk-ros-pkg/jsk_visualization). + + Ahmed Ebrahim + + BSD-3-Clause + + autoware_auto_vehicle_msgs + autoware_overlay_msgs + autoware_perception_msgs + autoware_planning_msgs + boost + rviz_common + rviz_ogre_vendor + rviz_rendering + tier4_planning_msgs + + ament_lint_auto + autoware_lint_common + + ament_cmake_auto + + + ament_cmake + + diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml new file mode 100644 index 0000000000000..2d9e96dbb285f --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml @@ -0,0 +1,5 @@ + + + Mission Details overlay plugin for the 3D view. + + diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp new file mode 100644 index 0000000000000..b9be347561cd7 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -0,0 +1,237 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "mission_details_display.hpp" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +namespace autoware_mission_details_overlay_rviz_plugin +{ + +MissionDetailsDisplay::MissionDetailsDisplay() +{ + property_width_ = new rviz_common::properties::IntProperty( + "Width", 300, "Width of the overlay", this, SLOT(updateOverlaySize())); + property_height_ = new rviz_common::properties::IntProperty( + "Height", 100, "Height of the overlay", this, SLOT(updateOverlaySize())); + property_left_ = new rviz_common::properties::IntProperty( + "Left", 10, "Left position of the overlay", this, SLOT(updateOverlayPosition())); + property_top_ = new rviz_common::properties::IntProperty( + "Top", 10, "Top position of the overlay", this, SLOT(updateOverlayPosition())); + + // Initialize the component displays + remaining_distance_time_display_ = std::make_unique(); +} + +void MissionDetailsDisplay::onInitialize() +{ + std::lock_guard lock(property_mutex_); + + rviz_common::Display::onInitialize(); + rviz_rendering::RenderSystem::get()->prepareOverlays(scene_manager_); + static int count = 0; + std::stringstream ss; + ss << "MissionDetailsDisplay" << count++; + overlay_.reset(new autoware_mission_details_overlay_rviz_plugin::OverlayObject(ss.str())); + overlay_->show(); + updateOverlaySize(); + updateOverlayPosition(); + + auto rviz_ros_node = context_->getRosNodeAbstraction(); + + remaining_distance_time_topic_property_ = std::make_unique( + "Remaining Distance and Time Topic", "/planning/mission_remaining_distance_time", + "autoware_planning_msgs/msg/MissionRemainingDistanceTime", "Topic for Mission Remaining Distance and Time Data", this, + SLOT(topic_updated_remaining_distance_time())); + remaining_distance_time_topic_property_->initialize(rviz_ros_node); +} + +void MissionDetailsDisplay::setupRosSubscriptions() +{ + // Don't create a node, just use the one from the parent class + auto rviz_node_ = context_->getRosNodeAbstraction().lock()->get_raw_node(); + + remaining_distance_time_sub_ = rviz_node_->create_subscription( + "/planning/mission_remaining_distance_time", + rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + [this](const autoware_planning_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { + updateRemainingDistanceTimeData(msg); + }); +} + +MissionDetailsDisplay::~MissionDetailsDisplay() +{ + std::lock_guard lock(property_mutex_); + overlay_.reset(); + + remaining_distance_time_sub_.reset(); + + remaining_distance_time_display_.reset(); + + remaining_distance_time_topic_property_.reset(); +} + +void MissionDetailsDisplay::update(float /* wall_dt */, float /* ros_dt */) +{ + if (!overlay_) { + return; + } + autoware_mission_details_overlay_rviz_plugin::ScopedPixelBuffer buffer = overlay_->getBuffer(); + QImage hud = buffer.getQImage(*overlay_); + hud.fill(Qt::transparent); + drawWidget(hud); +} + +void MissionDetailsDisplay::onEnable() +{ + std::lock_guard lock(property_mutex_); + if (overlay_) { + overlay_->show(); + } + setupRosSubscriptions(); +} + +void MissionDetailsDisplay::onDisable() +{ + std::lock_guard lock(property_mutex_); + + remaining_distance_time_sub_.reset(); + + if (overlay_) { + overlay_->hide(); + } +} + +void MissionDetailsDisplay::updateRemainingDistanceTimeData( + const autoware_planning_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg) +{ + std::lock_guard lock(property_mutex_); + + if (remaining_distance_time_display_) { + remaining_distance_time_display_->updateRemainingDistanceTimeData(msg); + queueRender(); + } +} + +void MissionDetailsDisplay::drawWidget(QImage & hud) +{ + std::lock_guard lock(property_mutex_); + + if (!overlay_->isVisible()) { + return; + } + + QPainter painter(&hud); + painter.setRenderHint(QPainter::Antialiasing, true); + + QRectF backgroundRect(0, 0, 300, 100); + drawHorizontalRoundedRectangle(painter, backgroundRect); + + if (remaining_distance_time_display_) { + remaining_distance_time_display_->drawRemainingDistanceTimeDisplay(painter, backgroundRect); + } + + painter.end(); +} + +void MissionDetailsDisplay::drawHorizontalRoundedRectangle( + QPainter & painter, const QRectF & backgroundRect) +{ + painter.setRenderHint(QPainter::Antialiasing, true); + QColor colorFromHSV; + colorFromHSV.setHsv(0, 0, 0); // Hue, Saturation, Value + colorFromHSV.setAlphaF(0.65); // Transparency + + painter.setBrush(colorFromHSV); + + painter.setPen(Qt::NoPen); + painter.drawRoundedRect( + backgroundRect, backgroundRect.height() / 2, backgroundRect.height() / 2); // Circular ends +} +void MissionDetailsDisplay::drawVerticalRoundedRectangle(QPainter & painter, const QRectF & backgroundRect) +{ + painter.setRenderHint(QPainter::Antialiasing, true); + QColor colorFromHSV; + colorFromHSV.setHsv(0, 0, 0); // Hue, Saturation, Value + colorFromHSV.setAlphaF(0.65); // Transparency + + painter.setBrush(colorFromHSV); + + painter.setPen(Qt::NoPen); + painter.drawRoundedRect( + backgroundRect, backgroundRect.width() / 2, backgroundRect.width() / 2); // Circular ends +} + +void MissionDetailsDisplay::reset() +{ + rviz_common::Display::reset(); + overlay_->hide(); +} + +void MissionDetailsDisplay::updateOverlaySize() +{ + std::lock_guard lock(mutex_); + overlay_->updateTextureSize(property_width_->getInt(), property_height_->getInt()); + overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); + queueRender(); +} + +void MissionDetailsDisplay::updateOverlayPosition() +{ + std::lock_guard lock(mutex_); + overlay_->setPosition(property_left_->getInt(), property_top_->getInt()); + queueRender(); +} + +void MissionDetailsDisplay::updateOverlayColor() +{ + std::lock_guard lock(mutex_); + queueRender(); +} + +void MissionDetailsDisplay::topic_updated_remaining_distance_time() +{ + // resubscribe to the topic + remaining_distance_time_sub_.reset(); + auto rviz_ros_node = context_->getRosNodeAbstraction().lock(); + remaining_distance_time_sub_ = rviz_ros_node->get_raw_node() + ->create_subscription( + remaining_distance_time_topic_property_->getTopicStd(), + rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + [this](const autoware_planning_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { + updateRemainingDistanceTimeData(msg); + }); +} + +} // namespace autoware_mission_details_overlay_rviz_plugin + +#include +PLUGINLIB_EXPORT_CLASS(autoware_mission_details_overlay_rviz_plugin::MissionDetailsDisplay, rviz_common::Display) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp new file mode 100644 index 0000000000000..88c30a2d1ec71 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp @@ -0,0 +1,556 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// -*- mode: c++; -*- +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Team Spatzenhirn + * Copyright (c) 2014, JSK Lab + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/o2r other materials provided + * with the distribution. + * * Neither the name of the JSK Lab nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +#include "overlay_text_display.hpp" + +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include +#include + +namespace autoware_mission_details_overlay_rviz_plugin +{ +OverlayTextDisplay::OverlayTextDisplay() +: texture_width_(0), + texture_height_(0), + bg_color_(0, 0, 0, 0), + fg_color_(255, 255, 255, 255.0), + text_size_(14), + line_width_(2), + text_(""), + font_(""), + require_update_texture_(false) +{ + overtake_position_properties_property_ = new rviz_common::properties::BoolProperty( + "Overtake Position Properties", false, + "overtake position properties specified by message such as left, top and font", this, + SLOT(updateOvertakePositionProperties())); + overtake_fg_color_properties_property_ = new rviz_common::properties::BoolProperty( + "Overtake FG Color Properties", false, + "overtake color properties specified by message such as foreground color and alpha", this, + SLOT(updateOvertakeFGColorProperties())); + overtake_bg_color_properties_property_ = new rviz_common::properties::BoolProperty( + "Overtake BG Color Properties", false, + "overtake color properties specified by message such as background color and alpha", this, + SLOT(updateOvertakeBGColorProperties())); + align_bottom_property_ = new rviz_common::properties::BoolProperty( + "Align Bottom", false, "align text with the bottom of the overlay region", this, + SLOT(updateAlignBottom())); + invert_shadow_property_ = new rviz_common::properties::BoolProperty( + "Invert Shadow", false, "make shadow lighter than original text", this, + SLOT(updateInvertShadow())); + hor_dist_property_ = new rviz_common::properties::IntProperty( + "hor_dist", 0, "horizontal distance to anchor", this, SLOT(updateHorizontalDistance())); + ver_dist_property_ = new rviz_common::properties::IntProperty( + "ver_dist", 0, "vertical distance to anchor", this, SLOT(updateVerticalDistance())); + hor_alignment_property_ = new rviz_common::properties::EnumProperty( + "hor_alignment", "left", "horizontal alignment of the overlay", this, + SLOT(updateHorizontalAlignment())); + hor_alignment_property_->addOption("left", autoware_overlay_msgs::msg::OverlayText::LEFT); + hor_alignment_property_->addOption("center", autoware_overlay_msgs::msg::OverlayText::CENTER); + hor_alignment_property_->addOption("right", autoware_overlay_msgs::msg::OverlayText::RIGHT); + ver_alignment_property_ = new rviz_common::properties::EnumProperty( + "ver_alignment", "top", "vertical alignment of the overlay", this, + SLOT(updateVerticalAlignment())); + ver_alignment_property_->addOption("top", autoware_overlay_msgs::msg::OverlayText::TOP); + ver_alignment_property_->addOption("center", autoware_overlay_msgs::msg::OverlayText::CENTER); + ver_alignment_property_->addOption("bottom", autoware_overlay_msgs::msg::OverlayText::BOTTOM); + width_property_ = new rviz_common::properties::IntProperty( + "width", 128, "width position", this, SLOT(updateWidth())); + width_property_->setMin(0); + height_property_ = new rviz_common::properties::IntProperty( + "height", 128, "height position", this, SLOT(updateHeight())); + height_property_->setMin(0); + text_size_property_ = new rviz_common::properties::IntProperty( + "text size", 12, "text size", this, SLOT(updateTextSize())); + text_size_property_->setMin(0); + line_width_property_ = new rviz_common::properties::IntProperty( + "line width", 2, "line width", this, SLOT(updateLineWidth())); + line_width_property_->setMin(0); + fg_color_property_ = new rviz_common::properties::ColorProperty( + "Foreground Color", QColor(25, 255, 240), "Foreground Color", this, SLOT(updateFGColor())); + fg_alpha_property_ = new rviz_common::properties::FloatProperty( + "Foreground Alpha", 0.8, "Foreground Alpha", this, SLOT(updateFGAlpha())); + fg_alpha_property_->setMin(0.0); + fg_alpha_property_->setMax(1.0); + bg_color_property_ = new rviz_common::properties::ColorProperty( + "Background Color", QColor(0, 0, 0), "Background Color", this, SLOT(updateBGColor())); + bg_alpha_property_ = new rviz_common::properties::FloatProperty( + "Background Alpha", 0.8, "Background Alpha", this, SLOT(updateBGAlpha())); + bg_alpha_property_->setMin(0.0); + bg_alpha_property_->setMax(1.0); + + QFontDatabase database; + font_families_ = database.families(); + font_property_ = new rviz_common::properties::EnumProperty( + "font", "DejaVu Sans Mono", "font", this, SLOT(updateFont())); + for (ssize_t i = 0; i < font_families_.size(); i++) { + font_property_->addOption(font_families_[i], static_cast(i)); + } +} + +OverlayTextDisplay::~OverlayTextDisplay() +{ + onDisable(); +} + +void OverlayTextDisplay::onEnable() +{ + if (overlay_) { + overlay_->show(); + } + subscribe(); +} + +void OverlayTextDisplay::onDisable() +{ + if (overlay_) { + overlay_->hide(); + } + unsubscribe(); +} + +// only the first time +void OverlayTextDisplay::onInitialize() +{ + RTDClass::onInitialize(); + rviz_rendering::RenderSystem::get()->prepareOverlays(scene_manager_); + + onEnable(); + updateTopic(); + updateOvertakePositionProperties(); + updateOvertakeFGColorProperties(); + updateOvertakeBGColorProperties(); + updateAlignBottom(); + updateInvertShadow(); + updateHorizontalDistance(); + updateVerticalDistance(); + updateHorizontalAlignment(); + updateVerticalAlignment(); + updateWidth(); + updateHeight(); + updateTextSize(); + updateFGColor(); + updateFGAlpha(); + updateBGColor(); + updateBGAlpha(); + updateFont(); + updateLineWidth(); + require_update_texture_ = true; +} + +void OverlayTextDisplay::update(float /*wall_dt*/, float /*ros_dt*/) +{ + if (!require_update_texture_) { + return; + } + if (!isEnabled()) { + return; + } + if (!overlay_) { + return; + } + + overlay_->updateTextureSize(texture_width_, texture_height_); + { + autoware_mission_details_overlay_rviz_plugin::ScopedPixelBuffer buffer = overlay_->getBuffer(); + QImage Hud = buffer.getQImage(*overlay_, bg_color_); + QPainter painter(&Hud); + painter.setRenderHint(QPainter::Antialiasing, true); + painter.setPen(QPen(fg_color_, std::max(line_width_, 1), Qt::SolidLine)); + uint16_t w = overlay_->getTextureWidth(); + uint16_t h = overlay_->getTextureHeight(); + + // font + if (text_size_ != 0) { + // QFont font = painter.font(); + QFont font(font_.length() > 0 ? font_.c_str() : "Liberation Sans"); + font.setPointSize(text_size_); + font.setBold(true); + painter.setFont(font); + } + if (text_.length() > 0) { + QColor shadow_color; + if (invert_shadow_) + shadow_color = Qt::white; // fg_color_.lighter(); + else + shadow_color = Qt::black; // fg_color_.darker(); + shadow_color.setAlpha(fg_color_.alpha()); + + std::string color_wrapped_text = + (boost::format("%1%") % text_ % + fg_color_.red() % fg_color_.green() % fg_color_.blue() % fg_color_.alpha()) + .str(); + + // find a remove "color: XXX;" regex match to generate a proper shadow + std::regex color_tag_re("color:.+?;"); + std::string null_char(""); + std::string formatted_text_ = std::regex_replace(text_, color_tag_re, null_char); + std::string color_wrapped_shadow = + (boost::format("%1%") % + formatted_text_ % shadow_color.red() % shadow_color.green() % shadow_color.blue() % + shadow_color.alpha()) + .str(); + + QStaticText static_text( + boost::algorithm::replace_all_copy(color_wrapped_text, "\n", "
").c_str()); + static_text.setTextWidth(w); + + painter.setPen(QPen(shadow_color, std::max(line_width_, 1), Qt::SolidLine)); + QStaticText static_shadow( + boost::algorithm::replace_all_copy(color_wrapped_shadow, "\n", "
").c_str()); + static_shadow.setTextWidth(w); + + if (!align_bottom_) { + painter.drawStaticText(1, 1, static_shadow); + painter.drawStaticText(0, 0, static_text); + } else { + QStaticText only_wrapped_text(color_wrapped_text.c_str()); + QFontMetrics fm(painter.fontMetrics()); + QRect text_rect = fm.boundingRect( + 0, 0, w, h, Qt::TextWordWrap | Qt::AlignLeft | Qt::AlignTop, + only_wrapped_text.text().remove(QRegExp("<[^>]*>"))); + painter.drawStaticText(1, h - text_rect.height() + 1, static_shadow); + painter.drawStaticText(0, h - text_rect.height(), static_text); + } + } + painter.end(); + } + overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); + require_update_texture_ = false; +} + +void OverlayTextDisplay::reset() +{ + RTDClass::reset(); + + if (overlay_) { + overlay_->hide(); + } +} + +void OverlayTextDisplay::processMessage(autoware_overlay_msgs::msg::OverlayText::ConstSharedPtr msg) +{ + if (!isEnabled()) { + return; + } + if (!overlay_) { + static int count = 0; + std::stringstream ss; + ss << "OverlayTextDisplayObject" << count++; + overlay_.reset(new autoware_mission_details_overlay_rviz_plugin::OverlayObject(ss.str())); + overlay_->show(); + } + if (overlay_) { + if (msg->action == autoware_overlay_msgs::msg::OverlayText::DELETE) { + overlay_->hide(); + } else if (msg->action == autoware_overlay_msgs::msg::OverlayText::ADD) { + overlay_->show(); + } + } + + // store message for update method + text_ = msg->text; + + if (!overtake_position_properties_) { + texture_width_ = msg->width; + texture_height_ = msg->height; + text_size_ = msg->text_size; + horizontal_dist_ = msg->horizontal_distance; + vertical_dist_ = msg->vertical_distance; + + horizontal_alignment_ = HorizontalAlignment{msg->horizontal_alignment}; + vertical_alignment_ = VerticalAlignment{msg->vertical_alignment}; + } + if (!overtake_bg_color_properties_) + bg_color_ = QColor( + msg->bg_color.r * 255.0, msg->bg_color.g * 255.0, msg->bg_color.b * 255.0, + msg->bg_color.a * 255.0); + if (!overtake_fg_color_properties_) { + fg_color_ = QColor( + msg->fg_color.r * 255.0, msg->fg_color.g * 255.0, msg->fg_color.b * 255.0, + msg->fg_color.a * 255.0); + font_ = msg->font; + line_width_ = msg->line_width; + } + if (overlay_) { + overlay_->setPosition( + horizontal_dist_, vertical_dist_, horizontal_alignment_, vertical_alignment_); + } + require_update_texture_ = true; +} + +void OverlayTextDisplay::updateOvertakePositionProperties() +{ + if (!overtake_position_properties_ && overtake_position_properties_property_->getBool()) { + updateVerticalDistance(); + updateHorizontalDistance(); + updateVerticalAlignment(); + updateHorizontalAlignment(); + updateWidth(); + updateHeight(); + updateTextSize(); + require_update_texture_ = true; + } + + overtake_position_properties_ = overtake_position_properties_property_->getBool(); + if (overtake_position_properties_) { + hor_dist_property_->show(); + ver_dist_property_->show(); + hor_alignment_property_->show(); + ver_alignment_property_->show(); + width_property_->show(); + height_property_->show(); + text_size_property_->show(); + } else { + hor_dist_property_->hide(); + ver_dist_property_->hide(); + hor_alignment_property_->hide(); + ver_alignment_property_->hide(); + width_property_->hide(); + height_property_->hide(); + text_size_property_->hide(); + } +} + +void OverlayTextDisplay::updateOvertakeFGColorProperties() +{ + if (!overtake_fg_color_properties_ && overtake_fg_color_properties_property_->getBool()) { + // read all the parameters from properties + updateFGColor(); + updateFGAlpha(); + updateFont(); + updateLineWidth(); + require_update_texture_ = true; + } + overtake_fg_color_properties_ = overtake_fg_color_properties_property_->getBool(); + if (overtake_fg_color_properties_) { + fg_color_property_->show(); + fg_alpha_property_->show(); + line_width_property_->show(); + font_property_->show(); + } else { + fg_color_property_->hide(); + fg_alpha_property_->hide(); + line_width_property_->hide(); + font_property_->hide(); + } +} + +void OverlayTextDisplay::updateOvertakeBGColorProperties() +{ + if (!overtake_bg_color_properties_ && overtake_bg_color_properties_property_->getBool()) { + // read all the parameters from properties + updateBGColor(); + updateBGAlpha(); + require_update_texture_ = true; + } + overtake_bg_color_properties_ = overtake_bg_color_properties_property_->getBool(); + if (overtake_bg_color_properties_) { + bg_color_property_->show(); + bg_alpha_property_->show(); + } else { + bg_color_property_->hide(); + bg_alpha_property_->hide(); + } +} + +void OverlayTextDisplay::updateAlignBottom() +{ + if (align_bottom_ != align_bottom_property_->getBool()) { + require_update_texture_ = true; + } + align_bottom_ = align_bottom_property_->getBool(); +} + +void OverlayTextDisplay::updateInvertShadow() +{ + if (invert_shadow_ != invert_shadow_property_->getBool()) { + require_update_texture_ = true; + } + invert_shadow_ = invert_shadow_property_->getBool(); +} + +void OverlayTextDisplay::updateVerticalDistance() +{ + vertical_dist_ = ver_dist_property_->getInt(); + if (overtake_position_properties_) { + require_update_texture_ = true; + } +} + +void OverlayTextDisplay::updateHorizontalDistance() +{ + horizontal_dist_ = hor_dist_property_->getInt(); + if (overtake_position_properties_) { + require_update_texture_ = true; + } +} + +void OverlayTextDisplay::updateVerticalAlignment() +{ + vertical_alignment_ = + VerticalAlignment{static_cast(ver_alignment_property_->getOptionInt())}; + + if (overtake_position_properties_) { + require_update_texture_ = true; + } +} + +void OverlayTextDisplay::updateHorizontalAlignment() +{ + horizontal_alignment_ = + HorizontalAlignment{static_cast(hor_alignment_property_->getOptionInt())}; + + if (overtake_position_properties_) { + require_update_texture_ = true; + } +} + +void OverlayTextDisplay::updateWidth() +{ + texture_width_ = width_property_->getInt(); + if (overtake_position_properties_) { + require_update_texture_ = true; + } +} + +void OverlayTextDisplay::updateHeight() +{ + texture_height_ = height_property_->getInt(); + if (overtake_position_properties_) { + require_update_texture_ = true; + } +} + +void OverlayTextDisplay::updateTextSize() +{ + text_size_ = text_size_property_->getInt(); + if (overtake_position_properties_) { + require_update_texture_ = true; + } +} + +void OverlayTextDisplay::updateBGColor() +{ + QColor c = bg_color_property_->getColor(); + bg_color_.setRed(c.red()); + bg_color_.setGreen(c.green()); + bg_color_.setBlue(c.blue()); + if (overtake_bg_color_properties_) { + require_update_texture_ = true; + } +} + +void OverlayTextDisplay::updateBGAlpha() +{ + bg_color_.setAlpha(bg_alpha_property_->getFloat() * 255.0); + if (overtake_bg_color_properties_) { + require_update_texture_ = true; + } +} + +void OverlayTextDisplay::updateFGColor() +{ + QColor c = fg_color_property_->getColor(); + fg_color_.setRed(c.red()); + fg_color_.setGreen(c.green()); + fg_color_.setBlue(c.blue()); + if (overtake_fg_color_properties_) { + require_update_texture_ = true; + } +} + +void OverlayTextDisplay::updateFGAlpha() +{ + fg_color_.setAlpha(fg_alpha_property_->getFloat() * 255.0); + if (overtake_fg_color_properties_) { + require_update_texture_ = true; + } +} + +void OverlayTextDisplay::updateFont() +{ + int font_index = font_property_->getOptionInt(); + if (font_index < font_families_.size()) { + font_ = font_families_[font_index].toStdString(); + } else { + RVIZ_COMMON_LOG_ERROR_STREAM("Unexpected error at selecting font index " << font_index); + return; + } + if (overtake_fg_color_properties_) { + require_update_texture_ = true; + } +} + +void OverlayTextDisplay::updateLineWidth() +{ + line_width_ = line_width_property_->getInt(); + if (overtake_fg_color_properties_) { + require_update_texture_ = true; + } +} + +} // namespace autoware_mission_details_overlay_rviz_plugin + +#include +PLUGINLIB_EXPORT_CLASS(autoware_mission_details_overlay_rviz_plugin::OverlayTextDisplay, rviz_common::Display) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp new file mode 100644 index 0000000000000..68c4277e5d677 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp @@ -0,0 +1,267 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// -*- mode: c++ -*- +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Team Spatzenhirn + * Copyright (c) 2014, JSK Lab + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/o2r other materials provided + * with the distribution. + * * Neither the name of the JSK Lab nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +#include "overlay_utils.hpp" + +#include + +namespace autoware_mission_details_overlay_rviz_plugin +{ +ScopedPixelBuffer::ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr pixel_buffer) +: pixel_buffer_(pixel_buffer) +{ + pixel_buffer_->lock(Ogre::HardwareBuffer::HBL_NORMAL); +} + +ScopedPixelBuffer::~ScopedPixelBuffer() +{ + pixel_buffer_->unlock(); +} + +Ogre::HardwarePixelBufferSharedPtr ScopedPixelBuffer::getPixelBuffer() +{ + return pixel_buffer_; +} + +QImage ScopedPixelBuffer::getQImage(unsigned int width, unsigned int height) +{ + const Ogre::PixelBox & pixelBox = pixel_buffer_->getCurrentLock(); + Ogre::uint8 * pDest = static_cast(pixelBox.data); + memset(pDest, 0, width * height); + return QImage(pDest, width, height, QImage::Format_ARGB32); +} + +QImage ScopedPixelBuffer::getQImage(unsigned int width, unsigned int height, QColor & bg_color) +{ + QImage Hud = getQImage(width, height); + for (unsigned int i = 0; i < width; i++) { + for (unsigned int j = 0; j < height; j++) { + Hud.setPixel(i, j, bg_color.rgba()); + } + } + return Hud; +} + +QImage ScopedPixelBuffer::getQImage(OverlayObject & overlay) +{ + return getQImage(overlay.getTextureWidth(), overlay.getTextureHeight()); +} + +QImage ScopedPixelBuffer::getQImage(OverlayObject & overlay, QColor & bg_color) +{ + return getQImage(overlay.getTextureWidth(), overlay.getTextureHeight(), bg_color); +} + +OverlayObject::OverlayObject(const std::string & name) : name_(name) +{ + std::string material_name = name_ + "Material"; + Ogre::OverlayManager * mOverlayMgr = Ogre::OverlayManager::getSingletonPtr(); + overlay_ = mOverlayMgr->create(name_); + panel_ = static_cast( + mOverlayMgr->createOverlayElement("Panel", name_ + "Panel")); + panel_->setMetricsMode(Ogre::GMM_PIXELS); + + panel_material_ = Ogre::MaterialManager::getSingleton().create( + material_name, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME); + panel_->setMaterialName(panel_material_->getName()); + overlay_->add2D(panel_); +} + +OverlayObject::~OverlayObject() +{ + Ogre::OverlayManager * mOverlayMgr = Ogre::OverlayManager::getSingletonPtr(); + if (mOverlayMgr) { + mOverlayMgr->destroyOverlayElement(panel_); + mOverlayMgr->destroy(overlay_); + } + if (panel_material_) { + panel_material_->unload(); + Ogre::MaterialManager::getSingleton().remove(panel_material_->getName()); + } +} + +std::string OverlayObject::getName() const +{ + return name_; +} + +void OverlayObject::hide() +{ + if (overlay_->isVisible()) { + overlay_->hide(); + } +} + +void OverlayObject::show() +{ + if (!overlay_->isVisible()) { + overlay_->show(); + } +} + +bool OverlayObject::isTextureReady() const +{ + return texture_ != nullptr; +} + +void OverlayObject::updateTextureSize(unsigned int width, unsigned int height) +{ + const std::string texture_name = name_ + "Texture"; + if (width == 0) { + RVIZ_COMMON_LOG_WARNING_STREAM("[OverlayObject] width=0 is specified as texture size"); + width = 1; + } + + if (height == 0) { + RVIZ_COMMON_LOG_WARNING_STREAM("[OverlayObject] height=0 is specified as texture size"); + height = 1; + } + + if (!isTextureReady() || ((width != texture_->getWidth()) || (height != texture_->getHeight()))) { + if (isTextureReady()) { + Ogre::TextureManager::getSingleton().remove(texture_name); + panel_material_->getTechnique(0)->getPass(0)->removeAllTextureUnitStates(); + } + + texture_ = Ogre::TextureManager::getSingleton().createManual( + texture_name, // name + Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, + Ogre::TEX_TYPE_2D, // type + width, height, // width & height of the render window + 0, // number of mipmaps + Ogre::PF_A8R8G8B8, // pixel format chosen to match a format Qt can use + Ogre::TU_DEFAULT // usage + ); + panel_material_->getTechnique(0)->getPass(0)->createTextureUnitState(texture_name); + + panel_material_->getTechnique(0)->getPass(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA); + } +} + +ScopedPixelBuffer OverlayObject::getBuffer() +{ + if (isTextureReady()) { + return ScopedPixelBuffer(texture_->getBuffer()); + } else { + return ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr()); + } +} + +void OverlayObject::setPosition( + double hor_dist, double ver_dist, HorizontalAlignment hor_alignment, + VerticalAlignment ver_alignment) +{ + // ogre position is always based on the top left corner of the panel, while our position input + // depends on the chosen alignment, i.e. if the horizontal alignment is right, increasing the + // horizontal dist moves the panel to the left (further away from the right border) + double left = 0; + double top = 0; + + switch (hor_alignment) { + case HorizontalAlignment::LEFT: + panel_->setHorizontalAlignment(Ogre::GuiHorizontalAlignment::GHA_LEFT); + left = hor_dist; + break; + case HorizontalAlignment::CENTER: + panel_->setHorizontalAlignment(Ogre::GuiHorizontalAlignment::GHA_CENTER); + left = hor_dist - panel_->getWidth() / 2; + break; + case HorizontalAlignment::RIGHT: + panel_->setHorizontalAlignment(Ogre::GuiHorizontalAlignment::GHA_RIGHT); + left = -hor_dist - panel_->getWidth(); + break; + } + + switch (ver_alignment) { + case VerticalAlignment::BOTTOM: + panel_->setVerticalAlignment(Ogre::GuiVerticalAlignment::GVA_BOTTOM); + top = -ver_dist - panel_->getHeight(); + break; + case VerticalAlignment::CENTER: + panel_->setVerticalAlignment(Ogre::GuiVerticalAlignment::GVA_CENTER); + top = ver_dist - panel_->getHeight() / 2; + break; + case VerticalAlignment::TOP: + panel_->setVerticalAlignment(Ogre::GuiVerticalAlignment::GVA_TOP); + top = ver_dist; + break; + } + + panel_->setPosition(left, top); +} + +void OverlayObject::setDimensions(double width, double height) +{ + panel_->setDimensions(width, height); +} + +bool OverlayObject::isVisible() const +{ + return overlay_->isVisible(); +} + +unsigned int OverlayObject::getTextureWidth() const +{ + if (isTextureReady()) { + return texture_->getWidth(); + } else { + return 0; + } +} + +unsigned int OverlayObject::getTextureHeight() const +{ + if (isTextureReady()) { + return texture_->getHeight(); + } else { + return 0; + } +} +} // namespace autoware_mission_details_overlay_rviz_plugin diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp new file mode 100644 index 0000000000000..4ac6fe9831184 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -0,0 +1,190 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "remaining_distance_time_display.hpp" + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace autoware_mission_details_overlay_rviz_plugin +{ + +RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() : remaining_distance_(0.0), hours_(0), minutes_(0), seconds_(0) +{ + std::string package_path = + ament_index_cpp::get_package_share_directory("autoware_mission_details_overlay_rviz_plugin"); + std::string font_path = package_path + "/assets/font/Quicksand/static/Quicksand-Regular.ttf"; + std::string font_path2 = package_path + "/assets/font/Quicksand/static/Quicksand-Bold.ttf"; + int fontId = QFontDatabase::addApplicationFont( + font_path.c_str()); // returns -1 on failure (see docs for more info) + int fontId2 = QFontDatabase::addApplicationFont( + font_path2.c_str()); // returns -1 on failure (see docs for more info) + if (fontId == -1 || fontId2 == -1) { + std::cout << "Failed to load the Quicksand font."; + } +} + +void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData( + const autoware_planning_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg) +{ + try { + remaining_distance_ = msg->remaining_distance; + hours_ = msg->remaining_hours; + minutes_ = msg->remaining_minutes; + seconds_ = msg->remaining_seconds; + } catch (const std::exception & e) { + // Log the error + std::cerr << "Error in processMessage: " << e.what() << std::endl; + } +} + +void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay(QPainter & painter, const QRectF & backgroundRect) +{ + QFont referenceFont("Quicksand", 80, QFont::Bold); + painter.setFont(referenceFont); + QRect referenceRect = painter.fontMetrics().boundingRect("88"); + QPointF remainingDistReferencePos( + backgroundRect.width() / 2 - referenceRect.width() / 2, backgroundRect.height() / 3); + + QPointF remainingTimeReferencePos( + backgroundRect.width() / 2 - referenceRect.width() / 2, backgroundRect.height() / 1.3); + + QString remainingDistanceValue = QString::number(remaining_distance_, 'f', 0); + int fontSize = 15; + QFont remainingDistancValueFont("Quicksand", fontSize); + painter.setFont(remainingDistancValueFont); + + // Calculate the bounding box of the remaining distance value + QRect remainingDistancValueRect = painter.fontMetrics().boundingRect(remainingDistanceValue); + + // Top the remaining distance in the backgroundRect + QPointF remainingDistancePos( + remainingDistReferencePos.x() + 100 , remainingDistReferencePos.y()); + painter.setPen(gray); + painter.drawText(remainingDistancePos, remainingDistanceValue); + + QFont remainingDistancTextFont("Quicksand", 12); + painter.setFont(remainingDistancTextFont); + QString remainingDistText = "Remaining Distance: "; + QRect remainingDistancTextRect = painter.fontMetrics().boundingRect(remainingDistText); + // QPointF remainingDistancTextPos( + // (backgroundRect.width() / 2 - remainingDistancTextRect.width() / 2), referencePos.y() + remainingDistancTextRect.height()); + QPointF remainingDistancTextPos(remainingDistReferencePos.x() - 80, remainingDistReferencePos.y()); + painter.drawText(remainingDistancTextPos, remainingDistText); + + + QFont remainingDistancUnitFont("Quicksand", 12); + painter.setFont(remainingDistancUnitFont); + QString remainingDistUnitText = " m"; + QRect remainingDistUnitTextRect = painter.fontMetrics().boundingRect(remainingDistUnitText); + // QPointF remainingDistancTextPos( + // (backgroundRect.width() / 2 - remainingDistancTextRect.width() / 2), referencePos.y() + remainingDistancTextRect.height()); + QPointF remainingDistancUnitPos(remainingDistReferencePos.x() + 150, remainingDistReferencePos.y()); + painter.drawText(remainingDistancUnitPos, remainingDistUnitText); + + + QFont remainingTimeTextFont("Quicksand", 12); + painter.setFont(remainingDistancTextFont); + QString remainingTimeText = "Remaining Time: "; + QRect remainingTimeTextRect = painter.fontMetrics().boundingRect(remainingTimeText); + // QPointF remainingDistancTextPos( + // (backgroundRect.width() / 2 - remainingDistancTextRect.width() / 2), referencePos.y() + remainingDistancTextRect.height()); + QPointF remainingTimeTextPos(remainingTimeReferencePos.x() - 80, remainingTimeReferencePos.y()); + painter.drawText(remainingTimeTextPos, remainingTimeText); + + + QString remaininghoursValue = QString::number(hours_, 'f', 0); + QFont remaininghoursValueFont("Quicksand", fontSize); + painter.setFont(remaininghoursValueFont); + + // Calculate the bounding box of the remaining distance value + QRect remaininghoursValueRect = painter.fontMetrics().boundingRect(remaininghoursValue); + + // Top the remaining distance in the backgroundRect + QPointF remaininghoursValuePos( + remainingTimeReferencePos.x() + 50 , remainingTimeReferencePos.y()); + painter.setPen(gray); + painter.drawText(remaininghoursValuePos, remaininghoursValue); + + QFont hoursSeparatorTextFont("Quicksand", 12); + painter.setFont(hoursSeparatorTextFont); + QString hoursSeparatorText = " h : "; + QRect hoursSeparatorTextRect = painter.fontMetrics().boundingRect(hoursSeparatorText); + // QPointF remainingDistancTextPos( + // (backgroundRect.width() / 2 - remainingDistancTextRect.width() / 2), referencePos.y() + remainingDistancTextRect.height()); + QPointF hoursSeparatorTextPos(remainingTimeReferencePos.x() + 70, remainingTimeReferencePos.y()); + painter.drawText(hoursSeparatorTextPos, hoursSeparatorText); + + QString remainingminutesValue = QString::number(minutes_, 'f', 0); + QFont remainingminutesValueFont("Quicksand", fontSize); + painter.setFont(remainingminutesValueFont); + + // Calculate the bounding box of the remaining distance value + QRect remainingminutesValueRect = painter.fontMetrics().boundingRect(remainingminutesValue); + + // Top the remaining distance in the backgroundRect + QPointF remainingminutesValuePos( + remainingTimeReferencePos.x() + 100 , remainingTimeReferencePos.y()); + painter.setPen(gray); + painter.drawText(remainingminutesValuePos, remainingminutesValue); + + + QFont minutesSeparatorTextFont("Quicksand", 12); + painter.setFont(minutesSeparatorTextFont); + QString minutesSeparatorText = " m : "; + QRect minutesSeparatorTextRect = painter.fontMetrics().boundingRect(minutesSeparatorText); + // QPointF remainingDistancTextPos( + // (backgroundRect.width() / 2 - remainingDistancTextRect.width() / 2), referencePos.y() + remainingDistancTextRect.height()); + QPointF minutesSeparatorTextPos(remainingTimeReferencePos.x() + 120, remainingTimeReferencePos.y()); + painter.drawText(minutesSeparatorTextPos, minutesSeparatorText); + + QString remainingsecondsValue = QString::number(seconds_, 'f', 0); + QFont remainingsecondsValueFont("Quicksand", fontSize); + painter.setFont(remainingsecondsValueFont); + + // Calculate the bounding box of the remaining distance value + QRect remainingsecondsValueRect = painter.fontMetrics().boundingRect(remainingsecondsValue); + + // Top the remaining distance in the backgroundRect + QPointF remainingsecondValuePos( + remainingTimeReferencePos.x() + 160 , remainingTimeReferencePos.y()); + painter.setPen(gray); + painter.drawText(remainingsecondValuePos, remainingsecondsValue); + + QFont secondsSeparatorTextFont("Quicksand", 12); + painter.setFont(secondsSeparatorTextFont); + QString secondsSeparatorText = " s"; + QRect secondsSeparatorTextRect = painter.fontMetrics().boundingRect(secondsSeparatorText); + // QPointF remainingDistancTextPos( + // (backgroundRect.width() / 2 - remainingDistancTextRect.width() / 2), referencePos.y() + remainingDistancTextRect.height()); + QPointF secondsSeparatorTextPos(remainingTimeReferencePos.x() + 180, remainingTimeReferencePos.y()); + painter.drawText(secondsSeparatorTextPos, secondsSeparatorText); + +} + +} // namespace autoware_mission_details_overlay_rviz_plugin From 287677695b43e29aaee57d36a1c4d78e74a94faa Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Tue, 23 Apr 2024 05:33:42 +0200 Subject: [PATCH 11/77] feat(remaining_dist_eta): update visualization and behavior path planner readme files Signed-off-by: Ahmed Ebrahim --- .../README.md | 27 ++++++++----------- planning/behavior_path_planner/README.md | 1 + 2 files changed, 12 insertions(+), 16 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md index 0d0def1a46997..8d71cde7b8763 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md @@ -1,13 +1,13 @@ # autoware_overlay_rviz_plugin -Plugin for displaying 2D overlays over the RViz2 3D scene. +Plugin for displaying 2D overlays over the RViz2 3D scene for mission details (such as remaining distance and time). Based on the [jsk_visualization](https://github.com/jsk-ros-pkg/jsk_visualization) package, under the 3-Clause BSD license. ## Purpose -This plugin provides a visual and easy-to-understand display of vehicle speed, turn signal, steering status and gears. +This plugin provides a visual and easy-to-understand display of mission details (remaining distance and time) ## Inputs / Outputs @@ -15,13 +15,8 @@ This plugin provides a visual and easy-to-understand display of vehicle speed, t | Name | Type | Description | | ------------------------------------------------------- | ------------------------------------------------------- | ------------------------------------ | -| `/vehicle/status/velocity_status` | `autoware_auto_vehicle_msgs::msg::VelocityReport` | The topic is vehicle velocity | -| `/vehicle/status/turn_indicators_status` | `autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport` | The topic is status of turn signal | -| `/vehicle/status/hazard_status` | `autoware_auto_vehicle_msgs::msg::HazardReport` | The topic is status of hazard | -| `/vehicle/status/steering_status` | `autoware_auto_vehicle_msgs::msg::SteeringReport` | The topic is status of steering | -| `/vehicle/status/gear_status` | `autoware_auto_vehicle_msgs::msg::GearReport` | The topic is status of gear | -| `/planning/scenario_planning/current_max_velocity` | `tier4_planning_msgs::msg::VelocityLimit` | The topic is velocity limit | -| `/perception/traffic_light_recognition/traffic_signals` | `autoware_perception_msgs::msg::TrafficSignalArray` | The topic is status of traffic light | +| `/planning/mission_remaining_distance_time` | `autoware_planning_msgs::msg::MissionRemainingDistanceTime` | The topic is for mission remaining distance and time Data | + ## Parameter @@ -31,11 +26,10 @@ This plugin provides a visual and easy-to-understand display of vehicle speed, t | Name | Type | Default Value | Description | | ------------------------ | ------ | -------------------- | --------------------------------- | -| `property_width_` | int | 128 | Width of the plotter window [px] | -| `property_height_` | int | 128 | Height of the plotter window [px] | -| `property_left_` | int | 128 | Left of the plotter window [px] | -| `property_top_` | int | 128 | Top of the plotter window [px] | -| `property_signal_color_` | QColor | QColor(25, 255, 240) | Turn Signal color | +| `property_width_` | int | 300 | Width of the plotter window [px] | +| `property_height_` | int | 100 | Height of the plotter window [px] | +| `property_left_` | int | 800 | Left of the plotter window [px] | +| `property_top_` | int | 10 | Top of the plotter window [px] | ## Assumptions / Known limits @@ -47,8 +41,9 @@ TBD. ![select_add](./assets/images/select_add.png) -2. Under `By display type` tab, select `autoware_overlay_rviz_plugin/SignalDisplay` and press OK. +2. Under `By display type` tab, select `autoware_mission_details_overlay_rviz_plugin/MissionDetailsDisplay` and press OK. + ![select_add](./assets/images/select_plugin.png) -3. Enter the names of the topics if necessary. +3. Enter the names of the topics if necessary `/planning/mission_remaining_distance_time`. ![select_topic_name](./assets/images/select_topic_name.png) diff --git a/planning/behavior_path_planner/README.md b/planning/behavior_path_planner/README.md index 03f8c8d2a5696..369c2c2aa2531 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -115,6 +115,7 @@ The Planner Manager's responsibilities include: | ~/output/modified_goal | `autoware_planning_msgs::msg::PoseWithUuidStamped` | output modified goal commands. | `transient_local` | | ~/output/stop_reasons | `tier4_planning_msgs::msg::StopReasonArray` | describe the reason for ego vehicle stop | `volatile` | | ~/output/reroute_availability | `tier4_planning_msgs::msg::RerouteAvailability` | the path the module is about to take. to be executed as soon as external approval is obtained. | `volatile` | +| ~/output/mission_remaining_distance_time | `autoware_planning_msgs::msg::MissionRemainingDistanceTime` | information about mission remaining distance and time. | `volatile` | ### Debug From 8dd46aaee6ec0969bc3613387608570a4bc21050 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Tue, 23 Apr 2024 05:34:25 +0200 Subject: [PATCH 12/77] feat(remaining_dist_eta): cleaning up Signed-off-by: Ahmed Ebrahim --- .../assets/images/arrow.png | Bin 260 -> 0 bytes .../assets/images/select_plugin.png | Bin 0 -> 48546 bytes .../assets/images/select_topic_name.png | Bin 185036 -> 13679 bytes .../assets/images/traffic.png | Bin 8439 -> 0 bytes .../assets/images/wheel.png | Bin 1632 -> 0 bytes .../src/remaining_distance_time_display.cpp | 61 +++++------------- .../include/route_handler/route_handler.hpp | 1 - 7 files changed, 17 insertions(+), 45 deletions(-) delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/arrow.png create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/select_plugin.png delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/traffic.png delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/wheel.png diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/arrow.png b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/arrow.png deleted file mode 100644 index 18de535ce4489feb886c852c842fa523a624693a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 260 zcmeAS@N?(olHy`uVBq!ia0vp^3P5be!3HFkeVttdq&N#aB8wRqxP?KOkzv*x37{Zj zage(c!@6@aFM%AEbVpxD28NCO+XmdKI;Vst E0R8`9>Hq)$ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/select_plugin.png b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/select_plugin.png new file mode 100644 index 0000000000000000000000000000000000000000..79d6625f5398d5f6036b46475a3971f92745d369 GIT binary patch literal 48546 zcma&Nb9h``)IL0I(lkwDqp@wPQDfVUZM(5;+qTiz_DpQs`liqOd$0H3Z(Va`&YUx6 zpS5>pFWl>1p>i^!a4^^~0000^TufL20QhtZ0DNwR{tP}dm?n7*euHoj6jy?Vh6ZlQ zZh}7|I*O<{D%u!3y6D*(0TfN0937494g99R0RRL5abW=^*VWTCCoR+y?5~$D#>wZj zzmI+?prRsv7f^zfM{U=Pc0E0}XvVu+*7x-dh$KQUBntDTARuh5k?dO>e=`t3!Z=BJ z^yK$E=cQ{$xfp-n&vXfLt1+3%;`Mq~QdMpCdb!uH4IzMzBR~WI{^;Td=|OLy!UXA2 zQpz$hF7!sa`kgIa~YsxmVx#>)Lfh9nXJ^mIxRrW4NsVHZ|&x3e5Rt zZ}-F!&`KwXE>&G$Uqch}W&7~%8w==dwa63m`w&fsf1<@NGCp5jUo3J8b`F}o(NKzU zB;A*HmoEh5D}=ON_o`magjPRI+ixDosjAY`P<6SomQ__%MNM@(vXD?%620L{YYFQBm2ySKdz%Xu^oH5{h6->?Sjt{7PXF z=pn`c#9q`yR0dPyOGOGwN;eO;(z3EkS01|P;);U#x$^d~x@!z+NcZzim!MKLkLN~{ zE$~kSlgR0gmGa3g@yTWs$bbf82UcXy}6p!8mqU3GT2w1h+`u;ovkoV~bBMV85x zLe&{*Ct!DdCK{+OwK6{`2-l1I%7O|LC|EjW0+T3MDA(l(Gwtw|_EXdjG@+FIhFW-7 zNL>ayn$uHjAW^^^T%=N=p`+D(XZn<@K9&lw>I@FY{m{@#M_l>~Ka$7B3C$ zm87w;5rbZL>&o@m+#LMc+e1sP`n9mQ=>3i=78hXql{VC`tF{T2NWy_hp&kY@q?d{5 zl>s>mbUF-AK6NU{Kx9Ly1I*({_7oJP_kM2+2Q@XtCtBw+9|{owuXI z!?m=$G%+z*x78UJyg0HlF3b>a5t}?dx4-@vE~Eb%m9EdMkc#w((F|6S(gsOkdrK}B z3=I?|qJ%w9@^Yn`$>k9Kol+Xzn>Ay(z|(>GPrw5ovS?5yzlfmtGP+FH4cE{{CNgKK zhJBNoSqA;gJ-Rrli^D^Q77O@(jh}(w@dvRtL5iDOarXL=q*s_!wkn8M0Gcp>GOgv# zd?Mf+;qfXBG*y+8GrhEQAW8mt3tj^=%$QnoqTwa5psf&1v+2lYWObD4Qz#-gV%W^AV1Lw@MC1Jw0swwWULUGsCtCgf4EG8AJQ|SR_&*~;0PO-ceYRi!-$;Oe4+s1k z9`NtNqfk%15%~C@3IGBS_{N`Lg9CVE`~Ba|ISnkXO|W3I#Id-z_)nYZ*$`o(e>a-? zdXL#+bg%9J-K9*wJ;9MBw$3Tq^tWOM1R$t5*=IQApIa0Qqi5r-v|V&bF`g;`{%jC~ zzFE)CeDQBz#x`eEw={U66KdWlf0AWJ>*}!G7kF9{WfqyT*dGnWWvQ`QK~@TX4_Ae6 zPJUTM`)g_)ukyZ@DeapH1Gv1A=U*YDZEq}ixD;D6I}vJfVO7OI>u!1QV^Mshzp0Sq zY1t0hQuh&Utd=%$+o9_k+-MoYyw%Hiy+ zP={fvqvCR2Yg@7S-TQSc!^5WA$=VvhLOWBZy&k&X2e-At$KyK+N;n&@NtRgR?b!() zZp!AF{?h39@baRA#w9ghS$i|(@6oIAg2+w{U?Z+KN$}5-=cmxrPGDMkibm5(GYgaC zwCTOy*Rj>qNI09rz3=f!&CFPKN%2?CG^8)Daqp9rQjw9;l^HKp?TX@g*D-(H*FM~& z=Vdonb@%DY@j?*=w^fTx?oSSX8(CYa_R&4lZ|pN{P!%KUit-!L+q$5Jo`)ov8a95{J4C&7OFQGM|51q{+;~Y=sEv) zcLrMi;zqR)^hg~LRs$*R@pPelIWdS)l1*f3v^m|&)6PUBm@^r#kOUW}Fj`rd9;>aW z=At&ZT4x=2hRScyo0WVKRB5D%a9Hfb%n~L^6c9sj1bTv*63}S~!t36gTx?a9UL5Kk zAD4>cZnghYc`Z8m#a5bnLtXTO$1OFhVd?JaLnWI!iI0Kgp!LXGLPBD6hnw4zrO}K0 zey)$-L}a~@Bo>3m$uQLN1l1ROFa@Qnm5C&jt4i1->T0(G_}zWRV!}ynzI{8dCvZJy?hl2sFeP!)^S3l zGD+A@id($Xs_Xk^R9?ltI&N~=wb6=#5*%P!iH~K*SH;Go*}r0`ezs{2%}p>Fe#qMf zee#7%N#ku>9eSDc--WX4i7xm?Lb-4(c-&?1h1_6AjvTYu2e#yG14z~=f4wV0j3?NV zjGfPnAvyB{dLFJr8C|p@i+&}cCL@Q4KV7;E4vs(1V_=}6-&Dyqbz<$+zWDc^ zdZPV~7;>(06qMmrV4wpEs9EPkW(ZL*yOt<&(o`ahLoB^gy&Eb8MpLx4Aw-A(U64bl zK6iwH3hi9z3*fcF)`YwLusQ_RgU!l!?dwDA?`5EA0fV~KS+2)<^#uWtqQwD03Kz}N znc=jqxao(wz2%=i^^pT?Bf6?VLn;lK@D9dew8B=AORRbCv(Ov*#%$r4=S;g8k&>CU zpp-PH?k``TC#b^K*sOO;;EL?1X>EVRLdx^MVbe7S%?pOmgr~4Oa(8iU3;wD7JlM@M zV?Hqil|MP5c{^`%u}~E!*(Gc}O|DungA|-QAjoI~18o>U955W#!LBT&ioV`30k-Sh z>Mgcg#az)!?cZ)Z96qpk^$zYZ1{OTMoy3jpuTPGPLdkY8r*%o~`|jJnIFS$q8l@sA zhJVY;3y?fsU9lJ;RJys=GOUxkHde>hCVV)$VM2~2DP4ApksYXA2*yu>Mj|?q&>`#I z?&Nohm~r@Be0!Pr)%p+t^Y_#GOvtco>qnblKnzVEXz-^x1tI}SwaxIbgcJ=ralrAc zpZ^XdG@Ajw zR<(tA|5SUE-jq=Lr_RVNba6lr!tF@xC#|`Q?C)Q{D$tMLG_n6aN#S^&;CwGQ_CGJ{ z*m*_KTrH%zHZ80+`8{KI8pQ!GV8yCGV>)x5h1=%t3cn(9f6W{VnUMkPcax!H&XlTr z{g5V~=UsxLU+iXDn2?fP>S=mu$QhCju4iPO`kPgqzfA-6jMIr9D|~f!=bs@3J3&*? zR!NWFVH8vk8)wFD^){VmrE|vR=7yl9JzrQ&ibfbKVc0n*V z4)Y!Ve8awy&a5s#}VFW<4{fP#YBAOMvrmF4B-MMS`| z&;bCiT9`o#^PVb{9kS7_eWqX+{>sJ29M6B^M-?#$PEhD)9X`fgde@l1F8%Yr9OM5& z0>FP!$A6l#_&-Y*#igc#vzw7U`&@x;H0(%lT4QW#3N8H!@W{E9m6|G^D+gLz%Vq7Z zEGQ^gs@BE9!V*vf>nGUqFTJVrL9hZgb=vLx($Ueeva(WERvuHMG%_+GB_#!aTW zkqf{_t|gv7z&!+yiB%h9pT|?1Y90}nQ@DDC3;4=IHG+>6K zwOd+OXK!y0Lj@}ooTd1%M*s4BnRnSCigU{qM|OV2Q+qSvHotBU(G{deGYA!M+__}#%u3<@#_u2>gf$0uBzMy zytGhr!%mqSgf$^H9XZt?N&1lvB7D?sw9w)Z2q5S^^`niuDpr9kc? z{iB(_C@6OD|846%s)gz1_=-C5ysIhaJ0k2;yG(3 zf9j;VRaY*~!zNu>YguUKWeypnh2c8l=^^nc_-5a3If(F{3R4jJ%HUok&02b#mQrHf z+}o@7(rT*zB3t;7BT~)d$jn)9D<5uf>7b%jDp)YZOi% zvfFN00gkR4@nc@b$7Pko#6+^shYv*2x(hH{K`sGro!{bbPU4l*#!(ApzWK6UNVCyI zI{V&2^L~>R^UE*kzAYN#CjY+i<`2|P4j%8*ZrR!B2wP{%4VxhpB*E8+kUb%;6-^Db zRVP?APqNBiOs{oyiq&YM?2*UE)1%{gkq;X~*~&}Z>wonoX$b|PV-sa%#&0fuTUq`F zjk@)3IWl@y10L&pGkx56G{N>lN1)Gs7q__aifgV(H?bl+^Xp1Zx> zq!O?3T7?uGCg+ip_m=qTJt!*fxU_d_aq1atdmIRm(3{Vcz_sE5ZMwvK+)o~1@P%Oh zXT`Lu4&GnW($d=6Ml-16$C91#TshKz)@u%zmJ5CIjDPit;OPFGiUs^#pGVWLO5Pl{4((0H04A4r(YK_ZC8-lxy<`uRsX zE-?mKuxOG?HrGh(FA-E$U@Y_V7E=XN_JsM1PmRK>GS9M2nH0>$R!M$ESSXA(?`bF2BAJd;RCktll?{3<+d#?muG+ zb5~7mYF?&viLI+lM#WJ`M5|5v82%05jmv{~ao|b%r7$`gw?kuPbloouv3KR&pq&rM z|KchWjnui`EgW3W>jC6n={}O^0>m!R%f6wcEfkDNcDN<#q`(yr|wSC4r$~fqKUbA!af?C0jBD%#j-I^S&CX%&9OHT`BS zPfjV;Zf|+O(yCkq8&gnh!K=hYy+2F{0SNhc$g;AW0wtXo{~SRqNFp%WaI}%_=5>(u zqJ=~>nhj;eO@4f~Auy|VFod_}lT9s{7x#$!a$eWw(dhz}GoKsnv6ng_AUi57rj?nT zqzvx^1L&E0=o=KJM0eP+IA8-NR#%{=!C{|MeQZ@5M!vC&JlVLvTp-1LFlVBTf&JLL z@%{igGye|?WD7T&)pk?h%N6M4w*Y+rqF`I+lIWez$34aznfGKI#j-TKcoyjJi=B~C zX3<6n-tqF#L3m6>>{M7iA9a`R4GezOkzoruVSwR$B=E_ahh<3IK0i8RE~d+HS|FL1 z7gO3svtSiId&Ob)*qY74Nffu0qx)=J2#1|64LHHp9VFO%)X89KrivC20Ig>^HJRu0 z%(*sJuF`PWslQ<)7y!-kR(0n%zUa2E6DJoc1M6>2DVqUoJYy=A6we?fX8LG~>4O+S7RE0v?s; z7Z=}m$9@aH$9{UInG;w7S^}BZp+B^f3hrNp4T`)U2nJ{S98QhA_oTJr-A(5>2Xgbd zsopntNC2A%SV^()Ced8+%*UFtcWakpE*i*RvO7~VIyVfvHe}Zp)Nwyg-K?BDxO^B9 zL$q^&17h8odjA8AclX^+Hu6HN_i9Bmp4ZQSKUv(5DjMtcKDpHY;^&`4v0^mV^0F4b zV6?3lm%xueL#;)~*Amdh&X@fG#%+hT=%>0d(8JO2@i&N6Y01c-n&<)e$E%Ge)yU_Y zFLq8&fxiHoQ%HDt@6tuY$e~>VEhvz_h+$DtL2%#*UAI!R*?PlVVS@~`0Y>ZnCcx)x zL_|eh&Q|Zvcx@(lUlU12mY0`pICN{(VEgvK1qx!82Sb~Y%^~(|jQg&NDgS@#*GZ>t;j*eE3* zg}AVKy?M^Wt|yAlF3G`GA0}k&Bp~s)*Y$7r7D4TDB*^0LOp0+Aj$GQ{oI+kcRxo#y zLq|?dPD$x@Vz%({{>p<($UXfv=?huNDK$CMX;53ePw^b4p84|8b(K)Y0%HJ!d-4%Z zqm!eL+zB;D6tG2NRz--PuWPLyvr!mSqmVJqFVgLclrbIG86^zG{gYV>OyRjJz> znZ1q;xr3J#l=R%F$3P@9GNF?5yy}9J!>>19Q9nro7AthpZ*?+JH#(lo^o9kkx$-9~ zjGqI9ZRqGP4swR3bIj75f3%m^RCCcycZBju+dhL2Z zWY-BEKFJJcPlbm?vbHqGw5YxwT!b<(Fga+fs=SeJbZ0}!eO$h3=8?2{RQ2gS9lz-8 zo|Tp5sEtiMKyGbJvEE&y{)nZmDe>UeV5+QeipVQIeJ>zWGnfmTX<=an{!_Ys>m6E6 z>lILx1E&^~hWDk5x*82}Rt0jQi-&gzm{eJoBg}l*LggEcSmti;YLCGz4Hdsu_L4Cz zB~b5B8vdeNEgw94QF&}=X}V~mo0NjFo4@KN3h#?ZBynzux3AxyH!GJ9q&@ zwB9nA2bJ(D+=^Ek?tes0LTTcg{AV+i+ZmYU7N5BEZ<0chMhhMzdmUuaPe@wW`DUCK zI$nBqGo5agj>pAH58IEsGQS+1+Oj$~>hi~U#y{J9LqaASZ=BC`mHvbHv2E%+r7Vi! z3Or_3X^83-J~H2S<(1$2+(B z8$-IWY&67zAqAThq~$!M<*(w-Pw}VM#VdQV4pi&!9mC}$NGszgCALK(Q$0BW5uau5 z_XI!_HwXo+51X_g+u<&V9ceXxKON&v?}pOyipQsWMUE# zVG3*?UK&15mO3+ul+Q;Wuvq9t-RC;q;^&p!p;izk+BEUc+JlXjFZ3{83EKT`P8D-= z1ClamtPhFBt5Up;YuRR8q)fcj#Kyi5jcnFt8$E{25R@XI?RgYFtedxeEekS+{_1Gl zQCz2Y(%^IlJGGUdKUlFwBt$TNQrYVVGAJba(048}5>V zdPXB-IA4cW$71(XOW><06wzcFP}al$>;}nW=ZjAjm!! z4}w@6mbMSR6|9++LJ+%45~C0l!pfTj&9{|$?z|r^
6Ulf zbx=VCc1-tEID4rsT)VO0n$>Xc@FsUrU(iZ7uX3Ti%?;CO#fF;>Yvk@BLAr zIw|OOM>~r?%ZnrZ4L94JT_q=)(=UycFhOa3P2m!ZoCp8z61lHvU< zdJ2=7!ge%iC_O4?olM8D4OH)QmtPs!*w-MdL4DaKn%;!*uk`69K6{se*Y{bthknoQ z|H}m!y#RTWlG)Si3_GXuE>IrnJ7Q5vMTIJ!9_xvSgy=8l217`q3tf|~txa&ceTl=0 z^E?p;nm8@0Dk~Ip@i?%wYH#M9TVjz|O#67+T&prFC@9$D+0p@vd7IAtm$2E=RO|g;55!|(Cn~K)ue-URK|TzJBikg3c-jOIEWU; ziqHjZ2;=3~@sPnAZoq_7l5glDamwotA2Dr+g!A5^mBPTHI5d4OYqh(jak})oYNFz( zTD0B{S(GKBGeVjeFKjI&52wrQFk&+k_c8ba2I}4D)3*{(9rwXuYybtBzcGBh(qL>w zl`OtVLSpQOR{HNzK1nvX1|teesv38=2Rd#XPuV|+S7bCKwRa(Z_wivnzhznBHz$2O z{B^TRYwZzd#D7%fC;kGf$b!%1L-HciA6Ykbs2i>;9AM;_##jA4Jgh`&sT;zhL~KQw zu}yX}p$QvRSkLkHWOR6B7+r|Ocf)MF)2_v5GNoOPLYO4fAO%)r6hn}N>`72iDu!cS zsv&-FL{zn!+nu@|Isf-UYpXuL83JPRGaMQQMpDUfP2w@R)Xa=Qd`2EJsjlqMx8iej zcyhW9`}BEWx`XAwK)TU=sf#%mtxJMP2^p>9+p(8?sg|E05-J}?qXma!S$dk8L{#>6 zZ%5v0N-Epx4QZ#60PU7CsqmryIg$L2_5+`E8S;+O0ZKJD<3i9py}CQyT-chNLUixq z+&(#ma*UX~gwU2FS?Bw-%)+eR!aDt4c=&brF<#|S332I$aM*E)6*cw9gDPZbSa^$+ zg>!zd7bJam4%LZY_4>@SQ)ND;a~VlY-Fz!c`yS_)fso4bNOoA6ljE`kRCE-v?}QnJ z6Xvd&5(D4-OzD18LhTR2S(TkK=2hEjiGj>b{HGP8wMB84hGt%d(BJc=cbZ2gqThiU zO)KY9?W{SbC#JFN5@TWoGp9&p-eV!07iVJjG_=_FdbT^TRue%s1c?%akB|{#e{3N7 zYVaKe?i}>rtXjf_1!4P+A@zR{`Uw*;Qj&@L5qyh74HNStK@wDg8N@(T@Hl@>4}aY^ z9B;uxvn&q!ZeY@c-76|~ZK!{3MWK|Ov>0>RtUD6)T3}k2iWX`^B`ypuuxzt)x}_M? zqX(`G^qK382Zod#;0CpqTO{8xX*v+{P_YAz9KU`caqrOET&BnlKR|H$EjK{F*xKN+ zToQ-_4tWL??z9u|POD#Q7s%aAil3}^Jy>5ama=y3ShJ z%s+({v1P`mlM6d51t20H7#)mRn3YQKLn4cO8GuyyizL|Fks&AoB^1>=Z#dd6EfbYi zu=dE@`}&aeS0R4yMAk^p7 zO)xOX!`>XXQ2QQp{WSGwsK&)4|Ju3_V)wJ4{$OgB+tGV-wsE}KJV=-KT=)4J7(c;( z%}Njk69#P6e~u89Lfl5NA>swYO|D)#%pehQB~ENq%TEGSc0au5Q)Q= zam$=`M<*ZELnb6xpmy{eOP(i_hldg)}w-^=2rYY09o zbAbVjPqkbZSy^E!2`BJEhkDY*E#^1CU>bWltj*q}ExN|3o5(%q-xKUr_mTPWd@AAl_zl(&Bh^5~51)1q+b#qn; z2ZYp#dZ=WhJ|UcxEstZ$%x+n!f|aC@U9H{vG02=P+DT>nE=7dpPTqJxmEi(sa* zwsudDe14DBy!%$K%uy^BoBltXkf&;%kuKmex+f^Jd; z$HM54=*RwKrJWWd5mh$s^8*tG*Pc(o>gsAsOUvWqV*pfWXz0WFTD!}|`rFF`K8u)y z#Pi!As2f!P@v|==*3ezR$PBH!PKM&HI8Q}QO^5uBqXcB}{_*1?!t88%vURK=T}Ft9 zm%Zz$6XSFL)HBK-~JzM{YX%K@$ZLhcM~ zr?dR$zI(XEK`?0I;fTyTWqo#1>Pslhcyv^lkYs(jRTWA|0JAigS|#N~vwDcFYPWj+vR|$xWJ#w02g7#%oy29HM{Pg0diD z^C)GT3zfURoZ;QK7@VHIz#Uh!HLq{R4zgX-``Y)}=>DNTr@U-7V(kOojnJrHXT{5E znGDE{a*7o;x>_~Y>i{j4ztlARft7`CHKm{|zvP0|OfSyFKBNyPJx; zM{Ig+?mrnwnYJ%gjB&cF563bqFU?)EWA?cX?d)^9d|*H6r@b)~^=PVdIG^`2*MIS) zW4a4Y{6fyAu8pHVIm_ah8o$t%{^^U~xokmh?$+_~@%HvMDCb`Qz1nE8RFxSYA8+8_ zWCiqoLHU9g{cz=iijHn>YARPck<~ib-~agZ1kTfa;zi%1uvteJ7VgCA>P*PFeN$eC zzrhC~xoqo#*0BKG)5*xiHue@M{G9}jF|#)O$rqvj<;Cakw}UKiAB*3Sg{4{EHHm4A zGEtOHC&BUlAmTG=?oMqivnpr z&bpa<13vCD?3;Giq?u7ObH5VpbI5h?K|bK?5#A>H=Q>qypCh49?mMdcJ=i|ni|yJ^ zBgf&s{_F;w8=q`C9=E~>?xtsKM|Z~;QSld6k6nNsQO8P6;)}cwQYmhiGnRMy`0g&c zc1AhqyWVZDT(Ss8zCS+`ySz6lD?;FPl@cK;FMxI~P)^*-ey;z)-y2$^y?HYJcw4eu zX4-fu(dXjs$_pIdYxfpl`IS|T`Q((XeB5!mI%iZxf>C`-(&6LRePr{?;5!`JaoXVE{F&y1!_Evf<$pMe`@CkfWiG|B#0VFr7_H(??H5$DtQnTQibkh_)VZS1?X_G#ABOB!w3Qbk>Px^cD?lILIYbzX)9 z8Xoqpu^7cVp@#vZD=LoCWRdVvCeZ94>HdeQG$~YH%R#?jq+W%?cl2=AyQBBHA!E5A-}(; zU+%bu6}69urR=V+i|+I#%e3BPGXB^pLkP0yGA0b|wV;0CJgmobY-@5GI@+5FWpUTDQb*MaRjBPg|lKrP7CF-nc725D(34cKoZck(at2LjVQ&_te z#2Y2?UCb@Vy*>#-Bef>mP}8^GwS~mnEs{I@?b)ln$aIU*ZH$o^;Wjx}RkNk@+0kZ@@d>LR-!Uv!U{RniaulN9F?QHoD5Cg>0j>oi>>o3t#n+%eyY0 zE6UcX*v!WbRhQ#q-OqbXaC;SeOM{q;LJ84VSMvOXi4aNv^&h?+Q(PI6UhoLnhLnH4KFMn_s{ zm~#6!*E82dQSR+_p*~%3aZzzONG@1WQd1!qW$CwRj)DxOuUaI`&kzYtBN&#nAA-<& zqp)p)ZztC@(yTi9b)LGNF&rNKp+M}9inV#5ep=Q>#+^lR3j@K%r$1RQ(T1j`92Sce z2)fyf20^j0GZ@lgG_d^6XeYC4;z6Uc;A$591ZBeJ7s+=@S^_H}e z(L-`mQX!+M;oo#JgZW54a!Q>xw$`85rFn5o=L?k2O4vgAbvY%u=y5F(sscm-h*dj_ zBMhw9ujPZCS7GT}?84UPGId}kj|v)w>Jq(zm7W0SS*P{8DjkWS*vPoadamXXJ(yFs z_>k^UirvNk&uW?898B?F`UZZ-0Mmc_7XoFgPk#U%jx*V)RqqQ8m?njSOMo2U{?WeN=Gkn)!bhL99u&=)pc z-!F!))E-%fVup_4y|uq6yiG(Y1(#AkqgCOuJpHy*Y5l1*B;MKKy<8x-#wq#2OuF{E zn$pR=Eh#KEF1_4z(`Ia=+df!qs@ohRd^OjPQTQ2I-n6K4!jz~BQ0DiKI3RTS^jcC< z@(fT^z~;2yU4EdXruLcSkm}X?u3i?AR}^`XM{VCHOBy6w7b5^Y!cC8`v6IF#ms(j= zR<+`MhyhQCJBbuvUnVBiXELef|NR{b)?Z*KoS}3; z(g;Wkvu=sYJD>4u$wjmGjDKCZsEfaH&u4RgJ%Gj_5J7dwXl2191P%@T393}Cu?eIl9Q2v;|o`J_oRdbOl)i_YH9<_q^v9%#Qw2ldMisyXulLL zr(^tv(!g&HRxhfjnyuR)ij!JBCwDKlY6}PiUMN6s=a*Q+XZ+MtXhP+W9IX$6 zW#Fer{~mF!|HnQ4kEnC0_!Ca~A8+}?>)%07HmrFGxXmQs#b!IXBzF`6CvRroM|J>u zK`YC2zvZ;+5GbYk>gl9;_xFHL{Y56DYeZy$f7id*BXq8*6$b%!zb9Vr-)NPd>DXmV zOxILt=(xev-SU^&?awe#J8V_hrsA>hz-pSmtB4CCF3wVy4SMCHBg3WUK*#Ks8|#@N zjFh|$kFCL;$p-qiy^n5Ma3N`^mjSGnx7eVYP})z55>J%wcGauJKc$2NAB^)1Me(|_ z)M!U$&#a_s8;c6G-JDB(Cgjxz`-iH9XrKs9pjY|*qjS1feuigrBtOq$iuZ^bUd zAYFBGbik!U49PcErF1wsEY=-s-+b;%#q7NhFnxz>b*kG|&(1}WRpcb_L1b1kE6(V_ z8P;ijLCyrT0k`2!J~M+v{po+9W-#Ay7b1R*R(%v^6jpIVJNm*~=bMV2%45bkx|CB| zQ{d2e_?J7)$YB_bCRrA~!$YZRm9$Y938@=vA6zarEMWKTZ!%v*LCnJQnaRI0gR8J< zGU>ixq}_0CD-EH%*V~F``3W({iKdIhN|6HBkTAoI(2ux zX&bYqhb{6#G!a>PORV2#_nf3^14r$mQDO7C=}P?*9yM!J=OCexOD`kOaUtVqJ{g!u zV?vV)pyYv_lqD9Jnr~sPwHMKSS@$R2!;8r0qzCI@17AH>1?@imducWfi;Kue$YF*8 z-ND`3n*&cI#U<}&aD*2O%l6icUDn(GWijkpLW=srh*AbfZ*`>rZV*uD$7}NrY)%b| z%hM`th$}AG)afVn&R+42I_8L5IA?S43@(~ltc>DBDrL}ra>S74#3H4YR8*PcmM>Ic zM??E1!qbq|(j%)2zeTl}U;I*U7l24a)nY`Fxv)Eu#gQpa?p7G*i-lDj>*F+2KqOVV zaM=B#P$k^|eO*)DOj(b=F{ULbwRLoE`b|$q)7UR8~AML2@fMr! z*NmaXHYqfrR%DfLGI}yHH0v=pN@0dV#4pu8L=3`=LDOMx7{zdThwg@|nbQK5Kr}CN z!dQ*!HJ9jf?QXr2Ga9rhGYhuy`+47PIEYQvlN~|01$vILzqLUb2`bm9LuRmzvwlGy z%EMGT>hXe(E!h4tl$Hubx6BeX=F_ahd474%(MWqBrV$^ic1N?mR%E;GrYo_r{9#GA z%64ZtFlZIBiE4MuPewO-K*5B09f_biTh=@3V-9Y)sB=G`dvCqwd0X9J3WgxVrT6<@ z`R@l9eZ65(;=P+g(YQ+)XLSJdNA5D3+JQm-7Jgy9;iEad>p!Xu;hu!A-FiT%8qlxI zImI+OJVp6;^!$8|%V;BL?CGT4E~Q5yhQq+h6{6Vntj7M-gJ?oVFjvzZ}Wo4d-UgpsEbI@s;u@kv;B{r zEjchf^hJf>R0h03yax&8%|{dqwi^izvsP!ap0TCovf7n`qZ=%lw0vuyFJLl7`B{6U zv;{;q4BTLYA2X0EP;a{Z?pKl@kY*u)KgPZM;J@o8M5MY%3BWDzhi>j$a(_S!+|rH7xFiLF?@0ni6N{JRK9k3uwe5Xz`F{Ec zc>R=vjPn2A>QhOjSeP-e{<<8%_f++~+Y!@=i8epLGulV?_K?T|56ycC* zuV}qtv!DZ9j2AUAP6cHyy7jEPblRKwB#SJZ9d1mhy?@^q+RfDL#5}Gsb%Z#m6`+5N^V|ik zG0iTdR2Afu8L={Pbj#ahSBR-Cj7(d(X>o?eaPXTacKg%C=b9~BFE>5s%}t={Rz|MZ zFs<9YrAi9{am*>G%8nXwYwqXw;U82gyBDWD$eH}f9a)z2W*aKp>02|%t(mllI~U6- z9IVU}?COTqb_k(^_nhZe)R8LKu>s9s@%%!$1W{nw8ZMvQP zo0#WDNzk!}KRT(NgQ_7MtoV-M=^+_)@tk%4Gxd~1c(@{4npS$}vjm)=@MP@Fdwal6 zuTG-!E-yzjNb<#MY_Z@J8WZ{4mB2H#9GlGhX(~of@A>3>FL`(UIenSUc5#5Iu64US z@1XhI9{BWR%DyUrSzeqi`E-_290%n2a)mMLp5+=hL@A~<0*l4BHJm;uBqr?Jpi!My zoDLC`Z9p3_S-EL65IAmIk5_lm1Zq*>lW z?DYv8EIhqCz$u%}Dc!5rndQ(5iOXk&+0quDPqu||dLfG_vH0Un7#&M@Jtw%i2ip{z8BXis3jLpV@Wx4R5PAim4Fzxau4U*SqT7535Et z0x@AhDWZA!$REPC)+uC>^q1~`QhYufBP21IcG zR>j=WQXI8I_6h5-u0Tfi{o&ffTbQsQGYe+8VP}9hKX_}_%fXIE;^5^|jEAnanTzh` z6A=aqCUl`5K9Gppi6ecTo3YVwP1w!SX-KIsipnjY#}J_%r!I?3HOuGKja&EA=q;BJ zQxd1|3bUAA5UJ+eBhl|1Q>`m&2&lF$BupicF<|3q!ZI;u6sHRoC5n7*mZ-j?+C~MJ zf{xfWaEsL@d3>ZzPTB^vRitb2+6;Hfww$M3zJeRgy8Uc)h3>2x)rmYd4nGOhDax#M zW~U(fn0b3(i4QWF8Vbbs=0g)cP2%8@SkLn_n!6h!g(BuLG^&+#z094IC!srxN&0=I zU{&=@TrG1Djr7pNz?My-=|aV;UR+sIu~#GG2)qa@*hkZIG|u;Ky49#w;)+*^P1ap= zBZkSig;FImkDzgC(OH;jwK0|aIuoyb|Df5 z*k zPg(P2EtN)l%{uh;?FQAM3-!_!u&kLejFb0){_EuUuN1bUuTM~Lfj8lN?#5l4%*i3cK<;7iL zd2MdpXX46+`4MOBH@|-lcEqMD98)CC$z~qvHVpR32`MM)9o0VyHeC`As8W)lOoBiQ zlopacnniw}``R{wRI9jcvaoCvd=R*;S-b^?aEL7%O*JN|TZN)7aG%zPW58?91b;L2 z<20+bM?_LQR*!#s`1_~c$RL^wiu!7lbR(`id#jnqL_Ty_xTGZOb~Gd6kIV}w<#fQ~ z890(j3jROb)64ac9Keq@FZafl6GTNMj(nwS((!kGev60#;KNjsyP6lGu;_TN_M!CG zZjce*2~6<^yMPY<0`NL`%hQ-3oh}0Y*r1B$zP2(bM~{CkE9ZV=#on3Bu4QQzc+*FgV+E`BzmJ-B9T8qCiKI%$Zshv@RY zd;>ElR#sLnXo(V!x3>NoGU-`-x}1wu!h(LNo&&+*#^F49``dm*>vVgsb$NOC5s*CG z69<%)m4O@0=W>ODpS{9K?0%RqrP97HVu0Jls|pH8xVX{;pVYJ)n$;hy-s}zj@s4QF zZ@~S;$(kA(8VU+Th|q|Fc6N5P{|Wd2%tbH^FpJ~FUn(y$^$>+w^W=NzF%>+_%k3~6cF1&1PD?w| z-efs^>fi?Xng35+U0rCXczJYPO$`G(yUi1?%Rgnp`}G+G5aZt4#YhyCl@q}dAD=Hr zffiJsQ`ZT z#jX=mi7u$m0mr&TNKrAChR04pY1N6Xm%v5w?uIjOO+|v^0eW^-9iM$6@>4iqoAvUQu4sRP9Mxm!Vex zt~^YGg<;nFV-mm?gosRPjd@9L_4dBrs)>&4sYEo6dH++U^#yrMFEK6`mX^HSkCM;OZ(xKp`Hhro(pbx?9hLP{PXwIT9R; z=($D8%{06ue2HIEYdL&cw|klY>=lmi;X$hHahq%PUMD`(e8HQoKoe)eeV>hfXhV8- zMc*56=ik>bgw6M@^*t{jXXP%PZ}9Q2FT|2U_z9{sPchANc{~}Nlp20bbgSM6CUeHi z=5kXf2DtPYR%#xkO-A=p4v{p!i^kqK-)WGf`~_;tzJRE1e_?>PUGUsEA$(80Nynfl z@;FDNGW!T}?tlu#Bg^f1b24}ZiBlA2=49>Bxr!(?(V@If;$8qWN^13xWnuGzI$(d zuijVhy;EH?^G8otSD(|}d#%0p+M7TvrN2%%E=nhJ#c93CEc$gnTJu=Dn->p{N>A3a z9-3754&qPZi8-H#(KuAqWXY$VJ|BkXlwZ8=S4qpt>@Yta#Fq6+Cufn?FzzsD% zSOmvP&Cg2)GxL$IEyTtJSU>do#tJ{#SYXwU4p`#~QBP#dsbIBTF}=BIdOzTCVH^`6 zxI`3c)(;Bm%X@RTR&1`)~=YN}^rYimklgs5?$DpS3HE5MatWTV~MJs#FgRQys zToP2VQpwlp#tFeAMne#0T?&-@nxj)ot!T5A{pS*+=h!dA0@opej>CRMcki%3>l2_s z3hAeRw|deKw@WD&WPvuTZMR}+k{X}fd3$wAGZ_*FC8Wh`+&^&{(Jtk^oD<>E*?!?8 zYU+ti!fUd=Hkd$o&5q`+?-cQJAIJ_VH-9J(Dh$_N?S2s=@-kPTS*yKwp->-!3X%{s zS^N~c%AQpsLaUE7%3ARgbw9|i$B5e;;#Rn9%)=n-m}!X~9=*$oicM~<;m7cLfpi@f z(`6(R%VRA}aWd-qjo=_XA{ zqZMSL$8s<$tV+<4o^k8$Q#%+AZQ$=$Js%%>NN2pZEKmZYpz7KIvZ&#{P`%w~Ci2^E z5r$qB5+TID-OisQ@+i;h)L)Ap8g6)f)RqCp-#|W+!yl8+ZPs$DIRiD!Qfi_0NHO7p zUBl$Z>$_n&z6pg>_JoFrfp6wbHyZ6 z^J^1Gf`>N!p#v139v7k+SKjok%#^_=fKRz+q%YTY?~XKMxaR@GjQ2X3=thIF^-L*Fg9Kq_$QdvcN*ufVn3ATvJ zG3w4t)sUsPPA4ceCF`2;9CaI+u0_li?~KM~lbHWS#J<>iwcMy4_my^`$cW4Zhj`Pv z$sW~u;9gQSSuvA@Ow002q_7e8gNnND^`%SvRcQodO1FIq!ptilYY^wVtE*~=A}Kkf zZY}xSyeTnS3-A8!ppY0y=4`3nxU-2OO1u~S)Y0lgK60d`GNfear>-2eSz6ta>X^{f zEw>sL!EWD*89e<*tv`*CUuTjb z1X-bp%?bEvAiL2Lp21{4|L6B8f7|uCc932#7Udb~X}1!)2S$!#IgV`iL12Y-seDWu z{)dv`iqg3hhazQGiFk4F5zQ6loG*r)8^MeZA~+ z)`{d@6Pc@B%X9KUfK~>D^7DZ#cl%iwOwjusdV1%n*Az5DZjO46_Nh#vb^$c$l9Lk} z_{?}^#DX5kTQ`H%x)6FgAhq&?0g%2U(N z;DMjDx5VJ5qcvH@M6{h*Y-?4baY~|z!&Ft5L+8|D{lUwN3z5}ed8M_rFh+by+tilC zPBMA|00Q^q(U#$bFQma{kSV)CFeY#dPWUaUdzR za4C2UUTP|wnso-hHlN9x27epPDVxI3I48X@#`upR=rP9O#k9Kq0ZrP8G{td%zI%NmDNEU6!Q?Q6j$A+l$T*Xw%xaqb734Lm1D z42|F^Cc&XJb)RXyS~9lP7{jK=sa4R{;QH)IT|U9PyvPJG4BZOwpGQeP zz5&je-{|>K_3TKTAO;buU}OAzOI`o3vtF%UiBCu3@=?P$dx_C*D#jSkt8herSAKtC zJ=%AHVuzBe#7U&Gj0`i4jN)1B%R3_$<$tmYOl8Cz+sT2v9oYID=^QmTkxp1)ER%eB zHTtaj&MG-DPE%K3pZhyHCXGSMUyv>?wM_*c4OO8mhQe%%Rf&DH(X-24-Zu$X+0mqT zDo+d9c8#o{_35}v{!jEhgH=g{y;sW(o5BMA)NAE#NLK*v)Iem_ zU8jF!cwDdsc)PA=U11WEmxsSX#rJMSR2BC9eV^%K3o)vD>e&~5%F33H^57_06(z6o z$EBd<+$&2^u-|%VdsZr@Fe})I^kJD#PC{sCVmr}Q!s)|f1xXmX9h6tsjMH_G_{cEp zfW=xAIV3r4Xx15!rb#Ov-ostbsh%V&D>>b{6(`196IC)lh9tn;)p&kV8buz0&kco^ zgVBin=zsnRr@mBM_Z_dM6UK>>Fd>ODhn2&RH;1%bRJNR;S=;&Y?-;D&o-Ys9Cm1qO zVaz(8+ot*2fe+zeq0qggV88SL|J6y(sXv=HGQiY83duz`C>br3n9ec=3w4>-_lYl%&L}Q zPkWaC(pJ~Evkf!VcF)^N6)#%-jnTYNNz5l_V34*_SK?CvCl-QkvIraMs@HTKyMd)2 z6B?s%Jh{hq;nMf(I5)eQNAbi*zvy!OUBb%4M3z>E)uZRDq@>J5rCqmVo&hhuScoJ8 z+)~`7W?Ewh(;xmjZpQ6Jn07U!jprjY>3HRa%HHD1Q4>fO&bum%`~^m1Tw_C^M{PDrL(EPk!@W)*m! zEu1xaM)x|YxLzk;?rh8uuzcr?D(bg`3Ympu1=;sTL$yi4_FXns#ldDA zuIGutD@`$%N=%6uM}tgolc_d6)tWJUSz+&2*MaQ5o12D4woP;Ogz9L*dXq5Jbw@Ug z&%V(^tY>b;yJ?k^VbIrvw#J!OvP;;FlAGpiHHaJ!Lkynhr1guN@^<+MDQK!SiP6^i z74OLeCn{!pAI)k~qBKakq5T&ZddcD&HP|MJ*j9|@73{2tse{? zEh$2|d}p~9082$x#DA&m*X8Rq*6M;Gwq)0t!xHl!pG(5U?>EY;NSk$@EM4P##X{o9BNJvOHI7#WVIM|Y%{?BcwLh7fdr^lu{+06Oq zp~8g-Hfwc-5+?S!=K`?;*K{U5TO2rR?}idrqV+^(YWuUF?tKzM$9q4pee{b!w0YMV*KWaK#nA56Hj)fe6k9J)t@+`l5vGj`7@9aez02-y0{F|b%hS_iH@DszT<|H z&1RmT39@$g)v0=0=$!GTM6w~1XO`uGhr2q@Ha^x2a&^AFcbl5gZ3>e^B@*!k3m}Ta zQ>ZTvPGkzc3wmr~`;u>T_7*5{4PbF*(YmSZcncfD0iXHt@6%f+Qx`uDagx@q049Ge zHjX62PURkG=$;WDnZp+q>QuQ7O%hwaMkt>cxJz7Ke1Rt>)@dU-ij6I0Dr=FiIY*~= zO*X+pn4wbmE{V!;(c>iUTY1I}YnDZ3OhiO0zMJPYuhzpwzQ_xIijs4Gju(Wef~vaoouaSd(QaqOhF4+?F3iJ2*W) z1_zAyQYh^xN~j;zB8V?!3AaAQ26p<~-N7m>c_+Mn7c@oY>NL-iX3Rcgh*~5_5+e`! z$$2^$b143Jb2Lvw`}MRnmP+P^ZL7v>Xx%R|m1HhpV~66*EL^Uu!F_o+@Y(zE;UQMn z@xso@?J%xELyywhEboG z9DKN}t3%Iqe31XRIT9sENcZFOEeRI|#1p zb}Rj8D3t68bA63RjxKeQj;gHr7&s1QIwiNh%ah4lv>$5;FS;I^y!RplZZT>2JS!}3 z2O&pAc?}&#@+f&qD+0c!O2NEepY<6r5Ru@C)y&y|yM;Y|c36t7ySGNlCG>|g=Zi=WHUY8fZU*{s7PI3Sv`tuYcR{F znMb{smCE!saJ7ZSUZm{ggWzXs5ONt z6u6l$?u2fZq$NywW6rOZy!9tS`WelrIfNcDvzvlq5B$S zZD&R|hOx7;yiAySV&K-5i&KInX_$)`8w4yt?=OG8FD;oUjLB){AP+o7*;v^mhobO? zRfvn=;(WaFB60ejTwh-0%U>XgmyK#u>~^i|zJf8Sn|lfa6X(MRJdEyV-!_x-f){$k zzK^Jzvm+wOIU-Y_YucEl$U6`@fKTM{OiU-coeuVNqt9a?M=pAc*;eiddi!L)3ZFu3 z^n7A8NljHKV!{0LHGJ&`CXY5KonNyCp`gcobG4J?Kn+V5w!PKS9@vl z)xREJYchm2vsf%8r&QZ?S^m(^&DlyMNT!`Rkm&HbD1~081~O?k-sLf#9z|4?nWQtz zb~)~t#E3s8<2>b5G-eJc2z5;4kgU1|Ll4Yq-tSYxeAX={^h?>dP!-;FW3CcHLRZJpX z$q)Z1pHLK)@%E6csb*jmlNF!po#gwnOPRB0dr~37_&MC_*!=$M(l4fnPyKFxvpD7x zqWl!$H5~Y&4&9+^wzu)>uT}~Kj@EB~->RGmsvo1@C&U5Ito7WJ-_2tCMyac>`p169 z4+qc3g?vmuUR?UWYwCe-gW=4Mm^ShrYVN+1mZRKDVtYMh$7KrJi8(0WOCJv+=4D z-2H@MPugq8ipXDobGYhi|YEdt>c?5U$Da@KW0FJmwQU zaDDbZ?*me{C;F}JZE_}{hX2o>;qmdx`r*#uVfcyk>*w7LuS-B_p!ozlm6% z4NvC~E7UtXAFjRi=!c_PMw2q`#Yu(U|LilbF}qL#uF2H@v2x253P}BChM$Lut0+Ew z3e_b4^eKOD*x*wfcKG2gmY`;cXC?f(HtANaV85wk_BZD2dTbIoY1B|_2?8Sa zk(=Dk4^l-15K1fm1Gg|zHN0hrGE~$^A%zQ}NS;+LKkRsA(w|aRkblNvvT^P&IbbNI z8)BIBQKC5Wu_CqrA*HIoVcx$#`H_#4K%leC-w`Nuh96mDbm&ucT2BU|1IwPkY+EoF z0(O?4U0HWjV_F<@hRu?fvqT*z8_jCX$_#Y(o(Bu%8ueIMxvn89>Vco|*!g+_FxU)W zDQWwlEw@IJakL5vFX&@yI8XIFFeA^ZtqF_S?!~LClaCJW;%{;xO_0fSH1Xyk5@!bg zE`Lt-bGpDCtg%01y&O;D%huE_pRf=r{pDSAa=OWu&BPde&Bre|^g9|237v^|S*!W} zB&;aAtYJfjEM_9-wg}N#0O!W+zM5PL7ppp1v9XlZ`~8&b6#$SACw@p9#ea0Vx+~su z{?VW#N5W01ia5(6Wf*XZa&2i|S};(1!hY`A(Q@&Ty3%R-N+?zDVI30Om0m4z7a zxW`x=50QVPJH1;aF_|1AAAwj%2^-itWiWwlfGT23csD6vt#EHPyn1lsE!gge#CgL| z%v*D&^<~M%9O}`G!duj|8AyE7`pM3t_|l5ghMuAxXzo zC)?R08HW-3nDwON6{&55C?`)AIiBhLQ{Dlk;*iYNp}X*7fl(Hbr{AZT_mvnp?h_^( zxtbu!cb8s9)M$h=L|Lfq%pQ=jc5HXeDkH}dXAhJjsNNbiF#LVn+GEM5L@57&&Q++p z>L_NcpM&R4DlLvP^a*hqphcD3I-HvkKi{lG$bwbB6HMK>wKi{lDGzEDe{ej8_MT6l z)jP)*!0lCMwVWd$>LdO^V@;(NGH&p9IMmDn8 zvXanE%X)caRw^ul6~(6pwPQRHxx7g>4@}c*)T)rZZQL)Gs+;iUQaU4h-9u__p-;p0 za?pn$$@c~nuXo^CB5h&nY;~AW;h`?jzQT(BY22Wl@2Hlw(DrbtNLJIjtwT%~;yWH% zMxwwquTF6GB79e~ActHNI`Y>^JcMDIa>x2%#A!8(E4*{)O6Pcypl74Ajv z=|`rIq|<9#$LQC8oDpY?F-R)bn zkYU7{S+g{Pw+h*Dx>h~!r~1Puw~*$1g>+xf7OQ^r%%$Dhn|j}UCDC=f(XH+~&X6Q| zv7QhsJvfcPk#{%r%~HS!q1?taMzh=lKESL>>_D!mQ$>9p)WMm6+%XJ0Ci?R zacbXqw--tCg!mYQUg4%3;5Su(=i( zJB0?ka{-e8M`CH$)^k@tjUYjkbS#zjfb}5N=2c5~&$;ylo?K_NL><)KPMWtevTD9C z&ryP8*oq3xw@Y2=JfGpfz)MKT3~Md_c(FA48w1ZLJ9_ze)NFW-(Zl|-MUa=t;bWdn zZpop5fN*7vcl4vu0g-cEyjsz4HlX{in=9lrd-qNOv}EV_P4)BLe4J)L_c8m35}9~m zb|9(4Vqi0ofM)u~uNPTWGiD0Qj>{c*uwmvT0??3NN^ZqgJcv#+JZmQR-s_`-yno`h22sZoV9`{H#u zTEy>fK-=)`7mDgPpP2-*n=f6!VlA@G_EKQ*iSORQvVD@+i;9h4~xjBzo&!zk~_EnG^di+W+d7E$R!G<7c%W4C`sfZK}C1 zGSS6v^a5WBB1R-oq}ck{uaC8xIFo|yzUC2oY`ddIqi1;pI4qiad6c=Gta4rcJ=!Ld zLys>uT5~>#z*aPcxkKsC%BPKx2(siC7BbTQILQ)6|FnZ6&mlpD_+6&+aeSc40o7r1 zvDl!54V($vHpViQ#+*kKhQsV(w|B5yI|OmP{kC^efeSI&sGJ_pBKdJuIhccmr7#%w z{k~+`j)yIxpO!1WXOE`JIC3G#&H)*aH92`w9q3!Kc)*0=vvnEL<9zO5CRcA zv-Rwxjb{E3Ov%McF@F1_OwPFUr|ymFqec;DPd_+;fo!ieCr6f5x$Tdg-CkC%dqaMK z+7ZEo4O&Qj)3h8td(i-`nHwzHAv=vqeB&#(BNxLj_em zE?3A4yzVF`j<$9>k9^2*y47XJ5ObAU9L{DS)o3aI(mF2CT@;I|S<>#chLh)TsawRJ z4FS#C?S83L3>T5CS$iILm(kN!M};ZZCj>XcF7fe`_!I@AXI;?M?=iV?CJkM?zhnvI zSaQGQNN)$2A(b}xJ!cm8=TblOgg#G+W#6#k|Jv{QM%IMakU`zN=>no^w+3!~zx<_R3lo=511zQs4c zwI=Nk{wE=)aC&6`0JpW~m?-49bHsHS1{b4`@;^*3 z51sFEvV!P;Grgoa%wO2y9|r|VOoJW39*3PvF$#kQjAa#jBU@SmHa93Nm0k?#0gK&n zL&cs;-8R-`rm(;}5Q?I)gvC*xhMXyj9xg@CnCzt%rF$Td=IkFBV54SdRvcfP=Qi|8 z5|c8rDk}X1@1d;wtGS(Bkrf{>kCyGr)d|bJf9+uY+1(uB#IK;wH46t4{l`7OR-VxH z>QjrdA_R?mbasx?T~5{2!}rx#KfDSqfIG2>5qT6<|LE!AHu8M0HHYd}QTC;E>b)`yHG2~p4}F&~3qRa8GoV$V#g z*Vl4xIW0Q-1)MW$7$ek;E728Zc{m7=P*I@-Q!{r$s*)IX`42jz^X+JZ?SeGV z(jjdVTfAuyj5(j_9udD2P>b%eR7@Zd>2L}`jkTWcsSNF*b`x3C%lMjM#MoYl2K$F1 zc4nrNZOihZT}R}Mh8+AjMe;)cqO5#}YHwIL^v;`P@T09?pN!>qud?9)(|YUuU4Q9= z*LP&c5#*_ekN6af&1QBujRNYWn1LTJZVqMJ7dS_U+z!xv$zr zJF(io*{TsaS^GOQ_ra$%-FjdkKBzZ7q<_5dtFf-Py-FT0lR^J)Ck-l1)nwN5)1hBk zYS?%^)_nUHjgk{NOgDAbJKVPOMLTlM)J3;S64>{lik3yu6ja&ZtLf?-JjZ@sA@RXR z6Rhx!rrYE3=ft0s;*oapHlaP!X7UnVIQ=9%w$`$10&P4GX53ZAdzJ=!3?&e+IWjvp z{O}$-5x;n!y`|Fqqy>dn<{@=}0f8K&xhr@MxrZql`~qvoK3^#4Cg`a%T)@hNO+}}OB+}eh&TDfu6$J_VRIhdioUKLU7?vAVB~OO)y1qHyIaKG<%3o;N z|IrEFUe81x)}6M{bp^PA>3d)Q!(c8~Q8{O3z2=|~R*f213b4_ZUXPX%ClTH2?gXlx zru6?F2G<(v0=zt$8YVjFhxBX&JceCLzK`d_H?mv|?Tjy@5ywulL1J_|Kb?K{dsgUC znV5w4nY8Vmd{Z%w-MeUW;}`|p$Fh&Pgq00D?aK1YkvO&{9SAptUd+e7Bl)=eie&TD zKOxEskqU{?h#KTCY;l#MYi;xEBY6`sJbpX|Hex$D)a&ssiXj13Tpv=e(v0mn9eb%*Ir>Lgy0Bd*xL>okdWU z-zumTRufwB(?)tCeXbUEWhT-q)n_)N4j-i9r?GhsXXmvGpcO_c)Kwtx)HddEcc89V2%}RI!O}pf+ z-A|r34%|Ycu>hfY#u*G_I;TtdRTf2qblFl8P*>Pnfs=MUG%k?X8! zYpbKPlP)s9bVj4e*~LXETX3mDi{&1cQ(>Fe-q!ZVwjU|=|(hO>ZUCIaENO5#(MetPl$fd@RR zmMgj*)`*%*e-1rPGtE@Q(jvIH>k3LF^w1$cXkI67W;M%fNfIdkeGhA%FxN*oMr$ zkHnj1@^bOCg+q$r9_sILc#qr0WB7Ib+Qfa`Q{!%X{qnLGLT#CZj!C0Tvoo^~?QF)Uzh*S&IDV3S z>DvNccWw<_`-g{)5NeX|7Ldrrzbbpx&j&Aa^&l zDY?XyZ|0V*x)I}b(b}PBdHvBEa-TG{O6x2?necXCaQV;R5aJ4bd1aQvE;i~?ZKU*W z@vkSimB&)wc_vusn2E=}`T9X^$$G-{4UFaR7IgpL(7NP_oMERF;|wg=kH`l$JlTI+ z3#AIAq~l^LW6qawI<*%+!?%l`b|-Ia4g7X?aNr7A&cTd1E~G(qG>joM^I)=G3IE@=w#L|V{%I`CnT+QcCJqh zyp{||rZH<2{zhKb#B*@u)YNrgx9#`>77<}L)M(M(DM`js z7Bs+3Gz@OxpDwjwU1pEnTES``TPqF-WI**rO43-nsC|P?GlOw;8XihE#wMyjD8C7-n0@*~!>ND6%bQPT zW>zjK@sN|Vu!0&Dq*_N!2d4qa&@qA--Te6T&Z7t%zIlgQBZ>lGE_w-L{2qnqoI}gc;Q|pp>9>~(NV5E9#(Z34FmS` zcdyFSpbli1C!YS!4wBYx^yXcHh2(Y9<~&; zC8k>OC2HIxL>o}^?M5LUIFFGN*E}HUClvH;l$_J`13*gMUNM>vsdDeJN_}S1_!*TG zsok?eKq+E!d3N=}@;>M8Fb#X=H-^~EoDxB~ezj_&o3Ey$S#!@Dxi_0y(z?&j)nk+* zew7zuP)W4pACSrWSgpF9ep@ zO2Zxm_;j<{N;4BO8SI;{w^g~+G&VSV-mY6_m(KZx3Rfm&zpkuBA~?V=pvEq$DR)>}?Ma_)z1yiFOBjTg1}V&m#lV(bTm{ zLPpRl`JBU)ff{!kFAtN4h!^W_oB8WPnl~FfTmJ#Svx&urv0{jQe=b9=(wi9>8LjNA z3l3PQ&dwku=}k7h#wvWV&Gz9ElRoLs$0SLeOPKf#6}=Q^sk*m~S}E@4^P7`$XG}Mw zx3L?S1;OuGEN>63V%CM}2lh+c(+Siz&FT8g#qNyO_4Tu^C}Ci_zj=EUFaIB)uV(3( zRSIr2nrEi!XYx>UtXo;>WFMQS<52X8!PiU6r`S~;^LD-zvZ=B$OpUgxh*M22=hwa5 zZf4+$03bF*jOH2Rq0_9?Ei-`5-v4=-rI-H7e$7G4&F=)5XzO>C=}17-@n4Fje^JOs zsGE{W`LC+moQN_pe5-$pfheX9fVrLKFMof>Rs0vaRUUnz{_e0^M|S{7q5#M$y|g|1 z0R(Hjo?2pRtGxff?9<*QU-0`^C5ur((pu``@TZ+N>=>X?5kQQ7tD`YD=OExs_=p~@ zuFZH^jN3SOo9|JQf_!Q{HmhpRs%CuW=-MGrzk~IgC!r9!8&Erks?2{4$#HmPDUgyRa z&`H(b!fe3xnAZ~}_9im;NGWFPFQg&o7fM9Z78aD5n_Bg6|Jr?c*)k~K`t3fij2L0B4YCs*1-8`zcSPyBebaJ!dv>K!}*Ab`^;$Xnd` zK{~_6cK;C^t#97iHv6@{>)j&8BTI581-*~k!N+x$UkW-?vrFLQhj#4@g2TGjW-dN6GZU5y3dnzUa7N9tWYJC7=!Tgc ze{r*M&3HX+Va2d=7{ma?LL3$k17o0Ex9grxLSUc491i$n>p3_v!+s^_YcUDRpO>e` ztIe4=YXXDaWbZL-odihYpxIhfV z`Pt7}^I^4&K1>X}nm}Vy80!(n_R?{q^3gY-aIC`W%_YP8S75ch7B!4RQ35~)zfvm7 zH1!$jXc=W?#zAtp#YOwLIFYk6lE}nb8YWa`2w3a>$SZu3wJk{O--rLSaGI%ln!v}7 z?K-!@+K*+AB|sZi5>Y6!kmu($=qpiWyZEt^=E%RATlfKQ@CFouGmUAR#6i%zF#c7( zze4t4Gh0gmb0S)uUA7PuHuVkTV z76sV}jvWBZFanJ&a&3~Vknp?p7@7**jPY3M1O)}XtxZbHE{juiij&ZYxaMXOuRe(e zx#CQ@*`gAenSUL<)@XcOepJd?GuqQl)T6}Hgp}55Xe3zD3ouBJ^=o&I+sys`b)lfC zKjmNvPJ!!POIWhFF{mRV)SkY~2XZO*J%*EtigqilS1ZKQ$q~ZEle@`PZ>p><3zHbe zi#L9LfZ6CyO%{a*(1^3&E!482xL;MxB*Hn;5!v+1U44IIdJ+kF$R)q4_0@&v9TFQ* z&`eL9UCS0*pu71(Tm7doX>3wyA1~!aD>)-U>;7B@C<$X-|Ir7R-*>Zq#@djww$DCn z!SGI6pECo`?N;=pbH&&+J!wohYib{FI4TcGHQr@u7Zv<(POBQm@gCNCT5HQO$7VoU z5hE?<7k*nSvC>US<)TX%V&R*Ahw4N>*gU*v6nf_5GLlo-g3KXLYl)eMHpZfz9SzPm zzh|c$^K0|7am5L8SlQUDQhUC%b~W1?(~r^_`s_FZ=K&BEx@m_2rzNS? zQ^`aY)P(vO+olsL=Jd4_tK1Q7H?A`kWhL5n=3!M!Ygy#{A=O=0Mg(OVRSH0T~G9A^D!g>+&i4r|AR;U zY0OxHLpgx9at@zpXi5T0oPa+sx{UqPo!-^Fxji_d8h2+{FZ|2{bak-9$H)IY3pgRd zphN@R;r=n1-(cbYBVGN^$6o>EGyBqPUZ<_=V=zv)F?*V*s3@QuVbulx(p}LqG%(=x zziCV$5J&=z5+G}o?|P#EBxHz)h_-q4-GP0dsJ9gV=}UlaaTm=^JE}40k&%({HbP=R zFSn_lo;>MT(sli)lT&ZBv-Sd$KDYxDN1!V=%od>1F_4R=lvLS$nA~(sOiBU_s1SmF zI|&L20jnuMi7CV?R;MD<*7fs0-0Jj7H~f`7KGCj~nGQRp+dmdiQ>X_im*HV3{NMB; zO!K9{)4VZg6M)hE&wAni8FyRq|4TMN_{k$eLiJ;@7U=KKM^J#F$@l7p<;al2efuaC z<&dkjD_o9Nq9MwuoTk^Z`|v;==}X*Bq~nrk@{qz?i$#yvoJVUf-5N~~n&O;;sc=#U z5ojflq@!%L5_{Ber~!Q2;>T$crkK(MJ*IZG-uBz`+fH4(t#Zl(x(y*GEocUp!!AS#h#dOCHK+tLCeS5TKJ@c#<#wB7QhgpD{3TMpw_%ASzq2d{bBh}|`{kG>H4tIi3vz?D3O$*neb zC;*V^>CV-IOguY4CRb;knS6WUJ+g2a4+AwH3(dLW-B&FXbzcj^v!68f?KzkA97be^ zX{@sj%SEbTsOP(OB}5LMKa;bF=To{DOIEnE2AYKtI7~~*!oF8`GF7c|yH2J>_#<&V z=6JJ=k9anWoDY_+MUh3y2ei|HJT{{xMBSe@6>IiFpz?3SsDVa<)&HLmPBW`*c5Ba+ z8+2+}URGRgj)y(B^Dr$V9IZTZ`WL=z9bIXHeg!FCe8|vowIQ!YbRN^JMk%!0J*}9&N|pUx?#Q_L#?~-2Z8Wm7}|OY09OYO3D~P~GCsd= z?liK1mV{6e5CbLfPjd~R*5ZKkSi+wp{~KO&PxznIJS-F*3}nxZ_?2E22|PQDsV$fUF!FGDF<3V+bu_9J{X6EH;3hnW(HHi!sEI-(ty^ zT2pwapR=?$t$zXEKPqsrJ!;ycYKV*rC}C6m1e4WOZ0redjbu zvitlm72WOMi3@~uFtQS&>Ofjr#@>%cUO`Tco0V3<&$My)TYwpn{>o<~x>Gg!@1DG3 z@Up7$^{y!LB@D>yCqU>E9vLau>4O&jkC!sWA05RiF-xH|!znVyv)D=e8rdHt7*Q&d zZUh$vchq9VcP+3wpgKw7a;7kIOLcU{|2>n`f5 z%BB!iZ`dtMk!A;nG9%J%G6ArprI3=9WMZmE)T2sWkJa2|H%pPjxT1E$9Tk~$FPGg> z%ix!Hx*VISA7FBEvGMT00!}5ga-ZTprpG8v;o*i~$`>Mvcn!=TtH|1kYlBt<76mp> zP>w~PnIhx@;?~wXIQcKPyFL^BhvgZY9LxTx;Xmn`d4Eef6(W*_GN;~(+Vi+B^D}-H zk|3aOGStBOXOj~poK?@;J37Uj#Qk0IZY#fY+F`^u>NeYFTvM_ZTM;%e0!aN0Olf2I z91q$&;7$RU3ZDezL#KNTKNVCc*?hs5TJ3n;8!U#wmjoC|n(k5Y`L(sKwa$Kt*(+)C z@5TpSV%`&axVXujJm9k9BaU9F8~t;chkK&rv5rfK6L4yFapk{}dq>W{ zt7bl-cVtN)dwi-7)?$Z!cO!@oGX(hY0&qkApio527$9e0y3n+_@PP0CO1u5zLqGp( zQU0whaQde^?2{Jon=rQ}_!VHrKflAi&Driogn?0hwNid#+xl7#qE4tmGE!CT-E>4o zL8+>&Oy{<Q|@-|0D_6zpRdG7x8kO z&lg}f5xk25GDiSz(b;+Fe5t7OSfOSfBgOO!aPx5k`gV;1LH^(ZJbA0gk^O#m`#Ngc z@u&d-he@JIv1hFuf9#|W(1R$+Zv6M=c{Rn3OrG@5GieqIuuxYOE&bq~ zK_fLzT-$)U0o{zEWEb<6^cjPk%8ri4a6n;oDG?e9uGCDK_GH=PVPhx`OOG&z=LFLm#~G&hgqp@)?SVK zhbz0fmX`7S7Z+U;{O0`@;|VUue)gL*p@nm^oqGw^W*~3b|IFaK*{ypWOimf6idm=o zs*yQiTrmCv)VfpdZshZNIQuxJALSgivm8Uj)kJ@-S|srVipY~S%TV*z)TpigiPrm1 zWfRE%Un-lA(Eqv;3=cJ*2;(T3l2r#xbc_+w^gd27#77pfha4O|X*n5&DMlLtWZ*wz zT+sJE4(>fCbrFY%O|#b*TNnBg$R75PlZ2XC_561+pa}B5_hXh3;j-Fcj_Oxp15`l= zptdCZQLFUbt43%a*%&NN<&I-7((nBvaq>+<&1buIu>WB6zoQ|&YJk8NW6>N~DAg0^wR^N2NsD{- z84?CQ{D&HcWxxUdp9+YnWC*gJNXp%aqF_^X-yGVi2U)r$ipRgK3pre6`PSQgW8m}AmEVCsuc-Gv(+=iqL=VRvh_mwR>_4!Z# zS8Hzp6xXx80ZxRVL4#Y6gy8O$kO0Bm9fHf?u0Jfn6M_Zz5M*$N2_D>nI|LmVTxS^e zlDGfediCCaw`yx|rBYN+&D`$3eNTUV&Uemt$7%&^JYVSE4dVDu!@t!K!~rMv*NgU} zoEIkLMwDx*k3g%k7Ut#?Io-FU2ng^#{Kf;YD&^P48StG}A&VXmj0mPh6DtE=zJGTV z+`pbn_gL~DynnrrUPo_$SNbY&FH>S*=EL^sH90x??(VLwtu3Jbi;)Y|XZ`i}0{(a# ziF;omU4^~60oKBYg)?}QtP@or_)?%6qsh2yz8z3X5vEBt6zKaEaBDCJWi|l3>sd>S zeJk)?rZ&O0wBsFxFF|*Md2acX4Ow@f{l^bL^p~_uaP=>Y%uy_tO zRiUh`ER+`Q?{9R9ena}3AM!(Q6O6puJ>~_>=kv?PBX~+C8Y*bszQ~mPVoLkFXNPGR z%2F;{pOAVAQBJ=|+h`4b|U5Fp(sY^w9KIk*#ZCpx}tkc&#`9hvsSl|9uyBO+n;vWUp4y-_wx$PVnP5>Fz@l z_mDJ5JHopR=U7*4L|jQVM~HvCb#fr}2-E2$#ohtaEhNqO4(g^brRy6M!QXH=K6F`{ z$&ZL2rDu$zS@~@k_gO%pr0Yre@_T7cyf|BM$M_b-!Zpf+Aw`emcyNM)V-IFiHaH~+ z=C!$PqxvQB}@J2ZE+Dj3|-_spXD%=Q*T4&Xcsrn^A- z(4>~L&4v*xJy<2rc$^fV?e;X#r9FE~r#YWFBK0+i`hRyn%#j*>_8Zfgv{aJXU4H*B z;`BTEu>Tt9*XxN%U<<5EKc6j6k7(B2v$uCGYgQCaVtk9CMxH`)0mKnET!kW(=2c?e zqvsO|i3`l9X6l>Py(BCH!t0?y=id_(+OIEPIW$4kqw{GndocjA`3D`yuxpnoY0iAoxtB}gAhrRPKbUbY)#qyde&PeFHDE_YJ*jN9)V{;I%Pn?#Vd z#>`GuLy2FDza=N<5(s+X!zv?Kxw7YLSb7U`0;@o^qj)f8kY=qn5Jr zoVI=*p}dfAZ0uSrKDPkHldvV?S(yCzN!JRM?>lC#vQ$pL6xL)fC@W49@s(Y?g|A<} zyv19m>GZqg{2mv6=tAHP2O0)+*xZJuO_{D0A z(|9^HDG=w*zYs@sk-bmT^}k%k!D9o{lz* zesAe|H9q2iNvWTyA}I#-Og|!I^qV>aMlCWo(S<#$rrxO&(y`x@|XB5|1_IxQ!o2%gLo}*N(9V#?wa$e2crrfAQPr1 z%G%S1VHiCUS6Z1nHVc?yb>ytzA`&+s7g{$Ttx@wcYQmXI-yCtI8I10B`NmPB_o4<( zSaYgav;Be*@7{qk_8$H1M~?S$BbI`tAAbG#IWPre(z?0Vg_Ha1?T(RtI$=DU5vioA z>lL@&KOkrEuXPMF$+q1(M)-d3V15j`8?POL7UKG=mSQDU9IjRzqO$7F^L$iQPX|uP zliW=gWAH+~*c~8h2ajzIHo97xUC!A++#LJ9&AZFUM+ zf;lD`fW1EYm6u@C{{FF7aX`JF>3k7!o`XtGdi!Dbc32^wR}zk0%PlA<2-zBcrky@# zX8*14G5`2lYV+{$1??vNs2%=)(hVm_*GK--QxrWIB;Ie}eQ_Y-9T)FNxieJ8 zlV6KmF@z3<$K5$BD#;G*Io6a>my{%7;gpWm(0GBQunhpo7N zD6JZ{`A&_Fa{h1J!QKcmfIR4N3Qwm@e~60Sc-bbnG$IL}j69$zJ7i(vEQ{YIY3LIy z;``@J81!45o12@2goK5Kh2Mc8$lw(4D;c$T#(w;`1JvaoZi>ywpnCKu^c$?Mp#kE> z$$e{1t0}_Z@L`lVo+WI6EyZWM;q03GusYB$G4Dw}_{^fvZNsTetp@Cv+mmntE?f2= z9&?Pqd?gCvIWco7;{n6e`Pg34Xxx*#I^hr0Z@<=Mp5q(=~r>J|v7f$XZhy|9yGJ$S&><1BT* zPH#W#P5{;QjX%`P%~Ti})L6yF#twfZU;uO+%q%QwtcJe5cf(~bkSvqs;SxNW4yKO9;Z74E(kP1hHDStun}3qX9BptxJ_v|2Rh z7P>6N40I`AZtmUyy^xmVdDu?Iqjs5FokNPr_9_X3g|XbbBGGuV z5`YQqmQ(!Z=MN)`MYi);Z!No+cZh&{swj=JZ>O*sez!lc#PWhj;VgtGy>B4Izx#>okx6m*KA7QL7#R6wCn z7`c&nv@9IqH)QpfYLRBBIMiEFv3bf1wTjW6hOO&Z=z{q{Ta1543lNYJdNtnp9Utl= zCxI}=IK6VQp1!D||9)0^cfRzGQah5F^ zN2949WuQ)=WI?&^o zMqi9lL&d}{|ImaXN=tHbg7Mea*52G_N`@uu@9!UP^l=)udM`G*08(DXw%_tz;o;$J zkSQl6k*N~}4#UM?%Dl$*jg4wT*dr|;(Y*`uJX9bJJ{*Pa1!|nhIh!LzRUBf=VCK)-0TjSe(i$v-4S{F z^cEsMn^sHw)7{tE*=o+C23ZWHe9|+`4n@OrRjG( zSWlx6(G`GVVaC`%-T;db7Vl|OxOn-`#Btt0E>l$G^P z!iIakqbH52zu%(2%YVBG%ZPo!-`Q*h0pH|Q**nylk8ScR#cM}!aeJR0w_cCKH#w|a z2cS&nw-J{CC%I-%%Sx&by2Q66_a-ELwBBfcW3v3jsf1zXdbp)N!tpRGe{8sD{OpnS zc6gFOSk$n@%hduO_2jFuF#P(;*Wq&_AhKj1X<*+RU0g&0dASP>;O%1;PGKd~4Gi*$ zi0LI0Q+j%O%Hg17jCQ}I{iOhzL~~t3@n@A3m$yAF(@vjL+m5YF(#xZv!t~<=+HQw? zO2YOFE~cZMVQ8$Qq+}Qx{+D(|Q6JZ3Jmm~T{3f-C-(nc}9-f37^lXa2drA)CJR>##;t``08rdAA8k< zS$%OUBCINqDSO6gD0rAs<0?*Z^@br> zf%Ie8lGn^Y^exS{Rt2$qy&l8hqL2urtEZ^+<0R!E4)@Rc*TrNH6$VQGZlSQz2ijSE6*g*u;pY5#z#%^*%M zK)Hv&c&z)1f62+8Y;BLx>7*mvX~S241M=W!SgWi3cN8#6X~+3mIVB}(0f*V%SV~qX zNtLc51|}ZfO1)z`1OmaNmRBZUS+IWFz>5CTXJh`=&(a6>->1p_{1AZb+;E1l8?eBW zf>@tn0Zh;}fWNoCuD;ng49h;ELS=x0Q~$6BNz;!*peX(GJLYFodD7Ta9zcQUF4#YW zF^g(^gg}*sFw+-6{N!F2{`tLEbIH5(&FVTo(@L zJPN4y%N*H~&p;P8R!bho2l~yb?^pt~grm`gJtN(a*#xOV$N20A)|_nRFzB9i@wWDE z*F~^^eqz5?dnvw!TJ^+L2}%#yuKn8vYfVS8@{wg-7}sl+SyF_IM34eJ*Hs&zyBsDR>ymp`Ue3j<`zkaTu^ zVR{IxC>3^pa43S*{$<$F4}ESeFX!U|qc?*U?@vz;3!M<2HWs2-*5tr=VIC{>#-_+yJ zH-Vacvy@KTwke%rz^w(yg}$RPN?zJZDVcKrB`bO{dMwG`@bW z4JoJ5oJ7aTp@$zfCS7+zl~u2u@2{41Nr~$<*SSz)4N{X|iT7%y?|!Hf?^7Qt5e;y! zAB+lSwtM(E!W1T#^_}(OiJpRtg*0$3VKbi+HI93t4U7y${`?ubyk?o<5R^?k&Ae&Z zS+~h!Xz7Q$e8@P&Tp0+swVP4hbe~C%zs<8j-e^fe(j9C3&+=*tHIrD2s)b3Ftw<;^ zxV^Ar&uS)N?n3>*azkamU`!ZO^^xlz2@VcyY7!V3=^dt-rkUI?Dx59cu?_e~gsz^i zo^uy*Wl?JK)?=dr-0N?V+U)CFfClaGW8H2kBNxB3k<$WhF!2a`{U4*pPV}Q&*`+cl zo|>l;&#^(AS#ssM14>zn$(&H7_wul5FtunzKF~fhsQY&?lv^<_jV6Js?bvfh zQP6L%Pte)sLBN1)$ez;=O% zx*?LBQ>I-0RnBh$QTcd9s9L0T#sgq|20h)MZ*v>XTH;SR#s?||U1bV=+Wi7LTAUK= zr(QE=C1Q%D z?Ci|vbgQSYkBN~n1`udkX%C2ur~1Mt>D5gjKhl1`SPiD;lKb)ed~mDN@kt#Di^oHESMkpTtRYb9l6D>9i9wp3AT zV<&(FZJEq|$6ci3P#Ebt@Mo9$hRIjOq~5|~MwKb_&t8A2;YWUDb&$7jeSLkoe%-pz z2-&)!R?Nb^?o>mIKu1Y}iT`mAAfX3P&V7+r$AIP(O?-B8vVhC(r%wth%7&h<6V)1t zDcL_RI)>_qX(9Bq$m^L_2?Bb1UN=9;cewaBA+@mKIh343&2z99DU(@O>L}hTA*uIs z6>95Q*aC`&Bzqjr&e*X=ss3gQLs@27BNq=>>JteMxh_{)H3a>~=u~&sS#S>o7><+U z@H;>F&j`3~jbysD@Hsb@Sk-yYrN(-i6Qp$nVZu*S$?#Y7r_4|EvAE8rLQ< z23`h9la6W!<#rB};a}L~K*$b~Gw)Yc(}ez|0{tn~bgjBhrsq?*urNx~DhoN1)qtHm zWa!tGx@alK+JMF(?gx49*9Y3|Or>GXB%x_Z=M)w1x(J$tN>(t1u`Y_X9U}c6-SsEP zO$Ivp?6;Xo7IB9G{VY$vA-Y`4S~#gWO+P9v1?nQLDgXM}@Z??+j5FJgkD`PRqH-7* zhM#PP^Ca^P#LT_WvQT;|!Y`yXn6SA;Yn+XwgSwgDormG8(Ys4enrf;~$HU34pKez( zRSlx5!Gx2`gVjsl@$#r`&F6A-8pe;J$p!!D_0~))XCoKWi}L@do9Szxc4GI~l({NELJ^cm61tc^1%S1^&J7Q7HLW z`TU)x8F~NCCp7V-6!Vpi3!avimQ;O!Qv^Q_-{`Y;CPaI{CbdljLQ;l*3P zl6ic#I|;Z3BsLqmfsLW3CwJS}pyN%hd|@@vs9&y4|G6=`J4J)D&Su=TFP_1EhDMD@ z64v1I`)97_paku7eMs;#OB3kZ@W-qlq~mgxLaA)b6KED&1tWJ=7p#Hep6~8ddPfn3 zeS0p$hS&Pn=d5U*JEoCQ;b)`9lAu-^-%I$gOGecl4Jj!pCFP*_XwaAv`yw%xw5@Fk zp#7#@I%QWkJuSeeRBqJp!?iylAwuh-c4xQA{M3a>CNY*fE>n#m@Q0MYvmWY*dDy&aggK*A2())!@dO6Jr1T(NFv2 z!?1+y%>C}}Y1K?2TQR!snZ6Z3RT%(*wY9a)TMDC%AuSOPex4?0WGn&-ba1&>Q6hmz z@1=@dJ9Y8PwCo`X*Rx;Y*xP(CN8Nc4i2C6@7l1-(_(iOS4G5%|Bp2RNT)dso@iqd7 z#vJ+CQZH`9TZ{&m7ue~Q(3LDkF#kfF)u!AZX@W{>zfT(*^;6c`y$+43BtgL^7l$i% z6qk#DfNs=V4A9ZuV_WJlKX-S&I3SskwGg*+X?dCE0Qf+@!yjPL{@;KJ2=Co*0}UH0;CMO+b_>A(qDK4qASRc z-L#EL?7ytAJ$QOMY!p=d%(adK?;hiP(wiJr-j*x$Y2bukyL>!dBj*kcY*yFq8%^SL zBA6NJ%Znhiv=(6dsG{al$Nu*#S{_>uS4iHHIO;F+BKo91@x?+>>EXmN3nZe&xxUEYFZ$@s^x zNlGSntn)MK;}rQipO4_hJ*s3bJyvslMWdRNwh^@s6e?CE#@I!_|8q63!V@K=I1Krv zap$`g0}-4DZ;+^SEBog9mPY9xNs~ziSgLisp5-mG@v99hgI1k#8HrVRdOPXVtqS6Uw+z_Wx>A5nj1PL=C* zU3Yq?rUIx24*zLFY#&}e0gD7MY)ov0gb&J$-ZqT2Ue|`r9hBu49SC`?IUq3(WjSMq zm&A56y-zP24CP1PFI`uiCRc4tukhgZ@OlZ9L&mD!w3xn3r}(vz}6JQVZen zY0qR|90->};Qh`g1>Hms4i#Ys7IFk`@fEzw@y)e921VRU*Rhd``*6!QuN3Z#m%4s? z!M_Vh`JLao-s;@?1M0}Ya{Ku_g{9mmlbyWeUD3P*9Sh&z%eVK9wuye{MBbZH&%il0 z`I~2>3iZW8+**~h@vA=Vq2*5O^*mb~&qiTWQ!}2P zi=9hppUCnwYKe&xCXu^35rG#Oj~o)+M6Zf|9U!efKyZqsr#!C3$*iE;q}f4e@D1Pm z*WhP8VNpGNbs+Yi)S0$T@A@Lr^;CCVfk;Zo!^x>iL16}6&ty2S4g}h1lH6xZ8JPGo z<1ciyk@&gBs#i$ON@<14v|(exvhQ?2sB>3Kk96V#n;Eg~_5`*&)fy(U6N#pn7PohnG$j1G zj9#5!+44H5RbT(CLl7?8n#y2Q+1$8vdJSuAdxHOL!&WN0Qa714+18>)AT*QhX0KIk z^6Muj=Ys@`Tb^=bXIGoq_LXt^hWYwDsi(Yyx(CD}^2-)HNbk67eNdu>@ZbjNuvM! zeal?w8((J_!1^Q#b4CYoy+O_#%bg-$BK;`)0NW`J7}Ni1U4MIVaBz5V5%auwfu@8B zQe^^|JU1(>1fSk{@Q$|mUBZQcoQb>fac4G$`WV z-w3$={+C;z!AmZ;p2tVEHn48)?!$Jdo_2*+c;0FIQ zhJWkiU;Who=wz7aHz1zzU;A<%nxB9FiK(3?%ZvYie*0(8_B#DLU}jS(KK~-R|LwmI zph$+k|IOdlaH*)j3*dep?)%z$!bMC7jOrSJem^k9;c^2(g8Qj_QUl~;D-!)bPNaA2 zF{}V6(sh}~41ASkFp>)d%;2$vlVbTly~5t~f~$LY!e zDkB&Z)D8V%3X%ejbvAqyaT@>`@)Z_4Ht0zGW}m9hmX9K|Lsf7MzPI;7^_9GWf{z%@ zJSk}P#l;+Xgo}qqdAf5$ef`D7g-p#uP^-j}Ki1y?#Fmzl{heY)Ld^g7DGv6ffPX6} z8K)-A78IKbJ!8%m01KVx;3@%N`lK^+@a};9b7D>O{WZqh=mV*WZdhXDURIs0K0ZQo zyFqXJweV?objWdiZwgjSc@vrLj$nG?b0==EagC6DDs6C7C6^kI z#~48L(15-9!}G8tYNVBSOXW{c(A{d0xHbGs^}Fm7+vti@0e|sYk9-h#rLux(1M*c& zn=TQxEql8l!;f=viS2j^|AGDDo!e3VQ6+PK;U%`smtsCUA>oqR^~oc00lyso{+RQ$ zqzxlKmxIRCWP;p~K-8KM(=BIP41VXL{&N1ctbHKO0&`wSJXm)IPtZiD<>IzN?M?e~ z2zw;tJ@Xb2w${kH-Mp>%9P%I}b{+?@mGjK{3Fvo@_FCPP*n;qpX4VuHF9ebC;BLR!N}xviH4>U&QyPy~bBVb)K-bNqKY`L=dl zbG`GpB+sBg*GlzLn=LeoAuM6N>(ib7nNLf(N4TtuC2}Wi1@DW$C<7hrxQfipC9y$L zMJ#|{{PybMO6Y03!Zg{6G~8j{8$7$^M!ws(?%ob;HYr)ayw25k`wNf zCo0A3QH{(U7^NpzEn zP8uDh?74U6=@#900p{YWFSlYR_dbM?Qyyx@c+Ho~6&IPaemhzc^}wB!dlBAS`Uv^G zV`IKK4S*XQM)cl+ZGC4)wa;rc2A#mOe-_*NoTJ3kalKeRb-PkkNlUQ6au32z7#~VcFN6a!l)eZ@W2rY3 zFGHT)943S1nu-g3G}j#KddT7!#O^}6@>3j9+wj#8=1-ArPXYuAB{H9ePJLUKw@^Om9=R`q)>}GFpS~Dn><@X#I1;+GIVOlNw)a zuCOz`MSqI%-IF8E5jLmrWYPGn-->x91E8}Ahz53w-tkh_n2m-M+#*mJghp^6efx@a zv}d>{Z?jmoVxR?!kE!CU)1O#Y&{Y)VILBPV zn2zx9@VP8SEDBPnjqV21{2y`uioa_-`B-TUk%@0!%P4wovN8SrQvtcn1MADJ*>_W#uF@Y-0L7$d>7^fRlM^skKQB1jl3d{2u}2KN zYM==fUDRz_J%okh(3Q!!p7V_0fV=}fy~~>qYoXhmv~uF8SpS(E3VqK*TPtyWsTM+f zb6_~$q;*)2dGQnj*OvcWKk{(0%mY8^GHXe5ur1^wjpb?O4*-bY{Fy?eKs3Pfn14$pAwZtwXjub$45Xi4ld!}_-eDwgdD!e8X zw;@!n&6+Y8;O}q8!G@2KMFsblxIbMF;qU^42VSOgl<*m%&gTY!AaVLu zuH_ux&H0{yR*83;W~v#j?ore8`>ptXtNk}%p_%VQ0t1Mes-;sbNmx&@Ku0)K)YQ~e zRLI*~lU(P~U%$9`dF>|(FmdsKAr1mO%b_703=D6rPNQ;duiXhWbl@&fXIEFCy2Ovt z`90Hrb;2VLcjFl;Ks^8d29y4+i~n={{yUYv)bO~tI2&0|unvnd?D-(Is7Z(=@xIE5d9n2bk=S`c@~2 zlDT$VWPB7)`&{me^@b;-fxMXmJmWU_C}KNIzo$EU0ooF;o&lx9#c1#j0I)%b*asec zbMv%PBTxg_&(AMk4|tXgsX)Qt{{(nbs{n9Rd@Umrp? z0M9ne;OFx4^29`SvIZS; zddVJcZlz7S@7_K3g@YjCb^3skCE~^z4`Azl?~26JS+1C}>+0;>dy9Pqa2T3g3k6;P zhz-()L?Un8yr3+RS-Bl;wf9G_DY1aa4D<@0D=j1~)3A-}_s&7vAQbJ-G z;N>C_k;V{OVOK_A@fjyoz<|gnG>dC)aoGtzLEFhdKX51iGBN4v*Q@L6wi`&*mRC{p zL2Icdi?y}2fx*HFWleRpF&v6f7X+4Re3bgWdWK45rowP{bB+37tKIqJEB`{n{M;OQ zLlB~ebmoHg6$^V>ovZYu)v#hCS{BJ*HK!@(D4s<3V^fheiFq|oP+@wS7lW#eZT_)wZ8p@2w{b@+nlCUNO#GV$on_(oNheaGAt zCse=fz+2xK(~%R`NgN(&Qe0Qby{pYbhI4#;jMK$u_xmG$-sJ9?@2v&e05tb2v)kd; zfL4$Gquk;0{mjL-wnc}lF#Nof!pszrcM;L-m~`(T1I@{LdlZE9^*&~U=D<6$*Hei@ z_owUnR3JdC7&6;ZoZk0)JbyzB`OuL{op@rSP}-#2z{1v6ui}Za$5CPh7<~S%n$bmi z8$aaDH_sai(huhu5sWcYs0M=gI|);B#f!?yN>-hUN;U&sU0ro`smU`7OB%SeNrKCZ zn(mGTNw(SP3?7^4KVCHzMY|LNXO+2_YmMlTk80b7qpwIFhc_Bbayl!b14i-OTsLB) z@#C-eg*9)@(jxGASosDJe@bQGwb0h(bXE%SxXkH zWnrn}ME>9ZF`9hBkr2P)?x{dTsg)ddQJmH)$%JEUd3!!W`KWcOpZ1cBzvHw!yK9N2 z2cfXrM2QpO0hVdLNr{DFpF8RGG`wW|&?y*?~iepH!T zll0WXofAMk6_lXs%mGOW?ZRW_mheI z>v?#2{Vw*ek1qJBEKD)7MHjjbNWsBq!lR%@HG79=I=a^1nqNs?(7WO7aR>52*BJSiGc64+#Wdo)p?oUZp4aIWPm?K1d2O!M z_UJEAWW9sHjMHklRa;wHp6`q^aB&@tbJ$44lb!h{vt}Qb8H01K#iBNJ0Yn>O@|N4} za{j=85cWKG6IZtnI7PmNY7OB-qLi|IT>}`2W%gO z6tTVDC1W268*DZMEDX$l)SHXXGi0}kZ`++h>Z!%tSAVt_K3d#Cd>SH%(xiH}B@|cf z<+?8C29N*Y2CU}Vn$l?L!O?i@55U%FWwqR#nBL|Q!_-3n-;8Y{k^+o7P*Tcc3aD7W zKVN4L$W4Yvrp?Xk*=WkM8=%ysKUaU81uSGx7gtT?YC5JrGQ*=Ot*K`SI}7WRGdkC? z|LDj_dpl=SS|UukXHmR-jwTo@|{Z8C0rUoIoo4SQ>3sEyLLN52V0P@fz2y>1qw5&n3fSA#f=QbvZR3 zjpjR|nh|i29OVY%F4&08mPDL>8~Ev>xZCzSTCc}p6Dx~-CQFzD2n$hCP_QJ)KPBEh zzX51r08|ikn5~@9sB$I7KJ!Uy*t9DTu_SMkN%Df#PZ;jNf3eeTf@u;Qy{;f+kek!FOeUCRfS7+x+loHtmxjKja;&$Ie);SyzN>Q-&EC0JybF z`6*(xOAqF1ti21dM`WxXu9yZrC~nO3+(lkvmk7E|k*w#u_JYZm$Qxkawv}mm!T-RF zS6MsFseyeQfJ!vtzM9uAKKT#0t1S1{XWu-ce2lJVV1OOo`Q^(Om6hzVg^m}cs>EEr zv%kjkO`>(=C(odFsD(m>l)ieCHeY@op6Upa@8pBky%je=UZK-cvn3bV`uaLB&45?M z_8Wk6ul<2{O(J`A=F|b6R_8Bpu63~ z($x7K`0^{YEmd#AT%li?;+iDg8hLT@CwIRIf-7cVoQ93BF~)b@@w%3DYmWPL>d|OI zfu(or9JCQD$b#NosdnhT2MDHa2#bnJUd*ys`y?_cG5Z8`Wfs|PY$xd^A551U046?G zi##zCI2H0KO#)9R?3k`sFnI5sv^0SDRtpKDdmvUHq2AA=$=x#W&CSe?yH7?r+hJIp z)IZPs;6-OV;}0>sfEqN<@hjOB)PD1tsQI&x@eNlyB)ydp5D+*oMsskm^RQPA6a8rq zB*)XSv$HcYcGsqiS?CF{vkwF5@+S}gy1|!Pw&8H66ZV9Z6rI3LD1|8tV=(i36%|ev z7M=r1>yX#0tE*!t!VG) z36w)mjxe?U7dPwwpyy!zTz{1}F?e{rxWP z?zNSbuUJ@sMt(6BsgLr7^kJF}E0J~Li^kV}tgNiDG8*j#E(#uwC#&q48^^kWg1L$> zJ=~uGjIzNG6Ol>>JFiqrzG?+(EcKq)y)s?2*gPyPgAUMQ(!F^@XJyq2@U|&}9OkOE zd~cM(rPMZUHLlls*=cC9nwo?+8(Ny97zxwT)8DfsNgO-G#KbU$0ZX;Sd^lde@rU)v zmD=}V3s$fo&C2{&zAWM-1&YzAJsJa4!&HDtlmBLbmPDfcvd*J5*j)3;`A!761SsNQet70sx$;ls{J9X~|Tdc;sOtTJ{CzD4AxP0k=I7&f zFg_vt^r4d!v*G!E(oWiy^o5)!0pJ)NQsTA#Rn%Y7^VOCA3qr^*z{Nb%n@ksIB7PR; zQ!jF`{-Z-;QF?`r?GK=e=?s1^@(j9`SLMC6a4#|u+!e8I+@UoOs!Rts%ENaiG*ar@e}Yu?^HKn>+LB64J6BBE?p?7EFW7K<;>6G)L6<8`-n?kaePeYA#dn+Y+IX;xtRn3{h#_5llZ-`UWZU7i5KgGu}Kv5-#8H!^Ee{p7 zwM9T3@DNyIz32PJFhPy<5Xb0o(ZkphB*_(-GYjMrFk^YrO3kY&i>xR(6mX)7V&D!9 zo$L2mtB*|d;b^Krm5HTjD--xVqxGAPs3OohlAmcxrLR51S1F4!LHgXBc`0_-g!v)C zLicd=V)18L)Qq1CS*55G<2x9}!@Bzz^wp)$d|Ychn2jZF5QMmt=_RB6H28~r7(}{B zi=E11beu;(Qq^2V$gjnLQwPzAsiNg}f)+{v?w>OCZ-QeKOMmPvOyX1zza!CB)F+~j zLW{B^-r4FnJ$Oo4+5(!+#$dOw)WaX@Pj}^TIFs31S_Bch)_ylN{<*-5VER+84JK>g z6Z-gR04gMh7(+c{_;+X5uPRR#9Z6wrSzp7Tys_;unI7+YhfNdCJBTx-j+PtaLU~W0 zLT~TiB{b}$WE?~S*05448JJ|H2oun#J&n4?a3oiLbOofvYX0Ogziz-gFc?MJ4smrr z$H5V>2Rs<;JjBVkx9{I|qRrTpn*M`Ku2!zk&({4I_E ziEz0|=}6PF&N)Nu45EfYlh)Yf* zDf%3c8%*}se^ZLb?ePk%0ocis9%9L{Tb3%$MCm|DP4p~eySPQVw#h*<5y6PX$tX!4 zrxF%j@ry~a3uP}A=}9TXy~<7h9uYGqnraL#?s7v6kYQStKZ`!{_h@ zTEkxN2FFeVx73qW+MY+#1NJgVThOF`YT@chdIEX4bmlEZNUg zy&f+s^}(Z;*!uC&1u?q2Up}|I*-sD{YtBR)q;IfOo6^VVp)yJ)CC#5Ex`ivijRSwc zAk5L@z8!>$gP*2#r5mtZSs$kqdMFbSKLUy(4I(+zTH!u_&b^eB6IGcXq|vr+`ohA^ zI@5?J_P)74N}PI5fPA>u;>%0JwmH@)OOxkO#X1x|D;`MUohB`(-|Q!oKuzs@Z_q<< z59fsFl1|RbH6zyN-d0roRKHnwBZ6|^K!9V1Bp1r7^$2C5_`Yz5U?oDR_O-|w1o5#@ z7IwJrSds>vMlA1}3Z;obeiB96;SwLnMO=PzbpC`-7|5W3kO4g!Gm+!m+84i%AmGFo9c8 zMW<5s`K@~ACHV}APXdDaVP720=eQ38#DrunRZRS;FGM@CiwD`Gd2!shJl#5 zbN_stFKns=G#xkj;(X+`Q`@pj_9BBd~j;HfG?)DNVdK0x;FKeOZ29`gtSC;A}e z+nC-uQsjP*aydNuNP1lry-j3xNz5hCwaH$!wlLb~KR{G%3m;3CeqnPf}Ee`Ynscwzw}IW8)(RB+TL*=obpR% zr~Cd4cI1#IR~yZ4FaNUiF-c_6`=f(9Zu;A*!?AhBFMWE=9GZ`Yz^(RJu*{#y-8E2h zs+G-Fq+_s4lbZ+E^IFLR1@knfZFofW*hrKerjw8TRxBK+$QSAFO!#Yy>l;u)uz|>V zET!QJ7KJF_ff*wM=CWxSj)5iagJWvb?(@sYW zdY#j?7RSWNs{L7jpS{<(2Xop+%^5WCL1Q}}>4X9dE{+(b-_wtFhNoWLibB4~DFg=f zgk#XF9+=Bh13G;MlKZ^oQqkm3TE~#@Nq9*jiw`V#E1Fcif4j*W^6>KJ0s&r>tbA%n z0Dy`I^T*@i*XFj_hZX=Z;s0Y}F8{H95zzlUjClUB-*+HB?9c<3h^uK<$aR8a|2cmp zC#UjZ%T38v@4;lLE$?MJIvd-+Dpdu>1>K;wPPXYjog5jhB+=0nE~b%O{RO#KsFLd0 zY|y?MmYW*i(-qZL{pG&x0i9mWCx%#&teoYx*N6q|wsiD(U0; zT5Yl*=)Y81@}4HvFAYz~wAaP4(M4?@(&?JC!k%ic9{vGQk-2k7-oN8AfhIN`=-Ok! zHUPgB7*yx9M!kq+RvaM?kO2L;$5nEPq~!gDaLSDBzA_S@ENW9G{uC$Su6Vis2*2-3 z>q#GHhgAyZ>a_0}X8eUWMp#ZTU~VEpEKteR_S%;YtVopK>~I`xcrPI2>COj?9?Om4 zdzxX@_RQYjD>_6wFh$bI;G|$tPfB;Q(6Z^n!U{sB!)x^(eDElI^Zcq9NATI%;CtXu z{qMS6`h%~`j=GsR3e6@fPaz&lH-I^d1h#{%^?vTzHiW-aJ<6e%ScqqI5pn!A+F;VgS`t3NkN*i=iFy_`&PAB1=IV_6}z`}fhSYw9{4~v~{eYVslqtycZM~rvWrUP3v zC_DZrzDjG{>S(8*^4{n#xOz6NliA0DtP7<#&#~*FF(PbzamaI~zR>`?ry1eNsp9_0 z9d>L7Qr^;BHnMKpkz>DNpTtF{F+ZDCmJ*GsZ@*e>>Ey;(VDXF&$_CuK__$vZKD198O<6|EE}i#QJvF_6rp1Y2@s zNkZw&L!mMi>%?A-Jz}zUxpHz4SBWZ`V?@hEkRHIodVpAmJKLmW@r}zRV12%c5rI%^ zrB}`4U~EAO>BRZ2(Zkfr0CnD!{1fn2iNnW5PeK5OTh8BUxxEmhu`=m z=Jq`M*PhN6h8bZBHvCiu2lFMhGmiodAx(|7tW1U(+Xy+y@Hyv`dn%$KiaW5PCAeJd zeLWt2cDha$It3yVWq7(AWUqU!H!EQrxZ=?N5y?IiK0Kz4hNH|M?W{SQv|OpZNCu+S zM8~uICemL=^lKGFupCtht1g$sOC-(NR#cGsld*Gz6H#GwR*} zD{*uFUc#*$YMJyXc=r#O)dC9JGI1LP{k`;2LDP*Z9lbJnUK!JO6rzyqwJqGG-x;F@isWXb9ujjm0Q&HP_o=prSym62D;T!c5>`>>LfTlAlF zkc0Bz$*nxcUw4WS^Cll-EvTMXI+f@*Rj&YZY^6)Ds60^H)4rgNjllnAO(Sh{=vWsI zo9L&n_-cA!tHTuv&KDMTz{VU0ehqFLyqV=AXHz`MtSk*2yeA?S(huuA2_B9b?J8PW z%WDU4{Qli`F5E112#97Z8VqK$7#X^~{PKbMj(E`^2{qm!T1n6qTxYlMK9hUTtHu&@Fqf{NbRCW>x zhv=?W%4%J1MXI>b9-|SMKj>SkgIcwn7;SHpWWuy)wvbxOsCN1&3mPLMHmYJvc9hI(jTKFgE^qUt=WOdZzm(@EM{w z97_&Oc;Z4chVP;8`m}rrq_L60;bncwZD=WK|~jNaBQM56N!R|aExP+UD%b#4w&1ISlrN^8<}a3P+2V~ zP#Z0w`^zi(e71Or;Lb5&%V=*De^@etHR?mX(c0V=0t>Ja(KQFkl?%N2Xs*ieZeCOOrZLYq=WAouPs1h1+W8%X&R`;#_J@<9@_*a{RuaXf-}Dre_H)CGi$ zL~aA-VY)^R!QkB#x7|50$sa8MH`EAcQw7dUu{-)DPTv!LPOiY>?TjVQ%i1f5akH%h zDJ1PWUJU`l02+(gi82)}v5;^QL6OrP5`;W)aSwpSwO;;kOg9-yw^kHolFTEMZvfMHLTWpA=1u_!wm>pqN?X7sAh zJD9%Lp{<;QBLvjeRqtJ+)YQb{oZ%q~`TPmcfYC908iUq2 z_$=}0CH5}9nB&ciGmG3q60mTN7spnV8fdv<5$d)3<_syliHi%^`*oe3Sx(2ZwBZuJ z7+?v3Xy<|Gw?aosDngYghzEE8;SH*V#_@OfkhlDZMxHU&hFfv#&$HIV0sg~Q??q-C zGb3hkvSV4S99%*&2JrU1>!U*Z4LQAJUjTp$U)TV+Q3!x8-q<{(JgOcQ&PSX7#V7p# zk(z8C>^an9ODe30i45fVp`Ow|aq$Muosu8yOoJ zZtgA{1x{btC;-lQsgBNjuC%A)GNfP2zVMphd+IniQug;+|It_hHuHqmP2Qjm7lhmf z*Uvh7&Lv+oe>yP{S`;1LI^Y95unk-W&tX(W@M z+}&*d?rBCu$cgr3WOgHeykOdDcnF;|0q$EZ1HX&wYB448;vfz((d?ZpHX51s?e`{% z*Ae=MFYj2Uu;2F}iVd;khHa{FmPgi=tt@7nH@2^_ND>{{swW?K>6wLsxmVj{ms@?N z{5GL4)1NscPnqw!MuNe0;fr2(!?1XG{lbZvw%uZ;~B@@gXY_f zvyfcmfw-Zp@{b46x~`cVMac-LhTKn+c!pm)&jnEukp0+?yUyq1v7pJ}m-^Hl37xC8 zw_38f5z_UpzgykR*j3iP*}YEmA>bVW%?qOc7N!UB>#Rq7S^ehM8UeN*$dG}24VguU zXKw2t`^o6N3bfR6Cgtnx9t=`=`ljZ(x;t2d9YFPOiegeG#KoRt$MsIjBbWlVLI93O zII>2f9!@gA4_*GZ5e#YO$)Q3tRax!u*Y*IfI>HS-yC3`u{kM*Vva5ua+?Bq>h7pQX z%D>0;lh<+nn}JTFE;+)j^QjaC4*);#M%;u{Jyb9M?ENht8~-R3t>tpL=3!wuSdbSo zc@8~fE?K16KF^QWyK^`Y!HIl6IH=Dqpl(48QNHM;SKZOB*SWmb~R#DOw zOdrR(pP#q&Ri=A>7q$8ETe*PWJtg1G7c)A%?^pTZV5*03EJGi3&KXgD6dV0Sh8qPr zN}h7)pxin}Yik&mOfWoKC~*C%IEG~xtb>PZ4hCi8AfUS7tlT~}CKl;hQaaB}qqWVn zBA$%}VSkcOXV!5wjp7bb`L$}G&SK8%bugTL=zHhN$jFAy>GtkLA^ZAfX_ke$|7=Wu z$G~jc`5o2=3EGb#;;jK?g;mnZ}*L;5o8^bc7>m5mE zyF2u+hqc1b^kmD&{}tmo%7D3o2r(cz5Ia)z&qpGuI_{m+uAF1*;s*aLiHrypjy>D_ z*&qQ(nBT@c+A$wt9sYv7{QFUGb;0n>tK4rK<_B2J5Jr>sHxI^A+Wj56Lu&|mPl69~ zk;jF7TJzrY$K?OuE2I@5zsQ`m?(kq&2U7d8F)~lA_+~a*3;6`m%Uy#a2t?Ce zZ#`43#6PO5dh5K46FKLLG^-YYc=$4%29IU+6{USofzW)Yt%HkWrq!39-Rul7_ZT5I zwtp>WWr@mK652A~R{x3iv z+=eLrDyrao-HHazR7ZeDw-H}C?)9qx{?Ja2iz7;u%tZvefFgIOA(Q9-`NwUT{LA^z zA#!%9#0Oj;__uffj>QL>%=}?tb7}#8#~;VliOUNM(a)EV3Kj2bMsgjakWPDbRc;NFjF=bf5V4POC|4)1|FQk5qb`fArI>}Isj!=|O1V^smF zB1g!<)0hKs9$8>98TyYlFV69+lrd2r3k3&+5%n( zSadCohuv_(Z19tv96uP@p!q=-ySKJt^Sjjh)e~BQm?^srxXrWhSWpjS%)TKbJC;95 z5K^eDa(&F)caF);y1UoL3sW&HM_Bfps`~s28v2-r$g>@|7$GBQb+F}yJoB5$no$=C zYUpmA7_ZSxmIP=&VwL$%&@{%OZ|7<4t1H#{0-qt+GRL#1_AE=T>R?CzD%+)UukGgD zDPW;zm1}B^{JlZHI!GY(_VnhdUuq%kTzy65p`hu@Y^k|tnPfWJYNyI7eNCG>(sI40 zfwxxGn7a?V!9h~CuX~FZIB)XF}u)lP|W^JW7(bE6``1bzKU4V_! zntLCm6tMensw_!Ral{{fIkzQZBXw6p_+C5s!D=cC9q+)=CG7)IrEfDE2v-|Jn)Q}> z+z9#{QNANSR|Ra0#j!&Do~E`J+|Zn_ro7(>&F6Hk=vyzAhQf~#nRz2RrQfeblK+BE z5vWcU_$}C}m&Zwe0DeTAKe(U@7Ioz)> zFihv`Z_cYkSw<(3H0cO0mqidZJkqYFd#>cP1CoD`w11D1ibOui;q2Ji4n|$qEcc&! z@G0%TPOZa>iN_;j*HhAP$yClTm3It`Jr<;$Gj3}SfBW?ADjVIkOLqF`TA zbO2G=ub$2C#N{9geH*RE1pDQni`a?7h#RyeY*Z+k4IM~-1fazdlg%hyUTgTiVgEqMWxq#tW{zUn~NsKHFZw6Hlz7$!wkFS z4sXk*SG>#$wyB4iDAWTNX`S2Wqk6BW`tvBpj1XwrV^ZmtLn`U?^!0+O{g;~Jginwg z1<(1*@hhoYK!vMAL(Rs__E(DgDuTtpAw_~E;)}> z#dk>Cdw)(85RZ4TnLP%p#VJeAegU_;vqW57v05X6i^h4Lp1oO)&@SlXT+ zR+6g?Ymo&P$(m=@+B!bOJAEEsu{>SF;ypbC5^6s+Xj{5whEEnXyXf@#rq1+sYQ2YU zarh(W*}?1o{to>0k>>k*GRn<%+VYKhc1C0ZFXWA(vuqA{l>M>JvA9!Av^VF6(hafo z;NN}(p7VyeP3bAYELByf>&^FqPHDf8Igqq4d1erT?{!@T&li?G*|Z0jwvAS{%t4)J zbDDVWFFI+zOs2i2>ixPA*1_J6HrBcw_o9ljxoO{8A7!4M^PxfYjwzcDr&EthG-%-3 zN7q@?yQ;~`3;R+EhphJ_leWb>j3TwUTKMHAmzSD7D=P^7?QPz2^ZfNF{zWdvZo}<2a6!(Cdm%gsZZK)2_ReH`HY>$MtUEX>2_N&O?+!l(UWTFgbaOu^fgK+?+GE>T142 zXUVUUg{vq&EdXPyb`z<9?}_qdctMnIi+dQ7#C4*)!E>IiYK&J^1pF@90^a+Pc-^ZL z1L(+tMNyr`v(UEuJ>u~%HjI$ze434$;(}yp?5Cf4^X~Iczn(q;>=g|PwVkZQPZQ= zyjA@AWI`s=n5PmW358YH{nhx!$~!8w;!*KD?ox+(XM=z2p2SNfff>@PZ+|XLJ42Qj zhBvM$$bWb|9Rx13Paze9J<)Ww*&y4Aa)zB6oT$L;we88)=Di^$UO^yZ-))Q&J zaC{q?=K4nMd*yyW=tebY-iP`=L=;zhS>4{K_wpbZ3436E=U&Ta-G_$9>cHp(I^9Kw zJ`Y*N&AKtxsgtL1Dn_ch!z)ex=XQ>qUcO9S`?BrBS+#M5{9^7M*S4^&t-RiooD zztH~baD4t}6+PO5u!pLAJ-ur;h5atGk#5)Q@KQ!7<)9JQv#_d}>FMEBYGJT#as?IL z#SCn>@S1*cXQk1t*8Z%W5DqP`NX+3X*CCm?BZPSyn z>P>Bv3&z)4XLNkd<7HIIPd1RAxD7Q@TM@MRa^>ZI3|!otNL%jQ&=B z)D9-^y_>X&X(rX{rY-X0j}9R~xKhC1K)>81YJ$nBvI z_hES8UO7UIc1Fv$6;(_t+5gH~8x?025gZRZP;@-32#EpqgzTq3}3b<9}K z%rO_3?C@E2WO~{3nw$f-(Tz|9mY#N zO_Ivp4pBRIX!BYeUjX(-lyf1T?aN1&5Ul;wi%5`Ec?^-ZqD7db%LtXE%v&;%b@_#a zG)1NHIn8mB(0U9LXsF@d;G%47^i3h*^e$*n)yJ@PacA1hDzxG=QdzTyZE|^=Xrb-zJ69zlNLY+4KcRd{m59 z`iG1rZFG!f{8d4o?}cP6fi;;=k4=MT>k;nv*mA8h@g^=j*gZ>#<2a$$jz**in9Md{ zP!%(h7zZdf8JeG)cU1mpXYYWWf1&nFC%oo_cWg8viXkfCJO|NMwn*^`Cl=|n&84wt zRCdbw_{3OLthwt?BF<>D@wrW-DCR)r;)qgQdaO#PYqyLw4IDuhuP?uh$VEABg*zrw zZ8hU?JD&ZKd1De;wIc&P|D)V+9vxrf8FOC1XH+4lS=9}sQUU_^29`v=+A*}b!hS6|OhOuA6na%0NL8 zL7hQD*B9r6~(3&hNK&}NjrNs^{Nd7RR zqSL!2pVe-?y{DkGffMT~?a;+h;_8XOX>c+%HrR8QOD`*GiQK5suNE;`8XGQx z_d?|o{GG73Z%JT-&#UJ-+&FJJv~S@pVFLS^bQO)*uIKk4bw@gnfZp#saacm3yADIo z=nb!|szLkGi-z_3y=P5;VW@EVOvi`Z4tu)bfX7G!O1Tn5d}oNuqmZObJ`sr=y`z$* z_^Q0)Hyo3l9t{VzN3OvTU+I6+Opb*6=G@1nME?%6^SbtU9;7Bx<`*vfiybbCI4&Pq zJ%)aeq;T7TKwjZ?-Ntjg%o6%eY|T?$c)MBWZe~+M!njzlP592i07Lj z43wyG{29jtD_sRJYUekR1T2=3`=f}fniqzO!=~`Dcw=x(3@qF)RysvHs=dd^Pp!&Gg?RQEf1v$Qz9IqLXbe2+Y-k9zUo2RCLKj zr$dIRj@!V?t)&wiXuZ#PES%nYVej}Vi>#%y9Ja|J+u<32yyh}>rFS_E$?dz|rn+Lh zyUWOjXw_tInJk76tIqu>H`1_pI83~v-hnk7|JnWV@Gp}dZfKzP_xSjs{hd**?qzRB z95|07DB~>YOn1-q&7nAqIE}UTny_+JxB_LggpMmFRq%bBgF1v5jn8Z^P#Eoo!6>&K zIbM8ZBnnO@@Mrh4{*?eD);T`8*T{qrdzLpmKB zSHcntr%mS@uXd41`;Hz{YnXc&e7(qP5kZ&LEyC;7x)FY{5ab>z0%1kn!gjOn>zbf_#>u`u~_9Yu7)wTlqd)&PYsp!e01<`FiGon?`t&^X&H}h2P zS6({3R3Z5U3h`68IBViY^ai{tsniQ8!LH&Wv0>X@19uhM=Yc;+knbOyH^e4;RHl@L ziFSUS;__0Z$}{eMy`UcXugRs0DX zr1nO%poe^imz-`I6lhnN~1o^ zpLbwCi{1&T+TxkNPXI)8o#86-PqP(|qwg3#Wl>Rr%0qIMC0TE$v)~S}uPIV#vIR{r z1%E4}dmDYh@dc&4?eFp3%(~!5^s)~abGjRQ`}BV<*At<<;p8?_!E*zrm-#Y>Y%>{^ zt9cCFg}Z;F`+G?2?WA{K5n%vJsF;`-lTcB$kRBuHPRQiwz?Ms_oZ)e#k?|Hzo2`IK zKlySUQe|X@GIIb%;!XZJ?5VW!OD$T~Hlyw|Zpv5Cwa&E?Gmd<)5dD}k@cJL-{gRm_ z=w!%8d?Mn25=1d_AyMWhq2cW0iS@SFuSNxn_062VF08B+Uxk9+;3wzmHH$UTFM13rgXm@R{v6V-+vN@%ce9 zw}Z{tluwX(-zIzSby@1~FDbA(EeV1N!YLWP2fSSR8zM=s)Kd~1uq-0#h_VYJ^2Q#a z6bwtb(}q0L`ttT8P3RbUxH{9iS`|g}JD%E9;wy{9NS!+R{XQ-?*2g%sjMP8pA?0Ty3+^YR)BFg9Tepi#rClGg|AL-d=Rp zhUzpu`;WA@>>YRo6I9=r-c%HBUEb2Dx%C$dBai-|iW!E93zsO$hKQ+Di>EZZ;|%8i z4p4CS5Jm%aI&B|Ao2v7xN{^*Xj>~xvGJg-7@m|rW=HY5o7Cu9eqG9^3n3)+@S?mHa z>UxyD)ZyjxGJj_Oaj$Hr;mxOc=Rw;SY>hYN(AD$fbsul`H5u*DE~!Nml#RiiqH4HE zcIrKN6Se-fvt)-Kelpb}M1FFjYjp{=KD*xmyUyXf`6a`2er|C#GV3NbAYw73$c6XU zmQ&-<$Z*}xjZ8qh)jBWb$3{oduRF6VNf}~ao;U*^3RvMj0*IJyB%e<5rt{Ss6&I96|vu{DAf5oI7P6LbHdD6JjmqJPesKph>!_&vRJW1%4nyqH@6XuLBn(}n!5Jl+Z$`wYFUU{K4$-zFNW>#U2dLw3|odY#u@Ve7L zxvJ3MI#7qzh9}vQm&(e_YzAI>qiX%JvM@O7FHe{s8Py)aHD-I` zzGxToh;&bvjTbM*h$&s;8SPhtVE!bw$PO*iPSJ-cozyZ|o&9oZm+$78v&HKzF`XpC z{Id8hmIf|b$N&0SeFqqu4IXTK(SKaZOjnCqO|2lp67;NMy#8e6Ht%MPkd(R4Lt|G< z<2HPOicO4)aekL&GK?0O?F`a2-G#EooOR`t*XLG+jr}5F=?}y8(*Cp2eY8j4ci;S|u!5}e=ceZPrhtg^uIeS98- z3nINw>Oi4;=6~w&pgQTBG(3C8*I7sm|51_muej2l95iHFH`e_MH8b<zgucidm)6dlQu!wz#&HnOzfwvL#T!Kq|aC`>Xw|DHxR|2(?;x)YSz;yCiKj zl7#MTc$rFTF`u`vspb7rp816s@dh5?M>V|X;Qs^gPaL}Cg)vH=8u{r#%NxPuU)KcR zhzUmBQZzr($AC^5Ry)27{4L~`nI0^@FGq9Xbg}Lkrl2K)cf^+0LE|I-v9sr literal 185036 zcmY(r2RxSTA2xp3TV-!5Bzx~YlD+qqP4*7iLLwuptdbopIWxIF93coZ_`Lm5K0a@DT(dQn{_Diy)Yn5d_^27ajg)`&YUz z{DI*kucD8Oi~D6!YXQEc_Ej?W)$?%h4Y2XHM;zTf?%H$t-0`-zclUAf@ZHAfkVX(D zL`6|fKk(_#X931!1AjYLn^adz@!8p#u3fu@B}azE;Y3Eu`as8afGxfso4qTNs4pSD zsP+nZ?|f0MBJ-5B92p*yv8>Jy&G%hi0e}DAX&>^Kdn-XK$~<-~DJ}is*Uupd0g1-# z*1dLt%G6X6S*FXlnCKCxKi-czyP*C14Q6)-r7iD&|Av_{Ib+Sn#^y9tNiCTtx?T?Qd0Uavv6?@_xG>-`q~;15%K8Jqf+hv-9J3WsQ%=y)ZS%pETI}>&N&vm)t$v2 z1_p*VZ{DDxp#=p69bAqXcGwGSgP*+@94sAjbQ!4$KG@KFCf?vQR%BFd3ID|m9{&0& z;r-*?=%_Xi4^KeApY(LH!1Li;5z-r)zMh_*US2b8K>}QR2?+`Dq&H?~W*VF)`UeI| zDl01)NZ5;8T7qX@+jDbs6B85HISiMVmKLzAjTZK7e5&~SXM1~notlEe(7>R$stE7@ zEPQnTEeW}i`{&22MM{Zb$IF>>b8`_GIGS0!h4a!%Bl$8N_x`+k_KY6s?CM%fmN|bn zGLkQRcee3c7{}w=+Fqor>bEsCEZRekhq4702X~hS%uGy*OG@%30^Bdo&m2EK?W+6Q z8c?lxZSdW@cY}lRNlDAz%|xZYa4Id|o~#V#Qu0`a>@3Kcn9TfM{*dkL{SX~}Hz+e73Q%@!p}XL@VFY*!XCF zeWE4d`{w56!otGJ%2dbwi-iSir1Qa*>zrI%Gj4~UYwsjIe3&O0gs#`p+}zySih-OQ zZv8zy_Ng^~nw=d47ls(Y$3&;4%`MX_VUX}A9C`X-xjkraCI9}pO|9`WiGY>8V?Xlk zcaN|83pF)27w)wNY(IMVu)e;2^3x}a8f&yF^LIZ6)0)k>bBFVU@0xmhds`&3{u^64 z3A1;ox_f#s&>>st9=-2HtukC4mVGq4sHo`8-7ixr>Ak(ZhE=B7IXN3^ry~zlR8>!o zSM#mj2KPDCS#^Y2n41%hmF95enBqS#e}8{#>w=03j`~PJWg{cX28^77 z(NCYq@ni1&`Q_*DZ|LI@78W-B$^s36)PeY~)@%Mh5sN8LTJ(%67Sd58SGc&iSclBO z)HL|?$ZN&uutnF@w7jCi)x+Zwa<|C<^fYb@^fEEYmM?tw{(XzjDsdhY z3k!>cL~aqAo}M0eW<}pWm)zOe$>gy@M=ak49}F3u}M;_;FpGkKPCQfA2vMZNoqK)`Pz9kXx^fIkVNLKBJ#i zSl7)!b%q-7|18m{pp)PoCX#qxU*8|zL3h;lJQTPyH`mre+#ebL``PI76I8JybmOZ3 z{6)wtUF(yKFe&5oi6?{it!?3o%gcst^Ao2?Sy zRJ{3 z#|0Vzyqpxr&h_jZQ7@4OvS_Wip14Z`y}isVEJFXR)6TjN*I8doz2nA&dCQ;Ek-sA{ zkN$VD&5+AI3(Lz`NC6u@eQ6696Vt-SXA(&GC-B+Ms&ns zD9gst@lS2^N$>IZL>{-hcPY8en_NDzBb^YT`t(D2Qun4RO#-&(@0vz5s2Lb!R9A05 zS5CftN?15JI6l~c!+^t%jk>3d6loV+Z>$FOy5!*xhgN@njz0ZRww%ab=zNuamI`hv z+)$&+?^vH9+0oekIr*Q(0_`TI%{fXcm7D0+G+#_ZX=G_=uMilZC5#K))bO zDEDJaVCUe#K+>N)(IxA%t<5pL*6pZ@R^cS}CsX3}L$ib^4K4yXu@}iSn%#ZMO4kPa z{Hz*lcysCx)m2X}?)$ladta%3Ep+!K*?G1eTl>j^(l_om8q7E4uHTLm#%63{{@NCl z*0Z>P<6>P4ak(jA?n;hhLf{6)*P&+#7V71bO+9P4m+(Fu&a2j~$eY9s45Lne<0elV zy$=;a43dGDDJiGhg7#pYzkL3Ddb&4qiBa0kr4Tote%tu_%$(527POM`SLUf(ZZ2N9 zs!X9T$QA7~Xj3opBwpV8`{ZRYi^r7a-m=%lpSLqZxBm>i?|kNi^SoO4Zf@>=K%Uv}PV4Zz+eZ=XDbIGOX$YfmE?KtvL#=Vm_X*33@;C*PO*#eF&EiD`C>&-1KAG7$bOGx~M zpVZ)@S@bDL;&E>Rzt@V3|Z;AHDTGiYgY`(5zfl z&5RokPTb+vmwd?}ekLXa@%;Ij&o?|ZC^-1nY{Q4aK^13KFE1~>63r^1p%%@#W*=qt zjKj4t1&-#$s!0F@@7~>RHb4JlWM$Fp-S_@II|~bzB|b6nuTK@z0pCI?uUzp0@L_!2 z*W=5ZyJB=7mj;p-kD)?qnC#KeN&r%2)zS=0Qs=R=_zs7`pyHSHd3PLGX^(X8A*J2`m& zUX_uNk!WHX7M$V7@^TW5kV{W2(f0gXT7J8C062z*hkLraNk~cU`AwjQI5*bc{qm%U zjXRS7+1cF%gl0vf@?4Ck=f6m?db%NOoIHV)Yx9ciek5fBh4bbRq! zUg(PY_3PK&FK?DgQJbTPc|Y|m4O;-Oz`{S3x_20-6Pk8DRGIpo^`tdVI&}8a zr-Qh$Uzyudn_IKq1!i9!Jb0iGM?CyYf^tNWW2yV|=RgSgyu3W3$}vE`73JkmI8BP! z<^22(;0Z3#i87@P`uh1P2n`VtBdd#x;mM<;qX!Rg)zs8tw$>`6?!KRLm&g#c!cPvk=V;85Y%tlG^=y~yQaiK8F zz7K75|LQ*9mYtGP1Bmu5V4AP3lnl`2mG^|w-?)D@b)Cdi+`~)ixHy*(5;ExN^;2R^ ztDX6&lE%tq)qZ;R_s`LT{rb|{*z;ALt_$~5WBeEG);Pa@TLgX^^Eg%t%~w1cVO#)ADgb6VrX$a$09H}A){F~ieS zjqV24)gwoMWKY8-xC?Y;Sb&Gel(c@xoL}mn9Ywv?At0Vb1 zNN<0?p^=eR7O&0E&$YmgK7IOBVOT}OXWN@;71r#z*j-)@9U1QE`Sa(FLs_+udEdW( z_gd=5!o)oK`}evsS(!c!J^j}9_65|Ck59z}WMnQNX>Vxd(MkCKY!CfQGcKzRZB#*C zzWsQGmXb2_^XJbNt^Qqun8LZCu-+&lXV&os|)08b9wm_BoSP@t5+eG&;+176lln0Nss?L^I64eXiAxTbR$igeF) zQBhG5kw1_|8tUqFf=($@2fu&(_sCxm%>A>2 z%-hWG2M3*JUN1vmgJR_QD!B8pg zB|}Gs{_^%-fT*w+Uc-?SpV>Y5-m@(Px`Kg$f!<5?^-mRb0vlDva8E zI+r0ei2C!X!bna|Zhn3qGzqgeZV@-KpD(RXlt8J8J1}kbX3-uasDG(_G3WAZRZ7i- zG-lx`F2cKf{7$9cif;lpraL?wVMrdZtqlnY$&)GJQFU^1YVzMQmCnC^v}0p{MMNXG z2J{#WF>mrjla@I@KlikEaZo6`_^OA`MLK&F`uhi-{)bmq9rM7Iq5t@=j~7FHWM^l? zT>+zJ5O$*q=@Q7_xij$SYqO6daMdVmqL#3;U@1FSrleWr!NEa*A!?c21dK2AkPCjClta&jP>xHvc}+S)>(JwqpQcXtOFA;xIB%53%5ulYJhEg-v2#k^Ju zNfA{UI=621Ll0ZbhdY4fz}xrAk*@qOQ|Gun*G$UDcmV-HFLNUCMle?*;8knuUx)zb zY$tp3{jD#5`VuL3vcv>G=1KkiWOT9lD?L5^szPk%QfX-^z`H+NUqr;kgGUQ4xY7z6Z?NnO)GNtmUkz3Gfy39=+tnHe2L~evcjlLu z8nkP~auV80lantsa-rw~@qYyI))|f_bGoAt5^@SHtdN_8k`ihvjzN(@g&_)7p6st9 z;p5}FN8TB##WEMCb?xo#=G>Qvh~9cHt3r+f-#P?g2a1JH^BhQih1y2|#@^n)$P*rT zL9PiZ%=ccrJ9m~cIE=(4B(!pchlhp;Er0LquyJ#1YHEh zqs9CCzGh}-O`|MC4js_-1?~?|>N6tRIyzpU(>$dkFBcPwq&?v#EWUCvWvcuquL z9z-MLp`InnMrH|n384m&JqLl8K+XXG0+@XrtP-khDJ%C3IDqI>?oc{f{c3#reY4N1 zX1?^ZoE*^HXvxShJ#5Z*!Y=oC0*Zvv@y?Flx093nEFJW40f9O|BGlB>XowSz3o9Qq zXEX!_qM%}zmq+@efB)W>NT$@~ybSzkpJr{knvp#KxCXR{Ph(>@IXOdq|4@N?^2)rK zgn@yWi=y)pTBuMWRs1(GKXUfIu&H2N<25oyn9ko;;Bb++kv4dr-uttUSQee)JvMf>qeDJ?P3% z;Uz#wgEWRLNG~b{2%}Ag^;hfK_uk#OH*ff?52;cSA$w zjqVl@wsAe6n2(Cay@eER zn8G^S-r71l`|~ZCim!Wmdb+Q#_%Q=laTO5)o0u=l6h3f6^QmayPJw(O8xK!oeZ5=v zGd36cw&msJva&Lu#h&MHD=RrABwAtRhQ=1x*Tp>M+n{2jB-r%{Wdk0h@}_=6#+1r) z{@C@{_|L`I&69kG)yroer0&kSaJfRAaTC4=30`k1o1Q0^6AEerYLM}z(WAAgsor(^ zQBf%<;n3PM)6;or%cs6c0h@UEknr?jY?X#iIw*yZifjqMZZ{$7-Q3*ZYan!*n#4*v z<$0dz8NoC4@02&M3y%NU{stLx^7{2_m=F+C^DC~aC5Y)~2gyU5Y4+PRjF9Dp68gV- zN*9|=Lq+wFT3`jLBS4wgjg5>lVIhDiafs=hASTzxSyo(20bdijtFefRi=%2Ls1Q3^ zwZ;#nKPjL>yWgs|@ z9G-c4c9xWsbTeTCTAI5%x8=2;wt=YD1emI-ynF*16O7KFil}c=%E-tRZwHrSxBY?% z%+Jw6jNIX0W6uXbp#l}UFNAT-Qm{NseseyKakQSke1&k{Y0Y?;mh|I6614#K`7Pk8 z@R+(}%PT8Sva)XL=tFKo-u&5FREUsG$n3#C?xGZ*91Aw zakhA79b0Ia$&8z0yx=LyRvHsjfM4$y_2?1tgqBgEHjI)=fFafI?Mz%pn66$etf}#Y zE17ds-a0Jh(cCmPGkd-Swag#HAQl!SW)d`nRV#0o0?9ky>~jMtfG+Pe zPM7WCCQK`xUhq?rQGvEv;wz>@jF+K#%~jqULq!H}(3H8IvU>T>gyd z&d#ol1p`F`uyk>{rv)(U?{PP#4Ezv)8-P^lhv=O--1Jh@s+O&oV3p^4w!QSrsA34I zm-hDa`}*cCE!{c6x0&LS`?1EEx(bn`oV%p8m7Yb@7c*asBUu!y-IlVu$l+ zml)Qc+6K<)hfJkgMz}26evr{+5Na^JyL$Dix>)u%z4Ug&1)Kl`c^`4SbSOs{rOp~v zhrcF!)6-Tiad#WotkWa7bN~Pp&mvScMy*Wmwa29(wV87pU3+Za7I@`r!@WQ5pV4-X zJNMiqAuk@Mrba#;2c0-2HPw45w&e_KYikQq^I@bf8UmLDq(3Tk0=W$RBZjfI{q*+- zP!NC!Kps#$5(E{Oh*ns3)f8r!85uFFlD54MK&)X=d(zoxYGZTtR9_ngL+zpW5LrV* z3K9dUom@?Pl6z-)hEZtcfYof=RAizLqn*jspI=>xr|7n z`fLGCZ$j8XeU%RQMHliL%0)0l_%=Xg=-h&4`Zr;YrlO+a+1dzXuv^F`%MXen*VC(2 zuU_4XXoD6CFfd=-&*k=Q+^YEcBd4-$f~=B^4DzQpCQqIV`Al7+6?9msWOQm2z^R7O zd`Zb_xk1Ik^*_Lc04K52)59jLtgKkwKl9VqC#!52x9luysG|8u_OWRD;0~Mfa=~A# zITydS>~<0!ELK32BOgC%-o9Nhd`STSHVDfAQ*J$^DwJk~p*$$Jowq(WdgQ02rPbE* z)fG-&{JI&Ft#a01J${33q@3aPr;OwoWx!FKJUjpq`9iRajEodIe2RI>VhIfx8S_!H z%1A!+o!`5=Wu>Ko2OAl1%MkZp=jH%9>2JE;Zq3Tdf>~*)R-Nafyikr7#sF4aj|oiL zQNw0>iI=`kAPft0aHth(BZzig;Jtf*2h^BJV&n_^dHaFE4cFN8yj0KD)z(HvI@bvb zDy?XKzcM7n+9Y$~!#jC+y=NpgWLpnfXS>8K_<#-C70H|iMml!|V);5{{dMf7QR51;* zN9e`bA8;br*3FC#(jut#2znv3&gh=S&tJZH%+?Q1PmA#Jc>xdsdFPp+b1Fq~AB>|x zW7~hBlC}_>>D>(8k@l&#l&qRhZ%fnx1ps~eE{Ll=iy*Vm)9j*0Sc6dm?%g#wSX^Bg zWTtq!A}l^o($dcE2gqyd3k##bkhi$w2}~MX47PuqhZhrs6OYznC%_DU zFZ}Lh)mAS+y)ZCX0IM9vN6qApHLawIi#Pi2{s{xx+Nkwb`+94Tpa&rZg2L{t_ zEVi*F_C=0GtKLH^nR?^GbSF?IZ`tDc{JWz0*pKcaN(~mBCOxOJAeLkcrAf^sSFH7N>XxX zd&=bq+!@oACIT?yfYB99tf_i1(hmrbg8A*>;_d4ziLu9|#S1aSbOlZS*4#eK~UjQ3GL93P)8hTz2)G&mOjxPOIZTNMP zcxg0OIR)%X41`9nSf>{PFFHn6^EsfeDZwtxGB7~KL=j#%SYH%@{?H# z#GDAo(d9T`L;;W4;PR=w4C^X9idG5~wS%>>p5b94Zoy^{j^SZoItQ}6Iwu7RK=#=} zcYg@$*B;Ugy7=MYAxKB9@D)4~w9;9S*ycLUPQt1cS|{vZ`t^K`ozFTwEM# zKbU;}b5?9IWvGH^goZdcH~_H|zjs&}7Z+DoCjceoge89jdiw^b^k1P100Gg+=3j;a z26GV@7&*Zx3UbZHrZ6rJ$J{%8^hXNuT{q(#PL0s>(;%|_(`K}&JRCx*(aFevEmpW1 z;hI}2|5;MHSMileJ-F`Nxf3JbHD`UA7B}p`L52_Cf1kMZe>@^bl8cjhm8R#uc8>LT~=XGXu2 z(~J7gBEu9C>qOS`p8@8ww3aB4b|)9=f8P$4M>0b&|LA@Azi&D(_Jr|Aj_E&EnUF`m zusJoTlN=f?i-%m!WN>_)1D2^Uc;0FSZ1z;smmt0k0f(Z+*ruHG3i5zt!^;mpV zsCQ}Khj-m|aoGThW^)3P1{pc|m0Z+2&J|8Ox_H691>~5>!v`j$Z-f1o9w?&H?Sc@5 zE3jncRF7^!p8`eb7I{4CUT2pth+;u3IJ+}&zRekzwlp*nfY1@g^(?{=Mb2G0WxLa% zZZTUau|@cCC(7e;M5&{%|3aH>G@n2Iho!puShG)f(Spog*jbCBqNlIlt{FH?a^;Ot z2BAru;L$pug_$3gcLUe%<8G--sp8||4Gs-ePH@%M)&f*1S2p?Qs#)4(N;>*}N_{;| zqUSwvR`qV{wk{jCF0(WJxBhfR#hJa)H`4DE)Zn^_den^}96mx%ezcEQJ%c2<|6Djy zHJNkwEql9YXIQ{w1ITk?AEf$Ss7;VxvBdP?FGNG20M)&I?Xr)51r~B~DUvgy)pcsk z-XZ6AAjstj5&?+P?$c))dwbs?Q5!2O&Ft*-)KpQ+cd`?)F|zFaxT|w%x5*rznoyD< z`TK5)QX%UAs!W2T57IB0Q3mLzV{q_EDvKI|fRvtOMvhtrL9BPyZ0AeK6jM{=x;O9j z;=ZX9$m}EW-DI_For>;LmGO!+ef^@01?7U34?U7SSltaAWdM7VB==MOqkOyw2PzjK zDzG$tb_2Up5ZGe@{qTY42vc1NF|nBF=pnEmLIVUR;>0T?_5rpr6b({Xw& zZ4k^uk5f`SVNL+!Nk}fn`=?`I+xU`%%Dd=`)r-(1GW?(*F#~-?da)u}n)j=F-#oss z4i5dGp@L4D{4?3^&YeBJL|1l@5TLCJiK$?`Np5HmLS&7M8e#Z~AZysCzn9e;|SrAv24YuxY7)Ua zp;4P`8T>mSuzd^rJKWuE3$i|fzyK7eMEm^<2Bbin4HT?#xLF|gklSF1X1Q?#1mEXZ z)KL3$E3zEz91RoQa^R7qaBlVUJ3D=p_zYU6`Y+hH&X}kRyO@-SoE>nB%fpkBG$1Kq zRst7ld;7NPpBDi>>h;RgS4{Ki8o#fGgyy{9`1wc5-4n zC9UR^jOQLJrz0heY9uG)VP#zbmvYaC$h+XT{IfDli^xJ+r&DJ{nwejFjEjJA^`^ew zBonMfR5$d)?tKu1chuqA-4&FmuA#97Ds-^nqD3j1j?m_dx-R14Pm~^vD^1$?T+~%o zg7v%z)NuUQFLQ^FRQMuE*|hJX&Gr8&t{6&0`Ud1Fw~b%El*GZ=eW{^TVYoi~1w%?|rZpg4 zJvLRSp^Y(DybP;dsb zntuU9@!-z(vS_J^|Mq+ptAcrin!0*)jy7zPzPOFvLTogM0M+bUe zD`>9T+Lztsy0TeBEy7(ezg)d}6VLgA_ib{rmXp&O%uKFbzplf|D+kQ5%H_7C=t%ep zw}?pQA=Bb5bOD?K^}mj9jQ#zE=gZkd(p3}~OeGyP_-!6}g~Td5)4VJz!-pId5orXK zq7`-oG}9Y5a7OSw%=S|%Xnb9E_V=HHu>|FgXS#6%W%!-0wo*0%J+I6zHbU&JtQm`n za$NhHR2mr85fKsX3QWAzNc*t-E%eVseHk{2BtLjb}yzYrX3~T7QDY+teGtKN{hQPC$0qF!adW@@{ZZvVkny7#_gF$_l)A8R7^W9Q|s9goJcb!Gdl@(43w-3+Zfp1hxy*%=Y(h zFgZMmEQfyqlGqP*z{tRWg_(I$#rmJ5Bmd$0ga3Y5aq`GL4i4!=mdp59{rz*ly`RJ= znOvNIovOOdts;70=#?Vwdgo3QXY_XaUt$wnV1h~%-LO78Vwk0ig?A*)N*_#{UBM$F z>N|^cdN018Jk89gk%M*Oy^tWS;r4qM(os=lUg*LweDjbZ%3;MHmfB%jQ#qa3tp}2Q?#HV^` z6>XsyNIT!EqjkKeFl#NVVB{0z<{7AMpsm4&rR|^Ih z!!o0+k5lwjbq)e26++_*oarXpHdf1=^7M~_OjV0-@gLQENPj8kR}0h9hK9Zy6oREG zBs=|u)X@l{rKJU6T(s5`;B|HT3BCqrr>aJtV*RjZ#=TDR5^;vUC=g4-}PeXfXw{ zUjE@FTKx82E2n8MCB95hRN=g7Vk`&~m^e5J1YKXgeEIm1c=##=Hkk=77$ObD9!9&C5fl>ik^z&=0NS>LkZIL=FhR`{? z%L+czyMcH^0?Z*C|6z#B-I+qUDD18%Xvh=nG53y_zWvM)Mt?6LDJjXxNf^rwsdfFW zSS_|MVT@cA4lUh^fd5b9xyZQ*7?x2u}{oiAgEfJX!I5cWtQtYY09zL zqFr*3b>3N|priyJ_xktmwjjA7aB^tiIz`q3dO=>_{X{3t(4$>ABZDep$mMuNV8DH$ zDNN8G!*>b6Sz!ap6LH=%nfvW4OU=NRRq0Y9#jHUpcuveMENrZcf{pGNV*$ei$qi^&ydpY6CFnHz%A!?v*z}f*Eman# zOU=#dp1X(bF@N*PO)k4Fobw%>HPMzt9!k z8NC1ZunGnsuvIj;M_Z-K*;*E73^I4+XeCm>ll%C#9V7_dyBtop;`&>Fsi5Ax1>Xwb zLtynZq9^)bGsG3GfP)bX(jo5z$q@vC_*G>kS-j$C%+CuVY*t8~Z!p_I7N9-10ZtXS-lRUV`GJE8z5r=tVPSO z=qg~KrKPpIiju+LxE73xZELfHox>}9kJ$5v1arvBeQ#>LSRWS@3t#uIHwgD!b^xOg zRL57Y2hRKz<1K>b4rC(~)}|77vvmRs9KIS8nUOfOg3<&=4~`5UC{`eS#bJk!f48-@ zh4vI@C|aD6co9$F;qHFkM`;Bnwk}91_UihN@?vbE`qso74Z1?9Y*J;DRK!F?e!jkh z1OzB!JvfhU-3xRgDyqk-C$6_rBM%FN6(Gck!6>9p29@yo`WB|+1;PDVyn>di4O zp0lRVpc%VRI=!;AwB+OC^Jz6U@x}ffnbKN2PYp_j>A@%A;&U*h%5G_;ANH)=HLr~U=S(V|oj9G+B+VQwNr$ zg6T(?+MdCYJT&k+orAszCYVbI6Yw&4F5U>;du6ZunX1~=UGeX`k9k!InBErV%He1* z90o@z0A~ocSW*Jhn`DvG=$bSLqIm7`t5?6kji&!KMxJu?eYtN`VO!fN9NPqE7$jzs zfR>8NAly1=<13q+9G7wHjY+kwq6*;@B-|HB!Qf@8fnn;a+o+`*O#xr93Ny*9OR_4T zh{*KBMAQ`ekt89uf$9x1kN4>}VG2@N@mM=qYI4Ju@)rlXJsjx+^qsWw>WYj0XK`oi zjSodPcMBYXu9-$-aKF(VAUQZ*qK>@uJdM<~sB~A`qHPW=5?fzer-A!)cXxxg0nQ45 zYQtmIK3Q`;%W9_30`j&5Ml*#1x2ZH%(6aoZaYi+8KRupuhm||n+XIc!1g3TKb%GPP zp^7++{n?$E&_Tg{Mlf$ESp6dSxk}%rP12})*M+`|;FN*p0|1|dM%o?pxvW9uWzWmE zKBuG8KXDpd!&Wdb_ym@El%=QR11CkPNh&U4edi7-HFepbBQq)mFHi0{QxW?8Hi80~ z&2NuChev?&x?QHHmkK)#G&NMUI`tb5JZ}`ZrI9WsFlTPCFSh?c7H0!^G`S?Nqb(-LsWDr7XYrz6mYtHTXi5Em*T$E8n&!X&K zIi|}y$01HvWk1MexUEq{gZK(FSxGztAN{AbwYy*!GEj+WyirMMS)`k&Y48>fQaU@A zfijlZX9_|xoZZzILNCp3M})!-oepKo8ZT{e8=UKShBJ|3DZMEeau)0SGImX72#>-b zwG_|M$W+fRtaK)cHX^Rj71x}fOl0Bv zat1?qT)t>J`QQJigd#`*fAqPcG_z-1H0%%fxWN|+r+!}*6j%c;_VlrL;^H;hv*UJ1 zcpZZiXtLAVpwAAV!vminda{_t?vk~OW+ zEK6xgy!K>SWrtSCD{RG66y_G%x7lvNviL@hPEW@jcanHf?>rsj)0kGiZ)j*J?+S}p zT1x?1q>~teK-|UkL?|tAy{xXjbS6rMk5!k09)XOMzkW@Uf$P&_kHL7zQx^n&g%C}! zufa(Wu)cqR;bfWKjTm{ffPmN!FXZ7A4iL~3n<%ni7_O$Tz?OS%#&_lj`H;E_>xNTz zFC85PHbtgYRBVFj3y*xFpn%DVD>^n-o}9wg!z1}2rf5h3)lh*WtdF^A+sh_3JEl9w z7LqJ^CFNUB#<+G03|-NRjo8R^%hEqAgSXsElunRg41qZUNa*I=nJAq)0n{8PF2r7e zJPaMu24$JZ$j~j*-#b{7hx6c;C};s4i1k1U|~d!nQK3cvdbns(A`)ihz{rG&UsPUz?9RYTlJ@iXIHyR zcROf%66aqp!0B^5Rf|+7^iB-etdAJES*kMV&Rb% zh=Cx9^JlA<={Nl)Rj)27xsmyy@M`qPm(udY985${MU3u|Irlb9eZh|q*HhT%3@&z1 zTo1qo1A}GI(jv=O0c(NL9!ysrK!xtF;4sE=uvy5dWqe5<$7_Km2dPPdE@W`2nA!SZf?>TFkzbI3W@1(OthCHW#i z_1#1i;jf#~4cLe*WNV}srF?NObarCMa51~@Cj!DbIXW6OUv=)>16FaN6BR+-`V-7< zD7En?|DMGw8#;CYnEymE5U;5}t3;oxwag&akVp=3TL{{h`CT`#=qU=bm8RFOkgMz= zX*b1wk-d0n34sjbB85BHy!Cd1S0c!SB4i67Mlq0HTfWNYg@rbLenPLlSCG(#e6GQz ziU`kqw3@t8^gfl3mlqHzoGjs_$j#1%*(vC*2X9D+uO_TBVs%M9_bix59DnQXEcXLR zr7DW*}L2r_CA-?KPsp5e*JY)Tgyto;;qoiUZRu?JnUN7HhI*yxKL1n#`05q-92 z0YunYVsrM?c<|mJ-AU1|fAT2Sed4l~)(BXO^a{11xaI7{v-^?i+(<+}p5XXo z?G!Zb?U1LR6P`_8I##0dkZ0H%DYqz}G`f6==GH>eOZ_n;)1sV~&RYsI@~#O3OII(k zl{QUWE6ivjoL!a8ND8(O&c#Ky+v=I~mVuNWNAih*vQd7d9XoSk2~^uBwu_a@?6cmmNnJ zvSo4W_pMj_@ZGUL6DEV_1x{at&#ph{=cmF}G>^quH98W!bsnung*v@_VIgf3g+_x1 z1ul+38T4B?t)TixFKXb(_Rz(bsdyIe6uV5nw&3Qz;IpWgI1}ALLPpx@{fr7{fWQxjr2w!xy1QGN zn5az5X0LDJKQy*}HHn$t5U%T5HGjh98%zyM1CXwBX2GS@)>a7t1{xf$N9pfAqoq8_ z&GFobB`xi0cRNr>!XT-dvGEk>WTl{KPo*NFNJJq9o1R#_7Ly;X9G)^b3(Z~QH6JqkoUc7={UR@KW%URjk z5jiRL>Eqz?J|^Q+)7N7IY2{Aj;#U32cTdrG?efjL$03E$Nli=pToh;RX0$&~*HRwb|AIl=uMp{usX^*Crdeu$KA_Vsdcsiw zsKd)!TlA!)7++JM4#R8$UT_{6i?l~d99b%h?dtUuZE9*N=-okBfiyHUHYUf%<6XLh z!}y3kJ>37+Fy9_B8SOPai;K$^9}EW+Fk6vVO8x5LIrLZ}7zi{acoou;%=7rYrqGvC z14eP}F`Jm!F%)mMCTb5YjY=#e{A8HAUaW_g>HF`~$Ha}VRk=$#8X6`K+&uiH>O?zk ze_yiwHLuwuew-gXBCMVxI5_0*nRdSisR8%`izqAo^KH85gJImhr0M9D*DeA0WHDW0_i3bXXC_`rO2K|s6fWr zN=h+MuGJb`ym=zul+~3xGqRv@r+^s+&d5!c-9|dADoHpB7dW;lcCWYwEQAiqof}_1s1YnwFt%mkl(0kv}6nLqY7Iq29^IVux6*e zO(|zX2&c!i86&46&ADX)emzyZ7Qx8mtn=_4PYm8Tui%AwOm&*xr2&TeP^z3tkiG;N zsRS`P&Htpmk$0*(h;)&<%P3MzGX8P&T+x-HP#oQDi?!5)udKYh=vm33W0%v z4i2pK6r*dMU(jR>v%iAp3cPZLt~R23ry4vZ9axBDs72Um|K7I=OU91fQ~O#>#8d2S zOY*+nK_eWK@&Wk>w%WQrg#5&&^NO@reSDTo*%|GZpLuT40v1jle-T+;KEBx}9UwrjsY8-G{` zr1vUFWEjkXR+pAW8qx}4bFJ~|`PscvtL_w&eRSKfDjcNrA`eS?-%?xk>}9Vr{wrfn zZVnDTb{G3$OMGyCH%ac$;0k=!KJadm_;&{ zuiA;$Aszc!bi19PvrZe1z)v|M*jP3;y0c^tG;HKDevGy?nRQaGF)w3;Y&h7;6`+l|`IUUm3tQvPFcq1j=IMwnqEv$6M zYzw=IQqZ(G?JVekG0c5teDOjak33g{}bw1vT3{ z9&l>i`)FrsWkt{iQ2b(%9RMu2uD<@l6D~njPzYJmbWn7hx@_uPcRdw##0Qa;l?{*G zBji;@3%*9*vD;SHP~?b{xL?vIlDAH{;ervG7QR8X2F(d}4i4u4ap$l8&aDDe>>G4R zkoQAFLO_9ZaCaxRNQHqX$~W&&2fiEv$6+wSm8fT@=H-1{+6CKu7J2M_)68Tx-(e>uhPs;O%3y0i$4xCcQ|dQlRJwUZVK0 zz!2m5!puA&!nCma|1tI5;auHlVO=ebB_R7u{vUm1YM#{>bB`aA; zA$!Xvl<~ct&-J^m-}&d9uA}1pdcN-GeLvRi=keX^ZDVbezge_lzxyB=;`X-NO~YN z3W9*j@3l8IQE)w`CqzX>y|K_BA}=m?Z%{^pTHQu z*x3VEy4UV3B_vYN(RD(tgq{stWtT%-osPs7`#-GV>>mOR6dDTmT2E%U-`-pK7=3x7 z^e^6qK<6Hd*Vfbk&Ta+C3Sc>guaq1fqHW)E`$hCzU0%Q0q&g{y2%0dRo`k+HGeq_; z5e7M&%F!kysdG_gp_!xUGN4;>9VWYZx|&A144f>qcX1zB{T+DINS3Pp7Sleo?hf}O zii%#CC1G}tFk7Bqu=o*NSa=7U0}z3JF3dS+0ExmLnm_vTSt|&gEMx?+kddg7q00s$ zJ)fb4(xQ^aNq&q(yUp!mY`^+y;oAw^Ux^oq+eG_)@Lo?^Y%Jp&-*6&PvP5dKvKh)of?b zH7EkXV|Oc|59m!$a!hvyNwksB(BSF|gBDgpMFj=nDg>%)cfh$oirMnaL1_I3ISYRQ zNC67a$w@HaCd7uroAA_*iS;o*npuxr`BJEQ(OwxGw+Q1Ov_h^owq@67U>05eI`Ik&_cgS^|?{0%ti1~to$vqLAt9q7Hl7jbi#?(WFOPVwqWlJ1UTsMD{$&P zAQ-P;Ev_SKLi+Y-2=sb)zS)1$G-50pmYjGqT0MXW1|A=-G69*cY@#^`4yzb6zWog~ z2h;w$iFV5h3CY0htV!_w7}RaFw`Fk4HA$1?lv)g$L?hYLv@FypGFjFbD27OB#1x=6 zy(b+c`;PWjrZ<)B)SH)&&+5aS)XXB*Ow|uhCzyp$g7-GjLt+@au~7Nq%|qY6=eB#y zm`m%sU5FBukwH!)dtyLEDyLKMpvf$yLM}WJ0gaPS)Prf`F!YO;1dL?zp1T)To8zyv ziXBtM(D6!2HJiLXMfo4C6L`6^adAz#_98c%;5(tOCF=l}(b(8HGB6Or;_z6noGeVr zBctSqJz(uTdyQPl@xEuSai&#!@@KRA!}q=)Y<|NK!1pf6mM_+E3a;hJ>=WU^uY6 zKyi<)-GTvIE6+~&ft`NWMH<)+zHpSg781@PZO{R_4Rz^x-b7A z%6f;E@L4v3O0IZMP@3|HHOsaqBx76{?BiTDv2`UEd3KG$Fzzg@BOxGPtvw(qKE|K3 z@E%&}3n^&cib&#S2R1L>@*OB@l6(N3Zdz%w zk5?9a@Sw7)DgcH>7#Xjx+BI2a{}9__2q6`fu@7G-v~v+86b(*GwCnrrsZS{VAl1^; zl0`)`A=G!ZAVg-^ZBjMqI+qRPEn4Oriuz(V>zb)S$rHHrFjR<*A*!gqf)LG$1?!hm z%Y;(J={%k7-!B7iE7Zf9hQIyW-`CZLOsVZh&;I84&zm>#L&R7yIMg2pc|S%n1ZJd(fgRI;3ALkl9W5R+rRy^B z>ZW@amG7=x4_BP2*qE>Q4ssRpL$2Flc$elK2Md@PCM8zVhz0AcvE-M4cY${KUGbN1 zBh!R9g~}(IFO@mPn`362k%9}KBR`n09Pw}lS|UJv-r-&Q3%bj|Ai&3X-K3yZ_x}AO zWTv5^;f)vqaly891-B-{jV-+#Kk^Ak$3$Qd0!?BbYAs8SYv}ymI#(jckPD=hz&*CV zOdxR)Or4}y($PWtPv3fPaqre8&op?RuD%88oBFPjn+4QBJQ3VA|8`rsG*oUs1QUgp z5dO5%!orgJ#hWy0+8Y7O%86eM(u*V_;9`_sPaOE<1S*F&aM#ldYl#z}L~@a`lcH64 z7m{GJXQVfa-A~0?upNt5e|<|$DKpx;965OFE~Zb>#O8`Dy*33#n3M%V86)@s^5H*~ z0437~q&duUL|0kTJdT+eO9mGOF0qU9v%`a`wKW?i@kI(FW8(&)gNxf;O8b88O+?rc ziCo`iXI15d?U+7^5|!OXAzuknPX1J`)^ks`4}2yR_|V(R7ZY)jgNHmbc79Kx9A%}g z*j31}#$f5d=V7k=*n`M%KK)^xPo+4s_3&X(%x|dnqv$%k}Z}XOhsMh1hzsASmi&BXgkl&w~}2 z+*gtmrg#1Tm2aE>T;O^VbhC>hyG_e!`livc3?S(M3g^#xz?7-~eStR>6-J<4=FPnE zB>}BGG&qQ$r@$?;id=45j)&~TAuufGD>8v^_k583T`Zl1>2?b^6O7=t)Mk3jsUPU{ z67mK;FFu%$O5QoY3Y5}(L00-+`whxn8o5GgYwK08?>r?yKt2&thWUUh$(d-s5KCpe zqnqX#qT8JC*1d}9;~cyZEk)6g?Dr9v8Bb~`remzyq&W}N^XlI7ye-q|@d0|`@j$JK zzP>`|i^2COM(zEWnv=Q<-;y*!XGmhY_}#1Zx-d~z>6bb}Dhv~}pUkQ=ryvu>JS3No zP)9ROdbvb2dR3-Ud>S=OMNN%1jOA;WI-g!0ABsI!r@4a9l4H}*)MOAvb>}t?+JsQv zix=n>0=Hv&x3;&Dg3stncDufaR{RmGfBdg=JF^nfi=R-yzyVwy@?9JAGEF2kVun70eKUUXDsyjAqrGH3cB-?_ zY4mHtr-RSbE;mtvAoR&pEd!gQ;4jY!c(_jmvhS&A3uNa)5Ez`6v2Wk_;Jt-HRzJ<7 zGX9Z3!jU)Ax%2YRjB_g<0%rkFaRw3KKk)i~ zN#=vo3BS{v<%W8OTslMmxN#u}7mUP1`ex6c0R!#=N&}m^T(9Y;BceyDt(k{c)CIOm zh=6O?F#3 zf$`PQAhss5L}Ya-N5dm}I-}7kTGm8zCXPRqWPUn$!N7A>aPJ(QkJ_yI2G;u#?q-xl z%=_f&%7GSY(bYg(#q|?i{&z%)$vv!o>Su*i_Vr`Vg|X(`2KxGa3hJe#sg$LMv-G(! z5ANM_XIQ2DaL7vh3?B2E6mc@WTWUr|zQ zfslNd`^Q(53jz~EwO_H2G?a#FTft#&p`mCTTXQ;F?at3P^} z0%{l;!_@maKEGiq+!u1xg7JQTH=B&c(62oA(I6_qrp_10cm%h@_o@q>I}3y&xTwc8 z1>6#g`uNV<+h>#oBDnBkdevC=zSL0{MjH}Fk$i;Lbggf^NolaEZ$~X(AXbr%K_#h@ z&e6S6(Nq$7%5HE(7K66)3(_o9nTt94<@#OriNfS!EK5vszHgZgTus>zaE&>y@=r=7 zF9T5Bk~el*UFAd7K$fZEF3Eun=JZBm9>E>d69USURllY%bx8~F#R$?{XIK1WQ=y$8vyz5QZQH=3E8-y!^G>=+b1dU=g`0xLt?v`CWNiWX`m4cX?||Z>Eu@{?eoJr)Yuy zX`#aHXJZF_r+eSyP7B;ZI4E$t!^}i)*G0 z{Es8Jzbr=KxZ><`uXJ-6L@pLcv6r0@v9sCzlzG+q_}Qf~sdA+ee?#Y}=?@gdqe@ci z2EZ_8Kd+7&kxy-%(-(MBxU#vLH^p)I<|UveRLoInl$9Lg9nObpzl@_p2| zR80*}K;E8^%QLtdpSF~m$-8&`XwhR`p8&M1n*E!eS*px!4i+|t23yMeg4kRv$1kLn z3*BgK6FPm4d(4qsDvpBD*f)fi?pQa5(v3p`0C6t1T!!9lmq{nufYE7jAy@AR`k~rk zn_F!Pv<8aIDd0u4so}W%NQX}AWsr9@HmXsgt-)yD6(G4Wbsl=fMgp+(GV4Z|qVteK)0Ik71&mAYUBV*;!cFz3KVl zqlGA2jbmPcB4PR6ko%}chjvo+_mzl^ayAGGNF8`H!+Twh@1oM;XPp#kV#fLFxgfcu z>}oZk(I9>?pU`1P*kzX`CCo0m7W@gmz@8;sS^I`He%UOIa9_pLJiHSwbS8w84HQ@sIl}ZrgiMj!G%AE=Y(92Z!tZX$J+!!c@r*nyb$7gY$a7ZSjTIs)a!IeX6()D5~`edM#b~Xlkju z-1P}ywlyT+x^V;d1+g@})d95tIEbH+;StL(qo=*STuIS@PKRU2Zj+dfN=@GU&t0n8 z3MR_?GA7)q0Jq*tU`aAg6q7EaH3~PngO<=&EN9Dx>f0|pORzX?Z8Cr!>?7*jI1^FL zkQBAR9WH%Go8^cBy~OB`U%OCEg_71lXAw8rUjA-71YCbDy;WL?DXbkK-rU)Ds&oA& zpn$=l%e@~xOv-Wj=-ektvLP1baeM{e!Znnaf8FC>oAPTFq&el1iG9LkBbLNaf(NXY z?n?PwiU(8{I&nTWbs+FwdShj%&P2RX?@Htp*qZ-af3|DLt+PlH)4G5EUp7m7;KN+9 z!ZTPOP_XAY)r^jM+%)?Y<>W$%_ zoJ5xq$ZkKVpO8P@eofUZ{eg64(4Pf|o(pUAHu`_Hp-|?QXe6T%Ek*Hb&%_Na*JdWl z0;6Zd+}GvF!o>~ULpfUh-Q@+CDAlMqa>Hz62hG!o>jQlq5-kq3NC=wShm=^FZB z9+h3_R*d@TD37AmPr$B3JodQ%$K4LR-IdD;QO)a$r}i}=@8iFsAa8oMG&GPJDp7D1 z)w!Z5Nm&Ux45ty6OX|?7G!#vQI*0KF>2l~>P_^GX4nnQYVp7UfWhRSBI!1n8ft*j( zO9>bUZ|0{N?}xcC2t&{vS&Y_|eBDpzRLSupbJcBmGns0{@u>5W$1+_%!>kA`lA?fM zXjQ;;fn!D6bTsd3uzOI5^tx!l3M#^!kE-32%RLdas6p>qFpx*oUj;W8>ivsmNm*VW z&i=EOz4<}VUor8k)o#FY+)$psy2_hilx*+wRU`giLQn65BI%Sem0)AtgTnIQhd(vh zr2KZ^2lg$f5TNswKo@Nb*5q`mHmF&u9paSHW8YnGbH&%=#btfN(G!SN|B17zAS_En zN+B%?wL4QQ*#dQQy&EY;RiRi*Sbqn{Lxd_$p3k-UR_|1sp1zXrN{Cm>FK5HI^nCex zEzc(jQ8^cjAFGeV*Y#@37FyX`pyaJ67n~ejdcL*`N-36(&nMh15P>0#IYr3^?eGk5 zDVPU6RE(a8E?52vTPqEn)&UYxWY6wIV_wlE^x>h0F)5Lh6VmAKYLDX`Rt-`}ft*8e z4^kV+5%k3g@Co|twV&E0RLCy&iJ%w!x$Lb{(5`lWV6)fT6)I`r=iGxT$iB}~z)W?U z*Wo)mbY06BnHWK44fg$2hWyh+)ZSWSZ9`o8oTxt>1&YTg68Z)v)L&0zs>-uJDh`m8 zNcp(m`#~>5{Q1xE;d~N9{&gex4B-Mh(?dF!qvr$qD_ zZU!)pxQn~Ud*$)g;jN_qsEMm>L%3j3mG%j}LCX9V%KT4(Ax&9pOQVV>b}`hBZ|lVG z?IU*EE=JvLA`3i>>dloL|Jky%XOkCo0VuW!*$XS~m~BBcc@=!pY4_B<-vY2n3?HXe zD0;z{G}-M-rsBvP2bNV{4$8RC&=2xaDVffH`xf5tktbQ^-K`gHO({zEG&f)7=tVru zrSE&?-ujC(Bc|uxqsp`wR&_sp8u_GGn300J%@s?vVdhkOJprvGQZNjLaT-JexcJBw z%;3Y?TPaD{b*(v&T<>R<5Zzg<7%9D>_Ov;-FW$z2U1gDI=IOVx+ujs zoRHS2tdQw*A@AI*uNX9m>&f%qZC;=A-&@5yWO8QNZ?GzNdZ{rEEN;F{_+p|#DVW;2EA(9g%9n~d$jO%Ox1D@92Hmt&$XHhh zO1|$}Ci0NRmCsEuDujSM^c#V6g}<;70%-x%-J*MKM~C?airFY~Ad zBg!O?CiWV*$C(yJI3 z{h6XBrsLDo*oZ|}3Ku;7J3lzmln=hV9~DRqsYP`$rp`cpcV5vIJfmp=oNWuJlqE zzqt{CpnHCtRMBMEbzdg3!Vd>wj_|QMSjzutj0o<0XT-mJdD`%e>dK^bUd!o30^-S)UMBAE6uvZwV}V}fCB;e3@kxh1jr98$Z2ha;2Rji zk*{A~lK8+&Q4QfQ_jJm@{mTKU9T20odA@5dd`v|*S41b4W(}IfHIV|1lme)%hjCPL zz2|)UKM|6&_?~gw@uai_W3Ed3>usl`WU)3A+HKzj(aO~y_Vdd@Iw2ZhyRn4KSIu<` zw_ehRJKt53uB`8>sxs=DfH&k^Z$Fw|0%MPaA6=25hu7*yM|E}l_*dl0hN{%i#3jlQ z{gTZ=4|0>1;O`IoxKcNxx(ta;6zTT^zSz{!^Z)S??Z@w-z#m3@SR{K--}WNsqNThX zi{*7q&Di=;@3LDPnOary`R6bSSsTWmVuo)5cn1g|3>-|@AsDm>xtEjR#zK+=IcTk7 zk5q6Q(duanEPA29o%5P;0^e=FRM8AkM;g?BOWt2ze|{S2pEtGqt!|wAdr&Nfc>(Ym z&r}5)GXb^DKzYS}?)n_sFLO1uVE}7x_B%kJG*I5+|9;o~k7fGazj|%2{BFE>_qMM_Yuxg|*=_Gx9w@ij&MoC|1k_)9K-4F&-h;0Wixb5C z&K4svkVC+EzTc1!!&G`&+B0Au#dHxrAb9TS>s&~HR#sMaZd!aH8gz0)OkzhsvfJ+i zAHa$sU?pg){52e_lRq;q*Dwe`z;qx0Q%GIZE^Th`AHX-l;kaJq3PM6yXCHkP*@KL= z&(1e?%M=Z9N?1I#*8yq}zxFxC1W|X$lR*G%`~tvW4PgRM?&m^|D@dN&O zt*Oy!SV4X>%ynBKJo z^d@DIeaG*sB8*4d~D(X1WOD~&^vnZ(%w%5;h%6S(}R zzI{9XZtOz(6z9*g{{~knD5%Ki#GukH)P!^zeu7x7m&y=v|8&z(OX@kOfO=een#;QNo4xH^N3W$Sw;zYPb}80tTK7<`EyU86f znB5^2QT8LiSFlQq3IY7JcQ+cjW*x*=&ASiX2U!MsFg*2)w6w)T4dxWz{ca2=fti{< zTK|(t{m#QdcH0~`dEh*2tPKr+Le!Y)^OH&76J$=d9#uZ;eMt&u@TREQHXfjp0GwN0;?gtu=q5HB{6`f>^ojUDJoHlo z&egn86axu2$G_`FJ{Y5z{IAJib-jn7c56~@^d>6aQNS5j${3HcK{r`aQ*JPhm^iw~ zJhh75G6YBBeD*^7Ww7s%=r?9{FY>QNfx4t0jWn5Obsv94MF5QulS@KKNcQ&VnCnY+ zmtRi;0Mio7u@B;f*Iq$EWDmM=1B0gT1|)BsgWH^y4*&1{T8>r|PLfhkcoA!`?_o}( zGn}a}1t-ayBr|>U?X%>G{3xYMH|g)WHmLQaAUGas$}wJ)MMN%WB6NHm5BoHYzX;pZ z7<^ejx=W1J#;BAG@<28E0aGQ}xzW)D0HoR1@~G1zKiW|6Nw((Wke)eeJ{Q9m6-ycT zw0r>gIVNSw;X)tk-Oz4xB_%BJ28g_X3!K%#dm%h=>ox*LMHGAy)t|;>^qIt3%AGv74I=FP1812`aNDFI61$Ym5mh<}qm*8I8-_u@IdB zi6lGtf=TLahrOXM)?TC;O9Y*@Q%37v%(TzvxqaK5%JWleU1tD;{_=rPM*(7gT!rf{ zaWwE%dS`*~;br_jgAlXq;SZ3^25r;opbWAkv^Hd1rnm^;DIsCvA6%F)KN}-N4m8o<5of@Pf4Nw%n{$ z0qg5cXj!_CE-c!DkLc!$9{iqZOxSe>l?UAC5b-+Nj&?Jyu@XW?hn$~h2qfw%ob-sD z&enn62l5_4{h-MTu-zochQQYAp`J9gEmtjJM(fr3D_S-*uxB(Dw1v<=dhAIWPvk%H za2w0`Vz+f`gyAUWi#4zFXtKlUciox&FA^lXqr}1P=J<5Gfh*0}bL77o2s^r}T@xy< z=~woNXzC0&ybcFg%zRhV6zHCN<{^pD#Q!hb1GaZuz*V0m5p)HKqK`SrDWd?&T0tHB zrixhbYIQq#d_vnyAWvBevq_6-G80jP$t3AY6?b8f9}QoeL3ZYYDxcV>C4`l_`I~T2 z`7iG5L%e=3&KM5flZqQ!Fe#dWz&Egyj*`+hPZyG@4y>DwWCZgDtgfz3JB>NWR#mTj z_N$cPAjp&f!2+KdWb(*fah#>jaa%=g{cT5Dh%Qy}t}ku8iKGPA?-cJo;mOGfB=?P~MR;fmTPnxDH@dgrm*Otjc=M^JCC09^Xo#v+XKp#ytqD|G;|N3EBww>R1Q^6(N~kn8tEG^40FEi z=h;lA`fIpgx8XLpXF2Lb|1X(qBl!!$eY?Xh>EGp*B2y2!Wwfib$U!3k3jXoL3tKq` zBBqg10*TAff`+%fu?qXe0WgS6Qw~k;FVSQB1B;@aFj}_K__0;)g&6niD10~eTN;b9 zTV7&xg;K!wL7*XoCm;Ib&^)RGr56f9@7AF7@V1pulukE%}KMdRlvR~e#Iz8dX zgdb}_v4j--oh03wcfIe0ky5NK=yFcOv;(~Fr%Y;rfO_$ zrgi93wa7wO7bFXTEcO>y9sNeBig%aF&+uNGO%3=Xgx|xZ2JP$(ef~Pn&mNq`pbY_= zI~XYmdF3DbZI)_?9>@Za2T5QMIszG{A=Pzbc900@$B=Xeu_~qjB7;mCS(1rZ_^_XG z$IIWrf&CHLw;p(XA$(#N)QJPNZ6KUr$qyiImhU#dN!~x!=b(!FvpLac#k(`xoKkXI zIva#(oQAci2qPmSn7$}yn{Sp#us<@NLkIhnnY!Ls-LQ>6T&8=#z=IqEiYzFCz*IB6 zesnNZSyZ$HJ(Sqdmj|c6f9jm!ZvV#s2#8y9CuC1rX@3tgs*Q(eIfrT6a zIKtaG>k3QXUzlGPPDXquO{*oA{6og8>S}BdlFkHs9~Rh1sfv}e^^{-*sDj=->{-uc zE0$@QWa}z&bf^0SA*~6fx8A=&>m>j3Q@L1sj$@8%XUx(7Mw0Uga#Q-R`$*l+jq@-} z-2mphc$CNeU)KkbNZ43~Z2}hCKxOhvRD8jJ)9r1QX5&$GDXMZ4-KAtHV@SH+yL=j_YY=azm|3yebiyNAVo|skgKcH$<}~1L%%gSzfYo@DD$=;Pec;rHnr#nll}c3X26(C2$bh{Ubo`;IuOIpEL1wHwk)g13Yp;92 z`d79~DqORjA6jn}mkrG=HB6~Qr}8Zzbt}WfJ^K4ScyxzP62#<9D}#sm`76DDBN|95 zpFez-%#rS;!)R4!SUS>m%>*XOH4loz)9O!MA2DcVHVqI$WfMH)G!oM6B2{EJLpEpw z4oWjjfmhJyrfAzN%ck|)D1;2{SB;e5QU~BF0H*Pq)h?x_5$+f;k3oq0vz_Ua9FMQf zFpu4k;fN+URBI442IdEFzvsJsru609ac>5L1;q2azMB#O7cIoUgE|qZD-#BJI5H62 zPEW8kz>?qgyLJe?6khAO-g%IL?NdFvmTv3}rXWBAZd$C3BJd$K&br6U@9lxr8jd`O z3Z-O@V~_S>Ui=E%>nLy`e3pp<7bXN1+lq`% z`vWFH$50z~;OUy0xD}=hxq+r*dCLfJS0ebSyrE0Vl6Z-l!!0ch806qo(1OgJ` zM$5YfI3P@(4b8TCmNsZ&BOUFTP&;uOZ}e7e`@&rdr{&pT?v2S0PC=6a(p54{aU+=z6olNM1qS$q z)C-#|076tCZl~&5r;EeNubRx^u$jv6m_4SiSl$ESd^(X$<4490bEan})DPq(Ot$Wc zh5y<*dlzcDX&4zl&lxz8mZul-wSQIa8AoQXodqNdnsYaK@0soj+iiLaE6_=yd15J> zip)pzqVxSy{J7v~tda3m`@W(oqb^$o455FupIh6pC!;^|%REh7f9YF>rnY!78Q%as zDhv$@R1!TPe7q^rAWhnZe#3MVGWyOUk5wmE3h0g3^of(YbojvqunX?_nwK;a>*8X%tw&V z@mq#(73$ay8+BN#+*!VP(bNQgh2J=1p_$)4oevtJZu+$gD$cLIu&iho@Xjpd(wkWj z;32n|jTh9;go6rK4x(cIoUNB$lSrZvb`lh@j5k}RP<$Z{xLx*eS(VrI9y;3WZzS_G zw~y_GMzxZ0!SZZaH6!G^90SZja>}1J|Y{tMYW-J zx+QW_A6|8v7ZhQWP;?)wkt7tA{+*sSYTqB5gxM2tnTdfHBAs8h?3FvvF#de}j?=I!2qT zNa@VSw+?yLJQf*XTXP9mysB zyZ_doAU>bpQJJ>lO-oHZ3+MpNxNo~D4E72|s&}I$D<50xttVp1puH&PLlrzg!z7cK zu9`K6#T(7X#k2_+Y6hh`QlIWKEKQvC0SfZYOkz%mI9fGN)E5T-O-~~VtONV~C!)01 z6Zu!iTb1vyGqOc}-66yb2>g-t6ay_$_afAPc`xOcJqnMT5|`b^I0~PHokj^plrZXT zK3Fj&R;`a{ArI^BGE0DANOd>-%Uz{p8hni8n9%NmzGc|N%A7I)XNfDqL<%?flly9W zbpCg+??b;42W9tBPdZa{#i!&eB#FZ=D!e>C0u1cRN#!!pQw$$rfzZU$TfM`9ok1|e zvpO^Ph9dNk!r1&gHws#UAUL%sI5Zl{S1#mYIKQ6Qgwd^%>^IeCVw!dsqC*vk;^g!F zcZL57S@jc63V}y$x+SP{i@SaodHUgnG9^m>pMWCU|Ixq85-4^71t`J9{Ikpwh2EUx z$}pdSCK3935$I-)?}GA6AiI|)wF@=o6Mv-190d#e5SlQ~9P}?Q`R^BbR14esPyFR^ z&j(yO1DQBNKHZwO3Is(~O2v#2MA~NhZorB+d$`*ijK~Gp@%`LZ4YwR35|F}(bu$gh z74cD#o0io5eSU{(_&=W%W{=v5`@k zdTxu`vb=aE>K&nAm1V%Oq@NlA%pm;dZ2GX4uaLu zhp!ch1Y6Udlx2js#g~;a4~onBb0fpx=Okb(BLnM;J(^8y>V8`BLMS5;XeJA%=K(9F zqx&!o`elP8Bzt&i5<0*MX!9o;Km-WkQM96k1G2*p-)B6Eu`0bQrS*$0rk6DW_Y?!0 ztM8GS+08b?iWcl+>-9P0p!4RDuv6orJA8jlKaws|{LfWzFq1lLL+7_~XY$({uhz?c z#)OiD7_$4?AI>+56E@H|+1QqLggYh@O)^#(YziK=<}w1J6~+GlKf^}+i%Xehl-mf^ zpzs-4-6lXCH#6J;C4!)WED>)`1TGaH=2PNNW-Pv}+MbDIp^xxK5>bRJIcXD~h*PTm zlhM|7lp(gQU9e7%&HtkFZYsvpiy_^0`9&5#A74SHqSC;yO&#c&RSBZ?$Ye0T72EN> z3?OwjKD!L0@?a$?BK7Y7Ie$J$j_Is(cxiOEve`wZirQ1fx$QvSIUc18Zl=VU`>0Oz z3Oq%ZO;+&_xS^{E$>uZf3Whv|Be9AalBy6%i(7uXCgR{<=6P=}kUhX%DreGSE%hOu zPKk5mojOB^Id_!*_$FVOQ=BY=>AOZyccka5G3(G1N@mb!s$y#hlf}ptYkiXo|7cP5 zrt9@>TdaAF#fWZw%#Tz|&1)_=os18)wo6G9)nDUikrT4Mmt0!&s$)C2ImQ1iqk)8 zR`Rg5PCx!cV%>%Wn_E|s(zfx#{zqFU0D+g*Wvi)H{qnvql~h8XN8fGlfa5U*#TU`5 zTf_zT=ccEX+1~-+u_M4&ayG)viMS<2qho>X;Ggr9an-)@06oYEnH8Hof ztQ<~%#{}~A)tt|A++bDtj*T9h=+A`5%MRnIr}DqO{)G{UvkKLlzB{d-PzSpM%>x_U z`H^jb-+-|V8BVwR3p%B=vc@YHr+W|;bKmQ{O>=Hrma9C1wgh=kM0mzgI>mls8`RHsb(SKjF;Q*-e8G5Nv-CZiMDkGtH;B! z_92c-*4no4XLbO%&I*YS0OXP&{@0Gy?Y^0K?EaHV+z+8#vfZw8&yzu84}s;DB&93{&PSmqJhk?DFKz#4WXot4TIREPNr2 zB7C9n0cUkpRthce>tiatoe*B%H&ffCY)_II8jA^0Ak{$`;E@`G8~DA$7FKVBHYP@D zYbYowLc}w)t^77$C^}dJ2kvG7&Z3i<5pdw%DXwrpY(4CE%0mMexj+uPeSC)=2*hI-sFM@OLd&+ebYTfNcXB}5PRSu;Fm3S8_t>4&+n)RoH*r{MGCBmVNE9}!K{ zYAS2WqlgugLHZC(CS1g{I=v~?PY$0UbvYz#!*s5e4F+|4kWB^so0$(kU{{EGcFlWfeaUV*Z1RSoDob?X9H1QbPM?ex!}ZjLEQ)rD zc`M=@v$htjrp?NtGF?IX_03ht1k%I!sALKg7sNn8oIe6NN+5BG-j~_(;N(ZQ(Q!Y0 z!Rj&CMHHlZoK@bT7?62=NJOC(CWkZ zAdk_rSyz?;j_FX*NwMm*(JY>o@z;muXhxBcPE=AN```El?hNQb{ctJ{QQBxuRZ$s7 zGTDcM!zpWnBj#8apVH=k%4An7ct~MX*yl89b@7cic)>p-Jff_fCtYvp%aXdkfLzP{S?Gm=ra%+SB(K(v+vs zX|M!MH$Q{^FbE01hn5u5vo_SASkb#30l*h!s3T=uJzAZTNQWPZg2QN+6rjwnC>0KW z2kf<^jrs>M_RY2`lp*I1<#JY`A7Wk`{ca_W(`sNMmbh~3Djer7nb_22yZpowy(aX0 z9$b}ZlnZ8NhmPMd>BUZZFVt_FxQP2C)uv>dO>T5nRVvlak)40+hj}2 z`<3T~;Bxz|Ld>;T!-|B zBt2xtE9Lys5I+z1mR6~dSh=5Uo#M_^rm4dUa!Nje3o zj=WAu4vn}Y&}QqzZ!0*vCOi~+2yO$?{?jp?mQw(F6;MBNW(=8gGXaB$(>ODn`S*gf zN1M8*6{wt1ByqtaxiV00#W_{d>_CLIct-86h%T`Z}`JDwzrH)iJfP zb`n-C&4{jd%U1*)GdC~=&~%7`j*cs6BgHpxNO_5wF5rQ|PABSUPu*hS<8O(#*ZaV; zqsXR{#g5gN{}d!3se{jCVM4VtR(bEnG@;?~?Y5&KE)pC5M=%84vtmXMh8>x(nNhp) ze-?AggWs{nUq9E6UH_Sw;VmLA|9#9Nq5Eg_NAll}54~1=Z63yE1D2@4Ep|oy_J1vc zw)YjLe0J6}Uguf~Q2r74964+dM<+3>dwnM1y@NeOmQtuvZV`BBH( zoOhrNFO`6}&&!-IqL&A|r{5$02;RltGw(e4&H4KFDoSwW`tzgn@BMJ3+Lr$Hd-D(5 z-d@fRP;YECov-z>oj7=GQuq1f_rmxlXD5SIUGTd{4^u9;MW~r#Hvf7gIPWptjH$t} zS*}=faZG^@Ef{!2NSr$)qi@6&_SrXI@yP+o8)EU7)AJ|oC`sq?>*0lk6}aNj~}lFteP05#B6yfIYrjS zk;U0M_|zE}6{3TriE$iNaem}@Gp)Xi8F0GgiM^0goWpLI4*V(meo~Wz!s|q~+?0sv z20KXa9KQVmScYU28Q*kWCBq&CKZX@ett^gyy#(ek>dS{&w<;$A&KeWD#dMgO8tolF zV`Vw61HqIANYguBM^lKpZqU7@r;`!eE?36iE~>jBgXqu<9}IK9+q^T|FiKp%id}Jw zb#xLy262+}uHNC%^ki8OnJ9lw{ptAOr=yU*0R<}J!|r^L^i=hra{?y%TN{r%4KqSM zR>5Ts@EJjn)zgb)rW3FSf@nmj=FOW8DCz|XgXjoz{_LaF%wi|K`Pf7={OVfCO7O$@ z<0MXSBdpZq4LZeY1O2T&#`nLtofId+KLbd-d7 zBYz1Sg_Tl_@j{`uNPUtPAQA%pxuJo=U=MB>F0KwsQ^^KxkPo{)#6M7v)DvlO0VZ957d4FaH_QK_=!%ken69*5qxUEgH zl&6xXyJ)kr)TwD{V*=J9Fb1z0%ERJ^YSDwLy01mePR`C`%2JHrUV2sPRFd?*x$H$p za7Bkn{c&6W z&6ZUZ<-C^KQ#lq-M6kN}<|_4HRpCx*L_lk!p|IlZPR!o|N7GJ)omWp}p6i(WXZ%^F z--nS>;&@c1jUMH7Euk3=;&UwJ#Q1nFI-*;2Nxv91>+E{?$fL8w1-NjT< z=A=V`&g(0GaTfHjkU_@*;ozQT=>pm;3WqkMOigd;_a*lN!sULBN9f^pSg&^P5z;~^4kw|hd*cj9p7baB;PrgNtTXr^ z@1580GoEmsP-e6MCYjcDxGk-Cv3^#KnZJLfdqs&L9sr<|pGpq}a@fQC{3M!+=Vwy> z%{?2lcpOto_oq?(V389c)TmLT!W-09ZejN1qH+Cc(N_N=hbNO1vN3 zKNetgnAGxA{q}H?p+VFdQXFh#Nf88`ulI@|%>6g!Z+UwvV1TF51{lbckLC#dBua!4 zFfAjl8-Pn*jabOECvCi?cRZ%H1Dn0!pchqq*Js}T1NwL3n7N*3}(P0173KJkIGJ;K7wDU(I zRXyjx8vy(QsGC;GCIV>;=n3gP5@&H=8zJ#0TOYY%(=L51whMOGGJHBrKa6tgJcXZG z)#ZvF!M~>Jj3_8Iq^aPh&>PB|W`B;``s=2p?05};X8mx+k<_99VLQfSM$V5nWAodX zvu$J;iRCC(Ocor^%c*Y(9bMc2rOaWV)==!Bf4G*%8zCMe=k=?LqB}w zF3at$Oi4z?vf1!hYW6K_A>5w;>=r~=9S`8~4_Ilt(l>;nV-&i4?g|~YDeekQ{IZar zEpYc6(;31Q9HEuFouI6r3%b69zOrZ|lp7M>m2YJYSczYqJ$YDfH^wmDZOoAlqS&10 ze||Paxh_Ss!2enfkXvq;GS#6QaqBDJ1%QUG{%uMb_7!Hm$-988G30i%vy2Vlr`!}P zveTFdL&ehC1FJIrJm++sxEibayObJbNVNyD^87uCs zMmh+3!&vfTyiYortz^z>rFD$)1m+l1dEYmO{LwkvR?ny-y`1A;=U;nrAzr~b%%s7q zEFM8e$fJk``o3F#Cx(9gi>FQG@st%G0=pjR3-f(5`97{#t=BYOj{4UZrSlqoHqErA zH|m0J3z)Bg zxXn}}$fvn|7-zO;)hNVl$HjS2I-b= zq`Nyr8bnY!1f&(DOS-$HK|s1eKw4Tr1SQn(V&3)5AG2IDYtT98dG7m)y?=Xjz^Aa@ z-JoHck0munW6=OxvDfW>IFriVZE2tlvpT0M=6e?#Xv+#$bG$w9*DmtmLO@g(s-`d0 z57XRr_3l0-%2%t<{o!9KEnbz#8K%v16P8b%rYuyK^lC=~6M-mAB7oj|M9)Mcn;pf*hlfZ1P zXGq-lDkYe%UHH4)LYa?G_Iz)8H}z=+6Em~WTFBkM=Zzh(wSEOYSU@QG9#r?kB0+J4 znB8b#S9`+F19Y`NCl0+JTl*EvXm0QgkP_R%{e9|&UX6y^rl_RqxSxeTd-RpJsg!^E$IEcQP#8ALPO| z7%Q5g1Z`;%N@3DJDVm&g6Uu06AH5~boDr2oSNCT`wgPh#+kUM9yyiYQQ1d{;*5003 zVpKf)0zYoWi^S2X=5J^M@@ptRxI&rq<0kLLGhj{meCwc_XucoiugmJ>V80xwV zS;A}-?x1(d3>E%FLN^KTo2)t+ zSxmz?lb;l^8aDOhuGeX0*o2)3s8*c-=K`FCiuVTa^n(ube)?~aXq>)BIqQ7v2VP*1 zK5A2baAWvKgU3v+}qeQBE?_B!mI);ypq zW#3pF{uF6$9K%?BR1#acLd0_V#n0bnyEM$BHxDYB0m?msx?jxh2r!Nb)J*?{S~}Lh z>FG?v4q4kv|BuI<2!W4M6Co1TGQ^fMC10M;g&|f|>3x?3>fAr@UQGA5u9(!W7+Z;L zVU8#_3i;Iw6x$xxaQmDydhV~?h&Cx0?fMALMi4IN3%081U^XrRryWITM^hXbF1mta zK%tp@U?uTJn1FuSf=|_T=tCg^1(C=ZgGGf7aJCVmbbXr{yA1s z8kg0C#VywRS}KN_hjIxFpEIxp7s3{ypr7uZY-b&cke1wa#?+Pe)tV_-OI1g_mdz_6 zx@R{W7j-SqYREzyu)+2MIV-h+PWOk4{Hws4TM7x|iUsZy#tbUR??%OYbUFR+D|By< z_QyJ7hT(CRNaf-!!K}|2)O)Tx1MlAHtvRIjz_UnuSUlqZF=dKQ34In!EG(y2e}3=_TMJTXolM5JbWXn{n=~r&_3#5YhNp&- zOKtEzBQJS;B3u6QWEA8uAh3N_j>nxcd}H!}0)~a9(z}(Q&J&6i6#Gq08<}K=%jzENHT7MGWDbjgL*ad@%7s68}Sv4 z+P}B`GBFbz9W0X`dVerV%JM4;Hy^k^iGzgTlz!R!1yiqgZp{UDYmnwWe#h6m<^ zdY4GE9Zk-~cNc*jw9X$hdR1gck~X}5cidq72VS)ydb4m3^{rAmg@k1%)lF#L$4hVq##G% z<7YSdNV+dyvi=v;unsQ^+n3s3$?3_gC=F<)`+`?8$?9C#B2M zOjtK2uvH;0(RJz>Gf}6VsYWOU*DTPB5_8|YH7iyV7w6On^~MYpc)R`M)=PFSmiA9l z*wsb~s0fh10KjxR8E`9j;ZlODq%6Ik3JKqLBN-z@!)ublt&4-K@(-TQvd?k~_V!X1 z^@*?uXqPP3!rmYfIDFeoR5=6wYiT-y2a9=yT z^4fJ<2tZm$C)Vv8DsAt*Ro(o~%x2%^K*aPQuuPURyq#e@(Tt zrlI5b@}*>YlwpQ>dX@ zZ@q-vw+07ZgMIL`hO1TOhNQqz_%FxC#S8tNQP=&fG0tb%joBYv{jlzcve?3+@Lsg6 zlP(s?y6}Z}2%l9B9i_}DlPD}47k<6`bl~O7{I2_2zUgicR2r$H_a8@JQ{30im}@C; zUB72yWHh{i%a>MORyJ(LiMi0?ooQs0naD8cP(NA5th*Jupff7+z#a{u#VU>jFO0li z(9#^)uTu`*!|kW2pbolAJfV0ISm6KaZ|&Ikmersq*k@5l2;4Bitu5Qf=X#e2>xFRC z2YDwGk1Vygv5-2yhlO>#Itd-oftTgSW4xICidH;hv{ZH>4?Bvm#fK{|uV{DWZwblC z|F^rMpcv0oOC^9gIYbE3;GpbEff=JykNrPCih1a=9gjop0)qlJi{!NiyZRkdhHtXW zuORsga*3&8A7(t+@Tr~J^$?)&HvTIWgIgp`2TM&1#pl7|4>TAF*OeKl6!3q`2L-af z8Bbw}9PVc#z4V9`AYwEdXP)bn_<2u^vrO(&@_BXih>cWWAZ!83AF~ak5OlpG7D@1j zC&2Y_hg=Jz7>?b&6?nxK9Mc@sp)N6_Ru9j%p?-Se6|#2m$4_f`NRX1R@+>Smes~ss z`wuTSzC1oMazU@_%n~S>oZ9^fi;hR5*+0nw-T}C?OeR`a;<@_n%BsaiXJ9i~Tux*Dk;(JGE%fU$`N zpAGX|cDg&#`&#N{wsegd!ld`1#8`qQuD5B2gIJ~nwlx+RlxkQlnKjm^UX)4c*%XvD zbqDd^S9<5BpFs1_l{j*oHe|X&AWPmdZ?oB^wi#@>RMa-T-2p@qeJ8{W3IH(mXMU$K znR{&T^UY3lAJtB?ny4GFhmWWlB$CC8-}SrM2aUOlvrAB!iRlpX!zY|-SgwSrT6Mfx zVpP63Ki~B7!tE!qcZ>G-6GaEfm){x1TC4`0qV5>9ABB(xMS=3O0|lzr%S1@yUI=4x0(P|1WI0jbZBZ;h6@# z*(($$YWEtk@4e&>?;oN6lVc{R+=bs>{&A;=pkfeKvq)M3gZi^daJ%KUDRr!WWHtii zDi1l4BXaG+8+(5H84A50)I8lE8WuS1hxMEURbymmr3hkER((Vah`{%v!M@M(gh1$V zT08!^ z2ZDDZ)MjbEvelE&DgFK#j|}Ldt!O`ek%Ke4%N&d-VDayLxW~ zvT0M+lGeb6d=J``*904 z6oG7PNvAF$ak|X@S@2~0S6QTXi}!m^tP3nqGh%JsGcE{*YNY%<9_h~KRa2RJyCZoyrU-ZH=ivS7UMJj?!=HJA5) zB_}yum{N1;;tX|S`!`G~lO2i{4!r^yf@K+&eL?f`y{lxVDLWHnL#q`shW%5;1Bgvl z?k7`sh80sH(yR|1MI`TNC-7hjIS18HuRq9Xs}RYruh*8}eC>yJg#F9T+O}IMn^6Yy zDJD^rF?+Jc#*-&BK5|XZ>J2XL1vx^-c~BSrj4s{}@~#91&x831r$%@8yF_EKe7S4E zYM_v>r68@if+Z;b`v9AOe;X;`C)_+qVQb*5#toI+k!u5b6UJwW&#`klmF*|fn&Ibr z`99M&)gRqYM@V2+q$})2(H&Ki>)+^fwDhu8MG4u7^JUYE)2F4n!C_6WL4-CDg_6X_ z99wfex6g@7j;d=!VAqim^UnyJxsoD*@J;O5lD>f>$S?1I8WYKi4ugk54xfmxXYL=nEdSj%dAd~nkU6nG6VvA{>Etbk|>$}#suHK6Y1KssM ztI>(?V%g~s*++8ha!N{3W}Hm6s*L3{OEGc1#ClDGYc6K9^diX&WS}daYzDWaQ5b)U z@{VtIW9OjO&cZhZw^aW&fMa+a%oD6o13;^Ltx6-Pj3|~lq_DSd#Hczuq@)P_OABM2 zrgje`k})buKPd9Njrk%y_o<1GJy1BCqaw9bSv^~mRa4wX{{1~#(JdEhQX&aDK|vRR z2S4>IvUpv+=eiO{{bDTKOEJ{MGoPe8JvK_%7b=qzrgKnwH!}5$YL+w6iwgd_gX^w)^W?r z3u=t8)9i!90Ds?z&tv-9r19A`{oN6pN%A+Qia045oC`_IcDX7wI9;kH$vC@-90VB@ z);sVL7|fRfuCvq_0fh?03_%-&8CMEw494EaT}DPa1_Li{lZ?#?1Vo@Ji{ye9E8VM$ zp}e%TCq*tc=JnMkG)}ZX%tHp%Un$omQr-VV?0pZna!t6vhXVsCZ(_$o$n{gg;D-^L zjY}JAU#enFAu|fae(fTTbLda8zal4dPH-V%P-{>X+Q|vLTpr@Et<`7S3K+3S@jtA; z{qOtp2lYXgkMBSs6R)24&D6I%sWA=>>Y=%@tgMdnpasW*-lxEj?H0TKq-|W2)obp3 zI>PV&@*&^7^yiuOpWjxV@`EE2o%bWS4ig`$e)FYzu^CVOnE8LV?xGCj+6cJPIqB-? zP16H6bj8gg{rz|eiK@37af=X34TE%GU6rUYvl)0cSut2$M*M(2)K=@$wX7S zO}Ib+U&($qmZeT=&CVnvioFJgM@C-J20?TFA80#x$hC>Z#)7jxn+q_A^_c#1@ZMwcMZR;L zHU7zwuko9jhQ<%zO>CTl%oq;=n9uAy%>w0%6RFAn08|}% zaZipHl${Bl8gb#7uNf2old;my_s)F62pDO-7ZQ^M)Kq5yznp3p#+m3a6yAftci=HN z{iod!Qwr|YktMOccRyH&1P)Lw(dHy~t+^cEt?otAG2e(qF=hLE;Qdo7qvjAu^HbLHT%5J0|7} z&6&F8TAClG>rfC{RL2E6PYLzvPdw4RqRM~2`;#l03k;vo`H%0I7+p{D&b|E8|JVXu zySxO)jFa_C)5*WKs|p9Sr#HQ-yth)}6ad^X2vjbM85J%3h@G9Y{_h1RS;A8Z}VkmhLPHgXi(FXDI3&8=`QK0bQ2 zH3a^e(`K7)v9awJ9a-V-q~p4@SQt9auer46=O+p@iqFrzawj%^4xUSLAS0jzn`h@# zB4T@hN5rjC-Fii#H;S9=`dWIME|EF%S{0WyZZFk15dIqvESH$yuZvGUP8&_L6+p`Anh>XS#-ZMT>8S&)zS?QQmNp9`p$r+n(-MsLtGv0PhO4$f%Gu7f zt0|mJ8U97}%40cG^aVL@icOYF_qp)*-y0X(u~w4qp_W!JE~vpvb}Ib+{i|-Q7aV^6 zzrIIh`C!-6E$IS5>V;hmE6DsLKWszohKH9ImeVR0yo^UlnPKXe^!y=4Ox?1toTS1) zB*j>-Wr|*%k>R=}1g1cTShbokNu!sGZ1tQ)zm_UT48_>~5|t1~vcct^{LRRzB8+n9c z$+Dp%&fbt|Jss2o}SWAH7)9D_6G_#EOEJogt zzyiPR4}hV-WPG$oo$x+!6c`7pghxal;G~S$v@XYN%`-k_<~(}#bsRNnsRxwQf#L{3 zc`Y+q{wC8l9|oTiEa*T6H_7}jr%1$t@#HW?xl3t`_+MSlE;^fnS-*Tc-TggQEHRc2+7V1zZHyPXy95F>hub`aP-lsxgPh@}4v*>Lv&glQHe2SG^%` zk--mvxeySb!+W~Esr>L3iOl7J4`WbOMw@_rWNku$ZVY(l@(grV1S2|czOifa2ki$N z?y~xZkBCCxh+U8c)C@=dlA($dV%RMq`!Cj>|41%I)Mg zMB)4(fohPOl`+qv)EViaK__m583Hu5l<4Q7-vmxVi>Ap{vObAR)h{>((SVNa`JB(9 zfMjHmU6PySwxlR{YD-e&PrN@uf+PkNa^v(32~CtS%X;P3ELy&y&q0zJ`8X)?zzgF> zG(TM8=tCW35>U`%+x9Y{Ak6+iUt)&zd%Zzt91>cyWby{(i&)01Iqw*cLsvcJjb_+6R zX0V#7*1F$zZP4sWN*VU$zrVUGZ=)m8Q$_x8pV~0o7mM^4cB@LZ{QdoT$5r^_YoyqP zR|GfT8mAdpFkI{@BvzWbR9x$ht7Ov{6zm#z?*}ocb<3SIIEg4FNV9qke0DDu=irom z{InES=x0YOS*K*2XUqkN?!@UbAe22roa_!d%J>>2FqF7OPf4RtvRTeL&gAjDR{lhL zhOBXv-iR<(G7+CEs|>N?0@J^iv9XHnjd>j}xL}I}7rojE-LLnY>1B?M69U1!iZw4# zMc$L!8;_$q2LV?mq0{`4n7jRXFG)ArO0 zk-TEV*Zmvdk8egpPv6HeTLhT=a;N=Bs2^vtoAIMv>a=to zQo2;8q$~Tu1jQ*$$_GcJ3A?v7 z1-Yf;X+KCpdSn##Dgd#@PQqLPBJ)Ct{@rgEr!uc%%mQ76GG_GO-Z`R}uKnGTw7 zOa%cO4^A-B!x|J44|TVt8k?_Lh45U zhQlon=pPA;<<+{H@pBn#>%rfM;xvuBoiqNK5NOf$l_KYMnFkxrw&6jIDg=u&j)D zR3ZxEszs--q`27pvD-%yY*cf5G{>w2t~L20M{aD&E6)+fT8N`Clcw1_alvv}FjpIo z=)FCU>BBnk6m%D-KJab?o3Nd~dTM89c4YmGbX_wiHk^=aU4Lx~wEqLr8ooF%cb?N4 ztR1)91sg!^jDvOGNGK!m^mra~b$?`T)rVAY^(jokfw2<&J$t_cD^+w4OOVGDmbIr- z+nKG$&i+x^2xE>=^%Y5V1kIgT)8pS8k6(QkJo^kdo0siPM$K(#ZPvOQRrBMb$Hdv? zhpPUrOP3p#isp06Rb&+%?JLI5DPyY1IKdkg_>aKlB?DgQdjX4v7PuUumYw*&z1K~~ zjAMvk8&3;nR3?7^!1Qq{+g};J$f@1lSr_Ltt-GmW!E^h!AcOLLVs?-+5}+VYFBlYZ z-%20?&~Bj;wWbRELInYd0h^G7wqkKD7#4dA)m=d6`Q2MBUMG+ z|Aq`jNZF(215$Qgp41q&RqYBaS*y^n31u!oeQaNl+HK*rl2PL2LdZJ$rC>*qkx&TE zBS;J7-ZZOf$MEGyyQ}bQzFH}|GiL0E>23UTgT5vPB+@TF6+7U(xt?k20?ip{pr&I9;J(zm=WIyD_la=@}93+{6s^1hB<$2R1ac)lO@w}ml+x@gFw>K>|;SGP_h0%S;=7S+GO zRBPZ*3V+%NEIzs zMX)_c$sV1gXhBE*k+7cKpayY*1F&*c33y%cFZ{a<@Sz4 zUk!ZVVX`p$)(Ym+5#QUT&f?>~ z8JV!WJ-)t}<1p|LSPJ`dc=*qGt-I@V+dUAC4-W-VtyiYX>{VMqQjj8qUBmEagSs4t zBu4N^H*#Qg6>26_GruTY;#|iwR z9nf{-NJFPN1T}l^do3j;4)ay!2W`N`sQ9vCW*lVKFdb~e5I)o`O@qRdIJoK#W*)+a z6Sdt6@8DHhgp(9(fUqRAq=WbnQ&VSn&zicwj<)Cfpb}X%nWz5C93+~@7&#x!PwLKa z8*YBvb38&ob+8aOO;&N-)cQo7E937*n)6@lvpp7o!~D3bn$BaV#-XoBCUfC(^tBKe zvqwj5$y!Wj3QKR!e)!CW+E}Tw!Ooc?jLlG%dY6_|K&Y!g;=dEL9nIF=&H&x+R-Ws| zna|w_RI+_eygr8C8@>}|Tc z3}ZY2?>)Tm8%?+nF5vyx+1TD$>rV;IZCbiCm*B%Ps4SimFZ}W44!r@A2q-M9^=;;W zH*dlIK&v5cqhF^hxZ)FI+mo^b0pcjyr%D|9B}L3)QR_BdvtUTrK7|!TeIxAXIu&WM zpYDcH8M!w0Fj_>oJuGR z&rcraZKv&C*r#ex@G8Gr&nM#?51$8=7a(n8e=ZlnK2nq?8|H2!pmIwj}%Uh)-=tz$JGBj>%W19{lljGIF{4GR%) zdTISgvH1cvYr~CHVw9nce)i*12rGo0@3mrERykhgxY28ao+sEi!d3L!k-9D__I_Jl ztw8t$O6#y<9E?$1!OvNAZ}65E17JSEHOTsOA2L>&VJ1x5D$qpEx)3}P^;z0`CL+@L7I?Dq)|Gd-LLO+;zA0$9$T6b|Oz-%lzLTK!jS2i$tT6lI^Q z{jz^Fk?R0EwHZxUSOF;*4%CQKw_TzN1PQut`~U8_K}d)(N4hOoC&Q^TLFS{Or6u8h z>2o-x(6JJ$#Z#Y$Y4DMr*UiYR-k`Lk#O1y#G1x<4ilnu#Qb{=))k9c8s<(3sqZq%c z0+~c_;LskF6b>_5#@jL`;S$ad+vEIi`5Z~xpUYze(EwK8D1UVH$*ld6dw5_#W{*0J z4kyIY|M$%0o;Ek>zO{W==vV-batK}`x z77G64M?Fkr{MTsdMgOk_fI|x6zA^A9;;hLi0T>6W`A<&H`+;m$vLv+*_Vw+=THoRs z6kw$MJ}X=czlq$hBMVc0lUq#_&R}etr$PCxB7mPQs|8}7-&v`t>zuogrKm$YVWKP~Ntv8!moJWcZ$aL;+KaiNbGnfrKy=%lh`uTU;9tSbPC5~!Re ziAkTk;38dM`>$)_$8O}C=A#Q-KF`yV>~wVA2opN7oi}!AKyW^lb(a-4G)%i3YyL7F z$8fV=8UpV#n6n@w6pUJc^vmvgXzl)C{Zj`GCOm%vete3ZFEG7YDWf#<=B1LhKqHYg zCRdLpppQ)3Xe?v+(W2om&n=Dr`ecAIokH7Pu>VjcmB;ea8wl&R+(L@n+zt)EjqiN!ZMPNF+M<(JCvG+lZu<-iROsDIZupRAei`(xveO3lsCaDBuOLRdvO z7Mk2dc%ml=U$M%&r4f>-RIEyz&SngazZIiZ#TM)ZaM5E-LVDI<^8>qOf3)C7W}Th? z1g2*nq7e&JS1vn&$Imeu6w*cp28xsBEy<438iUssHR|9v@C^duIN36K2^$y^? zEY?y~ksCCZ+IUgBFigHbkLKoyfuabDHZ|%R|>^5M?qO4OYnsSg^FtATp9Y{Z`dvHr3LeDUW z24J1~NoQeQeYT7S?-cXrH>lpMeM|GN^*OteqrYzt1SxO?v;wA2AKl#4944Rt{v7!? zCnhjJqL$dichVih-`Jh;R5t^dcE14v^YJTPnNw%fg2{)K0gh<1O>$E?Aolu$G`tmi zkv+2*P52Cf04M#6S>_QX+RjT{J>$T(&|0^qh2~|a%DJ>bt2p_dRG%d(&d(b8j@J7C zt&qv9zUf2=IYG$AJSE$X&;O+1hXL(d4+?)v%MEZ2e#(UU1rS|B0MWJgk`J;lw5i7* zwE6+*Ul7(tz6g+2A!I%Z3oSP=3H2@9Y4;7r#8?-CE@>VU~UVCOY1OPMQb75^)$+njPJ6Zm92;iU$v!Gz4^_wo$Hta`xU zSOP0^QgSi?v9@nelhgY})gHT(z<9#K$xe6a#)=g^e_ud>VkvB`d(KohN` zsBkvfMUL=?L**}v#3)f_f2E7)AT`aIWD5%?;3(g9-|-%3kUSz3z2(6-kW32U3uXGX zKn+($!9gE7UUd<~6+I?PV%6tz|2BMsYi;cKa|n}ZK&N~H<3oi}v)i}f6dV%v;a5ix zFXsx}MiY+-nHyL%R3_iS=5up^!j$cRH!>F-G5vkZy2`fPn_Bi^?^AH7ZI6j zNB+lxm?98$#G{4kbbHmRZ&3FRcS!;0{;~>KeKB9k2BilcWP`R1}ix zj$ppj@%OCqH(L})AfGKYske1JkqEZqfz9~Izp}C*wy|L!yPr)`Irw4pO(YMVTl0?> z*6grl*tjSkMbP(Pv&rix`7$}pCLYoe;4}_e>&v>jXT7Df>2gS&xgS}m`uORmH%F8L zE_Mg=Co?lB)`DQH;!Gw?e#De9YQ;tNgLv936lu?SkamnfkcojJkXQtr7+%7uT^>QK z9a@n3Dzb&fR@TRweW0wYfs652QGthy!B`{-T|`$)^TvB|O|W0fGL1PqTo1 zdV};&U|=(BIDoN97LWa;@$+TtdIRUSvss{^6+0(eH`mm-0hEBVw0eC*$+YhM^m^TK9594F(qRx-z(8BEl?dZ zJ#OtBf@}SlXmvk9M?2wzeuohckJSI98pslH=&L*`Etj6`ds; z&B1^!LK;~`s4O=wt@a7BodLxeZ)jNnxd1QU74!4J0j+qH05i_t$33?}X7#iIKBg~= ziK}5A~7vqg7xr$T(eWq<52NCQDodCDc-z!@QpqLlF34i^>TXp|IWm3!F3;-B|Z?Eu_`5H zP}D` zgHZqH$58OdiTqv-PEGqvDw1RAg|liwZj=N(vpsuqGv}RuuB-HxRY{m?z1!cXDcn zLT1H#9`jfkU zldTA$iu=Pq&5wXDje#}hf<}zLtg^qry{h8|RR}}^7d#QgQmv`LiA3dW7@s}Q&q@mJ z*Y-Y2H3@(4Jj(D;}4z9}{Q0X#9f7%M+PR*J#p5P8UBKpC3BtwR)X? zsZUGh@c+Xpgd3`v0OXn^c4MDDBHinor3oZQ+%O}dg#`}(`AI+Z?NG_vV!v0R_XAc4 z(=cm}EQl4XQ__!sacTpGDNx#FO3TQEURJ;YQseP$Dv_qeDenJ1a8tvd?_)~scd|8z ziF$srrG8`0L1S~Qe=+^#%N}GscSrSESncJ^>O8v)c5qI}j{?aHA0_@iLmXp@_r)~k zR}BbuX?0GIjwvyXOoH>5L3_%~N`Ll>JK90FPVMa6DMDH1?wS?pgdGI)q9Y?o;9Kc` zsvH*v9?joFXMf+GTl|g-H8QoXyjJ=qz$d-!cN`3`Ok!^wVehOlT|jLtDD4_vzvi=J zeg{YgX#7$ee^FVjRkxst{*j`KuQDjN3O+X%q%BBn-nWaxL0e)7P|CNh~T@4Q}Z}pT` z;mmmQfu+@wcAo-GBG zFfjP_9DdY~OCg}9QU(x?8wd!XHR_;xq-ZE(jD&HdhFNhI?~JmUt+Xq8%NuMoweI_B zSohq5GsHMKZkPLi4JrK1jEq1h#y-%keeQ%iJ`?c$;DA9^B@m4mJH%$K_PfPg1tsVZ zx1TUa!iTQGS3keW8rtZr^#~Xa8?mp6dY!ee35*Zn|lmcccDV~PRpBlIms10D)-ai^8^&ZE6|M&os(gO*zEi$5eam&z8R zz6Ndbira67zD`@npDGnAh;Y(h^O8z&o%b3|?aOI=MUrCvTs(AKEQc zt69(ydRuB!(X8p6vOYT$Vwol(ff>R{pPd|+t^k{PJ;JXmoIw@d)9kpgA3kKhGja&P zK_5sMeiSVm*l6TAqYcKq8w&)Op|S?8;0%Js!v!GB-NTL*W~s%mNKYT+R7Y{=|3EI*illqEgDI0Y0V=#r zyXt5&h5KzXHf)l!O$0KJ5(l%@gu`bB7EbEkLkdfHMFr(1kLpa#t#tau))swgp zjS~+KkL)zmg&NXyH)B!UHns~!&Bp@#^Fy%DX{ZuU{ydV}_VW{6|E356=3l_rZKzDK zj>?dXeZGYi`u?@u)%poga!mbR^nq&>S$|iOj@uSl$;Ko;?8Ctw0X@|_oJNk475dePT~U| z9SwNRec*IWQO#kQdmY74)XKuno>XVm6pA~)eX8CY>;qYiWsTW`JvrPv+;%2|j|#8@ zGtnvq5kQFud)gGW@O9A4Vy;7c=w3@wsLu0{Xb2}6tf7E%SRW&}OOI8S>rPu?&;6dQ zb~ese%)eOYE2}8(A?$2a4j)Y~kxJmhAHF4Mc_j6VFHC=LCWU2-5PJn9VZI~dslqY6 zw#yYnobm(gVw`mTOQhvtZY6zKz!FCvF7KZeOxZ6L0Mh&B5uw@q`arISPz4E>tI9&U4wH$Wv2{=`ZG4jrpCDA5>visc(^_dx zMO>%Tqsex9r;v?DkSG#BfKu-{fK97cBld7p`?Q?bn10qvj+wA@TlNp4)$V}RO$~Gc zKYZG}%lP_S5JvA%MEk{6?ntc`xs-$8LkFd^UF~Dc*pu3rka=FyTdkP#=s4j$>5bWq zN-7v-TXGZ(YG}l6Qn552n5g1v6mg^a666^MBo80`h(!G<{uLQPxXy;?1m;i)qayP= zEnl3}o`JP51lVL%sljh8Cz`T?ZC(Z(X0(O1jBCBB3QGF!lW;Tp-Rb*%@=rN_bkPLU~6(o(?tm}XY6U^TdR`b&>VQ6|5jBgOp1H$G*3 z!#Et)O}5qoIsD0&D|Trg#a-Qf1;Vy_C;j}?7kYlz~ zQK;G7wba)q)1AXLMRcriC?tR|q+HM@8&*U+>=qq*dT{qlDbQ>_Ay5F2>CJc+=8QDhswG{>SZqsVAM(`ttOx$S zkiCk)uFhFw^c>MgMK}f@9v*riJ@v~81^91urU4K6$TPc|>^q~5`Y3Kn^W~;VuRx&; z#4@E^@n-H(c2e9sY$dQOSkBJpt3F4jlk?LUcSV_Rd&xkqK4fieYV*2qc3#naC&`Q+ zk}IjO(fG$BEJ#8cF78Hz3}|_a|HF=@-A7-=9w&wSDVMR!Y#cbv$;o+1lo+abV5W#E ze83gjvfw%8kv@+ifqy3gwLmh#T97Js-*ZCg_n*HM@6vKgC-i?`>C;Sq14OVz25K2q zz&Q5{ci}tBp(fQ1J`am2423eBpzTpP;l=ZDM!RRS+JH4}J$i%WGRGTN=yCaLX~cqGs+@FtFNW#8I?vIJlIc z5TaK-++`UK?#+NCUf}g*aPT&!ZPBdB!8q2dkYDmrkvkrbGOy%bGUiy3T*Vw0K*4c> z@UcUuBW-mqRLoS}wpg2DX!ifXQB^nL+N>uT_28jcmNH zPK!wdN+Bbn`ntn{vE}fx6l;Gu4Km~J5#5!3+TncrjM|V@r-^loFVPgys!$y`=%A4h z$%I71qR9BpNl`w!I!1NzSNp{a#r0CDs>okVSf8M;V_#|Nr5O*g0R3IpdwaxK;bS8VaL()z zSG$+NAPpqynllh_1A(T<`C+2L)G-?anbO+aQz5=|+uYsAfS44ek-dv2tW^?soC)nh zA{OdCzzF-Z zN%#JOxU;wN3`KUqz0#1wS<;Km{QUCy!IfVXeth31oDT@L=&{wuz&-25UV zk@%rf_#sY*@rjfavHi_*<0#2A7>r|%LKzK2!k~xh=B6#etqLl?r>>%j{I<>QXI{fH z$4g?txW`Y4ktxx?E4Y3Qn%X^pF%F>jmcM?5Af6q4iW&U`v5U<_D6#IHec5RP>oN=+ zHJ_o%s6$kir)PbORbHSoAFRu1GdqC~*b&qPui$E02r`p`gMGoWQ{#f8-8_LN=6hsA zNR@ZE3a+0VV6^&`P_9#&Njdx_-a9(;GNse{H?1HN%lv(0+%I?UXez+*PWdoY8W;;H zK4sK&k#v_>CY2;A#7<0ZjtdFDfL-!GCh4|9;S|r4k|`q{9a)XL zd>;c=VA8VGh6l3D0Jy>(fUI6jG<>w<`tCud(OZ`8y06 zUrjt1kD#3}n!lf46HFWx`YLM>vN&PjzPBxz*%!~>_2`Zdpx+A$3PAn?4P^Q`Oj|A? z0q7$no!$6oxW`0lE&3wG4m>oCzal5q`hhuok77(50Bq|h;isCc^U zcoZuzx&FEi*LB63R?{;)My>3ct&&LnvNMslJ(i^^Ws!yaY_c};)LUd!jKoN}&eXN$ zK*-F+{$RekC;YZ)wM8gnBn+l*K%&y>z4uPoQ?*{a5R4R`XFHUpTl;kd{Axx*X4nPF zK_EG>A^SJFESJ*yD;B?e$u3=#1xeh&l&vWhpK}vfH68(+%!(^wGDeI9AEl=Q1My+3 zIR62rm-*=fpS?#-)Pz?4-3&@*o;YQh5~_>YUefO3Q7F#N^z z$n1|$SQc?PCrx}dsx*^cI{zf<_q{ebi)$kKR4Dru*)E^-Z_SHZeeQ{%Z{jhWkn#-- zPzYDlk*cubBrPi{A{Fx3fyon8^OwJlVioCCu2)Y~Z@wB;mi?XK*)To${-T>N{xpz| zA%>#5?#EbOy@)hgo(dxU%^W|<_}JHRgshQW>BD6KRWy_~e+yj}pEYjb>DLwnjBT@w zugBk@vdo7ZxHFzoM-zb&;sM7T8bP}J${<0wfQwDhJa1tfoFH#x$7fuiq}`!GA9P{t=QqOEiZ0xn*J|-G2=)UCioRidw2(wP@ZN{u4-*XQS7?!NF z&?;zvBt(Qt&N=Y?NiL&?C(cjhYrl^FEp^Xw!uv`}Y4-(O-E(Si2RgfO22;Zle}cQIQ#0H3Z|TsEH01H)o+l?P64Wdn7CmIj z)bbqO&_r>^uwwRbPdg_~!B#T+9^k5~T$;+I<}4rgY714uEV1aD17G5rm+E||MQp6d zeSo$VYV3x8ebQ@%{pCGE90_YRDm;hL25~asIi~Z@J89|6xFYn3O82_!`*Gw5+g#=Z z^%(1-HzuM0_w-li_m16k3DNY3z)EZuzUf0p+jZMB=YpWbYju{ zpB7+9u%}`dt=4b58DrjGh4Q@?>!iPHO*X4;4L#ZEU#w^1eX6eu=nWCVN z>x;)f_-f5VyM->&3Bpra6;!J$JW&*$n~l;iojmvMIWyE{vS?z}-oX@6>kj^PGdgah z<&eDFvWPN+bRoqwwiT6|oW7~4?S)YNuX)vOBfN$ADTfTRB_*`NNg7VRPxAMFky*t2 zGHNa?*Pd$?_j3?$$m@(5Dnq#JyD}gukMgBd%bv|llXD)=aX|iASPJXV*VTaaw$B~q zVmZveyERM7MVjs+)JW2VDy|OWz@`lChnq0>PV$Qm?PTb2iZ(zd{5~z zgD|voZW-EVpy?-CRu)U&0iRSsf%HhT`JnpB48%t`rnv{2y$$jBEcWj9F+#33XD2ED zHqJOEC@m53*0sUvSaE`SiF`x)4R0mo<8!>t>I|N(rrf)mGZ&O#9b4x*m@P-2Xe;^s zA7QPe5p?-+f?J%8c-2YihQhn+4-Fgi!52>p$^8 ze#&^XrRxj<%_raY8kX=_mx4Rhll|s}KSA`KQMnfDS_LNF#c`vO?~*K0tr_wlOSZEp z|LURP6tA;gaJe``=1`hS;Z|WE9VAtBoBa{wy*?O|qH!KA1{vlevL!DtalJU1r;+@> zaGhsK7OOcg`rCgqdEPm5HVlkHj$z!IxNqz^%dbud4spmDzJ}yJV{_o>I zU2N}KnH1f(Mr+mj`^HtLMZ6}A6}DJ|s;$Q2rC(=>6&FwE76aKYzPoRHTX-Ji{#;S^ zhpg{8l67hvTM$RiGBqEZW@_{6s&3Bb$uHTSP3_(e}f>thE&FdQO z1I-^E1u)>)**&wEv3#_WXj@1b6_s!I>{-`x^o{>(e#K>(kL!4FF4kcteEk-JG!`t} z0_b10S>?ZhC<3ShwAyK~rd2?FAn+Q{tK$#CEeK@#yQTV^^+ule1|U=z6%K)zxzP?( zl$9}fzc5a`iM^#3Jp*p^(@R3rs_%Qy;I;=j_o(+)Bnoo zK7E~B6ql@ibQSo{*9a5QTHnN*AF#sr_8}v)!O%#lBWm!@@UFPO+rNv9FvRj!Ir^pe zbCLCant1A``&xuEQxgmvWGUmZ{5&X~7P@f;E{mg492CCY`Y4S-hxN`mr!I35@hyf| ztpSRLQ4ZlG@aRW%H+9xUmF7@pJBCU_VsqlXhN~qL)g)8IhJ$*u`>5=Ha3yb0k! z^_*|+3%li+tn%I@uR&v)NzlJFkn$nGPym{hvmxi8LkQ6_aqDN8hGJxpUi^pb1YQpQ z{!RTcfU=>`jOzdqDg;a_U@m;+g-O$QBj>Xn%S%YWOT(tW^$B1`Dy#@#%iUKZNN&Py zfRIV=TZOI$twf}a$;CzLTc~n}2z~GtVZEVZ>9_;M8ThxB8$jl1*&|0KX@gSHBO>QR ztt>kA<-VZ8%dT>69jDJ)azE251p>r^KZGJ{iQ}S@#BEE?DRC_4Obd&moy@uxnabmd z{l>6Bp2pGe)4Xb?n&Ln=p1_F#@=nDt0@;O}KgbwcR;y-|)w zLC{`2|Kd&SUS$?Y8Qeh?1UT8r8(#aF0#cwjq1z4Ek*8^c;Js>n`YVR$!D7InvdAHH zA^1uBK(0)MNkA1U?R#X$$1uMjmLL|z6s*vqBzGr`6;86@bbC+;l^ zgjV-D(BjoS1^MVJK|g@NLXU`?2n|85`EWw&hlPb)m@_I;fiXl=!H63z+E2Z6Tuz27 zg>R3I059&4CqeIAa;ubRD_6*Ab#e5f=Je7rAL8|pwYdRn%nuKt<10apca}7X)^
*Dca)H()zk0qyTlM5|9tPxDzYEh6z8))V$vYXT*L0u`clOA5o<=7QH^k>y2HZZ z`EA5|?wEod_NMRrqhLey9TnFJyxKJs&JMJXy7LsUBZ+skr;H2*my*MnGKj=C$-DZ?`FV9)vWb^N_4V(f)qz)bEu zQyD@?MI39@9f@nZVRj$%@}Po)>T@Wd1+p=kDf>&^b5ON#7&Rs`KCmK~fj73aKUhqI zixmFcU0NFLY2;65BfBFFdU;@)e5&Z>0gw7l4uiiId8kfUcFz0c;*>@*1aon)uDPIK zf@?X`Ei)P+Di=lN-d;a8Cu>J#A?ud?^590pzr)_`HEwGPo7*TjR6<&T3_Fhrvo)eo z3_(;@GUm=i_^LORLg;S^w2(P@E+16%mKi1JOEc(J5AXNUH>5IXgu34`2}Y%E(ITm7{J5XQwS}BFZ-hJhiAMQ73vGc6yODn zlkyO@aB}d|!g(ukzbm{D0X0EmGJOqs1qBQ#{ov_GKo4}`3yfj)0iCP7%X8=_*&L+{ zAbu~z@DRmg(xGyf*W-lCz8HEDN{dPx5VN)~*ZqoLy7ys$4L>9T1i+%sA!SRlOik%( zf%8meSoI{H)us>&q_oK{p-W>5vYEDD#<*R+>h zbR{aj_w)AuJ5V_Ygk%etrqW-?&@F4&Bgzn)O05ycR1_^poGpomJ2q z6nc}Kdcs3`htAYmFzboy+>M@oQBgiG@T6^_H11^z80d~KX1tYXfP!O5{P7|W}c zo#^kHrF=gsJBZRSrp#m;B<1|(U%-ok2I1D(w{vD&p4x_{hV6L1(w!Bt8X!DQJc{fa z=mOc+^?+cH;Un)aD=P2i9AD>H?k9e$N<{>x4q>r;LKttTbSQg~-4;qr4Lbb( zxbbpf>XiP847s(dzQDEk)k!A%zVxXC&NY>Uy!gG>R-@;nZW44kQs+;E{6Slh z-zC3Rm8P~Oo$+5Zu<)@G$||p@=m28bN+06)Z<@k5pZ^;K{}5*AvWL(?S1yHhok8>g zgY}@YsWMLewh<3G70~D5m;{icamRxdEDs=sbbU*E9#B;tN-xh$EuHJdOn6VSi8%(; zWN?Iaym}BlML>n(Mkvn{YX9j`EEtc;`Se{ zy~;K$(;0X(H#;jIcr2*@B1iup(hwU~py>N4*ym(W#Q?VJ{iv z`!P(A@M=JipO7N1@i6=(Hcc}S{bXaLUD{3(`(CO-?!?oS7SEql=+f#Zwbn|EGp!{L zPgAR2^Z1#L>2kB8$f6*JbQWuqr}9sv2mV(UJx#dr?s+@4Ztm|}C=HqkeQ(L4^y7F! z7@Cjf5egq)(qPZ`t;Mk`T#uwh)2_#@v*+{{%bMyx{8G$0;okSjanw_mxW&3|dN&TM z0Z*PRj$aI_pTWk`u~+}SylI^rVe8~1qe+cTPM-o^23-@A+XxWv`7 zU4C~{6Yil;HlX>mt`W={-rlwY;20_cpe6v&bQmyz@^?c!A^=mefuZ4TN`cD%R+~cz zao_5}d|S=v_(S{l?@=Q}4>N}#i9_&sLX(6|uTuyGenauc?|}2m9TQnH6hoU2E!A$kuwS`+b?xi;oq-`Cs5brfeBfS%z^Q+V zyNLyW(Fd!%k7aIdZKLczxkzT--)qWkqAQG?b2E>ZYs+hWUotF;t`ma$HI0s9r*hW8 zNYK(Q4NKkP-u+Dj#tb=4AJIrWiCBVAv^W-F0*^X#_X_myXtsCKTsYXOsGFoZ{tY=p zF-bf8Jcr4=?=U9s2Ks6kvnA}s5x_CRg^z*eVbdrGPgMn0!f7Bdg9qUjgDTnCqgKr( zOo?~2kLUy%D|MP){*%W?AlMXiO85(_ep8;Qhe*&;zZ|y`FwvR+3YNv_vI#%e^4}S~ z<_A7EY#q!A6j0F8=(-A?-RM6($Q2$I*!QxX6jI!h05r{S@1zc#!(r-d14?C zO*U-~iAL4;e{s#bEVNQ29Q}V(8$am&Lq^$k?#?>CI^l8Nm*cR)r~dfs+xIBzkY3b} zca+~??N?|P0*3fZ5Yo+_(prA0RHlnB#IF}3+blH=`|j}J`!iBDs!&hoM*Y>czu-~L z)eE7$WnJ^{L#C78atOxf1gaK@>H;*r<%$pqLe@zSZlQ;Pa{{2^|8_1kG~{1;gRYd* zxVbhrH)MbhDtRe=SyN+V@?l@Foz*>*Ri>|82!q|QQWD|fSW~YymBMC#PT}p zaqFVz+nowZVD~-Nh3%p28l>%BJpkIu#4$g3U@>Un-gyY}A>D4LhVy`S30g>W`iO#o z7jOY`jDX*g#>Q0DJu6&)5vXn9Dr`I^(pZH@A5MX3T7p8v?Iek`Fw2_R9|w&>Bc-!; zWEa<;sXV`-@hWls-B{foS&GGbxrjwDlTJ_+JdgG>nW(nLyt7j`8baXkCUEyOf!dkgEt9tqPvz*Gh5g3R_mOLJq4^y$ zCoDe*?whkatGvybrjm6X?3-e zHb{VmQu;C&bfF4rVIhr!zRTXE%dXCDd;N~D;zI<1=>5tNv^J3%Uh&uXZ}~rNtX|oT zou!L<#@5pj#Vb#zd0QY$IldA2qn`|~_sto0A8q*WW?BO@LLc>X`Ke=jCRupOs1FpP z&f-49u`+!$PPw|WDM~3<8GBvGCKJ>FL3wIf)(N>ib*cfEK*Ert)DBM?Yj$Bd{g}7S zpMB%%ldNE?DQ!u~#FubpZTdxP%=QT0WFA&>I;%L(mIXLce)L4cj1H%ptSi?(P0EW5 z4Fk+jiKj@G53ufsl|X-bnj9D&U83A>HB(O`$wGTYq-J+8&iZ%Q_8|H&9<5pZa4RL; zAW&IezP}3Y?jZVszBG3*2SNZls8E=(V(yKOm}QwMzgA)_nKaPS@_WL<}eO?Klvl^n^>kc|1r}h*ruaiwibVgG5{^_2t?BiT?K8+A-4+!Pk`!H_ByeCcl zoKDoO?p>8Rl~Z2HuYyC$``CyXy>Ou?-JUV;?~mTQERhT$|4Ik`EuiE8s1(W~MuiLS zE*cs&bY=|d=aASy85JKzFaAtU{Gxl887RLB$Ds?InHHH?4HgFTa z6u)ZB&86#;JEIiL7BB zo_wXGk34)jf=rl9MuQpuf4nJ{Qi#dl<2N7T=6cNBX;vCuPe!#Vjd0~1dI*yp`I&1r zqm>||tX4^+F?AE^Ef-V8&I%1sO1^_0jQ9-mJ9*4M+J$%6X&+)XEcP3A&eGenKjsK%!uSVVYLOYIh8njB$PdPgx;f(g zPxs+%lC;wAw=RD?AGWYzuG_WfelE#Xko7M)->mJylD4_<^*h-S&glRinBG;{ToKL-rC=`%U7y{U$W&<_p0;c z^~!Nz-KyfRt9BWrL$N-Fmrnm|P5LfL@UDmT7TnxS4icNO>+A2tI$}H~l2&CpX!%fm{11ePh~f+mut4JF=hzyH}s)fUJ7I`X@NWJ|%gQbyy^51ie> zw^H3M6M{Iv1QnH)?d=;kEcu>Jkm>q9NVp6bDK8?}e*Q0I9J}=ZSxfpr<9yOX! zM?YbfWwJDW0mcQiIM~AkC>h;j$Yrkr6GB|a!eGTiclI!aSs70`3tPk2tisnQ)>s7zq8eJ+BtpTS;;~FmYT4Nvl)h^+7^irB?+s zle$f8c|gs3Qc18w9$fc#$JX3dz=|K;hkzpwRZ^nj}$17S$oHx*#9~7 z1DxQ{F!+;uSRlW;`YsF47h0$mf}|Yi6+Hm>&}(llb^4@Nj=cFHut3<4cITT84Z%PI z)V+KOByfU{piuQ4Fic{iBlxf zQpN1S=I6(53~Rk$`bvURRkPm6=B)S?nk;n-AMBgQ zNY=O@`$~j3NZ96Iu5wtw?XSJ^{wuo)!idq6=Zn_*1i07Ee3?n>;m@yJ3n_<;beNQL z-sU_R~;ngVZ&ei{VVvZg-%5d_EvdKg@uh-0Dq`4x|84WxIs z(v~g`spro4AeSQ^mckPaTePcN$KA4hG%$ntBcyLt5Ikc*>wE<{02lxWrQwK4OG|@I z_i97@dbajiiUCOy#fWq3j0`<; z#EZaJg0G%L(P=XkY`=F9CVoAhg4EbYVul9F>_y|Kkbs*06ej5Pyg3Fu@lZU*ZEWrB zAycTR_S@*pu8RN^xs@|xwGsHbet!K!IDNm!K9%p+OX}|fbjkIk5Rz5HH*J0h{_Sj|Jm71f+?K=PaJ||+3M!2ID?}uxLnzT~ zEtG%pZ<0N4(rq#$|7KVs<#IW?cWO=Fa4zSicUvfr{Q^jIJ_bX4Tm)F`Cmf z&@b=ehSHj@zRm5|_F!z8Up)XdeZG9pBRw8RKY7`=@q%7QuNptne@@1G^(%ESubWsd zvi$umzH?j>d6y<5xPssLYP}^%K~9B&)tjTIj}M_*TgQGx(p#IGzz_y?(9oc6iAk&X zu*nOMQlh93XmUZpgB#AMd_DtmsuRT^=kk0JB}Ggoiye|aFLu06%8@jUpjXPI9TlI$ z%qtd6ctvP$A^T!O1T0){y1*p|%JUB@5$|oTid&$(6X&Yf_G@W+xg#XLgn0j(=^OEwVnSXBX7i&_8<-bp(5B=w~ybzVjn`U(a;}R{j zLI1vwoas6V1ga_Q?d*VF zDM!O5CR|LCtyQ8TLjux5pLfkM ze#0|!x@5ef>}kR}vai>CJ~oMQp|TQ_Qu5~0AJy!|X5Z@-*6)iAw$XCpL4UJ4%I0He z9{!J#E<(YD%MYUViGS0Wh5Hjn)Rf`IygX#^BQR%_c|;l^+l93EzAb+Ll$nD=$5}CD za>qkxRy1hdwr^i8_N(u$_xMuSMC=xihGrAdq`4ZC2(F{D2;T%c1WONWzi!e_rpILZ zvX%Wz4(8`Zavnsj6;e)HTN_j#k>Wr)vLrruuV1sHzCwb;%~OjmghbLW?wWxt@VnB&_lYr!uHC7&U7$bfKVk<$a5P`94b5v zUu+Ny-uPlc`POVRLS4P8-=HvZF)8&ZV;-)?Kx~1*^BNEh1cN9{kk&Qvl!AYt?S5ye zqodiJ{QS|!@pZS+xa_U0JKFt*lj0*VKbi#IfUWyK;dD_E+M;JGXn?W@5Hou3+&MZw zQG@sc`My(yqjm+yohMMe_=A&XfX>-vVw*3SA_kXLm0FHyzWG>3DOe z-y#aP4%wn^HCk{}HG6CU8;i7@BuiaXUJjLpa7+Jmb&1!5h5rip$o7GADZ+U}v_?^#5R5_gE8J}NO>?QeZ z=Q(RvnuwkU-A7#f5JveWf&pX{mJe9(8?me*i;fzk&JmNFp};(UZ!TMataVLdA61QJqBQajl+n?bU!{rh@v{-v-~zt zx{QDO^cTT+RcKZdHle5xMwKgdBl}s}lmP}zE#$$RrIJ6g?A0O*jqYZjP+6rUH_Ht* z1ZL7)FUQPGFOjCc=C8uv{C3mE?9TWLv=mDVNrX^^Q(VBS1$GJa zLIfrk-0Hhk+89p|5=Byl^AQ&YOC0wj)@OoDP?J%yO;km^&k{dUq&mpl zSHBii(YfKOBrK|khl2rzxwXkz8#n56RLm7 zf&VaT!j;I9cCCH2f{e8Lu;8%h2y>U732h8s!~ z4+2EV~YB_r0!86>j0?#uaGSHOIm_UdKFGDZRn4 zwtct|s+Ym^2gP{9A1vTOBT#_Otp_s3 z#tSzwDBq!sDKC}-aw417(hT=o4^>(l+uEqEJy&VBcI5L)SasZ{GfFXY+);WgizaRNcVL_j1sCKBxL^mfEZ8| zF9cWSa@XwrEIw>yktJjr_WvtgA2Ry2ueNS$zV!y=-|~=FAb$9jTUBuF6-1o?Q2)nB6!1+s z`foEce{Vp2@GaX4+5cI0HT6N-BB0kE(E8%$qsFZ~ODd?$Z5i8gNBG5#0iiS-Qy=bY z?I)vv$pf_{MEw#B5HI_lIqb&xwmqGDz{bk@Y1<-{HYb~c1iwZRq6m}whgI0`Mgwe; z#DayynjuSzuSN(-LHXt(4&GB2lROfWy8)trm_Y2v$*(07_%E7(k%hsz9jdZmhuJtG zp2@Yd4xGfs@bvQ9U+TC9O%GK3P>TB1!gpr=4S?gw+cfQPdio^@=4=sGNtyRa^$EUy zTzZR%Q?C~oG(f!sJT40*xDQGeL-hvEY5iM#6eL6#Mh^;w2zl-+snnc)2-&)<{+3Zs z-B&``!yRjst|d`n#?k#^xO!l{%pn*{MvQ@K$v@57A87Au#5H7=wcX@U>1*?z|PxZWicZ;sv_KJGv zTX9gti;G4+%h6&r6|RAJefV=KlVq>;WOn42zax#eGTq+w-|v&puUBlfw7i?V-2@Rg zgIa~j+`sOQ=U50EDgvD5GEfpA!GLE#9gx3I!s#GBaS+kHTo0VINwWHKRl_#_lxJ&8 z+hrI3cDqbQ`d7wrc9J0V<4Y7en71#EnG)ia+i<_XU-RDf5un_8fDTw^lwn znjGS4^qb$WL)Wzfy2g*ShWh&Cl3+*kMeU2URx}6^b!&n+(`e=xx4pV)4ue`-Fn9nX z!@|KayvL3R9Fh}g}#mlP4)WXqC% zC#eU~>C|xj{G?q(toYCTwIH{Pgu*yLSR0@7m9wl}5-XRd*5%Z8NA}J594yIWu5StrV`oj1PGSqFRcFVBBBz zJ5iNPm-(dc&t5sa6~TjJ^}#@N_0(W$NGrvFCkTWQR_ESZ^fT`o*0oUfREkgD*O z|EL96n(1Mh%W2s3ySl zvG8ArB2sBd>Tq;>cl~DUHX`!$p@{2V4vE<1dX_P+yNs~R39q^QUBpF)J^H!<&(5jv z^@VS|d3MC43jmf|fs~r>FN9 zWMc}9U&m2L4zY>Z8h5J)Ar!$tU!UcfTArh%C3;vFKCu5Gv?s|7`Co3O{R?({*_$3Y z4BekcJ|ebR7M}Pz#L$J1y)lN{Y4oJh*y=^zl>=s4-)inQOYx(;kQH*CyNQm;>FK(L zhS-QNui$oT>$1wi#Tkwv*=3ZyAxeFlx7)m*LR7bf>GjY$s97sT=YAag1?U)$T7-F% zdX$c`Tx)%8Z75sRALu1mWP?#^=h*z+e-B{S1W$MkNL}d(#QyvX0GqOGs&?@fxqyo) zfHTU<@eN~&HZM+ADt|Kz~mU1)*w zlqy)%S7R^NIrX@H0bMvUG;{@tSRd3nA?2nC_Hy{9*i70l!fuN}qA1f-DDj4+9XKtO zHYNz7Ua*YZMo{oOwO;%g6kZS;8iI?iD|IErxF#njKe1UBaQa^F2rhCV@B96OJEPk# z91@^tZvhrRix;%|=>4MOT4GQX&dEn&r^OuQfRMS86_yp+8Fj=#)9>^kXuSg&hD71N za2^2fZ=gWn;tCp>4dkYtD<>-6ImFc~eEfZ}64{u=1MzWw(18yM&cB%!++Tk4_3KxF zI~63gNWnh$Q0K+iK2T?@^0q`!YO%`={fGe3FNV^N@37y$kMgXiw6UyvrPIIXjZTl= zs9oLD3Vt{t%XuPH7+MM%Uxu4n@GQHzxjD7$)q^16#dZ=DH7xmVWPzHB-k$%17ArOu z7F^amf#kKZw7iw~=dWBo*k1m%!{>5y#J~-qKL9=A@k78M4V{`8I5}@)+>BBXM*}fY zEf7!>c!ug9ze~ulGe<`)Bjm8aLxz3p=uMAQGG+fyM{LQ3z<0T8<@a6RjYdt3j66Q3 zKXq0ytw9?id{A$VU2123i5kvoV(;rWlmfe~NSjfCsWUPP=x1O6Wo~&<5j4L;%n?EReUQDFK$UW%_phgjnR>@e znf#jwYi|)FGUM+g-O7DAa>QC%R!UOm6{hk*HU#+)Gnk*W~kYFi(AD|tLeKR@G` z7y-0FE>Wm;iB1VaiIyoBX3TN#22eV%;vmg~l=TV@Uici<6<_U1^c@C>P#3P72nq_q z>W1JSKS&gJ%F!vI@!QP(Zvg*+G*Y+p@X!$S?Sv(~La9A3A_{|~vP`3+JLiuRWkXsZ ziDbgt+;EIe&r3ktMxQMWB(JC_ySyR!V87XvV~j~zEU~w-enEwJa#Z=wpeCZe*3R1cH=0mC`=q9y+U-y89G73L1#FU% z#zQK1hP|Fsc{~AA zOIcdXaK`YBe^2g7wpzAwfZ4lVEZe{(9xv)XC1kwW{e0z4Da#!+4&nk_FZ}1=kD9jI?qU#loSv?7$QKfJg4`?l*7Qj{z0!4f>$aDj}-CZQi*uUIf{;-{}du} zUtMg2Swd(eED7>IaL7mqN6-4KrsPePW5Ana1Oaog#O$9^8%0MBwXU)md)9;;5Y$6D zSjT4Jw_|_Jk`q0$!2~qR_R~$8)+^=Xe*rfY{Xrb)!H&&WMz|dj>bp#A*<1@4iGzY1*iw29VaQ8 zd94R``Va)@Gg=yuu@p_f#N5`I4Lv0g<>`EN z@eiUk8IWxXC6Zp>p!^dP;Fr#}T21878?%M`E%7bX7i9^kN7-MRKHSzC?zM8A_9~SG zNLaBDo#m4ITTe0;7fEC`kCPM&{YZ+o`8&zfib<6!w1!$luv41xqqdxZY4TrN)0g8Y z5}Uh2_ZU%v-k)srt3gnxP(6HfP0L!z@ZP|)faBX2o0iC%zU)0b14&sjhHulVxH@F$ zhLu34U>)Q+ck;PeJ3f++mhZ1OA^n*x?9EZ;3n^w_41>MYKfHZQdC)#FfIA`=29LuJ z9>cR5h!NB<A(}6Q}MP8!M~a#XDz224#H2v5-gE@Ew5hcoeD0`#&956Xhf)fvKwnWth2k z^7KwwMFo>FEj_=537+MX#6PK|Jq;>%7Hm$f(yO?$Wb!eix&g>)dt=M<=H0syomEgU zH5+kM6$~Fil zRU&+&e`X{ul|QBHrdISi`+uv$MdTP$yvXLcc;QU!DE*S-+$M3)uL^R=XkK;WCp1B+O$PyC_!Q23|9ds>;6*nHaUI;orwowpCH z_g+0+wqcxqs8qC)B4dQcIw>`3n3$Kdb8ej6^CO>AmCbKks%xO*((dGKEJh&HYSNf{ z0Hh9Wy%I5COT#2!d>eJ}pGhN@P&}Nl{7=)h#%n0yfsb;ED@@4KOZ)6_YBunXU zX2Yq+eX1X(LaoOE*RoBA+$9`r=Pz<-Nl#SO-s{ju4z8U+8WTG1*$I=|_C(PS7B?^y z&2)du(QoFvN+q7SHtmgVjLw|iA^L8~;}g~;L3nGIyVunSd~6`H&$ypIMjHJjPR4?Z zw0713J^?)}9@aX81$dGcs{(k@xFFB-Hes}=XnH68 zCog)&qSx-~bUYr;4?>!v4+%8lLC`#oJgIdurY!Tlz)=q`Y?(I~)^Blf*u-GaqEcOkL{_oeHwV?{Qz}9y z!U-uwbD+UQM*7UFCN931$_lD$T}e7QRki_zXZo5FWpCymsdv(@txTyoqBH1oQyJOmdTe@#X_=*$R@q5r8jYJg zeAhAZr**tc_n}CJ?MyzdKQ977d^Ap}fkrs>NF5W`a5_8;2fEKQGHg}hF8wv0HbUrb z^m11bJNmG=!G@2_gd!T^NQPEEORpg$LYuTk7Dc5se%8S{|1W|IwtFBTa#j+qfp;&^ zfHAV_ZuCN9aq%{Ml>nwZZS^_0;e>uiiMRg#gbk1;AL54e>o}XN;Aq~=J6P@5i-@5- zxVX50xKP-q&8Up&?@G2mp~e3)G-M@uvmyq*BuebOKgf4Lu zuw`?=yATzJ=2bqkGR8I2g|QQWzWG)*8>gQ>8Gk=Ym9|0h;EuDu7uUJ=Up2$OqYWwj zTd50Pq@O&4l+2P$$gv{0zSAy}+C&!kR}G5eN3B%Y50q>(T#@VW`&?C9kBpEg?JkVR z2l?0tkY68N9r)I}7qn`r@3pNITn3iDiN76365x6G?(~=7-sL+A^bzVkxxmD9{zEmp%CS~(}wa3x+V8~jE@bYZK>-xpK;-YNt6uFr9i|U~pB#m6q(*0di z>{G?3B|Fbxm`2a|jJ$ap0{lVcsWH>Te()TM-I=G8c6${WCb~|nU5>OpJ$X6srAVlN zueH8~94<0)<5mI_OEWBwhq}SMn3lJxMEzdzeb9WNNo@N)iI8Ph@0Ftj$qP~5lLC+p z!EH}3DO46R<6#DJ_(HaU!Ng98HRe`n9FaC0@t{fvV|sNAYRr>y6W>ds;Gu`X6@@sq zpuS!QHtl_6%*{>qM7@-!6@4vno|63r1Rg{`POzEP2wwK}2dC^FGw#=fY`x$CUzJni zN+f{U#swN^$RS{kBS1hKg^Y|0l$k;)phRZsszAJqrk>u5aBDX?1Y&_{s`01q(`vmJ zXb++X%WXJymZiSA85&YVb{{zQ_8>cr0`-(!&)Mgiyg=83$AzffcPB3&+W#hx`Sxip zwKaWBzvcD5w@?TEzz;wjEvY)FVCkB`i|J1U0x7vst3>YrV% zX3-b!;gco0-bJ(A2%h@Ci{IUTE-#T(%(`B5rHf+(i$rZD|7ic^B!r5faS%T-Ib?eO zrN-!LVxPNgNyREMgl2Zc=T~WH-tPWVHsOrnUf^2nT-)SRRoXXZ%TXr}=RI79C+O~4 z*`dd~X^CroC`y@jo813ga4m#~z{0~Jx9Y&z+Z{_V074dsW?B1j8XZ{6X-Rb^9EV_ra^*Ye4M}C*z3KYR%6X#%ngc9P_ zqj?MYWc1p2wcDHJ@q8=YeX+GJGkkc9q4Lf5}We@?1M zb`Jkl5~2z*64To+e%sYa!|`efJowSuI6pcXJXA9{FaS#1Y@jsljyA`@f>&iq@)HMN zQiOMgg1zVk!|d|yWTR4q!$Xb2y&1jd5`PNPF0h0B+WTd&sk)Jt0)kqdeV#N#Bzqik zrwHO8>uX1dJ!6k+Z`nfQz&ZY2tZzfjDME;~qHJl;l50_e_mD%t!X7eROLQytzj3IR z&m0WyFt(ix{COZN{Q34UQtGu^dU1N{ZHKVOjp|Jd5Lwa?H+60H2lHs7JwUD3Z-%l zs)S`V(1RG15jWwN7PBCB=jv`sL;%L|27`Gj)4PB_0D2(>!*~SOd!?}Dq%s}*M_1*h z@sM|(RzGG-?~D|pWLx^^+s-kV21_RMB4U(he;X>?l2dupW!ecRR!hgqXBYvL^(-BK zkixUCXZ!sx;3G?TlrsHYEe;4Ya9Q2mbuf)Hm{0~F1oU&O2eeIOh{XBbV?X`xcQ&Hj z1b(n6IC@mm4m@KcK0Lonwvt2jIMHxO6a)VRzr&0R0K6y?Dk{UUleD?54Zz*{!?=@e zQAmVgBb$pb!`K!&>JOpxS8yfN?Re~L1{eZo$Aw!*(B194{*TyM+0t&J3u}1cyQcK& zsoOyXk#--SikmbmNx>9dL5QAuwf@%9PVVfVeldMUluFV^EJ+@yqtXwgM->YXOM8!*QKO)_^A3vQ+gS(Ce4GM8{^{17$J!?b{W}?3(9R|{ z>3OeBbjmBnRd^k&L{*#4F3QvJyROW}{GcbQgYvv(lF8zrXRVt%yS-hmPzO1fpHy@T zAMpY4Y$d$(xkE*!(2SS6Jf30lk)-eV;k$rUye9)319$pfQOX4MX5B|JwXixAb*7qi zpF1Bek2F+tpG|(Be|*&^Cg8gn$4RbgX*e-$^2+`Em6*?>QOUZj1^3d@IH_ubA}NQ{Hus}$tc@`Dvn9T!+lY&^h1HT%o||tX zum976KUy^EatdWEQ?^Ns$>4+MervzoUGLqTdY!?!vaj@%B?E7|g=z&yU(i)Qvoj?$ zQ8HnSrmO!O!Yf*5z}`=pJA?Ny6K#Xxfsspq7s__jja`YtsSybQk|@9*Vo(t!lLL6k z5jmTbeG+VruHmm4>aA^TV4QJq4KD25b9Zz5{S6Y{x>s)1W7FJ;Ajzy-DS~86;#-io zVkv?WJibM5R^TI|viB2O(-i$d6W6_}+1de$-MJxJfLXAL!LZU(F2h34m#1`?SZe)2 z(e!&&(r#O$R&-VXr6XW?F3$IoY$0YI6}b_8C@`*PJmQ7Aq2W0Mw-OT)&iky!H_GIy zRet)gfZ|oKxgv>AxcC7rdjp(F`+(Obn5WNGNhU|ep>7X^x@o-5v5>#$O3*;Esd4mw z6CdWDLRGK1xo#7xa%X<|ZiD&g(1?}e zgIE?&d242R$VZabjW9kUyIRU)0gN+c>DP0(Vx+U_|2c79Z#z5Hy&26Y1^oiHKL&L) z+K;8Eie(JD{=ocL>X@!O&Z^3XM%?DcMHz3R@8Df8Ehe@sq_<;u82iwmy*oVH;YgLj zZm`O>z5I`Z*f+NiytV5ceWMLf7sKmli(c`gU2N?DJsVvW`yC)& zwLYO+D8irqa}KANAU=e3WA^Un=Bd%EH}yM=)*a1jU&nWfv8d(-Bdt7IKX?8Xi}bbN z-kD!HZFlp(n73p_F+Ka({zHW^m*4aJ>l)zXS z_KdM7$!VqU80Q|octo+Q`(uvutiLZ+%QCbU3!zq|rMG|kp1N*YTf99gN#<8487ewU zHq`Ge`s1HL(<=*bEuKW^T7@mh8hZ zAo>t+e#B24>o{9o(Ar8_ct?L&C`+Yc8YBnooSdqZq)yMCHNiTBxFAhc(Nq;rf_0nL zr_OA|_oGm+H+-|L)LvL2lC{U>r|heC&;rm?6+FSWYxb+jsn&vEln7x8*Q#BG`Uis_ z)$>_dS!pqyB`X8|yi3g=aP!wl%Fnc#9;)_F*N*b`m;66modr2JP>;$n%6 zQ`6c8)}&x|h1u)lHTq7azhCaPpQ0v{A~RTZPBVL0qa=|dtkchV(F&oy6WAGD^fen4 zzh0yFts_KaT_0zho$+H*MJRr_ldZ?Piisg_S(J|4TqgFTsI^u>=XZc6#pu& z>}t9Bo(A6?p1a-B%i#pIdZyLUMF0wBS>=feRMi$7}yX zG1`QF9c*!;_vD?WhbbZKEOwm~G%;@9_q<*q^*#*bUAu$OV#HAXY*)glO5U!^LOgp5 zQtx_UK7Cvyi5BcC6#J7Pf9fBx@gP%Nx>0^=Xx(}T^imF=flUM??DZ5KSnTCFUDz|w zzRcuGQkt5XfqwX_;2tB!zczUF*nifxJDx>e-y7t*3O#Ils@x&04c0!e+j;0#-ssY>4UIh^ef-fI-``qM_O8m znVFnQe2`ysi^eCrzTOL1Dqy?&V#g0%0X6L`5W>Sq8YKCk<$=-s1iiGAN$oc=xTeC~ z@k?5cR#a+SuA;se=129S%mF0G?d3H3h(SbW%J3k?ll@QI8glp`>!2$@{`eE{5LxM@ zLKLAn;v|jQw*|7hJJ{&%hVhxt5rJ}tP_aAfyUVrN;~@g!vjMkz3@~ltCC7oTFGL;F z=357Ga%)Adq&s}rB0TwXgW?9GAWBFFd}ok$5@_-V=21`UzJqhxBc6wUCecdU_~dVK zU>_P$4KdYJJt~rgMIkPNn2Ole-oYqTEIh|&cFu2~ zdGrf2mI*$MlY zG`L#$Cba_0{VTe$8M(@Fk{y;-AOeEXV;)2xN!s&M4B=T=w?d;F6NmiIOF4#5NDjkT zK3~RZ(h50{{1%~k{CLft6lM*ihY``dvCa6;5YmR&u|ui~@pnTSu^C8pRBf9K!a7}l ze!c@%UBs`{q$D?h=Kzun20=dsl(Uh6#@C%S!n979(C;=&lW)=5E zSfXEbAn`QaW6ZYof@n`GJKLVZD(ewKgXe@HaEd0>pWheyYk3 zNZ?RNpy6~Sr=Xyyy1N8|LOg`nSOTr2#QpmuZi4t2R1*F^AfYZ6Q+=J1l2YrsBJ=ez zSehVwjk!o4t07ilO*8P2=wIb3g*GIeJCS|=ro;A56E7p7A*{nrXUinut3 z(%J}8&)?e^-&yPT^}LTgvL`up|9sE#c5*OzW>gg+hI%ZoU5fqu`aI}f-u6oHC|c7t zCqfD=n>V=#&@fZ0x*}^omxuYBh@uoON;C6VAzE;XI*9S^We?p!MSRA?|N8q`Yhx?d z(uaV*-=&!=+$Y#?99=jFl{p-h}ICuC)CDXXg;}!0elw%2D5^FuVjr+1!W)YcPI!~|6 zu$d?t%UZ3-R(~?ywibl;Isrj7dl25$Y(LEw))_22GBmXMoF-M_8>u^tH}K?tO!ybs z`C?s%q;_^@p-0QfROqD`CMfuWFpY`O;2?L}zWU-WMO(4Xa@E;RMog`a`iPW)nn<$THewq8F7|2fiMbThj7aZDy5Y z0|Rv8Vc?1>9c#(Hmbyu2fer#$c?+oTn#Gf$^s1QEZg75opHx$5j$w)a){$fS zQ(4h-e_}Vh7gia#5ArCInU3v$xCA~r-|ZQYX-04itp3nRx+|-tryIS`VCK6)Z z`QrKsDWPjLZIAz+1pP%t1p0ro_@6L`pPonH3;q3Z!PU6v&%v~Yl<5_vMSFv|dL@tS zvQ~X#YOFY@)(#A!5~i=Mdzs77Wc*$`T?Oy_7w9sa#0M#PP=%L=Ilb z;uCR>-v`*&CTF&IjLBoB2f($Wpw9^1v>!}d$I-HsE_w8YsdfydSq*!)gtZZ-PZ9r8 zmD2@bq|40>XHS;8c(_asES+Bq%@0IHDXEK`W5tq`U>k$qqY-kI+9x>_zc?0VwX6IY^{i^mO@_0#3 z=J&}dX%YAhieyzM?NX%c*dEJjXx~C-D!aR{rg8Rd`|=~!=5w4fdPS4op+P3@e(glhZJwqdSBVadMk;X$%W!O-BK^lQvkI;tRkin_Ty@cyuL zzPL3wGE#twOURV?eF6+`dSw&K3i=_w)hie&!jgl>3g7m6SF4KCODF8K1X4KjK04V%^u~tK*s;iJcnBW0rDf4-3V#@=B zUrc=%jijM^5y|$ACBir`xVy6gV{m}2`hYm7xyQx!N5WRG8gum!m$#klS9zyzjO?fG z)8d{SV|bq?CuCiAHCk^MQfR&6pojwsqAw&OfvJVntMNwd*G1{ll9Z9r4C)DhKiu@M zz&6sp8pHlh;|ZK~yzIW9GV>7&gl6ID>MHyPq;AmCddo_a6k~aTK!{)#Bg8|N}3~3_ItK#(CDNGr~6Ntfg?t=M5fNqVNS4{s&N}9e5G#BDOOsAl3*+p{Xr8d2*4QsA!kIB zV~~I7qc$u>zaXS5ozGsqOF_7`h(Nq;BtKDXAJ{m8b1Ynj00R}ME!xW%I=9!+U>a4* z(Y203LmOuWb2NSZds+O)BSP`A(vW7aK_7tlR;xoCoGTj(DrZkOJ8)3*-|Fu zsA(5XiROm=M$GX{xzXox$Qlw259EDAI)2{SR{_WXTGrf|l%9aPPwOIhm)8JN%f-z- zHZ+vZXA=X-=)T8xEW{#SyAb2u4IjH04L29p2Nks7ZtX$2b0++N_Gw%X;RCaG zsj z=J5m9w;nQv>}fck02_xJIdLB%E>~R1Gg0#Ai3O7&0!f&L49>NhdnK%|WUPC-cZdA*#YbdQ(Q}-`IblPYy7SFLF5+#MCA* zJWN$77hQdBrpAt7lyYF)J$p5`WzzuKZ zaW}d&U+2z=^S7E_+uD)0_hEd5}UGCD0-*w`op9m#2K zPhu;^Q$0SqXNnfBhy-}(Oc3mXwmE`UM~k@UPW!Rn$AXR&0m7keC>oDdACO6#}F zt9PUrZ2glCt=3RL_oF_l2ZqIGm4yB^SATX{$R?icb9&Qeq3b&kulP?(M6`|-fpA>> zoJJ1lD=JEo*5&0re)s%kOIkRKo7o zu)7Qh{}dWsaaGF{se?B8A)7~EVPPR;jR6Hn^DW5z%?=5-B}9MpuOu7DK#6j1};K|vgwOyeRJ3nIMkBM z@tc>0a9Yv)b*)|K1*-O0<+b(f|2`WW_?M8{;(zIy_Y*nb`OWT>w~;OKvh`#flJfv9T2tvV+SmLGJXR~ zdtN#S0dkz&g7~k33O)U?!gIDCKYYLy7RWnK$zIJ{#wOZDc+xt3Jxg%DMMlsTx2*3|X3)%}MJ&eq=U>5kYRx+&gK)LAYnY zzAGpopq-Q;^!G+8lJeLCl+3VO%2pxOi{*8Zml8uE(3yS(_g~O9_VvN?dTG65z)=qf zVd*gR6|S480@#}eA|ZwjEO!om#b2X-kfVy8YNKnL!f!%x;iE7_j*zmoEi|ft{dHt` z_+|fEadXTFOYqal2pxKs)R6ehE(Ekr9^WNI6i;tY9sDNFHcrWX>wQsLVj8+m-H%)k zeVfsY2MNBy!1e=GLi^dGA4obAKWp!cy?_56R{4IVwpn}DOKu)N&y=73)`;Ly|2If9g5;Bn@t-skwG(&_dtzadd= zZPSDiEIO~Md?a)RDsWq$m#<}okdeNnM;f)chuf~ZIQ20(wyWy+kH8`uB0bE?HJvyh$v7h7*$K&YpVpfS>=`@(&;Sk~u?)iyxM7z;nfGrJz005HK`OAnvtmU}Iw=^5`~l zjN)TUq&@fewJH;p7B{}QyhXH(_zoMU)~Xb#N4doAWsys4-q(4jRJUvV_FJ^sw>ZaX z?+&(WK+V`Q2W`1{7^O|3=UbqEuF(GZ`ESA^&8auK1gXX@_w``h{hH%Ix5GJIs&@8urDHPf66_)rnFIY^d34hiipKVuDxWQ)zBR5aGM8}!DNHWl19U> zAgE5inMvA$IvHMOi;;_+7{U`Fvm!|Yfq)Xn+S|U)sOGa$0v{|N-~j-)VfR*~f*>L> zB#IJvM3plT>sp*L1B4}bHX}YyX|c$07;un9E96ZfIxVY#Df+TEG+ac8CR}C$Ub3Gy z=v~y5!_0?;s>djN48=L*G(Zn;cBnI2$F$G}8C*y3M}@pjfmu~95Q+Z|xk7J3qKHEm zpn~NNVcA9%VD8^UTS=PO%Xz9@HVqUk=Z0IzNFO~D2||cS68d%7NQ`pD#u%$bX%b+^ zgqcFe+S-uwN3*YX{34mSHkV^wHl)eXD27PLV#aRuZ-kA4lGCTXe`y(yqwwT zJ$3b9m?wKumz`|^;zl?iJ~1NT{^!#6=SJyVR$PpaQOX>qQUI7?v9UZWDh$-F6`r4@ z4?hx-wwNp+{9Ztn;SZzSP#dFeu4h#JhXa$u#ZG@~nAzEN1U`zUy0peGZxEdTCW-_PIQQY@)`+(gY>0d zS;3chEtVHq==F-AM`K}@mD~p+Cj8iNNB~M{_DZcnZ|t4$QHD#~jX0RHzvCEJhb?u* z_09H^alf}G5rgJ9ENYf`5( zLS(yi9gg;j3Uxw^3@#x* zu7nu83;jX1B!en$vet;*%Yh4&r^pjN~Bn#^gC4U!_Jzq|Kx&C&tlrr?2bIaZ z)O`_?s}KDwFq@;rZ8E~`6pYs`o3{IMCr*KFv;Ts@B+N#&+90+ks!A}}I;!eias1)! zxO4Dt7pT5YZnWhg2X1K+s7l->azVTrOYiyA-XmBsULg-Itcb*n3{gmz0--20QGA@33r;Epp(w$qc8}Ns%)HjF+ymEVqaJ2jp0(-iadUH$XFU0O zg!Nj|{o~+uWZb=-)|I~c{i~*W7bDT%S(8NN#$sGERw6q z(#BCzAPdi~ay17lS1q5)F^Rpmo}S)K7B-&vF@7rHZ3_MmPL<4Y2fsSDXCf4KUmt)ju9M&# z=vjH|av!nX=i^gRQ2{Og4fF>{@}<9#ZJEDa(B{?!5B$<+AqHPkhJeFY*y@0k>*a2d zAw?_Vp`;acH~7uG8rjRYcTWW#zgAUMJ@8chiE}LSUiuI%2--1K1jh2xxB8BQ-~hnc3WZRuAix={mZH(4abb^X?yQq^WYe{s<}5( zivgP~OgG1%N~sQ^i2n-RuWgi(fC{}~HxnLmh*SV+5un|DQLh!Lbzeo@4wnIT!S6Fh zA`zHQPEP}c044;?LKIx&KZ~r<0(%(ldNhm+Kc1to*lQE2?ieM!BuG#gembh0zHTeH z&%v^dA7-OnWEC6(_aw-y{RbJ!kI^W;;3YnheEKE-#-b1CnhYVg+!5REW7YJTGB8~G z{)20{bL+|1Ip=04AW%Y#@I@O0w!#kF0vHPzSE`6RI+CcBmh=$PyC8|QG4CD%$frqy zR;H>1^FU>Dz*FNils$Eb_;1XVUAa*0Q6HXFMyqRJZZl?-)9J64gKqv-G<Hzh!a{K?SS?QkKN_iHkL<@kf0e8BF!lC- zn?i`sG(QaU2)-};{0~ctym;u&H4zd z1Ji49<%&n2pFbbFqq#Y%dNIO2>Q3%s&f?YeBgkTpw}?CTNsxp0!amj7vf95Dg(a66 zTFJF7sqJK{=IpC5{~TlM2+ZESpgJ6UNid2En4ob>*^OT*md*>6Z4c7sOje}rdh3{9P0GWXtx(sbc(0#%P+S*RNXoxR%{YJ*;m{0G#b#VU!xQ{^B z!j}MkgzXF5fEt#G(va5)$0_G#S)KO_B1X$nJKNV$BBU7oAb)Q*i#`Wjwq>>sTS$xmNL7cC@*+D)geV4VIIsBl#W(7a6 z=eR3@n{t=OyU|tWrl*CPy_uISYK(;uXs7?dB-*CUgQeURXpHE6Kebc%iLszUnL0v3 z)Tqwl3q)+AWrj`sbasfG+jF+JH-bBQC>pjIsJLOoCYm{_QBn-h&n*v_+900d!Nncx z0%g{Vj7&?Dl^h3(nTYPkxhz_dsA(EfVz>2*U(F+q@7lEvTDuETDe*{gp?(+}9WDGY zouu?4mXbJ7-i3+uB}Dtc{pAiO5~^~<6#gX1jae4@M=Bi0mI>j+iRG!9%s(J-@uz#^ zjUf{Bu(ZPNJsU^WOr~L-JWv#6I5%yb!mhVfm;p{FeIujqP>~ZI0tQN!i1-=U6 zop*&&HT?3G0LvssOxX)m|Dk`*#%efJ;AK3Wwxicl=y!hpsV?+8yjm4y0K+dde-rO6?E;jVoJc*WTG+fJAR;#)AFgq-7N$SQJRj@ z?sKiA`z&~2cY6gF*J6!#CV-Yomz{+27nRF|*PEtPzn%A2E%w`pxtc$+k+ydb%dz)9 z?$@;*pcd=Kpm;iQb5VI|2W}kCyBNu0B5*qjclHane9#c6j0f9k%Y|#4V*%Q|6sIn~ zORkSjUHI90H&mH%hXrvy?tBYKiL;)*>T?Sic^2^`&@I>IyA&m&TylNa1Uq+<8?eH(1@*qL<(cWnx4Ka>+Q? zY(i%01Z!6=>pUMmhL#isW$sGbYT*FK<1n`D(9UeLN-$;tePH7V+Om&w)NKp2+0b?F zu-f9}bGWN$O zrnfw%aw%;pLCtaB;VTC?g^t7sGfA+}=1RpN|D(R1M$E?*FzWyZ8hpr~9E&F7<>lqz z!2a+ZnjxB7@?&t+(tasCVmuDSh}OBs)Qsl<`8mA@s9`+jxK z#E+(D;Drf@$9{h1rbKo7!3W`hV{?*3lR;&^w{(3_vz3*WW(R1baTr26PA@Bk$<0VB z=%mb?S~8FdJB5oQ66t#Yx)(i~OiMhiFlj)jv zH3|#d$ zh9TXozjgD}BICAzS36?#2n_i(&XB118S9KGGiK#vN2d2wo(qz#*99n!!nPxy+J5@F zd}{e=QX+MX`u{6>E`2gD($wpJg>1Yy43AQhJ@_{zcjA9a$KEfNyAp*+?Acu;{){4NR(R~Voqi*l`l&482{YDKG&^rh5%np@g(ebF zDKauLb5~rH{0%mI1{HxnIJfZLuMod$=geQ0LW=QdK{Fdv=dK9~EdK)s=ls^p!O(ln z!3PfElV8S3(Sxt=7p%;S(qa1gxYZ-uX?QU0f%nXhxsP}wv!bTNn4;DQ9 z{NSJGAf3EvZV#`xVu;-q!9_dCX^p{bcr1QPOq4Hm;#cIU1hjR-?=sO%LPS(FHKB(~ zRR})$;W%6HknaoG*QJ*_Lqk5UbOY6rg0gqO zs+#FH@m-GKQJl#Eb*;n9eZ8#{yz+_r#j^?C!K zrHHWv`1x-%V&H*-nL`Q0*eK+QjZG?p1Qxci3;oTr7#-f(-p0bh2;E=51(ScE+KD%J zLi^TE(aR7=&|8{%2pbgYAgrT!=OG_JB#vtE88FM!ta@tp4NI@ zI|8QKll0FokJP%IwoO|36uS*yWh0HV1mB86yjaB#eIZI(hKDxxvF_Kiz}hW2ejhQ%2=f^F6toZIw|4D9Xomt0cOkQ`Ap!P%0nMluJw+%ptlJ zi}pzo!TKy$JVgU!@tO9x@Ih-gG9%7QjW$15R5&)-$h>DqpSwOw&k<&>Q=Sw~r8zMb z#{FzGtt(4i^1#gG%UK#`z+r_^oeDwRJ(|mPYoV|7NBq1?hexb`{OnsRLX_&2ZzDLb zYBj&q<<&a*whiRyvy((p_}??VvW&1vvShkmTrv=3zU5HO_1Tx{#s8!9u|B=gi+zz! ze~$P(tg7(+i?ED6+r4R2AmM^B9t`I1??Pw5TKpi0LHK4Nzz_0D0a~eZWN*EmIAKV8 z+-dKPi|&sV|2|ubO+L#pV~7x;;Im1x>LAt2DcEsu9FOU}PBOZ^=Wiz+kEW}`%SRn8 zXGbVSjHy98h|vSk?~RZOY0H4%MR(O6rL=U5*Ms5lo)=piKZX zD4?%Hz>#!)j*c8d5(q8;8$u)D{|P_>An)Om=V)(%sf-0rb`S{$YR^JVs>r(inWhIEDA znjbN?e3_&$=_QMT1iI%v)SpO7r;nIanF{~-gVm>+QSk$Es-eo4A!VBrWCrmwRDyzZ zO5sx|rbJw&3fnnbe0AiloKPOPJ3d;7wz&guLQ~$){NbgUTj^2-*JOqTrIOs?kz zBQ34lLj7vTMt}I!hr)VS7K-bMsL#z@TN^z4zxDY4K660{xNI=3GgR=*lCLf5dv=|k z7b+(mlSK9OnA(0HsY6+R*)9c-%R-G~sOh=UL zIvcyJIPZFI+LU||jIS6mRI`h&uqQj2XKf@cK@@zF+Lo(O;$H-HV~dA96{jfT)uc8H zG5H?p@jS_cF_r3wR;+5%aA*UZY80k_cd9~3S?5G4`fB7(~L;5=t`b6`TudRen-&8I>=n_m)$^;tW?STOm*BB+?`Xu z(($*V@WT)&@BAJ0BiSB?NFk11cw9or(}H0Xz{M_V|J_u&XJb8Jjh2;deVj%6T}Xim;O0JD70SL$xH4wsmln#=Izol zy-G9Ar^VIT?}NU!6;;l5F)3?Jnp@;2CTE74q98Wu6D1SB%aQu4n#K9>920aG1Hd7G zrn4_uL*^{eXj)P1ic1&;IXhf29_d3)v)Tfu)H*u;EcWkGomV)Uu{rsK5rb|_LRHqx z+z(Zl)Xmf)s+=`{hX!Q$F5KGORsydGXUG>ftSUU?A~j#-DD@!UVpn*GEdq#>{GlbE zvuoiDgR87Dn#EAs^lsN*`?I=XD%eiGb-5FiSF3Wv=H6d@LN`o`8g-6)9)HSjKj{tc zHfbBUpHV6y;*Uf?KJXZJlfEAud3VcWJEf|w;dp9eIk7) zISV3+w@Ia6H%!5^U4EQ6`_X0+4VhMId@N);9@ROPX<*)Z=P{`4DR$(Qm~R74>laNz ze~It*e4H5Cmz8(NsH{W3(9o2UzZZVwQ2zdSf@m&NT&S62P-5GY!>r{TPz}Ud6p6YV z8Uy+JA(PVS4R7`yhBkwQ3lxspV3)3`Z@buL|B}+%7Ffk_YT0_maOEtXkIe7KUrmeZGZEXJhyCRNzTU1*P|HCJx?}YxePr_1e7BSv1JPSCQi1t&j)IhPO3t4mZfHk zf9&BhA$tP&3u|mqKU60DZI~X2N{&j^JdTQ#vw1PjOF!8yxRSj2@M|%!031T`w)aX-`-I)A*wSbGVj`?V zdbwUsEW|LZrb#H$!8&a8!tpIIDAph4`jGMZxKb#-yZHI8N$SA5+bwatUp?x*!*8DfF@eA zSq)i+MZjws!WJ8`F;xvun82tj!M~ik1xu9Tpvc&RyD)r^HQk9=H$#442K4NJ>UR}z z+A%X{dviB2O&ftGFvx+23|ncEBauJ&-RN&AIb5f7nDxWL1`!hfGK7PF;;hyyyAAh~ z*qv`uRt+I92CO4gVJ^ieGwt7EQ%ZGSYgtb%=}_6UQyR<%MbV3n>ylVVh25`V>b|@h9=y+De`2d9w0a_ z5*h$eCG(c{z$Pc;e+!t1ZaS5em1T%}J9~Kv_PaSY905z!4JYR1%l16&VW?hYY^KC2@$;eW?V6($B8v@aKJK2;*iUYr4Vp30Xknc& zNCU_7*ipm0`%9tL6b8KDO3j)NgQjTIMU(4NHF`bblAbj-MxceY`svfW)~&v}Wvx$) zZ%!&tSM1vPNXt)lYF?}Pt=pcb`UFp$$pELU`T&Fa2W76O$?h%`Cr!`P?+a+tbH2_< zpS%4^UK<}1^+cC6DCqN8F_QcKe4a1w` zvi9~Mxb++)=4Xm}qu;va=i~GFoiI_>;P7w;w6RvYBT&74k&VO!>m>OD zXDY|ueha4E-Q9QZ-YxrKjQKo&uKtz}lonj?lC*{+dFw!Bwbq~TK(rPI2S*Rf5DTGZ zv}_)A3#kk{-RH&d!>E+mSs;6fdTu`w6>XNh{(A(kr1iWCgrIeG0)3xZ3FHjh;lTj{ zYPblBN;_$>bI+fY;s}H)d1F(P3}quo$1^hl@xB1xwq2T!(RrKYG9eAGJGG>q8ue(b zh(C5MJyo-fmDSPyiY&YYmXa!P~Q zS_x_J#i0?@nT?ElEg5?$H$vCd4&9CR3{^u)^~Drw7A56!;SjyDe`=- zU;hGb?o%eh2_F)4QBlzfJ-_t<0z?Pg>KPar{Z4nI1NWxO$Rs|2ehS)=AQOXmHaK>F z0Im-SAuTP<%E}7+?daH;q~9qA)!U?`8%4+b{5(84HrCc}{?%v6Fx|cT=g*&$y}2`R zXApA#nQ6Z|`J&1#4zP4)o7j+$oScp~q*zq#FM9Ae|GJlL7LIRu2;Hk}yI{Lwf5o=D zx0i$T<=eMACHPgBAyAK2R&vvPWDRHG3`*zTnVXyIHu@kSAb?!x%Q7Kzhs>;Z0-uVC zDlx*s%Bnkon~xla<(#IEPPvgF8h^y>2h;5%&C=YoWff%Y$5KPVad9KS)?GnT+YZ*G z;wpzvFeOC?N>0#v0$W5(T>R+pFp8m)n6B{%3?&qIZoc6Chu@HJhjo6#-G@+;%*+L_ zZ*pset^PY(Iy*UWnl9D#@HhrTxq1M$rZ}@^){XB4CUVfl^MON-@Y&GypRu66o}M>v z1klkV&{0APhnWjlGCvgC)1Q?kJi=fJ7Znld;#0wZRqsvO4Jw`f1X^yf8c;gIV`Kth zBp{W;t|fbynR%cJ@LV*!@4!)|p#g;E^1#5r`T04J^1;>)?}mDo*d4J`9&mYe-GRRj zYt2;#zVA$+hr%~aOG|shaPJ~_o-kgnUD@3Q*p{V7Y;6p4kFuoyxt0hCYX@tt)n6u! z%vubgcUh>fR91*0+n5mul`rAw?k+Aat7$}m1j|Z+ZRNc9BgK8+?rRnkj`lry9}w}C zQ$Qew<=m5Db(z=m`iJg#U@F7!EvwRb^<1j?vK%AX)k- z{FvJrAq9{5h`IRQ){XP1yQ@n^M&@SxV>g}+eBrxvGT~ zPToQ7crA$9L&p#~K5wTMMLZf7%tXHoaiIJQO`en@9>tv&O6uy=yq2h9v;+i5+?cQt zVPl6W{DNxl{PMCLlJB6G3SR(?0rC)hH37*VR;YaA4~#Z{q6p|^Lt-`jQHA8#%hK;fBHcs%7QExN^OX~U;6ztOU~Q)z z{vnt~vPRHE~uQV@L4&;q@IULGXD z$pFob%^5IZ`eZw65}`lt;1HR3ytTD8F)`s&NR0wt$ciEpJ13ts%}HNydbzJ9**PxX zot_xX&u5xgRHHIf@2HSwFPBR>O-@Mx3H-l*|6m&e*xPeZ{6S|B46DWTvvYHdw~-K4 zutGyaLt&A^g`&c&_2NGwk{O9bhOBAXG?#fBm2OdWLxUnRRYg_dR=%qVR?mAfx12|n zTx@qk$QdAFh?yCEOP?iOo>ypP|>t0N&cPcBwhEq%=LCWwiNtJZCaR^Wkw2n{waE>Mr3_Qg@&zkmPww4uFI5`_KG zKt&+5mUQ4+F;nZqgpQ8B)o~PUBYjTEJ@ZtGpB;+_JwtP{?bzQ_2HvfV7sX|$XlQ%0 z)hLA)5Z|ygGIG207M##w6v)T)Qny#&>YPh~%xR@tIU|eo3tnrW+Tsh7(F6;%2^RmN zy0i{Kfd^&wLbG03=KUucT3TAp&L5CbgtG@;Qysjv`zUCdsgoY0Ag@W#A0F=4DtE%q znt$MrXA|}EW%mjH)zxQExk}*HeP0)_4@W|bLjeJw6AY5N%o!OOLG$$oOIAv%T}R!O5==dA5m5Lm1S28I zBU9&n8*jxXYug10R(s&TuI_Ggu=ocDBmDgQia)}qVbbD5FoTbdNAtNzCgc5^`!S`H z2>B#>IlBA8>hio#`*{N!Le|%BY2%S2PBUMSa0G2}oH;(n4fqC+}y2FAwlFfgk4 z$>7OWNlZz}o3^Ko?(FMhzIU$(Y_ElD`2Y<1a;uw9C0AM^H!3PBF_lmyKWfG!x0;xM z;Ghee`^^W9yQpf5NBjGm5ZD32g~umn;11b=gJ9sP#ot^vD4)T>fT0^66N43kbL$;{ zpre{LhfU()fLhGvrX9;62jBBRE_--NJw-t*?++VpBFphTMGR@Jh`}G{Kwws?-6;l~X=OUXOnvrH>FxvSa5S1&Wpt}ZSDOpq)`*1{KlWY9oj?_tKY*V zygg=AaS9#dRq}xlm6yRwLT1&seA7@ZvQDvc?+^!H32E(;YHfGr_Bs#)7T7 zm@nNVMVqwTJ<3R4ipbC19TuJzG;q*GyhPuA+(AG_rmv@G8_39;MATMQklRZ7mJl`} zD@#jUYLWHTRYF2Scd$W&&0glQI6ptJ;9V9l@eL2_gmWdOz}^kh7IZYUg|+}uZtjFx zwV5fN_6(UO&UYBPIP3VBn3z0wJ46Bm*eHIwk)?HLFdEGlRMF3jut=qQ#nPl1(Jhi~ zFdgyy@9Qs~k3SEs|1i}EgPs5923G+R#tl3i95K+TzzK#fjtRRQkIqfl9QaC%poA+= z--d<9Lym=owQdhKF_DjTr4<$7@!>5kVwTg7dhrE@R<#z?L-b3NQhDgGTI|^>s400R zvNp@0BcX)ob-0}|r7t_*!EYXS@Ey5@b+Zc#4^Q#wao2NEtXceNQaK$JI+F8yQ_Ofp zT=K?=sgHXbD_^}L?l@xP#X||34tY*aPENs7^*_pSSTO$zX zVdM;_&(%p~kXs?Z31F;8=*1zm-AAc&H{I_~{t7Rr-s0zIR3YK}yQJ|}IZ$Ai-os%r zkkW4c^i3-NgGJFDyp<`mX=X)Ri9%VdP;cKVgg1-dL@X664Dp!`M;hson~~r{ z!tuAz!ayLZr=H5m^}uQu7ZXDu(8F@z)DRRTO?afOPm#s{lu*U_r{a`>pdfl=O|zau z#lGM5emCClC7@l{LD32ya%?5lUFxq#Ld15A_Px#%18;-e_7{3rV#f0K*_5r{gfqb@ z4PQ~RZkS$lwf^+Cv^avp%?qBW<<8s8(jc8GNR6aMe-Bm21B&Y?cq|^{5IXj!Wn^Gq zV=0#vaLOqv-n`<#{L2O_SsqQA`%XU&j)s1v2c^1-QSOm1ipENZewUG#?}fyz*cnpW z&u>EFZBmVO|GDAk6-A*0eyK977 z%>J8hPFPX~)NkOS%vs5;eoh{h=wP`XOZLehsvIz8Emv=L+#w|=--KOudmD=}9u^Sv zmMb96L}`Vdg~bkP6gZOY?><=b4pHP%u1qf_ReR0GriNSm#7EDTuE?gw*Vor*NRrNi z>;YPKsq5vb(;C@!`MJ+C z_mkrg_%v~DlW7)o(Jdd`i!p!t^l5c<^2V zx7}|P@$Cn>}^EhmO=&NE|nBvk6mMwfngpF})SXf#bHbY9dLru-eeS;)%W8#;*WD*v($84*YRfK(&L&(DD zi?J~Q%qVALXZKThJvut}Fod3P+w%$C#s(T5xh^$w^1ad2usiC>vIx+ zjUtN-9(MU1NW2TgPVz+I8!~e8u2jDGec~+%qD_OfpK4m+3N%L+MsssB8VrQZA3P{F z!qsx2J~yGv%9@Rz#xO47W$J`7voK4phekr6(v0r|0?~Axflrm;;;OL0j8S5|b+sIg z-C}%;VC3mK%F(Hamfdc%A3siPy~Sz8%GvR&Yi-I(-=*b7p`_Bj_@Ji!RDEn`RBTR? z-6_~x?7%ZUiCG4VqxDs#4}4sgzJE72GsAQzm9QYdOFsog(Zwk#)#4E>St5{CH=K^1 z{w~EcQu|9yNhVLwzV)j8meOp{L3sEtXzXt6Jq>5XP~bi z*_9Rxz_LiO@>Mp+cntXq7go`vz`(#FsU{U2c7eU*4_t3tVs_PpbB8?rl$5ol@_uGI zp-*m8wst@64Y@kmoQ#!yaA5guqyTl6H07Z6>IxBDvEgvT*%ieZ_M^xz3}YHYQ=erpu4pxl*+4r>ufw9UTZSoov)lr!Ayd-3$y(NTIbhSQSGB^ z{j;$F@a7)ek{i;G+(@b3B(-}(!}yrslG@idgM)!>F|-(Bt@`1rib+X%ISJ8=A4R>d zq(th|0UzORFgGz-N1ZG8OaQ-R2VrM3>)Us_G~v!3%oN(STTHn}DLmzHPT+&QC69f$ z+e*bimmz$efnM*@M1KCZCTakvJXfQ`Zt{+FBt(O%}h-5GO z{M(fL`QIdR>)E=t9aI}n&uVFD{Z-gEtsd1Pa6ur~(1pVKK&r9V{e-i%6%{nQxG?u? znRLC_Bs~(LIcDd*89rbS%}_z)CxuqiTRrm_iIG@ zJjLTd6Bd2I-qkf_>|meF!spNQ%z3JQNt4+;W<(&iuRbq_mfXI58yGw_HFfiHCm-hi z>cEZivBAsT{WjM)S*o_pHbblNXN+}Agt;Id3F^vI`&mw)$Ppi<3tN)93AB^j z<%;t{Im>x&D)>gm5K9jHT3ajR5i45Vw(d%Ca8FYfTPFLY*o?8vB{tcP=2IFclbeT2 zqRZk~z3vA*-On+<<=(d>K^3Y%wP;fjY1@Llv!U!ORqYyZYUiH+P8y-qbQI z3xr!xGx0}sKVLI?;;C-EkqVqCF;S=WXNLfNnM{djo-xA+OZYCw>)pP5ak+ZQX`oz? zE}zs?u3lnx`fb+WjfP!J zMn(q4-@1d{SvYK-v&kweC}{Xa6qtFJ<_K9WDg|$&nU-HkhAl~Ab)p~1F&4~42cs*? z$Ot{pp6Oq>;(LZw-SULtr|)N`oe;x*ktbS=yU4h%?Q#d5c1kbK6ZX`7nUa5{CFk~D zK!&%bJSCmsjT>ank9j%mIU0uD1BmZ@B?tEUCq3{K(p}?gb!M@fp|PHRwLPmZE0~+Q zW?NQN(Bb@MrPxRUAKw+25nyBljc`IhKtNGZ5hxM&9uho?OhIf`F|iVmOauaU!00h~ zd3iJmSR;WaPS|F6ynMQhmJ6LM0(7J`HQ%GR4SC)OUpc(K0Nv7=NvR>=BzN$dA3OF1 z!u8ZD(lyM$&+>$xSVOq~Fj8VKjnB#ytD%*#wlA&YEjLciy9p73VS@youorer$Cn5N z)ce$h1MZL~@~WJQnXKHS#<}upN1IOFgGnj6&@E@DOrH;#tS8L8rJ>2|QOopx= zG*-MXN{I9GboYgg*K$*D#+w{eELem$QpaU!+-8i_6SkKrT*$xBwrB6)<~}mn9rM!0 zmE%~M$jTwHFDjyz%ueNp(Q(m#zLB*`f;i2*y(#@-OqokdN;aUs-?-V!g7&fEyHZVO zCc)Iep;_nZ6(S)sGZSPbccHh~QstifJstc-4o*XcT&5kA*|nADq%n>R;bJJ`_MHA! zGI{b9ozS{`ZnNB-RXS6$t+%`*om_e~C>wl~>8&^p8E`rzHj3=n!5NaU*PSk!4XbPs zTmy0uu~-2U`JwQ0bINNqQivrL&248msP;MA=jBSS`%!uRXq%p%E(lvsye09J&1`CN zk~Eh2!do@7Z-<%a=y=tGeQ@QUKE11}s!%?F*f%_k^ZjbYmq(YMIZMAJ9(*o)RAWKc z+1}PWvh2#`*}&X9_3Avj?3c4U`bEa)xgOJ?#*iG-*-xqca;>2Ox;UlBwPIV%JglOy zNxzk{gT${NvB;6)*j;72v5mAmXK@M>ysRDS0dm#+5L-&@3Pt=?zeNGm?5|Q zrvt1u@n}gs(n)SWTio9itf}Kfmhrcgn`a9zFZ$DwyNCO6`bnixKAEH}-+Cn=gx7jp z#_L)r4{!F9ZljoB@&~6qy{ZMRbYt(hXs2G?wzaN&dnI{=g>_Hp1BFAjcS;VUZla1S zX9o>TEbj*4=BF@k^y zzpPI4tH+nuI$9rcV=0&7EzSFi2+sGEa60Awkz@+o-f zjI36?ew@HhPnyAun$cY^^_SPjKuL?kj+rVfy`*vXJGOnhMm1_s>%Q+n0O3mYjg*x4 zZBzBVUkh3jF^_`hrM10cmqDxf^)8Q%C@f!m1-u*5X0ztmci&%5b9!I-FeNp$goMQB z;D;!|U@&E+Q6ncGZ1o;nAujQ<5gm1n^dj54o-TkeOB4(F{&5Ct*Z{I&{ zQ&qy8$++^#x9+kz_hs@F3x5YH%A-ayk_U@a*!t>5|AxVvXiXe@Da7iOBNp8au5Bj(cZVa6TK z?78{u8H~*h9XT%Na@4>qk#XzxUfs=o&#Qg+PEj4=`LBWA#&uFktO{!aN9b)v?{p_! z3G@w*`-q`Nc(r)<-5g!~BDb}fk&!mXu45;-sQ*g4?jRbS4d}QUk*0tA zw)I&a^;3)df`ZI^DfGpF)=@1XnZ5a1L4hC}n#E_#qsFEI7C@9OTI2qLMg zQ&HKbtc(GLmoY6mJtYML;EHS46R|8S+mC26s1@#DdNU1_7s8`Y0JwO0D_?!~U_O-0 zT`{qwfWHP9pNxPaA3?Qgm1TKtVkwU1oIc#{Z|rSe?eH)wNwp}Kk(QoE*%ulbipiJhuMKM?dzop`F~!sIxYhZvR#Vq_21>kZZR4Oari;FRpJZV+ zGNQ5N=_R;&yncMX5u6oDXi#~XZB|ZBJZx;W2=D-D1nLOZ{_1L3)4*pfEfMYOoK&l{ z_#IePIANzcwg&dR71h(zBaLFIsIH7)DO79Tl0~o_rC;uQUgqD0VT`MA4YrSy;_J=x z)dqv>gtEU6D)W^*b(uF9n{uu!J9<}$vcreJUhKH{_tSE3x93-o=U)F4Tdi33Rzg;6 zjuz9FdJD8ZeE4vnc(9|h6O}7B0gYZf3NFkjy9FMT6uJXRGub~M%vy9u;~NH`2L(&^ zF!xumvGmN$f{LCoSFX6Ag#mT?ZDmESLkM;M#VB^A7$%E+waCe|)iat}i$=FzvBzd% zTv(_;SUTn79xE4ZVd~J7)*}7nHHlwhEMPO-8M2UsB`IlDC^ujt`E6=vQE~Csty`_- zOhf7^H^NFs5>)nw+L)NoEo-p0jgm3E1EA#QHU@az+n2t>q&Pw3uwb5rOW}(maf7J} zky}&WPd{pE%D5-A@2?YA$b`ssmJZ3SlLT$r0(Nt`!as>TN)jKX=+iSFTe6TB(Nn(h zqHAY2GBH6c&#&*V4y>%Kz)J*4CV`+9{I@i!_J6ex`_cp4gZ;qBoA<%CP#2ZN-Q z*?w4`w+Q@RUq7Ofhd;UGh~sEKO1|;1`1l4MZRxB8VF%rdsXO03y-o3?+E;%>UzD!B z^dE3UQZ^QG$pL5wK&Q*NM|0Jr3Gzv;1!<2k`kbb(jLy};wADz9N#Dgzy`upSZCVt> z_V{9U#aW7cCypnwtP-qOS$@V{9u4dFHM6_X5SLaKN(VLUBL<1?A&%UAl2G++q_nWoI5e zE-N#L_yj`3Drf~grirO30)r~lO3g-4!Z(aR6BNz3(-UtTLO!XPlo$EJd+)!D)x4v^ zgDvxpHcE-UWRm+{fOWRRnCa8a1zZe)r#Mj@MXC>YcrKR1Xdh9i5-p`*u z%RT2N=YF2Iqw&Nn(|Ubv?GUUWQ5!%&orDXoE%ojGDiq!Z=C)sui;s^!^h40&dYbct zsoZMNR9lokd;a`Mf1%g3(|CuF@txov&K+2*9$N1)D${3iVW^Zouw;&IZa`y~3Nbr0 zy)x!A%SDmLYH62No$npHyzdd&K;`64qZ1tCKdbzAYV&vGZaJqDaASX{BhOS@k#Dq` zPqLTB(&a?@s9Rc#lH<|Gqgl>hgn&`8HnX3qD*_{c{zw#`+~{#<4gNGRfr@o$4YbmI|M&9)*Q33iJ<*e@YHNC6&4sEe z`zg$RPPj5juso8@#?(sPL^rzN^HB*DETwUXVWdytR>do1?#ad4S`&@8^-2TyZ8!)| zlB0L?EKhSy_I6NOcN$=R_MY4yd7rb(;>SLJXx3VE z!VwVlynL5zqCrVO3++gpYS8PZE$J1RG;_`)E!j6|nN0QORiyGiJkaF{b)@qkf8e?N zDmaWU&*q@IYQUpl;7PYRY*03PdyBj7bhc^moX@YN?s!G5&LfOnYs8eiV(LL;1QC30Z?oeI59xT0pzF8oWZb+ z_?Q?B2E&1jvmb>tZZ!m7?@Rez&K>IfqN77ESCj_KzN`=V)85{5DAlY4<5c}donq`s zPoTQFT3V1SmWEqyUoeR8IrB^oBMtm3_MBSG&#t`D$!(Tx^DN70`_RS?&E=uGP(Rzj zZ$By>$Mo!NH8nMH%F*h(O>uYSikH^+sBR7LPpqlkbwB#6innH)cTM_|NX27IwVf8# zZPi@6=2AIQjy(`cGN{3>k_bTm5qaICb(DiD@q@3$EQP4dReA=%(FTB{22cGVMKoa8 zI3|TePe6CJBsT3FvgPWqe9Oz1Ig*)IsBKn>Q`en7#dKNCFTA?-0kLn{#*cd3|N4{9 zA4!~7En|uBWGZcL3%XL6*eCmWVlsMoXeb~&A*sbBoaJ)-vHz?ekJ|E-Xy17)ytFXe z+x=6k<>WCSryGlnUy<}-HG9a`y(e1=p^gLZ-eN4|2z^_y!rd#nJ-rQe65dS@ZMKg} zt3=nG=A!;^r)+>Nb}N0ybD>l56^&M%Uo7ViQH~mo7ArRIWsY3YVw{Zu7x3TAj*40= zk?Lx)iADb3#t80()ID`J)3-@=s=JN@Lzd4$%5Z`Nm2t?4Tfe-#Vy?3vZIh#1EAl>k z_}M;1=Rw=b_Tb07Qcev4*IV5Q1k?}6iKD!Eh4K{T&C)3WIZkJ`d(YXw6IZ@aB#P%A zlrlxNdRzV9p0B7?ih(R*NZZ6DDd|lHZ))d<4}t{vkGEtG#$iTo1g+m*p?XrZj@ zGB9s^;h5RPc?Sp|t2#Ol%d(Vne(VSyr3pNA)qTSi{as6C`C{Xe4t6CVDgF) zCU%jT4=5_z(RNxnstq5h2c+=e!2@h|ub}%VF3bFEZ<-|!`)b6 zTIx^3eUd_c54-M%E>D7E-6keBJu}0*MPKUF8#J-GZ6qd?4wOZ^e!D%7Plikz6TceE z$8AOZ%1Js1ig*A(7TgPvx|{UX*D6G`i51NH0Q}bm2;=nz5Nq!j$)3ZUxR-kfQ@4JhL1jHyPCKOISE3vmt%*YxmUiX@0 zS9*Jw<-0lU8bvmzPZ_5pp4|VuNqrA1{>R&0D{204?jq^ZtMjDu@(XjtIku3Asc}`8 z-^_gXi6bO(wF*S;NnEpsa?Y^IzKu$4kf0QZ&y<&SW**g`Rppm1%G_1?)qW*3iR1Iz zwMTC&pIVXY`uWu`(t?i5Ih2a>V_$tGaI+sje&mOVgAc}g!76~dwJGe+!_wD4QGE(q zN+||Y$d=TG2uoSlCh7-Ls0k6Aj{j<9uIA^%zWeg#{@pxr6zqAwlnwRtmYlO_pjY%A z65}wucJ=DQ!ou^}E#=9{C1vcEgXV!1Q?rAAf^xDOOll=NpFFwlwK37Q5-?bJ52Gvo z0KBQHkc0eC$3jR>Z|mW1jdb$zsO@BrM?djMm|xgdTwDy^WNv1L>Qr8^U*wNP8fH~D zmzG!j8V`g3dnC|3Rzu-&&Y@J6spyGt5ApEvt|w1~`#HnhIQ@vTF>3>*t_er)roL(? zR8f)>P-4GCV2FDQfe`WN(RlzsvOV1G>;iFs+}^%<15MTQv9UdJa*Wpy?#Dn&`vwEf z?dWPl#rS)FL`tOa1{#*4_zd?itg~{a_ zX2sjQjcOUkll7C!)VlUwRC4HSACY?{%?*=L$5bieNrv18Dv>5tJ7>+Za4Y_J|Hv0Z-^G zQDGgmR^6hF>u+V|`QR-mhbt;8YlXD%n_tov#qtOU#p=+F+duuAy6Fox==$~R;H~!6 z+=EUQxHw42HsbR$kK6)-l<6KDMr}XL(09!>({YR1Q2LVlyF_7c-6#2lQ~g?-{Bw>l zQ%mL>Jc-#yq~$!oQlt^DC2H@)cAj62({=ktl`@w1zHQnilrg@Ke^d<5r8v6oa%`;= zp=nTC>u+dKtMklv+`Bd?IaW%D7$0{JmR;I2xp^{%=zOsuJmH49o@T1oJ$JhH%_(TQ z5x%GJgM$EGGs4CfJ>h`D@#9~iN~2%uin#84_YkTYoo2M|FyHRW5F|lNWNBMm9)4#{ z?f95pSXij_cdZyuDt;(#CCVNrZM(JWophmbCD&8W!CTNKRbIK9I>AOQwJ6w6Prjf| z<4|4{ViB&7&}+S^EphwnH+dL~GsZ&qrrO!WdqVT`Cy=#UEUrp)RETptsZ| z`T9{2ecLPTr2_O(nOBas9=5mpHlyv?me|oH;TWQmKlR%o=~^dx8bj1eS9TtEv$7(D zKkx51T)qV~T)+LM>x0S9pN|s%@+kbjYkngsM>4I{bHwaT#+evKOvWAhW!-&&~Oq4CJphSr5>2 z##riTKFC=r)G|A?mhJ+d)J-57`w8NP*>Z86x+$XB6ts2soB^_00uN9N~)Q`gZ z(Xwx)4MHl8Qp2|^&YW9iDeC~<1zg*+tjilRxG6l|-LRwSCTn;WMx0DtC?u;V`+2iG zI5?9gQgY8@=!vHx~4K@PfjPC?Y$z@ckVsSK}(@hSQJmk z`?9U_26R0CR)pBXIhCa}*JPI}uMx7Fdz{K=N_ zk=gytVUNgEdzsH!COI_Q-!a+V{QAzSXGi5~kJUMPx_ytAq?7<-;Ip@wpvbnDCqOJn z7G(K(Q2Drc*&eZ+_fD+c{(Kksy^Pcia6<#{j@mq{^P!@Y|5(AtoA!bGG0j?1BG-8` zODg{@&O_8z{M#gVCI;lSXVqrOHZvy|| z6~iyBA}ws2oxc?0hu+88)KM1o(}i;-6*Rni=P#m95`p2PB5$<02yFtV_|C?M55a@n zD=N};n4|YxB3OSxrHo@)p)5zdKtxe&pC?sprqGPsK-6ttOTBFNeL;79nsPX#T)$5f z2fK8#{p~%-%ay!)I3_A@RQeUG#+A_CA2|l8ioLioyscQUy>w~=n$%{@*tKb=N}Q|u7A1^huro;p(V%S!Ipa(|FA_R z&{k32A{{LS;eQ`!PZqllQd52)Cmi$h18&lD*rm0OuF(IS29rjFi-QfdTr`Bzyu44n z^~dXcQqs_$*HLy?@}A>lPnOl zRW?3r@JVB|E~sGJf5{*o~k4N$e$?7q}1tgrIstj;Q;rMq{(GD+v zx)t7&s>|%^=!odDx6Qmq=(Qi%e{n5zP~>7=1M8r?U0eeNK0m_pCTuyL8ZZ%__Vqd3sbo&oT#4{ub4X^a^C_YV8a*));7N6*&RdW= z^h+BZ6I0*w=O4eStlSo>y2%=tqG;J8@=Ts?l8e*Z-hFGyhq78q4*}RT2z<1+RnkeX zkf7p6yyx{Bb`PjlA>}LdB7VIQ(8_K$KIJiPp+8)DHQ&mT)2Vaq zokqCQZe=YWYjGn!y)(YBAlEBVQ^yg{&iQ$d@tooHo3E2xJ|&JUuUq4M6^1RMw)^-U_(@svaOwrsn1l$BS+ZV}qj1_Eq44 zpypA~M-xcEuk#&tzpdo-AU-kyB@TdpGJ=w_vd4DSVIuQm!v(SgDy@4vic19h8}m*%Nk~>sLIM(2xGQ92^Tf8@v!ilW!4; zYSX8=|rc&G(V>fsU~nZe$_C&ie;0lGXmR2|*Y?8)~xi!5f~-XM2?WSAO?x5Ybl;jgUl;za`l6^_-^3{ zH5N29G~_v5aP69Z(> z0mTt6g7|4|k@&S{O3!Vy1)8o}t>HmWyN9@zf+?+;X$N(L=UX!Ai;}CC&+s6a<~1q~ zjG#BWqKd%mzgRJVzmro^>@Lv_?jiyGkItULLx2}JCME{Y_&inC!q4G zzkAm%o#0WXJ5L{G@Y+!r`^EG@Uo$Q*_18gAyjy1G8fFb*N4D-0>( zYu$LIQ1g?5PS#iF3J~><6`Ib!i;N&CFYiBG_8eg@XoBzgzefW$g7TKFJoO*hT<4!? z8gvzIZf>X#;riODbkHa?bj?ukJOzRDRsm~YDk#_rF9PD%e*JQmK3A|Q+dFr!?S{-v`hzy(RUYRAeV!amZhS`ZdhKWP=KD}h z26*An>@P1b<6eeb3L;8{5iaytDn0{3YKI_=1DXNJ3^)z=JGilw840B80z$6D#5tH$ zkThF(fQ*m<4LS?U`276ngA<3HZeEFl6w<-b5&LAfhDH+_74%ITNW&)HfB=?}Uv1$1 zdre3mL`9>+7ruRbMzWMZfCSSOITsz&Kp`hixI7H@_3`)k8_DlE4c-!S3lNdS+1uUH(n5V^FSH6+aa6l^BGnZ26>Aru z{=AyZ19pa+cpL8w_8jixw|iz2xLft_enJv=Tgk_Z2@Bjy6wLXWPvR__N|=+HE=@KT zUf!Q*Ra%kusrkJ9hN>P*vOoM^A7^HYt{zhVl{=HCJ;wI;uGM|3?Hc18cXeBCth_x? zak0C_*i@T3bo~OysZu4s$eHxE{VE;Y?9D8vE)Bk3gB1@*FIZn=BS!(P)W35Aae~#9luVPTZ49%p;2=OLNHWd}hOJ${eS6?vMdi{t#LSV* zq*r&}_Z{B$g#Mcfk?sw&{_)NCdsM20$RPfD1-T&4C#DbPP1EC;p z<$=pM8S~Xcj^NlK)fM@-A@Y5mVkyAOyN&@(J>K=01@!*Z2Xk|C$kINVjTPzB2XDtM z+v$a4fH(CJwk4J*Ap+mx7V6Eqy6jvn0<#s-aGyJ^&QaLzO)fn2A_Z^J%+0pT5`G$^_qRTJ`T#gu}EQUC4uloY=!#LQShU|)X#cLnb61CQ9>e;gDP z%(*z{w&e3ampvaO;{UE;usM7a<5tpmchCi<-A!EtA=1jz(tiZAa+{ksF<%37+^`fW zOx8@9x0Ij%j_*K4sYZynbcs7imgNcSNLZJ1;3Vs8^jx}3 z+)p{lPw1Jl(p1TRDeaOiGOJN77;8rv8N$vq%+0wZM7MMik^1OgC7$g?(J-gj|w!n}24 z?(1#b!r5NYk9;#Z0j6ZneR(Rrp2v?f`?cWY#uIBSC^(?4t&PEBV@@&H5H4KY+$;SE zJp@5sRH;TJ5<^?}s1fe5lMzDCo+X)ZiCFH(N9%6%HiqX7VplpkzCvf)b^zlXhOh6X zo-jp{MKUSoRwFdSsfHOdtOkqmtq275;7<{U9;51kJ5x_WqNuK}4kI&2sqDK>Y*SCP z48y$H@bGX_U&WIS!A0)7V+uU(FYGuaW=Aq(RD*m@MX>H@cwoIhTE(2M>mzfKSjm}A zX@9D1`}W4xeA`#^5(0@kk@-F`Ge$)f*^FV==T?b%#yng33M!Hu%`tPQs=9i*%RjJV zPq6Hus9th7J5L<>hqDRneK)O6e%+{omzrqI%0|^w<&eKij^2k=jn%f{-l3WKgDOEA zOC{jOgiz#}<*Crp9{F?-PfX+Hty{BC7x|%y-hrzTlXox@38xa;eX=*xus46etpHiZ z(gm36zJ32Lhv8~BZbTl2_F|XuS)5u=8EtHAzKyq%tD#C)^BF4X# z_(+{?3@9io4*XyeShu2Zul1QT^Xs!&r#rl!ZAUr6HlN11uy{J*YEG2sR=xa zo^bw1K-_DMbZYn3sHabja*G~?e0C_R{a<+4acoa~{j(^ZV4n6y>N^$rI|aO&-#CCF z@CwCIg)%Gep*$b?UN1thtlF+!7cX6Er=s6bwAuG)sI%~RxP=8%dBM%h^9lMj-&Cad zFKKa@Y82g390(^Pc>#rjRE|or^53|0T&U}K{-KK!yw~kdWhK1aA!0IJ*_a}v-!M#a zU)sqQee*gfU2}WMWJF(|Q>;GQzK@T1dR#`g?HaZB&@MlVyoXU?v6ny4Ne&6|TRxqz zeaIe{&{?Ix!NnB@a0(Akg@*wJ^e+h8cYRj}*^g7F;NnGlN5}g}XY;&9-iCS|3i^Vx zi@OLdI0$gYTSm6pmYMmE*3E(Y!njw|y61m=`v||fAc91puffIw2pt9!9`?SHl9F1z znqew$Jp^pqY8LShU%qU>RYFd{rmTfs6fi7g0WUULn{ro3HrQ=ZjDLyDLMJo0U`w z$QS#qWpj(VNs0ii?$bNO{C6cX8zmi+uWNW?#3$N0f# zHfwL0a#lq~aI$ z)(m=bg=*6#%059--oJfKSbJzN*KzXFs&(lgG3+jC>9#L}0+Bcaou$NS__=ecU(4lv z+soe`$W(aP{H?Iw2d2k+eHvqjEw>6VAS^oEM*r$%udU;C#+@=8Q|&1q7;4q`54f2P zhG;v#@5vV5Gp?>OwuhnC%F%IlVc|S}2{aAPd6&usr}r>;y6?Um*~;s#d7cL%Kn#OH z(N**%|FyVU)qn$Nj^ ziISJEGJCU&&lV!fWqV5Ho#$8z{fD0Y5-oiv8yHrvev-YQ(I=hbu8!fnehtCQgQX2G z<@f5G*YV?U~5k2Y>~ge;hcm#*5-;}cXqgH;jjx!Wb>TW-8fV~pGu zk;jxzX>B^9t)0B>p{L$yQ#sX=b`v|+rsV_P-lb9-0&J(a56DfpR=rf#mFX>DxyCAf zaLBQf!DVox@hVM;gW|Fy4VX_{WIw)rBaK(X#hH5#wRFpXl@;8+pN~g~FmiOc6hCDl zLy+Sr{iD`J5t>as(ptuOPCrZtNe8w_$#l-r>3Z&_mtqL;XL)Y+ z?687T`Q@kN1R)6t>c_eNVKJuvysQvV**l@oxhl!Kh3vXRU9^%B?JGs*kkINEN5G73 z;pfNPS!3HqPoG)2Ph~9Li8P73pRW^-+xn+)4L%X$-bmH)iZ;^yUK3?$6l@bHS^52V zjHPL7jpBt}|6sFIQJ&XN|K0dCVDR_L-TtC%ThDEGjO!@}O^WL{-0Y9t)Jtmc;4Eh{ zU2jPV2zh&lcx-b;z>#dd@Qxb9a)SyH;8p@ zc}qM7aT@2=SV-&cC%81xR>zPlk9=|?=cH4IxP)P^%oVY&&6N2*wEmt=oG0x@Zhw|^ zMiIlnw1szm;kxyB_j*&(l^_}dBRiKF^fxhSzLla;9ihVKZtE>|FJIi-#7NWPZ`FEN zsFJ1a()h*2<;6#Ji-SF9l*Z@dvxll!*rGpC%)hA35Q9LS-q@2Ql%L5E^Cs?^-?p>L zO~X(z#5p8&I*P}_>y6SLy#Xhs{^E)Fj+S+6l(t5c4lQ2f6go&Usn;yGTv&K*V{6OV;crZ9)e7GHs}yHz^MR*VZi|{ad?xU3 zNLP`$>TKuAWcS>Dgcw$`W|LsM{J~u65!o^wX8esX(dB%qdq zfMU5Hh7zRI<)6H`bO0wdFTdI{ZEb|eUXVtd7KJOBISMx+11!#;^ZVdK6cnX5gz zL0-a3SDuLOU0PvfW%U`fG8TNXP?(@zz9FOTuv6QJ&S&V_>Ji6^FphV=wRV(~Q32X! z{)wrnoYyYjH6FNCx9CMSaUx%ZO6pc(ZNOHhHMw?=rHhK!O<2etN?LCf@wW~Zs;p-F zye&{W`IG1#?tMe7nezPaUUSC5vhW>xJ2dP5{{GOukeW?QFS5V<3+;@m*!1kI>4SIg z-=BYy#97o1d1;G;u;MidP0jNIg*r9{`$)*yo;`aiJNm>C(LqJUs~jC6s30VyZTBHV z$$;pq+%j^itHs?SAubw#5g=l1qP(W&)*amKA9O;7^GZ9qM0qxEMdXP0ZgP?}JHOiz z*>|*l6ouH{8;(gb1{^AL1^ zkr5ySXdQo~qanhN#V<*c=(v~)CFmGBAH;qf?#m|(_x{yi;$Gv=C65E1!Yv*>5u6SQd&1@=^s_>&U5B;&i~;#)Fi1^qPA{FVXo<5 z#`O2>^e4Lp<)pi6sg53i1zMp~yCmoG12EM3@83JYo?(0&X!x1#7ypa6IsgJqw?}6l zG&Y_^@YXerH|`28H!!yDF3exB4&ogZ|MK(mgOCLubi4!td~U!$Nm}=$q@Yu$m}zOd zpFWKc1w;B90@YQhv{9d+Bfu~QGRrtI&Cn$wfTaowx6uxfqW>TsVdaG9%IFECGytOo z3bexaC@BpAHd0Xu#v2Kk2DNl8{O@TDr3dtfVhwlX^J|*FQH`KUyQ&_d^!*55G;(H; zwJ0VoPMNNR{+H|AX^47BY3PGK8-M=T+Sm+4fI5dF4*?|_YHDk!cbCNI)Y+VDv`?=S zB0!g_?cPmILGca9h_pBf;t<;s<}=wzS+0(jMbAYibus-^}e zK@3_1fr|Pq%0k&|F)gxH58*-=cL=02WJ<2-CiM7i z^0TAL7Hg9>Lf6T@E!%{Kx)~YEpL>Z>*q9V1eFtA#bhS)2TDQloNSt9HNFZA-!BvZs zNowc;+4vmYQm$pf56{W7>G!OL4jkMN%;cE8=;Np2T)69V!luA-k7@oB-zK_tWJ4Ex z`xZ31=YLh3hhhjQ8aQ9yxv$NeVL)Z@CdpD!g{=c{jxqoJ{rh*IOu&^~jE%c7zCiQz zw`l|=wrP1EI^;jr^oumjz|L+2(vI#2NMz8`2>xURZ3ChgFip0QN_Q^?Y+`qQIREoK zFj>U+1&vf#qnjs003d;>*U`?-6)Hne6aQDrS#=EMT?QOwkpHWoI012w^~J1S3^8>x zrey&;Bqu;pxHvUs3q<4U)kiqHaT>PLBYg4|Xl=OC`tx>tuDL%pX(rQD(oxP#c#V=* z=2jCK2@P$;5rIM)sx|yHgofQl!Z#pPRMnyY`_Z^|)U<8c+vweQVKM`b?GpwDozUxS z-~TYCPG?ko;N-FY4~Vvh+-7mH{*_xJn%Ka=JMfik%zE~|S5(NQ8Ctj{sYIb+;s0Z0 zWp6m=#i!=we}+2f=L~!zy|lUGVs`1+Y^QtI)7OU%RdG{#%1hU0NUXe0BT&b#--|0G zC81J0H0Z7;cTUH~p*?(+vNVB~L%m}~-cFIMes>eUib@xzl*_budB;#xie2}b?9`SB zbS&q18@YUzb2gQ$Qm-*awQO0M0cAP%Hx}s9D@V7}PY~$#_ASo8_k;+5hUYN|W^8N> zCQ67-T<#qs66%h=TEqglcmMv+<>kx39r3&ej}4bwo(c};U;^0j{{ylz8&rd)jgTFt zW@%y3hxTxZ9+FrrE$msGGwto|=twCm&TanriTVJI&9R{pV>lep>fa~vBoQ#L0IotT z7-H=(&b`9@iEI>(CLC1YfzVPuM6$rZ_^Gue4=BL^?!)(h2)Q#*5a75$bBnzlZAnKU zdF@GKULjypRR!%U$b6R4)70b~P6oiBL@LTRZ{J?Z$w7o%H*$bvWqSt)Gu!XAIIvPK z8w(Gec@%~OWC-9w0t1~9e6S(ox0T{GB6j2n5e;7YU;D%6RSo*uGlHo?+&71EQ}I;ymE zayULM)s83#O}y`LQItFsz4qnclM&+*$uq`iInf&aLOL4mNBV!R$PHM2!2?3yj0OX* z|9^2Mn3|Z3fxv=V59eH8-VXW?bf^Z3IFOup{``3e7$R0Il4*`((_{M(B#c4YafZNm^>b8fd!NG5Qom4)~0^$EFKpLH%>J9r)OtF{rCavDld^*8|JWMudh+zBbJ_v`%#mV&X9 z1k$Mr`6`U&4M_0dNkUeeGp8b*{^p;OP9?Ldt4YyJACE4~rlEJo5dR4+r`}Myr;@bFyrWZE@ z$f@z2%zf2g7I}DN$y_6Bt)69(C&u>v>Z*)*xunxjQXJ(jtPwz;v)W32KY+$Zh(9p( z1b5PR;=YeEo{U@e`6Nl}hpgRK#q>pxj)j#sfHUfcXN5JhMRyI{j)|cNJC?H8J?1eV zH#Au1S>!JLQ?4+TJH%>u$@_sL3Pi;uCr(v?h)}e|jD4Yf<-DMdg4< zSS>LjWm^<}XqLDsmdstO^r9k=C6!R>A;{!_RZbpMFPLOTO<9Y#0e*#yfVfo>LdVU0 z3E;`f(SpRH{{@CC9HA!+eEtrstMbMTV-)ypPoI!PMAWxTH6WK84m#d(Oj26dI7`?Dm((A?gq(Th93ZO7B3ISMpgFZ*h|@KtJYR5gmDyAq`VDahaEg$P#0o#&#Uy^)%5gq zgJL2EHE8sZs-lf?y*QQ+OxEREOvB=RlZD*|D$BYxS!o19jYA{QO}ioLIY+uf29vy* zE~7Td4sE6OmP%JY7?=zx*xbQHFr&A=Y*I;F&t@4+Ei7hcgDUEI^j;rw)P#zCvrldLWDD3n5Voin)7W)t28@sF>9CHZJM^(KqTH02}@|L z%gf8dF&hKbEUY;s*2=;n3}739fa~xP08#*HRaHj;j3K^+nLx_zKR+cT1kbNpbFQT)zO)vsk#TL8Uyw3NZgLAfrZ z|E#m~5Eyct^?*wA*g$2hd8n5MehhpqHnt&P#)OFIXmY=; z*$YmCjTm?8iE9JmCWQQ9=!T2eqJ;?5%aua%@=Uw9zy`-ee|>IiWN63KDg1s>Qc>R3 zq?K#Qsrg~xRNT8sYc}JlrPWoj+7go;_SP19--&aTH1B+ko@8as=$P?jWR)IKFHOiP zOKI#&VABW}<1c$1FM94Se>zu@$Wd7QXFTJCfhrKOMxEGsf z$x?a!PiU5@vZow!0plOd#xZThK#kpa2Bs${EDH8)<>NcMzUo^gLSkQu!9_5}@WSi#jVvr22BOVY9}to(wL_$~SjQ~9j;Si6`${4Dinyi5_h*HF z6W1VH|1K%T-%;%sUB@UAf=nU<4;j$kbaE;D<>AA~axixHWX9udb(sx@MkbW18@Z=> zWSM6?#tDeITSLyxX-xJ5=Dd}kpNfG8Ww(hPuM-h-#=GByqWIXR)TpGw=5!^Vct0~) zovZf?3k$*Geelauyi5P+MImRJ?kh~Xlk-EZchg7AhU27cf^Lra`;9*0J6k&khtBdo zk8TDx(Mgd3hUt9edHF)u=G5g8{Y~c^e|!GZl~rZKlR=;+Ny$){-(@==A!&Nqjv`xr zpLw3j4Ln~Q$Tpe*$)a}9cW#y9oZ${nj4Jj_Wp%t$d-v}1Lnp1RB_-q&eobBS;dpW0 zqg3xp0^5$cO_q`%`p;TrRAK4=;fO*CMjVWCk}U|z0c|`S93zzQA!xYUrR=unk@|hP zCG;a1XMoUw@Ta(@Vsu5z>>a~R+H5}2{F&>a%DMitxjs4^3e_()i*`?bRTG}s8-Mqx{F+E9|fDStSj%#TqwM6yy$GHm1;72(snA( z_*B9tOH5sZJgrMFp2fB)g6H}1y$|ALXiB@#PNBsI`8tL{H< z$s`df6xpr)-&z2J9X+{XWfr_r2}>8QEbFt>$R`O_70D&!UD6kA_?ajlfT>HN9Wu9lsJQI?Tu}le}3>nItkjz6- zGG!JKGL(5*=8RFu*gz?Th*VMh!o=!?MUD_qJC-5A=@Nt{$EE2^C`%Ou0(yS{@BZq z7nXh}X^|^8=>b2|V$}Fjt&WgHQz9aWyZL_CtU!${pYr%FUE`x2Q2$O-M&uQ%E> z-}rvF;^y}-lIIg$xyjvfaV$D8!qu1&e^!08-CgG)hBfG-5;AAMi$ zY~R+L^)nfy6ViOKZ>!-UA=#1 zr^O~cVRs{XI#DiB$5+SimdOoWSlqVz?6-5pxBQcJ1s9*n?239RQH|#Pq&_-B6{z`Bg3Vsi!R;W1ye7v`VqvI75oO!S)Ju z#FFR9y$j8v@}C8d%JyyNq*O2zct?uK6v#ie+hh8yN6A$eR^JA@dXiTf=mty&$OQ5T_iX05PD#!yLNuPV|d@ceS0-%VGPh8^p|h$T|7~_4d$+`ThFDX`Hz;xLtlsH5n9jw%p-iz8=?f+ ziyDD6^#pIsJ-IvoG=M-rbjO2(nP_PtkJ$cQ^)tqv|5#t|?C2n+H1Tg``y=S>?fv5P zI{`E^c#5DF(@~d2l07naP=7EpFuWhDxQC+Y<(m-0F?4F^^QX|WrKhLkfAe<#QfvaG ziS%tEkvMyRL|Veq1855RNoa<8d$qkz(G%d($p2e-gh0&FOd4kqRa{o&rXdm62Z$7= zOu@|HTi{}1GW_eu7hu1Cr#z7o=zsjbfP)EuJ3*}8gJksHJ#P%t4iF0*;Ma}>=E%*) z#KQ6iWiA;3cw#67TF;+73y+8xeadV!IWh4sm?k-a5o6u^c^=zw5l;bNw~oMUp`Zf`vpzp3f-$`ZK@J^uYaw3jsqB9QXs! z&249Mq$l+Ks}e7QYUNN`@7r7Uvt7)PxWLVgE4~l&8D=7X`Vw>i$LQ!pp_WBKhfV1i zDXB;Bm^D@qkXh<21%O`vGJCM|I5+9uVHens41Tr#Z5MB`X!JhKS}7Uq2hue9+F8 zY3y}bqy+$;9)J1r<-?Ib-rx%pqK1Zy34MToaTaT@&zIL7YJ4RI;p6*v?^F@<3k5-Q zS66|yHOf&4Eb)S}gtX3D_vSyDm{>!W2y`^haB)yhATs$-_*IA{vBUocW`f6*qyx)W z`7=0^ouD7=_Q7Q@?Z|WPlIWa+JbHS!btuV2WoTUnDq^ck*r+aYCm96pDUab$rr>bh zFD^NsZZ_Uta-rnxfG`_>>W#AuC2T&Ml32x=Jhry1ek&LBmbv!nF`sk$CzhgnA3B54 z^*xO+Ev(>QplN|>1+-aKcD7^3@i(aErrNwWcb$28BOa~8W-cx`dyU1}bN44`XJ=-T z1`?vj9CB+x7eXJe`}o2mPNbJ0@)YJI+{Tm0lX1ITSN9$(1~oh(YI!-J)Z7LTxVd=~ z8h1#OzB>cU2EI2pn0Bb%j*Ek1&-_WOQoIEOC|P&iuu|ijn-w-ZU0htCVTKy2!ot(r z`#rJ(UjD}A+K(9og!G&o)XG<;r>6%72JnGUPeVWYbaZqDMiz^jAP6n!<3$w|noCPx z;x7XDU8YGGN$|P@^v=x8?BZQFsBM8UsV$(Pts)Xr1a=*i$p+w>Y2Y_JJbb)^q>T)S zc5Dwgg3Mhk=>0}U2Xd&TvxK7eeM8I>;vwvCwf_8m@rO+iLloJQZVe4B;)#h^oo9QN z;wF}ijRm1sI2gm_22JGiEse=E%6~ z23ZU#($7Ken6$MDW59gjNT`xLv%}s4J#(+w1ky5lemma=@h|X`S=_P82wN}Oa)u!aic?Ed3g1f-69<9+ zrKY3+4XLn@?x)1t?lUq1Z4wjH*3{IejV=8Xn%WObOE3sS856Uv5wWhsNDrxtmxl)e z#wQ;=f^bGjK|!QR6E;QcpzyHK#oxgBSNA$oK}ktgS{ip+L-67A=Y=|XnvXBrQb42p zcyjU^hy!v$AC*x$X|Z+SZvww0>BaZ#xrr2oH@|W~FaQxC4TR3g$-(L$xi(%jUNvCpxoLqg)~sej#+un>6PJPLIu_cQ|jTv#Z4E1Lu}!sXJTYDcU>GkU%+?%e-?F46dQDHrYsUaKy7%B%aGoA)3c+lRyMHs=B?~OLHD91#)2E-RWHBE2Tjcjx46nwmmZ zv=cY(8w#{X;ur7b=jBx!;8)Z+V3i!F-l4JscQT5{du;4DLPoy-WaHrAz{CMTK|gw{(E7*BPdmlf3 zynF*{7^n_UkIL-%k%3gv48u6lBDm7^LeSt3^!G=bD#ne(s#K*45NC6+{{C zc%3$i+Uqw1fubbuzuf!#ga4i8zINT9&G!xD^|QXvM}7UJ62M7(7gPq!k_+U&mf&;a^i@Yp19Y}MGtCI zPMlJmHvR@2But)s0OMB+5&xxUV1Qu-R@TZEFVafU(-K$(1z{G3!=n(j`CJBO701Wx z!>^Bn1uxKM-(H+~I8_Ddk&bW)FWWDr9XmL_o(2__kU$*~@f-Uy4TK0hJYe=$eI??2rp*sYaSReMi=aYx_|Ajr|nFMXHSsGB6-y?>t%72DJlB;1UT z2mxauEK#AOUJ`o?FoohL-hZ{RWv3i_65J_gS?HTM;=8*w?Q*a%Ku~!cEsIVca^M+i zq%fVwVMOA(-{$)x6^Lk2lbOl!Ix*GCR_l{+`yXx1YDjv(TJ%C*z@36Mg_hZT$mw6L%ciz()GgOZ1* zCy!Qmdo(bu;58Iaw8c5u*~kGn859Jd884l}3)HA5W&lL)mkdKIh0PUX%P2nmfx;6Q z_NS#KD3StTf-AlC8WG!o2EY9I^-h~U9!U5iBo~+6N=Z3Nc6N5=Hs^JOY3b=HDm@nO8}hbVmUN6(%u!Bg+fvB4vVxwu^>~K6Xb@6X$s77Hes&;dqW_o ztE(?}$>>N z(y5Tl#4WGWZHf*Mw+lUDhz7zCi=nS~YUd@8LLTvW=H}jg_vM=JQ|MQB3o#aA598ue zK5`=tp1?Ue7FKACQ<3;fONk*|xX|TkT4l$!tE)dj#42g#BicPCCK%e(yM%aoLl?#* zqIH@8Xrnw`{t^DG1`QBNn1Bo(oSp#Qp)PmX$~+tZ{PjjU4wEy#R`$+2VNTb=LZMn< zS#$H~?c4gotjGf_AJbfgl;QKYZ;8E3aOLgE6TJmh7VKQJM|e@p_MUimUbhs6B>nq_ z73g>6w{ES2X=Z<};!$*2fAQTC;^NC8U5F$^pNYEzHBDk-B6gj!q7@Z)cX#LsF%%kJ z8xl8#CyhWr4Xdm?(ciyYn3d$U!?{m6h94z_oB&+2l$VG;4nudb~rGxDY{Y@7vY%DrO(oiOReB#*|G ziAUw7oYzx|l<0*xCQpZ5gZ+_7x|5l;(L1f|*T6JQ3{BCgT8GXlS@o~D(OJyQr*)Sf zOCaz*P3Ylan!1x*v{kddAo2EYU#u_`ct{a%q&W?p#XVScPaa<7#3pJZOHIICkN~Cz zLAT~G8@zbuQ&Zt6_-IK~4=|^IuMPVpy(I2Ab|rTHrfDjAABr8vRzu3ZcVg2i_bDi|HrJ`QE#&5==Z}qVQdL0KlrRt+inmr-z(*XRf>q4?7MS8 z)=k>W(O=|O2^(PQwup;soY{CbGqWM|=ldY4u&|tBr}sx@OT;unS7`-T5}<1l%9dID z{hfjFWn=Qp!jTattX;3#6rHv?@J2huw6ARQvs17@f}l?9 zu)qOdOYJvmwsV2H=##$U8>5c zJy}onCSCo(&A!q}TzGtj#aG*BkC=1GRET)>Y(@cm?tGwx&Ip|myE%*XX{i1L`Y{eFfoeVy%kMen=eeGTwPqgcWRc6fYPC8+jhFJ{h-nyCT4#dZ)CFAixl!Pgxrgn7yiNpfV+X(vs`3+e2!u>ROu% zEvZtl0&W1tShcp~>A%!!a+5t@+FX!);-gyju9#J=mz5`3!i6PLcW%kDxos;^@!)L` z?OI<;nba%u>yOFH^U0e6oN6fZGIg?^I3JF}v4Ja1`Ygu<7}BizCup;+=v9VzykaeH zVKgr`aCvGv0-?>x_l>G$%~fJDvo&MF<7;&p{M_DmMlAO>+hg5$(K4Bk4X5m&Ph`q^ zsB-Y})oc^mf$}ZYYp#~OBCFDMmCTSSuQhlsAG2D(YS3rv?qAWAv`w!>Ax?>< zr)<5YEV1@0_v_3Z+(FDjLd8oW+1)mFap6eK>{UEwpD)v|kXkuEVpeV-orhPAaY@wBweHlMC0>EF&q zr^^E$%!bXR>^=I3;(@SJ{Ux^cebKAl(OTE^cxoFc*T4E)u;%W)Jbu+EYw&3mQv%A@ z{zu_I!Z$$2!+lFZ4&Ed z@Jgv%hT-yS_nenXKAh%Xt!J#`jXmGkB|@jB)LinBR)9e?gI3vDBP*84YG+yWikpXZ zRg_m`#%rSwJl0!i2NpUzOfIAI z5gv@0?o?zRlaiLn88;O>LNPXO9cARiksP3x!Y*c*G@h!XrbynK7FQGeQdrk&<-oGm z>%&zY{In^L&l>wQ(P@@_UQC~+AP!Q=lz-x7MB9nAgJQ9%rRCL^AMkwh?r>)$2xEY& znwlEquZXdS>q?Z*6Ns zVZ;cdH}nXDgYN)PtKCLI9%wIE<)DE@HVb53oHN^zAu-uljP@RSQG6k2v$nI+Lcw5X zZ;vEE5HYaG%56Fa*V8*hE+uGKkAeYDW7`O2>JURP{O6ukTuLW4p9vm4cuK{pwjZF%-VHTu4K9n2YluBDA;9 zw~^g+jua>czY?&9<#KE?K|1yp78lSXrVXA53>;lsu;O2*wW8l-5xmbvLLxgrN-?GD z+vm@^FO{suCz$g@rBtg+v^w`3rB!ghT+1}T&A6T(p*vyK_DG|8AZD*ohFz@BxYj^* zgn@TlkiX5jmyHjzQC4Rt=~AgQYD@%q zw3x0p^aHjaWEi%>2#Fp|MOpc!5D6B=g$0KIs}y^Zo@6E&0fQIODgo%-y}KVB*_D`YD8d_1V-*T!25l5wyspPX0s&|vLjLY0oYvJQ z5EvNFed_ty(9!V&ohKNWp3pTJ!YsgWK+hI6Rx;Tj%QC(?U|r?pAim@8z+ zj?YH*wQqlLX-DlgYD3kkK;cF9Bw}~BfTZfXw{N|Qp6wsGk&&E4vsc7JQzL1dy2PSL zsr0 zvh18GUjiR|f~ItE4zrHQ=i8p0F_YM_!?nUPTUR0LQ zH#j&rJiKko7LZ4~t{!G@`ll8Es6K=-@ZNGH>0x>nctQ$7IAS>Pd;hML1o+OAxwZmx zv4Md!Hy3jI??6zo7eXoua7jV&1iTIH?d=GK$;-{fC=<71$My_!6PkRUD54WY1UTSY zF%z~|;3T0Je2dVUl+@JI8bx4gbB>NPpjw}Q`*vV%1uh2UMwXsX*VcZ4{_^3&G%s|J zXzzjhDJv=_r=|krH!NaB#QcR8a`X8d3*Se&wz@Wg<48Wj~E#x?U$Te3GomU$~d2r zLdy6p(F~X$5%EyYXxP*B5N65BY+lgy4VHvfRY%~o4TwXOvmf_ z2NOd2)^-qGyfn{Hq!uciu)D4=p7E??1Qy+qy|oAHNBOPjrE0e7ByyKBiVkXBk4@7Q5=`+2bz%QrU7A*ksm06gwbngyf(HfSP6N?ct$@ zjm*Fle-6hWt3I}wL>3|TOVI_hW-zk!73cKIJ8Q6a;R41VJJQDnb3T~+~`cTdg;<7aNc0R z00IKMICb(Q`_7ui#$pUkMY>%S83jCy`kk43NetsZ;b7Y5mTC*=`k*Zb4>bAsu@i{i z!c#M3obOqKzyA$#xAxs~QE+gSsV~Ni1>8Fr$S`sZ3h+d)*u%M}$w5~B3u^xL0s`S} zV4emOMmnB=fUmEI=CB-}EurRiuYMNlF7jO-^dhn8e;T=FtWE#ayPL3{#(z z?b%$Gc_+kM{T^ZrVV1kQQ3O@(CcY7YpjJuGPU{7}6zYg+XC2nR5aBox4nh?8i;^_x zRsmY-|0m#>$D}h%r@DVXZr6LOFS;ziNTPLgBzAuHba$6r`T~9&4;!9J zNc&l!MNw2FC*bD!Jnvk?QHJ9kTTATqsP*+fVWhkaZ$H0C?8I0|=+w&yB3-E+9qRjy zqjgSm;#>jL;92fWeP< zXh=&ZCF6rs_}>WepZ%2lhyDILB|_&u@B zu6=GqXKYycUG!qRK~73Djq7m+X{()c`o61c=|o%*2(R&>G%-p7j69&Lr%(AJ zS0M_-*y>)ad0Yd08I(E!EW5O{dJxe95E;s=0jKS@E#m6xKOo}=s9RC-2B#Q&8|+E1 zfi26g0BkC!yhf15Bl#OzQJlYr$v92g5)-%Cn~Q5182P+`q%bQC?2mYUMl17>U!eOM#NM}N5>N!P51AonE#>wAL7G= zC_I#)8jiZT>D1AgU)~e0_n!dqOOMl1Q<;KhOLpO~|5#NVX@`lH&v}Q0j~0!XVc)^^ z1#^aN67@Wl|5r@L#W*Cyhi<%o`7#ja{nSg6qSyc5;P<`<*wzzkrMnhAxvcWTt;Saz zPrtTlM?ZRrE#f!q`!~^YOqM{zpB!`S^B_pW^ES!lu75I{^CiL0H)fzH>Up^2a zEs}oz+-S1%!fUssMAp5N*zHlrAnYGq7YN&T?~ZwU=jY^5YXgDo4qCXNBTNeSLN>?u z@SdWg8T2 zCV6o$5HdpY%x9GCSKglTPiXiNn&z7mE(DUTorDeZ2>kzu4HF0uH)s`a&o<8Z6dxq; zO3c{Q^dx8yMYlV6f>2l;IemP6Z3ikL%+?}JHnph)9|QUV%tdzk=jf9AUB|Ui(?gxW zA-SI<8RN|Yp{%QW17v%M#thCisB1_RMELh*m|BGwG(mjJ$(ahXqAtJl=5w0X`q^Q< z6Z3N;p7h&eKF`Q#2DfiDgCz6h@h?zRj4HP<1z?q=Djh!fUU)(~>tSiEdDvuTfP8#Q z((M7MvY61j?LPF2b3gcqTlIXSo9K*7$rdbqtbAp@Tw1=Iu(Z4S^_?4AGRA`qDk|U0 z#TKOQpo~^Xiw~@63Oa7Fw#WL1vDwylM}B8RACgm8nEF*KY!iAmu;1p{OS{sID_okn z3GzpWve4k-WMqgI;qX~HU-H^{l`21;J?5`Bn2Dl$+-;!K+tOqBh#bAX4!e3ie|iDSB;OjE#=RStG>@-7Y`Z#3Ra8y5!!J2)e9GO{)^O_# zW9TB0fkJuYmR-py*(RQhhHXj@oM%VE*o1`q{rqMgftVtNJ0<^F*hLJaq@ub#F!1ro z6&eXCFdxZ(QeeqjmCfW=lcM;YV_ET`mNLgSjWy1Yi!=5$5Q)sY7cw)UD&6hM*mT+9 zZe^r~>mfV3O)f-3>*)(cJ4?N4jXec@E+nvxGqaZ2ni8*)8K(=IA2_JfMiu_N?7>Q( z>Dpx%nL3^BJ958lrR0cvc6=>2I&fg%VxHF#55c~KJ$oDIc#~;;diIElijpASZe}U* zBoc7U@6?elZeXsyj^i-B@(wqnaE9Rs8N-l*p;yyx-i^}hXK7{TchXbc_Co@fR6f0$ ze)!H-t_<>@Rg0-gyon06CLHrS#|&=v6$vutmXm8SypM~IQY7iM zU^aW!Gat;GzAup=Ea#h?y9MFyk*=dt{4_on(A%3QN~P=I}!cRe7yM z7SB6c<2#(+;Zay7H**$FA9!+bS4_N&oxt<)h8`-Z$|zR(*!`Em(28;FJC(!_%#!1t zo^#ai+(Fqi!<+Y{YR0vhbsc5LN~HB1pA__^QciI>1sc9LlC=^ZX6lQ7yR>xKdn`)y zH(hVil`5|CLgU&L|4w6tOqqT(Q4B_}M&9?uiw6SkF1r>l?kTvXy!M+=_G&a&bLr!{ z+Z3AuWQM+FyShgC-Ef_{QZ>fuA$Yw)FzC<`>f6Sn`(M|}+gVOZ%HJ%o)!+nwKJTtUtEY)6 zi6x$s>N+P(j5FSF&NkbF@KI{ECq@!fJ`hc?#XS^kP&dFd5RUv%Jhn652XCLSIM+bWq#kvg_&cyUxwMOlwWa6 z9~Y!{MAG-;Cr^F={m{IvgANepU(ml{$z*M%2rylgX99MHU@I8f#(*||U;vE`U5V2* zKS#42H(qiX_oQ6IIvg#QX;C~D@BrkGx{TD=f_XWs0+iihf{+@7a?^9~ZLo-CxcdDgQh zTx;b1x`Jp+xF-+fTZx^nh1 zRS74XDSdb>|3Q=A56^7etaK6~AOA9Yb*sqeCf&^E4i-&E%&ybt9)H`~*hs314@_9O zZ6jDebO3PeTbgm%Aw z925FvfVZ=%y0hX_!SA4IyT#5LU9NGz-#Z$6^b(Edj{41^7DeQog)IIU2hUJ-{<^GERf7f< zF*Bx0dG79TRH(Jb(Rkt50-0ue^>F4!ni7VfJ*8WeJ1cA%zn7Jf{Wc09M#!8x_vh&; zrUaD1(3f#-J!oTVyYl0gQKn=n&kop*MB$gw);=t|DUDl!oG>yo(}P3N~UoS_x zyH{Shaz#hjrsH@;TACSTY!6B?6AC2>UTChOqsh8Z{eLUj9ZPcNx(+age7^@+`m}}< z(haX&y9V@PU2^Eo9i4^?Xcy5?f%QlG4UyUVgDukofb*a_00s^bc!FPpT^oImDOx`$ zzFV4`A@DOcGTP0Adx5+QcL>0jmKY=U5(r3NYL9-72~Fwg*tB(^xBwdj8h(zmMzZ_w zC_b0w?s5r;RMaLC#>tEN6Rt{Rj9SkGS!clG0$8 z=~(~;$wxvF|9{Zvh+xq%KtH%BfNZ9xLxCX@qVV?D+S>ZdA3=>scKemAoSYy4|Kf*2 zTH)WZW4ttJSKNXE0df?;f4FbB+!Q38>?RDo77)xtk`p8@=D#Ov%S% zA+57i>J>vtKJktHl^e3&;?l6eDJ5x?eq(+)ae&VH@Cx;F3b*ttfkOR(HAiml=)4f% z@%|3;fOn4Yl>d?L+FO#LI!#O zt5spfyMI^dnjfYlD570T?Q)sNfm622(JiAu22u08Dby>q9OL zY!mbaCdg^SJ4qmvGEJld(Lma=T;^S@8p!c!iKO`x;5Ag0l}Ypl=B5e$H<(xsDJlbK zu6jTS;wR$C!l_AsHAssc;7jP^0Xy~vEwKL- z;p62+Hv1hnMYQ4{KQ`>|L?;3D>C_amTSkY{GUXoNmWG6eBESLDU6HnU29t6Cbwz&w zLJf|Lj1Z@fhvg@72Vujm6Un?wN{0p0g1*4n8DnbXF|w*wB&Zh$ehFFk`o8ZIZimNc z3}z^%19)Xz2?s<9TBBYZ%9aS79nZ*&OC2b86ql3~AVFdvvy_2F*=<66s^Tr1(d_PUD3oC!EKJQ_bCcztPnQ291 z&`T-CH8!_0WPxDd`F>@a|U zNbdFTuNWpT5(p%biM~GtfNdkgSP|t? zvIAV+5a@xu0;vQ$^HLF|3xB{EUC@f^E7V=&+Y=ivpQ;TMy<}{?H?Vmw@p7FpXUw<;HRpq^ z_3z|Iiuakgey({pE=rlNK<-~-q5oFPS6&!$V+fCLaEnL${&V*h26_pz0%XMuD!g7` z8!au}efaQUarSz|LI09~{ekj~M%0+fHq8TB_o2C>vOW_!_4KKjsv+*By*;1Ojw0gpO0u>6;CO3jmoCUJFj6(cesQ`=_KGz&^Kq}W_?=$xfEI}Qcr=a*}0Z1KN* z8po12Ev6+pTJ#ec0ecz>8Hd4lRqDL!a8#6)k+AE+@{E^TAz~WM|V<{{C9td@>i*H(s8Hd<%*A_P4qLSRDv~Fr>F5SOBxjF4IDQOYyD#$d!KpvgWD)I$`^WR>hu(M7BzEDKtLk zg|ufTCMsko{>F~sDIz7sV&c*PK`N&IgdZ=T+J~$QY=7W(5%X$nW(N1of5wkx>NMkl zPNJsbJSoabi$n?>x?um1T*6F<>WK&64J-}EKY~Rd)ooc&hvpES7IqYX*`Ui&^^*?v z^D!|50z~QH{w$?9@mFx(nrB~YZtghqN6TmApAusODWCXjJQ^VZa6ci0ii`kn_yyw% z0-?hJ2wq@^gP)5FK8Eu{wFO{|s!B=_FhVXd|NcE656{~F27eVAyVQWhLWRaGqy?cK z77?7G5@XoAFvG#d-X8v^AheO4K}m1Vrv3deo9|lQ{O4t&M1(mbd->ygP7DW(#6BS= zUPWg6zP_n#14=9djIJuTC6pi9_w7RF0^dS{(gQkAe%d0p{kLn4OX$MOK3Q(9)BiAX zX050!)S=?@VLLJ|{V{=v^|Raa%obRToLvPU?fJ5FCJsFo^g7rP(G9JHXh4K+Z~qiz zIiU|606Y(F5YWV)fy;&+mi#ntZcMYoNk|}oVfnK@*^3FW9(cOmz6GdVVKDj-nz72N zDntf$ZLGh?u1zXCnAaqoAw>Z)i}}cGNqWaS!f_OP$bvV-V}#QcW)hOYawDt0-q+9X zBO2uADA$1=AF6)v8-+Jr^k;0k7?36w1U3-Q8D@UtB*XZ1Tz_=De~?O|qPayv0?gD+ zfkwc}B0pJmPmgiY>%$P|Vjz>95Fd{XHx=2^(4ZoYg^GYl)N&#s(Svi)PDx5g2xx?i zAg~z6IX2|Alxqq*c09duEKN@ou`>6exuraD9`EMmRf{TAN0_9JgPNC?2shwm^wS8HOl?En`TF_+FFt**E5-q~=>{Jj9kaxg5-SO7Gv9-rf^JW$K2Pu2nt8zT z5Z6*-lBHh1qtAt_!H38%4Jo=g6tDL1=9x_d>>ANFoYylGS(iTVk4Meub-N{=-{QiDOU15%|)AULTRbx$5<8(cGPi=5#Q@&-rjSi ziRb!6gZz_Tmx#%mBYe=3eE}c<>>1a)8!K^70^@?``OwXv1SI!g8X*h$V&0gy+#6Qe*J~{jc<{BJg9~^Qg3i#_D;Ku)fpWp_|YZ%wSProg>5Z z8;lNU<&}5-U%H-}pKCAXFFG@n4scO%j z(_X4Y#45w;=#OW_3~SySs&!kw^&x#AcC;XfYDdfT;NinV5A86le%G!)*_Wx9yLsT- z`Gez(G}!{zZ-23t06`ujNfwIxZ5jAO=?pVzxW667h;PMQS#|Z?iZ-38F7f)@J)K+4 z>~8CG$P4x-SdJfD5PWSD-dSvJ07$(ae~ES zzWOUZ)o1C%SdMsN%eqy`3GkO*Y_(B|&Jo20Pz z9UFGu^ESeS7qR2728ty6RMpxbSZeXAJzsr=j7vRF+}}iPNptu1?nDlL%7)fUHkTJS zX?cd#GnjB(WZ-je{l0c%L*k7F@Z`x#^=s!h9y!H)EI#$O{C6x3O|9;pJ!I$Jz#bM+of$Yg;_GZBhI)73 z;0-w5R|=iSQoMd$I|xy8{&XdAWIgbZRL7G?k1|J_OM(}P&KiPz&NI}cPt2U`{zKOF z^EG3=Xp5s0uoaMRnKsTj`l&>CxMNGe?MpWI1>+|9jV>)_i~P1T&t@7pJ$~!W4G&L3 zW#i^-$->|JrmL8!Sy<8_!d?9Y90Z$Y7{wL>6qqD9wr12Cz#*Sz54!C%MoJYAR+wlo z(n49yiVKPa-BR{sbLj!juKCvOYl`&6##?+KOQe{ za})7ld*Iwi6)M%CYxJUhS1o*je*-xlM)Z)fP0X z*OAen`^pu%A)urj5-pIuiNIColT4f8)g4zN{bob?utGIMHvv-)dBxW_%EIP7( zlsa_7y6v&dZ=&T2MX|-fC)a7LBDs&A;dM#*{XX_7Atfee>+am-gPSNcJ@dZuUT~#T z>5<-6S;J}*Kdv4d&5x8Xm*y$pkvDJ70YWAxK*Il|TMwnl5w`;<4|Q}1#Sek`0T^1r zHurK4$H}gfO9-n9I&lJpBTx&7lm+CS!4**Nqh97tL+20qEjU4_Zh=}sICt|W)&&Zm zE3K`l@g9(1dwz|OWt3L<#z{7^$dY6uV3hOSnVF)&xsLXBR{p`t?PLTfnxWqy=^Jqv zpn~QX5C9KW^6?UiUsSw2JPkVXQi|5Q^y^nFOnR8jeg zGiEsw0yX8^4=|6Bf{^tzE+L`pqQb6SPm$M2DAB0*8F)}SseAeyn_s%Bib`$$n#`UG zySF=^uen+69j}DU(!(X4wpn3l@;Qgi!w~A*XzQ|1tk}B1v`i5QV!C0o5jvjS+IQX`sdn1J%ap#&z^EV_}`~-Xm369;tg9cm- zrm>);li;~EM1O>uGclk4-(gOIFlcZMjd1A1Eow-bAUSDiBLw0igl)ehj_v|Lshaf& zXU6ix;Fcwfx6}T$d=mj7v%evq$E?_P1Z68LTZ?9}K1f2}XNxZYxaO$h6Tl^)m}*^# zyFtr1In7{v3zYta`S}b+r~bDRm}C%^G)kst@3Rm*Rv9od1QxA4r4YI6y^;9<~bt-DVpfKR*ma za<^9R3Y;?l6oR-zIE;04`bcBK_WqmtcIchv&GvE(7Xuz}_O?rgp`O`$^cIi|DHK1% zWB&|#A9Rkhzag(q71*_jFgrIl_x5c%8jo{@0? zTAkCUJD~i99R-+Sv~ON~KP~pp3l|W@0?jcBb2{u`23K52W6Y2hi3j&{hz3GBq3Z4a zI_(Wv^wX}>I~J0M@83sn8xCbJvQVI}19(5R!|aL!7yWH~HUwDAgv>EvpdQ}&P4pGp z2IA*_HcrmhZ{JcM`wHQyw3L+dU5&Zc<01OdduKrBar5$)r5T=Cs<}Wp68bpwhnP(K zg}>I#ICV{QT)qvw6L)U8oKaNTohqgrLhH=P*3Z{8=`pJABKtJ6g*Y(h6(-M`o{+d# zqO@D1L_)uSeu+tt-|lcGEx3m7y{l~IGR>t%+2T2oT#iu@e|(;Crp#mUSXhjuUhJc= zLlmc4=&A>JhE3-X>oB5-;oyG;wKoD`vYm7aVak`~o5`S%;EJKdfKLFL{<0}s5#};xgWcR-L*z+DfKWS6Gwfy!V)8oItRlhuDmN<$=svWVXP{%KZ1q1lC;x~0q4UPSKc z#Ee*`h_Hy?+QSR~9xovX!Vma4;O>||#uXMpri&!!{1rq!5u0?+>Xm{2Iaz*yCq&8= za2fK{04hN>oU#|j7fASF-9d$c7j&-}kEiKc3_giGIx6|t|BJXdlEvY(6$1qc<2|2+ zJdmOC<+U}W0(v5NfSI{S)nAZ6*kVFo%k>ob;&6yV_zk?LFNfsS1ZqIa07Aq`q{yq( zAQUXH)^O`5k1*Y{w$+L=g|JCfObjzbKwG#!D4?S;^oV5;GAatPQ}62RtE+@i;9Q`t zb**!`MeN5K{{%h_q946V16{VuwE%fZmf4ZV54MhXJkhJ2edn5PC%pQE$}4JR_cM_w zvq6~aZWSdzu6M{jFD%Z*Tk|!^elMkmYC@`lu(AC}x;4`|0nf=(yVr+H_IEe(F%ppk zu>c3xxpOe(z|R4kjfw#Ga5#)V7z3c?R8#p+?JP-6VfEt#YRG5UBEdfr2uc-OKx!2C z>S2~%=cku1k;_nsX^~H!oJPTUY4bh`=no)8y7?X_DT?az=aKtHdhw=mxImqOgZ{!@ zHzY+r18{~J!?VAkg%3utjRF})fQIU7;jAjm1b7M7ccb{vuf3(_h$InN%tP!kW-(C3 z7t&J3K+k{a5;w4RJm(aI5`U5ZqGDcx_QWR?&hmeamgxRxw1m}3>^#o2{~=m}>fF8} zuOqX*r2JaY{ct4z6*A_$(d-}xxU=0sPE|pHjh3?MSb>tX;UQUqGv=ybL%2Cng3KE* zF#yI1eU^R!5dEQ105L&MKn9F)fYj)o$$QyWq(u6W$vC0{LNs7&0UZSdQbad|5A7p7 zD*enzVfGHm{O5ug^XMMZ?xvJr{M|bDZ9?vH4SPUxO0CF7W!)hAM;lO4SFc>zBa|T{ zW#vb2usB^CNEz%WbDa3iI`!$OF){fgy;F^VTUlvE|CmW!!vyU`3*{Mu+|Js5|3>=I zMIWsP&cgkO2Ll_giUtCP891?kHjxuR50YJp%-Bor7bEyz(9rbOYY<06ebNoS6sT_# zC6n}~ZFb|IBruXK?IRyIH~1X9KL7XyuuWf2ZzS>Hb}%5=FvGR9Wn>m{sKOFN9^Ho^ z1-XkmKH7_K*|JMb4H1KGU@`&!-ucAyKg^0KtGXcwfy+SbEE(Z{jtCbI01E(>%fggyTld!XRn$EbDP64%b$FRWJ;&ywrvE%UGVScyC>l#J2v*w33Y!eK zz6q@sJz?m7GHp|XOpcsm?d`%y4P$yI4sL{WJqlm?e%ys$tu*?4t8WZrw)Gk7N58F^ zB4bNd(nh}Xq=aSQVasTO0>I^$#n zH9pODnW@Z=HP7FCEIr3im48@h)u5Wp;HCV@2MIgxNt*{(PTk>e8RTJXB+xT3U=srW zgy@GY8HSK*SP$))VAb@HM^H!?GA*PmuhInKfro7;%Vcz~VO?U8V*`IEfA^5H`KR3~ zdGs4~P?wFwZt3+ZJ7grzeyKqiZ2OCzVMWL2ETz=EGO=N^y;pO29oYt$!$wBrorz<< zg-x8a*)vH}uT+&sA6yq|+;pvzV)KPn`dL(^e?`;$A&pgm-08)EUgYP5#kLU$kToqz zXLr*W&DmV@EByZOJ92A`?7adzFvE%ctf2aFy$>@W^J$z)<7K{Mfuzsv;(by@) zocG$@V3A1l95>%)$6ysL<&|kJxcOd##{*)lriase%X1HFC+Sl9L>S|0Z^>A*GkDr{ zNQV88c|OT6Wt~t-HnG>|RZOdeoKc0lS1h!%^T9em3i;K#j?cFVQn&U$vD_`d+P;gt z_u~Tsizjp@7t~#%B_PJATHr$>zHY&axJCfA0mpr%#Fa{rA-L|3{9p#*l zY_jFC=e+`399nmNj#v}C7JINVDNqfp$G^a=b&Lrg4@rcXRkM>f(97Dk5HTp+o`=Eb zf3fu?&{Xbk+mCt9m@#AKsBH|HXEKG9p%6kUgp!bXE;3if425H;XjG<3sO(Zi5>li@ z6O#C@eg5CO*89HSXPtG{Ivv^evwy>VU-vaUNWb~X;Au%(vvkMA+#ac^{F5D@h)MMXv;`>FH3D4a@H-5oaz5#V5q?cA>~-=w5@=Uw*Y^2Y+Kn<9iY z;{Stu_Ii*bN-Jj(CL{HwW*b~ZE-)*fvStM+9Jb<2**3mf!#PYpcPe5&x2Y2QMH z#riF(n3uuOJcM$WxTKdw(#jAXpd~dORoj^%w0-NgZMJHrRJcU9Z-2jjZAu0DpaRy8 zCmxcuE=A{dBxu;9A(abm^c`9+vyWu5X94FFt?0TcX}! z%cZ5m8v~-0^!-0aG<|tWxLq}!UB)Dm61ubgr){0)v{Oy+jp5`OKmI52)iH;*nioja z(28Ao!s@e2?3w@JjQxJ>egP)I^fbx)89*6tpLk^wsKRfa-W;mOkG9jizpUm$@3lwg z&XWKB7V^u`;fiVqW2&2CE>orJ5HlM;_%vQwNDP5T?U-cGp}LB!{i5+VyzgZo!v__O4rI5uXqG z1@ywe0lRUi-u3dvhUPay3_e$`A`dtKe}-VG2A1fEiybi)7g^Sq{<+@*XItpeI<(AD zXCf7|*2!9GE}xm!{fyw&3u8Cb-mo2H_3{&V>5Reexg^VZ=H)l<){>49=KH7|kGm|1 zUN2+Wx!r@WUJ>T9SNItELG^7SJV8g4_hQB>` z9rI4+$|>)6xSEgz7d~j0ts#ztEfKIud_ne!FUU~X1XURcyWd=9?vqb;wxV-Q+=lF| z{cBv6QhwjaJgt#UBLN%P&V=q~^ia6j%eZn4bBMU$jwZKu4)ZlXd!)x+2mMqd0QL73 zsUkOx=YV+aYfv4$+$nYWfW?nRyC#g}7T_j{vh71(LHEOlsNgAHrwC3GQaPA0$aF4( zA6zdGlwg{mHm|3pHS+3JUQ_&=SFe8IuMzD4yb!Q0m(zoO>|eqLM7bBZU&%3wBmt2C zC&<31c4?V*=J!iE@LYjPx4d$l|HcHGYWs3c3Ux5kf;70E;oL%oDvwI@T*OX_VnXA3MU1;d6?q8 zg)JvIXgD8qOZC9J@>8rtP0PSwW@?HzLka8Ny$0{fLbZT=wBb294wjb8v(tb`AQy(R z7;VqvSOLzBo82IB0Y%l^=q6ZEgS^?7z1ZmyUd8`#M(^YtFbyDm(Q3tBBfpp{hq_AW92RZ_@3CEGg=c5Y` zLcjzkwM)>qtky{9c?Ji6L;dBk2h*g>6Zwby{yQ#D^EwyfrT^_0Q5l!$MZvEiMGOgf z1B2aigZ~NeE2VkFh5}KBnr#fnC%%t@F}uKC8rvGi5y*^4TMff_JE*Rt*1+Gt23%(( zGw;drlg7v~8>3cVfSWg#5rsLvi1OaIO)+5{f<` zqBWIEh~5S-1+X0z0n(H=#E*#T`S1)mc@%E-+P;=U8%Jq23sav(M{){06KCgpIJ+no z857nYJ^-vo$I48k{7;JXI#Ptu&!$EQp-9D0%OZK5+2A+7vKuEYAr?U8_bWw7UY&6$ zVkoO{}SUtqVrDGkJLyZL4n+%=oIjdxz&bC-u{WYfBFP zox}l}6PE3HG1^?_SO2+kMPGzzCbwOOi!4{3-J(C91?!+yic)|T)^?Iy6z&z8SKt-P zW^hN@+ZrB>vKYJ#fa4T$@c(Ow{90L8cMVD)%srz2%-zKLE4PzHuMRjA^4&VvN8&jn z1+lJU4E~UKI={hSZVUg``R2_IS=kvpC78dsfZ8>t@V^lD>Q7AoosjPW`+|cY0b)h- zZrh*1zgc)&Cq5)7SdmXIo6|!fGy27b3gPg=pV?XU;h3ZlOMsW+%m+~YUJ+;^J{lY! z=wTtQUb_L%(%0J?e1-0zp%aigFG#BnBYGOxI{p^gH+?bd5f6C2U{j*!)`r*;yEymv z>gmM>ZQbg+zoqAUyz_LfnMv47q=@C09XGjR>gSkHnUZZka*5Vt;}Mg4uk!O>)}4U? zZ%e+@5sTf4gM#}lylW0i{Ly_gpE*$S?o;vIqT3<9$`jFgy1Ls>Jky!hoF3cpBeMTG zfbq=`6C;=bppI6^$Bdgdx0ktg;l1(g51#2rPrgghwYhkzfv z&)(*G;|m%a@O3~fe?$4c^MtM$XhR=*^KjTB67CmN$+=SdAiQyQ9tK=+616#c&vJ@q zNl{5jG)9r|aWU3~djf^j0YW|)K5%DuJ*6>6f2c(Z!!>2)YnLt^0DC@#racdCE{G<< zm_S%3A`~z=U=q-iyE;1yt1IqFg9sCH`0y9pLP%0=!pno%jw=`;mKZ`%Gz^N=%S&gZ zBkKWGZ{2q%6t9kS1r!m1$VA7q0&(|694u(VTTYdL*NPT- z;^GyjI!q+^g@xG&j|tXD za&sKs9QaRosYv`ebWyjkS;xRqxZG>>cB0d+vRCnmCXtb=po*iJ!pcU9(U-4Z&+2xz zsb*Qme&%g8Ij|B@K9}Xs8M@ole+$RJ1~b>_LjP+E+U&OG%t|q%6ml^j9F6Vz4aP8S zOyOU+AsIBLTs+#WG0&&h^iSnlAno0#n1P_~vD<63sowTQ2ij#SF(OIXDORd_WWE|+ zLi!T1w`e7}61eP3xGm#-3rK}H>%F~i-M&qk7bC_NT{*DiWKnqU2Y`c1!~j1AmloLr zvv_luz)KzF^K}Q&&gUL^6(o4HOnu(UxB3c!@8{>MLu-LK0*oy0{dl$` zTvbOCH=LoNA-c_KtMikyv-pXQI9P!sH3wYT0@!00+|iHEx!})G5Sf^nZHD>Y{pCbV zKP@aQFfg#M!6E(<0+do>71IIW^Ry0;1cBusR?vq57@lla3A1=XALbyqU3`6fT7Zy3 zjar_GmxjSMLBMUC5~wGG??(C=B=d;o8on;WYTjw^ModjD3^YZ|nRp%w_rMcj5Hl?> zBGDv)jt9A!{>>y@m0t!fQ*taNa(Vz%X&;+HF7+a_JL7^eLlM>R0jn((z7=R~}blzQ$;Asjn9#9xR3#@kZbBshx zAa~-)7wXHf{^{%MD^PI8>md$;dX9+$7V|N@7g09gAfvF(@y3wbcXO6Z?Vf`bnn95x zL8W;gAsdiXAc7V*6~-gH_d8?8Ej&75JB3V&d3g1MV-2XkoR9Z@rB&S$%!rPE9;Adt zUk*#jGJPsbDSCg!k(?_|)CZIg^kk380?*r0+?_i4D>~^lL69Qkv zIw84~nxJ&+cx`gtRqObrk5Wf&QI82V1if#Vi1X#E(s}gB64y0IB8VUYdE#P8$%X(0 z@@#Lbk{?-Ygw7e0_?{1~O97nR1N%?jqHexvIs{fM(|~X#KO5+13`-Fx>wJt^QO}%v zPJzXnP2+LO6hH9dE0hb5Nz7*A7cv!M==6R%(B`|z>ZXP5o48===}_i7Wl^W)Jh^1; zskd9&bxLZ`NWN~9rTua0XgaLZW52S2HwS>V1d+F)>@l-~35f26V-AWD!}6K2dpop; z;i-}dK!$Qa;++e&Y=e!Byu9Jn%Rt?PwL-_mg+?}AyK&=Drhj^6R@s#+j|T=Ewia~h zLB~odMKW8a)7L0^)hkzG=)XEqeg6@wf60D|mbl_ri%NJ2Cke)yFkM1b0;zKC4q4|| z7zDetLyKKr@3g8NcRU`f`;ieB7?cn*M8S2;9k4M#D!2m^CU6oTjfJqIUAX0RHOZT zO_Kj+UiqgA&JMp~kBd>g-03IfNqzsN_N-=mo`H^^8K?e9*_-t0&1VT0S0bo=fR0=CDO3EBTfKPQ|>?DH#FS0;!ntb{6$=SsvEkbt77L_Xt_Hxgy z(O99JiTnDIh(YoQ59bvf_n()sOwgLx*qjaeKAVKo2V`%Nzp2JmkC_N_3k#&fKEXYX z52gG~!#LGnFb%G^v?K=85k#o|ITf%-z$pMN0iP8`_cSMnj)GNGcax4Lv~WDWDxEd{ z$xUw{VH_S74-ts2Xn77&a>?#Fsi^7V6F9t~b8^N(9roGDNYWf{6h5*}HI56m&6WRQ zCeFXPxsBphW%h@u`RY{z1BKjMf|1r_rB)V9+JZVj$aY6i*!Qm-_nj0xT<&2(;^6ec zy@uarKeT}Z9{^BV*xJIa26kidYvx4`3qOAvF9{P_rKR&9K0N%*>~Ii{7nBTP!1lOb zI_%w#2%?bBeR}YSqVYnjspRhvS^*tpIz(&xu11kw z#&7#W&Fx9QEm$n5M?0MFMTB9jg@e!8`8<+tMjI)zJ5@o@E%>(!F1$XY9z8>{m`SlY z$UI^)D5J=3kt8KzWY_Q^Ql0j;T2Vz-YmCq2RDa1yU9%Okq7>@NHS81#l6Wy}(V7ry#=5e+#=0o4m!PI4>^@+#RAF zqdL?Ikq8z&W9s1G5CTi9nVi1^wt5{G&t14+Im~EgSL0~C9>djE#|^m6;tORy0DuS8 za-hHeZFpp%=q%$k+~L03iPfRtdgGt6GW~id_q)g0=tBh=@VP^O^SFtIc#X746nsd< zNn#VKwkb~Aj>BjXB~Mrw9Wg$(*g1)%PElG@Of)>jSB`ajcmgx=$B*sg^U$Q?i(FZ8 zFA1eSh*3b{?PPhdi(!D?xm$-hv=}w`0Oe7j_yJx7z+FySI;p10Q66p5Ze05?*1$Tb zxK{~kJAT&D!-o@WHpFd~lzcEetO=e>l|AY@rm7Xqu-TU^+ggdRVH~EA7$8Ju=wBCf zW|v2(FaUqxmVBm(t_Fps4nP=je8o>}Q_k2Sw^C3u09-86b& z)W~)y;LP#N@e5fBjW#!9wD(fa^JZSHrZu5uV0gbub+iXLUw?`w6#$fc*3y~ zWgUvBg$fk$l;mX$R8gq|qPPd)rm@6t_|>AuK#7ig3B-Twfl`^^*NONE?-oGbXpa$3 zLUH0tHJ+TFzKLEJkQE9TiY>j>)*)OlEh`Kw%d0rcx2UKLz+4T3OogZ3%ES03NKpZM zftR)f>etfep-g{NblB-*$h(@*9fW8z>r5vjo-ys$mm7$bvuDvX1?lVS<1UlkaF!y# zse1(tsvt$0u${z(z+w~W9PHD?TD}?6UUGj0%Vwsx7F7N`y)?Ot}#d15DA4) zNn|U10aJ2r?jGnd&3z4Q`!3%AU1r<1Mzjb&KMw^0m{zcPgvEwV19r>Un_no=>38)y zF+9P{^*)+S%yxXB&i39?Ddeq;0~%i!AUg%3T5;*pc=lw2Ur;@K1V2qqa-k$uF;H~7 z)r5V6B@S(*WbP51z#y8%R_!s(;18aDCY=8$p>ZRN-=29ewD3)TzxRP^h?^WQ_edC- zerM03>n!EGI$ab8iIa=V2n_rHGeJ#%5kF90k9l!VI9etUCt?1MUpU4W1MQQ@-ry}6 zPAcoqmt14(YBoEnu}5lC?(=fb@>{p~1$dX~IJmcN@XaE8ILka^$)yQ7GG!Bf55-zH ziIYeRz(g@bYpkn#)8t7ba*mZ~7og55it#ik7UBa23?*$- z#MloPIkfoNl9H8biCsmYCpV!J)G%zdgV#xGCkqT`Cz_9e#q`?nZ2jGhKpcjm>=p9Z%|3UR$7AFmE+w%Y)Fl|OEovAlV zeH>&==(&p??x|IzUV5r8!*+AMx0$JwGzj_H!E17q?fov4H4H8cvdU-7W(=}!nWx1>=O2kQ?_8wZt!7h7&niIsGV z{VSQNJ~AFEap03c>f1YqsW|%gwfpc4HpS5BXg7bn0N>hkq!iLV%xHiHR<~3w^PxHf zJCF7APehDx-}jJ~m7y~`yXo7X?HY9g{A?hdt>g3r>O~2?MehuwMK}Uc6h!rkL+@ne zSvQ%Fp#`Ls7}O7zycl zo?=rodI5w!osaY)pOodg`=YDnL)p&&o+Kj29M*&+AMHB1xk*3KAe)?h(a$2wl4u_K z8ND%m9eJ0hsgd=F4hOS_sGg0CMA;HA(X*wj&a8B8p8?01vPi5zQM&XU$yAc2Sb-#` zgmJTG;kBJy+#37xGUl(-nkDF(0~iK6$wvyPwNV~VCuUw;JmlW#rI5x)D|kU!;;Rqs zK1dJAeJLmCRC$}iKV^A;QIlcRGcIa{8HFDz3`HfTj z?vi{uJygZc#FoyAIcloMA2Kg0KK;E%M%F~=wq!GFIqDzCu_|m>V+XY!Jb3yuxkO7M z`t~`+ji$uFAtAG?ytDgR_}?AYB3rmn)`DhAf zu}1IPLnl46?jX#|y9gSR;f<`4lCuR~6~ZP#9|&8w_>X6|G48)ud9xkh%BW;cu#w+(WK`XEQ@tI#%!IxEOk;0In!Lty z3Fl44hSUB5(@c!7+syex9|3ronxCJanJGMfp5iNuRSMTFP*y1C7!au>5gjqHm=n>V zoN?pm)2^Y5S-S->C$7AZ(9l(Qry%ZXlc3-sI5eaE1yK;1*ZfuxTR%oFbTAMxXgKU^ zBOGv!ZQ|rCzx>*iet_kL{I;`}Re;Hk9Y0>8?2~3%fzD(P@NkM<3EumxGo$V6xT28%gI%Yfhcf9c`VMVgP3W6mtV~u$Mvt~daDJ+Vw{P2)Y4;r%1=1nUHGLb11)Uy1#o({v z^z`(2OLc;%{j$1Z5b_P&gx#nAe!1R{;T7CXZo_k&0({|MhgugPAx_fO=6leBf9umL(93L$tAA<^1~k_7uYFRuf{$ z)8dizv2_m1{Y}BW+sM_f4>Qp#*~QY0{8J-2{=~{wE+&Syte&>ffqt*_92*-aKfj-^ zZ?btOisme-ay0bK`Ly3%X{LAX2vGI0`I~)Bn%)E+JL-DRlg8QQb1sQ*p1#7xX(e+6EMOKDubdDj|(=wlq9xkVyR{+lQ+umq@_2ebQ#D`0QhE-W zcQToShv&h|n7{cjc!5E|Yg;H|pFDj^MWB4fB4uXx7dWfMufbUA8BV$Ed_Xsd^{E>n$WgwMVw)RMJK+(0p;_ex08`jalVhp$UvS0QZ{a z(~fqP9Otni+c1|H7hiPb02ijVVKw2?Bc(jra-EvGXsfZ32g+TcA{OTMQAG~&oAL5I0hSs?xD&2W&{w|G9`@Ei^gzx8{}d02s3RMhSJ`XGz7&Gb15DLL zbs|)el@6gNemG!;_IyO$U;-nGcs}siVX2In5o7=6e&+mLCCWu`^3&GdL?9UN9x~<% z^(4V(0|cY~8qx|Bq8>_W{PGM!r*S#}0FJF41JH?H4UAW1!4#cTb0Q%F@P#K$dUB1w76&kL-{*i z$Buo+Xzf2!J4(bUOe=fcpz&P>R}cx=NRbZ&*&c-n3P9vFc~bIwyu9)(VVqfsmIK8p z+R5@?{^+LgkX(U6M!v>534)Vp_~C$nbhm6snY6qgbAZ_Z(ld_K+$hgrvs_A|-~79G zU{`8uuVOIldd-_jyV1S|5UU5?Eu_aXhR$qrN96`Q?-(>+iiYtc?0Mi{w5@Gb`Fp+% zXuXV#n50E~uD^-TB?$WLe3PVYDL1la9+uzpG5-jB5^1Xxds5Q@P0HsPe(QL0E(1Jf z!xr{q#tGbT8xez@RPT2CJKn>Bx}x*7DKK(lyD@+<+iD?s^9!Cn>O}zekn%)B8_?0V zFWYZkcp$^CZ7_(!69Qix&jp)+S3UDGQ{13gN>8wP&<8OXdu&%|cQn8C$jCKuk4$C_ z908P{^V3S74pu!O$<-Hh#dqc?a_ctKDPW;U0;Iv(58q3zNdEIoQ%<(8~YFaVe5>Q|)p$UUr(+c1d*N{1}NeeCkzya+l z5mgEBDjba1Rm=}yD+oT?ab%Fm$uS)V3XYi(o*qhWbUs&f_yA>wi>e7e#gZThiut=~ z#jd(n$bW!QeGP={nC9b5hDOBWI%Yxhu!9moc2*Q+R=1259=~&!z5Ri}!1Y&q+!1Ss zGX9cGP8>d!uG_$|f!CW>JO@CFZjn+PSXO<<&;w@_;6wGI6t}JG2&qFmi1&R~I<7HE zU3Q@S9ySJrxQXEqz&@x9vHMF&p45^20MBriUv`uSCIL%F&{Q5>dptu|&Y1daU`$!| z2LeUQp8KK5KwUvG@J|Gbh(dflp1e#`{oD^UFFQ9kSVB=O_a`Uq-Q63X`|1AuIe_)l zxrk#z5N(yVZqPUpS-}+O4Ch}=H(wqK1F!;%E!EdXk3;7R4;uezNh(RehY3LPGF&+t zA`J|v2KF7KihK^)j$t{-$>75u#p#Y;7ijgrXBy0Apc2L7{0klG7PeH7T`*L@7YvIZ ztcX5%_|RF1Z+T{ca#$m`+68?(fL*M@428_`nYVW-XeY9{xcK9y?0t72Sfjh3vfRQLO~yRI*gBV2nt$;PXOw7 z-oO98cMo(l>fVpDzp$ca|L91a9-ZypZBm@^wo!-8E68gr4%)MWQ=Q3Wm4VE>2#6gW+ z27k54$Vl^pp4arxE+?gX(X-xHwW?0V#n3f=FwN6IW`^fm507)X3^ff6l2GjSc2c(e zUPFYFAGIKhD59X2zxae5+;a54M z8s{^n6B9Uj64=>&RXR2^u+DC(`mAELw&3Tg_Phlw841s2K5cDn@;3@!AB6_ygCO(Z z^x0r5(;bKU8Wez;9LqSk1VVU=aJluL(4Qa_S=)5$5J*9|p1??MHS@o#zh=(iXAK?G zMBLQ$^y$T6-`I76u(P+Pep7bWdGB6xXHXxKFtew4_SHedfamb?keV*7F0&%43<|!u z$`n0MVIjr-JE3V>9MGAg3AU?x- z?sK;;z%hl1ed-v70-8mPG7F!`V`475Kw}^uxP$58-o3DQ0?^9XvpLW5+mjW1z#H;i zDRie9Sw;fEJ8}1L*J6GWjoza9-h?|J9L0b=mu6;Wg3AY-cw&fdLh;R=usV#=a2led zA}3MP_T8%}=KM3{g8u|r0x1Bmu*@(PLcfvito?92!;AjTl_>DoaO)+y(vxnTAN`a* zsFO<9Z2ze;RDxYJl!Q1L6nLP}8)e&}uQ^bFENwcAP9Sp@tG9w=M1eu1$#Bihc?e$E zZb42y@O&kL)3WnY+qJ2Y7rGX=7*}8VEZ%@{}L>6GH7>v)4{$U`!V>}%HwK_AC z-KTz>8ZwKHI#|VHOd^d3F21m9+>8fxG6pgqrl-5~zMbmU;f{vX*`XQ4QK=3>#4z7ZwyC&2`Hc#UJ0lk6ib)1;0b4G*UTWP{BAg_UqEw9|4O0 zdydqjFv6?xOL3F-WTAiTwQ6btDld;gM``-b^I!5fas_s+O^s3|Hkx{PjH6J%%WM=8 z8H0Ju{5<9A?Rf3OpI;Uw-ZQEHo_(Tnfx|PDX>N|Ah=1YupR;Lcm%J}XOo>8DR)6BFs9eJ-5$_g20neBzmvgdoCCl%2AAmD0DXzK1p&fCF|`HG)OD}WrQ@da@drQS%lr4&(Yiv5 zjY%jx7R9u*1fz2=T!@$(QTsRIMg!yO$Q=$tyGCR|o&t*tL)f#=fKOLp&;w2jx@#Qh zbOb^Q0#R&`f8VXH{s<-^*)C?Yu5L6s9CD%#&W#;Ag!V6^iZG5}0hErmHYPt*M6+j&RZ3dg9Y`V3D!@?{%_j;? z({N97^OWn?Ly&x9S#<||T?C0g9xE{kKl1NhzifSR5s>q{w$p6@&@oiUIz15-lmcsa z)TPf#_0R+8f>DdL+!_3<&1d|bsd&Eg(94(LvxR*f6(G>h%JJ*zQ+K)^2WbSU2bdMi z&O$eQ&VXwsdLE}ZZQ+V=?1xH=}FspJ|#M3v;{JB)~vlTXjTLPixMX-96+S zi9~55aVVkUp90Pv)bC+K=^;=~Chf0##6JLPJ5=7{5RVmD!cZ%n2-k#zF=G*11dz(C-6e7P~ z7vp1ei}VBn$%AphgE|4FMHB@+FVPwHdC!x*nvao+EeH@J_Ft~U>f9F>61rf7)t^G6 z1N~06Ib%xTFe)fi>Yvc@p!GvRCiMFN)!TVt+zX)Uq1eU*2g)dD`J5W}TWfF*B*aFy z%C(=i`)2(VCeXQRzfkZ|@LgBpi)-b`_4igk6ZGp&)6&zA-3q2@yo=$JWzF3uFU5WQ znx!#gSr8K!H;~;Pe5C$d4N0_Jp8WjiC6(PGWOwaIRDOJ+PbwqdkJPV?h!4=j@G`hd z{Y^H~8Bd~1(G1zoK$utQzfrPq)waoMeZEkyRAYQcBQ)yK@=l>2q0BqJPGH#U5 z>wWw7FIL%=#%)_XnB9=#;now)2rL}hY0&||__sn@o zg2)iwkv|~OD|Aay@WXdg(pp78FFD$waL`PWRhs!6i6C&lQ&ei5zHd}L%bq-ZNnvks zaEyQacpUc^bO%^Tv)-d5S$IsS!DZ>T+kJS^0Jnii@uEtKA;%`I&?}fb0wqxC+`H2L z@@w%YZhDtQSAAjX!L-@|U`K%#Id$fla{p z_4!Memp1w-2_44bT=a84j$9x$GvgKMKi?OpWT}uAaV$@kgko}N+_rV2+(7ng7= zLlU`xo|e0tVC|z$<-RKyFPd>XO8?KelFpfbMyDh#2_hIBfhC9UH+=<+i9a@@#n(Ckf< z{)QGoRkdB*In7!LQN*|+ip9A5_Lwkh6tr7!&wbSC?#x=6>3OMX!H`q1d{Q&y zChxbG29kJS&HDaZIj28qdF0T_73Dw?(YeRpvI2J)ZyQq zpReFdZ6d#I+q6|xpw&!G>{SK}p-JAX&;M9GVETPC1ELEpMuU3JC9jFg%CisjEO--M zlvhcKib}dP?U2@?BmX*y%X1hABXwr^#hgV4DpG}UU29Xd2|tJHt))HwE26{BL-XlH z69TjntN{GM{Q@Zn^Jmrn{F3b|hWxrKGZnBZr+It5`a6An8p)4bhDm792sbV5Lt4&_ z8$UoG@q}6{%;ZXB&QFDZUYU!I=NRtjeLV0MrvcE4Jq>PDtr_%Rx+e5*rrzvfY_pT5 z;pL_NoCe;bl!9gbz+2U<%p%UX{eH1RQsWLk5!qOwuv=lwx|tjjY?VS1yOFieZR@!h zncZP}KBM)^b;eVy{enTA`kl0l7gIUJI~o046JooQRFCe3<S z?U0u&jaEl9n~KeF?~*V=NQeim*^6Y2mN?awFTHxnQbZA zB2}lbgM2>DC7ocTvzf0(<%Wx9W?GtuHTzkSnUm!M-tWEgQwQyDThXhw_l}M>?(D7! z$^I^)eIu)gxq_4S6sZj;N{6n@mzT#0`xDVsCILH1_fQItsQ|k zho-B3ygf7fz>V0{48Mz%Ipo7axDr~_JjjTty*KIO{>`g3Md3)tzDNVVfbK~)#+{3u z2a8%jh&jm8to+#}=z=}Z@H@(v9_Ya^kpEA{7$7%8fC+%FU|2$kq0-jVTgP+>4I3a- zkX_tB+x)8MagKv2skD+mB#U3mI+m$Rn4_Oni*s) zS!bNLcvZ z!KZ?RKJ0Me*93DOa9oHw0U)##%o~svc%NE8(-96pjDx|BQWb0~wD4I)z}~iO-u(Xd zbjgnBRgJNAr0xOl`HiQ3c9SM*)$edR0&eqtaq(lDsiA(2BZ41W8d#HJ{5(0tFU@sU zDzH)?UA{`Y{e1=h1QdTO5tUT z05t`S_I9tpzK7Zu4K{Z*O>djn4&rG-5UC=7*R-}9`yFsR#ql>4^uV- z#sFfoUxWf%DJdDlaj+oATaZnni{y#i;kN!f_*5s@QRj3#F+&{D+r1oQ)y=4_uF=x? z;bv*tVw1ljp+)s8WVXtTK3XDU@;vAa~tg7DRnsGu5%6Z^LCW2LS<_mtTV zW`|SRu1P|?Vj9*Ak~Wqjhp7k;|KCd`YDILvCue>TIWcZre?`4)W>kj381YVzNn-Sa zFE8BgUR)3>{CHHhlSt8|@n-p;_A5*NvCp-S2YpVO?CWpP71l0pcqgAlof>$`w{5HN zw8Bb8Rq1resb|P;`Pb3{IN|tNQ${RR6!^g>P6Q4$2y1DAFM=dwq8&pA=+O=a1~x`{ zf&oksX&ic0i)I_1{J}QNl*|VB^HyP_;^$bQPW?Ps50?@AH2hHl8@OFM;NIg9w<^;3 zR#mXS_t~>(?0jr(SSo1xXqEn(TvT+FHJ`v0P(1w->tCEgWwXO?M>qE zgEPtw6rBKPxxN`wjw{-Bw+()OjQ{~FDkzk(+ebvKpnRz5=TK-jqj-Wf|2@ma&3$gS zCvYx>3!zLTAk__^%`Q5pww&2<~|brIuCg zqnn7ymdUvSAB~nV#w11&SN7&+fw)f5W;xm%mK-W38u4sB=Y_>PZ?_&-KXXPg?3cCX zNuS?|wrOc~g0mOX)9Rj9+6S=wSnam`{#8%A>4)NC1LYdY&ZZ<8pdt$cAhSLLKeBvt zNx05J=b#-r!*Mi{!UIGf2QUym{X#Ams0cv$-I!Zq#6fYchrtl;fRGnS@OEekd^d*4 zBme+h8}Jy0P7lmEW@W~o80TZ)4I&=Kus~j*j{s~Kf&HZ>XpQj$;Q^aoh%5gUc!a`U zj8x4Wwt;~ECVm8kMq2lZh`|wnJ=L^Rib6i=-%!Y7?IvJybTXGe36Iiy@8h1H=jsYs z@p9H|TgM<2IHyzI)Rd*88_UbH&+?6ou9DKZOX}h#w3+|JtQ#fLsKul@|BgML=>ID^ zoNGhcHbLKTrX2Z)EL2M382{buz$DWmA-XUw7zk-`__xuX6~QZ^TaJ zxmm{68APY=5lK=RXrfioU--y0Lq#%n_Ve7q!>eVoW+!Wmc6j3CDD72P&C_tvcaoAs zitlZZ-gffT+oOSdx_2z4i4+V0PheQSb9^E6&|$x;H%M)83?Ghbvpu!g0QM~epc7M5 z-be1~sjE9xJg1DoFgpdfxooC<{xBXW>Z03N$$$BE87q!p)=$aMY}k91TJ9YO%%zd37=Tfu1#2)s3J?{;!G0iO&YZCh2~p8rpJFnT zm)VCxaig$sG2~69rFu{=@symsXhslNq$m-sEi4d)NRgR2(SwYZ5?;;0%X5# z0v`%)BsC~Vf66_SCfGxN*(J}x{2tccm^j-^Fy%gK?kV;-;H0|AC%MFq^;vGsa_OzD z5AUC3@+o_p$0u2tFwnLI*u_P0Lg6&$0mj@E+p)ogm zbMs!}=$FZ2hLcO8U;i9XVsednedEX*1O`BbS11T(G3JFou-ZColm0WK-{SO-#~rLd z2OP!|Ok4?y|B_u$oZXe0norLwlHvac54BW!G`pIZn5FCG zfkI}S(r$3~4@*=Q#1E_lwy=S-L$I15$5ZwTJP`PRdJM;Saa)gGRm*RJFLe7)X8YF( znc-uSa-$kNV8r$~OwJ|q^0~qX7uy7m&b#l~&}GCGb(kgT z_+4cl&+*`mldSiQv>f-SN4L)V7Fw&d51nbv0hyxA(Zp&mpj42i&K|pDz$&Ev1bX>T zTmaR8o`UM!KQR!;%m zBhjhRQJ#)ZpTe;l(b8aHZ1+lIe}M{tb`vKZw^7c&)Fum0;A~B7795HbLCaCO&`xYT8F9v@h>zYoRZt{OVzTJ4SE!5Lr*&*_KSwMHwX}@PWp>@=vKBf{`UApP{v%thYB$hWsI(pnv9Z|z2^e)- z!b+|@b6l?Xqu5!hn@7KgXJ31Jwr#7`SyIet4WsWeED@p7 zD|b#mLV^tcrcKaHyo!m58O%4~7wZfH0}ys*&lW++K~bsxpYBlqjRb4%vBTh)cZNh= ziV7AP5ou+%hgc@CM4yvptu!kO4kgbvd$B4umaW!&j%4e$2U_th%|A+~w@H3@fauj<8DAw$?}a|x)wj!ROYK6 zw`OB0nLU2i;?d7L9iF#>tq06Isb!li1h4#C$0aZt#QIv-*VY<3J5c4D=E!l&I?xL( z*q(K4%{L4RBIz;t|KRKJ%JpUPCuz8j7o6T#N_)21r_iE#%jwgn_li(etM~TzQ}j&o z8T$TDLRmtoGoPsE?hKXhsCL-3p|?^aeQ%CrxXHBt^=eaND<4mms6QJH^6@uS@05^x z9&^+C9BqGL<>hp}`2egMmqf*x(x%<~EJhgNIyv!1n{F)thvDs;H?Hf?Otb^^d6Qs6 z331*tM0qd5hk>4NCzb;($(n_R^{9yY;nz4Q%Gk3@-XxDm(}{TIHqXi>G)$H+MwpVW z>z|5CDE{;3&kjvZ1lo2sC16xe=)+N~p8Z6?5t)p&0B8oq2n%Ba$AGTo?C~v6x;liJ ztb|6NY~Z>Z8*_t>3)?A$(M$6B*!F&`lm8udG zE?R?k_v3;4PajSyWIFjsl2&JEASm|nqn@dqEalQtte$(ZZ!zQ-(To1azDCR!b}#7T zFygwh4hLS$7;Fkj2I~{X+Hb{bx`O5#<=JHdP6dQ49>mQ&&h%-cZvz@3qspMNb>`FmHu zzCEiWVGkRfO@1vr5&hk=V71(RI*Vm98bizalU}|nEb}6PyJ}rsd2vS;%2KdgSKN-E zP4Tg~mW8pIjm?hiVt(8dv!|{6*8v$SK}NpKNO8DJ^-ov(3!0vpa4#+?rUKeCXMGKR zEiIi!&kJ=al6yS&QvcIpC6wPzJF!(tE|zh6UjpUTekO~|DmG3)ExXWqXWTYQ|9I#Qgmy5O>Fw+i85>3;LqxnhFo+n}qlIPFE~ zcP~20yqh(VNKLs+6!9i`?fJnsXI1*caOgq7sq3oTV48pP)Z$HAU!B(D>7w?{kJ=O` zse53AYw)^!QG*f721^Syp8WRcyiX5gh>8Mdau45586`h9mZY=WNe8uQ*t;b;lL#SC zg5WrobaO1?b0U~+OF<8lSlpJ$`o2j zgM|Rc9 zB;UD|Dd^((>P&Cyy^(&=uSa~g>V#MQ)bsuREnq;oZ$GfDmYmb4>%Ziv&=nm>_v4mr z^uKWP?}6{<+XjM)Tb+P>3ahlLc(YKt2?LgW!_=WVBaj*W)YXDT49b|6Vd}4!;sX@3 z6bZuK!6EU*!7>M`uP!kR+mKJ?Fj67LylSgM#a)ig?1>T{;^$yhME{JAx*gAjZ*5;A0Mp^fmY-n#cDIOiNo>9!7T7ImCk$Y4PKN)j-|JK>d$xUJeDn{_2-(D zli7fV?zr zQnTPZvrNO`gjnqvXE?3oF{c{8czG!sQ3U!mFIBg^JoB`6McQX~@ug~m=l|GImH8jt zb={SpAaefPxp2`!@xu#?sFC;6dVgyc+?-7GPXAed_UVRnrzoM%)V}O)K|_oi;9u>} zO^+UxeniriN@4x{`d<9N{U7YSb5?v$Df@!VG@`edC67)EZbOtIifv>i_k!X{{mcKT zRNZoh&7cj<^B2U(l)3f|{&F4hEn8S_%8)*2TslKe{K(fVI5MeJwKTz&{qvgDv}>PP zQP1uSJCTqOQrID$BM+!A2gf{=E~}e-M$Pqxy8Jvf)yC3~PtY5Fzdtj7%yff@*QfW{ z4B}rL&YVc(-ea0~p-3^N&5PfWiz(b~z|HY_?)t5XT_#=@J`T=dAt$YOhQ(jHv5RS4 zr{U=2Bujgb>HVdauczEU9}VzND&13qFrqW`j@#vJN6S`@QWJy1J^R+)#&1l%Mn!O+ zY8g5zcIk|v{JDRktJt-9|9$V{Y(?^w)zt^Rz47){)T*BzNuyc21~$RIHzybaiH<36 z!yU9fIqbHL3C}9B4oH8~p!$1u?-wQ>@=+ZqsttdzxUjv>&gT!>O3gx^^Kg;nJ*{Z) zL~x`c$kc9p-1?ZeGI70H`N)`x0K@B4+Lv!FsLPmyvR?CselJW*DNN&wfN1rxw=v(W zh2`@zV)JIArBZ+E3*wsSo}I`!L&{>WaH?~4afva_+2{7Bvf=g(3xhw6)w_1tTRSFH zB%io@bpM>JjJxQEf$sjVOQW;>(OWn1kC#Qgnp6^Ad)&BN_7&&7eSB@?Shr}->dgE7 zw{1ih-DFPec-|@oAWJ01(eqJ;K$d*F7CGkYP2RtYFchlDS(#6VDGT|~&6yMM!JTWq zNcPLgbYii!wtgr;$JG3u8!#uIpkSIH$$!eqHIv6rCP3nLTFsWwjGyw=VpO~>siixa zj_}hANRX`0^D3<7Q1f2g`XCwxVbik3)bOEIy%CHzP*is?ECx2?RQ!Bw>lVo&*C^smo5V)8!PxH zpxq=jbgcHslq$G1KQ1$BA{w}S&V8%mCaKBv2|vHAantHiwdm)Zo4G0hwMu;oGijGM z_tnZ>w)Kf4C5Wr552}#994IfYlS$re7Zv3o!&fI9nEB$g-6jdo@Cz}FU6^{ns7dq9 z4lOOXF1#5(fH7MfA#K8MXF@lI#Q51m9eTSGX)9{Bg(_-B-O}CNNJvXJBGMt<-AH$LigY(f zBaM_OprmvO(%oHW^1Ns7^Pbq}jBkvOaSzA(1B5l#9rOBK)zUud87UkF*F8ilYY89e z_ow;D@HMhF!?B?lCZ_7u(aakM`)Eb6DwKb-5Tg91L}dsIgljRbc-kc2Mf;A}yA1kn z3T?2|^?HooiLwWINuIprB+9!8HVbMw`XsCdd+a5Ps7XeIr$vRWCCs^z0MipFi{h*> zfmF5O3mSELzjkzZWB(gB|4fLI$LtgLeQXW=eI)yCBaKSJ+L|euRJuFxJS1^StVGIi zV$iaG?G?**AHsQLEYHI#BEQ4}nlihhr7&d(B`Q#|1NX!=VXN-5?F3Z9JP6{Se1^jO zcbw%RE(*5Tja2gtMk}sz6LN5q*!v;}G?%b`-CIGE2FQf$u-eACFYR7=?%gIMZa0}) zl}E1pDL{WF8g-In{akQO!`K3yMxJG7OI_5>@??? zrUFIk$@x>51LW;=>J*YO1i4(YS#?k9a6aO>rhvR>Aw~>GLSnA^@49(P#KNzj`nFi* z*`W@qZ^7seWED?N!b14Kpa~3v05b9d0&*}%2ir_!P7;xCPgnLcxLsslHKwCDBgSwq zQ5mYIAg#Es?d=EwO*Q^0z%L9bMZ}pkP=%1F4QqVbI5X<#%_*c$Ok_d2c*V4mv#vttF(5?}*TuEvBD z1u6o;?Gcy}!A$2l;_KO1AN~TcLM+)hudUuEI6JJ|X-a53@c@KXa)TSL??%31S zsa_jjl^mc8m z@jacsVpB zw3!pwT!n^8Gi^-QreAkw@z*3rmb;81h8g1Af1^7IOZxf5GdY%YrV%I{BPGgepyeRP z(5mEEakBEpA=j4WlNnAn@9x$0-A{rM@de+=b3NZ$ z*c7tgb>V(Us|CSBG5wM2E|j}!iMGghJ7dcwabV<78fg-GQHL8azkx-Q?Wg8mT7%{pO+wAGNh4IrF1a-O6Q-e7t zo8D;=GGTjINRcTH3p&4HRRwNaJu`|J(yqJXpG=B>%-akW`cPX3L;;T$-IZ#wV{?e-Pkfaq`K+$WGlUL zrYHGSJRSZebS}4bBR8i-U3uZNijA<4+fNm?OhLM`FB@0@LzPQltO=`dB$9!t0i3_2 zHjXY`3Xww-$ew#GADB!p`dxgS)i4|f4!?~@nQg0+$jf?^;d=&8Q6|RxZ&M>1j9V?# z*_kND>r5*6bFuo`v2F4XdFZmz^piW3>J;=4_~A_0tZ))R&rtc z`+HkT$jU!Mp^g0gz$1g$n^PW0-sh6y{0)bn$!`Q(3u8$jkYP-;VJ2pmIUN(9Oq^YH zt2x!?KSbA$Q(VotV{zA6ncR@>dGJ0#kEld+TVoqYDcZ9&qe}*(oiELQv)U0Q`sRCW zcRC+uE9Je}yjapcM#5xEBSg5)w+s&P|mX(PSA`0_S{%wQ! z((LC72NjJeMr$IRVPsrL#wH$jRj640L{^9La)Fx2mbsA7FBADPVn|+_G6*enu7yBY zyz=`F=ayEwUK+P&{Cxa$?_l=yCr#+v-fqU@pO^dm4lVA!4c1r1R0llQUu0?AyUx5z%Vo(tGvt`BKD??JGpff=io_Yq^P~-=c(~ zmF4B)!cNBlgBg&^pPHUtt{UE$Z4+!oPbMPmf{utNO7G-=EaV9tN(}`cC2qrz$M*rT z{qCnJI}q_HECv+w$~!g)55~#fM`($1ew(V?$+Gh}#_MaPWYud++E5iDO}_3C75h$u zF`XJo+bjmiJ!&Hg3zU^30{9e3XtJ4C`0B4VMC?7(#zG zW?H^QMNYXraCqW9ey9ZJMpo(-Br8{`-i6@$KA=blidk>|!0>jv&<07m2U|0^(R(7({DkikAd-#y$`TX17;lpP-2 ze~-EB6f6WvI(&6`J4sdy?V9L2E&psJ(SL|?>aq2HjTKqc(0(!3j+>j!dN0&$u9deo zgfEDt_^nsrR!VmUK-)*n2}8ORh21q|i0CvbW>v)hieM#R82`4&1-f~YK@u`DkU!WT zk2ueV;2BM;Pzc=C{$Dm^hp~v2ycqEN&EF2bliTV^0 zP<1_P#Lr~f$0dSv)M7~Gfk08xcjvS-Iyb}qwTE3Ya+m}JV(h+jBh>75A^Eh;el?x4 zn+|RFUL7yON?j^~oixq-y*izeiVt#``ZeHBZf~I>ASDOX1i21*0lUu-^;9`!-d=`f z^e{hW3H z3n!dC31Z9$cHJ(&&ieYK29VKZ0&EdzY@eRbJwug{9z@RvMvyKzIx@ne_`JFmtqRz@ zi$MvFkoj>qe54PuJKEg}H=CP~_qgx%ROvBA%Xn@Zd0%{#mqYQD_I(^n{+_AGP2h(S z#!mCF)e!6+$(bN9rw!PYgVh?H#WaqSx6&s$=LM(pc=W`cqc57G^|x1EZpw4AVSt&n zxMXIq9436vovE^m)m!8aT-AfXG^XhMPc-u}CusQJ^Jx_}W>I;muA7YlNm-b_P`>h5 z-d=ELmqTqF7nu1?@q3YlBT>bk4w0-T@_z!YIWKwxo-*p6>cw*c6p#UxFlDc>OiZ6= z&JuxVkF5VL1RL|43JuE#u`swiUh*;Q5D9`FVtLVRYF1;qAU-;z(~ND0aZb3s5P}ir zXN3?|j-sRV9;f;S6cxb~wt)sE_$4jx zN?OmDTSawNji%Lbg5OluxZv^QRb&uTQexH;1!H!{vvzwpnf@3n|457t z>-qNl%HQTg6GRdv7!f<d?u2)4-G_=mi2eQ05+*oA`4Bm~=oi z#B`Sn<|q+{5un*VS66S^0zeD;IjtS*p2z9|rD^Qo1Rl*5c><=HMyO%m|j%q!J=d@nQNy8`B`-BobB<-CYYDh<7=^#s_V}>TK`VRM`t%v;0*1C ztchZ5vc%k00}Lc@20%No>3~ZcScz0s!R#EQK>Pz;&$mH*9l*7qPn2=M@%5O?g#%#G zZp-S^ommWz@LMZivwT?w6bD+Lr*QzF%9^@@S2nz3gMTq zca12Qb=RS-2qqea{VuP{YdlNMa!+*mQo?UfJL zF1{^cu%_b?=V0kxF%Re;p9qqS-#X`{I$6RW>-ytp-N}K5xo)DoIEcDcOCK>MUUuaU zCX&#%a`l+-&Lep$CmNL2UZ-IhNwiC^gM5O`_rNR6zBR$(RUsCD|~9q$%p zH9q+G%6VzLqNkM6G5kqJSIP`$6l(+o{|EtKPy^(*%lePEGhK=quXes<^G?4ONu+>4 z9=FdgAK&6R&xPN``<}O$&|lRsmRY~5_T#(kSzSG!amUlWJ5^HeN0ZR9$c=<)f6bd; znj4P?8PT=#bT^PPQn$$*oEPbRI*SRklU_K>G?$&r{|_xd^w92tPRw-ei11ZELf5Ne z_kbEaNEpjcE^S+pmxN@v1%+`E0-k6FejkOWi^TGegfXvn0*CfZzRYAOyhp?QJ$2NI zB=qBZ=)H^Pj(;5JG&(vUKKJ}C>ebBcwbs_T@k2fn)!gPOLeW1RN2uT(1?2U`&5Z;; z@oyP-5rZkO>UvtX-lr;=J9qTyljSKvJTFuj+$_Ub_K>qPJ{Ti};x4Sgq#-6t%Qus1;zB47 z$IHBNex!YY9kTW*50O5_Sye&~J4CgM^EGiJ^Z}S)g0>**71#7fa457sAGY9-!oJW{ zn^S<6i#Yi+m*~%G<9(7s{QYBlFCw(Cpw`7u92SJ3(jm9~#P+cGyS~xa-(jv(%{npW zI+=qN4$Z#^<}c<>gzkM_>BLWeZK%mAbaALMw|8D&Tp!>sr1I_L1|7WHFp%Pzc?8#^ z^GRQ2#^AmYjV6|PpL}VD4thFErT7sD2Kk&7_!+S1=hZQI3(2`ze_SfQ%HS_;KT`hq znVEBcz8IRpQ_-_YJ@wFbbA>og`qIJA-5@kV$MJ{iA5)LbV3^$f_Vh56bo|YjqxeQR zRQO;_#I@=L5Hf;+jeQ34Pk}ZH#AQNhccMp9xX*jEnJr@x){n#_368T zCYFcFeD@_~&9mb2-#+PLkgfH!x5xM-gjk|P<9GEgNHbb#p3%{Z&VkQwjXmM0S_Xv`Y1>eHAtQdJmuHGJT29v$157(x(h^fS>K zqQ&{;sv_J(BwGXmxy-5VS~eaL*05n;NV$How5#?t0bS^}M;6Fa`IUh(ksvXWkfH{)>NXOy9?AoK0K@h=QTfWM+xSqjA@(6 z9{Q+Gt~)VnMz+sV2Rk7vKI)anf&nKpp4luQ>v!u{ta;&-boC$K?=w2>hNlqsQIy~w z4}!RNs_OxhAe$B))Hgr(`2uHet2c(twgrxb=4Y+I7ax7*L`0l0Iux&e_5zO=5&Je_D-)u&3M6p_GqDaI!<> zMJIU|(IH+T*Sj6BAWBn~9bSEi5Qzd9dwqB)B53=@jNApaSGJz|f9pHoa&r*^h^z3H zDTPI}F4XNm)Uf|S-}+81C^2%LtRa6js-N%o9t{doxB564 z9pSfh4+XiA`9hd&h_%;pz1Q)`!(3Oqbbnc`I@=M@V~7)|g1bLK&OtTTOc05K1q&_D z*(9jxH$h`HtH-DJD*qcDSeYBBl1cT24^lJaAr|V;pH|Fi3SEBi{=|%9EZ3a7Hm97A z77f(-TqRoamxg3;6Y&SijAb{QNs?oT)rNP)oGTW-6`VdEGkRy04cNM zWc{P9GG(cIp|rnQim)_Q$OTCdg@&lW+bZZ4cz!bA)v}|3eAKlm)tAh3;h0EEnY2)H zO=a!U_cB_ewAJr6WOt5;jPwM_G7RcH)w3wH*dTzP5jU9O*tPBYjof#)tqCckCI!h} znSA&DvMG?J%FLF*{^HyAX^%&0NO#MVJRx3ys`OS$QK;;?cm>t58&y>uSTF4>`kMhl z#O$9QtHz|sSr$DmsgEyV&r^#0FSKysSLdM@V~lFCU?;f=EA0t}_U4%!8fRV+RPV%I zyruKaY;9c%dfYvSxA$G`GpH6m?IApOZ&Z7dRDp$je#qaSBJDpD5k!Ef9wMV1>}R{V z^BOn|_e96K2n*cJH`8)0^XEHoQ5$8`i2bpjbE(L2pP!2Tp4yC?O!F=5&OuoB;rmr8 zc&IhZ$pXcig2qC6C2Q!Ee+#-4>}MEfVFlnWmLL8ONiI9 zno@+T3@>?5$V?1FA^$4X+&pnbgJv#=%X!`M(8ZH9dG@dMM=A4B#VKAAe~cC!_|=Db zTb|@WSQ>5JC7;gzSzC6lNA53~Hs`N#+iDisv%XHmJQ6LipvP`sj%xcBio1F%PU(DJ z?-*aw6vjb;boSkUeb3I&YT#(4cXyclA=~wRcC-0vNKT(O0vYpE*V9>wa$Qfy@9Ab8 zC90>w;@cYM%C4cR$1i1+oLX0>jmv?4`cJoY_daHO1Hyr7cUBT@bp7x<3oM!Fnp+0; z1@6UX6FxlthC?g0QN&@v_(WmS2tES-qCTedt5+C(!vlV+?_&05c&RWl@!1Jt7(k(< z3@Dla>Sa*D@-a0P5GO#}rV<&jJ-lsEXV-T2cf0;bOCYxT6XH>N;bj)XwqQvICqkh@ zpShi(T2u&*P(u7ts8S)f`b=$itcuxW$eW1*Y1hCP6v)a%ali85?7KK2W0u|F zT;yM6)B@a+==v@fdNVZCaX`*5@UPwemE4LnLCF04nG^^GF`9y9qF#K~d_(v;2H8lV zatKPXGODKx;Y+bPDTlEn_yR^Q5HIhZ7o_lU$QrqM>pffmNKLcwpl_hO#L7xlO*-h^ zSOmie|c=IdqJ3n#uWIl6?5^xLpQ(+Ck#lOLF^qP8=E~alyz_ns~Ob; z(+WPlTv7Z8bGhKlQGraH!wizM0{fs>jqi^yzgnp$1Sj+&4&lAqE-NM=(C)a#P3>1% zur*vc@lqxz7G8GqMy?hk3^iI3JaP~srz$c_75(!e{b~spo9@5=G2mnRkxv$C1RVBk zm0e+ZrZ&xQ-H<&e+6xE1Vxr-AiH{%Mq!<-0&SCuO zap&mNYjgGkt-ofH-Ml^HAPYud7#yW>9l~Hw)QYjXSO%rkV}aohnm`8C7PR0VLw14> zz09;I?=mCabHXD>N11F|N?4IjGP_m<_)G(*{M6Tk5vKM{@?t`{d?lH=c*!@xQ| z@ZdjRG3QZoWN$8uGIqp8(!~p!buAc*Q=}C0No8q2+vHa9k=!lu^cHmbqdOd_+8@M< zN-z}&{)yQt5J!PoV+Mq1K5R|;R!l}ttT-)$Q zizQ^RNNdZQr)BVYv4La(WaXc0c64^;di;$9eCogviA$*%BP#HJdUfVB`+}q;y&YOq z_%*i4LiP@jou}w!dv-evs%UWW@m*pL>(ivHDQ1|FTw8OAvLy&H_Kf<&n0*s)+*O=& zW|D~}aRt>j{uZ16pfTgd80=&$WdE#HM@389Z{9Fx%QI;Nif!cN27!H3877Gac&7lR z`|6Yn$524vys<+3RUlCPW@+FCD?tq2&50prXi5lj=uCPu+R-Xxh3H1NB!O7QEVjV!H#AIyx_H)Kkq{qVc^W#^V~fkpwa|<=wpg2R*uV*p; zxQaB{@qE*&T&vEeDdJoq1RdU+kep22fgjy(T$jd*7Y&9QS}b504cUQ7Qd(LXctyX1 z)DvKJmXVp6o_2P1e#!_6DGnbuI34LfFV-UIv< z>h{Fo0_$1NtkIXmXdbeR^ZBbXC0_X8o?4?TNzKybI~vWSMey`lsUg$qCf*ia7?Isms8}j{MOGpw&bnd2{`l zL2^zy3kNkep`?yQ|2}HnB|A11zkKSH*Q8Rn+PrKDmOs0;jiwl6-2n|$NeS|f*DJr@yjV^RyS+oy z5`{#koKG;BC<=JgIrVI9tx*de=)RIne8Ew$Qgz;OcXf)-LpGH5F@f8gK!yvP++LHL zNw9~<$(Y-l>)K+o#!ka_nnfg;w@cn?+!FZjzNhr@3()1iEMM?Fn1sxvve47Zebq0<@G-d&C}&CcPe+4!_=O~T-3=E=w)z`e5gx7Ra6;CsLxxzS^<-}}ka z7JP$D)D4Uq2XsD;Vr8su*Ii6avs=$PlzlcPeDDb>&PlS^4-y{V+wc5(Xe)eh+^XLy z1D7Mu7HK47du_Z|1L^{oq6ZMpevlY~mBFp%=8?j6ntaHKmwA9LV{qT8(j<1yHz z6)u=rSv~_#)$;BA%1+%G;iEMd03yjq$b^e5L@(>+yL?>|t#zw-?fF%>+6)|z*#Feu zUbYgCZt7d_<8BJt$!hwx_ggkO<-ULjp4JE@5a5w*KiKtralcYON51Iv7sZDl?yL*( z@}G_tQXP~u`&bNqH>jDnWw(>n`cUX}Gm_*GH?4GZDB|B|N*R8E{JF(mQ~*_)?&58j zg)rao;MYv67C(kEhU)22!apJ`V>6xDeTM9$SVP6(kH4gUki2th8h~0x=%SK__o6Ql zFipPO@q7DmmeLMKrabg2hn=Su#a=^F9U}rGUHzjjb5WgXtHGp#a)pJ72(ejvS}VxXAN`3U8rnmfWHb=wc3dia;5s@=_x(I= z*hG7U@;J)nUgcAEgzis@w|+G2eOpiHn?v?z?PBsPN%83H z%Bpkcw+)Y$dv+O2KD1xQ@HFXGxE;dQM5YqAsqu8*+=ky z#*xPa1b?XoW24dKNbw%$f2F;9bO;Cw7=ovU><`qCemT7wuk@3l^3e7bwEk0^>~72J z@9J|Ah6xFiL|E+Lf%X6cuR}_K-7d5$^FzM*3Tf)yR`)b=2-yEaEs{Ww*JO%7uJ0_l zVIiWKNHQBk{RUeX&DxQy2b<0A*}a=!mO+iSTr0w_vw2RrZO0b^x%ogqV8iO-AyHS( za7v5Iqe*M6VQZET-m*)f0j8N229`g|j}txF8w+|$vDsopOuxYqH=QJr5Sv37>IQQm zDt42kAcnGBzCp&sH%1s_=eA$ov*K}yVZbM=!$4@XSc=ANZFt}7pndv|=c1Z9XW0au zAe|h$(8~@^`94o1hhK5NV2F^N3J)m|cZINTRF92rqD%Ud7t^EejuU>7vBMB*+lH+C zN-;lwM~uXiwB-tE(fSP!NwuDbP!uIM$EU*gD=wt<_Ov7HDUEK-EI{S0zZc||`1V!` zD&UTjqu~Dl4Y3kdZj#f}cgkS858~b081~bwCKVC$qHrU!k*IC4;B|H>iwgLVu?uK$ zmvJiHuF}T`C~9?XBgN}Wf*_fY8r9gp6+v2Dp|D0X+@&qHh=FruI3(kBrOWO9}5ZZ~D0%2ysHWt^7^=4S51R zet&bV_~uL5YHBYr{ZOWJoPkb~FXQZ=pLJ&QO91z9BfR7px!K;g`SaP<#bjM7=Z_Cc&e{4+|*!$i`$CkI}?4$Wn5c_JKHiVg-r(rJ~ z*?x2B!zS*zXSQ`n8FB$nSLhy@@zrFpr$YIkrj_qLO6M!K>uKxIAM0897Q&;z39%eK zY|fRgAez)aH9VseGYrqQW}w>MD*du8N&k;y*Go=#I%$M`VePBIz#*3uR<3Y2vvb>B z(#@->ATfYa-|Wr1=YHNR`n}u1-BJ2v=6oJ`YTnTQNr2`4WpV)&MM>qKEagPM!i`eenMsecc#_ie)Py_kmPsVj?1sh47G&XFu-F?_NW8=wm*x6BhefN#F8y zg{b+}3bb|)oW$5sMLfFFDl(X2QnB*K?}ci9ke{8f&tpEy$*MCQNxpLZp<-|B^j$be zM~SX#S5HFb(TBg=l(I%cckPk-SII8~Y+OQ|->Zbcm-hhOJr8cctD(*?d4ecVq9Bq* zATOMaFGnhz8a3cfQhDsINVk+Akz$BTF~0AE`~U{$OTs1f_7!u(c!8DS@`{KK=AjuW zaZm2R(gCN|#1i|~61A-LYx9KNAGB_kvG6{=q4u8_9-1g#tLZr2b1QxC4d`J&G&2J8 zA+qoxR#e3$M)%H*z&KUX5WX;%5I^!Va}wTgYYAQ!Nc&MN3OK>rAAllwo>hG?E5y`0 zu9V`SuWv7Hefj9CjiY+HB$y3@>3S^ec>26mL#4?|nvvYsZxl3~X{>LsK3IJWu)k`f zI^O&QS8`t8?dbxrzp^8jo(`lWPk&j@h*D=sd>#=U3!|7-b~dtf>%eJObQ>qt3WZH} z`dh>+b=A_fIUV=Trj-tH2U{T%03ZSEb7wf0Sp$)xK`*vd1bxYu*sf<4MKw)1-Ih^+ zWH&BH4G?AGAE9orP`Q!yR14x64Cv+Fypa%=b%Q3%d^N~?fP{(Ay1@6Pt%1P`cUbbH zxcJ*;ZYk7t#0N5b;HFgUrq^!po0?{&US+2!&p z8-63{V{UHE%%0~00vuc{0Y~q@P8g-CH&|E?z=sObUb9HM_PoB)xjKtsG+^xeB+&Hj zi50crtIEhDtp7z-%kkb*OX3*xG|)fHNl||8PfturGJXbY#Jix=p{}UN6yWbND7hq} z*b+cv5}`F&8G7WEs^bE5Fx-kyYd&fI7rXVlU=(YO85bK_{#N86*k>Fu}T z2n)y2kzjB5YmcSY+k$Z8|3qPQ(ZfqF;M{6fHZTBDagTpMk2J_o1^FR-pbQ?AE`V}j zP{Qm3GRi@sB+x@|0+HdyMyq#8v(Z+Bu7SZjQeGaO0vNC3fHPx~hWh&Lkv|(<+8&d2@@9-M7sRoQ-Dcx9u32j&ja$ zyhs*u(&mq-gq8-5#i z&md%U=OO`Fd7r%FW5)cjbZdTQLY^acyH(e&FU0vc95mx1pMj>)ve9&2$_;n);VT6QwEfk>O_ z9&JMkECgV&=4PMCp+7&m(!2H~NjU>1c{4*7@nV9MkW2ravuPed4DKm=E~}R2NX7c- z`30_t)O}ED=s9xqt=#@)hvRI?TXNZtQN5L{wM!(f`)e?dkErv|wGOWZ-$~G%b2l0qImN#x*m|DVL;u_t8i zKLJ~D*OYnv?gA@Un47Pg54s5X@O0sqqkZPm#dRb$UURzy6xbIHnHrB%t*^&CB@^>{P0 zNBui#xECH2_1F3#>*S#i+ILBi0~P-FYW}WhFsc>tMfXF9xld|UFN}kRjF}0+thp3< z#=&Oo4Fy#D@et*tvut3ml+h}3fL6Zl=cF|+?7;QK@`pn*%hb4@48H6V_K9hn-&-CE)tHno)rde5HIY(<$?S*IrbJCIf3PgzXInqA) zc;utKTEyWUemGn9vc;pXGT`r^0t#vUiBVu=uYKCLvwwKds^2;{S_ay&U?3Df% z7Epqp6b>F%jvXO<22;q8KcqD<0jVYD?;jlZ1>=9nbxIKI0Io{$({#-rmrdyg%zq}{ z^-5yUZYS-?c)}7wj#m=?smKlHEM5?nl<|+yXd$pD(m%tF`5ef}0T7k0<^SRmVcC)S z&{0s!K&UpU*s;!Jg%cSm2M$I?^x~q|uPjD__+9W=bX!7hC2BtF-tbrlJdQCM|40dl z-s7S$jk=3U!*6-H_%nLantwSp2xXCa19i3kp{bi49+*pbG6QM2VOOin#t>LECM=t@ z?TV!PObjF9_i-@SvGwj%{RZ~>AWZHfa73#(NxxxLJn?gLE zf)>qG(rx?uA6kGDbo_>A#;*I1OeJNvw0Pzqo^vLhvrYrV;3dS8YaWu8cC?R$XA zbKpzWWcx1nFGkO4a7$)+`NQtv<5E=R1z|E)ttWWI9|tX-C+wxK+s!~b&PSo<@aFj zO({56V5&r^!ig(Ip<4v{aWaJNR)Otx51CUsID4ULZCN911#H4cb7JqwwQ?^6ad)`A%5ZX^IZ*c+S! zQV#l!|2sWsOQZF4y+i&dk5(U8C8($#qj3O4+mG5Xl-f>BOER(EWsf$P-B1kTvq~DPZVt%*Xz~83k#H%ie3)Q98doWx# zczR#_o1!QijIP7r~u?4{7v3CQF?)d)JSu;J8LVkgi}((|&46zB}(4GV;+jD>|H z!TPqFjh1^YU!JD(H}1_aoVRbl+M>~ zX)>gDEA&V9H~cN-sq7iM9?n*)NBs~r+ZYN`F~9>?wA5raNkST8^+Jlo;p7lj@TDvy z_6;MvTYWn<2kWl2K*CCrRz4=)lh$Hs?$an8ecr>?KFN z-HHvjWUPMNR|pFIIZKy4pGHNE^(#eEl287va?%z-9{bA?M4eVLeg{XzZ%5zl-|PaB zNOv)@?&!amvs6vB=;7zLOLtDs;Gk@Z6tB~MDXwTiEahDEg~6jH@lLOZ$>(woUZxKk zi>er|>vZUIl&K2VUw?5%c+evi9fchDJ0)V=xYnreJ(3GHbC;L5jj}6ep*}E@ND>Nx zW|ML9v5w5`u!wrjaczAX{7@wcKdr$*7dQbr4nI%5WCiW=F~t8DpmX^x#Rz^0HN*!< z1CH-DKwRT!nCq$V{jRM0XeD)@PI%7?-Ecqwp;uJ&LH66ANcG8ym5<{F@cO!EgKbJ^ zJOPamkIud+_P5*9xZpk~(F;Va>QSh0By`EW+>%7Hm@CJKLj#}7x}?}5r4|cpp-Ix- z&kjCZGo0rpz7O&51RQDEJG?ayKUGzQeKqnU|N2VoF|RuRZ`eKmiz$_iiWOTAI3*^Qp7Es!WjUp9Cvu2nGyGdL)!;w ztVD-oBZ)6@a!~>Qvz!95r+MMs^0`KMDt{9GlAO);Q9$=TOTi9}5fk`Vb=V zU!270e71nQ}t=O-NX~4ZuBU@g9Cb%GPijk}CDeoc%s|~`=K(Bfo0CkyYAAoyVOGV{5 z{dO{dMlM$RccBb=>^y2Z!G+knN+wC{fzi<)R_YuCDS14hJ%otpY34SfGb&kEFl^Af;f~P2%@Taq}@)?Pp?+( zfnHAc7bumMQSXF<>|(BX0IpTn%BWVtS&|}iP@MJ?veYEHeP7U-N{I^M$CyNp9_42n z8pwVRJzf>~{;7*NKb&{_A{NwFsQCalo9|$Lp#WXo;nnl@|L7TYvX}!T_dF+!1}j5= z3KEMzVK%_LK)ValgT}|lL00GD0}0TjUH522)Wg?VC>uARN<7(XR5OX<7DqEq9Vn zSr5ipW7u)ubhP}o%fg_3eqd~58Em*JiDNbG3F2701iNS6tn@2^g=<+kJ3C3tc4H&@ zd(9>n6iYK_&1i@cys-L(egCoZJ~TF*laAJOnC$yFYH&|W4yXr+Cl|?C52lC!sVV3m zyyj>VDq7{-56d99l_k+4t@g(zqUB#mXg9{o!2a?HH`ajjjYGB)cqgX;nH!}F6w zNol(1Yy#39dAjL-sg9%ZWw#@8wG$fu-2o|X0Zahp&r=1wg{1OMp!%t_e--y`yMA|d z)&SYz-s~qFgrUOzt(KQoCFMx9yts9Dkdx43+HZmY&<5D{GSti0uq}G!hQBH#xl4$JB&|@4 zB^U`73a$8VDUfjHP3h#Z{%(G&VnR$0+e_S+ElhG1#VVi!jm;6RK*xbMFiAMskb!kr z+RSV9#jC>v>tQB_9+n?aoDmL5|6CT3A`O_*pXcDP7`k{qeqLBGXOwjn44Gre2JOIa z8i01SW=MCERcB%o1OgO1w;opVd-K0V_}xFNi7@e$X_o!*AJu>Nbe+|6AO3P^3!zf_ z3jJ~dtNq>dfq+w$X4%mLOdAAf%#K<-XisH&+V09KH_0V4lsnU%$^$y#Ry* z_$hw<<@5E@Ew;(V6Me?-7n8h%IX5fa^mq0ptGD@i1ugGIEPS47MGdYL!HMDli}l)t zAtanusc<%19DkTGMRbnAVtIL=sP@a%2~->U#NYm!0C90*2l~Z%ad6WDsfJ=NWC!jn z&o*P-=AkoKc_(yL*F7d>$M8&--CpSwOWIj+OoLm<2rY*3OvGV5Q*zI*S|3Jj>k@gA3?~SHDiKPwl9DRe)y?6V ziqp1L4G-x&lU&q9fxkdJ>6|ybHdsZg=sBHCqgC~$MlU#1uL9QxSt~s>qz&$tC3|`6 z=(m?DD?K{$gLO~dh0EWcyQpB-jwvRbiHCYSWAb2udSG3b1SGo*&b;hHe{0SJwBL96 zjiwV1OFs|VUx$Jlk3DGR05PcG3+Rt0L3cgq#jN!PCi+pydRN6A2=Fe%#PzzWf8*9x z+Mym&4%r{G?wLs~QlX^GS2Z_n5arL5c%`7AAYK8D`}SuU6Gg}`jnA{;-`>*W-WW@4 z+PR{aFvh=TX4B=fD;&^F;-xRWG|h>NiQE#>xRh)536YX`1GFs`m_DIyWUSB4lBc0YPrUUyOD(5d)B}D0^0uN z3w3@T*+cwA=3mXy4q5Fd`vzTKua_ci-lHV~VQ1h>v=awWkk;k)Fip&}rq=_5%YM~s zA!wGqx)II$hs(|n+ud+etAMwYdEW0h6n`ClSPu?q5`l{vkoEhEYfT%i?Ut_6Z1+>z zN`+qyj&dlV`)1(d^Lj8L9i-G$v$KVZW{c5I<2v>#ydtV~QE;y74?qiijJ+2d?fnAa z>zplJGLme4OWTcCblsex`Mr%b@65J#rS`K5|7R(DY%B_g_5e2SFipa{xShkTssrM~ zC(rNQtDP_|FS+%rZE{~RoC9ZspRlf<5s>$6#zdW;O`DQeK0KOsn!seIZZ_P&sKSS< zFS3(#jIqBGSowVe1E_DLF4LH3!nv3Ckxmb{(y-42{F-))luiPw3N8unKEE2Gg$F@{ z(9Z)&v>&G^wiSpEABGT+`e#n@gjTYv5&}#NQ;&8kg7p8)wl@3;L$hf`fk&Ae$EUrK zOP*h1-eme4UA#hDyCgv=5KJ|VD^=Z3=tfqQ-u~GzNOZP|e^#kv0<^o{mMIs0 zJKIBdsbT{(kRb;vi3KowxF}P-uCGJXyh?)ifK+d{CwP~AtRcFsS&@qyJ1~?KmdAx< zvs*d)K?U5Sd6yg5GSv^&Kt5Wl{LAZxB9MCsB! z;|d%iq9HxC9!#?-0{p@e?N%(AY%%d{1Q|6ylk%PNhL6M-zk42jegcN%nBLmM?5pOS zEo7#=ZLIBfwzIG8#=Yz4Q9ETy0MP`W@Tpa^QzT};&D#p7O80(?Z96-x(PGpCM^TPR zx_1%#_~=K>`;~cJl6xTZFgy6{vP&;a-~g3PM?-TLReXp$O8nnsk0^Q|OiC2E}R+N_v-Cs8ONU$W9{yZ^+6d4l?ili?cnAMcFeejxs~Y%HFf=aWWHy zWM@<|5*gWh?+9fco9qx76;6^p%3hhj>wI6|@6Uhr;ymYh?)$m!`@XKv^?5(+LC%6U z+2epoFnQ{sgTqBqQjY^ZI6#iNHhz-p`vr-5Aow-~;794=jF7kdyZ$Xue&Y=^2!t4K z$5m+lFr~qlWV4P}xYW%cx&4>ap^-f}+SC;Ei}R@~T%=b!Rhj-Hw;T#A7gQsmCvVIc zqAkznbE?X1EoWiP@9fN8%_kw$XrJ-uZShz%kJ z(sFfdwd~b7HD93$QuA`z=RJBu+TLk2(u@S(Pw9&NZB%IXZ!&N;%<@6WoiQ3{U(2hm z?rawQnQqLHe&xxNx-Q(!GfFq77%LJyLJs151n@?6iPqDF2;J@Hn&=6;en+9mqrxwd zFr^K8up-|I^P#_&WGlqq^bjY!A6h9~JUor7XTLz&gS5YH)kaH5szMH7gBy{18J_QC z_N{Gmebv4%&e7@Ve-3HQQP~4@Hd&{|ZdEFC7fW#`>+E>T0Dgp<&kx6;Ce9zoxu)Dl zu{8uw|C&evtxWP}y?BUoI9%l}3h}OLdz-!H-rnni?9kda>!nWY{A;(8ycW@b!&lL?edQ@o(DQhh7em8_K-sw`xdsYkHwNS>Cdv51JcoXzW=?4VfzHP{`g8) zlrFv$L}){f^vFPlIQr5WF8UuY&0_^&vpw3LGc~&+5k((Fv|PcP%P)Au_wnDwQB~V3 z=A{IdmU>o^1nY!MH&e)qs3A5YASq;Kw)q4(JvbWL%OShsqpr$gnAw%)h> zT<_;{1r3zz$(?I=mADCae_bNz$o>eGaJc2D3wxmjvZ50MTO;=(ei%?R7GF@^lXH4S zw3?hLnm~6;A`CSvU&&V&@qi8krCHFgUcJjl#rdS5P=@`Umq!V;j%Rr&U#Z%42P1Q2 z?{fSX$cx5yb|UQuG$^PIWJMUQ`rDlk@&aCT{uv|W2@5QyzKkm@J{9oa8^y79SEqcC zXD__oFSP3}&ggo~c3~)W)oIC_$I-#oc7Ffw1dDO4Y0YIGX1tWTq$7`oMV9!TuiM#% zb{<-8CovQzSEtpZ;>Bn}0QnA-1i+W@${*PR znl+yGbxdfqw|-kGroo*dZ<>B!{b8cbiVZy_-Z+3Opah9hS63l
%WF&fOLa1s8KF z{I7LSEE~UXF}}lZl3OLJi1}=dV(W6%{C!I$Ja}MN12-t`frhXGw2tupDlac5Tp|(+ zS9n|>!lauMT9N&ybmp{ZNTc#g_Sp~~he0VFKi(yz z8KUzl2;&?0Gd=y@HL0(U>zEgAa3>3?6WjQsMG!A9?Un?(N^CN|Bl_=GcbzZ`^<~o2 z4cZNrI}$>ju{T1VEn0nIY!bgBlZ2O<)ieX^e`FQ&d5V^LkO! z*>mdEZl*lrW*tWZXE*Kn+f=mg3nnR`64qbEBa*1t zd>Kd;0+)*PM*G+8B=a~kqIwdzEP9`<>ioMCO$}SbD5mUKo=Zi$Iu76XeL-?_kMnP3 zq1&Ii?G{cS)s#%pn(As>$d%}9Ux*P@Oi_L(K`-G}9p{@EqUWr(EroONz*5;0V`Fnv z$!WIN8A=d5$G^8-`HTC5VhfHwHS4oYoV`(x9kITjcgVXAH~i22HkuD4TVz1b0jx3f z3mHl))UBsOnv!>9Pj_KAqaKT?e9#ZvRE#upy+;$lsyFug>akknx~_I4Sa=4wDmA?M zls1ioCZJLRe}6*50L9$ceOdwcMLxNOAKuTSktBH|Iv%xGVs{KEesit$m+V8HyTb{3-Kfuhljo0=)W=#vmbgiw_3zt?2QX%>9cN6F=7^_K z>%AFaHzb*%Q#AVT_!tm_&w&mAej$kyOQ94TnLdjQx<&B`2|&R5%w%k8P$}p23^3sj zo54Xkgp^@>Q0y1_sm!|aD@Ud0Ie@|jx_Tl%3KZ=aan=L&t#(cpT~KobAWj@HAwD;w7N$5St|u>|_2n5hqJ+VnJ6d^NREV7hh(<7cGN zVtjYrGj^BnnJ2W_>zSG1B8rJcUI||d!S@C4pBgmSi<`y9?E^)}RuPWQ~RqK~&;Top^;4}NTh?to1%==)lV7T@k z-Q>{Q-`@y$3n1k*1Aj57{iTJIgF~vYy^fL+AeuOUTB$6Gh1!GK1Y|5pe5SL7|9o$o zl^GR{c6E2RY!|sE-85glrP1#w8TU^ z5k?Ttzz@)fajXEA1PmT9=T4UNTm>$lx##uUcme_f{{H9K2DtCv5B^M4A*^ntB?(wg zgIETv(q)eSQ~@i-#j)U)GY0TuKS3c=(Ry|SR2g7)0J&^;a16k>0#~nI<>6Tc6shW? z$999M%9h^%&;+S?L>rJ;H(JkM>@s73BU~ylX0&;AU}koBk7mdC}0L8cG_fFNA(H@J($#TrI6IGB98Q_7c!SfR@Cj?gk?&nNbb~$>4e>BXgEy`2stEAkd9M zq$$kLzYTci@`JUzeYiq85lHpCuZIvYs;jGaS4LkW`wUBsm;rDM6BL%B!NEZoSV;%q z^npp_v)`XyL49>OGWuW$fuJzPG6JwJ=@451qm-1CbkId-Nli^1jjVruybm|Kfqf6W zw{mrg{8rx;sl{q(Y69DxcNIPdOTYr->b<=^fb94ktrP)E=LmB4U{_lQb|TVsGqgPS zI2>?|O7{SU?&ISFpU9~m`HGPa}w8KKf}0w6`GQv-U&XZNcr zXxdOlM&B?PES1_VV)lkNtIkDs*}@4|Su*JlE42PcR7twRt_He)NJ-Sh-SxC^E39!A z0)v;?X)Bol0~3Y$)c+rc(kc` zOnZ35v#HN5+{$zMeJGAP1dt3c$D#Z7QO%@jmEGg%CWhvg$5XY&me0rkL*qDlSCpxc zR0WX>iWE=4ao?Y$`3Bkd1jt_#_F0kP;X6A! zDA=?>sJn9I3c%BhOiV)8|9vY%0fl;fZLJZW2gvMXPBuFjBd>9DKZ2(qdv=)D=!~n7 z;fRlbsu0|sj)sPYx_XM(6PCWS7?svBi~s!iAB|?glB4eSLe=8gRu_mEssnp({NC8e zN=<#EW6(kO`tlTRJ#)7UK?AOw|IrBlS?(AmHO9%fX@Y-xACA)(NS$fJZ8tdjDC-@a zvjg2qBoBHsBzgZ$%K)1xG<2Dfn%aqOAX}&SPI&d(NEJM%DD_XH61^Cqobw}}*iV}P z#hP-e<<>8ZMy4bt?gP^my25Iqx+EqB%xsdH73g$pNC!N}s&bjp6kvu9w9IZh^)Du- z44<2#P>vr>09d3>OM-_*=Xn7Wy?MF}RR_P{(~VTOsCVPMc~h@wbYf4||LjCQh!D>5 z%_rOa01SSbuA;2m)p~xq(TPIHJ$_u4OE>t|m$o+w#sDmUz*7tcjdH@v427z&Y|V^` z32-(xGfVBWtu!k`kOM_|W8=_>?ypJ5bT$g zEG;doxtM-Y99{H+z%A+g`0)aLm-(h_VSG>>)0NY&{b|mIi=*F#(58XHb#mVQADj0l z8F?Ie(#T?Mw{$BH*Ta4jji?xx(56)u`!BtisO*YrCyjOePIs3LMxlHt0Y9@q&tJEgw>_atnAmbok*C%a&m~hP0+G3Hl%}tC}5yi@DlvS-fXx4ORKWF`i1+n=0&-g1a9dx>ak~MXHS~8y1_x$|7hhp zyf*;2g3rjF@|^7q17IQi_031FUOlix0v~J{U0eI@p$K#s#v&yEdlqmA!qpm98&Y(47$Nvc@Bg?TM0m+}t*lOM|E}K$2Yrj zIA$jD>Br&{_?-g|zVdb!3glnM-Q#lQ9g$y@ybt?)=wkbMvfv&)?KI-1SOvm&}| zgy>1Zg%=hoZ@?qMu5@v3PBC^Kb`IDl7K`lv{CWS+gyNuf-q({k)^kV>0Hznpsykrr zuSWDZ0NEED91K*>lhY0VC(h2d7$bYD6e_;=bax;9`v+_8b07s4yFPqaJmJ*hyT>Ex z3Lz3(j**uS7_mbC5=?#GwHI2I*$(JfO2-rCxyD7tD8%L_PT> zGe&5lq_vubwdGJ{eeMC|Pe3z6Bzyqa!QP4u*n3sHduRI5rVEzu;;#?YVxK`z$y?y2 zKAwX9eOp0#P!V%$ckmZ`MK0&H?v7}(KHvQcUgHxoBN5@B4w3W=fGYQNa zt#C=XgmOP4BqWN-V;0(Cm4*QHIXDSF~}g7jP>i-&GY zC(D}|>+Ch@)wBrk&_eAA4TO0>L;;)F)Yw?e zZXg+ZLjYx4cJtl;QxDj=9u_|=CJ=Pz;J04fSRu#dq`8ooLdtM69~Kfg-=D*ts}U@} zin3lXHrM#>tqQcBxB-X^l8xXIU8u7H=TilRPq1yUA55)*%fZ}@tsZ<5OFQrZhtw z`(P#S;NbA=*)tUC3XSF3!h)##;s8WX|0??-l?w2L_JkgL%V%54z+Z&(_xCcC{YR7Z z=N~b}?vcw>YFb(VlV3jCTY~}f3J;88Xyu5CWF|7~fFUy~3H05qls09UV+fAU$iONQ z=`OECqSoho^MgrAuvM#<7QcEaFnmUs82vzPHwGfQ^uW7@2j@#=;bQLOu~+fN^UkBb&e zZj`Tc{{4o`cS!nvU=Y}tiVzmd{;Qb1 zdc5Bz1bY<}K7P0IFNdiL3^U_GHfnB`(~87A+HyQp7xfZ#?9`8m??OdTXi|<8GGHWu7KdF2ty^lz9WQb4;F#F6zn;KL1HVQ=5d$`XrDbI*0>Cv6 zl;K@P!%|;d+TFc2*R5S#)~wRpReGOTenPnpFTwv-ig&7RBh42CFX`&1ya&wh1wH;a z9#BJih)Glc=O@1W`Sm^eTE{l;^0#Ee9W-bHS0s_U2swL?@Vdr`A%R6lAXkim!l~%L z?ed*KedZVm)C2vB#d#+~BNTZ#;c&rYH0PEj+9lwO-F)mz-$dceZ3;L%2|vZNm3DkA zDj22HY9bZMdE-WuWZ@dU%kitcDhJ03&ox>Ll%F=mcpzRB+1n(#M>Uj2rKfAVtejUT z18wJ4wUhE8PiCXp%sBi|1orw=d13?>9HKAj)K0Of3@4I&@m|ib%X4wDibUk$CalOM zY;ei4mKQI7`oZ<|OM{DWxZd@f?B_-t^7W`Xm;4LJ>uLYpt^)Kh7x0~Zx z|B-nJPA%R0G$OcafFNgLQuto@XFZc-J0jve<1PkdBfZqZ6 z&EM%yj`@WDOWNHJpa#jCQpyVF8ktuJfwMQWlXn5rE!Q{BCd-qefA+p75vNlUQO+BS zHEcBY2lVjYeS?Fkq+|=DeMAr$c}XpiS=3>mD9dZ!uM$+Lh~7cz<;uhK;NW(zeTLO9 z{RT+1Y#S{}`&x2m$Uqx^E}Rq5=pVK>yLx)^(humL%E#J5dxK62qBjvGXolMxt-*4j13&^lRXwAOc z8M{@)6HMvsWMiY}woUIc%y94AboMTC#w#w$Haz%i?+o+?!b2fMpgmT=7MDu08yyaN zg6wRz+9fUvj=G@#4iAPTpYIb5p$4l}xV4od8T%y?3^9fC4=pN>4g~{)gZJ-Sxo&cP z#OO92zX_uK{w0mrB!ZA>c9A(DBMkRZzwdLb>ZsjNOdg%7UPpja^ptAj^JiDBSSlLr z8T;%1DJ!rp!+=Ef+hBIDS?7vm;0=$bC3*%V=nc|>}=jq?iuJ=DuC?`va zLGu(TVq}D6s9$QnSQh<5h?}4P5-%wf27*>za?y9lsmik=B|<-^z9DC4Z-zX_&7)BklR6!tzUhh5Mfps-_>0Y;eZ79^H*HzO#mHP=lKOegqqSpvv& zCUg|6pka$~>+vK$0*;+h&nLOF zME-XH1#VJomzrTpR|Ag(BQ1u~jHk)1DlXb<{7q=c_7n81W_Qk2@e(4I>N^|q`UQ$* z71s%c)q>o#7;k&KczcT@V7r5lj}J!+j;%~%fATZU|F5>d;YV3HmyUWMl}E{H;h`dd z7>NiUF_Uh#$8tADYE|eV+a(;D3yb6AZI8tGLBk0)GI!!vGJ=0Tx9hJgv7>JdY5Jw@ z+l_2keo`chc!$YwpWg6DLav*Os8Hcc!j`%$ssuNU znoGZYf&4NT4lx23SF-irq9exKGr2SM&0%MVQ;tF5;n8J3K7=P*s8^l();wCs-AmaLvt8E#=-B#;PwuI8cgkp^rFQdsZ zd`u~{WP2Re+Yz^d;XM1&p71Jh4;4h+n3d%D)H^NgdBeijE|5M@Il{}^ZX+}TAuZIC zaB`>#Yu%ij?tBAD_>jyL+h?LMMV48b1bjPf(KOg!xA5BNWJZK{&@5}<;yxk<9imN9 z&inY4uak_-MHa*rbXiWGbOzik&*(bBBU4^ zJWCm>3M(a2dMO0Z&!f3I6rMdhU&dHDw*=V|P_a@0000_I4HW~z zFYx4{AR~Mu)Tvtlfb+zDMy4JHC~qzoH)mU%BbLj<*9FUk^}*Q!06yczX*jP*L`Cp1 znz518MuWGEJ!)a+-1OH2tuiAqO+Kpw&%z?0Y7nzqSQKDw`1r`b;m%gPn}%3;(slP& z-!?+$jl0cEYUt1O`vnVK9S_CdUcM}MM;JCP`C+G~U!YXB z@9za(ib#!qO5d7X9pt);?qX`|W49sPyGF$6vO8*gtC(&}=y&pb)ScqTl@_} z5_Oj*1y7rMxe5(D%KoR;?$%}dBG>jHaEGgZ#3vc1JE6rRE_PKdZwCh@d=Qni-&bM| zCdhYdjG9}%;6&ybgIFHnQWjPp+4{6?+}HoY{C#%&TgM^m*5i~!kg9O#nm3c>A(%I; zqdzXRWlM*tbi1F3-^LyVmH$liaz6L_DwyU6a`;mn;*e>;f=f+Ck*OHub4}Rvk6K*NK22f zy#_L`PBb-$dl;Eya1#d~qOiZ(d(GilbxnK9gG@GEDb}iCEBwK{C50cLLY_&cb`lvo?Q(1Anx;PhGly zf23tA0X~#JQuq8ve~6Sc-8RcPYB68gl6hicL`q-DXG5xaneDM_Bxc-qH6!*N{kEAo zw7bd2eztmxO>)5dj!bU5r^)Yw4)4e<^myJ`da-faf1w(OwP%l+GP74}1deqaT{9Q# zjhL#d=;W+M&US5<>45<_vBVoIaR$C7-^1nWi^y67Ik_cNpZ+doTxO#Z>GZRNP z!?`6KPK#@E+W6qvZPy1S3%bols~V`x@A1tJ5|-tX-wN})&uib?0UUuk?R~IAXqQ|&nsjfL zb|yLYpjm=ta<`mL5w1m%QNSx$NJ4+60TnUi&sTzG5%J2UnFWUBXSsrec~LjrMIO~J zT66|EP$hL6=h%8A3UvLTuB{!a{$2yc*@bxYASxu?oO)UVd6N+VH-d>BRxekGW-VtX zl6KJdX(g9Vn6JFkEQ>5D>u|BF|2$LGR$E_&2%Th z-zvE>Us4a?nc*h+?)My2`LKU18B#9bxEQWnl7)F9W<@I9n|L9>Ac z%(@^rwR!M^U2su&*fY}?qm(Lh>xE=fkOua@Owjym;bB>rw&nj2`!_d3_WOQT7rV~hNDiIy zDN59_*T)+?K*zkCGnhelFE1u?QBt*k=2OJVbKJbXET7fGi2;^X=EORCZcKXLyjQrx zYOLqysqK4Jdg@_Ll8v0apO0@Q!dAri=8Q%j`jz&;w8%O$#&)kajQL4GM3-(yp2a!& zI9t(IqZ&}KzWOR`U6Ar4i>t-{E7s=OL7s$}OJ}mwVUUm{&nW1JJdt}Ge3(dK+IBb5 zz%fsKJ%K#$`!a*9Shy{(X`N+5V)1-hGE0N5VGQrVTCdf+BI)O=DMw)S45iM5u7tz> z=>XYS0ir5z;-cN<>Py{_=TD82H@}3>is@~~V-9jTuCSVRez?T_(I1IjO{&B)K>4Dl z>4lbg%B!9YfQl(%Y0d&G21!fHt5*#GQJH67sB@TKWVE(Tganb23S zE@_z)HPa_~?M1GLS%{)K1-@y&apYEXR-F}ey?d069iUk1iE^Qpx=&J_04JfJ95^BC|LNT2= zu5@?FwOy%nolb|MflPB8=P}>#IpxvUd|!jcIw!%SgO6`5SUsRCXZmVhX{uH3poLs?B7`iq4b1F zKX!?m53YA5@EFBDe;^Tb?dmY41-lh-TLuNrm{a%+Il|RZjXUrfm7id5?C@8Wb4M3; zwv42kBcE6l@{KY9S0XlZ#Ze!eb9cW9R$Cd3>9kPMk}pk|boq^{JtBQ#0I_Rb^M~}2 zGd)*!ci5E`P~ipM9AW@1P+IVE}u^?9w^Oh+Mt%GP=mZI-lbyX@ZEZV`bgiFD^b z-)A+7Z(_DFXwiJM{}A}&lBk71^DAW$_#TyuuU>`=L*e&c_z*7iiT)C3$2wuVrzKZD zS&l@&SNq3cLiaY2cAsTe|55NpkQlSdBq0ASewfC>v@Bnl#wq5W7^Wz`@5P-feB`2< zWa-D*X=Sn6XQ>?6!WwM*ROT>dl#!`D%c+PLVH;?^|dN!L*oOP+Dr!Q^HgzJuHAisMc`b`dj1=5JEPxnl>P$E%_zbr|`UbpN8kf}A#$||p(K8>ajW^u>Ii^FLmS)-OR zRO-f$&%CZm0&CXUNOmP%=1YCaQmoxRRAppSfE}S)!PcOn&|)2L1ASfLU6Kdm_?JVt zm&OmAKU-x$H4TKXlq$W8PfBfn$|bm|Qg)E4Jn9N#D;DupfD*f}dd!k4HGK<;znmzH zxl@t#%)rmFUvA#>?cKDNJmZ#~F774<93@Gfp`D%W%{L=Ss!QN4*@ahfbwsMb$hkWo z%G$@Nw>*PX`L??Ua@Xc3dE35Fg>ha~s-?bYfaLmlfjVwBcjUcWzOktwJH}B8x_&Q; zMWni@ZB5bcPNjj+Da zIymzNvYr{0crD8K_R@uk+UrzWT18)iKIPm!*IM1#u0B`S_w@`7V|h6)TfDKnHL!90 zQba*h{N;6ITmbrlb%_G>T=aLHs(J;JV)d%w=mHYXA<`Au{+kG_m)#c&Hb2o=6E_{tU7$7db;VBkkbHlW>;$eE*B$G} z`odh6w073<<0TSh@Yyjv?wJDdr)W({A|fweM}?G&kVRz%<+t3=p0WoEE1CI%gk{xk zS{%c2fY##N6}wNlHXGwEOlCP&80A4w|3 z2k>o8j)%KbQD>TyOp`NB+%S9%?-n?_Q@~yG!77})v389sCE00WESeh^bN$W~^p=$v ze+#VlA@V8p)%PCtXE!2c=B<5o26QbAsefb(kOhBzFi%s^tE4-BBQrSX!VE_83t%6& z>0z|nulrc<8ad#$L&W9DMSl5oz$i%}gJZH`HdK_@XqV0I=Ih~pw*-}MaP^ef4N9V`w_9txqTuM>M zhO`Gp5F+1~k5X5*@MICr4C`B;?G$bt&XEMZ<(RNp1ulGxGB0^uivA%R=2`>mS-li#)S z&CyP?e4`wwQQUoN&5^VE==?Ni{c$Jt+Zpd*#uGv%CK5h_?#ClU5{RdXjlZ|CS!yi_YhSvBIWvzGf38l3{2{; zt3Q71u=()%jhP9#$rai|fUB2_fkzzuaq>m;HXoPC81Fp}?+rkB7}FXL-vrQ#0r?KR03p{ zxu_RPHumk_@#_tI@noA1j}QY1!is$X%}lXM{O$SdEzZk2N2HqyBqn~{RwYERtS2TG z=5rK_Q)FT#7HJja*Vh3@x}lC;C3E>gb8gKCECGgOiw$S$M_3!-d#*nKPYMd#Xk1(< zqUMDBr)H;K?@s@e8(iHWck6b`4@bh0gj)+%9N~7t6se6sJ3EP?FwQnuF&`%v!tDhB zAgkcxfjcdvzr|lA|oRM7KehNP!K@^2|1?mQs-J4=j4J!{sE77|BVF#A7CGp z3m76M4t8<^|5d}?L)D7_@|#2dQN!JcaLEHUz`8qox}mYEURb;b&tD-h=s)ybJlz~m z!@;1zSVycALDZdK74kQe>Y7NsKQvA#u){gIoN5us{+px+&h}5T{^r}s%4s-%b%db) z2kzgbe~`8jB2=8wo+s{Us>lIP>?1JFXdDLdYbcG85Qo@Efuzwg5+DhvBnl*B zgT;W*a5x+#DS?rZhDiMdN)zwyfx@G)Cr|`%F&qKM28*(R!C?>(R0a(LNl0TbAZckC zC`b|tk%HSwp|BV@>MszwZa6|!q8$I~)d>`a0ENOrq@if6BnT!UEk%HWNrF(~Xd4g; zDlI9F!osmqaG6sm3>u;4?B;|bq!Z_avcrO1@OGyQCxj!e=xNFUp3o}>jq z2!=o`>ZDEy0H+#+SP;r?Sd@pen~}4#qa5(WC9V_A)AHt${go6AoI63n_oU)~t9e7L z>#w(8Tfh-_y2QnGTDAxj`j-)Rlou9rYKWlsYYA=ipgq=aY)1#}t>m*6Rt zLVx$g+a7zulQ>iYBn}0MOBz9-2&fc793~r7~c$ZWLKRZg2Cz`kK z8nHUHwc4}SdyD$zn8MAu`uBTB>z_V-Qb%iloJ$eZ8T6$FVH%jI7XZB% z<%3HYhYe`)w-^K~8=8#J)ksfhP#mzpi=huA5hJHtMHr&3-RP+bjj5$)HiCY8E zd|5s43;eFFCyU4@koSIbp`wniZb04;cqIBw&t1sV!s-&VdEGlfy6oWr`(oILq4+j? z^L3$b8L3TmH34=}rVbs^JD~H;{hghfD~eUaI_V@!9tbI?>e8Ijdsxq&XJ?5JiX-~6QiJ2K0-qj=#nXga=)(OFY z0}0`&!+!OU0BRPO7sJ%V4o<~4NdgxZ7M!mM@aGW0nwG~)Xh7GM{W7f6*wD8CdRHxp zq)V(jAHRovnP;v}B7{7tO2$BNPi7|W)s_xckuhLzch_9#=<8Sdbt5tc0FBA^6I@%e z*6llYj@@&!1%UdcBL_&8WY3lt085A6FhQyIU?jA83Guqe%ETrm>~lRLIn^MLVR(GY z?M2jh34;!_*_`b{e_806Yb)Ky@flMNyL)^2DhZAd3;JZ+n*PMf_rg4RLviSf+x*%u d$L^r-0J=2sY1U6W_fM){Q&mT$M9Dhne*kRXJrn={ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/wheel.png b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/wheel.png deleted file mode 100644 index 07b1e33132e430476307b9d5f57d35b9da9f0097..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1632 zcmV-m2A}zfP)92ut1VzFk$_)z#&eG=!_GtF`6j<#qh~zSU~2zr4KgTEpk0R5Zi;5%0L} za19oI4fJ6fr!CXFVZ*QMT4OAvf^@W|D z&ugRef;NuH?PFDGS0a3KbJGRU3sFiHWjO=)aqmOzzpk#Xe(!WT-zLiphr{2Vo}LoU z;+)O#s4KHGxeFQU{tnW2%JO=`*VorQ+|Ct6xtyf9F1NO}22umiqV=Vvr2|othi&&Z zHa7kc1yqD#uP4S{eHfw48Px1^tToh_&pxEzlK^pJ*C!G{kg!s+mr$*vnCs;vNE{O9 zfcJdmG?H!wzKE*zr>6*|da}8>`B@eKvof6e%3$C>_-xuq*o^9xxK*k0gb@SEe(kul zt?j5Ja43!yjV_cdK_dKadG)<*$d^r5eJf$wt;c)vj^H8?B26EG>Ti2DqtXGD85tYN zX0R{I;6L^xBC^VQOb0FtWt*N?iL@$gdxRUM_ZRw zC#t$+3)CTPB$(RX8DBg{PMDDkhtbnjtK>G$OSV8A(&+0K+jDL`$&vr(giUnOhOCM= z1+pBpxycqFX>_!!EswtT#i7=?a*l;cZ#&xPixPAKBqG@YSSBw_+ghZKc5;&~2zMQo zFGYcX$1^Y1*mecdUmedA{wWAsI|`flCIK`|wt$*6`rLQC`d6iC)V2~K`&|&(0xHs; z6(!-H7H2Os^j&@eK>EK@!i$b8|1cnG`b%4WGW<{YzYY>^<$ZFF3O`1`>xHK~aF&HH-s``*cqOn#c$3xikCb%1|hC znj-9r?fQ-&%b>ksRNoo9&b0L~uskd3v2K;%q36UT1E;BFbLRBW6Tw&KQIr8!ZyO`c z44^}qRl7Vlgv&;qBp6@*iS5M1c3iq<(i{?7BXy5L2**)Qt_@NHfs_nuyEEHEE>XTE z1~cJV#jt53FdLT(*L##?@B9Z z63hnlnVh`N@Xn>tN!X}1^C+AyBU6ZAm!}%XBnCLZ&^%vQcx3WVoPG9&cqWoZd^qHY z*E!Nop%a5nr!($^W?8E7GXkpbo^}ma6E>X*&5kx?X7hdLaXjceted@TB6?KL8LLE? z&?b5=0IAtFR@#SGCR_l-dxm%-i$!LL2Dgkh)Fw{d%h`K*CC_Z3q*RO&%y7@RABLv% e%RdB(iGKhQFK?{O$+Euy0000 #include #include -#include #include #include From 52ca290958470b4e93371efe338edd8d3e72a9db Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 23 Apr 2024 03:38:24 +0000 Subject: [PATCH 13/77] style(pre-commit): autofix --- .../README.md | 19 ++++---- .../include/mission_details_display.hpp | 15 ++++--- .../remaining_distance_time_display.hpp | 15 ++++--- .../src/mission_details_display.cpp | 44 ++++++++++-------- .../src/overlay_text_display.cpp | 3 +- .../src/remaining_distance_time_display.cpp | 45 ++++++++++--------- planning/behavior_path_planner/README.md | 18 ++++---- .../behavior_path_planner_node.hpp | 9 ++-- .../src/behavior_path_planner_node.cpp | 17 ++++--- 9 files changed, 101 insertions(+), 84 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md index 8d71cde7b8763..ef69547087893 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md @@ -13,10 +13,9 @@ This plugin provides a visual and easy-to-understand display of mission details ### Input -| Name | Type | Description | -| ------------------------------------------------------- | ------------------------------------------------------- | ------------------------------------ | -| `/planning/mission_remaining_distance_time` | `autoware_planning_msgs::msg::MissionRemainingDistanceTime` | The topic is for mission remaining distance and time Data | - +| Name | Type | Description | +| ------------------------------------------- | ----------------------------------------------------------- | --------------------------------------------------------- | +| `/planning/mission_remaining_distance_time` | `autoware_planning_msgs::msg::MissionRemainingDistanceTime` | The topic is for mission remaining distance and time Data | ## Parameter @@ -24,12 +23,12 @@ This plugin provides a visual and easy-to-understand display of mission details #### SignalDisplay -| Name | Type | Default Value | Description | -| ------------------------ | ------ | -------------------- | --------------------------------- | -| `property_width_` | int | 300 | Width of the plotter window [px] | -| `property_height_` | int | 100 | Height of the plotter window [px] | -| `property_left_` | int | 800 | Left of the plotter window [px] | -| `property_top_` | int | 10 | Top of the plotter window [px] | +| Name | Type | Default Value | Description | +| ------------------ | ---- | ------------- | --------------------------------- | +| `property_width_` | int | 300 | Width of the plotter window [px] | +| `property_height_` | int | 100 | Height of the plotter window [px] | +| `property_left_` | int | 800 | Left of the plotter window [px] | +| `property_top_` | int | 10 | Top of the plotter window [px] | ## Assumptions / Known limits diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp index 1c2df0709627a..340f50c6b094a 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIGNAL_DISPLAY_HPP_ -#define SIGNAL_DISPLAY_HPP_ +#ifndef MISSION_DETAILS_DISPLAY_HPP_ +#define MISSION_DETAILS_DISPLAY_HPP_ #ifndef Q_MOC_RUN #include "overlay_utils.hpp" #include "remaining_distance_time_display.hpp" @@ -64,7 +64,8 @@ private Q_SLOTS: rviz_common::properties::IntProperty * property_height_; rviz_common::properties::IntProperty * property_left_; rviz_common::properties::IntProperty * property_top_; - std::unique_ptr remaining_distance_time_topic_property_; + std::unique_ptr + remaining_distance_time_topic_property_; void drawHorizontalRoundedRectangle(QPainter & painter, const QRectF & backgroundRect); void drawVerticalRoundedRectangle(QPainter & painter, const QRectF & backgroundRect); @@ -72,13 +73,15 @@ private Q_SLOTS: std::unique_ptr remaining_distance_time_display_; - rclcpp::Subscription::SharedPtr remaining_distance_time_sub_; + rclcpp::Subscription::SharedPtr + remaining_distance_time_sub_; std::mutex property_mutex_; - void updateRemainingDistanceTimeData(const autoware_planning_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); + void updateRemainingDistanceTimeData( + const autoware_planning_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); void drawWidget(QImage & hud); }; } // namespace autoware_mission_details_overlay_rviz_plugin -#endif // SIGNAL_DISPLAY_HPP_ +#endif // MISSION_DETAILS_DISPLAY_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp index 6ccc319aad158..bc9ad92b08bce 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef REMAINING_DISTANCE_TIME_HPP_ -#define REMAINING_DISTANCE_TIME_HPP_ +#ifndef REMAINING_DISTANCE_TIME_DISPLAY_HPP_ +#define REMAINING_DISTANCE_TIME_DISPLAY_HPP_ #include "overlay_utils.hpp" #include @@ -37,16 +37,17 @@ class RemainingDistanceTimeDisplay public: RemainingDistanceTimeDisplay(); void drawRemainingDistanceTimeDisplay(QPainter & painter, const QRectF & backgroundRect); - void updateRemainingDistanceTimeData(const autoware_planning_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); + void updateRemainingDistanceTimeData( + const autoware_planning_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); private: double remaining_distance_; // Internal variable to store remaining distance - uint32_t hours_; // Internal variable to store remaining time hours - uint32_t minutes_; // Internal variable to store remaining time minutes - uint32_t seconds_; // Internal variable to store remaining time seconds + uint32_t hours_; // Internal variable to store remaining time hours + uint32_t minutes_; // Internal variable to store remaining time minutes + uint32_t seconds_; // Internal variable to store remaining time seconds QColor gray = QColor(194, 194, 194); }; } // namespace autoware_mission_details_overlay_rviz_plugin -#endif // REMAINING_DISTANCE_TIME_HPP_ +#endif // REMAINING_DISTANCE_TIME_DISPLAY_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp index b9be347561cd7..3eec8a534fec3 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -67,10 +67,12 @@ void MissionDetailsDisplay::onInitialize() auto rviz_ros_node = context_->getRosNodeAbstraction(); - remaining_distance_time_topic_property_ = std::make_unique( - "Remaining Distance and Time Topic", "/planning/mission_remaining_distance_time", - "autoware_planning_msgs/msg/MissionRemainingDistanceTime", "Topic for Mission Remaining Distance and Time Data", this, - SLOT(topic_updated_remaining_distance_time())); + remaining_distance_time_topic_property_ = + std::make_unique( + "Remaining Distance and Time Topic", "/planning/mission_remaining_distance_time", + "autoware_planning_msgs/msg/MissionRemainingDistanceTime", + "Topic for Mission Remaining Distance and Time Data", this, + SLOT(topic_updated_remaining_distance_time())); remaining_distance_time_topic_property_->initialize(rviz_ros_node); } @@ -79,12 +81,13 @@ void MissionDetailsDisplay::setupRosSubscriptions() // Don't create a node, just use the one from the parent class auto rviz_node_ = context_->getRosNodeAbstraction().lock()->get_raw_node(); - remaining_distance_time_sub_ = rviz_node_->create_subscription( - "/planning/mission_remaining_distance_time", - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), - [this](const autoware_planning_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { - updateRemainingDistanceTimeData(msg); - }); + remaining_distance_time_sub_ = + rviz_node_->create_subscription( + "/planning/mission_remaining_distance_time", + rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + [this](const autoware_planning_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { + updateRemainingDistanceTimeData(msg); + }); } MissionDetailsDisplay::~MissionDetailsDisplay() @@ -176,7 +179,8 @@ void MissionDetailsDisplay::drawHorizontalRoundedRectangle( painter.drawRoundedRect( backgroundRect, backgroundRect.height() / 2, backgroundRect.height() / 2); // Circular ends } -void MissionDetailsDisplay::drawVerticalRoundedRectangle(QPainter & painter, const QRectF & backgroundRect) +void MissionDetailsDisplay::drawVerticalRoundedRectangle( + QPainter & painter, const QRectF & backgroundRect) { painter.setRenderHint(QPainter::Antialiasing, true); QColor colorFromHSV; @@ -222,16 +226,18 @@ void MissionDetailsDisplay::topic_updated_remaining_distance_time() // resubscribe to the topic remaining_distance_time_sub_.reset(); auto rviz_ros_node = context_->getRosNodeAbstraction().lock(); - remaining_distance_time_sub_ = rviz_ros_node->get_raw_node() - ->create_subscription( - remaining_distance_time_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), - [this](const autoware_planning_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { - updateRemainingDistanceTimeData(msg); - }); + remaining_distance_time_sub_ = + rviz_ros_node->get_raw_node() + ->create_subscription( + remaining_distance_time_topic_property_->getTopicStd(), + rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + [this](const autoware_planning_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { + updateRemainingDistanceTimeData(msg); + }); } } // namespace autoware_mission_details_overlay_rviz_plugin #include -PLUGINLIB_EXPORT_CLASS(autoware_mission_details_overlay_rviz_plugin::MissionDetailsDisplay, rviz_common::Display) +PLUGINLIB_EXPORT_CLASS( + autoware_mission_details_overlay_rviz_plugin::MissionDetailsDisplay, rviz_common::Display) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp index 88c30a2d1ec71..10a7b8cb3e4ca 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp @@ -553,4 +553,5 @@ void OverlayTextDisplay::updateLineWidth() } // namespace autoware_mission_details_overlay_rviz_plugin #include -PLUGINLIB_EXPORT_CLASS(autoware_mission_details_overlay_rviz_plugin::OverlayTextDisplay, rviz_common::Display) +PLUGINLIB_EXPORT_CLASS( + autoware_mission_details_overlay_rviz_plugin::OverlayTextDisplay, rviz_common::Display) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index ab81959296e16..62336ff180663 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -34,7 +34,8 @@ namespace autoware_mission_details_overlay_rviz_plugin { -RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() : remaining_distance_(0.0), hours_(0), minutes_(0), seconds_(0) +RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() +: remaining_distance_(0.0), hours_(0), minutes_(0), seconds_(0) { std::string package_path = ament_index_cpp::get_package_share_directory("autoware_mission_details_overlay_rviz_plugin"); @@ -54,7 +55,7 @@ void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData( { try { remaining_distance_ = msg->remaining_distance; - hours_ = msg->remaining_hours; + hours_ = msg->remaining_hours; minutes_ = msg->remaining_minutes; seconds_ = msg->remaining_seconds; } catch (const std::exception & e) { @@ -63,7 +64,8 @@ void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData( } } -void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay(QPainter & painter, const QRectF & backgroundRect) +void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( + QPainter & painter, const QRectF & backgroundRect) { QFont referenceFont("Quicksand", 80, QFont::Bold); painter.setFont(referenceFont); @@ -80,23 +82,24 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay(QPainter & p QFont remainingDistancValueFont("Quicksand", fontSize); painter.setFont(remainingDistancValueFont); - QPointF remainingDistancePos( - remainingDistReferencePos.x() + 100 , remainingDistReferencePos.y()); + QPointF remainingDistancePos(remainingDistReferencePos.x() + 100, remainingDistReferencePos.y()); painter.setPen(gray); painter.drawText(remainingDistancePos, remainingDistanceValue); - + // Remaining distance text QFont remainingDistancTextFont("Quicksand", 12); painter.setFont(remainingDistancTextFont); QString remainingDistText = "Remaining Distance: "; - QPointF remainingDistancTextPos(remainingDistReferencePos.x() - 80, remainingDistReferencePos.y()); + QPointF remainingDistancTextPos( + remainingDistReferencePos.x() - 80, remainingDistReferencePos.y()); painter.drawText(remainingDistancTextPos, remainingDistText); - + // Remaining distance unit QFont remainingDistancUnitFont("Quicksand", 12); painter.setFont(remainingDistancUnitFont); QString remainingDistUnitText = " m"; - QPointF remainingDistancUnitPos(remainingDistReferencePos.x() + 150, remainingDistReferencePos.y()); + QPointF remainingDistancUnitPos( + remainingDistReferencePos.x() + 150, remainingDistReferencePos.y()); painter.drawText(remainingDistancUnitPos, remainingDistUnitText); // Remaining time text @@ -105,17 +108,16 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay(QPainter & p QString remainingTimeText = "Remaining Time: "; QPointF remainingTimeTextPos(remainingTimeReferencePos.x() - 80, remainingTimeReferencePos.y()); painter.drawText(remainingTimeTextPos, remainingTimeText); - + // Remaining time value - hours QString remaininghoursValue = QString::number(hours_, 'f', 0); QFont remaininghoursValueFont("Quicksand", fontSize); painter.setFont(remaininghoursValueFont); - QPointF remaininghoursValuePos( - remainingTimeReferencePos.x() + 50 , remainingTimeReferencePos.y()); + QPointF remaininghoursValuePos(remainingTimeReferencePos.x() + 50, remainingTimeReferencePos.y()); painter.setPen(gray); painter.drawText(remaininghoursValuePos, remaininghoursValue); - + // Remaining time hours separator QFont hoursSeparatorTextFont("Quicksand", 12); painter.setFont(hoursSeparatorTextFont); @@ -130,34 +132,35 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay(QPainter & p painter.setFont(remainingminutesValueFont); QPointF remainingminutesValuePos( - remainingTimeReferencePos.x() + 100 , remainingTimeReferencePos.y()); + remainingTimeReferencePos.x() + 100, remainingTimeReferencePos.y()); painter.setPen(gray); painter.drawText(remainingminutesValuePos, remainingminutesValue); - + // Remaining time minutes separator QFont minutesSeparatorTextFont("Quicksand", 12); painter.setFont(minutesSeparatorTextFont); QString minutesSeparatorText = " m : "; - QPointF minutesSeparatorTextPos(remainingTimeReferencePos.x() + 120, remainingTimeReferencePos.y()); + QPointF minutesSeparatorTextPos( + remainingTimeReferencePos.x() + 120, remainingTimeReferencePos.y()); painter.drawText(minutesSeparatorTextPos, minutesSeparatorText); - + // Remaining time value - seconds QString remainingsecondsValue = QString::number(seconds_, 'f', 0); QFont remainingsecondsValueFont("Quicksand", fontSize); painter.setFont(remainingsecondsValueFont); QPointF remainingsecondValuePos( - remainingTimeReferencePos.x() + 160 , remainingTimeReferencePos.y()); + remainingTimeReferencePos.x() + 160, remainingTimeReferencePos.y()); painter.setPen(gray); painter.drawText(remainingsecondValuePos, remainingsecondsValue); - + // Remaining time seconds separator QFont secondsSeparatorTextFont("Quicksand", 12); painter.setFont(secondsSeparatorTextFont); QString secondsSeparatorText = " s"; - QPointF secondsSeparatorTextPos(remainingTimeReferencePos.x() + 180, remainingTimeReferencePos.y()); + QPointF secondsSeparatorTextPos( + remainingTimeReferencePos.x() + 180, remainingTimeReferencePos.y()); painter.drawText(secondsSeparatorTextPos, secondsSeparatorText); - } } // namespace autoware_mission_details_overlay_rviz_plugin diff --git a/planning/behavior_path_planner/README.md b/planning/behavior_path_planner/README.md index 369c2c2aa2531..41911b22ac6e9 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -107,15 +107,15 @@ The Planner Manager's responsibilities include: ### Output -| Name | Type | Description | QoS Durability | -| :---------------------------- | :------------------------------------------------------- | :--------------------------------------------------------------------------------------------- | ----------------- | -| ~/output/path | `autoware_auto_planning_msgs::msg::PathWithLaneId` | the path generated by modules. | `volatile` | -| ~/output/turn_indicators_cmd | `autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand` | turn indicators command. | `volatile` | -| ~/output/hazard_lights_cmd | `autoware_auto_vehicle_msgs::msg::HazardLightsCommand` | hazard lights command. | `volatile` | -| ~/output/modified_goal | `autoware_planning_msgs::msg::PoseWithUuidStamped` | output modified goal commands. | `transient_local` | -| ~/output/stop_reasons | `tier4_planning_msgs::msg::StopReasonArray` | describe the reason for ego vehicle stop | `volatile` | -| ~/output/reroute_availability | `tier4_planning_msgs::msg::RerouteAvailability` | the path the module is about to take. to be executed as soon as external approval is obtained. | `volatile` | -| ~/output/mission_remaining_distance_time | `autoware_planning_msgs::msg::MissionRemainingDistanceTime` | information about mission remaining distance and time. | `volatile` | +| Name | Type | Description | QoS Durability | +| :--------------------------------------- | :---------------------------------------------------------- | :--------------------------------------------------------------------------------------------- | ----------------- | +| ~/output/path | `autoware_auto_planning_msgs::msg::PathWithLaneId` | the path generated by modules. | `volatile` | +| ~/output/turn_indicators_cmd | `autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand` | turn indicators command. | `volatile` | +| ~/output/hazard_lights_cmd | `autoware_auto_vehicle_msgs::msg::HazardLightsCommand` | hazard lights command. | `volatile` | +| ~/output/modified_goal | `autoware_planning_msgs::msg::PoseWithUuidStamped` | output modified goal commands. | `transient_local` | +| ~/output/stop_reasons | `tier4_planning_msgs::msg::StopReasonArray` | describe the reason for ego vehicle stop | `volatile` | +| ~/output/reroute_availability | `tier4_planning_msgs::msg::RerouteAvailability` | the path the module is about to take. to be executed as soon as external approval is obtained. | `volatile` | +| ~/output/mission_remaining_distance_time | `autoware_planning_msgs::msg::MissionRemainingDistanceTime` | information about mission remaining distance and time. | `volatile` | ### Debug diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index 6a8ebb24875b9..ee2f8ee11fe88 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -31,8 +31,8 @@ #include #include #include -#include #include +#include #include #include #include @@ -63,8 +63,8 @@ using autoware_auto_vehicle_msgs::msg::HazardLightsCommand; using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand; using autoware_perception_msgs::msg::TrafficSignalArray; using autoware_planning_msgs::msg::LaneletRoute; -using autoware_planning_msgs::msg::PoseWithUuidStamped; using autoware_planning_msgs::msg::MissionRemainingDistanceTime; +using autoware_planning_msgs::msg::PoseWithUuidStamped; using geometry_msgs::msg::Pose; using nav_msgs::msg::OccupancyGrid; using nav_msgs::msg::Odometry; @@ -111,7 +111,8 @@ class BehaviorPathPlannerNode : public rclcpp::Node rclcpp::Subscription::SharedPtr lateral_offset_subscriber_; rclcpp::Subscription::SharedPtr operation_mode_subscriber_; rclcpp::Publisher::SharedPtr path_publisher_; - rclcpp::Publisher::SharedPtr mission_remaining_distance_time_publisher_; + rclcpp::Publisher::SharedPtr + mission_remaining_distance_time_publisher_; rclcpp::Publisher::SharedPtr turn_signal_publisher_; rclcpp::Publisher::SharedPtr hazard_signal_publisher_; rclcpp::Publisher::SharedPtr bound_publisher_; @@ -193,7 +194,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node // debug rclcpp::Publisher::SharedPtr debug_avoidance_msg_array_publisher_; rclcpp::Publisher::SharedPtr debug_turn_signal_info_publisher_; - + /** * @brief compute mission remaining distance and time */ diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 21397169a935d..840ed99afe5a1 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -495,14 +495,16 @@ void BehaviorPathPlannerNode::computeTurnSignal( publish_steering_factor(planner_data, turn_signal); } -void BehaviorPathPlannerNode::computeMissionRemainingDistanceTime(const behavior_path_planner::PlanResult & path) +void BehaviorPathPlannerNode::computeMissionRemainingDistanceTime( + const behavior_path_planner::PlanResult & path) { - remaining_distance_time_.remaining_distance = - motion_utils::calcSignedArcLength(path->points, planner_data_->self_odometry->pose.pose.position, goal_pose_.position); + remaining_distance_time_.remaining_distance = motion_utils::calcSignedArcLength( + path->points, planner_data_->self_odometry->pose.pose.position, goal_pose_.position); - geometry_msgs::msg::Vector3 current_vehicle_velocity = planner_data_->self_odometry->twist.twist.linear; + geometry_msgs::msg::Vector3 current_vehicle_velocity = + planner_data_->self_odometry->twist.twist.linear; - double current_vehicle_velocity_norm = std::sqrt( + double current_vehicle_velocity_norm = std::sqrt( current_vehicle_velocity.x * current_vehicle_velocity.x + current_vehicle_velocity.y * current_vehicle_velocity.y); @@ -515,14 +517,15 @@ void BehaviorPathPlannerNode::computeMissionRemainingDistanceTime(const behavior return; } - double remaining_time = remaining_distance_time_.remaining_distance / current_vehicle_velocity_norm; + double remaining_time = + remaining_distance_time_.remaining_distance / current_vehicle_velocity_norm; remaining_distance_time_.remaining_time = remaining_time; remaining_distance_time_.hours = static_cast(remaining_time / 3600.0); remaining_time = std::fmod(remaining_time, 3600); remaining_distance_time_.minutes = static_cast(remaining_time / 60.0); remaining_distance_time_.seconds = static_cast(std::fmod(remaining_time, 60)); - return ; + return; } void BehaviorPathPlannerNode::publish_steering_factor( From 73a3428bf61cbb9958c117177bb0e2280e3fb985 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Wed, 24 Apr 2024 17:27:49 +0200 Subject: [PATCH 14/77] feat(remaining_dist_eta): change dependency from autoware_planning_msgs to autoware_internal_msgs Signed-off-by: AhmedEbrahim --- .../CMakeLists.txt | 3 ++- .../include/mission_details_display.hpp | 4 ++-- .../include/remaining_distance_time_display.hpp | 4 ++-- .../package.xml | 2 +- .../src/mission_details_display.cpp | 12 ++++++------ .../src/remaining_distance_time_display.cpp | 2 +- .../behavior_path_planner_node.hpp | 4 ++-- planning/behavior_path_planner/package.xml | 1 + 8 files changed, 17 insertions(+), 15 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt index 6f7ca17f3d7b2..46b82d3fa6031 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt @@ -7,7 +7,7 @@ find_package(ament_cmake REQUIRED) find_package(autoware_auto_vehicle_msgs REQUIRED) find_package(tier4_planning_msgs REQUIRED) find_package(autoware_perception_msgs REQUIRED) -find_package(autoware_planning_msgs REQUIRED) +find_package(autoware_internal_msgs REQUIRED) ament_auto_find_build_dependencies() find_package(autoware_overlay_msgs REQUIRED) @@ -85,6 +85,7 @@ ament_target_dependencies( autoware_auto_vehicle_msgs tier4_planning_msgs autoware_perception_msgs + autoware_internal_msgs ) ament_export_include_directories(include) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp index 340f50c6b094a..ec97f13fb6b97 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp @@ -73,13 +73,13 @@ private Q_SLOTS: std::unique_ptr remaining_distance_time_display_; - rclcpp::Subscription::SharedPtr + rclcpp::Subscription::SharedPtr remaining_distance_time_sub_; std::mutex property_mutex_; void updateRemainingDistanceTimeData( - const autoware_planning_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); + const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); void drawWidget(QImage & hud); }; } // namespace autoware_mission_details_overlay_rviz_plugin diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp index bc9ad92b08bce..4bc0f8a7b903c 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp @@ -23,7 +23,7 @@ #include #include -#include "autoware_planning_msgs/msg/mission_remaining_distance_time.hpp" +#include #include #include @@ -38,7 +38,7 @@ class RemainingDistanceTimeDisplay RemainingDistanceTimeDisplay(); void drawRemainingDistanceTimeDisplay(QPainter & painter, const QRectF & backgroundRect); void updateRemainingDistanceTimeData( - const autoware_planning_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); + const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); private: double remaining_distance_; // Internal variable to store remaining distance diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml index 4b072b6379e5b..a9139c8c3b235 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml @@ -14,7 +14,7 @@ autoware_auto_vehicle_msgs autoware_overlay_msgs autoware_perception_msgs - autoware_planning_msgs + autoware_internal_msgs boost rviz_common rviz_ogre_vendor diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp index 3eec8a534fec3..ba4217a2ab896 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -70,7 +70,7 @@ void MissionDetailsDisplay::onInitialize() remaining_distance_time_topic_property_ = std::make_unique( "Remaining Distance and Time Topic", "/planning/mission_remaining_distance_time", - "autoware_planning_msgs/msg/MissionRemainingDistanceTime", + "autoware_internal_msgs/msg/MissionRemainingDistanceTime", "Topic for Mission Remaining Distance and Time Data", this, SLOT(topic_updated_remaining_distance_time())); remaining_distance_time_topic_property_->initialize(rviz_ros_node); @@ -82,10 +82,10 @@ void MissionDetailsDisplay::setupRosSubscriptions() auto rviz_node_ = context_->getRosNodeAbstraction().lock()->get_raw_node(); remaining_distance_time_sub_ = - rviz_node_->create_subscription( + rviz_node_->create_subscription( "/planning/mission_remaining_distance_time", rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), - [this](const autoware_planning_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { + [this](const autoware_internal_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { updateRemainingDistanceTimeData(msg); }); } @@ -134,7 +134,7 @@ void MissionDetailsDisplay::onDisable() } void MissionDetailsDisplay::updateRemainingDistanceTimeData( - const autoware_planning_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg) + const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg) { std::lock_guard lock(property_mutex_); @@ -228,10 +228,10 @@ void MissionDetailsDisplay::topic_updated_remaining_distance_time() auto rviz_ros_node = context_->getRosNodeAbstraction().lock(); remaining_distance_time_sub_ = rviz_ros_node->get_raw_node() - ->create_subscription( + ->create_subscription( remaining_distance_time_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), - [this](const autoware_planning_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { + [this](const autoware_internal_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { updateRemainingDistanceTimeData(msg); }); } diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index 62336ff180663..dabbe3b269513 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -51,7 +51,7 @@ RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() } void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData( - const autoware_planning_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg) + const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg) { try { remaining_distance_ = msg->remaining_distance; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index ee2f8ee11fe88..7113f2b6e95c0 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -31,7 +31,7 @@ #include #include #include -#include +#include #include #include #include @@ -63,7 +63,7 @@ using autoware_auto_vehicle_msgs::msg::HazardLightsCommand; using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand; using autoware_perception_msgs::msg::TrafficSignalArray; using autoware_planning_msgs::msg::LaneletRoute; -using autoware_planning_msgs::msg::MissionRemainingDistanceTime; +using autoware_internal_msgs::msg::MissionRemainingDistanceTime; using autoware_planning_msgs::msg::PoseWithUuidStamped; using geometry_msgs::msg::Pose; using nav_msgs::msg::OccupancyGrid; diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index 7f50c61a8343a..7a37fa2767615 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -40,6 +40,7 @@ autoware_auto_planning_msgs autoware_auto_tf2 autoware_auto_vehicle_msgs + autoware_internal_msgs autoware_perception_msgs behavior_path_planner_common freespace_planning_algorithms From 62df4033393d098b3256297e0ac0a8fcec24c364 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 24 Apr 2024 15:31:47 +0000 Subject: [PATCH 15/77] style(pre-commit): autofix --- .../autoware_mission_details_overlay_rviz_plugin/package.xml | 2 +- .../behavior_path_planner/behavior_path_planner_node.hpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml index a9139c8c3b235..e50da3d55de46 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml @@ -12,9 +12,9 @@ BSD-3-Clause autoware_auto_vehicle_msgs + autoware_internal_msgs autoware_overlay_msgs autoware_perception_msgs - autoware_internal_msgs boost rviz_common rviz_ogre_vendor diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index 7113f2b6e95c0..c01d6f58d83de 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -30,8 +30,8 @@ #include #include #include -#include #include +#include #include #include #include @@ -61,9 +61,9 @@ using autoware_auto_planning_msgs::msg::Path; using autoware_auto_planning_msgs::msg::PathWithLaneId; using autoware_auto_vehicle_msgs::msg::HazardLightsCommand; using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand; +using autoware_internal_msgs::msg::MissionRemainingDistanceTime; using autoware_perception_msgs::msg::TrafficSignalArray; using autoware_planning_msgs::msg::LaneletRoute; -using autoware_internal_msgs::msg::MissionRemainingDistanceTime; using autoware_planning_msgs::msg::PoseWithUuidStamped; using geometry_msgs::msg::Pose; using nav_msgs::msg::OccupancyGrid; From 10e5f81ed849132a29f8ed12720e4fb75ca43ebd Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Thu, 25 Apr 2024 15:12:13 +0200 Subject: [PATCH 16/77] feat(remaining_dist_eta): reverting back to route_handler and lanelet2 APIs approach after receiving the feedback that behavior planner path will not be enough in larger missions Signed-off-by: AhmedEbrahim --- .../behavior_path_planner_node.hpp | 17 +---- .../src/behavior_path_planner_node.cpp | 59 +++++------------ .../include/route_handler/route_handler.hpp | 15 +++++ planning/route_handler/src/route_handler.cpp | 65 +++++++++++++++++++ 4 files changed, 98 insertions(+), 58 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index c01d6f58d83de..a4cb17aaf4a53 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -78,14 +78,6 @@ using tier4_planning_msgs::msg::StopReasonArray; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; -struct RemainingDistanceTime -{ - double remaining_distance; - double remaining_time; - uint32_t hours; - uint32_t minutes; - uint32_t seconds; -}; class BehaviorPathPlannerNode : public rclcpp::Node { @@ -139,7 +131,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node bool has_received_route_{false}; Pose goal_pose_; - RemainingDistanceTime remaining_distance_time_; + route_handler::RemainingDistanceTime remaining_distance_time_; std::mutex mutex_pd_; // mutex for planner_data_ std::mutex mutex_manager_; // mutex for bt_manager_ or planner_manager_ @@ -195,11 +187,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_avoidance_msg_array_publisher_; rclcpp::Publisher::SharedPtr debug_turn_signal_info_publisher_; - /** - * @brief compute mission remaining distance and time - */ - void computeMissionRemainingDistanceTime(const behavior_path_planner::PlanResult & path); - /** * @brief publish reroute availability */ @@ -241,7 +228,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node /** * @brief publish mission remaining distance and time */ - void publishMissionRemainingDistanceTime() const; + void publishMissionRemainingDistanceTime(const route_handler::RemainingDistanceTime & remaining_distance_time_) const; /** * @brief convert path with lane id to path for publish path candidate diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 840ed99afe5a1..2d472263a0561 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -394,18 +394,24 @@ void BehaviorPathPlannerNode::run() if (!controlled_by_autoware_autonomously && !planner_manager_->hasApprovedModules()) planner_manager_->resetCurrentRouteLanelet(planner_data_); + if (planner_data_->route_handler->isHandlerReady()) { + // compute mission remaining distance + planner_data_->route_handler->getRemainingDistance( + planner_data_->self_odometry->pose.pose, goal_pose_, remaining_distance_time_); + + // compute mission remaining time + planner_data_->route_handler->getRemainingTime(planner_data_->self_odometry->twist.twist.linear, remaining_distance_time_); + + // publish remaining distance and time + publishMissionRemainingDistanceTime(remaining_distance_time_); + } + // run behavior planner const auto output = planner_manager_->run(planner_data_); // path handling const auto path = getPath(output, planner_data_, planner_manager_); - // compute remaining distance and time based on generated path - computeMissionRemainingDistanceTime(path); - - // publish remaining distance and time - publishMissionRemainingDistanceTime(); - // update planner data planner_data_->prev_output_path = path; @@ -495,39 +501,6 @@ void BehaviorPathPlannerNode::computeTurnSignal( publish_steering_factor(planner_data, turn_signal); } -void BehaviorPathPlannerNode::computeMissionRemainingDistanceTime( - const behavior_path_planner::PlanResult & path) -{ - remaining_distance_time_.remaining_distance = motion_utils::calcSignedArcLength( - path->points, planner_data_->self_odometry->pose.pose.position, goal_pose_.position); - - geometry_msgs::msg::Vector3 current_vehicle_velocity = - planner_data_->self_odometry->twist.twist.linear; - - double current_vehicle_velocity_norm = std::sqrt( - current_vehicle_velocity.x * current_vehicle_velocity.x + - current_vehicle_velocity.y * current_vehicle_velocity.y); - - if (remaining_distance_time_.remaining_distance < 0.01 || current_vehicle_velocity_norm < 0.01) { - remaining_distance_time_.remaining_distance = 0.0; - remaining_distance_time_.remaining_time = 0.0; - remaining_distance_time_.hours = 0; - remaining_distance_time_.minutes = 0; - remaining_distance_time_.seconds = 0; - return; - } - - double remaining_time = - remaining_distance_time_.remaining_distance / current_vehicle_velocity_norm; - remaining_distance_time_.remaining_time = remaining_time; - - remaining_distance_time_.hours = static_cast(remaining_time / 3600.0); - remaining_time = std::fmod(remaining_time, 3600); - remaining_distance_time_.minutes = static_cast(remaining_time / 60.0); - remaining_distance_time_.seconds = static_cast(std::fmod(remaining_time, 60)); - return; -} - void BehaviorPathPlannerNode::publish_steering_factor( const std::shared_ptr & planner_data, const TurnIndicatorsCommand & turn_signal) { @@ -741,15 +714,15 @@ void BehaviorPathPlannerNode::publishPathReference( } } -void BehaviorPathPlannerNode::publishMissionRemainingDistanceTime() const +void BehaviorPathPlannerNode::publishMissionRemainingDistanceTime(const route_handler::RemainingDistanceTime & remaining_distance_time_) const { MissionRemainingDistanceTime mission_remaining_distance_time; mission_remaining_distance_time.remaining_distance = remaining_distance_time_.remaining_distance; mission_remaining_distance_time.remaining_time = remaining_distance_time_.remaining_time; - mission_remaining_distance_time.remaining_hours = remaining_distance_time_.hours; - mission_remaining_distance_time.remaining_minutes = remaining_distance_time_.minutes; - mission_remaining_distance_time.remaining_seconds = remaining_distance_time_.seconds; + mission_remaining_distance_time.remaining_hours = remaining_distance_time_.remaining_hours; + mission_remaining_distance_time.remaining_minutes = remaining_distance_time_.remaining_minutes; + mission_remaining_distance_time.remaining_seconds = remaining_distance_time_.remaining_seconds; mission_remaining_distance_time_publisher_->publish(mission_remaining_distance_time); } diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index ac8e472b2f943..db17619384254 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -22,6 +22,7 @@ #include #include #include +#include #include #include @@ -42,6 +43,7 @@ using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::LaneletSegment; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; +using geometry_msgs::msg::Vector3; using std_msgs::msg::Header; using unique_identifier_msgs::msg::UUID; using RouteSections = std::vector; @@ -50,6 +52,15 @@ enum class Direction { NONE, LEFT, RIGHT }; enum class PullOverDirection { NONE, LEFT, RIGHT }; enum class PullOutDirection { NONE, LEFT, RIGHT }; +struct RemainingDistanceTime +{ + double remaining_distance; + double remaining_time; + uint32_t remaining_hours; + uint32_t remaining_minutes; + uint32_t remaining_seconds; +}; + class RouteHandler { public: @@ -355,6 +366,10 @@ class RouteHandler lanelet::ConstPolygon3d getIntersectionAreaById(const lanelet::Id id) const; bool isPreferredLane(const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getClosestLanelets(const geometry_msgs::msg::Pose & target_pose) const; + + void getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_, RemainingDistanceTime & remaining_dist_time) const; + void getRemainingTime(const Vector3 & current_vehicle_velocity, RemainingDistanceTime & remaining_dist_time) const; + private: // MUST diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 76763821998bd..0bd0f2dc80b9a 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -2293,4 +2293,69 @@ lanelet::ConstLanelets RouteHandler::getClosestLanelets( lanelet::utils::query::getCurrentLanelets(road_lanelets_, target_pose, &target_lanelets); return target_lanelets; } + +void RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_, RemainingDistanceTime & remaining_dist_time) const +{ + double remaining_distance = 0.0; + size_t index = 0; + + lanelet::ConstLanelet current_lanelet; + getClosestLaneletWithinRoute(current_pose, ¤t_lanelet); + + lanelet::ConstLanelet goal_lanelet; + getGoalLanelet(&goal_lanelet); + + const lanelet::Optional optional_route = + routing_graph_ptr_->getRoute(current_lanelet, goal_lanelet, 0); + + lanelet::routing::LaneletPath remaining_shortest_path; + remaining_shortest_path = optional_route->shortestPath(); + + for (auto & llt : remaining_shortest_path) { + if (remaining_shortest_path.size() == 1) { + remaining_distance += + tier4_autoware_utils::calcDistance2d(current_pose.position, goal_pose_.position); + break; + } + + if (index == 0) { + lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, current_pose); + double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt); + remaining_distance += this_lanelet_length - arc_coord.length; + } else if (index == (remaining_shortest_path.size() - 1)) { + lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, goal_pose_); + remaining_distance += arc_coord.length; + } else { + remaining_distance += lanelet::utils::getLaneletLength2d(llt); + } + + index++; + } + + remaining_dist_time.remaining_distance = remaining_distance; +} + +void RouteHandler::getRemainingTime(const Vector3 & current_vehicle_velocity, RemainingDistanceTime & remaining_dist_time) const +{ + double current_velocity_norm = std::sqrt( + current_vehicle_velocity.x * current_vehicle_velocity.x + + current_vehicle_velocity.y * current_vehicle_velocity.y); + + if (remaining_dist_time.remaining_distance < 0.01 || current_velocity_norm < 0.01) { + remaining_dist_time.remaining_distance = 0.0; + remaining_dist_time.remaining_time = 0.0; + remaining_dist_time.remaining_hours = 0; + remaining_dist_time.remaining_minutes = 0; + remaining_dist_time.remaining_seconds = 0; + return; + } + + double remaining_time = remaining_dist_time.remaining_distance / current_velocity_norm; + remaining_dist_time.remaining_time = remaining_time; + remaining_dist_time.remaining_hours = static_cast(remaining_time / 3600.0); + remaining_time = std::fmod(remaining_time, 3600); + remaining_dist_time.remaining_minutes = static_cast(remaining_time / 60.0); + remaining_dist_time.remaining_seconds = static_cast(std::fmod(remaining_time, 60)); + return; +} } // namespace route_handler From a7408be71c824a34e89f3ac14d6423c289b1d85b Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 25 Apr 2024 13:14:31 +0000 Subject: [PATCH 17/77] style(pre-commit): autofix --- .../behavior_path_planner_node.hpp | 4 ++-- .../src/behavior_path_planner_node.cpp | 10 ++++++---- .../include/route_handler/route_handler.hpp | 8 +++++--- planning/route_handler/src/route_handler.cpp | 7 +++++-- 4 files changed, 18 insertions(+), 11 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index a4cb17aaf4a53..c858c0adf7a61 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -78,7 +78,6 @@ using tier4_planning_msgs::msg::StopReasonArray; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; - class BehaviorPathPlannerNode : public rclcpp::Node { public: @@ -228,7 +227,8 @@ class BehaviorPathPlannerNode : public rclcpp::Node /** * @brief publish mission remaining distance and time */ - void publishMissionRemainingDistanceTime(const route_handler::RemainingDistanceTime & remaining_distance_time_) const; + void publishMissionRemainingDistanceTime( + const route_handler::RemainingDistanceTime & remaining_distance_time_) const; /** * @brief convert path with lane id to path for publish path candidate diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 2d472263a0561..59677b1a76a8b 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -398,9 +398,10 @@ void BehaviorPathPlannerNode::run() // compute mission remaining distance planner_data_->route_handler->getRemainingDistance( planner_data_->self_odometry->pose.pose, goal_pose_, remaining_distance_time_); - - // compute mission remaining time - planner_data_->route_handler->getRemainingTime(planner_data_->self_odometry->twist.twist.linear, remaining_distance_time_); + + // compute mission remaining time + planner_data_->route_handler->getRemainingTime( + planner_data_->self_odometry->twist.twist.linear, remaining_distance_time_); // publish remaining distance and time publishMissionRemainingDistanceTime(remaining_distance_time_); @@ -714,7 +715,8 @@ void BehaviorPathPlannerNode::publishPathReference( } } -void BehaviorPathPlannerNode::publishMissionRemainingDistanceTime(const route_handler::RemainingDistanceTime & remaining_distance_time_) const +void BehaviorPathPlannerNode::publishMissionRemainingDistanceTime( + const route_handler::RemainingDistanceTime & remaining_distance_time_) const { MissionRemainingDistanceTime mission_remaining_distance_time; diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index db17619384254..082782ea91a10 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -366,10 +366,12 @@ class RouteHandler lanelet::ConstPolygon3d getIntersectionAreaById(const lanelet::Id id) const; bool isPreferredLane(const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getClosestLanelets(const geometry_msgs::msg::Pose & target_pose) const; - - void getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_, RemainingDistanceTime & remaining_dist_time) const; - void getRemainingTime(const Vector3 & current_vehicle_velocity, RemainingDistanceTime & remaining_dist_time) const; + void getRemainingDistance( + const Pose & current_pose, const Pose & goal_pose_, + RemainingDistanceTime & remaining_dist_time) const; + void getRemainingTime( + const Vector3 & current_vehicle_velocity, RemainingDistanceTime & remaining_dist_time) const; private: // MUST diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 0bd0f2dc80b9a..1e3f1429e7125 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -2294,7 +2294,9 @@ lanelet::ConstLanelets RouteHandler::getClosestLanelets( return target_lanelets; } -void RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_, RemainingDistanceTime & remaining_dist_time) const +void RouteHandler::getRemainingDistance( + const Pose & current_pose, const Pose & goal_pose_, + RemainingDistanceTime & remaining_dist_time) const { double remaining_distance = 0.0; size_t index = 0; @@ -2335,7 +2337,8 @@ void RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose & remaining_dist_time.remaining_distance = remaining_distance; } -void RouteHandler::getRemainingTime(const Vector3 & current_vehicle_velocity, RemainingDistanceTime & remaining_dist_time) const +void RouteHandler::getRemainingTime( + const Vector3 & current_vehicle_velocity, RemainingDistanceTime & remaining_dist_time) const { double current_velocity_norm = std::sqrt( current_vehicle_velocity.x * current_vehicle_velocity.x + From 2c1bc345c725c6d85c7d5b08c56e9975abbfa1cd Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Thu, 25 Apr 2024 15:23:51 +0200 Subject: [PATCH 18/77] feat(remaining_dist_eta): fix review comment to have the remaining distance metric only Signed-off-by: AhmedEbrahim --- .../remaining_distance_time_display.hpp | 3 - .../src/mission_details_display.cpp | 2 +- .../src/remaining_distance_time_display.cpp | 70 +------------------ 3 files changed, 3 insertions(+), 72 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp index 4bc0f8a7b903c..a58cf5b3d9dbf 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp @@ -42,9 +42,6 @@ class RemainingDistanceTimeDisplay private: double remaining_distance_; // Internal variable to store remaining distance - uint32_t hours_; // Internal variable to store remaining time hours - uint32_t minutes_; // Internal variable to store remaining time minutes - uint32_t seconds_; // Internal variable to store remaining time seconds QColor gray = QColor(194, 194, 194); }; diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp index ba4217a2ab896..295a76c940aea 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -83,7 +83,7 @@ void MissionDetailsDisplay::setupRosSubscriptions() remaining_distance_time_sub_ = rviz_node_->create_subscription( - "/planning/mission_remaining_distance_time", + remaining_distance_time_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), [this](const autoware_internal_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { updateRemainingDistanceTimeData(msg); diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index dabbe3b269513..ad0215277bd8d 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -35,7 +35,7 @@ namespace autoware_mission_details_overlay_rviz_plugin { RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() -: remaining_distance_(0.0), hours_(0), minutes_(0), seconds_(0) +: remaining_distance_(0.0) { std::string package_path = ament_index_cpp::get_package_share_directory("autoware_mission_details_overlay_rviz_plugin"); @@ -55,9 +55,6 @@ void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData( { try { remaining_distance_ = msg->remaining_distance; - hours_ = msg->remaining_hours; - minutes_ = msg->remaining_minutes; - seconds_ = msg->remaining_seconds; } catch (const std::exception & e) { // Log the error std::cerr << "Error in processMessage: " << e.what() << std::endl; @@ -71,10 +68,7 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( painter.setFont(referenceFont); QRect referenceRect = painter.fontMetrics().boundingRect("88"); QPointF remainingDistReferencePos( - backgroundRect.width() / 2 - referenceRect.width() / 2, backgroundRect.height() / 3); - - QPointF remainingTimeReferencePos( - backgroundRect.width() / 2 - referenceRect.width() / 2, backgroundRect.height() / 1.3); + backgroundRect.width() / 2 - referenceRect.width() / 2, backgroundRect.height() / 2); // Remaining distance value QString remainingDistanceValue = QString::number(remaining_distance_, 'f', 0); @@ -101,66 +95,6 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( QPointF remainingDistancUnitPos( remainingDistReferencePos.x() + 150, remainingDistReferencePos.y()); painter.drawText(remainingDistancUnitPos, remainingDistUnitText); - - // Remaining time text - QFont remainingTimeTextFont("Quicksand", 12); - painter.setFont(remainingDistancTextFont); - QString remainingTimeText = "Remaining Time: "; - QPointF remainingTimeTextPos(remainingTimeReferencePos.x() - 80, remainingTimeReferencePos.y()); - painter.drawText(remainingTimeTextPos, remainingTimeText); - - // Remaining time value - hours - QString remaininghoursValue = QString::number(hours_, 'f', 0); - QFont remaininghoursValueFont("Quicksand", fontSize); - painter.setFont(remaininghoursValueFont); - - QPointF remaininghoursValuePos(remainingTimeReferencePos.x() + 50, remainingTimeReferencePos.y()); - painter.setPen(gray); - painter.drawText(remaininghoursValuePos, remaininghoursValue); - - // Remaining time hours separator - QFont hoursSeparatorTextFont("Quicksand", 12); - painter.setFont(hoursSeparatorTextFont); - QString hoursSeparatorText = " h : "; - - QPointF hoursSeparatorTextPos(remainingTimeReferencePos.x() + 70, remainingTimeReferencePos.y()); - painter.drawText(hoursSeparatorTextPos, hoursSeparatorText); - - // Remaining time value - minutes - QString remainingminutesValue = QString::number(minutes_, 'f', 0); - QFont remainingminutesValueFont("Quicksand", fontSize); - painter.setFont(remainingminutesValueFont); - - QPointF remainingminutesValuePos( - remainingTimeReferencePos.x() + 100, remainingTimeReferencePos.y()); - painter.setPen(gray); - painter.drawText(remainingminutesValuePos, remainingminutesValue); - - // Remaining time minutes separator - QFont minutesSeparatorTextFont("Quicksand", 12); - painter.setFont(minutesSeparatorTextFont); - QString minutesSeparatorText = " m : "; - QPointF minutesSeparatorTextPos( - remainingTimeReferencePos.x() + 120, remainingTimeReferencePos.y()); - painter.drawText(minutesSeparatorTextPos, minutesSeparatorText); - - // Remaining time value - seconds - QString remainingsecondsValue = QString::number(seconds_, 'f', 0); - QFont remainingsecondsValueFont("Quicksand", fontSize); - painter.setFont(remainingsecondsValueFont); - - QPointF remainingsecondValuePos( - remainingTimeReferencePos.x() + 160, remainingTimeReferencePos.y()); - painter.setPen(gray); - painter.drawText(remainingsecondValuePos, remainingsecondsValue); - - // Remaining time seconds separator - QFont secondsSeparatorTextFont("Quicksand", 12); - painter.setFont(secondsSeparatorTextFont); - QString secondsSeparatorText = " s"; - QPointF secondsSeparatorTextPos( - remainingTimeReferencePos.x() + 180, remainingTimeReferencePos.y()); - painter.drawText(secondsSeparatorTextPos, secondsSeparatorText); } } // namespace autoware_mission_details_overlay_rviz_plugin From 662f409d7f7aedd27b11826f5143f1efebe73fbc Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 25 Apr 2024 13:25:58 +0000 Subject: [PATCH 19/77] style(pre-commit): autofix --- .../src/remaining_distance_time_display.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index ad0215277bd8d..83d06c75dc21a 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -34,8 +34,7 @@ namespace autoware_mission_details_overlay_rviz_plugin { -RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() -: remaining_distance_(0.0) +RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() : remaining_distance_(0.0) { std::string package_path = ament_index_cpp::get_package_share_directory("autoware_mission_details_overlay_rviz_plugin"); From d39f1b40f8c3680a0b309027295531a4edbd70ad Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Mon, 29 Apr 2024 13:33:08 +0300 Subject: [PATCH 20/77] feat(remaining_dist_eta): add remaining time back to the visualization display Signed-off-by: AhmedEbrahim --- .../remaining_distance_time_display.hpp | 5 +- .../src/remaining_distance_time_display.cpp | 71 ++++++++++++++++++- 2 files changed, 73 insertions(+), 3 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp index a58cf5b3d9dbf..2c63b06281c86 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp @@ -41,7 +41,10 @@ class RemainingDistanceTimeDisplay const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); private: - double remaining_distance_; // Internal variable to store remaining distance + double remaining_distance_; // Internal variable to store remaining distance + uint32_t remaining_hours_; // Internal variable to store remaining time hours + uint32_t remaining_minutes_; // Internal variable to store remaining time minutes + uint32_t remaining_seconds_; // Internal variable to store remaining time seconds QColor gray = QColor(194, 194, 194); }; diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index 83d06c75dc21a..013a9fce20026 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -34,7 +34,8 @@ namespace autoware_mission_details_overlay_rviz_plugin { -RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() : remaining_distance_(0.0) +RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() : +remaining_distance_(0.0), remaining_hours_(0), remaining_minutes_(0), remaining_seconds_(0) { std::string package_path = ament_index_cpp::get_package_share_directory("autoware_mission_details_overlay_rviz_plugin"); @@ -54,6 +55,9 @@ void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData( { try { remaining_distance_ = msg->remaining_distance; + remaining_hours_ = msg->remaining_hours; + remaining_minutes_ = msg->remaining_minutes; + remaining_seconds_ = msg->remaining_seconds; } catch (const std::exception & e) { // Log the error std::cerr << "Error in processMessage: " << e.what() << std::endl; @@ -67,7 +71,10 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( painter.setFont(referenceFont); QRect referenceRect = painter.fontMetrics().boundingRect("88"); QPointF remainingDistReferencePos( - backgroundRect.width() / 2 - referenceRect.width() / 2, backgroundRect.height() / 2); + backgroundRect.width() / 2 - referenceRect.width() / 2, backgroundRect.height() / 3); + + QPointF remainingTimeReferencePos( + backgroundRect.width() / 2 - referenceRect.width() / 2, backgroundRect.height() / 1.3); // Remaining distance value QString remainingDistanceValue = QString::number(remaining_distance_, 'f', 0); @@ -94,6 +101,66 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( QPointF remainingDistancUnitPos( remainingDistReferencePos.x() + 150, remainingDistReferencePos.y()); painter.drawText(remainingDistancUnitPos, remainingDistUnitText); + + // Remaining time text + QFont remainingTimeTextFont("Quicksand", 12); + painter.setFont(remainingDistancTextFont); + QString remainingTimeText = "Remaining Time: "; + QPointF remainingTimeTextPos(remainingTimeReferencePos.x() - 80, remainingTimeReferencePos.y()); + painter.drawText(remainingTimeTextPos, remainingTimeText); + + // Remaining hours value + QString remaininghoursValue = QString::number(remaining_hours_, 'f', 0); + QFont remaininghoursValueFont("Quicksand", fontSize); + painter.setFont(remaininghoursValueFont); + + QPointF remaininghoursValuePos(remainingTimeReferencePos.x() + 50, remainingTimeReferencePos.y()); + painter.setPen(gray); + painter.drawText(remaininghoursValuePos, remaininghoursValue); + + // Remaining hours separator + QFont hoursSeparatorTextFont("Quicksand", 12); + painter.setFont(hoursSeparatorTextFont); + QString hoursSeparatorText = " h : "; + + QPointF hoursSeparatorTextPos(remainingTimeReferencePos.x() + 70, remainingTimeReferencePos.y()); + painter.drawText(hoursSeparatorTextPos, hoursSeparatorText); + + // Remaining minutes value + QString remainingminutesValue = QString::number(remaining_minutes_, 'f', 0); + QFont remainingminutesValueFont("Quicksand", fontSize); + painter.setFont(remainingminutesValueFont); + + QPointF remainingminutesValuePos( + remainingTimeReferencePos.x() + 100, remainingTimeReferencePos.y()); + painter.setPen(gray); + painter.drawText(remainingminutesValuePos, remainingminutesValue); + + // Remaining minutes separator + QFont minutesSeparatorTextFont("Quicksand", 12); + painter.setFont(minutesSeparatorTextFont); + QString minutesSeparatorText = " m : "; + QPointF minutesSeparatorTextPos( + remainingTimeReferencePos.x() + 120, remainingTimeReferencePos.y()); + painter.drawText(minutesSeparatorTextPos, minutesSeparatorText); + + // Remaining seconds value + QString remainingsecondsValue = QString::number(remaining_seconds_, 'f', 0); + QFont remainingsecondsValueFont("Quicksand", fontSize); + painter.setFont(remainingsecondsValueFont); + + QPointF remainingsecondValuePos( + remainingTimeReferencePos.x() + 160, remainingTimeReferencePos.y()); + painter.setPen(gray); + painter.drawText(remainingsecondValuePos, remainingsecondsValue); + + // Remaining seconds separator + QFont secondsSeparatorTextFont("Quicksand", 12); + painter.setFont(secondsSeparatorTextFont); + QString secondsSeparatorText = " s"; + QPointF secondsSeparatorTextPos( + remainingTimeReferencePos.x() + 180, remainingTimeReferencePos.y()); + painter.drawText(secondsSeparatorTextPos, secondsSeparatorText); } } // namespace autoware_mission_details_overlay_rviz_plugin From 1776e43b7b01b443697d8305eea77b69895a7dd7 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 29 Apr 2024 10:35:07 +0000 Subject: [PATCH 21/77] style(pre-commit): autofix --- .../include/remaining_distance_time_display.hpp | 8 ++++---- .../src/remaining_distance_time_display.cpp | 10 +++++----- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp index 2c63b06281c86..099bfd9249c9e 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp @@ -41,10 +41,10 @@ class RemainingDistanceTimeDisplay const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); private: - double remaining_distance_; // Internal variable to store remaining distance - uint32_t remaining_hours_; // Internal variable to store remaining time hours - uint32_t remaining_minutes_; // Internal variable to store remaining time minutes - uint32_t remaining_seconds_; // Internal variable to store remaining time seconds + double remaining_distance_; // Internal variable to store remaining distance + uint32_t remaining_hours_; // Internal variable to store remaining time hours + uint32_t remaining_minutes_; // Internal variable to store remaining time minutes + uint32_t remaining_seconds_; // Internal variable to store remaining time seconds QColor gray = QColor(194, 194, 194); }; diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index 013a9fce20026..0f19f3655c702 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -34,8 +34,8 @@ namespace autoware_mission_details_overlay_rviz_plugin { -RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() : -remaining_distance_(0.0), remaining_hours_(0), remaining_minutes_(0), remaining_seconds_(0) +RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() +: remaining_distance_(0.0), remaining_hours_(0), remaining_minutes_(0), remaining_seconds_(0) { std::string package_path = ament_index_cpp::get_package_share_directory("autoware_mission_details_overlay_rviz_plugin"); @@ -55,9 +55,9 @@ void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData( { try { remaining_distance_ = msg->remaining_distance; - remaining_hours_ = msg->remaining_hours; - remaining_minutes_ = msg->remaining_minutes; - remaining_seconds_ = msg->remaining_seconds; + remaining_hours_ = msg->remaining_hours; + remaining_minutes_ = msg->remaining_minutes; + remaining_seconds_ = msg->remaining_seconds; } catch (const std::exception & e) { // Log the error std::cerr << "Error in processMessage: " << e.what() << std::endl; From bcf9dbb6db02b1376ff6d8a45ffbc0da45959b3f Mon Sep 17 00:00:00 2001 From: KhalilSelyan Date: Tue, 30 Apr 2024 13:07:14 +0300 Subject: [PATCH 22/77] added goal distance/time icons Signed-off-by: KhalilSelyan --- .../assets/score_white.png | Bin 0 -> 100 bytes .../assets/white_flag.png | Bin 0 -> 131 bytes 2 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/score_white.png create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/white_flag.png diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/score_white.png b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/score_white.png new file mode 100644 index 0000000000000000000000000000000000000000..9ed3974ffc6bda3bb13ea5e5b84a7c46b263e80c GIT binary patch literal 100 zcmeAS@N?(olHy`uVBq!ia0vp^1|ZA`BpB)|k7xlYrjj7PU^#LU6*+47el6`rnsF6*2UngFu#COZHC literal 0 HcmV?d00001 From 20e076b7967fa47b3acf664fe0fc09172253d555 Mon Sep 17 00:00:00 2001 From: KhalilSelyan Date: Tue, 30 Apr 2024 13:09:53 +0300 Subject: [PATCH 23/77] Refactor remaining_distance_time_display.hpp to add goal distance/time icons Signed-off-by: KhalilSelyan --- .../include/remaining_distance_time_display.hpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp index 099bfd9249c9e..bd8a8e093e035 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp @@ -46,6 +46,11 @@ class RemainingDistanceTimeDisplay uint32_t remaining_minutes_; // Internal variable to store remaining time minutes uint32_t remaining_seconds_; // Internal variable to store remaining time seconds QColor gray = QColor(194, 194, 194); + + QImage distToGoalFlag; + QImage scaledDistToGoalFlag; + QImage timeToGoalFlag; + QImage scaledTimeToGoalFlag; }; } // namespace autoware_mission_details_overlay_rviz_plugin From f17f11bcff4f1fd1ffe5ac58aa8647d8c981c3b2 Mon Sep 17 00:00:00 2001 From: KhalilSelyan Date: Tue, 30 Apr 2024 13:10:55 +0300 Subject: [PATCH 24/77] Refactor to use icons and use km/m depending on distance Signed-off-by: KhalilSelyan --- .../src/remaining_distance_time_display.cpp | 130 +++++++++++------- 1 file changed, 77 insertions(+), 53 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index 0f19f3655c702..436d3fb329bff 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -24,6 +24,8 @@ #include #include #include +#include +#include #include #include @@ -48,6 +50,16 @@ RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() if (fontId == -1 || fontId2 == -1) { std::cout << "Failed to load the Quicksand font."; } + + // Load the wheel image + std::string dist_image = package_path + "/assets/white_flag.png"; + std::string time_image = package_path + "/assets/score_white.png"; + distToGoalFlag.load(dist_image.c_str()); + timeToGoalFlag.load(time_image.c_str()); + scaledDistToGoalFlag = + distToGoalFlag.scaled(32, 32, Qt::KeepAspectRatio, Qt::SmoothTransformation); + scaledTimeToGoalFlag = + timeToGoalFlag.scaled(32, 32, Qt::KeepAspectRatio, Qt::SmoothTransformation); } void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData( @@ -76,90 +88,102 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( QPointF remainingTimeReferencePos( backgroundRect.width() / 2 - referenceRect.width() / 2, backgroundRect.height() / 1.3); - // Remaining distance value - QString remainingDistanceValue = QString::number(remaining_distance_, 'f', 0); + // ----------------- Remaining Distance ----------------- + int fontSize = 15; - QFont remainingDistancValueFont("Quicksand", fontSize); + QFont remainingDistancValueFont("Quicksand", fontSize, QFont::Bold); painter.setFont(remainingDistancValueFont); - QPointF remainingDistancePos(remainingDistReferencePos.x() + 100, remainingDistReferencePos.y()); + // Remaining distance icon + QPointF remainingDistanceIconPos( + remainingDistReferencePos.x() - 25, remainingDistReferencePos.y()); + painter.drawImage( + remainingDistanceIconPos.x(), + remainingDistanceIconPos.y() - scaledDistToGoalFlag.height() / 2.0, scaledDistToGoalFlag); + + // Remaining distance value + QString remainingDistanceValue = QString::number( + remaining_distance_ > 1000 ? remaining_distance_ / 1000 : remaining_distance_, 'f', 0); + QPointF remainingDistancePos; + switch (remainingDistanceValue.size()) { + case 1: + remainingDistancePos = + QPointF(remainingDistReferencePos.x() + 95, remainingDistReferencePos.y() + 10); + break; + case 2: + remainingDistancePos = + QPointF(remainingDistReferencePos.x() + 90, remainingDistReferencePos.y() + 10); + break; + case 3: + remainingDistancePos = + QPointF(remainingDistReferencePos.x() + 80, remainingDistReferencePos.y() + 10); + break; + case 4: + remainingDistancePos = + QPointF(remainingDistReferencePos.x() + 70, remainingDistReferencePos.y() + 10); + break; + default: + remainingDistancePos = + QPointF(remainingDistReferencePos.x() + 95, remainingDistReferencePos.y() + 10); + break; + } painter.setPen(gray); painter.drawText(remainingDistancePos, remainingDistanceValue); - // Remaining distance text - QFont remainingDistancTextFont("Quicksand", 12); - painter.setFont(remainingDistancTextFont); - QString remainingDistText = "Remaining Distance: "; - QPointF remainingDistancTextPos( - remainingDistReferencePos.x() - 80, remainingDistReferencePos.y()); - painter.drawText(remainingDistancTextPos, remainingDistText); - // Remaining distance unit - QFont remainingDistancUnitFont("Quicksand", 12); + QFont remainingDistancUnitFont("Quicksand", 12, QFont::Bold); painter.setFont(remainingDistancUnitFont); - QString remainingDistUnitText = " m"; + QString remainingDistUnitText = remaining_distance_ > 1000 ? "km" : "m"; QPointF remainingDistancUnitPos( - remainingDistReferencePos.x() + 150, remainingDistReferencePos.y()); + remaining_distance_ > 1000 ? remainingDistReferencePos.x() + 120 + : remainingDistReferencePos.x() + 115, + remainingDistReferencePos.y() + 10); painter.drawText(remainingDistancUnitPos, remainingDistUnitText); + // ----------------- Remaining Time ----------------- + // Remaining time text - QFont remainingTimeTextFont("Quicksand", 12); - painter.setFont(remainingDistancTextFont); - QString remainingTimeText = "Remaining Time: "; - QPointF remainingTimeTextPos(remainingTimeReferencePos.x() - 80, remainingTimeReferencePos.y()); - painter.drawText(remainingTimeTextPos, remainingTimeText); + painter.drawImage( + remainingDistanceIconPos.x(), + remainingDistanceIconPos.y() + scaledTimeToGoalFlag.height() / 2.0, scaledTimeToGoalFlag); // Remaining hours value - QString remaininghoursValue = QString::number(remaining_hours_, 'f', 0); - QFont remaininghoursValueFont("Quicksand", fontSize); - painter.setFont(remaininghoursValueFont); - - QPointF remaininghoursValuePos(remainingTimeReferencePos.x() + 50, remainingTimeReferencePos.y()); + QString remaininghoursValue = + QString::number(remaining_hours_ != 0 ? remaining_hours_ : 0, 'f', 0); + QPointF remaininghoursValuePos(remainingTimeReferencePos.x() + 30, remainingTimeReferencePos.y()); painter.setPen(gray); - painter.drawText(remaininghoursValuePos, remaininghoursValue); + if (remaining_hours_ != 0) painter.drawText(remaininghoursValuePos, remaininghoursValue); // Remaining hours separator - QFont hoursSeparatorTextFont("Quicksand", 12); - painter.setFont(hoursSeparatorTextFont); - QString hoursSeparatorText = " h : "; - - QPointF hoursSeparatorTextPos(remainingTimeReferencePos.x() + 70, remainingTimeReferencePos.y()); - painter.drawText(hoursSeparatorTextPos, hoursSeparatorText); + QString hoursSeparatorText = "h"; + QPointF hoursSeparatorTextPos(remainingTimeReferencePos.x() + 50, remainingTimeReferencePos.y()); + if (remaining_hours_ != 0) painter.drawText(hoursSeparatorTextPos, hoursSeparatorText); // Remaining minutes value - QString remainingminutesValue = QString::number(remaining_minutes_, 'f', 0); - QFont remainingminutesValueFont("Quicksand", fontSize); - painter.setFont(remainingminutesValueFont); - + QString remainingminutesValue = + QString::number(remaining_minutes_ != 0 ? remaining_minutes_ : 0, 'f', 0); QPointF remainingminutesValuePos( - remainingTimeReferencePos.x() + 100, remainingTimeReferencePos.y()); + remainingTimeReferencePos.x() + 65, remainingTimeReferencePos.y()); painter.setPen(gray); - painter.drawText(remainingminutesValuePos, remainingminutesValue); - + if (remaining_minutes_ != 0) painter.drawText(remainingminutesValuePos, remainingminutesValue); // Remaining minutes separator - QFont minutesSeparatorTextFont("Quicksand", 12); - painter.setFont(minutesSeparatorTextFont); - QString minutesSeparatorText = " m : "; + QString minutesSeparatorText = "m"; QPointF minutesSeparatorTextPos( - remainingTimeReferencePos.x() + 120, remainingTimeReferencePos.y()); - painter.drawText(minutesSeparatorTextPos, minutesSeparatorText); + remainingTimeReferencePos.x() + 85, remainingTimeReferencePos.y()); + if (remaining_minutes_ != 0) painter.drawText(minutesSeparatorTextPos, minutesSeparatorText); // Remaining seconds value - QString remainingsecondsValue = QString::number(remaining_seconds_, 'f', 0); - QFont remainingsecondsValueFont("Quicksand", fontSize); - painter.setFont(remainingsecondsValueFont); - + QString remainingsecondsValue = + QString::number(remaining_seconds_ != 0 ? remaining_seconds_ : 0, 'f', 0); QPointF remainingsecondValuePos( - remainingTimeReferencePos.x() + 160, remainingTimeReferencePos.y()); + remainingTimeReferencePos.x() + 102.5, remainingTimeReferencePos.y()); painter.setPen(gray); painter.drawText(remainingsecondValuePos, remainingsecondsValue); // Remaining seconds separator - QFont secondsSeparatorTextFont("Quicksand", 12); - painter.setFont(secondsSeparatorTextFont); - QString secondsSeparatorText = " s"; + QString secondsSeparatorText = "s"; QPointF secondsSeparatorTextPos( - remainingTimeReferencePos.x() + 180, remainingTimeReferencePos.y()); + remainingTimeReferencePos.x() + 120, remainingTimeReferencePos.y()); painter.drawText(secondsSeparatorTextPos, secondsSeparatorText); } From 82471ad63fb9ad3e6bb79fa5a29733facd555b4a Mon Sep 17 00:00:00 2001 From: KhalilSelyan Date: Tue, 30 Apr 2024 13:11:30 +0300 Subject: [PATCH 25/77] update widget size Signed-off-by: KhalilSelyan --- .../src/mission_details_display.cpp | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp index 295a76c940aea..06bc8ce247155 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -39,7 +39,7 @@ namespace autoware_mission_details_overlay_rviz_plugin MissionDetailsDisplay::MissionDetailsDisplay() { property_width_ = new rviz_common::properties::IntProperty( - "Width", 300, "Width of the overlay", this, SLOT(updateOverlaySize())); + "Width", 225, "Width of the overlay", this, SLOT(updateOverlaySize())); property_height_ = new rviz_common::properties::IntProperty( "Height", 100, "Height of the overlay", this, SLOT(updateOverlaySize())); property_left_ = new rviz_common::properties::IntProperty( @@ -155,7 +155,7 @@ void MissionDetailsDisplay::drawWidget(QImage & hud) QPainter painter(&hud); painter.setRenderHint(QPainter::Antialiasing, true); - QRectF backgroundRect(0, 0, 300, 100); + QRectF backgroundRect(0, 0, 225, 100); drawHorizontalRoundedRectangle(painter, backgroundRect); if (remaining_distance_time_display_) { @@ -170,8 +170,8 @@ void MissionDetailsDisplay::drawHorizontalRoundedRectangle( { painter.setRenderHint(QPainter::Antialiasing, true); QColor colorFromHSV; - colorFromHSV.setHsv(0, 0, 0); // Hue, Saturation, Value - colorFromHSV.setAlphaF(0.65); // Transparency + colorFromHSV.setHsv(0, 0, 29); // Hue, Saturation, Value + colorFromHSV.setAlphaF(0.60); // Transparency painter.setBrush(colorFromHSV); @@ -211,7 +211,9 @@ void MissionDetailsDisplay::updateOverlaySize() void MissionDetailsDisplay::updateOverlayPosition() { std::lock_guard lock(mutex_); - overlay_->setPosition(property_left_->getInt(), property_top_->getInt()); + overlay_->setPosition( + property_left_->getInt(), property_top_->getInt(), HorizontalAlignment::RIGHT, + VerticalAlignment::TOP); queueRender(); } From 1ddb209839d54313658579adbeaa0b093193809d Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Tue, 30 Apr 2024 15:52:31 +0300 Subject: [PATCH 26/77] feat(remaining_dist_eta): add slight changes to icons and values/text pos to prevent overlapping Signed-off-by: AhmedEbrahim --- .../assets/timelapse.png | Bin 0 -> 2972 bytes .../src/remaining_distance_time_display.cpp | 36 ++++++++---------- 2 files changed, 16 insertions(+), 20 deletions(-) create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/timelapse.png diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/timelapse.png b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/timelapse.png new file mode 100644 index 0000000000000000000000000000000000000000..459d642823ce98fb4e8fb0d154c3271c5475c0ce GIT binary patch literal 2972 zcmV;N3uE+&P)5WnH~+()aC3iK%X zOEAQLqfQVGS60+nx7(ex%;(bK7fu5%uExKpC^`Ve^lzUC)b89PKn5xd2RobH-`%_O z*TX^paQ^vU2ciDwb1?c4Q+w!ddWAhrFzM4M2;c2K>JDlii|xKu04^`Do<}-3`No{E zWP54=vlRyVWNT~lou?j+yJ;K%vg`l(8a;p=cg?OgbDb#8haEkPbZ4Sg)M#EhNz2q!?S;YYVKfU6z9MG`f&)DN zLp;8{x$5m~ZM<}xL+RtS0FXM`KQL;NIGKOWpdkHFhl8!HF2(THpUcbfeiR_D(CP@C z{A}6L5Dxlj9S+(%02%Y4`unWv-{-~+e(mekuveGujeXJAh%}PGNHjzKsRabD0L0R! zB9eTQWa>t1)mvW+dv!=y5r0WY{{1C74uaS`%7KXUhVYrIR_1B)20$wLA5EAKSNv{$ zH9T&L@$+EBKzxmQV8ZhSVcXJX z&H#Y$?N+alFu7};1p&%0gxtH?!W*}S>gw9WFLuYFME^}E0GxliK7kbdR>dlc z^O4!^o2a`v>ysxe0iZ|4)y_0?9;v&(e&-&1Sbj%5a z=P@TdWj-(;h?tmQIRL!+H7@;*PPhnbw!V`V9!Ge%R0~YZuowVH+8BdYWxdXI5mV{E z1Hj)Jv&0`1*1zt@;uF+}x{~>b0Fb2RNXH-BrsEPq%i4G}LCFw;cs?z|(Ar1oM_PUn z0U)S&o&j-LIogHW1!x!jS09aKM5Ly@Wso!c1aEp#0Se5)?i*y3h z%mctIIZ7N>qX5|Nfcu6_E|STTvI>P_9We_4>OTW4&;6~`);TW8xq?%d4Ae0AQa|l?*H|&m>!dy#T-!;Mz*SGBCUXFlS3R26B-Q zC3ReRn$-Yqf}EqOL+bN=a`d^3AAx~CGWC4~DY2@Q?Y`#t^VbBxz)^DyG=3`uL-Sl`&I0`U%j;+%s6kktUhx}&Pa=r)|NH|8_y!8u{B zDk=ex2Y|@~nhryoVt$+lFmXJ$N~lBR0h=}F0bI7|YJ>C7H_3cSBF53f0Z3!88o;du zaM_|S0JzEe8Yk%|Nu)U866}$3FGVauF|JwW-$BVa(0nnj(3krt#&LEI7I$kfJs$$9`Iy=)l*(uQp=?h7&`wcoCP&c(a}RWp@-@64Al z{fiw$dau6R&b9rNnjy37sonaQ4~at zxVm>dbx+$;yi0x&>ebr7N`I1oDQrtAKOw13rP?}P|g5|PYfCyUQQP_=x#RK z8?B^}WbMw7w;W2h)6XADFB;7DWT>$Q#AZlxVvrgdN<^Yv`UDS_YC~~eE8c<_Uk+t* zj7p^On5s$SW9@|V53>6r)5cO8oAoWa&Fa>)2+9nJABnF+LzsEO?N-juk@ZnoV?pJ# zOhv6UAl8E9{xv$Jz}jwUTAn8|xy@>Jh;5N{9gMAMI)ec8)>k{HCX6RKB;}Ws-W!;+ zeW^Kf_5t}042Wd++gBNJ0^`eUc0kur;)?nMfI{2h=RqN6PhblMbiL(Tr!z2RdPaj- z^2y3N?v1t9fQ(qSE|QBxR&j^u#@5E0DrUF+9p*!qPf0J8a;|?l13(NDoR_-eE21M@ zS@yzKI_m-`y|V0W{t6yuEVgbWq16ijX^K7&+v*lB$*y9?XGC=~x>S7rtsLbKox!0W z_z)s501%y$1Iz^usE>10FMUizB5m_+V&C#LdW|6VNcy~OykFM8HvnjWbe)tmfsKrE z1Wo7?rL~ptO;bR`jGsoof|(RyiO;tY^YLDqL!So{y#kQa1i3l7Ln6Lb3?bbc+mMcv z;xu$7Crc79W_;SOH?xzc(>nl;AY`<~m+j&B>jzh9OSO`YSP|2050lrze41=60AyTb zLsU*=lkXAR>p>6(L!|q|j#iWD3U)2ey_yt(e3s1rjkBSm2;?B zHO*Q9pn;96oo3rdis$C1jD3S7>&WF!P>Foi4ge96zQUx(UVN8Qd=G<^nLcolFeGk+ z+74b}f>O2YQa^FO1q~YkARCvesCY@++$GuKN~X&^MbEZzsd%FR+&buKbfhCi_xDS0 zD;F`)wh=Kt2=N-Lm9XDbD4fySH~@JjQPB& z7iQyCh5?eeqD60iPT&UJ<096uZ*$YFl(Euw3jsi$*feT7z~AVf?K;5x{Lk 1000 ? "km" : "m"; - QPointF remainingDistancUnitPos( - remaining_distance_ > 1000 ? remainingDistReferencePos.x() + 120 - : remainingDistReferencePos.x() + 115, + QPointF remainingDistancUnitPos(remainingDistReferencePos.x() + 125, remainingDistReferencePos.y() + 10); painter.drawText(remainingDistancUnitPos, remainingDistUnitText); @@ -150,40 +146,40 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( // Remaining hours value QString remaininghoursValue = QString::number(remaining_hours_ != 0 ? remaining_hours_ : 0, 'f', 0); - QPointF remaininghoursValuePos(remainingTimeReferencePos.x() + 30, remainingTimeReferencePos.y()); + QPointF remaininghoursValuePos(remainingTimeReferencePos.x() + 17, remainingTimeReferencePos.y()); painter.setPen(gray); if (remaining_hours_ != 0) painter.drawText(remaininghoursValuePos, remaininghoursValue); // Remaining hours separator QString hoursSeparatorText = "h"; - QPointF hoursSeparatorTextPos(remainingTimeReferencePos.x() + 50, remainingTimeReferencePos.y()); + QPointF hoursSeparatorTextPos(remainingTimeReferencePos.x() + 35, remainingTimeReferencePos.y()); if (remaining_hours_ != 0) painter.drawText(hoursSeparatorTextPos, hoursSeparatorText); // Remaining minutes value QString remainingminutesValue = QString::number(remaining_minutes_ != 0 ? remaining_minutes_ : 0, 'f', 0); QPointF remainingminutesValuePos( - remainingTimeReferencePos.x() + 65, remainingTimeReferencePos.y()); + remainingTimeReferencePos.x() + 55, remainingTimeReferencePos.y()); painter.setPen(gray); if (remaining_minutes_ != 0) painter.drawText(remainingminutesValuePos, remainingminutesValue); // Remaining minutes separator QString minutesSeparatorText = "m"; QPointF minutesSeparatorTextPos( - remainingTimeReferencePos.x() + 85, remainingTimeReferencePos.y()); + remainingTimeReferencePos.x() + 80, remainingTimeReferencePos.y()); if (remaining_minutes_ != 0) painter.drawText(minutesSeparatorTextPos, minutesSeparatorText); // Remaining seconds value QString remainingsecondsValue = QString::number(remaining_seconds_ != 0 ? remaining_seconds_ : 0, 'f', 0); QPointF remainingsecondValuePos( - remainingTimeReferencePos.x() + 102.5, remainingTimeReferencePos.y()); + remainingTimeReferencePos.x() + 100, remainingTimeReferencePos.y()); painter.setPen(gray); painter.drawText(remainingsecondValuePos, remainingsecondsValue); // Remaining seconds separator QString secondsSeparatorText = "s"; QPointF secondsSeparatorTextPos( - remainingTimeReferencePos.x() + 120, remainingTimeReferencePos.y()); + remainingTimeReferencePos.x() + 125, remainingTimeReferencePos.y()); painter.drawText(secondsSeparatorTextPos, secondsSeparatorText); } From 7f29beb8f5e60bcf6930d871153c6558f1460591 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Tue, 30 Apr 2024 15:54:14 +0300 Subject: [PATCH 27/77] feat(remaining_dist_eta): update readme file Signed-off-by: AhmedEbrahim --- .../autoware_mission_details_overlay_rviz_plugin/README.md | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md index ef69547087893..162db440754cb 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md @@ -25,11 +25,13 @@ This plugin provides a visual and easy-to-understand display of mission details | Name | Type | Default Value | Description | | ------------------ | ---- | ------------- | --------------------------------- | -| `property_width_` | int | 300 | Width of the plotter window [px] | +| `property_width_` | int | 225 | Width of the plotter window [px] | | `property_height_` | int | 100 | Height of the plotter window [px] | -| `property_left_` | int | 800 | Left of the plotter window [px] | +| `property_left_` | int | 10 | Left of the plotter window [px] | | `property_top_` | int | 10 | Top of the plotter window [px] | +Note that mission details display is aligned with top right corner of the screen. + ## Assumptions / Known limits TBD. From 64d1114f705c61d3705cc877ca8d0d4534c2ce5e Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 30 Apr 2024 12:57:44 +0000 Subject: [PATCH 28/77] style(pre-commit): autofix --- .../autoware_mission_details_overlay_rviz_plugin/README.md | 2 +- .../src/remaining_distance_time_display.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md index 162db440754cb..28b0c4393ab7b 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md @@ -27,7 +27,7 @@ This plugin provides a visual and easy-to-understand display of mission details | ------------------ | ---- | ------------- | --------------------------------- | | `property_width_` | int | 225 | Width of the plotter window [px] | | `property_height_` | int | 100 | Height of the plotter window [px] | -| `property_left_` | int | 10 | Left of the plotter window [px] | +| `property_left_` | int | 10 | Left of the plotter window [px] | | `property_top_` | int | 10 | Top of the plotter window [px] | Note that mission details display is aligned with top right corner of the screen. diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index 4beb79bfeb3d3..273ab819cfe98 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -132,8 +132,8 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( // Remaining distance unit QString remainingDistUnitText = remaining_distance_ > 1000 ? "km" : "m"; - QPointF remainingDistancUnitPos(remainingDistReferencePos.x() + 125, - remainingDistReferencePos.y() + 10); + QPointF remainingDistancUnitPos( + remainingDistReferencePos.x() + 125, remainingDistReferencePos.y() + 10); painter.drawText(remainingDistancUnitPos, remainingDistUnitText); // ----------------- Remaining Time ----------------- From 4e60c1695cfd4eb8854a23c9ec1a1d0cb29e72e0 Mon Sep 17 00:00:00 2001 From: AhmedEbrahim Date: Tue, 7 May 2024 05:33:48 +0300 Subject: [PATCH 29/77] feat(remaining_dist_eta): [wip] fix review comments - separate the implementation logic in a standalone package/node Signed-off-by: Ahmed Ebrahim --- .../launch/planning.launch.xml | 6 + launch/tier4_planning_launch/package.xml | 1 + .../src/behavior_path_planner_node.cpp | 24 +- .../CMakeLists.txt | 22 + .../README.md | 17 + ...aining_distance_time_calculator.param.yaml | 3 + ...ion_remaining_distance_time_calculator.hpp | 346 ++++++++ ...emaining_distance_time_calculator_node.hpp | 113 +++ ...aining_distance_time_calculator.launch.xml | 25 + .../package.xml | 46 + ...ion_remaining_distance_time_calculator.cpp | 785 ++++++++++++++++++ ...emaining_distance_time_calculator_node.cpp | 184 ++++ 12 files changed, 1560 insertions(+), 12 deletions(-) create mode 100644 planning/mission_remaining_distance_time_calculator/CMakeLists.txt create mode 100644 planning/mission_remaining_distance_time_calculator/README.md create mode 100644 planning/mission_remaining_distance_time_calculator/config/mission_remaining_distance_time_calculator.param.yaml create mode 100644 planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator.hpp create mode 100644 planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp create mode 100644 planning/mission_remaining_distance_time_calculator/launch/mission_remaining_distance_time_calculator.launch.xml create mode 100644 planning/mission_remaining_distance_time_calculator/package.xml create mode 100644 planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator.cpp create mode 100644 planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp diff --git a/launch/tier4_planning_launch/launch/planning.launch.xml b/launch/tier4_planning_launch/launch/planning.launch.xml index 710fb20631a45..a69746085e205 100644 --- a/launch/tier4_planning_launch/launch/planning.launch.xml +++ b/launch/tier4_planning_launch/launch/planning.launch.xml @@ -43,5 +43,11 @@ + + + + + + diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 950ef67865a85..7c290046cc8a2 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -65,6 +65,7 @@ freespace_planner glog_component mission_planner + mission_remaining_distance_time_calculator motion_velocity_smoother obstacle_avoidance_planner obstacle_cruise_planner diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 59677b1a76a8b..de959e0d27019 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -394,18 +394,18 @@ void BehaviorPathPlannerNode::run() if (!controlled_by_autoware_autonomously && !planner_manager_->hasApprovedModules()) planner_manager_->resetCurrentRouteLanelet(planner_data_); - if (planner_data_->route_handler->isHandlerReady()) { - // compute mission remaining distance - planner_data_->route_handler->getRemainingDistance( - planner_data_->self_odometry->pose.pose, goal_pose_, remaining_distance_time_); - - // compute mission remaining time - planner_data_->route_handler->getRemainingTime( - planner_data_->self_odometry->twist.twist.linear, remaining_distance_time_); - - // publish remaining distance and time - publishMissionRemainingDistanceTime(remaining_distance_time_); - } + // if (planner_data_->route_handler->isHandlerReady()) { + // // compute mission remaining distance + // planner_data_->route_handler->getRemainingDistance( + // planner_data_->self_odometry->pose.pose, goal_pose_, remaining_distance_time_); + + // // compute mission remaining time + // planner_data_->route_handler->getRemainingTime( + // planner_data_->self_odometry->twist.twist.linear, remaining_distance_time_); + + // // publish remaining distance and time + // publishMissionRemainingDistanceTime(remaining_distance_time_); + // } // run behavior planner const auto output = planner_manager_->run(planner_data_); diff --git a/planning/mission_remaining_distance_time_calculator/CMakeLists.txt b/planning/mission_remaining_distance_time_calculator/CMakeLists.txt new file mode 100644 index 0000000000000..aa355a4c3cf07 --- /dev/null +++ b/planning/mission_remaining_distance_time_calculator/CMakeLists.txt @@ -0,0 +1,22 @@ +cmake_minimum_required(VERSION 3.14) +project(mission_remaining_distance_time_calculator) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(mission_remaining_distance_time_calculator SHARED + src/mission_remaining_distance_time_calculator_node.cpp + #src/mission_remaining_distance_time_calculator.cpp +) + +rclcpp_components_register_node(mission_remaining_distance_time_calculator + PLUGIN "mission_remaining_distance_time_calculator::MissionRemainingDistanceTimeCalculatorNode" + EXECUTABLE mission_remaining_distance_time_calculator_node +) + + +ament_auto_package( + INSTALL_TO_SHARE + launch + config +) diff --git a/planning/mission_remaining_distance_time_calculator/README.md b/planning/mission_remaining_distance_time_calculator/README.md new file mode 100644 index 0000000000000..cdec3bbcd16ec --- /dev/null +++ b/planning/mission_remaining_distance_time_calculator/README.md @@ -0,0 +1,17 @@ +## Mission Remaining Distance and Time Calculator + +### Role + + + +### Activation Timing + + +### Module Parameters + + +### Inner-workings / Algorithms + + +### Future Work + diff --git a/planning/mission_remaining_distance_time_calculator/config/mission_remaining_distance_time_calculator.param.yaml b/planning/mission_remaining_distance_time_calculator/config/mission_remaining_distance_time_calculator.param.yaml new file mode 100644 index 0000000000000..5b8c019de5a20 --- /dev/null +++ b/planning/mission_remaining_distance_time_calculator/config/mission_remaining_distance_time_calculator.param.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + update_rate: 10.0 diff --git a/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator.hpp b/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator.hpp new file mode 100644 index 0000000000000..416c36b116059 --- /dev/null +++ b/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator.hpp @@ -0,0 +1,346 @@ +// 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 OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_ +#define OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_ + +#include "motion_utils/trajectory/trajectory.hpp" +#include "obstacle_cruise_planner/common_structs.hpp" +#include "obstacle_cruise_planner/stop_planning_debug_info.hpp" +#include "obstacle_cruise_planner/type_alias.hpp" +#include "obstacle_cruise_planner/utils.hpp" +#include "tier4_autoware_utils/ros/update_param.hpp" +#include "tier4_autoware_utils/system/stop_watch.hpp" + +#include +#include +#include +#include +#include +#include +#include + +class PlannerInterface +{ +public: + PlannerInterface( + rclcpp::Node & node, const LongitudinalInfo & longitudinal_info, + const vehicle_info_util::VehicleInfo & vehicle_info, const EgoNearestParam & ego_nearest_param, + const std::shared_ptr debug_data_ptr) + : longitudinal_info_(longitudinal_info), + vehicle_info_(vehicle_info), + ego_nearest_param_(ego_nearest_param), + debug_data_ptr_(debug_data_ptr), + slow_down_param_(SlowDownParam(node)) + { + stop_reasons_pub_ = node.create_publisher("~/output/stop_reasons", 1); + velocity_factors_pub_ = + node.create_publisher("/planning/velocity_factors/obstacle_cruise", 1); + stop_speed_exceeded_pub_ = + node.create_publisher("~/output/stop_speed_exceeded", 1); + + moving_object_speed_threshold = + node.declare_parameter("slow_down.moving_object_speed_threshold"); + moving_object_hysteresis_range = + node.declare_parameter("slow_down.moving_object_hysteresis_range"); + } + + PlannerInterface() = default; + + void setParam( + const bool enable_debug_info, const bool enable_calculation_time_info, + const double min_behavior_stop_margin, const double enable_approaching_on_curve, + const double additional_safe_distance_margin_on_curve, + const double min_safe_distance_margin_on_curve, const bool suppress_sudden_obstacle_stop) + { + enable_debug_info_ = enable_debug_info; + enable_calculation_time_info_ = enable_calculation_time_info; + min_behavior_stop_margin_ = min_behavior_stop_margin; + enable_approaching_on_curve_ = enable_approaching_on_curve; + additional_safe_distance_margin_on_curve_ = additional_safe_distance_margin_on_curve; + min_safe_distance_margin_on_curve_ = min_safe_distance_margin_on_curve; + suppress_sudden_obstacle_stop_ = suppress_sudden_obstacle_stop; + } + + std::vector generateStopTrajectory( + const PlannerData & planner_data, const std::vector & stop_obstacles); + + virtual std::vector generateCruiseTrajectory( + const PlannerData & planner_data, const std::vector & stop_traj_points, + const std::vector & cruise_obstacles, + std::optional & vel_limit) = 0; + + std::vector generateSlowDownTrajectory( + const PlannerData & planner_data, const std::vector & stop_traj_points, + const std::vector & slow_down_obstacles, + std::optional & vel_limit); + + void onParam(const std::vector & parameters) + { + updateCommonParam(parameters); + updateCruiseParam(parameters); + slow_down_param_.onParam(parameters); + } + + Float32MultiArrayStamped getStopPlanningDebugMessage(const rclcpp::Time & current_time) const + { + return stop_planning_debug_info_.convertToMessage(current_time); + } + virtual Float32MultiArrayStamped getCruisePlanningDebugMessage( + [[maybe_unused]] const rclcpp::Time & current_time) const + { + return Float32MultiArrayStamped{}; + } + Float32MultiArrayStamped getSlowDownPlanningDebugMessage(const rclcpp::Time & current_time) + { + slow_down_debug_multi_array_.stamp = current_time; + return slow_down_debug_multi_array_; + } + double getSafeDistanceMargin() const { return longitudinal_info_.safe_distance_margin; } + +protected: + // Parameters + bool enable_debug_info_{false}; + bool enable_calculation_time_info_{false}; + LongitudinalInfo longitudinal_info_; + double min_behavior_stop_margin_; + bool enable_approaching_on_curve_; + double additional_safe_distance_margin_on_curve_; + double min_safe_distance_margin_on_curve_; + bool suppress_sudden_obstacle_stop_; + + // stop watch + tier4_autoware_utils::StopWatch< + std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> + stop_watch_; + + // Publishers + rclcpp::Publisher::SharedPtr stop_reasons_pub_; + rclcpp::Publisher::SharedPtr velocity_factors_pub_; + rclcpp::Publisher::SharedPtr stop_speed_exceeded_pub_; + + // Vehicle Parameters + vehicle_info_util::VehicleInfo vehicle_info_; + + EgoNearestParam ego_nearest_param_; + + mutable std::shared_ptr debug_data_ptr_; + + // debug info + StopPlanningDebugInfo stop_planning_debug_info_; + Float32MultiArrayStamped slow_down_debug_multi_array_; + + double calcDistanceToCollisionPoint( + const PlannerData & planner_data, const geometry_msgs::msg::Point & collision_point); + + double calcRSSDistance( + const double ego_vel, const double obstacle_vel, const double margin = 0.0) const + { + const auto & i = longitudinal_info_; + const double rss_dist_with_margin = + ego_vel * i.idling_time + std::pow(ego_vel, 2) * 0.5 / std::abs(i.min_ego_accel_for_rss) - + std::pow(obstacle_vel, 2) * 0.5 / std::abs(i.min_object_accel_for_rss) + margin; + return rss_dist_with_margin; + } + + void updateCommonParam(const std::vector & parameters) + { + longitudinal_info_.onParam(parameters); + } + + virtual void updateCruiseParam([[maybe_unused]] const std::vector & parameters) + { + } + + size_t findEgoIndex( + const std::vector & traj_points, + const geometry_msgs::msg::Pose & ego_pose) const + { + const auto & p = ego_nearest_param_; + return motion_utils::findFirstNearestIndexWithSoftConstraints( + traj_points, ego_pose, p.dist_threshold, p.yaw_threshold); + } + + size_t findEgoSegmentIndex( + const std::vector & traj_points, + const geometry_msgs::msg::Pose & ego_pose) const + { + const auto & p = ego_nearest_param_; + return motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + traj_points, ego_pose, p.dist_threshold, p.yaw_threshold); + } + +private: + struct SlowDownOutput + { + SlowDownOutput() = default; + SlowDownOutput( + const std::string & arg_uuid, const std::vector & traj_points, + const std::optional & start_idx, const std::optional & end_idx, + const double arg_target_vel, const double arg_feasible_target_vel, + const double arg_precise_lat_dist, const bool is_moving) + : uuid(arg_uuid), + target_vel(arg_target_vel), + feasible_target_vel(arg_feasible_target_vel), + precise_lat_dist(arg_precise_lat_dist), + is_moving(is_moving) + { + if (start_idx) { + start_point = traj_points.at(*start_idx).pose; + } + if (end_idx) { + end_point = traj_points.at(*end_idx).pose; + } + } + + std::string uuid; + double target_vel; + double feasible_target_vel; + double precise_lat_dist; + std::optional start_point{std::nullopt}; + std::optional end_point{std::nullopt}; + bool is_moving; + }; + double calculateMarginFromObstacleOnCurve( + const PlannerData & planner_data, const StopObstacle & stop_obstacle) const; + double calculateSlowDownVelocity( + const SlowDownObstacle & obstacle, const std::optional & prev_output, + const bool is_obstacle_moving) const; + std::optional> calculateDistanceToSlowDownWithConstraints( + const PlannerData & planner_data, const std::vector & traj_points, + const SlowDownObstacle & obstacle, const std::optional & prev_output, + const double dist_to_ego, const bool is_obstacle_moving) const; + + struct SlowDownInfo + { + // NOTE: Acceleration limit is applied to lon_dist not to occur sudden brake. + const double lon_dist; // from ego pose to slow down point + const double vel; // slow down velocity + }; + + struct SlowDownParam + { + std::vector obstacle_labels{"default"}; + std::vector obstacle_moving_classification{"static", "moving"}; + std::unordered_map types_map; + struct ObstacleSpecificParams + { + double max_lat_margin; + double min_lat_margin; + double max_ego_velocity; + double min_ego_velocity; + }; + explicit SlowDownParam(rclcpp::Node & node) + { + obstacle_labels = + node.declare_parameter>("slow_down.labels", obstacle_labels); + // obstacle label dependant parameters + for (const auto & label : obstacle_labels) { + for (const auto & movement_postfix : obstacle_moving_classification) { + ObstacleSpecificParams params; + params.max_lat_margin = node.declare_parameter( + "slow_down." + label + "." + movement_postfix + ".max_lat_margin"); + params.min_lat_margin = node.declare_parameter( + "slow_down." + label + "." + movement_postfix + ".min_lat_margin"); + params.max_ego_velocity = node.declare_parameter( + "slow_down." + label + "." + movement_postfix + ".max_ego_velocity"); + params.min_ego_velocity = node.declare_parameter( + "slow_down." + label + "." + movement_postfix + ".min_ego_velocity"); + obstacle_to_param_struct_map.emplace( + std::make_pair(label + "." + movement_postfix, params)); + } + } + + // common parameters + time_margin_on_target_velocity = + node.declare_parameter("slow_down.time_margin_on_target_velocity"); + lpf_gain_slow_down_vel = node.declare_parameter("slow_down.lpf_gain_slow_down_vel"); + lpf_gain_lat_dist = node.declare_parameter("slow_down.lpf_gain_lat_dist"); + lpf_gain_dist_to_slow_down = + node.declare_parameter("slow_down.lpf_gain_dist_to_slow_down"); + + types_map = {{ObjectClassification::UNKNOWN, "unknown"}, + {ObjectClassification::CAR, "car"}, + {ObjectClassification::TRUCK, "truck"}, + {ObjectClassification::BUS, "bus"}, + {ObjectClassification::TRAILER, "trailer"}, + {ObjectClassification::MOTORCYCLE, "motorcycle"}, + {ObjectClassification::BICYCLE, "bicycle"}, + {ObjectClassification::PEDESTRIAN, "pedestrian"}}; + } + + ObstacleSpecificParams getObstacleParamByLabel( + const ObjectClassification & label_id, const bool is_obstacle_moving) const + { + const std::string label = + (types_map.count(label_id.label) > 0) ? types_map.at(label_id.label) : "default"; + const std::string movement_postfix = (is_obstacle_moving) ? "moving" : "static"; + return (obstacle_to_param_struct_map.count(label + "." + movement_postfix) > 0) + ? obstacle_to_param_struct_map.at(label + "." + movement_postfix) + : obstacle_to_param_struct_map.at("default." + movement_postfix); + } + + void onParam(const std::vector & parameters) + { + // obstacle type dependant parameters + for (const auto & label : obstacle_labels) { + for (const auto & movement_postfix : obstacle_moving_classification) { + if (obstacle_to_param_struct_map.count(label + "." + movement_postfix) < 1) continue; + auto & param_by_obstacle_label = + obstacle_to_param_struct_map.at(label + "." + movement_postfix); + tier4_autoware_utils::updateParam( + parameters, "slow_down." + label + "." + movement_postfix + ".max_lat_margin", + param_by_obstacle_label.max_lat_margin); + tier4_autoware_utils::updateParam( + parameters, "slow_down." + label + "." + movement_postfix + ".min_lat_margin", + param_by_obstacle_label.min_lat_margin); + tier4_autoware_utils::updateParam( + parameters, "slow_down." + label + "." + movement_postfix + ".max_ego_velocity", + param_by_obstacle_label.max_ego_velocity); + tier4_autoware_utils::updateParam( + parameters, "slow_down." + label + "." + movement_postfix + ".min_ego_velocity", + param_by_obstacle_label.min_ego_velocity); + } + } + + // common parameters + tier4_autoware_utils::updateParam( + parameters, "slow_down.time_margin_on_target_velocity", time_margin_on_target_velocity); + tier4_autoware_utils::updateParam( + parameters, "slow_down.lpf_gain_slow_down_vel", lpf_gain_slow_down_vel); + tier4_autoware_utils::updateParam( + parameters, "slow_down.lpf_gain_lat_dist", lpf_gain_lat_dist); + tier4_autoware_utils::updateParam( + parameters, "slow_down.lpf_gain_dist_to_slow_down", lpf_gain_dist_to_slow_down); + } + + std::unordered_map obstacle_to_param_struct_map; + + double time_margin_on_target_velocity; + double lpf_gain_slow_down_vel; + double lpf_gain_lat_dist; + double lpf_gain_dist_to_slow_down; + }; + SlowDownParam slow_down_param_; + double moving_object_speed_threshold; + double moving_object_hysteresis_range; + std::vector prev_slow_down_output_; + // previous trajectory and distance to stop + // NOTE: Previous trajectory is memorized to deal with nearest index search for overlapping or + // crossing lanes. + std::optional, double>> prev_stop_distance_info_{ + std::nullopt}; +}; + +#endif // OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_ diff --git a/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp b/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp new file mode 100644 index 0000000000000..50483fcfc4b7a --- /dev/null +++ b/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp @@ -0,0 +1,113 @@ +// 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 MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__HPP_ +#define MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__HPP_ + +//#include "mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +namespace mission_remaining_distance_time_calculator +{ + + using geometry_msgs::msg::Pose; + using nav_msgs::msg::Odometry; + using geometry_msgs::msg::Vector3; + using autoware_planning_msgs::msg::LaneletRoute; + using autoware_auto_mapping_msgs::msg::HADMapBin; + using autoware_internal_msgs::msg::MissionRemainingDistanceTime; + +struct NodeParam +{ + double update_rate{0.0}; +}; + +class MissionRemainingDistanceTimeCalculatorNode : public rclcpp::Node +{ +public: + explicit MissionRemainingDistanceTimeCalculatorNode(const rclcpp::NodeOptions & options); + +private: + // Subscriber + rclcpp::Subscription::SharedPtr route_subscriber_; + rclcpp::Subscription::SharedPtr map_subscriber_; + rclcpp::Subscription::SharedPtr odometry_subscriber_; + // rclcpp::Subscription::SharedPtr sub_initial_pose_; + // tier4_autoware_utils::SelfPoseListener self_pose_listener_; + // rclcpp::Subscription::SharedPtr sub_route_; + + // // Data Buffer + // geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_; + // autoware_auto_planning_msgs::msg::Route::SharedPtr route_; + + // // Callback + // void onRoute(const autoware_auto_planning_msgs::msg::Route::ConstSharedPtr & msg); + + // // Publisher + rclcpp::Publisher::SharedPtr + mission_remaining_distance_time_publisher_; + // tier4_autoware_utils::DebugPublisher debug_publisher_; + + // Timer + rclcpp::TimerBase::SharedPtr timer_; + + route_handler::RouteHandler route_handler_; + lanelet::LaneletMapPtr lanelet_map_ptr_; + lanelet::routing::RoutingGraphPtr routing_graph_ptr_; + lanelet::traffic_rules::TrafficRulesPtr traffic_rules_ptr_; + lanelet::ConstLanelets road_lanelets_; + bool is_graph_ready_; + + void onTimer(); + void onOdometry(const Odometry::ConstSharedPtr msg); + void onRoute(const LaneletRoute::ConstSharedPtr msg); + void onMap(const HADMapBin::ConstSharedPtr msg); + double calcuateMissionRemainingDistance() const; + double calcuateMissionRemainingTime(const double remaining_distance) const; + void publishMissionRemainingDistanceTime(const double remaining_distance, const double remaining_time) const; + + Pose current_vehicle_pose_; + Vector3 current_vehicle_velocity_; + Pose goal_pose_; + bool has_received_route_; + + // Parameter + NodeParam node_param_; + + + // Core + // Input input_; + // Output output_; + // std::unique_ptr goal_distance_calculator_; +}; +} // namespace mission_remaining_distance_time_calculator +#endif // MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__HPP_ diff --git a/planning/mission_remaining_distance_time_calculator/launch/mission_remaining_distance_time_calculator.launch.xml b/planning/mission_remaining_distance_time_calculator/launch/mission_remaining_distance_time_calculator.launch.xml new file mode 100644 index 0000000000000..1bebbe23c7c52 --- /dev/null +++ b/planning/mission_remaining_distance_time_calculator/launch/mission_remaining_distance_time_calculator.launch.xml @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/mission_remaining_distance_time_calculator/package.xml b/planning/mission_remaining_distance_time_calculator/package.xml new file mode 100644 index 0000000000000..25c79d8d65610 --- /dev/null +++ b/planning/mission_remaining_distance_time_calculator/package.xml @@ -0,0 +1,46 @@ + + + mission_remaining_distance_time_calculator + 0.1.0 + The mission_remaining_distance_time_calculator package + + Ahmed Ebrahim + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + autoware_internal_msgs + route_handler + autoware_adapi_v1_msgs + autoware_auto_perception_msgs + autoware_auto_planning_msgs + geometry_msgs + interpolation + lanelet2_extension + motion_utils + nav_msgs + object_recognition_utils + osqp_interface + planning_test_utils + rclcpp + rclcpp_components + signal_processing + std_msgs + tf2 + tf2_ros + tier4_autoware_utils + tier4_debug_msgs + tier4_planning_msgs + vehicle_info_util + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator.cpp b/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator.cpp new file mode 100644 index 0000000000000..f7ce218cf3ccf --- /dev/null +++ b/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator.cpp @@ -0,0 +1,785 @@ +// 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 "obstacle_cruise_planner/planner_interface.hpp" + +#include "motion_utils/distance/distance.hpp" +#include "motion_utils/marker/marker_helper.hpp" +#include "motion_utils/resample/resample.hpp" +#include "motion_utils/trajectory/conversion.hpp" +#include "motion_utils/trajectory/trajectory.hpp" +#include "signal_processing/lowpass_filter_1d.hpp" +#include "tier4_autoware_utils/ros/marker_helper.hpp" + +#include +#include + +namespace +{ +StopSpeedExceeded createStopSpeedExceededMsg( + const rclcpp::Time & current_time, const bool stop_flag) +{ + StopSpeedExceeded msg{}; + msg.stamp = current_time; + msg.stop_speed_exceeded = stop_flag; + return msg; +} + +tier4_planning_msgs::msg::StopReasonArray makeStopReasonArray( + const PlannerData & planner_data, const geometry_msgs::msg::Pose & stop_pose, + const StopObstacle & stop_obstacle) +{ + // create header + std_msgs::msg::Header header; + header.frame_id = "map"; + header.stamp = planner_data.current_time; + + // create stop factor + StopFactor stop_factor; + stop_factor.stop_pose = stop_pose; + geometry_msgs::msg::Point stop_factor_point = stop_obstacle.collision_point; + stop_factor_point.z = stop_pose.position.z; + stop_factor.dist_to_stop_pose = motion_utils::calcSignedArcLength( + planner_data.traj_points, planner_data.ego_pose.position, stop_pose.position); + stop_factor.stop_factor_points.emplace_back(stop_factor_point); + + // create stop reason stamped + StopReason stop_reason_msg; + stop_reason_msg.reason = StopReason::OBSTACLE_STOP; + stop_reason_msg.stop_factors.emplace_back(stop_factor); + + // create stop reason array + StopReasonArray stop_reason_array; + stop_reason_array.header = header; + stop_reason_array.stop_reasons.emplace_back(stop_reason_msg); + return stop_reason_array; +} + +StopReasonArray makeEmptyStopReasonArray(const rclcpp::Time & current_time) +{ + // create header + std_msgs::msg::Header header; + header.frame_id = "map"; + header.stamp = current_time; + + // create stop reason stamped + StopReason stop_reason_msg; + stop_reason_msg.reason = StopReason::OBSTACLE_STOP; + + // create stop reason array + StopReasonArray stop_reason_array; + stop_reason_array.header = header; + stop_reason_array.stop_reasons.emplace_back(stop_reason_msg); + return stop_reason_array; +} + +VelocityFactorArray makeVelocityFactorArray( + const rclcpp::Time & time, const std::optional pose = std::nullopt) +{ + VelocityFactorArray velocity_factor_array; + velocity_factor_array.header.frame_id = "map"; + velocity_factor_array.header.stamp = time; + + if (pose) { + using distance_type = VelocityFactor::_distance_type; + VelocityFactor velocity_factor; + velocity_factor.behavior = PlanningBehavior::ROUTE_OBSTACLE; + velocity_factor.pose = pose.value(); + velocity_factor.distance = std::numeric_limits::quiet_NaN(); + velocity_factor.status = VelocityFactor::UNKNOWN; + velocity_factor.detail = std::string(); + velocity_factor_array.factors.push_back(velocity_factor); + } + return velocity_factor_array; +} + +double calcMinimumDistanceToStop( + const double initial_vel, const double max_acc, const double min_acc) +{ + if (initial_vel < 0.0) { + return -std::pow(initial_vel, 2) / 2.0 / max_acc; + } + + return -std::pow(initial_vel, 2) / 2.0 / min_acc; +} + +template +std::optional getObjectFromUuid(const std::vector & objects, const std::string & target_uuid) +{ + const auto itr = std::find_if(objects.begin(), objects.end(), [&](const auto & object) { + return object.uuid == target_uuid; + }); + + if (itr == objects.end()) { + return std::nullopt; + } + return *itr; +} + +// TODO(murooka) following two functions are copied from behavior_velocity_planner. +// These should be refactored. +double findReachTime( + const double jerk, const double accel, const double velocity, const double distance, + const double t_min, const double t_max) +{ + const double j = jerk; + const double a = accel; + const double v = velocity; + const double d = distance; + const double min = t_min; + const double max = t_max; + auto f = [](const double t, const double j, const double a, const double v, const double d) { + return j * t * t * t / 6.0 + a * t * t / 2.0 + v * t - d; + }; + if (f(min, j, a, v, d) > 0 || f(max, j, a, v, d) < 0) { + std::logic_error("[obstacle_cruise_planner](findReachTime): search range is invalid"); + } + const double eps = 1e-5; + const int warn_iter = 100; + double lower = min; + double upper = max; + double t; + int iter = 0; + for (int i = 0;; i++) { + t = 0.5 * (lower + upper); + const double fx = f(t, j, a, v, d); + // std::cout<<"fx: "< 0.0) { + upper = t; + } else { + lower = t; + } + iter++; + if (iter > warn_iter) + std::cerr << "[obstacle_cruise_planner](findReachTime): current iter is over warning" + << std::endl; + } + return t; +} + +double calcDecelerationVelocityFromDistanceToTarget( + const double max_slowdown_jerk, const double max_slowdown_accel, const double current_accel, + const double current_velocity, const double distance_to_target) +{ + if (max_slowdown_jerk > 0 || max_slowdown_accel > 0) { + std::logic_error("max_slowdown_jerk and max_slowdown_accel should be negative"); + } + // case0: distance to target is behind ego + if (distance_to_target <= 0) return current_velocity; + auto ft = [](const double t, const double j, const double a, const double v, const double d) { + return j * t * t * t / 6.0 + a * t * t / 2.0 + v * t - d; + }; + auto vt = [](const double t, const double j, const double a, const double v) { + return j * t * t / 2.0 + a * t + v; + }; + const double j_max = max_slowdown_jerk; + const double a0 = current_accel; + const double a_max = max_slowdown_accel; + const double v0 = current_velocity; + const double l = distance_to_target; + const double t_const_jerk = (a_max - a0) / j_max; + const double d_const_jerk_stop = ft(t_const_jerk, j_max, a0, v0, 0.0); + const double d_const_acc_stop = l - d_const_jerk_stop; + + if (d_const_acc_stop < 0) { + // case0: distance to target is within constant jerk deceleration + // use binary search instead of solving cubic equation + const double t_jerk = findReachTime(j_max, a0, v0, l, 0, t_const_jerk); + const double velocity = vt(t_jerk, j_max, a0, v0); + return velocity; + } else { + const double v1 = vt(t_const_jerk, j_max, a0, v0); + const double discriminant_of_stop = 2.0 * a_max * d_const_acc_stop + v1 * v1; + // case3: distance to target is farther than distance to stop + if (discriminant_of_stop <= 0) { + return 0.0; + } + // case2: distance to target is within constant accel deceleration + // solve d = 0.5*a^2+v*t by t + const double t_acc = (-v1 + std::sqrt(discriminant_of_stop)) / a_max; + return vt(t_acc, 0.0, a_max, v1); + } + return current_velocity; +} + +std::vector resampleTrajectoryPoints( + const std::vector & traj_points, const double interval) +{ + const auto traj = motion_utils::convertToTrajectory(traj_points); + const auto resampled_traj = motion_utils::resampleTrajectory(traj, interval); + return motion_utils::convertToTrajectoryPointArray(resampled_traj); +} + +tier4_autoware_utils::Point2d convertPoint(const geometry_msgs::msg::Point & p) +{ + return tier4_autoware_utils::Point2d{p.x, p.y}; +} +} // namespace + +std::vector PlannerInterface::generateStopTrajectory( + const PlannerData & planner_data, const std::vector & stop_obstacles) +{ + stop_watch_.tic(__func__); + + stop_planning_debug_info_.reset(); + stop_planning_debug_info_.set(StopPlanningDebugInfo::TYPE::EGO_VELOCITY, planner_data.ego_vel); + stop_planning_debug_info_.set(StopPlanningDebugInfo::TYPE::EGO_VELOCITY, planner_data.ego_acc); + + const double abs_ego_offset = planner_data.is_driving_forward + ? std::abs(vehicle_info_.max_longitudinal_offset_m) + : std::abs(vehicle_info_.min_longitudinal_offset_m); + + if (stop_obstacles.empty()) { + stop_reasons_pub_->publish(makeEmptyStopReasonArray(planner_data.current_time)); + velocity_factors_pub_->publish(makeVelocityFactorArray(planner_data.current_time)); + + // delete marker + const auto markers = + motion_utils::createDeletedStopVirtualWallMarker(planner_data.current_time, 0); + tier4_autoware_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); + + prev_stop_distance_info_ = std::nullopt; + return planner_data.traj_points; + } + + RCLCPP_INFO_EXPRESSION( + rclcpp::get_logger("ObstacleCruisePlanner::PIDBasedPlanner"), enable_debug_info_, + "stop planning"); + + // Get Closest Stop Obstacle + const auto closest_stop_obstacle = obstacle_cruise_utils::getClosestStopObstacle(stop_obstacles); + if (!closest_stop_obstacle) { + // delete marker + const auto markers = + motion_utils::createDeletedStopVirtualWallMarker(planner_data.current_time, 0); + tier4_autoware_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); + + prev_stop_distance_info_ = std::nullopt; + return planner_data.traj_points; + } + + const auto ego_segment_idx = + ego_nearest_param_.findSegmentIndex(planner_data.traj_points, planner_data.ego_pose); + const double dist_to_collide_on_ref_traj = + motion_utils::calcSignedArcLength(planner_data.traj_points, 0, ego_segment_idx) + + closest_stop_obstacle->dist_to_collide_on_decimated_traj; + + const double margin_from_obstacle_considering_behavior_module = [&]() { + const double margin_from_obstacle = + calculateMarginFromObstacleOnCurve(planner_data, *closest_stop_obstacle); + // Use terminal margin (terminal_safe_distance_margin) for obstacle stop + const auto ref_traj_length = motion_utils::calcSignedArcLength( + planner_data.traj_points, 0, planner_data.traj_points.size() - 1); + if (dist_to_collide_on_ref_traj > ref_traj_length) { + return longitudinal_info_.terminal_safe_distance_margin; + } + + // If behavior stop point is ahead of the closest_obstacle_stop point within a certain margin + // we set closest_obstacle_stop_distance to closest_behavior_stop_distance + const auto closest_behavior_stop_idx = + motion_utils::searchZeroVelocityIndex(planner_data.traj_points, ego_segment_idx + 1); + if (closest_behavior_stop_idx) { + const double closest_behavior_stop_dist_on_ref_traj = + motion_utils::calcSignedArcLength(planner_data.traj_points, 0, *closest_behavior_stop_idx); + const double stop_dist_diff = closest_behavior_stop_dist_on_ref_traj - + (dist_to_collide_on_ref_traj - margin_from_obstacle); + if (0.0 < stop_dist_diff && stop_dist_diff < margin_from_obstacle) { + return min_behavior_stop_margin_; + } + } + return margin_from_obstacle; + }(); + + // Generate Output Trajectory + const auto [zero_vel_dist, will_collide_with_obstacle] = [&]() { + double candidate_zero_vel_dist = + std::max(0.0, dist_to_collide_on_ref_traj - margin_from_obstacle_considering_behavior_module); + + // Check feasibility to stop + if (suppress_sudden_obstacle_stop_) { + // Calculate feasible stop margin (Check the feasibility) + const double feasible_stop_dist = + calcMinimumDistanceToStop( + planner_data.ego_vel, longitudinal_info_.limit_max_accel, + longitudinal_info_.limit_min_accel) + + motion_utils::calcSignedArcLength( + planner_data.traj_points, 0, planner_data.ego_pose.position); + + if (candidate_zero_vel_dist < feasible_stop_dist) { + candidate_zero_vel_dist = feasible_stop_dist; + return std::make_pair(candidate_zero_vel_dist, true); + } + } + + // Hold previous stop distance if necessary + if ( + std::abs(planner_data.ego_vel) < longitudinal_info_.hold_stop_velocity_threshold && + prev_stop_distance_info_) { + // NOTE: We assume that the current trajectory's front point is ahead of the previous + // trajectory's front point. + const size_t traj_front_point_prev_seg_idx = + motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + prev_stop_distance_info_->first, planner_data.traj_points.front().pose); + const double diff_dist_front_points = motion_utils::calcSignedArcLength( + prev_stop_distance_info_->first, 0, planner_data.traj_points.front().pose.position, + traj_front_point_prev_seg_idx); + + const double prev_zero_vel_dist = prev_stop_distance_info_->second - diff_dist_front_points; + if ( + std::abs(prev_zero_vel_dist - candidate_zero_vel_dist) < + longitudinal_info_.hold_stop_distance_threshold) { + candidate_zero_vel_dist = prev_zero_vel_dist; + } + } + return std::make_pair(candidate_zero_vel_dist, false); + }(); + + // Insert stop point + auto output_traj_points = planner_data.traj_points; + const auto zero_vel_idx = motion_utils::insertStopPoint(0, zero_vel_dist, output_traj_points); + if (zero_vel_idx) { + // virtual wall marker for stop obstacle + const auto markers = motion_utils::createStopVirtualWallMarker( + output_traj_points.at(*zero_vel_idx).pose, "obstacle stop", planner_data.current_time, 0, + abs_ego_offset, "", planner_data.is_driving_forward); + tier4_autoware_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); + debug_data_ptr_->obstacles_to_stop.push_back(*closest_stop_obstacle); + + // Publish Stop Reason + const auto stop_pose = output_traj_points.at(*zero_vel_idx).pose; + const auto stop_reasons_msg = + makeStopReasonArray(planner_data, stop_pose, *closest_stop_obstacle); + stop_reasons_pub_->publish(stop_reasons_msg); + velocity_factors_pub_->publish(makeVelocityFactorArray(planner_data.current_time, stop_pose)); + + // Publish if ego vehicle collides with the obstacle with a limit acceleration + const auto stop_speed_exceeded_msg = + createStopSpeedExceededMsg(planner_data.current_time, will_collide_with_obstacle); + stop_speed_exceeded_pub_->publish(stop_speed_exceeded_msg); + + prev_stop_distance_info_ = std::make_pair(output_traj_points, zero_vel_dist); + } + + stop_planning_debug_info_.set( + StopPlanningDebugInfo::TYPE::STOP_CURRENT_OBSTACLE_DISTANCE, + closest_stop_obstacle->dist_to_collide_on_decimated_traj); + stop_planning_debug_info_.set( + StopPlanningDebugInfo::TYPE::STOP_CURRENT_OBSTACLE_VELOCITY, closest_stop_obstacle->velocity); + + stop_planning_debug_info_.set( + StopPlanningDebugInfo::TYPE::STOP_TARGET_OBSTACLE_DISTANCE, + margin_from_obstacle_considering_behavior_module); + stop_planning_debug_info_.set(StopPlanningDebugInfo::TYPE::STOP_TARGET_VELOCITY, 0.0); + stop_planning_debug_info_.set(StopPlanningDebugInfo::TYPE::STOP_TARGET_ACCELERATION, 0.0); + + const double calculation_time = stop_watch_.toc(__func__); + RCLCPP_INFO_EXPRESSION( + rclcpp::get_logger("ObstacleCruisePlanner::SlowDownPlanner"), enable_calculation_time_info_, + " %s := %f [ms]", __func__, calculation_time); + + return output_traj_points; +} + +double PlannerInterface::calculateMarginFromObstacleOnCurve( + const PlannerData & planner_data, const StopObstacle & stop_obstacle) const +{ + if (!enable_approaching_on_curve_) { + return longitudinal_info_.safe_distance_margin; + } + + const double abs_ego_offset = planner_data.is_driving_forward + ? std::abs(vehicle_info_.max_longitudinal_offset_m) + : std::abs(vehicle_info_.min_longitudinal_offset_m); + + // calculate short trajectory points towards obstacle + const size_t obj_segment_idx = + motion_utils::findNearestSegmentIndex(planner_data.traj_points, stop_obstacle.collision_point); + std::vector short_traj_points{planner_data.traj_points.at(obj_segment_idx + 1)}; + double sum_short_traj_length{0.0}; + for (int i = obj_segment_idx; 0 <= i; --i) { + short_traj_points.push_back(planner_data.traj_points.at(i)); + + if ( + 1 < short_traj_points.size() && + longitudinal_info_.safe_distance_margin + abs_ego_offset < sum_short_traj_length) { + break; + } + sum_short_traj_length += tier4_autoware_utils::calcDistance2d( + planner_data.traj_points.at(i), planner_data.traj_points.at(i + 1)); + } + std::reverse(short_traj_points.begin(), short_traj_points.end()); + if (short_traj_points.size() < 2) { + return longitudinal_info_.safe_distance_margin; + } + + // calculate collision index between straight line from ego pose and object + const auto calculate_distance_from_straight_ego_path = + [&](const auto & ego_pose, const auto & object_polygon) { + const auto forward_ego_pose = tier4_autoware_utils::calcOffsetPose( + ego_pose, longitudinal_info_.safe_distance_margin + 3.0, 0.0, 0.0); + const auto ego_straight_segment = tier4_autoware_utils::Segment2d{ + convertPoint(ego_pose.position), convertPoint(forward_ego_pose.position)}; + return boost::geometry::distance(ego_straight_segment, object_polygon); + }; + const auto resampled_short_traj_points = resampleTrajectoryPoints(short_traj_points, 0.5); + const auto object_polygon = + tier4_autoware_utils::toPolygon2d(stop_obstacle.pose, stop_obstacle.shape); + const auto collision_idx = [&]() -> std::optional { + for (size_t i = 0; i < resampled_short_traj_points.size(); ++i) { + const double dist_to_obj = calculate_distance_from_straight_ego_path( + resampled_short_traj_points.at(i).pose, object_polygon); + if (dist_to_obj < vehicle_info_.vehicle_width_m / 2.0) { + return i; + } + } + return std::nullopt; + }(); + if (!collision_idx) { + return min_safe_distance_margin_on_curve_; + } + if (*collision_idx == 0) { + return longitudinal_info_.safe_distance_margin; + } + + // calculate margin from obstacle + const double partial_segment_length = [&]() { + const double collision_segment_length = tier4_autoware_utils::calcDistance2d( + resampled_short_traj_points.at(*collision_idx - 1), + resampled_short_traj_points.at(*collision_idx)); + const double prev_dist = calculate_distance_from_straight_ego_path( + resampled_short_traj_points.at(*collision_idx - 1).pose, object_polygon); + const double next_dist = calculate_distance_from_straight_ego_path( + resampled_short_traj_points.at(*collision_idx).pose, object_polygon); + return (next_dist - vehicle_info_.vehicle_width_m / 2.0) / (next_dist - prev_dist) * + collision_segment_length; + }(); + + const double short_margin_from_obstacle = + partial_segment_length + + motion_utils::calcSignedArcLength( + resampled_short_traj_points, *collision_idx, stop_obstacle.collision_point) - + abs_ego_offset + additional_safe_distance_margin_on_curve_; + + return std::min( + longitudinal_info_.safe_distance_margin, + std::max(min_safe_distance_margin_on_curve_, short_margin_from_obstacle)); +} + +double PlannerInterface::calcDistanceToCollisionPoint( + const PlannerData & planner_data, const geometry_msgs::msg::Point & collision_point) +{ + const double offset = planner_data.is_driving_forward + ? std::abs(vehicle_info_.max_longitudinal_offset_m) + : std::abs(vehicle_info_.min_longitudinal_offset_m); + + const size_t ego_segment_idx = + ego_nearest_param_.findSegmentIndex(planner_data.traj_points, planner_data.ego_pose); + + const size_t collision_segment_idx = + motion_utils::findNearestSegmentIndex(planner_data.traj_points, collision_point); + + const auto dist_to_collision_point = motion_utils::calcSignedArcLength( + planner_data.traj_points, planner_data.ego_pose.position, ego_segment_idx, collision_point, + collision_segment_idx); + + return dist_to_collision_point - offset; +} + +std::vector PlannerInterface::generateSlowDownTrajectory( + const PlannerData & planner_data, const std::vector & cruise_traj_points, + const std::vector & obstacles, + [[maybe_unused]] std::optional & vel_limit) +{ + stop_watch_.tic(__func__); + auto slow_down_traj_points = cruise_traj_points; + slow_down_debug_multi_array_ = Float32MultiArrayStamped(); + + const double dist_to_ego = [&]() { + const size_t ego_seg_idx = + ego_nearest_param_.findSegmentIndex(slow_down_traj_points, planner_data.ego_pose); + return motion_utils::calcSignedArcLength( + slow_down_traj_points, 0, planner_data.ego_pose.position, ego_seg_idx); + }(); + const double abs_ego_offset = planner_data.is_driving_forward + ? std::abs(vehicle_info_.max_longitudinal_offset_m) + : std::abs(vehicle_info_.min_longitudinal_offset_m); + + // define function to insert slow down velocity to trajectory + const auto insert_point_in_trajectory = [&](const double lon_dist) -> std::optional { + const auto inserted_idx = motion_utils::insertTargetPoint(0, lon_dist, slow_down_traj_points); + if (inserted_idx) { + if (inserted_idx.value() + 1 <= slow_down_traj_points.size() - 1) { + // zero-order hold for velocity interpolation + slow_down_traj_points.at(inserted_idx.value()).longitudinal_velocity_mps = + slow_down_traj_points.at(inserted_idx.value() + 1).longitudinal_velocity_mps; + } + return inserted_idx.value(); + } + return std::nullopt; + }; + + std::vector new_prev_slow_down_output; + for (size_t i = 0; i < obstacles.size(); ++i) { + const auto & obstacle = obstacles.at(i); + const auto prev_output = getObjectFromUuid(prev_slow_down_output_, obstacle.uuid); + + const bool is_obstacle_moving = [&]() -> bool { + const auto object_vel_norm = std::hypot(obstacle.velocity, obstacle.lat_velocity); + if (!prev_output) return object_vel_norm > moving_object_speed_threshold; + if (prev_output->is_moving) + return object_vel_norm > moving_object_speed_threshold - moving_object_hysteresis_range; + return object_vel_norm > moving_object_speed_threshold + moving_object_hysteresis_range; + }(); + + // calculate slow down start distance, and insert slow down velocity + const auto dist_vec_to_slow_down = calculateDistanceToSlowDownWithConstraints( + planner_data, slow_down_traj_points, obstacle, prev_output, dist_to_ego, is_obstacle_moving); + if (!dist_vec_to_slow_down) { + RCLCPP_INFO_EXPRESSION( + rclcpp::get_logger("ObstacleCruisePlanner::PlannerInterface"), enable_debug_info_, + "[SlowDown] Ignore obstacle (%s) since distance to slow down is not valid", + obstacle.uuid.c_str()); + continue; + } + const auto [dist_to_slow_down_start, dist_to_slow_down_end, feasible_slow_down_vel] = + *dist_vec_to_slow_down; + + // calculate slow down end distance, and insert slow down velocity + // NOTE: slow_down_start_idx will not be wrong since inserted back point is after inserted + // front point. + const auto slow_down_start_idx = insert_point_in_trajectory(dist_to_slow_down_start); + const auto slow_down_end_idx = dist_to_slow_down_start < dist_to_slow_down_end + ? insert_point_in_trajectory(dist_to_slow_down_end) + : std::nullopt; + if (!slow_down_end_idx) { + continue; + } + + // calculate slow down velocity + const double stable_slow_down_vel = [&]() { + if (prev_output) { + return signal_processing::lowpassFilter( + feasible_slow_down_vel, prev_output->target_vel, slow_down_param_.lpf_gain_slow_down_vel); + } + return feasible_slow_down_vel; + }(); + + // insert slow down velocity between slow start and end + for (size_t i = (slow_down_start_idx ? *slow_down_start_idx : 0); i <= *slow_down_end_idx; + ++i) { + auto & traj_point = slow_down_traj_points.at(i); + traj_point.longitudinal_velocity_mps = + std::min(traj_point.longitudinal_velocity_mps, static_cast(stable_slow_down_vel)); + } + + // add debug data + slow_down_debug_multi_array_.data.push_back(obstacle.precise_lat_dist); + slow_down_debug_multi_array_.data.push_back(dist_to_slow_down_start); + slow_down_debug_multi_array_.data.push_back(dist_to_slow_down_end); + slow_down_debug_multi_array_.data.push_back(feasible_slow_down_vel); + slow_down_debug_multi_array_.data.push_back(stable_slow_down_vel); + slow_down_debug_multi_array_.data.push_back(slow_down_start_idx ? *slow_down_start_idx : -1.0); + slow_down_debug_multi_array_.data.push_back(slow_down_end_idx ? *slow_down_end_idx : -1.0); + + // add virtual wall + if (slow_down_start_idx && slow_down_end_idx) { + const size_t ego_idx = + ego_nearest_param_.findIndex(slow_down_traj_points, planner_data.ego_pose); + const size_t slow_down_wall_idx = [&]() { + if (ego_idx < *slow_down_start_idx) return *slow_down_start_idx; + if (ego_idx < *slow_down_end_idx) return ego_idx; + return *slow_down_end_idx; + }(); + + const auto markers = motion_utils::createSlowDownVirtualWallMarker( + slow_down_traj_points.at(slow_down_wall_idx).pose, "obstacle slow down", + planner_data.current_time, i, abs_ego_offset, "", planner_data.is_driving_forward); + tier4_autoware_utils::appendMarkerArray(markers, &debug_data_ptr_->slow_down_wall_marker); + } + + // add debug virtual wall + if (slow_down_start_idx) { + const auto markers = motion_utils::createSlowDownVirtualWallMarker( + slow_down_traj_points.at(*slow_down_start_idx).pose, "obstacle slow down start", + planner_data.current_time, i * 2, abs_ego_offset, "", planner_data.is_driving_forward); + tier4_autoware_utils::appendMarkerArray( + markers, &debug_data_ptr_->slow_down_debug_wall_marker); + } + if (slow_down_end_idx) { + const auto markers = motion_utils::createSlowDownVirtualWallMarker( + slow_down_traj_points.at(*slow_down_end_idx).pose, "obstacle slow down end", + planner_data.current_time, i * 2 + 1, abs_ego_offset, "", planner_data.is_driving_forward); + tier4_autoware_utils::appendMarkerArray( + markers, &debug_data_ptr_->slow_down_debug_wall_marker); + } + + debug_data_ptr_->obstacles_to_slow_down.push_back(obstacle); + + // update prev_slow_down_output_ + new_prev_slow_down_output.push_back(SlowDownOutput{ + obstacle.uuid, slow_down_traj_points, slow_down_start_idx, slow_down_end_idx, + stable_slow_down_vel, feasible_slow_down_vel, obstacle.precise_lat_dist, is_obstacle_moving}); + } + + // update prev_slow_down_output_ + prev_slow_down_output_ = new_prev_slow_down_output; + + const double calculation_time = stop_watch_.toc(__func__); + RCLCPP_INFO_EXPRESSION( + rclcpp::get_logger("ObstacleCruisePlanner::SlowDownPlanner"), enable_calculation_time_info_, + " %s := %f [ms]", __func__, calculation_time); + + return slow_down_traj_points; +} + +double PlannerInterface::calculateSlowDownVelocity( + const SlowDownObstacle & obstacle, const std::optional & prev_output, + const bool is_obstacle_moving) const +{ + const auto & p = + slow_down_param_.getObstacleParamByLabel(obstacle.classification, is_obstacle_moving); + const double stable_precise_lat_dist = [&]() { + if (prev_output) { + return signal_processing::lowpassFilter( + obstacle.precise_lat_dist, prev_output->precise_lat_dist, + slow_down_param_.lpf_gain_lat_dist); + } + return obstacle.precise_lat_dist; + }(); + + const double ratio = std::clamp( + (std::abs(stable_precise_lat_dist) - p.min_lat_margin) / (p.max_lat_margin - p.min_lat_margin), + 0.0, 1.0); + const double slow_down_vel = + p.min_ego_velocity + ratio * (p.max_ego_velocity - p.min_ego_velocity); + + return slow_down_vel; +} + +std::optional> +PlannerInterface::calculateDistanceToSlowDownWithConstraints( + const PlannerData & planner_data, const std::vector & traj_points, + const SlowDownObstacle & obstacle, const std::optional & prev_output, + const double dist_to_ego, const bool is_obstacle_moving) const +{ + const double abs_ego_offset = planner_data.is_driving_forward + ? std::abs(vehicle_info_.max_longitudinal_offset_m) + : std::abs(vehicle_info_.min_longitudinal_offset_m); + const double obstacle_vel = obstacle.velocity; + // calculate slow down velocity + const double slow_down_vel = calculateSlowDownVelocity(obstacle, prev_output, is_obstacle_moving); + + // calculate distance to collision points + const double dist_to_front_collision = + motion_utils::calcSignedArcLength(traj_points, 0, obstacle.front_collision_point); + const double dist_to_back_collision = + motion_utils::calcSignedArcLength(traj_points, 0, obstacle.back_collision_point); + + // calculate offset distance to first collision considering relative velocity + const double relative_vel = planner_data.ego_vel - obstacle.velocity; + const double offset_dist_to_collision = [&]() { + if (dist_to_front_collision < dist_to_ego + abs_ego_offset) { + return 0.0; + } + + // NOTE: This min_relative_vel forces the relative velocity positive if the ego velocity is + // lower than the obstacle velocity. Without this, the slow down feature will flicker where + // the ego velocity is very close to the obstacle velocity. + constexpr double min_relative_vel = 1.0; + const double time_to_collision = (dist_to_front_collision - dist_to_ego - abs_ego_offset) / + std::max(min_relative_vel, relative_vel); + + constexpr double time_to_collision_margin = 1.0; + const double cropped_time_to_collision = + std::max(0.0, time_to_collision - time_to_collision_margin); + return obstacle_vel * cropped_time_to_collision; + }(); + + // calculate distance during deceleration, slow down preparation, and slow down + const double min_slow_down_prepare_dist = 3.0; + const double slow_down_prepare_dist = std::max( + min_slow_down_prepare_dist, slow_down_vel * slow_down_param_.time_margin_on_target_velocity); + const double deceleration_dist = offset_dist_to_collision + dist_to_front_collision - + abs_ego_offset - dist_to_ego - slow_down_prepare_dist; + const double slow_down_dist = + dist_to_back_collision - dist_to_front_collision + slow_down_prepare_dist; + + // calculate distance to start/end slow down + const double dist_to_slow_down_start = dist_to_ego + deceleration_dist; + const double dist_to_slow_down_end = dist_to_ego + deceleration_dist + slow_down_dist; + if (100.0 < dist_to_slow_down_start) { + // NOTE: distance to slow down is too far. + return std::nullopt; + } + + // apply low-pass filter to distance to start/end slow down + const auto apply_lowpass_filter = [&](const double dist_to_slow_down, const auto prev_point) { + if (prev_output && prev_point) { + const size_t seg_idx = + motion_utils::findNearestSegmentIndex(traj_points, prev_point->position); + const double prev_dist_to_slow_down = + motion_utils::calcSignedArcLength(traj_points, 0, prev_point->position, seg_idx); + return signal_processing::lowpassFilter( + dist_to_slow_down, prev_dist_to_slow_down, slow_down_param_.lpf_gain_dist_to_slow_down); + } + return dist_to_slow_down; + }; + const double filtered_dist_to_slow_down_start = + apply_lowpass_filter(dist_to_slow_down_start, prev_output->start_point); + const double filtered_dist_to_slow_down_end = + apply_lowpass_filter(dist_to_slow_down_end, prev_output->end_point); + + // calculate velocity considering constraints + const double feasible_slow_down_vel = [&]() { + if (deceleration_dist < 0) { + if (prev_output) { + return prev_output->target_vel; + } + return std::max(planner_data.ego_vel, slow_down_vel); + } + if (planner_data.ego_vel < slow_down_vel) { + return slow_down_vel; + } + + const double one_shot_feasible_slow_down_vel = [&]() { + if (planner_data.ego_acc < longitudinal_info_.min_accel) { + const double squared_vel = + std::pow(planner_data.ego_vel, 2) + 2 * deceleration_dist * longitudinal_info_.min_accel; + if (squared_vel < 0) { + return slow_down_vel; + } + return std::max(std::sqrt(squared_vel), slow_down_vel); + } + // TODO(murooka) Calculate more precisely. Final acceleration should be zero. + const double min_feasible_slow_down_vel = calcDecelerationVelocityFromDistanceToTarget( + longitudinal_info_.slow_down_min_jerk, longitudinal_info_.slow_down_min_accel, + planner_data.ego_acc, planner_data.ego_vel, deceleration_dist); + return min_feasible_slow_down_vel; + }(); + if (prev_output) { + // NOTE: If longitudinal controllability is not good, one_shot_slow_down_vel may be getting + // larger since we use actual ego's velocity and acceleration for its calculation. + // Suppress one_shot_slow_down_vel getting larger here. + const double feasible_slow_down_vel = + std::min(one_shot_feasible_slow_down_vel, prev_output->feasible_target_vel); + return std::max(slow_down_vel, feasible_slow_down_vel); + } + return std::max(slow_down_vel, one_shot_feasible_slow_down_vel); + }(); + + return std::make_tuple( + filtered_dist_to_slow_down_start, filtered_dist_to_slow_down_end, feasible_slow_down_vel); +} diff --git a/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp b/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp new file mode 100644 index 0000000000000..ab71eaec9164c --- /dev/null +++ b/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp @@ -0,0 +1,184 @@ +// 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 "mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp" + + + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace mission_remaining_distance_time_calculator +{ + + + +MissionRemainingDistanceTimeCalculatorNode::MissionRemainingDistanceTimeCalculatorNode(const rclcpp::NodeOptions & options) +: Node("mission_remaining_distance_time_calculator", options) +{ + using std::placeholders::_1; + + odometry_subscriber_ = create_subscription( + "~/input/odometry", 1, std::bind(&MissionRemainingDistanceTimeCalculatorNode::onOdometry, this, _1)); + + const auto qos_transient_local = rclcpp::QoS{1}.transient_local(); + + map_subscriber_ = create_subscription( + "~/input/map", qos_transient_local, std::bind(&MissionRemainingDistanceTimeCalculatorNode::onMap, this, _1)); + route_subscriber_ = create_subscription( + "~/input/route", qos_transient_local, std::bind(&MissionRemainingDistanceTimeCalculatorNode::onRoute, this, _1)); + + mission_remaining_distance_time_publisher_ = create_publisher( + "~/output/mission_remaining_distance_time", + rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable()); + + // Node Parameter + node_param_.update_rate = declare_parameter("update_rate", 10.0); + + // Core + //mission_remaining_distance_time_calculator_ = std::make_unique(); + + + + // Timer + const auto period_ns = rclcpp::Rate(node_param_.update_rate).period(); + timer_ = rclcpp::create_timer( + this, get_clock(), period_ns, std::bind(&MissionRemainingDistanceTimeCalculatorNode::onTimer, this)); + // timer_ = this->create_wall_timer(500ms, std::bind(&MissionRemainingDistanceTimeCalculatorNode::onTimer, this)); + + + RCLCPP_INFO_STREAM(this->get_logger(), "Finished"); + +} + +void MissionRemainingDistanceTimeCalculatorNode::onMap(const HADMapBin::ConstSharedPtr msg) +{ + route_handler_.setMap(*msg); + lanelet_map_ptr_ = std::make_shared(); + lanelet::utils::conversion::fromBinMsg( + *msg, lanelet_map_ptr_, &traffic_rules_ptr_, &routing_graph_ptr_); + lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_); + road_lanelets_ = lanelet::utils::query::roadLanelets(all_lanelets); + is_graph_ready_ = true; +} + +void MissionRemainingDistanceTimeCalculatorNode::onOdometry(const Odometry::ConstSharedPtr msg) +{ + current_vehicle_pose_ = msg->pose.pose; + current_vehicle_velocity_ = msg->twist.twist.linear; +} + +void MissionRemainingDistanceTimeCalculatorNode::onRoute(const LaneletRoute::ConstSharedPtr msg) +{ + goal_pose_ = msg->goal_pose; + has_received_route_ = true; +} + +void MissionRemainingDistanceTimeCalculatorNode::onTimer() +{ + RCLCPP_INFO_STREAM(this->get_logger(), "is_graph_ready_" << is_graph_ready_); + RCLCPP_INFO_STREAM(this->get_logger(), "has_received_route_" << has_received_route_); + + if(is_graph_ready_ && has_received_route_) + { + double remaining_distance = calcuateMissionRemainingDistance(); + double remaining_time = calcuateMissionRemainingTime(remaining_distance); + publishMissionRemainingDistanceTime(remaining_distance, remaining_time); + } + +} +double MissionRemainingDistanceTimeCalculatorNode::calcuateMissionRemainingDistance() const +{ + double remaining_distance = 0.0; + size_t index = 0; + + lanelet::ConstLanelet current_lanelet; + ///route_handler_.getClosestLaneletWithinRoute(current_vehicle_pose_, ¤t_lanelet); + lanelet::utils::query::getClosestLanelet(road_lanelets_, current_vehicle_pose_, ¤t_lanelet); + + lanelet::ConstLanelet goal_lanelet; + //route_handler_.getGoalLanelet(&goal_lanelet); + lanelet::utils::query::getClosestLanelet(road_lanelets_, goal_pose_, &goal_lanelet); + + + const lanelet::Optional optional_route = + routing_graph_ptr_->getRoute(current_lanelet, goal_lanelet, 0); + + + lanelet::routing::LaneletPath remaining_shortest_path; + remaining_shortest_path = optional_route->shortestPath(); + + for (auto & llt : remaining_shortest_path) { + if (remaining_shortest_path.size() == 1) { + remaining_distance += + tier4_autoware_utils::calcDistance2d(current_vehicle_pose_.position, goal_pose_.position); + break; + } + + if (index == 0) { + lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, current_vehicle_pose_); + double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt); + remaining_distance += this_lanelet_length - arc_coord.length; + } else if (index == (remaining_shortest_path.size() - 1)) { + lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, goal_pose_); + remaining_distance += arc_coord.length; + } else { + remaining_distance += lanelet::utils::getLaneletLength2d(llt); + } + + index++; + } + + return remaining_distance; + +} + +double MissionRemainingDistanceTimeCalculatorNode::calcuateMissionRemainingTime(const double remaining_distance) const +{ + double current_velocity_norm = std::sqrt( + current_vehicle_velocity_.x * current_vehicle_velocity_.x + + current_vehicle_velocity_.y * current_vehicle_velocity_.y); + + if (remaining_distance < 0.01 || current_velocity_norm < 0.01) { + return 0.0; + } + + double remaining_time = remaining_distance / current_velocity_norm; + + return remaining_time; +} + +void MissionRemainingDistanceTimeCalculatorNode::publishMissionRemainingDistanceTime(const double remaining_distance, const double remaining_time) const +{ + MissionRemainingDistanceTime mission_remaining_distance_time; + + mission_remaining_distance_time.remaining_distance = remaining_distance; + mission_remaining_distance_time.remaining_time = remaining_time; + mission_remaining_distance_time_publisher_->publish(mission_remaining_distance_time); +} + +} // namespace mission_remaining_distance_time_calculator + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(mission_remaining_distance_time_calculator::MissionRemainingDistanceTimeCalculatorNode) From 3401f910b807465547cf1ab588e8b4ce1b7ffdab Mon Sep 17 00:00:00 2001 From: AhmedEbrahim Date: Tue, 7 May 2024 06:35:46 +0300 Subject: [PATCH 30/77] feat(remaining_dist_eta): remove functionalities from behavior path planner and route handler Signed-off-by: Ahmed Ebrahim --- .../behavior_path_planner_node.hpp | 8 --- .../src/behavior_path_planner_node.cpp | 28 -------- .../include/route_handler/route_handler.hpp | 19 +----- planning/route_handler/src/route_handler.cpp | 68 ------------------- 4 files changed, 1 insertion(+), 122 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index c858c0adf7a61..80c9a82e89b69 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -129,8 +129,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node bool has_received_map_{false}; bool has_received_route_{false}; - Pose goal_pose_; - route_handler::RemainingDistanceTime remaining_distance_time_; std::mutex mutex_pd_; // mutex for planner_data_ std::mutex mutex_manager_; // mutex for bt_manager_ or planner_manager_ @@ -224,12 +222,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node const std::vector> & managers, const std::shared_ptr & planner_data); - /** - * @brief publish mission remaining distance and time - */ - void publishMissionRemainingDistanceTime( - const route_handler::RemainingDistanceTime & remaining_distance_time_) const; - /** * @brief convert path with lane id to path for publish path candidate */ diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index de959e0d27019..7b7c50c1671cd 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -386,7 +386,6 @@ void BehaviorPathPlannerNode::run() planner_data_->prev_modified_goal.reset(); } planner_manager_->resetCurrentRouteLanelet(planner_data_); - goal_pose_ = route_ptr->goal_pose; } const auto controlled_by_autoware_autonomously = planner_data_->operation_mode->mode == OperationModeState::AUTONOMOUS && @@ -394,19 +393,6 @@ void BehaviorPathPlannerNode::run() if (!controlled_by_autoware_autonomously && !planner_manager_->hasApprovedModules()) planner_manager_->resetCurrentRouteLanelet(planner_data_); - // if (planner_data_->route_handler->isHandlerReady()) { - // // compute mission remaining distance - // planner_data_->route_handler->getRemainingDistance( - // planner_data_->self_odometry->pose.pose, goal_pose_, remaining_distance_time_); - - // // compute mission remaining time - // planner_data_->route_handler->getRemainingTime( - // planner_data_->self_odometry->twist.twist.linear, remaining_distance_time_); - - // // publish remaining distance and time - // publishMissionRemainingDistanceTime(remaining_distance_time_); - // } - // run behavior planner const auto output = planner_manager_->run(planner_data_); @@ -715,20 +701,6 @@ void BehaviorPathPlannerNode::publishPathReference( } } -void BehaviorPathPlannerNode::publishMissionRemainingDistanceTime( - const route_handler::RemainingDistanceTime & remaining_distance_time_) const -{ - MissionRemainingDistanceTime mission_remaining_distance_time; - - mission_remaining_distance_time.remaining_distance = remaining_distance_time_.remaining_distance; - mission_remaining_distance_time.remaining_time = remaining_distance_time_.remaining_time; - mission_remaining_distance_time.remaining_hours = remaining_distance_time_.remaining_hours; - mission_remaining_distance_time.remaining_minutes = remaining_distance_time_.remaining_minutes; - mission_remaining_distance_time.remaining_seconds = remaining_distance_time_.remaining_seconds; - - mission_remaining_distance_time_publisher_->publish(mission_remaining_distance_time); -} - Path BehaviorPathPlannerNode::convertToPath( const std::shared_ptr & path_candidate_ptr, const bool is_ready, const std::shared_ptr & planner_data) diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index 082782ea91a10..2022e52186e1f 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -22,7 +22,6 @@ #include #include #include -#include #include #include @@ -43,7 +42,6 @@ using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::LaneletSegment; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; -using geometry_msgs::msg::Vector3; using std_msgs::msg::Header; using unique_identifier_msgs::msg::UUID; using RouteSections = std::vector; @@ -52,15 +50,6 @@ enum class Direction { NONE, LEFT, RIGHT }; enum class PullOverDirection { NONE, LEFT, RIGHT }; enum class PullOutDirection { NONE, LEFT, RIGHT }; -struct RemainingDistanceTime -{ - double remaining_distance; - double remaining_time; - uint32_t remaining_hours; - uint32_t remaining_minutes; - uint32_t remaining_seconds; -}; - class RouteHandler { public: @@ -366,13 +355,7 @@ class RouteHandler lanelet::ConstPolygon3d getIntersectionAreaById(const lanelet::Id id) const; bool isPreferredLane(const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getClosestLanelets(const geometry_msgs::msg::Pose & target_pose) const; - - void getRemainingDistance( - const Pose & current_pose, const Pose & goal_pose_, - RemainingDistanceTime & remaining_dist_time) const; - void getRemainingTime( - const Vector3 & current_vehicle_velocity, RemainingDistanceTime & remaining_dist_time) const; - + private: // MUST lanelet::routing::RoutingGraphPtr routing_graph_ptr_; diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 1e3f1429e7125..76763821998bd 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -2293,72 +2293,4 @@ lanelet::ConstLanelets RouteHandler::getClosestLanelets( lanelet::utils::query::getCurrentLanelets(road_lanelets_, target_pose, &target_lanelets); return target_lanelets; } - -void RouteHandler::getRemainingDistance( - const Pose & current_pose, const Pose & goal_pose_, - RemainingDistanceTime & remaining_dist_time) const -{ - double remaining_distance = 0.0; - size_t index = 0; - - lanelet::ConstLanelet current_lanelet; - getClosestLaneletWithinRoute(current_pose, ¤t_lanelet); - - lanelet::ConstLanelet goal_lanelet; - getGoalLanelet(&goal_lanelet); - - const lanelet::Optional optional_route = - routing_graph_ptr_->getRoute(current_lanelet, goal_lanelet, 0); - - lanelet::routing::LaneletPath remaining_shortest_path; - remaining_shortest_path = optional_route->shortestPath(); - - for (auto & llt : remaining_shortest_path) { - if (remaining_shortest_path.size() == 1) { - remaining_distance += - tier4_autoware_utils::calcDistance2d(current_pose.position, goal_pose_.position); - break; - } - - if (index == 0) { - lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, current_pose); - double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt); - remaining_distance += this_lanelet_length - arc_coord.length; - } else if (index == (remaining_shortest_path.size() - 1)) { - lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, goal_pose_); - remaining_distance += arc_coord.length; - } else { - remaining_distance += lanelet::utils::getLaneletLength2d(llt); - } - - index++; - } - - remaining_dist_time.remaining_distance = remaining_distance; -} - -void RouteHandler::getRemainingTime( - const Vector3 & current_vehicle_velocity, RemainingDistanceTime & remaining_dist_time) const -{ - double current_velocity_norm = std::sqrt( - current_vehicle_velocity.x * current_vehicle_velocity.x + - current_vehicle_velocity.y * current_vehicle_velocity.y); - - if (remaining_dist_time.remaining_distance < 0.01 || current_velocity_norm < 0.01) { - remaining_dist_time.remaining_distance = 0.0; - remaining_dist_time.remaining_time = 0.0; - remaining_dist_time.remaining_hours = 0; - remaining_dist_time.remaining_minutes = 0; - remaining_dist_time.remaining_seconds = 0; - return; - } - - double remaining_time = remaining_dist_time.remaining_distance / current_velocity_norm; - remaining_dist_time.remaining_time = remaining_time; - remaining_dist_time.remaining_hours = static_cast(remaining_time / 3600.0); - remaining_time = std::fmod(remaining_time, 3600); - remaining_dist_time.remaining_minutes = static_cast(remaining_time / 60.0); - remaining_dist_time.remaining_seconds = static_cast(std::fmod(remaining_time, 60)); - return; -} } // namespace route_handler From 64ce68a7c7dc87b68f81406144123a3aa215d590 Mon Sep 17 00:00:00 2001 From: AhmedEbrahim Date: Tue, 7 May 2024 06:50:22 +0300 Subject: [PATCH 31/77] feat(remaining_dist_eta): remove some other change in behavior path planner that are no longer needed Signed-off-by: Ahmed Ebrahim --- .../behavior_planning/behavior_planning.launch.xml | 1 - planning/behavior_path_planner/README.md | 1 - .../behavior_path_planner/behavior_path_planner_node.hpp | 5 ----- .../launch/behavior_path_planner.launch.xml | 1 - planning/behavior_path_planner/package.xml | 1 - .../behavior_path_planner/src/behavior_path_planner_node.cpp | 3 --- 6 files changed, 12 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index dd4fef900909f..aa649710836da 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -194,7 +194,6 @@ - diff --git a/planning/behavior_path_planner/README.md b/planning/behavior_path_planner/README.md index 41911b22ac6e9..5d6fdbb1d7012 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -115,7 +115,6 @@ The Planner Manager's responsibilities include: | ~/output/modified_goal | `autoware_planning_msgs::msg::PoseWithUuidStamped` | output modified goal commands. | `transient_local` | | ~/output/stop_reasons | `tier4_planning_msgs::msg::StopReasonArray` | describe the reason for ego vehicle stop | `volatile` | | ~/output/reroute_availability | `tier4_planning_msgs::msg::RerouteAvailability` | the path the module is about to take. to be executed as soon as external approval is obtained. | `volatile` | -| ~/output/mission_remaining_distance_time | `autoware_planning_msgs::msg::MissionRemainingDistanceTime` | information about mission remaining distance and time. | `volatile` | ### Debug diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index 80c9a82e89b69..15528c82e923b 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -30,7 +30,6 @@ #include #include #include -#include #include #include #include @@ -61,11 +60,9 @@ using autoware_auto_planning_msgs::msg::Path; using autoware_auto_planning_msgs::msg::PathWithLaneId; using autoware_auto_vehicle_msgs::msg::HazardLightsCommand; using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand; -using autoware_internal_msgs::msg::MissionRemainingDistanceTime; using autoware_perception_msgs::msg::TrafficSignalArray; using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::PoseWithUuidStamped; -using geometry_msgs::msg::Pose; using nav_msgs::msg::OccupancyGrid; using nav_msgs::msg::Odometry; using rcl_interfaces::msg::SetParametersResult; @@ -102,8 +99,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node rclcpp::Subscription::SharedPtr lateral_offset_subscriber_; rclcpp::Subscription::SharedPtr operation_mode_subscriber_; rclcpp::Publisher::SharedPtr path_publisher_; - rclcpp::Publisher::SharedPtr - mission_remaining_distance_time_publisher_; rclcpp::Publisher::SharedPtr turn_signal_publisher_; rclcpp::Publisher::SharedPtr hazard_signal_publisher_; rclcpp::Publisher::SharedPtr bound_publisher_; diff --git a/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml b/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml index 32f23b7d13041..79c590363beb5 100644 --- a/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml +++ b/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml @@ -34,7 +34,6 @@ - diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index 7a37fa2767615..7f50c61a8343a 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -40,7 +40,6 @@ autoware_auto_planning_msgs autoware_auto_tf2 autoware_auto_vehicle_msgs - autoware_internal_msgs autoware_perception_msgs behavior_path_planner_common freespace_planning_algorithms diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 7b7c50c1671cd..d7a7633ff1243 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -62,9 +62,6 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod // publisher path_publisher_ = create_publisher("~/output/path", 1); - mission_remaining_distance_time_publisher_ = create_publisher( - "~/output/mission_remaining_distance_time", - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable()); turn_signal_publisher_ = create_publisher("~/output/turn_indicators_cmd", 1); hazard_signal_publisher_ = create_publisher("~/output/hazard_lights_cmd", 1); From 76389ec76490b9461a5b03b4ca3e7e6d1bcfa5c2 Mon Sep 17 00:00:00 2001 From: AhmedEbrahim Date: Tue, 7 May 2024 07:18:52 +0300 Subject: [PATCH 32/77] feat(remaining_dist_eta): removing unused files in remaining dist and time package Signed-off-by: Ahmed Ebrahim --- .../CMakeLists.txt | 1 - ...ion_remaining_distance_time_calculator.hpp | 346 -------- ...ion_remaining_distance_time_calculator.cpp | 785 ------------------ 3 files changed, 1132 deletions(-) delete mode 100644 planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator.hpp delete mode 100644 planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator.cpp diff --git a/planning/mission_remaining_distance_time_calculator/CMakeLists.txt b/planning/mission_remaining_distance_time_calculator/CMakeLists.txt index aa355a4c3cf07..d63f399764daa 100644 --- a/planning/mission_remaining_distance_time_calculator/CMakeLists.txt +++ b/planning/mission_remaining_distance_time_calculator/CMakeLists.txt @@ -6,7 +6,6 @@ autoware_package() ament_auto_add_library(mission_remaining_distance_time_calculator SHARED src/mission_remaining_distance_time_calculator_node.cpp - #src/mission_remaining_distance_time_calculator.cpp ) rclcpp_components_register_node(mission_remaining_distance_time_calculator diff --git a/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator.hpp b/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator.hpp deleted file mode 100644 index 416c36b116059..0000000000000 --- a/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator.hpp +++ /dev/null @@ -1,346 +0,0 @@ -// 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 OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_ -#define OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_ - -#include "motion_utils/trajectory/trajectory.hpp" -#include "obstacle_cruise_planner/common_structs.hpp" -#include "obstacle_cruise_planner/stop_planning_debug_info.hpp" -#include "obstacle_cruise_planner/type_alias.hpp" -#include "obstacle_cruise_planner/utils.hpp" -#include "tier4_autoware_utils/ros/update_param.hpp" -#include "tier4_autoware_utils/system/stop_watch.hpp" - -#include -#include -#include -#include -#include -#include -#include - -class PlannerInterface -{ -public: - PlannerInterface( - rclcpp::Node & node, const LongitudinalInfo & longitudinal_info, - const vehicle_info_util::VehicleInfo & vehicle_info, const EgoNearestParam & ego_nearest_param, - const std::shared_ptr debug_data_ptr) - : longitudinal_info_(longitudinal_info), - vehicle_info_(vehicle_info), - ego_nearest_param_(ego_nearest_param), - debug_data_ptr_(debug_data_ptr), - slow_down_param_(SlowDownParam(node)) - { - stop_reasons_pub_ = node.create_publisher("~/output/stop_reasons", 1); - velocity_factors_pub_ = - node.create_publisher("/planning/velocity_factors/obstacle_cruise", 1); - stop_speed_exceeded_pub_ = - node.create_publisher("~/output/stop_speed_exceeded", 1); - - moving_object_speed_threshold = - node.declare_parameter("slow_down.moving_object_speed_threshold"); - moving_object_hysteresis_range = - node.declare_parameter("slow_down.moving_object_hysteresis_range"); - } - - PlannerInterface() = default; - - void setParam( - const bool enable_debug_info, const bool enable_calculation_time_info, - const double min_behavior_stop_margin, const double enable_approaching_on_curve, - const double additional_safe_distance_margin_on_curve, - const double min_safe_distance_margin_on_curve, const bool suppress_sudden_obstacle_stop) - { - enable_debug_info_ = enable_debug_info; - enable_calculation_time_info_ = enable_calculation_time_info; - min_behavior_stop_margin_ = min_behavior_stop_margin; - enable_approaching_on_curve_ = enable_approaching_on_curve; - additional_safe_distance_margin_on_curve_ = additional_safe_distance_margin_on_curve; - min_safe_distance_margin_on_curve_ = min_safe_distance_margin_on_curve; - suppress_sudden_obstacle_stop_ = suppress_sudden_obstacle_stop; - } - - std::vector generateStopTrajectory( - const PlannerData & planner_data, const std::vector & stop_obstacles); - - virtual std::vector generateCruiseTrajectory( - const PlannerData & planner_data, const std::vector & stop_traj_points, - const std::vector & cruise_obstacles, - std::optional & vel_limit) = 0; - - std::vector generateSlowDownTrajectory( - const PlannerData & planner_data, const std::vector & stop_traj_points, - const std::vector & slow_down_obstacles, - std::optional & vel_limit); - - void onParam(const std::vector & parameters) - { - updateCommonParam(parameters); - updateCruiseParam(parameters); - slow_down_param_.onParam(parameters); - } - - Float32MultiArrayStamped getStopPlanningDebugMessage(const rclcpp::Time & current_time) const - { - return stop_planning_debug_info_.convertToMessage(current_time); - } - virtual Float32MultiArrayStamped getCruisePlanningDebugMessage( - [[maybe_unused]] const rclcpp::Time & current_time) const - { - return Float32MultiArrayStamped{}; - } - Float32MultiArrayStamped getSlowDownPlanningDebugMessage(const rclcpp::Time & current_time) - { - slow_down_debug_multi_array_.stamp = current_time; - return slow_down_debug_multi_array_; - } - double getSafeDistanceMargin() const { return longitudinal_info_.safe_distance_margin; } - -protected: - // Parameters - bool enable_debug_info_{false}; - bool enable_calculation_time_info_{false}; - LongitudinalInfo longitudinal_info_; - double min_behavior_stop_margin_; - bool enable_approaching_on_curve_; - double additional_safe_distance_margin_on_curve_; - double min_safe_distance_margin_on_curve_; - bool suppress_sudden_obstacle_stop_; - - // stop watch - tier4_autoware_utils::StopWatch< - std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> - stop_watch_; - - // Publishers - rclcpp::Publisher::SharedPtr stop_reasons_pub_; - rclcpp::Publisher::SharedPtr velocity_factors_pub_; - rclcpp::Publisher::SharedPtr stop_speed_exceeded_pub_; - - // Vehicle Parameters - vehicle_info_util::VehicleInfo vehicle_info_; - - EgoNearestParam ego_nearest_param_; - - mutable std::shared_ptr debug_data_ptr_; - - // debug info - StopPlanningDebugInfo stop_planning_debug_info_; - Float32MultiArrayStamped slow_down_debug_multi_array_; - - double calcDistanceToCollisionPoint( - const PlannerData & planner_data, const geometry_msgs::msg::Point & collision_point); - - double calcRSSDistance( - const double ego_vel, const double obstacle_vel, const double margin = 0.0) const - { - const auto & i = longitudinal_info_; - const double rss_dist_with_margin = - ego_vel * i.idling_time + std::pow(ego_vel, 2) * 0.5 / std::abs(i.min_ego_accel_for_rss) - - std::pow(obstacle_vel, 2) * 0.5 / std::abs(i.min_object_accel_for_rss) + margin; - return rss_dist_with_margin; - } - - void updateCommonParam(const std::vector & parameters) - { - longitudinal_info_.onParam(parameters); - } - - virtual void updateCruiseParam([[maybe_unused]] const std::vector & parameters) - { - } - - size_t findEgoIndex( - const std::vector & traj_points, - const geometry_msgs::msg::Pose & ego_pose) const - { - const auto & p = ego_nearest_param_; - return motion_utils::findFirstNearestIndexWithSoftConstraints( - traj_points, ego_pose, p.dist_threshold, p.yaw_threshold); - } - - size_t findEgoSegmentIndex( - const std::vector & traj_points, - const geometry_msgs::msg::Pose & ego_pose) const - { - const auto & p = ego_nearest_param_; - return motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - traj_points, ego_pose, p.dist_threshold, p.yaw_threshold); - } - -private: - struct SlowDownOutput - { - SlowDownOutput() = default; - SlowDownOutput( - const std::string & arg_uuid, const std::vector & traj_points, - const std::optional & start_idx, const std::optional & end_idx, - const double arg_target_vel, const double arg_feasible_target_vel, - const double arg_precise_lat_dist, const bool is_moving) - : uuid(arg_uuid), - target_vel(arg_target_vel), - feasible_target_vel(arg_feasible_target_vel), - precise_lat_dist(arg_precise_lat_dist), - is_moving(is_moving) - { - if (start_idx) { - start_point = traj_points.at(*start_idx).pose; - } - if (end_idx) { - end_point = traj_points.at(*end_idx).pose; - } - } - - std::string uuid; - double target_vel; - double feasible_target_vel; - double precise_lat_dist; - std::optional start_point{std::nullopt}; - std::optional end_point{std::nullopt}; - bool is_moving; - }; - double calculateMarginFromObstacleOnCurve( - const PlannerData & planner_data, const StopObstacle & stop_obstacle) const; - double calculateSlowDownVelocity( - const SlowDownObstacle & obstacle, const std::optional & prev_output, - const bool is_obstacle_moving) const; - std::optional> calculateDistanceToSlowDownWithConstraints( - const PlannerData & planner_data, const std::vector & traj_points, - const SlowDownObstacle & obstacle, const std::optional & prev_output, - const double dist_to_ego, const bool is_obstacle_moving) const; - - struct SlowDownInfo - { - // NOTE: Acceleration limit is applied to lon_dist not to occur sudden brake. - const double lon_dist; // from ego pose to slow down point - const double vel; // slow down velocity - }; - - struct SlowDownParam - { - std::vector obstacle_labels{"default"}; - std::vector obstacle_moving_classification{"static", "moving"}; - std::unordered_map types_map; - struct ObstacleSpecificParams - { - double max_lat_margin; - double min_lat_margin; - double max_ego_velocity; - double min_ego_velocity; - }; - explicit SlowDownParam(rclcpp::Node & node) - { - obstacle_labels = - node.declare_parameter>("slow_down.labels", obstacle_labels); - // obstacle label dependant parameters - for (const auto & label : obstacle_labels) { - for (const auto & movement_postfix : obstacle_moving_classification) { - ObstacleSpecificParams params; - params.max_lat_margin = node.declare_parameter( - "slow_down." + label + "." + movement_postfix + ".max_lat_margin"); - params.min_lat_margin = node.declare_parameter( - "slow_down." + label + "." + movement_postfix + ".min_lat_margin"); - params.max_ego_velocity = node.declare_parameter( - "slow_down." + label + "." + movement_postfix + ".max_ego_velocity"); - params.min_ego_velocity = node.declare_parameter( - "slow_down." + label + "." + movement_postfix + ".min_ego_velocity"); - obstacle_to_param_struct_map.emplace( - std::make_pair(label + "." + movement_postfix, params)); - } - } - - // common parameters - time_margin_on_target_velocity = - node.declare_parameter("slow_down.time_margin_on_target_velocity"); - lpf_gain_slow_down_vel = node.declare_parameter("slow_down.lpf_gain_slow_down_vel"); - lpf_gain_lat_dist = node.declare_parameter("slow_down.lpf_gain_lat_dist"); - lpf_gain_dist_to_slow_down = - node.declare_parameter("slow_down.lpf_gain_dist_to_slow_down"); - - types_map = {{ObjectClassification::UNKNOWN, "unknown"}, - {ObjectClassification::CAR, "car"}, - {ObjectClassification::TRUCK, "truck"}, - {ObjectClassification::BUS, "bus"}, - {ObjectClassification::TRAILER, "trailer"}, - {ObjectClassification::MOTORCYCLE, "motorcycle"}, - {ObjectClassification::BICYCLE, "bicycle"}, - {ObjectClassification::PEDESTRIAN, "pedestrian"}}; - } - - ObstacleSpecificParams getObstacleParamByLabel( - const ObjectClassification & label_id, const bool is_obstacle_moving) const - { - const std::string label = - (types_map.count(label_id.label) > 0) ? types_map.at(label_id.label) : "default"; - const std::string movement_postfix = (is_obstacle_moving) ? "moving" : "static"; - return (obstacle_to_param_struct_map.count(label + "." + movement_postfix) > 0) - ? obstacle_to_param_struct_map.at(label + "." + movement_postfix) - : obstacle_to_param_struct_map.at("default." + movement_postfix); - } - - void onParam(const std::vector & parameters) - { - // obstacle type dependant parameters - for (const auto & label : obstacle_labels) { - for (const auto & movement_postfix : obstacle_moving_classification) { - if (obstacle_to_param_struct_map.count(label + "." + movement_postfix) < 1) continue; - auto & param_by_obstacle_label = - obstacle_to_param_struct_map.at(label + "." + movement_postfix); - tier4_autoware_utils::updateParam( - parameters, "slow_down." + label + "." + movement_postfix + ".max_lat_margin", - param_by_obstacle_label.max_lat_margin); - tier4_autoware_utils::updateParam( - parameters, "slow_down." + label + "." + movement_postfix + ".min_lat_margin", - param_by_obstacle_label.min_lat_margin); - tier4_autoware_utils::updateParam( - parameters, "slow_down." + label + "." + movement_postfix + ".max_ego_velocity", - param_by_obstacle_label.max_ego_velocity); - tier4_autoware_utils::updateParam( - parameters, "slow_down." + label + "." + movement_postfix + ".min_ego_velocity", - param_by_obstacle_label.min_ego_velocity); - } - } - - // common parameters - tier4_autoware_utils::updateParam( - parameters, "slow_down.time_margin_on_target_velocity", time_margin_on_target_velocity); - tier4_autoware_utils::updateParam( - parameters, "slow_down.lpf_gain_slow_down_vel", lpf_gain_slow_down_vel); - tier4_autoware_utils::updateParam( - parameters, "slow_down.lpf_gain_lat_dist", lpf_gain_lat_dist); - tier4_autoware_utils::updateParam( - parameters, "slow_down.lpf_gain_dist_to_slow_down", lpf_gain_dist_to_slow_down); - } - - std::unordered_map obstacle_to_param_struct_map; - - double time_margin_on_target_velocity; - double lpf_gain_slow_down_vel; - double lpf_gain_lat_dist; - double lpf_gain_dist_to_slow_down; - }; - SlowDownParam slow_down_param_; - double moving_object_speed_threshold; - double moving_object_hysteresis_range; - std::vector prev_slow_down_output_; - // previous trajectory and distance to stop - // NOTE: Previous trajectory is memorized to deal with nearest index search for overlapping or - // crossing lanes. - std::optional, double>> prev_stop_distance_info_{ - std::nullopt}; -}; - -#endif // OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_ diff --git a/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator.cpp b/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator.cpp deleted file mode 100644 index f7ce218cf3ccf..0000000000000 --- a/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator.cpp +++ /dev/null @@ -1,785 +0,0 @@ -// 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 "obstacle_cruise_planner/planner_interface.hpp" - -#include "motion_utils/distance/distance.hpp" -#include "motion_utils/marker/marker_helper.hpp" -#include "motion_utils/resample/resample.hpp" -#include "motion_utils/trajectory/conversion.hpp" -#include "motion_utils/trajectory/trajectory.hpp" -#include "signal_processing/lowpass_filter_1d.hpp" -#include "tier4_autoware_utils/ros/marker_helper.hpp" - -#include -#include - -namespace -{ -StopSpeedExceeded createStopSpeedExceededMsg( - const rclcpp::Time & current_time, const bool stop_flag) -{ - StopSpeedExceeded msg{}; - msg.stamp = current_time; - msg.stop_speed_exceeded = stop_flag; - return msg; -} - -tier4_planning_msgs::msg::StopReasonArray makeStopReasonArray( - const PlannerData & planner_data, const geometry_msgs::msg::Pose & stop_pose, - const StopObstacle & stop_obstacle) -{ - // create header - std_msgs::msg::Header header; - header.frame_id = "map"; - header.stamp = planner_data.current_time; - - // create stop factor - StopFactor stop_factor; - stop_factor.stop_pose = stop_pose; - geometry_msgs::msg::Point stop_factor_point = stop_obstacle.collision_point; - stop_factor_point.z = stop_pose.position.z; - stop_factor.dist_to_stop_pose = motion_utils::calcSignedArcLength( - planner_data.traj_points, planner_data.ego_pose.position, stop_pose.position); - stop_factor.stop_factor_points.emplace_back(stop_factor_point); - - // create stop reason stamped - StopReason stop_reason_msg; - stop_reason_msg.reason = StopReason::OBSTACLE_STOP; - stop_reason_msg.stop_factors.emplace_back(stop_factor); - - // create stop reason array - StopReasonArray stop_reason_array; - stop_reason_array.header = header; - stop_reason_array.stop_reasons.emplace_back(stop_reason_msg); - return stop_reason_array; -} - -StopReasonArray makeEmptyStopReasonArray(const rclcpp::Time & current_time) -{ - // create header - std_msgs::msg::Header header; - header.frame_id = "map"; - header.stamp = current_time; - - // create stop reason stamped - StopReason stop_reason_msg; - stop_reason_msg.reason = StopReason::OBSTACLE_STOP; - - // create stop reason array - StopReasonArray stop_reason_array; - stop_reason_array.header = header; - stop_reason_array.stop_reasons.emplace_back(stop_reason_msg); - return stop_reason_array; -} - -VelocityFactorArray makeVelocityFactorArray( - const rclcpp::Time & time, const std::optional pose = std::nullopt) -{ - VelocityFactorArray velocity_factor_array; - velocity_factor_array.header.frame_id = "map"; - velocity_factor_array.header.stamp = time; - - if (pose) { - using distance_type = VelocityFactor::_distance_type; - VelocityFactor velocity_factor; - velocity_factor.behavior = PlanningBehavior::ROUTE_OBSTACLE; - velocity_factor.pose = pose.value(); - velocity_factor.distance = std::numeric_limits::quiet_NaN(); - velocity_factor.status = VelocityFactor::UNKNOWN; - velocity_factor.detail = std::string(); - velocity_factor_array.factors.push_back(velocity_factor); - } - return velocity_factor_array; -} - -double calcMinimumDistanceToStop( - const double initial_vel, const double max_acc, const double min_acc) -{ - if (initial_vel < 0.0) { - return -std::pow(initial_vel, 2) / 2.0 / max_acc; - } - - return -std::pow(initial_vel, 2) / 2.0 / min_acc; -} - -template -std::optional getObjectFromUuid(const std::vector & objects, const std::string & target_uuid) -{ - const auto itr = std::find_if(objects.begin(), objects.end(), [&](const auto & object) { - return object.uuid == target_uuid; - }); - - if (itr == objects.end()) { - return std::nullopt; - } - return *itr; -} - -// TODO(murooka) following two functions are copied from behavior_velocity_planner. -// These should be refactored. -double findReachTime( - const double jerk, const double accel, const double velocity, const double distance, - const double t_min, const double t_max) -{ - const double j = jerk; - const double a = accel; - const double v = velocity; - const double d = distance; - const double min = t_min; - const double max = t_max; - auto f = [](const double t, const double j, const double a, const double v, const double d) { - return j * t * t * t / 6.0 + a * t * t / 2.0 + v * t - d; - }; - if (f(min, j, a, v, d) > 0 || f(max, j, a, v, d) < 0) { - std::logic_error("[obstacle_cruise_planner](findReachTime): search range is invalid"); - } - const double eps = 1e-5; - const int warn_iter = 100; - double lower = min; - double upper = max; - double t; - int iter = 0; - for (int i = 0;; i++) { - t = 0.5 * (lower + upper); - const double fx = f(t, j, a, v, d); - // std::cout<<"fx: "< 0.0) { - upper = t; - } else { - lower = t; - } - iter++; - if (iter > warn_iter) - std::cerr << "[obstacle_cruise_planner](findReachTime): current iter is over warning" - << std::endl; - } - return t; -} - -double calcDecelerationVelocityFromDistanceToTarget( - const double max_slowdown_jerk, const double max_slowdown_accel, const double current_accel, - const double current_velocity, const double distance_to_target) -{ - if (max_slowdown_jerk > 0 || max_slowdown_accel > 0) { - std::logic_error("max_slowdown_jerk and max_slowdown_accel should be negative"); - } - // case0: distance to target is behind ego - if (distance_to_target <= 0) return current_velocity; - auto ft = [](const double t, const double j, const double a, const double v, const double d) { - return j * t * t * t / 6.0 + a * t * t / 2.0 + v * t - d; - }; - auto vt = [](const double t, const double j, const double a, const double v) { - return j * t * t / 2.0 + a * t + v; - }; - const double j_max = max_slowdown_jerk; - const double a0 = current_accel; - const double a_max = max_slowdown_accel; - const double v0 = current_velocity; - const double l = distance_to_target; - const double t_const_jerk = (a_max - a0) / j_max; - const double d_const_jerk_stop = ft(t_const_jerk, j_max, a0, v0, 0.0); - const double d_const_acc_stop = l - d_const_jerk_stop; - - if (d_const_acc_stop < 0) { - // case0: distance to target is within constant jerk deceleration - // use binary search instead of solving cubic equation - const double t_jerk = findReachTime(j_max, a0, v0, l, 0, t_const_jerk); - const double velocity = vt(t_jerk, j_max, a0, v0); - return velocity; - } else { - const double v1 = vt(t_const_jerk, j_max, a0, v0); - const double discriminant_of_stop = 2.0 * a_max * d_const_acc_stop + v1 * v1; - // case3: distance to target is farther than distance to stop - if (discriminant_of_stop <= 0) { - return 0.0; - } - // case2: distance to target is within constant accel deceleration - // solve d = 0.5*a^2+v*t by t - const double t_acc = (-v1 + std::sqrt(discriminant_of_stop)) / a_max; - return vt(t_acc, 0.0, a_max, v1); - } - return current_velocity; -} - -std::vector resampleTrajectoryPoints( - const std::vector & traj_points, const double interval) -{ - const auto traj = motion_utils::convertToTrajectory(traj_points); - const auto resampled_traj = motion_utils::resampleTrajectory(traj, interval); - return motion_utils::convertToTrajectoryPointArray(resampled_traj); -} - -tier4_autoware_utils::Point2d convertPoint(const geometry_msgs::msg::Point & p) -{ - return tier4_autoware_utils::Point2d{p.x, p.y}; -} -} // namespace - -std::vector PlannerInterface::generateStopTrajectory( - const PlannerData & planner_data, const std::vector & stop_obstacles) -{ - stop_watch_.tic(__func__); - - stop_planning_debug_info_.reset(); - stop_planning_debug_info_.set(StopPlanningDebugInfo::TYPE::EGO_VELOCITY, planner_data.ego_vel); - stop_planning_debug_info_.set(StopPlanningDebugInfo::TYPE::EGO_VELOCITY, planner_data.ego_acc); - - const double abs_ego_offset = planner_data.is_driving_forward - ? std::abs(vehicle_info_.max_longitudinal_offset_m) - : std::abs(vehicle_info_.min_longitudinal_offset_m); - - if (stop_obstacles.empty()) { - stop_reasons_pub_->publish(makeEmptyStopReasonArray(planner_data.current_time)); - velocity_factors_pub_->publish(makeVelocityFactorArray(planner_data.current_time)); - - // delete marker - const auto markers = - motion_utils::createDeletedStopVirtualWallMarker(planner_data.current_time, 0); - tier4_autoware_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); - - prev_stop_distance_info_ = std::nullopt; - return planner_data.traj_points; - } - - RCLCPP_INFO_EXPRESSION( - rclcpp::get_logger("ObstacleCruisePlanner::PIDBasedPlanner"), enable_debug_info_, - "stop planning"); - - // Get Closest Stop Obstacle - const auto closest_stop_obstacle = obstacle_cruise_utils::getClosestStopObstacle(stop_obstacles); - if (!closest_stop_obstacle) { - // delete marker - const auto markers = - motion_utils::createDeletedStopVirtualWallMarker(planner_data.current_time, 0); - tier4_autoware_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); - - prev_stop_distance_info_ = std::nullopt; - return planner_data.traj_points; - } - - const auto ego_segment_idx = - ego_nearest_param_.findSegmentIndex(planner_data.traj_points, planner_data.ego_pose); - const double dist_to_collide_on_ref_traj = - motion_utils::calcSignedArcLength(planner_data.traj_points, 0, ego_segment_idx) + - closest_stop_obstacle->dist_to_collide_on_decimated_traj; - - const double margin_from_obstacle_considering_behavior_module = [&]() { - const double margin_from_obstacle = - calculateMarginFromObstacleOnCurve(planner_data, *closest_stop_obstacle); - // Use terminal margin (terminal_safe_distance_margin) for obstacle stop - const auto ref_traj_length = motion_utils::calcSignedArcLength( - planner_data.traj_points, 0, planner_data.traj_points.size() - 1); - if (dist_to_collide_on_ref_traj > ref_traj_length) { - return longitudinal_info_.terminal_safe_distance_margin; - } - - // If behavior stop point is ahead of the closest_obstacle_stop point within a certain margin - // we set closest_obstacle_stop_distance to closest_behavior_stop_distance - const auto closest_behavior_stop_idx = - motion_utils::searchZeroVelocityIndex(planner_data.traj_points, ego_segment_idx + 1); - if (closest_behavior_stop_idx) { - const double closest_behavior_stop_dist_on_ref_traj = - motion_utils::calcSignedArcLength(planner_data.traj_points, 0, *closest_behavior_stop_idx); - const double stop_dist_diff = closest_behavior_stop_dist_on_ref_traj - - (dist_to_collide_on_ref_traj - margin_from_obstacle); - if (0.0 < stop_dist_diff && stop_dist_diff < margin_from_obstacle) { - return min_behavior_stop_margin_; - } - } - return margin_from_obstacle; - }(); - - // Generate Output Trajectory - const auto [zero_vel_dist, will_collide_with_obstacle] = [&]() { - double candidate_zero_vel_dist = - std::max(0.0, dist_to_collide_on_ref_traj - margin_from_obstacle_considering_behavior_module); - - // Check feasibility to stop - if (suppress_sudden_obstacle_stop_) { - // Calculate feasible stop margin (Check the feasibility) - const double feasible_stop_dist = - calcMinimumDistanceToStop( - planner_data.ego_vel, longitudinal_info_.limit_max_accel, - longitudinal_info_.limit_min_accel) + - motion_utils::calcSignedArcLength( - planner_data.traj_points, 0, planner_data.ego_pose.position); - - if (candidate_zero_vel_dist < feasible_stop_dist) { - candidate_zero_vel_dist = feasible_stop_dist; - return std::make_pair(candidate_zero_vel_dist, true); - } - } - - // Hold previous stop distance if necessary - if ( - std::abs(planner_data.ego_vel) < longitudinal_info_.hold_stop_velocity_threshold && - prev_stop_distance_info_) { - // NOTE: We assume that the current trajectory's front point is ahead of the previous - // trajectory's front point. - const size_t traj_front_point_prev_seg_idx = - motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - prev_stop_distance_info_->first, planner_data.traj_points.front().pose); - const double diff_dist_front_points = motion_utils::calcSignedArcLength( - prev_stop_distance_info_->first, 0, planner_data.traj_points.front().pose.position, - traj_front_point_prev_seg_idx); - - const double prev_zero_vel_dist = prev_stop_distance_info_->second - diff_dist_front_points; - if ( - std::abs(prev_zero_vel_dist - candidate_zero_vel_dist) < - longitudinal_info_.hold_stop_distance_threshold) { - candidate_zero_vel_dist = prev_zero_vel_dist; - } - } - return std::make_pair(candidate_zero_vel_dist, false); - }(); - - // Insert stop point - auto output_traj_points = planner_data.traj_points; - const auto zero_vel_idx = motion_utils::insertStopPoint(0, zero_vel_dist, output_traj_points); - if (zero_vel_idx) { - // virtual wall marker for stop obstacle - const auto markers = motion_utils::createStopVirtualWallMarker( - output_traj_points.at(*zero_vel_idx).pose, "obstacle stop", planner_data.current_time, 0, - abs_ego_offset, "", planner_data.is_driving_forward); - tier4_autoware_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); - debug_data_ptr_->obstacles_to_stop.push_back(*closest_stop_obstacle); - - // Publish Stop Reason - const auto stop_pose = output_traj_points.at(*zero_vel_idx).pose; - const auto stop_reasons_msg = - makeStopReasonArray(planner_data, stop_pose, *closest_stop_obstacle); - stop_reasons_pub_->publish(stop_reasons_msg); - velocity_factors_pub_->publish(makeVelocityFactorArray(planner_data.current_time, stop_pose)); - - // Publish if ego vehicle collides with the obstacle with a limit acceleration - const auto stop_speed_exceeded_msg = - createStopSpeedExceededMsg(planner_data.current_time, will_collide_with_obstacle); - stop_speed_exceeded_pub_->publish(stop_speed_exceeded_msg); - - prev_stop_distance_info_ = std::make_pair(output_traj_points, zero_vel_dist); - } - - stop_planning_debug_info_.set( - StopPlanningDebugInfo::TYPE::STOP_CURRENT_OBSTACLE_DISTANCE, - closest_stop_obstacle->dist_to_collide_on_decimated_traj); - stop_planning_debug_info_.set( - StopPlanningDebugInfo::TYPE::STOP_CURRENT_OBSTACLE_VELOCITY, closest_stop_obstacle->velocity); - - stop_planning_debug_info_.set( - StopPlanningDebugInfo::TYPE::STOP_TARGET_OBSTACLE_DISTANCE, - margin_from_obstacle_considering_behavior_module); - stop_planning_debug_info_.set(StopPlanningDebugInfo::TYPE::STOP_TARGET_VELOCITY, 0.0); - stop_planning_debug_info_.set(StopPlanningDebugInfo::TYPE::STOP_TARGET_ACCELERATION, 0.0); - - const double calculation_time = stop_watch_.toc(__func__); - RCLCPP_INFO_EXPRESSION( - rclcpp::get_logger("ObstacleCruisePlanner::SlowDownPlanner"), enable_calculation_time_info_, - " %s := %f [ms]", __func__, calculation_time); - - return output_traj_points; -} - -double PlannerInterface::calculateMarginFromObstacleOnCurve( - const PlannerData & planner_data, const StopObstacle & stop_obstacle) const -{ - if (!enable_approaching_on_curve_) { - return longitudinal_info_.safe_distance_margin; - } - - const double abs_ego_offset = planner_data.is_driving_forward - ? std::abs(vehicle_info_.max_longitudinal_offset_m) - : std::abs(vehicle_info_.min_longitudinal_offset_m); - - // calculate short trajectory points towards obstacle - const size_t obj_segment_idx = - motion_utils::findNearestSegmentIndex(planner_data.traj_points, stop_obstacle.collision_point); - std::vector short_traj_points{planner_data.traj_points.at(obj_segment_idx + 1)}; - double sum_short_traj_length{0.0}; - for (int i = obj_segment_idx; 0 <= i; --i) { - short_traj_points.push_back(planner_data.traj_points.at(i)); - - if ( - 1 < short_traj_points.size() && - longitudinal_info_.safe_distance_margin + abs_ego_offset < sum_short_traj_length) { - break; - } - sum_short_traj_length += tier4_autoware_utils::calcDistance2d( - planner_data.traj_points.at(i), planner_data.traj_points.at(i + 1)); - } - std::reverse(short_traj_points.begin(), short_traj_points.end()); - if (short_traj_points.size() < 2) { - return longitudinal_info_.safe_distance_margin; - } - - // calculate collision index between straight line from ego pose and object - const auto calculate_distance_from_straight_ego_path = - [&](const auto & ego_pose, const auto & object_polygon) { - const auto forward_ego_pose = tier4_autoware_utils::calcOffsetPose( - ego_pose, longitudinal_info_.safe_distance_margin + 3.0, 0.0, 0.0); - const auto ego_straight_segment = tier4_autoware_utils::Segment2d{ - convertPoint(ego_pose.position), convertPoint(forward_ego_pose.position)}; - return boost::geometry::distance(ego_straight_segment, object_polygon); - }; - const auto resampled_short_traj_points = resampleTrajectoryPoints(short_traj_points, 0.5); - const auto object_polygon = - tier4_autoware_utils::toPolygon2d(stop_obstacle.pose, stop_obstacle.shape); - const auto collision_idx = [&]() -> std::optional { - for (size_t i = 0; i < resampled_short_traj_points.size(); ++i) { - const double dist_to_obj = calculate_distance_from_straight_ego_path( - resampled_short_traj_points.at(i).pose, object_polygon); - if (dist_to_obj < vehicle_info_.vehicle_width_m / 2.0) { - return i; - } - } - return std::nullopt; - }(); - if (!collision_idx) { - return min_safe_distance_margin_on_curve_; - } - if (*collision_idx == 0) { - return longitudinal_info_.safe_distance_margin; - } - - // calculate margin from obstacle - const double partial_segment_length = [&]() { - const double collision_segment_length = tier4_autoware_utils::calcDistance2d( - resampled_short_traj_points.at(*collision_idx - 1), - resampled_short_traj_points.at(*collision_idx)); - const double prev_dist = calculate_distance_from_straight_ego_path( - resampled_short_traj_points.at(*collision_idx - 1).pose, object_polygon); - const double next_dist = calculate_distance_from_straight_ego_path( - resampled_short_traj_points.at(*collision_idx).pose, object_polygon); - return (next_dist - vehicle_info_.vehicle_width_m / 2.0) / (next_dist - prev_dist) * - collision_segment_length; - }(); - - const double short_margin_from_obstacle = - partial_segment_length + - motion_utils::calcSignedArcLength( - resampled_short_traj_points, *collision_idx, stop_obstacle.collision_point) - - abs_ego_offset + additional_safe_distance_margin_on_curve_; - - return std::min( - longitudinal_info_.safe_distance_margin, - std::max(min_safe_distance_margin_on_curve_, short_margin_from_obstacle)); -} - -double PlannerInterface::calcDistanceToCollisionPoint( - const PlannerData & planner_data, const geometry_msgs::msg::Point & collision_point) -{ - const double offset = planner_data.is_driving_forward - ? std::abs(vehicle_info_.max_longitudinal_offset_m) - : std::abs(vehicle_info_.min_longitudinal_offset_m); - - const size_t ego_segment_idx = - ego_nearest_param_.findSegmentIndex(planner_data.traj_points, planner_data.ego_pose); - - const size_t collision_segment_idx = - motion_utils::findNearestSegmentIndex(planner_data.traj_points, collision_point); - - const auto dist_to_collision_point = motion_utils::calcSignedArcLength( - planner_data.traj_points, planner_data.ego_pose.position, ego_segment_idx, collision_point, - collision_segment_idx); - - return dist_to_collision_point - offset; -} - -std::vector PlannerInterface::generateSlowDownTrajectory( - const PlannerData & planner_data, const std::vector & cruise_traj_points, - const std::vector & obstacles, - [[maybe_unused]] std::optional & vel_limit) -{ - stop_watch_.tic(__func__); - auto slow_down_traj_points = cruise_traj_points; - slow_down_debug_multi_array_ = Float32MultiArrayStamped(); - - const double dist_to_ego = [&]() { - const size_t ego_seg_idx = - ego_nearest_param_.findSegmentIndex(slow_down_traj_points, planner_data.ego_pose); - return motion_utils::calcSignedArcLength( - slow_down_traj_points, 0, planner_data.ego_pose.position, ego_seg_idx); - }(); - const double abs_ego_offset = planner_data.is_driving_forward - ? std::abs(vehicle_info_.max_longitudinal_offset_m) - : std::abs(vehicle_info_.min_longitudinal_offset_m); - - // define function to insert slow down velocity to trajectory - const auto insert_point_in_trajectory = [&](const double lon_dist) -> std::optional { - const auto inserted_idx = motion_utils::insertTargetPoint(0, lon_dist, slow_down_traj_points); - if (inserted_idx) { - if (inserted_idx.value() + 1 <= slow_down_traj_points.size() - 1) { - // zero-order hold for velocity interpolation - slow_down_traj_points.at(inserted_idx.value()).longitudinal_velocity_mps = - slow_down_traj_points.at(inserted_idx.value() + 1).longitudinal_velocity_mps; - } - return inserted_idx.value(); - } - return std::nullopt; - }; - - std::vector new_prev_slow_down_output; - for (size_t i = 0; i < obstacles.size(); ++i) { - const auto & obstacle = obstacles.at(i); - const auto prev_output = getObjectFromUuid(prev_slow_down_output_, obstacle.uuid); - - const bool is_obstacle_moving = [&]() -> bool { - const auto object_vel_norm = std::hypot(obstacle.velocity, obstacle.lat_velocity); - if (!prev_output) return object_vel_norm > moving_object_speed_threshold; - if (prev_output->is_moving) - return object_vel_norm > moving_object_speed_threshold - moving_object_hysteresis_range; - return object_vel_norm > moving_object_speed_threshold + moving_object_hysteresis_range; - }(); - - // calculate slow down start distance, and insert slow down velocity - const auto dist_vec_to_slow_down = calculateDistanceToSlowDownWithConstraints( - planner_data, slow_down_traj_points, obstacle, prev_output, dist_to_ego, is_obstacle_moving); - if (!dist_vec_to_slow_down) { - RCLCPP_INFO_EXPRESSION( - rclcpp::get_logger("ObstacleCruisePlanner::PlannerInterface"), enable_debug_info_, - "[SlowDown] Ignore obstacle (%s) since distance to slow down is not valid", - obstacle.uuid.c_str()); - continue; - } - const auto [dist_to_slow_down_start, dist_to_slow_down_end, feasible_slow_down_vel] = - *dist_vec_to_slow_down; - - // calculate slow down end distance, and insert slow down velocity - // NOTE: slow_down_start_idx will not be wrong since inserted back point is after inserted - // front point. - const auto slow_down_start_idx = insert_point_in_trajectory(dist_to_slow_down_start); - const auto slow_down_end_idx = dist_to_slow_down_start < dist_to_slow_down_end - ? insert_point_in_trajectory(dist_to_slow_down_end) - : std::nullopt; - if (!slow_down_end_idx) { - continue; - } - - // calculate slow down velocity - const double stable_slow_down_vel = [&]() { - if (prev_output) { - return signal_processing::lowpassFilter( - feasible_slow_down_vel, prev_output->target_vel, slow_down_param_.lpf_gain_slow_down_vel); - } - return feasible_slow_down_vel; - }(); - - // insert slow down velocity between slow start and end - for (size_t i = (slow_down_start_idx ? *slow_down_start_idx : 0); i <= *slow_down_end_idx; - ++i) { - auto & traj_point = slow_down_traj_points.at(i); - traj_point.longitudinal_velocity_mps = - std::min(traj_point.longitudinal_velocity_mps, static_cast(stable_slow_down_vel)); - } - - // add debug data - slow_down_debug_multi_array_.data.push_back(obstacle.precise_lat_dist); - slow_down_debug_multi_array_.data.push_back(dist_to_slow_down_start); - slow_down_debug_multi_array_.data.push_back(dist_to_slow_down_end); - slow_down_debug_multi_array_.data.push_back(feasible_slow_down_vel); - slow_down_debug_multi_array_.data.push_back(stable_slow_down_vel); - slow_down_debug_multi_array_.data.push_back(slow_down_start_idx ? *slow_down_start_idx : -1.0); - slow_down_debug_multi_array_.data.push_back(slow_down_end_idx ? *slow_down_end_idx : -1.0); - - // add virtual wall - if (slow_down_start_idx && slow_down_end_idx) { - const size_t ego_idx = - ego_nearest_param_.findIndex(slow_down_traj_points, planner_data.ego_pose); - const size_t slow_down_wall_idx = [&]() { - if (ego_idx < *slow_down_start_idx) return *slow_down_start_idx; - if (ego_idx < *slow_down_end_idx) return ego_idx; - return *slow_down_end_idx; - }(); - - const auto markers = motion_utils::createSlowDownVirtualWallMarker( - slow_down_traj_points.at(slow_down_wall_idx).pose, "obstacle slow down", - planner_data.current_time, i, abs_ego_offset, "", planner_data.is_driving_forward); - tier4_autoware_utils::appendMarkerArray(markers, &debug_data_ptr_->slow_down_wall_marker); - } - - // add debug virtual wall - if (slow_down_start_idx) { - const auto markers = motion_utils::createSlowDownVirtualWallMarker( - slow_down_traj_points.at(*slow_down_start_idx).pose, "obstacle slow down start", - planner_data.current_time, i * 2, abs_ego_offset, "", planner_data.is_driving_forward); - tier4_autoware_utils::appendMarkerArray( - markers, &debug_data_ptr_->slow_down_debug_wall_marker); - } - if (slow_down_end_idx) { - const auto markers = motion_utils::createSlowDownVirtualWallMarker( - slow_down_traj_points.at(*slow_down_end_idx).pose, "obstacle slow down end", - planner_data.current_time, i * 2 + 1, abs_ego_offset, "", planner_data.is_driving_forward); - tier4_autoware_utils::appendMarkerArray( - markers, &debug_data_ptr_->slow_down_debug_wall_marker); - } - - debug_data_ptr_->obstacles_to_slow_down.push_back(obstacle); - - // update prev_slow_down_output_ - new_prev_slow_down_output.push_back(SlowDownOutput{ - obstacle.uuid, slow_down_traj_points, slow_down_start_idx, slow_down_end_idx, - stable_slow_down_vel, feasible_slow_down_vel, obstacle.precise_lat_dist, is_obstacle_moving}); - } - - // update prev_slow_down_output_ - prev_slow_down_output_ = new_prev_slow_down_output; - - const double calculation_time = stop_watch_.toc(__func__); - RCLCPP_INFO_EXPRESSION( - rclcpp::get_logger("ObstacleCruisePlanner::SlowDownPlanner"), enable_calculation_time_info_, - " %s := %f [ms]", __func__, calculation_time); - - return slow_down_traj_points; -} - -double PlannerInterface::calculateSlowDownVelocity( - const SlowDownObstacle & obstacle, const std::optional & prev_output, - const bool is_obstacle_moving) const -{ - const auto & p = - slow_down_param_.getObstacleParamByLabel(obstacle.classification, is_obstacle_moving); - const double stable_precise_lat_dist = [&]() { - if (prev_output) { - return signal_processing::lowpassFilter( - obstacle.precise_lat_dist, prev_output->precise_lat_dist, - slow_down_param_.lpf_gain_lat_dist); - } - return obstacle.precise_lat_dist; - }(); - - const double ratio = std::clamp( - (std::abs(stable_precise_lat_dist) - p.min_lat_margin) / (p.max_lat_margin - p.min_lat_margin), - 0.0, 1.0); - const double slow_down_vel = - p.min_ego_velocity + ratio * (p.max_ego_velocity - p.min_ego_velocity); - - return slow_down_vel; -} - -std::optional> -PlannerInterface::calculateDistanceToSlowDownWithConstraints( - const PlannerData & planner_data, const std::vector & traj_points, - const SlowDownObstacle & obstacle, const std::optional & prev_output, - const double dist_to_ego, const bool is_obstacle_moving) const -{ - const double abs_ego_offset = planner_data.is_driving_forward - ? std::abs(vehicle_info_.max_longitudinal_offset_m) - : std::abs(vehicle_info_.min_longitudinal_offset_m); - const double obstacle_vel = obstacle.velocity; - // calculate slow down velocity - const double slow_down_vel = calculateSlowDownVelocity(obstacle, prev_output, is_obstacle_moving); - - // calculate distance to collision points - const double dist_to_front_collision = - motion_utils::calcSignedArcLength(traj_points, 0, obstacle.front_collision_point); - const double dist_to_back_collision = - motion_utils::calcSignedArcLength(traj_points, 0, obstacle.back_collision_point); - - // calculate offset distance to first collision considering relative velocity - const double relative_vel = planner_data.ego_vel - obstacle.velocity; - const double offset_dist_to_collision = [&]() { - if (dist_to_front_collision < dist_to_ego + abs_ego_offset) { - return 0.0; - } - - // NOTE: This min_relative_vel forces the relative velocity positive if the ego velocity is - // lower than the obstacle velocity. Without this, the slow down feature will flicker where - // the ego velocity is very close to the obstacle velocity. - constexpr double min_relative_vel = 1.0; - const double time_to_collision = (dist_to_front_collision - dist_to_ego - abs_ego_offset) / - std::max(min_relative_vel, relative_vel); - - constexpr double time_to_collision_margin = 1.0; - const double cropped_time_to_collision = - std::max(0.0, time_to_collision - time_to_collision_margin); - return obstacle_vel * cropped_time_to_collision; - }(); - - // calculate distance during deceleration, slow down preparation, and slow down - const double min_slow_down_prepare_dist = 3.0; - const double slow_down_prepare_dist = std::max( - min_slow_down_prepare_dist, slow_down_vel * slow_down_param_.time_margin_on_target_velocity); - const double deceleration_dist = offset_dist_to_collision + dist_to_front_collision - - abs_ego_offset - dist_to_ego - slow_down_prepare_dist; - const double slow_down_dist = - dist_to_back_collision - dist_to_front_collision + slow_down_prepare_dist; - - // calculate distance to start/end slow down - const double dist_to_slow_down_start = dist_to_ego + deceleration_dist; - const double dist_to_slow_down_end = dist_to_ego + deceleration_dist + slow_down_dist; - if (100.0 < dist_to_slow_down_start) { - // NOTE: distance to slow down is too far. - return std::nullopt; - } - - // apply low-pass filter to distance to start/end slow down - const auto apply_lowpass_filter = [&](const double dist_to_slow_down, const auto prev_point) { - if (prev_output && prev_point) { - const size_t seg_idx = - motion_utils::findNearestSegmentIndex(traj_points, prev_point->position); - const double prev_dist_to_slow_down = - motion_utils::calcSignedArcLength(traj_points, 0, prev_point->position, seg_idx); - return signal_processing::lowpassFilter( - dist_to_slow_down, prev_dist_to_slow_down, slow_down_param_.lpf_gain_dist_to_slow_down); - } - return dist_to_slow_down; - }; - const double filtered_dist_to_slow_down_start = - apply_lowpass_filter(dist_to_slow_down_start, prev_output->start_point); - const double filtered_dist_to_slow_down_end = - apply_lowpass_filter(dist_to_slow_down_end, prev_output->end_point); - - // calculate velocity considering constraints - const double feasible_slow_down_vel = [&]() { - if (deceleration_dist < 0) { - if (prev_output) { - return prev_output->target_vel; - } - return std::max(planner_data.ego_vel, slow_down_vel); - } - if (planner_data.ego_vel < slow_down_vel) { - return slow_down_vel; - } - - const double one_shot_feasible_slow_down_vel = [&]() { - if (planner_data.ego_acc < longitudinal_info_.min_accel) { - const double squared_vel = - std::pow(planner_data.ego_vel, 2) + 2 * deceleration_dist * longitudinal_info_.min_accel; - if (squared_vel < 0) { - return slow_down_vel; - } - return std::max(std::sqrt(squared_vel), slow_down_vel); - } - // TODO(murooka) Calculate more precisely. Final acceleration should be zero. - const double min_feasible_slow_down_vel = calcDecelerationVelocityFromDistanceToTarget( - longitudinal_info_.slow_down_min_jerk, longitudinal_info_.slow_down_min_accel, - planner_data.ego_acc, planner_data.ego_vel, deceleration_dist); - return min_feasible_slow_down_vel; - }(); - if (prev_output) { - // NOTE: If longitudinal controllability is not good, one_shot_slow_down_vel may be getting - // larger since we use actual ego's velocity and acceleration for its calculation. - // Suppress one_shot_slow_down_vel getting larger here. - const double feasible_slow_down_vel = - std::min(one_shot_feasible_slow_down_vel, prev_output->feasible_target_vel); - return std::max(slow_down_vel, feasible_slow_down_vel); - } - return std::max(slow_down_vel, one_shot_feasible_slow_down_vel); - }(); - - return std::make_tuple( - filtered_dist_to_slow_down_start, filtered_dist_to_slow_down_end, feasible_slow_down_vel); -} From 020c8dc5bfccb3270dbf3b2d609f3b327f6122b0 Mon Sep 17 00:00:00 2001 From: AhmedEbrahim Date: Tue, 7 May 2024 07:22:38 +0300 Subject: [PATCH 33/77] feat(remaining_dist_eta): header file cleaning up Signed-off-by: Ahmed Ebrahim --- ...emaining_distance_time_calculator_node.hpp | 30 +++++++------------ 1 file changed, 10 insertions(+), 20 deletions(-) diff --git a/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp b/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp index 50483fcfc4b7a..eb1c4016de757 100644 --- a/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp +++ b/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp @@ -58,43 +58,39 @@ class MissionRemainingDistanceTimeCalculatorNode : public rclcpp::Node private: // Subscriber - rclcpp::Subscription::SharedPtr route_subscriber_; + rclcpp::Subscription::SharedPtr route_subscriber_; rclcpp::Subscription::SharedPtr map_subscriber_; rclcpp::Subscription::SharedPtr odometry_subscriber_; - // rclcpp::Subscription::SharedPtr sub_initial_pose_; - // tier4_autoware_utils::SelfPoseListener self_pose_listener_; - // rclcpp::Subscription::SharedPtr sub_route_; - // // Data Buffer - // geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_; - // autoware_auto_planning_msgs::msg::Route::SharedPtr route_; - // // Callback - // void onRoute(const autoware_auto_planning_msgs::msg::Route::ConstSharedPtr & msg); - - // // Publisher + // Publisher rclcpp::Publisher::SharedPtr mission_remaining_distance_time_publisher_; - // tier4_autoware_utils::DebugPublisher debug_publisher_; + // Timer rclcpp::TimerBase::SharedPtr timer_; + // Route Handler route_handler::RouteHandler route_handler_; lanelet::LaneletMapPtr lanelet_map_ptr_; lanelet::routing::RoutingGraphPtr routing_graph_ptr_; lanelet::traffic_rules::TrafficRulesPtr traffic_rules_ptr_; lanelet::ConstLanelets road_lanelets_; bool is_graph_ready_; - + + // Callback void onTimer(); void onOdometry(const Odometry::ConstSharedPtr msg); void onRoute(const LaneletRoute::ConstSharedPtr msg); void onMap(const HADMapBin::ConstSharedPtr msg); + + // Calculate and publish methods double calcuateMissionRemainingDistance() const; double calcuateMissionRemainingTime(const double remaining_distance) const; void publishMissionRemainingDistanceTime(const double remaining_distance, const double remaining_time) const; - + + // Data Buffer Pose current_vehicle_pose_; Vector3 current_vehicle_velocity_; Pose goal_pose_; @@ -102,12 +98,6 @@ class MissionRemainingDistanceTimeCalculatorNode : public rclcpp::Node // Parameter NodeParam node_param_; - - - // Core - // Input input_; - // Output output_; - // std::unique_ptr goal_distance_calculator_; }; } // namespace mission_remaining_distance_time_calculator #endif // MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__HPP_ From 84b3c0ec33cb75c233809f91c34ed00f94a3f187 Mon Sep 17 00:00:00 2001 From: AhmedEbrahim Date: Tue, 7 May 2024 07:25:20 +0300 Subject: [PATCH 34/77] feat(remaining_dist_eta): node cpp file cleaning up Signed-off-by: Ahmed Ebrahim --- ...ssion_remaining_distance_time_calculator_node.cpp | 12 +----------- 1 file changed, 1 insertion(+), 11 deletions(-) diff --git a/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp b/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp index ab71eaec9164c..4a1b4dbf1e528 100644 --- a/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp +++ b/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp @@ -56,19 +56,11 @@ MissionRemainingDistanceTimeCalculatorNode::MissionRemainingDistanceTimeCalculat // Node Parameter node_param_.update_rate = declare_parameter("update_rate", 10.0); - // Core - //mission_remaining_distance_time_calculator_ = std::make_unique(); - - - + // Timer const auto period_ns = rclcpp::Rate(node_param_.update_rate).period(); timer_ = rclcpp::create_timer( this, get_clock(), period_ns, std::bind(&MissionRemainingDistanceTimeCalculatorNode::onTimer, this)); - // timer_ = this->create_wall_timer(500ms, std::bind(&MissionRemainingDistanceTimeCalculatorNode::onTimer, this)); - - - RCLCPP_INFO_STREAM(this->get_logger(), "Finished"); } @@ -114,11 +106,9 @@ double MissionRemainingDistanceTimeCalculatorNode::calcuateMissionRemainingDista size_t index = 0; lanelet::ConstLanelet current_lanelet; - ///route_handler_.getClosestLaneletWithinRoute(current_vehicle_pose_, ¤t_lanelet); lanelet::utils::query::getClosestLanelet(road_lanelets_, current_vehicle_pose_, ¤t_lanelet); lanelet::ConstLanelet goal_lanelet; - //route_handler_.getGoalLanelet(&goal_lanelet); lanelet::utils::query::getClosestLanelet(road_lanelets_, goal_pose_, &goal_lanelet); From ae74169164225769a0e09b441a134ec8c4ed4a7e Mon Sep 17 00:00:00 2001 From: AhmedEbrahim Date: Tue, 7 May 2024 07:37:02 +0300 Subject: [PATCH 35/77] feat(remaining_dist_eta): package.xml clean up Signed-off-by: Ahmed Ebrahim --- .../package.xml | 11 +---------- 1 file changed, 1 insertion(+), 10 deletions(-) diff --git a/planning/mission_remaining_distance_time_calculator/package.xml b/planning/mission_remaining_distance_time_calculator/package.xml index 25c79d8d65610..0260d24b620e9 100644 --- a/planning/mission_remaining_distance_time_calculator/package.xml +++ b/planning/mission_remaining_distance_time_calculator/package.xml @@ -13,28 +13,19 @@ autoware_internal_msgs route_handler - autoware_adapi_v1_msgs - autoware_auto_perception_msgs - autoware_auto_planning_msgs + autoware_planning_msgs geometry_msgs - interpolation lanelet2_extension motion_utils nav_msgs - object_recognition_utils - osqp_interface planning_test_utils rclcpp rclcpp_components - signal_processing std_msgs tf2 tf2_ros tier4_autoware_utils - tier4_debug_msgs tier4_planning_msgs - vehicle_info_util - visualization_msgs ament_cmake_ros ament_lint_auto From 33ff5dc2301901bc6830d1c358c0bff1bb93d4e0 Mon Sep 17 00:00:00 2001 From: AhmedEbrahim Date: Tue, 7 May 2024 07:38:22 +0300 Subject: [PATCH 36/77] feat(remaining_dist_eta): package.xml cleaning up Signed-off-by: Ahmed Ebrahim --- planning/mission_remaining_distance_time_calculator/package.xml | 2 -- 1 file changed, 2 deletions(-) diff --git a/planning/mission_remaining_distance_time_calculator/package.xml b/planning/mission_remaining_distance_time_calculator/package.xml index 0260d24b620e9..bd988b8f7585c 100644 --- a/planning/mission_remaining_distance_time_calculator/package.xml +++ b/planning/mission_remaining_distance_time_calculator/package.xml @@ -22,8 +22,6 @@ rclcpp rclcpp_components std_msgs - tf2 - tf2_ros tier4_autoware_utils tier4_planning_msgs From 87e48d29c044e9aae5b531fa7b90de45331d0d36 Mon Sep 17 00:00:00 2001 From: AhmedEbrahim Date: Tue, 7 May 2024 07:41:56 +0300 Subject: [PATCH 37/77] feat(remaining_dist_eta): package.xml cleaning up Signed-off-by: Ahmed Ebrahim --- planning/mission_remaining_distance_time_calculator/package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/planning/mission_remaining_distance_time_calculator/package.xml b/planning/mission_remaining_distance_time_calculator/package.xml index bd988b8f7585c..80152e3617fad 100644 --- a/planning/mission_remaining_distance_time_calculator/package.xml +++ b/planning/mission_remaining_distance_time_calculator/package.xml @@ -23,7 +23,6 @@ rclcpp_components std_msgs tier4_autoware_utils - tier4_planning_msgs ament_cmake_ros ament_lint_auto From 5e332ba3337831fd915a0afa8aba8cd767acabba Mon Sep 17 00:00:00 2001 From: AhmedEbrahim Date: Tue, 7 May 2024 07:44:41 +0300 Subject: [PATCH 38/77] feat(remaining_dist_eta): add comments Signed-off-by: Ahmed Ebrahim --- ...ion_remaining_distance_time_calculator_node.hpp | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp b/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp index eb1c4016de757..27f82aeb0b8e5 100644 --- a/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp +++ b/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp @@ -86,10 +86,20 @@ class MissionRemainingDistanceTimeCalculatorNode : public rclcpp::Node void onMap(const HADMapBin::ConstSharedPtr msg); // Calculate and publish methods + /** + * @brief calculate mission remaining distance + */ double calcuateMissionRemainingDistance() const; + /** + * @brief calculate mission remaining time + */ double calcuateMissionRemainingTime(const double remaining_distance) const; - void publishMissionRemainingDistanceTime(const double remaining_distance, const double remaining_time) const; - + /** + * @brief publish mission remaining distance and time + */ + void publishMissionRemainingDistanceTime( + const double remaining_distance, const double remaining_time) const; + // Data Buffer Pose current_vehicle_pose_; Vector3 current_vehicle_velocity_; From 686f80823b9ef2e64a0dd11c95e144b64adc2cc1 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 7 May 2024 04:50:09 +0000 Subject: [PATCH 39/77] style(pre-commit): autofix --- .../launch/planning.launch.xml | 3 +- planning/behavior_path_planner/README.md | 16 ++--- .../behavior_path_planner_node.hpp | 1 - .../README.md | 6 -- ...emaining_distance_time_calculator_node.hpp | 37 ++++++------ ...aining_distance_time_calculator.launch.xml | 9 +-- .../package.xml | 4 +- ...emaining_distance_time_calculator_node.cpp | 58 +++++++++---------- .../include/route_handler/route_handler.hpp | 2 +- 9 files changed, 63 insertions(+), 73 deletions(-) diff --git a/launch/tier4_planning_launch/launch/planning.launch.xml b/launch/tier4_planning_launch/launch/planning.launch.xml index a69746085e205..2e6cead267553 100644 --- a/launch/tier4_planning_launch/launch/planning.launch.xml +++ b/launch/tier4_planning_launch/launch/planning.launch.xml @@ -44,10 +44,9 @@ - + - diff --git a/planning/behavior_path_planner/README.md b/planning/behavior_path_planner/README.md index 5d6fdbb1d7012..03f8c8d2a5696 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -107,14 +107,14 @@ The Planner Manager's responsibilities include: ### Output -| Name | Type | Description | QoS Durability | -| :--------------------------------------- | :---------------------------------------------------------- | :--------------------------------------------------------------------------------------------- | ----------------- | -| ~/output/path | `autoware_auto_planning_msgs::msg::PathWithLaneId` | the path generated by modules. | `volatile` | -| ~/output/turn_indicators_cmd | `autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand` | turn indicators command. | `volatile` | -| ~/output/hazard_lights_cmd | `autoware_auto_vehicle_msgs::msg::HazardLightsCommand` | hazard lights command. | `volatile` | -| ~/output/modified_goal | `autoware_planning_msgs::msg::PoseWithUuidStamped` | output modified goal commands. | `transient_local` | -| ~/output/stop_reasons | `tier4_planning_msgs::msg::StopReasonArray` | describe the reason for ego vehicle stop | `volatile` | -| ~/output/reroute_availability | `tier4_planning_msgs::msg::RerouteAvailability` | the path the module is about to take. to be executed as soon as external approval is obtained. | `volatile` | +| Name | Type | Description | QoS Durability | +| :---------------------------- | :------------------------------------------------------- | :--------------------------------------------------------------------------------------------- | ----------------- | +| ~/output/path | `autoware_auto_planning_msgs::msg::PathWithLaneId` | the path generated by modules. | `volatile` | +| ~/output/turn_indicators_cmd | `autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand` | turn indicators command. | `volatile` | +| ~/output/hazard_lights_cmd | `autoware_auto_vehicle_msgs::msg::HazardLightsCommand` | hazard lights command. | `volatile` | +| ~/output/modified_goal | `autoware_planning_msgs::msg::PoseWithUuidStamped` | output modified goal commands. | `transient_local` | +| ~/output/stop_reasons | `tier4_planning_msgs::msg::StopReasonArray` | describe the reason for ego vehicle stop | `volatile` | +| ~/output/reroute_availability | `tier4_planning_msgs::msg::RerouteAvailability` | the path the module is about to take. to be executed as soon as external approval is obtained. | `volatile` | ### Debug diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index 15528c82e923b..44d453a3435fa 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -124,7 +124,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node bool has_received_map_{false}; bool has_received_route_{false}; - std::mutex mutex_pd_; // mutex for planner_data_ std::mutex mutex_manager_; // mutex for bt_manager_ or planner_manager_ std::mutex mutex_map_; // mutex for has_received_map_ and map_ptr_ diff --git a/planning/mission_remaining_distance_time_calculator/README.md b/planning/mission_remaining_distance_time_calculator/README.md index cdec3bbcd16ec..06b63bf5fef3e 100644 --- a/planning/mission_remaining_distance_time_calculator/README.md +++ b/planning/mission_remaining_distance_time_calculator/README.md @@ -2,16 +2,10 @@ ### Role - - ### Activation Timing - ### Module Parameters - ### Inner-workings / Algorithms - ### Future Work - diff --git a/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp b/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp index 27f82aeb0b8e5..a7b52ca77a70a 100644 --- a/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp +++ b/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp @@ -12,20 +12,21 @@ // See the License for the specific language governing permissions and // limitations under the License. +#ifndef MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__MISSION_REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ +#define MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__MISSION_REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ -#ifndef MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__HPP_ -#define MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__HPP_ - -//#include "mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator.hpp" +// #include +// "mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator.hpp" #include -#include -#include -#include -#include #include + #include #include +#include +#include +#include +#include #include #include @@ -39,12 +40,12 @@ namespace mission_remaining_distance_time_calculator { - using geometry_msgs::msg::Pose; - using nav_msgs::msg::Odometry; - using geometry_msgs::msg::Vector3; - using autoware_planning_msgs::msg::LaneletRoute; - using autoware_auto_mapping_msgs::msg::HADMapBin; - using autoware_internal_msgs::msg::MissionRemainingDistanceTime; +using autoware_auto_mapping_msgs::msg::HADMapBin; +using autoware_internal_msgs::msg::MissionRemainingDistanceTime; +using autoware_planning_msgs::msg::LaneletRoute; +using geometry_msgs::msg::Pose; +using geometry_msgs::msg::Vector3; +using nav_msgs::msg::Odometry; struct NodeParam { @@ -62,12 +63,10 @@ class MissionRemainingDistanceTimeCalculatorNode : public rclcpp::Node rclcpp::Subscription::SharedPtr map_subscriber_; rclcpp::Subscription::SharedPtr odometry_subscriber_; - // Publisher - rclcpp::Publisher::SharedPtr + rclcpp::Publisher::SharedPtr mission_remaining_distance_time_publisher_; - // Timer rclcpp::TimerBase::SharedPtr timer_; @@ -78,7 +77,7 @@ class MissionRemainingDistanceTimeCalculatorNode : public rclcpp::Node lanelet::traffic_rules::TrafficRulesPtr traffic_rules_ptr_; lanelet::ConstLanelets road_lanelets_; bool is_graph_ready_; - + // Callback void onTimer(); void onOdometry(const Odometry::ConstSharedPtr msg); @@ -110,4 +109,4 @@ class MissionRemainingDistanceTimeCalculatorNode : public rclcpp::Node NodeParam node_param_; }; } // namespace mission_remaining_distance_time_calculator -#endif // MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__HPP_ +#endif // MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__MISSION_REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ diff --git a/planning/mission_remaining_distance_time_calculator/launch/mission_remaining_distance_time_calculator.launch.xml b/planning/mission_remaining_distance_time_calculator/launch/mission_remaining_distance_time_calculator.launch.xml index 1bebbe23c7c52..039357d1ba725 100644 --- a/planning/mission_remaining_distance_time_calculator/launch/mission_remaining_distance_time_calculator.launch.xml +++ b/planning/mission_remaining_distance_time_calculator/launch/mission_remaining_distance_time_calculator.launch.xml @@ -1,7 +1,10 @@ - + @@ -16,10 +19,8 @@ - + - - diff --git a/planning/mission_remaining_distance_time_calculator/package.xml b/planning/mission_remaining_distance_time_calculator/package.xml index 80152e3617fad..175d6573576df 100644 --- a/planning/mission_remaining_distance_time_calculator/package.xml +++ b/planning/mission_remaining_distance_time_calculator/package.xml @@ -10,9 +10,8 @@ ament_cmake_auto autoware_cmake - + autoware_internal_msgs - route_handler autoware_planning_msgs geometry_msgs lanelet2_extension @@ -21,6 +20,7 @@ planning_test_utils rclcpp rclcpp_components + route_handler std_msgs tier4_autoware_utils diff --git a/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp b/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp index 4a1b4dbf1e528..55181c789e1dd 100644 --- a/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp +++ b/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp @@ -14,13 +14,11 @@ #include "mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp" - - -#include -#include #include #include #include +#include +#include #include #include @@ -32,36 +30,37 @@ namespace mission_remaining_distance_time_calculator { - - -MissionRemainingDistanceTimeCalculatorNode::MissionRemainingDistanceTimeCalculatorNode(const rclcpp::NodeOptions & options) +MissionRemainingDistanceTimeCalculatorNode::MissionRemainingDistanceTimeCalculatorNode( + const rclcpp::NodeOptions & options) : Node("mission_remaining_distance_time_calculator", options) { using std::placeholders::_1; - - odometry_subscriber_ = create_subscription( - "~/input/odometry", 1, std::bind(&MissionRemainingDistanceTimeCalculatorNode::onOdometry, this, _1)); - + + odometry_subscriber_ = create_subscription( + "~/input/odometry", 1, + std::bind(&MissionRemainingDistanceTimeCalculatorNode::onOdometry, this, _1)); + const auto qos_transient_local = rclcpp::QoS{1}.transient_local(); map_subscriber_ = create_subscription( - "~/input/map", qos_transient_local, std::bind(&MissionRemainingDistanceTimeCalculatorNode::onMap, this, _1)); + "~/input/map", qos_transient_local, + std::bind(&MissionRemainingDistanceTimeCalculatorNode::onMap, this, _1)); route_subscriber_ = create_subscription( - "~/input/route", qos_transient_local, std::bind(&MissionRemainingDistanceTimeCalculatorNode::onRoute, this, _1)); + "~/input/route", qos_transient_local, + std::bind(&MissionRemainingDistanceTimeCalculatorNode::onRoute, this, _1)); - mission_remaining_distance_time_publisher_ = create_publisher( + mission_remaining_distance_time_publisher_ = create_publisher( "~/output/mission_remaining_distance_time", rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable()); // Node Parameter node_param_.update_rate = declare_parameter("update_rate", 10.0); - // Timer const auto period_ns = rclcpp::Rate(node_param_.update_rate).period(); timer_ = rclcpp::create_timer( - this, get_clock(), period_ns, std::bind(&MissionRemainingDistanceTimeCalculatorNode::onTimer, this)); - + this, get_clock(), period_ns, + std::bind(&MissionRemainingDistanceTimeCalculatorNode::onTimer, this)); } void MissionRemainingDistanceTimeCalculatorNode::onMap(const HADMapBin::ConstSharedPtr msg) @@ -89,16 +88,14 @@ void MissionRemainingDistanceTimeCalculatorNode::onRoute(const LaneletRoute::Con void MissionRemainingDistanceTimeCalculatorNode::onTimer() { - RCLCPP_INFO_STREAM(this->get_logger(), "is_graph_ready_" << is_graph_ready_); - RCLCPP_INFO_STREAM(this->get_logger(), "has_received_route_" << has_received_route_); + RCLCPP_INFO_STREAM(this->get_logger(), "is_graph_ready_" << is_graph_ready_); + RCLCPP_INFO_STREAM(this->get_logger(), "has_received_route_" << has_received_route_); - if(is_graph_ready_ && has_received_route_) - { + if (is_graph_ready_ && has_received_route_) { double remaining_distance = calcuateMissionRemainingDistance(); double remaining_time = calcuateMissionRemainingTime(remaining_distance); publishMissionRemainingDistanceTime(remaining_distance, remaining_time); } - } double MissionRemainingDistanceTimeCalculatorNode::calcuateMissionRemainingDistance() const { @@ -111,11 +108,9 @@ double MissionRemainingDistanceTimeCalculatorNode::calcuateMissionRemainingDista lanelet::ConstLanelet goal_lanelet; lanelet::utils::query::getClosestLanelet(road_lanelets_, goal_pose_, &goal_lanelet); - const lanelet::Optional optional_route = routing_graph_ptr_->getRoute(current_lanelet, goal_lanelet, 0); - lanelet::routing::LaneletPath remaining_shortest_path; remaining_shortest_path = optional_route->shortestPath(); @@ -127,7 +122,8 @@ double MissionRemainingDistanceTimeCalculatorNode::calcuateMissionRemainingDista } if (index == 0) { - lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, current_vehicle_pose_); + lanelet::ArcCoordinates arc_coord = + lanelet::utils::getArcCoordinates({llt}, current_vehicle_pose_); double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt); remaining_distance += this_lanelet_length - arc_coord.length; } else if (index == (remaining_shortest_path.size() - 1)) { @@ -141,11 +137,11 @@ double MissionRemainingDistanceTimeCalculatorNode::calcuateMissionRemainingDista } return remaining_distance; - } -double MissionRemainingDistanceTimeCalculatorNode::calcuateMissionRemainingTime(const double remaining_distance) const -{ +double MissionRemainingDistanceTimeCalculatorNode::calcuateMissionRemainingTime( + const double remaining_distance) const +{ double current_velocity_norm = std::sqrt( current_vehicle_velocity_.x * current_vehicle_velocity_.x + current_vehicle_velocity_.y * current_vehicle_velocity_.y); @@ -159,7 +155,8 @@ double MissionRemainingDistanceTimeCalculatorNode::calcuateMissionRemainingTime( return remaining_time; } -void MissionRemainingDistanceTimeCalculatorNode::publishMissionRemainingDistanceTime(const double remaining_distance, const double remaining_time) const +void MissionRemainingDistanceTimeCalculatorNode::publishMissionRemainingDistanceTime( + const double remaining_distance, const double remaining_time) const { MissionRemainingDistanceTime mission_remaining_distance_time; @@ -171,4 +168,5 @@ void MissionRemainingDistanceTimeCalculatorNode::publishMissionRemainingDistance } // namespace mission_remaining_distance_time_calculator #include -RCLCPP_COMPONENTS_REGISTER_NODE(mission_remaining_distance_time_calculator::MissionRemainingDistanceTimeCalculatorNode) +RCLCPP_COMPONENTS_REGISTER_NODE( + mission_remaining_distance_time_calculator::MissionRemainingDistanceTimeCalculatorNode) diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index 2022e52186e1f..ac8e472b2f943 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -355,7 +355,7 @@ class RouteHandler lanelet::ConstPolygon3d getIntersectionAreaById(const lanelet::Id id) const; bool isPreferredLane(const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getClosestLanelets(const geometry_msgs::msg::Pose & target_pose) const; - + private: // MUST lanelet::routing::RoutingGraphPtr routing_graph_ptr_; From 614c82c0f8275db208accc50affaac8442062092 Mon Sep 17 00:00:00 2001 From: AhmedEbrahim Date: Tue, 7 May 2024 07:53:16 +0300 Subject: [PATCH 40/77] feat(remaining_dist_eta): remove unneeded changes Signed-off-by: Ahmed Ebrahim --- .../include/behavior_path_planner/behavior_path_planner_node.hpp | 1 - .../behavior_path_planner/src/behavior_path_planner_node.cpp | 1 - 2 files changed, 2 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index 44d453a3435fa..5a49f4d9ab66e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -32,7 +32,6 @@ #include #include #include -#include #include #include #include diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index d7a7633ff1243..b56d1a207f76d 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -395,7 +395,6 @@ void BehaviorPathPlannerNode::run() // path handling const auto path = getPath(output, planner_data_, planner_manager_); - // update planner data planner_data_->prev_output_path = path; From 4a25f9b2a4b09a7e8f89d4f191ba1fe9e129e605 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Tue, 7 May 2024 08:32:08 +0300 Subject: [PATCH 41/77] feat(remaining_dist_eta): update visualization to calculate remaining hours/minnutes/seconds - visualize only minutes and if minutes < 0 visualize seconds Signed-off-by: Ahmed Ebrahim --- .../remaining_distance_time_display.hpp | 5 +- .../src/remaining_distance_time_display.cpp | 67 ++++++++++--------- 2 files changed, 38 insertions(+), 34 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp index bd8a8e093e035..2c4b073c5e736 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp @@ -42,9 +42,8 @@ class RemainingDistanceTimeDisplay private: double remaining_distance_; // Internal variable to store remaining distance - uint32_t remaining_hours_; // Internal variable to store remaining time hours - uint32_t remaining_minutes_; // Internal variable to store remaining time minutes - uint32_t remaining_seconds_; // Internal variable to store remaining time seconds + double remaining_time_; // Internal variable to store remaining time + QColor gray = QColor(194, 194, 194); QImage distToGoalFlag; diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index 273ab819cfe98..668ec2c9e5252 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -37,7 +37,7 @@ namespace autoware_mission_details_overlay_rviz_plugin { RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() -: remaining_distance_(0.0), remaining_hours_(0), remaining_minutes_(0), remaining_seconds_(0) +: remaining_distance_(0.0), remaining_time_(0.0) { std::string package_path = ament_index_cpp::get_package_share_directory("autoware_mission_details_overlay_rviz_plugin"); @@ -67,9 +67,7 @@ void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData( { try { remaining_distance_ = msg->remaining_distance; - remaining_hours_ = msg->remaining_hours; - remaining_minutes_ = msg->remaining_minutes; - remaining_seconds_ = msg->remaining_seconds; + remaining_time_ = msg->remaining_time; } catch (const std::exception & e) { // Log the error std::cerr << "Error in processMessage: " << e.what() << std::endl; @@ -108,79 +106,86 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( switch (remainingDistanceValue.size()) { case 1: remainingDistancePos = - QPointF(remainingDistReferencePos.x() + 100, remainingDistReferencePos.y() + 10); + QPointF(remainingDistReferencePos.x() + 55, remainingDistReferencePos.y() + 10); break; case 2: remainingDistancePos = - QPointF(remainingDistReferencePos.x() + 95, remainingDistReferencePos.y() + 10); + QPointF(remainingDistReferencePos.x() + 50, remainingDistReferencePos.y() + 10); break; case 3: remainingDistancePos = - QPointF(remainingDistReferencePos.x() + 90, remainingDistReferencePos.y() + 10); + QPointF(remainingDistReferencePos.x() + 45, remainingDistReferencePos.y() + 10); break; case 4: remainingDistancePos = - QPointF(remainingDistReferencePos.x() + 85, remainingDistReferencePos.y() + 10); + QPointF(remainingDistReferencePos.x() + 40, remainingDistReferencePos.y() + 10); break; default: remainingDistancePos = - QPointF(remainingDistReferencePos.x() + 100, remainingDistReferencePos.y() + 10); + QPointF(remainingDistReferencePos.x() + 55, remainingDistReferencePos.y() + 10); break; } painter.setPen(gray); painter.drawText(remainingDistancePos, remainingDistanceValue); // Remaining distance unit - QString remainingDistUnitText = remaining_distance_ > 1000 ? "km" : "m"; + QString remainingDistUnitText = remaining_distance_ > 1000 ? "km" : "meter"; QPointF remainingDistancUnitPos( - remainingDistReferencePos.x() + 125, remainingDistReferencePos.y() + 10); + remainingDistReferencePos.x() + 80, remainingDistReferencePos.y() + 10); painter.drawText(remainingDistancUnitPos, remainingDistUnitText); // ----------------- Remaining Time ----------------- - - // Remaining time text + // Remaining time icon painter.drawImage( remainingDistanceIconPos.x(), remainingDistanceIconPos.y() + scaledTimeToGoalFlag.height() / 2.0, scaledTimeToGoalFlag); - // Remaining hours value - QString remaininghoursValue = - QString::number(remaining_hours_ != 0 ? remaining_hours_ : 0, 'f', 0); - QPointF remaininghoursValuePos(remainingTimeReferencePos.x() + 17, remainingTimeReferencePos.y()); - painter.setPen(gray); - if (remaining_hours_ != 0) painter.drawText(remaininghoursValuePos, remaininghoursValue); + // Calculate remaining minutes and seconds + //uint8_t remainig_hours = static_cast(remaining_time_ / 3600.0); + double remaining_time_mod = std::fmod(remaining_time_, 3600); + uint8_t remaining_minutes = static_cast(remaining_time_mod / 60.0); + uint8_t remaining_seconds = static_cast(std::fmod(remaining_time_mod, 60)); + + - // Remaining hours separator - QString hoursSeparatorText = "h"; - QPointF hoursSeparatorTextPos(remainingTimeReferencePos.x() + 35, remainingTimeReferencePos.y()); - if (remaining_hours_ != 0) painter.drawText(hoursSeparatorTextPos, hoursSeparatorText); + // // Remaining hours value + // QString remaininghoursValue = + // QString::number(remaining_hours_ != 0 ? remaining_hours_ : 0, 'f', 0); + // QPointF remaininghoursValuePos(remainingTimeReferencePos.x() + 17, remainingTimeReferencePos.y()); + // painter.setPen(gray); + // if (remaining_hours_ != 0) painter.drawText(remaininghoursValuePos, remaininghoursValue); + + // // Remaining hours separator + // QString hoursSeparatorText = "h"; + // QPointF hoursSeparatorTextPos(remainingTimeReferencePos.x() + 35, remainingTimeReferencePos.y()); + // if (remaining_hours_ != 0) painter.drawText(hoursSeparatorTextPos, hoursSeparatorText); // Remaining minutes value QString remainingminutesValue = - QString::number(remaining_minutes_ != 0 ? remaining_minutes_ : 0, 'f', 0); + QString::number(remaining_minutes != 0 ? remaining_minutes : 0, 'f', 0); QPointF remainingminutesValuePos( remainingTimeReferencePos.x() + 55, remainingTimeReferencePos.y()); painter.setPen(gray); - if (remaining_minutes_ != 0) painter.drawText(remainingminutesValuePos, remainingminutesValue); + if (remaining_minutes > 0) painter.drawText(remainingminutesValuePos, remainingminutesValue); // Remaining minutes separator QString minutesSeparatorText = "m"; QPointF minutesSeparatorTextPos( remainingTimeReferencePos.x() + 80, remainingTimeReferencePos.y()); - if (remaining_minutes_ != 0) painter.drawText(minutesSeparatorTextPos, minutesSeparatorText); + if (remaining_minutes > 0) painter.drawText(minutesSeparatorTextPos, minutesSeparatorText); // Remaining seconds value QString remainingsecondsValue = - QString::number(remaining_seconds_ != 0 ? remaining_seconds_ : 0, 'f', 0); + QString::number(remaining_seconds != 0 ? remaining_seconds : 0, 'f', 0); QPointF remainingsecondValuePos( - remainingTimeReferencePos.x() + 100, remainingTimeReferencePos.y()); + remainingTimeReferencePos.x() + 55, remainingTimeReferencePos.y()); painter.setPen(gray); - painter.drawText(remainingsecondValuePos, remainingsecondsValue); + if(remaining_minutes <= 0) painter.drawText(remainingsecondValuePos, remainingsecondsValue); // Remaining seconds separator QString secondsSeparatorText = "s"; QPointF secondsSeparatorTextPos( - remainingTimeReferencePos.x() + 125, remainingTimeReferencePos.y()); - painter.drawText(secondsSeparatorTextPos, secondsSeparatorText); + remainingTimeReferencePos.x() + 80, remainingTimeReferencePos.y()); + if(remaining_minutes <= 0) painter.drawText(secondsSeparatorTextPos, secondsSeparatorText); } } // namespace autoware_mission_details_overlay_rviz_plugin From 9662b2aa7386cedbb875f7c1bae52082c82863e5 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Tue, 7 May 2024 08:43:21 +0300 Subject: [PATCH 42/77] feat(remaining_dist_eta): fix review comments Signed-off-by: Ahmed Ebrahim --- .../CMakeLists.txt | 15 --------------- .../include/overlay_text_display.hpp | 1 - .../package.xml | 3 --- .../src/mission_details_display.cpp | 2 -- 4 files changed, 21 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt index 46b82d3fa6031..f4a4188638600 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt @@ -3,20 +3,8 @@ project(autoware_mission_details_overlay_rviz_plugin) # find dependencies find_package(ament_cmake_auto REQUIRED) -find_package(ament_cmake REQUIRED) -find_package(autoware_auto_vehicle_msgs REQUIRED) -find_package(tier4_planning_msgs REQUIRED) -find_package(autoware_perception_msgs REQUIRED) -find_package(autoware_internal_msgs REQUIRED) ament_auto_find_build_dependencies() -find_package(autoware_overlay_msgs REQUIRED) - -find_package(rviz_common REQUIRED) -find_package(rviz_rendering REQUIRED) -find_package(rviz_ogre_vendor REQUIRED) -find_package(std_msgs REQUIRED) - set( headers_to_moc include/overlay_text_display.hpp @@ -82,9 +70,6 @@ ament_target_dependencies( rviz_common rviz_rendering autoware_overlay_msgs - autoware_auto_vehicle_msgs - tier4_planning_msgs - autoware_perception_msgs autoware_internal_msgs ) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp index 822a1e2bbc18d..7156e9569676d 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp @@ -64,7 +64,6 @@ #include #include -#include #include #endif diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml index e50da3d55de46..e2b66ca469e8f 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml @@ -11,15 +11,12 @@ BSD-3-Clause - autoware_auto_vehicle_msgs autoware_internal_msgs autoware_overlay_msgs - autoware_perception_msgs boost rviz_common rviz_ogre_vendor rviz_rendering - tier4_planning_msgs ament_lint_auto autoware_lint_common diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp index 06bc8ce247155..da54fcccd5768 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -96,9 +96,7 @@ MissionDetailsDisplay::~MissionDetailsDisplay() overlay_.reset(); remaining_distance_time_sub_.reset(); - remaining_distance_time_display_.reset(); - remaining_distance_time_topic_property_.reset(); } From a9e34333ed28904e800f4c968f61ee0c0b6123a5 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 7 May 2024 05:46:25 +0000 Subject: [PATCH 43/77] style(pre-commit): autofix --- .../remaining_distance_time_display.hpp | 6 +++--- .../src/remaining_distance_time_display.cpp | 19 +++++++++---------- 2 files changed, 12 insertions(+), 13 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp index 2c4b073c5e736..2dc4e4b56d332 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp @@ -41,9 +41,9 @@ class RemainingDistanceTimeDisplay const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); private: - double remaining_distance_; // Internal variable to store remaining distance - double remaining_time_; // Internal variable to store remaining time - + double remaining_distance_; // Internal variable to store remaining distance + double remaining_time_; // Internal variable to store remaining time + QColor gray = QColor(194, 194, 194); QImage distToGoalFlag; diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index 668ec2c9e5252..52ca46300cfa3 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -141,24 +141,23 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( remainingDistanceIconPos.y() + scaledTimeToGoalFlag.height() / 2.0, scaledTimeToGoalFlag); // Calculate remaining minutes and seconds - //uint8_t remainig_hours = static_cast(remaining_time_ / 3600.0); + // uint8_t remainig_hours = static_cast(remaining_time_ / 3600.0); double remaining_time_mod = std::fmod(remaining_time_, 3600); uint8_t remaining_minutes = static_cast(remaining_time_mod / 60.0); uint8_t remaining_seconds = static_cast(std::fmod(remaining_time_mod, 60)); - - // // Remaining hours value // QString remaininghoursValue = // QString::number(remaining_hours_ != 0 ? remaining_hours_ : 0, 'f', 0); - // QPointF remaininghoursValuePos(remainingTimeReferencePos.x() + 17, remainingTimeReferencePos.y()); - // painter.setPen(gray); - // if (remaining_hours_ != 0) painter.drawText(remaininghoursValuePos, remaininghoursValue); + // QPointF remaininghoursValuePos(remainingTimeReferencePos.x() + 17, + // remainingTimeReferencePos.y()); painter.setPen(gray); if (remaining_hours_ != 0) + // painter.drawText(remaininghoursValuePos, remaininghoursValue); // // Remaining hours separator // QString hoursSeparatorText = "h"; - // QPointF hoursSeparatorTextPos(remainingTimeReferencePos.x() + 35, remainingTimeReferencePos.y()); - // if (remaining_hours_ != 0) painter.drawText(hoursSeparatorTextPos, hoursSeparatorText); + // QPointF hoursSeparatorTextPos(remainingTimeReferencePos.x() + 35, + // remainingTimeReferencePos.y()); if (remaining_hours_ != 0) + // painter.drawText(hoursSeparatorTextPos, hoursSeparatorText); // Remaining minutes value QString remainingminutesValue = @@ -179,13 +178,13 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( QPointF remainingsecondValuePos( remainingTimeReferencePos.x() + 55, remainingTimeReferencePos.y()); painter.setPen(gray); - if(remaining_minutes <= 0) painter.drawText(remainingsecondValuePos, remainingsecondsValue); + if (remaining_minutes <= 0) painter.drawText(remainingsecondValuePos, remainingsecondsValue); // Remaining seconds separator QString secondsSeparatorText = "s"; QPointF secondsSeparatorTextPos( remainingTimeReferencePos.x() + 80, remainingTimeReferencePos.y()); - if(remaining_minutes <= 0) painter.drawText(secondsSeparatorTextPos, secondsSeparatorText); + if (remaining_minutes <= 0) painter.drawText(secondsSeparatorTextPos, secondsSeparatorText); } } // namespace autoware_mission_details_overlay_rviz_plugin From 5b91356a67fa8e10337a3bc6e5c639dcf20a2088 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Tue, 7 May 2024 09:05:33 +0300 Subject: [PATCH 44/77] feat(remaining_dist_eta): add content to package readme file Signed-off-by: Ahmed Ebrahim --- .../README.md | 22 ++++++++++++++++++- 1 file changed, 21 insertions(+), 1 deletion(-) diff --git a/planning/mission_remaining_distance_time_calculator/README.md b/planning/mission_remaining_distance_time_calculator/README.md index 06b63bf5fef3e..3b78890968a68 100644 --- a/planning/mission_remaining_distance_time_calculator/README.md +++ b/planning/mission_remaining_distance_time_calculator/README.md @@ -1,11 +1,31 @@ ## Mission Remaining Distance and Time Calculator ### Role +This package aims to provide mission remaining distance and remaining time calculations -### Activation Timing +### Activation and Timing +- The calculations are activated once we have a route planned for a mission in Autoware +- The calculations are trigged timely based on the `update_rate` parameter ### Module Parameters +| Name | Type | Default Value | Explanation | +| ------------- | ------ | ------------- | --------------------------- | +| `update_rate` | double | 10.0 | Timer callback period. [Hz] | ### Inner-workings / Algorithms +- Remaining Distance Calculation + - The remaining distance calculation is based on getting the remaining shortest path between thecurrent vehicle pose and goal pose using `lanelet2` routing APIs. + - The remaining distance is calculated by summing the 2D length of remaining shortest path, with exception to current lanelet and goal lanelet + - For the current lanelet, the distance is calculated from the current vehicle position to the end of that lanelet + - For the goal lanelet, the distance is calculated from the start of the lanelet to the goal pose in this lanelet. + +- Remaining Time Calculation + - Remaining time is calculated using simple equation of motion by getting the current vehicle velocity magnitude. + - Then the calclated remaining distance is divided by the velocity magnitude. + + ### Future Work +- Find a more efficient way for remaining distance calculation instead of regularly searching the graph for finding the remaining shortest path +- Engage more sophisticated motion models for more accurate remainig time calculations +- Handle cases when the vehicle stops and Autoware got disengaged \ No newline at end of file From ab6c31660f1016c826e92d6d35aac1d67c923e87 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 7 May 2024 06:07:32 +0000 Subject: [PATCH 45/77] style(pre-commit): autofix --- .../README.md | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/planning/mission_remaining_distance_time_calculator/README.md b/planning/mission_remaining_distance_time_calculator/README.md index 3b78890968a68..e93d2fb6d59f5 100644 --- a/planning/mission_remaining_distance_time_calculator/README.md +++ b/planning/mission_remaining_distance_time_calculator/README.md @@ -1,19 +1,24 @@ ## Mission Remaining Distance and Time Calculator ### Role + This package aims to provide mission remaining distance and remaining time calculations ### Activation and Timing + - The calculations are activated once we have a route planned for a mission in Autoware - The calculations are trigged timely based on the `update_rate` parameter ### Module Parameters + | Name | Type | Default Value | Explanation | | ------------- | ------ | ------------- | --------------------------- | | `update_rate` | double | 10.0 | Timer callback period. [Hz] | ### Inner-workings / Algorithms + - Remaining Distance Calculation + - The remaining distance calculation is based on getting the remaining shortest path between thecurrent vehicle pose and goal pose using `lanelet2` routing APIs. - The remaining distance is calculated by summing the 2D length of remaining shortest path, with exception to current lanelet and goal lanelet - For the current lanelet, the distance is calculated from the current vehicle position to the end of that lanelet @@ -23,9 +28,8 @@ This package aims to provide mission remaining distance and remaining time calcu - Remaining time is calculated using simple equation of motion by getting the current vehicle velocity magnitude. - Then the calclated remaining distance is divided by the velocity magnitude. - - ### Future Work + - Find a more efficient way for remaining distance calculation instead of regularly searching the graph for finding the remaining shortest path - Engage more sophisticated motion models for more accurate remainig time calculations -- Handle cases when the vehicle stops and Autoware got disengaged \ No newline at end of file +- Handle cases when the vehicle stops and Autoware got disengaged From bd722f53771ec8aea7a731b6e023e406d0be9815 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Tue, 7 May 2024 09:25:21 +0300 Subject: [PATCH 46/77] feat(remaining_dist_eta): removing info log lines - minor update in readme file Signed-off-by: Ahmed Ebrahim --- .../mission_remaining_distance_time_calculator/README.md | 2 +- .../src/mission_remaining_distance_time_calculator_node.cpp | 6 ++---- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/planning/mission_remaining_distance_time_calculator/README.md b/planning/mission_remaining_distance_time_calculator/README.md index e93d2fb6d59f5..65049cae73dac 100644 --- a/planning/mission_remaining_distance_time_calculator/README.md +++ b/planning/mission_remaining_distance_time_calculator/README.md @@ -32,4 +32,4 @@ This package aims to provide mission remaining distance and remaining time calcu - Find a more efficient way for remaining distance calculation instead of regularly searching the graph for finding the remaining shortest path - Engage more sophisticated motion models for more accurate remainig time calculations -- Handle cases when the vehicle stops and Autoware got disengaged +- Handle cases when the vehicle stops during the mission or Autoware get disengaged then engaged for the same mission diff --git a/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp b/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp index 55181c789e1dd..23acd7dd75b19 100644 --- a/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp +++ b/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp @@ -88,10 +88,8 @@ void MissionRemainingDistanceTimeCalculatorNode::onRoute(const LaneletRoute::Con void MissionRemainingDistanceTimeCalculatorNode::onTimer() { - RCLCPP_INFO_STREAM(this->get_logger(), "is_graph_ready_" << is_graph_ready_); - RCLCPP_INFO_STREAM(this->get_logger(), "has_received_route_" << has_received_route_); - - if (is_graph_ready_ && has_received_route_) { + if (is_graph_ready_ && has_received_route_) + { double remaining_distance = calcuateMissionRemainingDistance(); double remaining_time = calcuateMissionRemainingTime(remaining_distance); publishMissionRemainingDistanceTime(remaining_distance, remaining_time); From 322f75174a3a63534d63b61b3b27b939031e660a Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 7 May 2024 06:27:17 +0000 Subject: [PATCH 47/77] style(pre-commit): autofix --- .../src/mission_remaining_distance_time_calculator_node.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp b/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp index 23acd7dd75b19..32822b8bf70e6 100644 --- a/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp +++ b/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp @@ -88,8 +88,7 @@ void MissionRemainingDistanceTimeCalculatorNode::onRoute(const LaneletRoute::Con void MissionRemainingDistanceTimeCalculatorNode::onTimer() { - if (is_graph_ready_ && has_received_route_) - { + if (is_graph_ready_ && has_received_route_) { double remaining_distance = calcuateMissionRemainingDistance(); double remaining_time = calcuateMissionRemainingTime(remaining_distance); publishMissionRemainingDistanceTime(remaining_distance, remaining_time); From 9fcda4df5e2db2fd9eb351ceb14c459f63ba4d5b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 10 May 2024 17:25:59 +0300 Subject: [PATCH 48/77] update the readme MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../README.md | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/planning/mission_remaining_distance_time_calculator/README.md b/planning/mission_remaining_distance_time_calculator/README.md index 65049cae73dac..0957a58ca52df 100644 --- a/planning/mission_remaining_distance_time_calculator/README.md +++ b/planning/mission_remaining_distance_time_calculator/README.md @@ -17,19 +17,20 @@ This package aims to provide mission remaining distance and remaining time calcu ### Inner-workings / Algorithms -- Remaining Distance Calculation +### Remaining Distance Calculation - - The remaining distance calculation is based on getting the remaining shortest path between thecurrent vehicle pose and goal pose using `lanelet2` routing APIs. - - The remaining distance is calculated by summing the 2D length of remaining shortest path, with exception to current lanelet and goal lanelet - - For the current lanelet, the distance is calculated from the current vehicle position to the end of that lanelet - - For the goal lanelet, the distance is calculated from the start of the lanelet to the goal pose in this lanelet. +- The remaining distance calculation is based on getting the remaining shortest path between the current vehicle pose and goal pose using `lanelet2` routing APIs. +- The remaining distance is calculated by summing the 2D length of remaining shortest path, with exception to current lanelet and goal lanelet + - For the current lanelet, the distance is calculated from the current vehicle position to the end of that lanelet + - For the goal lanelet, the distance is calculated from the start of the lanelet to the goal pose in this lanelet. -- Remaining Time Calculation - - Remaining time is calculated using simple equation of motion by getting the current vehicle velocity magnitude. - - Then the calclated remaining distance is divided by the velocity magnitude. +### Remaining Time Calculation + +- Remaining time is calculated using simple equation of motion by getting the current vehicle velocity magnitude. +- Then the calculated remaining distance is divided by the velocity magnitude. ### Future Work - Find a more efficient way for remaining distance calculation instead of regularly searching the graph for finding the remaining shortest path -- Engage more sophisticated motion models for more accurate remainig time calculations +- Engage more sophisticated motion models for more accurate remaining time calculations - Handle cases when the vehicle stops during the mission or Autoware get disengaged then engaged for the same mission From 694886bb0a46a979bbb9fbcac47224a5ef79d407 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 10 May 2024 18:19:21 +0300 Subject: [PATCH 49/77] refactor all MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../launch/planning.launch.xml | 2 +- launch/tier4_planning_launch/package.xml | 2 +- .../CMakeLists.txt | 21 ++++++ .../README.md | 2 +- ...ining_distance_time_calculator.param.yaml} | 0 ...ining_distance_time_calculator.launch.xml} | 11 ++-- .../package.xml | 4 +- ...ining_distance_time_calculator.schema.json | 33 ++++++++++ ...maining_distance_time_calculator_node.cpp} | 57 +++++++++-------- ...maining_distance_time_calculator_node.hpp} | 64 ++++++++----------- .../CMakeLists.txt | 21 ------ 11 files changed, 120 insertions(+), 97 deletions(-) create mode 100644 planning/autoware_remaining_distance_time_calculator/CMakeLists.txt rename planning/{mission_remaining_distance_time_calculator => autoware_remaining_distance_time_calculator}/README.md (97%) rename planning/{mission_remaining_distance_time_calculator/config/mission_remaining_distance_time_calculator.param.yaml => autoware_remaining_distance_time_calculator/config/remaining_distance_time_calculator.param.yaml} (100%) rename planning/{mission_remaining_distance_time_calculator/launch/mission_remaining_distance_time_calculator.launch.xml => autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml} (53%) rename planning/{mission_remaining_distance_time_calculator => autoware_remaining_distance_time_calculator}/package.xml (85%) create mode 100644 planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json rename planning/{mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp => autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp} (68%) rename planning/{mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp => autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp} (67%) delete mode 100644 planning/mission_remaining_distance_time_calculator/CMakeLists.txt diff --git a/launch/tier4_planning_launch/launch/planning.launch.xml b/launch/tier4_planning_launch/launch/planning.launch.xml index 2e6cead267553..0e693943a4d03 100644 --- a/launch/tier4_planning_launch/launch/planning.launch.xml +++ b/launch/tier4_planning_launch/launch/planning.launch.xml @@ -46,7 +46,7 @@ - + diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 7c290046cc8a2..d04a405a61c7b 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -57,6 +57,7 @@ ament_cmake_auto autoware_cmake + autoware_remaining_distance_time_calculator behavior_path_planner behavior_velocity_planner costmap_generator @@ -65,7 +66,6 @@ freespace_planner glog_component mission_planner - mission_remaining_distance_time_calculator motion_velocity_smoother obstacle_avoidance_planner obstacle_cruise_planner diff --git a/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt b/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt new file mode 100644 index 0000000000000..d29a153a0ce5d --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt @@ -0,0 +1,21 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_remaining_distance_time_calculator) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/remaining_distance_time_calculator_node.cpp +) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::remaining_distance_time_calculator::RemainingDistanceTimeCalculatorNode" + EXECUTABLE ${PROJECT_NAME}_node +) + + +ament_auto_package( + INSTALL_TO_SHARE + config + launch +) diff --git a/planning/mission_remaining_distance_time_calculator/README.md b/planning/autoware_remaining_distance_time_calculator/README.md similarity index 97% rename from planning/mission_remaining_distance_time_calculator/README.md rename to planning/autoware_remaining_distance_time_calculator/README.md index 0957a58ca52df..d49847b273c1f 100644 --- a/planning/mission_remaining_distance_time_calculator/README.md +++ b/planning/autoware_remaining_distance_time_calculator/README.md @@ -1,4 +1,4 @@ -## Mission Remaining Distance and Time Calculator +## Remaining Distance and Time Calculator ### Role diff --git a/planning/mission_remaining_distance_time_calculator/config/mission_remaining_distance_time_calculator.param.yaml b/planning/autoware_remaining_distance_time_calculator/config/remaining_distance_time_calculator.param.yaml similarity index 100% rename from planning/mission_remaining_distance_time_calculator/config/mission_remaining_distance_time_calculator.param.yaml rename to planning/autoware_remaining_distance_time_calculator/config/remaining_distance_time_calculator.param.yaml diff --git a/planning/mission_remaining_distance_time_calculator/launch/mission_remaining_distance_time_calculator.launch.xml b/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml similarity index 53% rename from planning/mission_remaining_distance_time_calculator/launch/mission_remaining_distance_time_calculator.launch.xml rename to planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml index 039357d1ba725..ebf088e6ad149 100644 --- a/planning/mission_remaining_distance_time_calculator/launch/mission_remaining_distance_time_calculator.launch.xml +++ b/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml @@ -1,19 +1,16 @@ - - - - + - + diff --git a/planning/mission_remaining_distance_time_calculator/package.xml b/planning/autoware_remaining_distance_time_calculator/package.xml similarity index 85% rename from planning/mission_remaining_distance_time_calculator/package.xml rename to planning/autoware_remaining_distance_time_calculator/package.xml index 175d6573576df..b8c9a3056de5b 100644 --- a/planning/mission_remaining_distance_time_calculator/package.xml +++ b/planning/autoware_remaining_distance_time_calculator/package.xml @@ -1,8 +1,8 @@ - mission_remaining_distance_time_calculator + autoware_remaining_distance_time_calculator 0.1.0 - The mission_remaining_distance_time_calculator package + Calculates and publishes remaining distance and time of the mission. Ahmed Ebrahim diff --git a/planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json b/planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json new file mode 100644 index 0000000000000..adb84e6f26cc7 --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json @@ -0,0 +1,33 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Remaining Distance Time Calculator Parameters", + "type": "object", + "actual_parameters": { + "type": "object", + "properties": { + "update_rate": { + "type": "number", + "default": 10.0, + "description": "Recalculate remaining distance and time at this rate, Hz" + } + }, + "required": [ + "update_rate" + ], + "additionalProperties": false + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/actual_parameters" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp similarity index 68% rename from planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp rename to planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp index 32822b8bf70e6..deccb65eb9cae 100644 --- a/planning/mission_remaining_distance_time_calculator/src/mission_remaining_distance_time_calculator_node.cpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp" +#include "remaining_distance_time_calculator_node.hpp" #include #include @@ -27,43 +27,43 @@ #include #include -namespace mission_remaining_distance_time_calculator +namespace autoware::remaining_distance_time_calculator { -MissionRemainingDistanceTimeCalculatorNode::MissionRemainingDistanceTimeCalculatorNode( +RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode( const rclcpp::NodeOptions & options) -: Node("mission_remaining_distance_time_calculator", options) +: Node("remaining_distance_time_calculator", options), + is_graph_ready_{false}, + has_received_route_{false} { using std::placeholders::_1; - odometry_subscriber_ = create_subscription( + sub_odometry_ = create_subscription( "~/input/odometry", 1, - std::bind(&MissionRemainingDistanceTimeCalculatorNode::onOdometry, this, _1)); + std::bind(&RemainingDistanceTimeCalculatorNode::on_odometry, this, _1)); const auto qos_transient_local = rclcpp::QoS{1}.transient_local(); - map_subscriber_ = create_subscription( + sub_map_ = create_subscription( "~/input/map", qos_transient_local, - std::bind(&MissionRemainingDistanceTimeCalculatorNode::onMap, this, _1)); - route_subscriber_ = create_subscription( + std::bind(&RemainingDistanceTimeCalculatorNode::on_map, this, _1)); + sub_route_ = create_subscription( "~/input/route", qos_transient_local, - std::bind(&MissionRemainingDistanceTimeCalculatorNode::onRoute, this, _1)); + std::bind(&RemainingDistanceTimeCalculatorNode::on_route, this, _1)); - mission_remaining_distance_time_publisher_ = create_publisher( + pub_mission_remaining_distance_time_ = create_publisher( "~/output/mission_remaining_distance_time", rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable()); - // Node Parameter - node_param_.update_rate = declare_parameter("update_rate", 10.0); + node_param_.update_rate = declare_parameter("update_rate"); - // Timer const auto period_ns = rclcpp::Rate(node_param_.update_rate).period(); timer_ = rclcpp::create_timer( this, get_clock(), period_ns, - std::bind(&MissionRemainingDistanceTimeCalculatorNode::onTimer, this)); + std::bind(&RemainingDistanceTimeCalculatorNode::on_timer, this)); } -void MissionRemainingDistanceTimeCalculatorNode::onMap(const HADMapBin::ConstSharedPtr msg) +void RemainingDistanceTimeCalculatorNode::on_map(const HADMapBin::ConstSharedPtr& msg) { route_handler_.setMap(*msg); lanelet_map_ptr_ = std::make_shared(); @@ -74,27 +74,28 @@ void MissionRemainingDistanceTimeCalculatorNode::onMap(const HADMapBin::ConstSha is_graph_ready_ = true; } -void MissionRemainingDistanceTimeCalculatorNode::onOdometry(const Odometry::ConstSharedPtr msg) +void RemainingDistanceTimeCalculatorNode::on_odometry(const Odometry::ConstSharedPtr& msg) { current_vehicle_pose_ = msg->pose.pose; current_vehicle_velocity_ = msg->twist.twist.linear; } -void MissionRemainingDistanceTimeCalculatorNode::onRoute(const LaneletRoute::ConstSharedPtr msg) +void RemainingDistanceTimeCalculatorNode::on_route(const LaneletRoute::ConstSharedPtr& msg) { goal_pose_ = msg->goal_pose; has_received_route_ = true; } -void MissionRemainingDistanceTimeCalculatorNode::onTimer() +void RemainingDistanceTimeCalculatorNode::on_timer() { if (is_graph_ready_ && has_received_route_) { - double remaining_distance = calcuateMissionRemainingDistance(); - double remaining_time = calcuateMissionRemainingTime(remaining_distance); - publishMissionRemainingDistanceTime(remaining_distance, remaining_time); + double remaining_distance = calculate_remaining_distance(); + double remaining_time = calculate_remaining_time(remaining_distance); + publish_mission_remaining_distance_time(remaining_distance, remaining_time); } } -double MissionRemainingDistanceTimeCalculatorNode::calcuateMissionRemainingDistance() const + +double RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() const { double remaining_distance = 0.0; size_t index = 0; @@ -136,7 +137,7 @@ double MissionRemainingDistanceTimeCalculatorNode::calcuateMissionRemainingDista return remaining_distance; } -double MissionRemainingDistanceTimeCalculatorNode::calcuateMissionRemainingTime( +double RemainingDistanceTimeCalculatorNode::calculate_remaining_time( const double remaining_distance) const { double current_velocity_norm = std::sqrt( @@ -152,18 +153,18 @@ double MissionRemainingDistanceTimeCalculatorNode::calcuateMissionRemainingTime( return remaining_time; } -void MissionRemainingDistanceTimeCalculatorNode::publishMissionRemainingDistanceTime( +void RemainingDistanceTimeCalculatorNode::publish_mission_remaining_distance_time( const double remaining_distance, const double remaining_time) const { MissionRemainingDistanceTime mission_remaining_distance_time; mission_remaining_distance_time.remaining_distance = remaining_distance; mission_remaining_distance_time.remaining_time = remaining_time; - mission_remaining_distance_time_publisher_->publish(mission_remaining_distance_time); + pub_mission_remaining_distance_time_->publish(mission_remaining_distance_time); } -} // namespace mission_remaining_distance_time_calculator +} // autoware::namespace mission_remaining_distance_time_calculator #include RCLCPP_COMPONENTS_REGISTER_NODE( - mission_remaining_distance_time_calculator::MissionRemainingDistanceTimeCalculatorNode) + autoware::remaining_distance_time_calculator::RemainingDistanceTimeCalculatorNode) diff --git a/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp similarity index 67% rename from planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp rename to planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp index a7b52ca77a70a..a297345cc0c3f 100644 --- a/planning/mission_remaining_distance_time_calculator/include/mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator_node.hpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp @@ -15,9 +15,6 @@ #ifndef MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__MISSION_REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ #define MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__MISSION_REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ -// #include -// "mission_remaining_distance_time_calculator/mission_remaining_distance_time_calculator.hpp" - #include #include @@ -37,9 +34,8 @@ #include -namespace mission_remaining_distance_time_calculator +namespace autoware::remaining_distance_time_calculator { - using autoware_auto_mapping_msgs::msg::HADMapBin; using autoware_internal_msgs::msg::MissionRemainingDistanceTime; using autoware_planning_msgs::msg::LaneletRoute; @@ -52,25 +48,20 @@ struct NodeParam double update_rate{0.0}; }; -class MissionRemainingDistanceTimeCalculatorNode : public rclcpp::Node +class RemainingDistanceTimeCalculatorNode : public rclcpp::Node { public: - explicit MissionRemainingDistanceTimeCalculatorNode(const rclcpp::NodeOptions & options); + explicit RemainingDistanceTimeCalculatorNode(const rclcpp::NodeOptions & options); private: - // Subscriber - rclcpp::Subscription::SharedPtr route_subscriber_; - rclcpp::Subscription::SharedPtr map_subscriber_; - rclcpp::Subscription::SharedPtr odometry_subscriber_; + rclcpp::Subscription::SharedPtr sub_route_; + rclcpp::Subscription::SharedPtr sub_map_; + rclcpp::Subscription::SharedPtr sub_odometry_; - // Publisher - rclcpp::Publisher::SharedPtr - mission_remaining_distance_time_publisher_; + rclcpp::Publisher::SharedPtr pub_mission_remaining_distance_time_; - // Timer rclcpp::TimerBase::SharedPtr timer_; - // Route Handler route_handler::RouteHandler route_handler_; lanelet::LaneletMapPtr lanelet_map_ptr_; lanelet::routing::RoutingGraphPtr routing_graph_ptr_; @@ -78,35 +69,36 @@ class MissionRemainingDistanceTimeCalculatorNode : public rclcpp::Node lanelet::ConstLanelets road_lanelets_; bool is_graph_ready_; - // Callback - void onTimer(); - void onOdometry(const Odometry::ConstSharedPtr msg); - void onRoute(const LaneletRoute::ConstSharedPtr msg); - void onMap(const HADMapBin::ConstSharedPtr msg); + // Data Buffer + Pose current_vehicle_pose_; + Vector3 current_vehicle_velocity_; + Pose goal_pose_; + bool has_received_route_; + + // Parameter + NodeParam node_param_; + + // Callbacks + void on_timer(); + void on_odometry(const Odometry::ConstSharedPtr& msg); + void on_route(const LaneletRoute::ConstSharedPtr& msg); + void on_map(const HADMapBin::ConstSharedPtr& msg); - // Calculate and publish methods /** * @brief calculate mission remaining distance */ - double calcuateMissionRemainingDistance() const; + double calculate_remaining_distance() const; + /** * @brief calculate mission remaining time */ - double calcuateMissionRemainingTime(const double remaining_distance) const; + double calculate_remaining_time(double remaining_distance) const; + /** * @brief publish mission remaining distance and time */ - void publishMissionRemainingDistanceTime( - const double remaining_distance, const double remaining_time) const; - - // Data Buffer - Pose current_vehicle_pose_; - Vector3 current_vehicle_velocity_; - Pose goal_pose_; - bool has_received_route_; - - // Parameter - NodeParam node_param_; + void publish_mission_remaining_distance_time( + double remaining_distance, double remaining_time) const; }; -} // namespace mission_remaining_distance_time_calculator +} // namespace autoware::remaining_distance_time_calculator #endif // MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__MISSION_REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ diff --git a/planning/mission_remaining_distance_time_calculator/CMakeLists.txt b/planning/mission_remaining_distance_time_calculator/CMakeLists.txt deleted file mode 100644 index d63f399764daa..0000000000000 --- a/planning/mission_remaining_distance_time_calculator/CMakeLists.txt +++ /dev/null @@ -1,21 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(mission_remaining_distance_time_calculator) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_add_library(mission_remaining_distance_time_calculator SHARED - src/mission_remaining_distance_time_calculator_node.cpp -) - -rclcpp_components_register_node(mission_remaining_distance_time_calculator - PLUGIN "mission_remaining_distance_time_calculator::MissionRemainingDistanceTimeCalculatorNode" - EXECUTABLE mission_remaining_distance_time_calculator_node -) - - -ament_auto_package( - INSTALL_TO_SHARE - launch - config -) From d43a1c32eff72e0128238ed85fe6ae24fe8c4a37 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 10 May 2024 15:21:40 +0000 Subject: [PATCH 50/77] style(pre-commit): autofix --- .../remaining_distance_time_calculator.launch.xml | 5 +---- .../remaining_distance_time_calculator.schema.json | 4 +--- .../remaining_distance_time_calculator_node.cpp | 14 ++++++-------- .../remaining_distance_time_calculator_node.hpp | 12 ++++++------ 4 files changed, 14 insertions(+), 21 deletions(-) diff --git a/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml b/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml index ebf088e6ad149..cfb456c57ca41 100644 --- a/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml +++ b/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml @@ -1,9 +1,6 @@ - + diff --git a/planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json b/planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json index adb84e6f26cc7..4b3bc15432d0d 100644 --- a/planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json +++ b/planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json @@ -11,9 +11,7 @@ "description": "Recalculate remaining distance and time at this rate, Hz" } }, - "required": [ - "update_rate" - ], + "required": ["update_rate"], "additionalProperties": false }, "properties": { diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp index deccb65eb9cae..9140fd8b4710d 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -39,8 +39,7 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode( using std::placeholders::_1; sub_odometry_ = create_subscription( - "~/input/odometry", 1, - std::bind(&RemainingDistanceTimeCalculatorNode::on_odometry, this, _1)); + "~/input/odometry", 1, std::bind(&RemainingDistanceTimeCalculatorNode::on_odometry, this, _1)); const auto qos_transient_local = rclcpp::QoS{1}.transient_local(); @@ -59,11 +58,10 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode( const auto period_ns = rclcpp::Rate(node_param_.update_rate).period(); timer_ = rclcpp::create_timer( - this, get_clock(), period_ns, - std::bind(&RemainingDistanceTimeCalculatorNode::on_timer, this)); + this, get_clock(), period_ns, std::bind(&RemainingDistanceTimeCalculatorNode::on_timer, this)); } -void RemainingDistanceTimeCalculatorNode::on_map(const HADMapBin::ConstSharedPtr& msg) +void RemainingDistanceTimeCalculatorNode::on_map(const HADMapBin::ConstSharedPtr & msg) { route_handler_.setMap(*msg); lanelet_map_ptr_ = std::make_shared(); @@ -74,13 +72,13 @@ void RemainingDistanceTimeCalculatorNode::on_map(const HADMapBin::ConstSharedPtr is_graph_ready_ = true; } -void RemainingDistanceTimeCalculatorNode::on_odometry(const Odometry::ConstSharedPtr& msg) +void RemainingDistanceTimeCalculatorNode::on_odometry(const Odometry::ConstSharedPtr & msg) { current_vehicle_pose_ = msg->pose.pose; current_vehicle_velocity_ = msg->twist.twist.linear; } -void RemainingDistanceTimeCalculatorNode::on_route(const LaneletRoute::ConstSharedPtr& msg) +void RemainingDistanceTimeCalculatorNode::on_route(const LaneletRoute::ConstSharedPtr & msg) { goal_pose_ = msg->goal_pose; has_received_route_ = true; @@ -163,7 +161,7 @@ void RemainingDistanceTimeCalculatorNode::publish_mission_remaining_distance_tim pub_mission_remaining_distance_time_->publish(mission_remaining_distance_time); } -} // autoware::namespace mission_remaining_distance_time_calculator +} // namespace autoware::remaining_distance_time_calculator #include RCLCPP_COMPONENTS_REGISTER_NODE( diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp index a297345cc0c3f..aeab5bbe3a331 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__MISSION_REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ -#define MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__MISSION_REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ +#ifndef REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ +#define REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ #include #include @@ -80,9 +80,9 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node // Callbacks void on_timer(); - void on_odometry(const Odometry::ConstSharedPtr& msg); - void on_route(const LaneletRoute::ConstSharedPtr& msg); - void on_map(const HADMapBin::ConstSharedPtr& msg); + void on_odometry(const Odometry::ConstSharedPtr & msg); + void on_route(const LaneletRoute::ConstSharedPtr & msg); + void on_map(const HADMapBin::ConstSharedPtr & msg); /** * @brief calculate mission remaining distance @@ -101,4 +101,4 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node double remaining_distance, double remaining_time) const; }; } // namespace autoware::remaining_distance_time_calculator -#endif // MISSION_REMAINING_DISTANCE_TIME_CALCULATOR__MISSION_REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ +#endif // REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ From 24db0c000ab24b59c823f0e0ffce10cb347c32ed Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 10 May 2024 18:28:18 +0300 Subject: [PATCH 51/77] remove unused dep MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../autoware_mission_details_overlay_rviz_plugin/package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml index e2b66ca469e8f..1054ac4f516bd 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml @@ -12,7 +12,6 @@ BSD-3-Clause autoware_internal_msgs - autoware_overlay_msgs boost rviz_common rviz_ogre_vendor From 4925f0393d0c434c7e86658b9e90edcfbbf81dd9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 10 May 2024 18:44:18 +0300 Subject: [PATCH 52/77] reformat cmakelists MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../CMakeLists.txt | 90 +++++++++---------- .../plugins_description.xml | 6 +- 2 files changed, 45 insertions(+), 51 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt index f4a4188638600..f689e6d613bcd 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt @@ -1,15 +1,13 @@ cmake_minimum_required(VERSION 3.8) project(autoware_mission_details_overlay_rviz_plugin) -# find dependencies find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() set( - headers_to_moc - include/overlay_text_display.hpp - include/mission_details_display.hpp - + headers_to_moc + include/overlay_text_display.hpp + include/mission_details_display.hpp ) set( @@ -17,46 +15,42 @@ set( include/remaining_distance_time_display.hpp ) - - foreach(header "${headers_to_moc}") - qt5_wrap_cpp(display_moc_files "${header}") + qt5_wrap_cpp(display_moc_files "${header}") endforeach() set( - display_source_files - src/overlay_text_display.cpp - src/overlay_utils.cpp - src/mission_details_display.cpp - src/remaining_distance_time_display.cpp - + display_source_files + src/overlay_text_display.cpp + src/overlay_utils.cpp + src/mission_details_display.cpp + src/remaining_distance_time_display.cpp ) add_library( - ${PROJECT_NAME} SHARED - ${display_moc_files} - ${headers_to_not_moc} - ${display_source_files} + ${PROJECT_NAME} SHARED + ${display_moc_files} + ${headers_to_not_moc} + ${display_source_files} ) set_property(TARGET ${PROJECT_NAME} PROPERTY CXX_STANDARD 17) target_compile_options(${PROJECT_NAME} PRIVATE -Wall -Wextra -Wpedantic) target_include_directories( - ${PROJECT_NAME} PUBLIC - $ - $ - ${Qt5Widgets_INCLUDE_DIRS} - ${OpenCV_INCLUDE_DIRS} + ${PROJECT_NAME} PUBLIC + $ + $ + ${Qt5Widgets_INCLUDE_DIRS} + ${OpenCV_INCLUDE_DIRS} ) target_link_libraries( - ${PROJECT_NAME} PUBLIC - rviz_ogre_vendor::OgreMain - rviz_ogre_vendor::OgreOverlay + ${PROJECT_NAME} PUBLIC + rviz_ogre_vendor::OgreMain + rviz_ogre_vendor::OgreOverlay ) - target_compile_definitions(${PROJECT_NAME} PRIVATE "${PROJECT_NAME}_BUILDING_LIBRARY") # prevent pluginlib from using boost @@ -65,19 +59,19 @@ target_compile_definitions(${PROJECT_NAME} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNC pluginlib_export_plugin_description_file(rviz_common plugins_description.xml) ament_target_dependencies( - ${PROJECT_NAME} - PUBLIC - rviz_common - rviz_rendering - autoware_overlay_msgs - autoware_internal_msgs + ${PROJECT_NAME} + PUBLIC + rviz_common + rviz_rendering + autoware_overlay_msgs + autoware_internal_msgs ) ament_export_include_directories(include) ament_export_targets(${PROJECT_NAME} HAS_LIBRARY_TARGET) ament_export_dependencies( - rviz_common - rviz_ogre_vendor + rviz_common + rviz_ogre_vendor ) if(BUILD_TESTING) @@ -86,32 +80,32 @@ if(BUILD_TESTING) endif() install( - TARGETS ${PROJECT_NAME} - EXPORT ${PROJECT_NAME} - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin - INCLUDES DESTINATION include + TARGETS ${PROJECT_NAME} + EXPORT ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin + INCLUDES DESTINATION include ) install( - DIRECTORY include/ - DESTINATION include + DIRECTORY include/ + DESTINATION include ) install( - TARGETS - DESTINATION lib/${PROJECT_NAME} + TARGETS + DESTINATION lib/${PROJECT_NAME} ) # Copy the assets directory to the installation directory install( - DIRECTORY assets/ - DESTINATION share/${PROJECT_NAME}/assets + DIRECTORY assets/ + DESTINATION share/${PROJECT_NAME}/assets ) add_definitions(-DQT_NO_KEYWORDS) ament_package( - CONFIG_EXTRAS "autoware_mission_details_overlay_rviz_plugin-extras.cmake" + CONFIG_EXTRAS "autoware_mission_details_overlay_rviz_plugin-extras.cmake" ) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml index 2d9e96dbb285f..fbb1dd2a43c14 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml @@ -1,5 +1,5 @@ - - Mission Details overlay plugin for the 3D view. - + + Mission Details overlay plugin for the 3D view. + From be4ba571bb6d58024ac61897fa5dc5d81af314da Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 10 May 2024 19:00:58 +0300 Subject: [PATCH 53/77] update the namespace, remove unused code MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../include/mission_details_display.hpp | 4 ++-- .../include/overlay_text_display.hpp | 4 ++-- .../include/overlay_utils.hpp | 2 +- .../include/remaining_distance_time_display.hpp | 4 ++-- .../package.xml | 1 + .../plugins_description.xml | 2 +- .../src/mission_details_display.cpp | 8 ++++---- .../src/overlay_text_display.cpp | 8 ++++---- .../src/overlay_utils.cpp | 2 +- .../src/remaining_distance_time_display.cpp | 16 +--------------- 10 files changed, 19 insertions(+), 32 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp index ec97f13fb6b97..7479b1d6f614b 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp @@ -34,7 +34,7 @@ #include #endif -namespace autoware_mission_details_overlay_rviz_plugin +namespace autoware::mission_details_overlay_rviz_plugin { class MissionDetailsDisplay : public rviz_common::Display { @@ -59,7 +59,7 @@ private Q_SLOTS: private: std::mutex mutex_; - autoware_mission_details_overlay_rviz_plugin::OverlayObject::SharedPtr overlay_; + autoware::mission_details_overlay_rviz_plugin::OverlayObject::SharedPtr overlay_; rviz_common::properties::IntProperty * property_width_; rviz_common::properties::IntProperty * property_height_; rviz_common::properties::IntProperty * property_left_; diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp index 7156e9569676d..eb9baa4d30ca3 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp @@ -68,7 +68,7 @@ #include #endif -namespace autoware_mission_details_overlay_rviz_plugin +namespace autoware::mission_details_overlay_rviz_plugin { class OverlayTextDisplay : public rviz_common::RosTopicDisplay @@ -79,7 +79,7 @@ class OverlayTextDisplay virtual ~OverlayTextDisplay(); protected: - autoware_mission_details_overlay_rviz_plugin::OverlayObject::SharedPtr overlay_; + autoware::mission_details_overlay_rviz_plugin::OverlayObject::SharedPtr overlay_; int texture_width_; int texture_height_; diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp index 4d27655dd33b7..a82b9397a30da 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp @@ -70,7 +70,7 @@ #include #include -namespace autoware_mission_details_overlay_rviz_plugin +namespace autoware::mission_details_overlay_rviz_plugin { class OverlayObject; diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp index 2dc4e4b56d332..9a1c34be910b6 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp @@ -29,7 +29,7 @@ #include #include -namespace autoware_mission_details_overlay_rviz_plugin +namespace autoware::mission_details_overlay_rviz_plugin { class RemainingDistanceTimeDisplay @@ -52,6 +52,6 @@ class RemainingDistanceTimeDisplay QImage scaledTimeToGoalFlag; }; -} // namespace autoware_mission_details_overlay_rviz_plugin +} // namespace autoware::mission_details_overlay_rviz_plugin #endif // REMAINING_DISTANCE_TIME_DISPLAY_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml index 1054ac4f516bd..e2b66ca469e8f 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml @@ -12,6 +12,7 @@ BSD-3-Clause autoware_internal_msgs + autoware_overlay_msgs boost rviz_common rviz_ogre_vendor diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml index fbb1dd2a43c14..5177b10859704 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml @@ -1,5 +1,5 @@ - + Mission Details overlay plugin for the 3D view. diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp index da54fcccd5768..99c76edaffbdf 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -33,7 +33,7 @@ #include #include -namespace autoware_mission_details_overlay_rviz_plugin +namespace autoware::mission_details_overlay_rviz_plugin { MissionDetailsDisplay::MissionDetailsDisplay() @@ -60,7 +60,7 @@ void MissionDetailsDisplay::onInitialize() static int count = 0; std::stringstream ss; ss << "MissionDetailsDisplay" << count++; - overlay_.reset(new autoware_mission_details_overlay_rviz_plugin::OverlayObject(ss.str())); + overlay_.reset(new autoware::mission_details_overlay_rviz_plugin::OverlayObject(ss.str())); overlay_->show(); updateOverlaySize(); updateOverlayPosition(); @@ -105,7 +105,7 @@ void MissionDetailsDisplay::update(float /* wall_dt */, float /* ros_dt */) if (!overlay_) { return; } - autoware_mission_details_overlay_rviz_plugin::ScopedPixelBuffer buffer = overlay_->getBuffer(); + autoware::mission_details_overlay_rviz_plugin::ScopedPixelBuffer buffer = overlay_->getBuffer(); QImage hud = buffer.getQImage(*overlay_); hud.fill(Qt::transparent); drawWidget(hud); @@ -240,4 +240,4 @@ void MissionDetailsDisplay::topic_updated_remaining_distance_time() #include PLUGINLIB_EXPORT_CLASS( - autoware_mission_details_overlay_rviz_plugin::MissionDetailsDisplay, rviz_common::Display) + autoware::mission_details_overlay_rviz_plugin::MissionDetailsDisplay, rviz_common::Display) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp index 10a7b8cb3e4ca..2cb4a39938047 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp @@ -67,7 +67,7 @@ #include #include -namespace autoware_mission_details_overlay_rviz_plugin +namespace autoware::mission_details_overlay_rviz_plugin { OverlayTextDisplay::OverlayTextDisplay() : texture_width_(0), @@ -212,7 +212,7 @@ void OverlayTextDisplay::update(float /*wall_dt*/, float /*ros_dt*/) overlay_->updateTextureSize(texture_width_, texture_height_); { - autoware_mission_details_overlay_rviz_plugin::ScopedPixelBuffer buffer = overlay_->getBuffer(); + autoware::mission_details_overlay_rviz_plugin::ScopedPixelBuffer buffer = overlay_->getBuffer(); QImage Hud = buffer.getQImage(*overlay_, bg_color_); QPainter painter(&Hud); painter.setRenderHint(QPainter::Antialiasing, true); @@ -297,7 +297,7 @@ void OverlayTextDisplay::processMessage(autoware_overlay_msgs::msg::OverlayText: static int count = 0; std::stringstream ss; ss << "OverlayTextDisplayObject" << count++; - overlay_.reset(new autoware_mission_details_overlay_rviz_plugin::OverlayObject(ss.str())); + overlay_.reset(new autoware::mission_details_overlay_rviz_plugin::OverlayObject(ss.str())); overlay_->show(); } if (overlay_) { @@ -554,4 +554,4 @@ void OverlayTextDisplay::updateLineWidth() #include PLUGINLIB_EXPORT_CLASS( - autoware_mission_details_overlay_rviz_plugin::OverlayTextDisplay, rviz_common::Display) + autoware::mission_details_overlay_rviz_plugin::OverlayTextDisplay, rviz_common::Display) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp index 68c4277e5d677..3f7debacdb210 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp @@ -52,7 +52,7 @@ #include -namespace autoware_mission_details_overlay_rviz_plugin +namespace autoware::mission_details_overlay_rviz_plugin { ScopedPixelBuffer::ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr pixel_buffer) : pixel_buffer_(pixel_buffer) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index 52ca46300cfa3..ded4cf377af62 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -33,7 +33,7 @@ #include #include -namespace autoware_mission_details_overlay_rviz_plugin +namespace autoware::mission_details_overlay_rviz_plugin { RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() @@ -141,24 +141,10 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( remainingDistanceIconPos.y() + scaledTimeToGoalFlag.height() / 2.0, scaledTimeToGoalFlag); // Calculate remaining minutes and seconds - // uint8_t remainig_hours = static_cast(remaining_time_ / 3600.0); double remaining_time_mod = std::fmod(remaining_time_, 3600); uint8_t remaining_minutes = static_cast(remaining_time_mod / 60.0); uint8_t remaining_seconds = static_cast(std::fmod(remaining_time_mod, 60)); - // // Remaining hours value - // QString remaininghoursValue = - // QString::number(remaining_hours_ != 0 ? remaining_hours_ : 0, 'f', 0); - // QPointF remaininghoursValuePos(remainingTimeReferencePos.x() + 17, - // remainingTimeReferencePos.y()); painter.setPen(gray); if (remaining_hours_ != 0) - // painter.drawText(remaininghoursValuePos, remaininghoursValue); - - // // Remaining hours separator - // QString hoursSeparatorText = "h"; - // QPointF hoursSeparatorTextPos(remainingTimeReferencePos.x() + 35, - // remainingTimeReferencePos.y()); if (remaining_hours_ != 0) - // painter.drawText(hoursSeparatorTextPos, hoursSeparatorText); - // Remaining minutes value QString remainingminutesValue = QString::number(remaining_minutes != 0 ? remaining_minutes : 0, 'f', 0); From 137cae42f38885c4aae891fade52ee5daf7c8650 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 10 May 2024 16:03:08 +0000 Subject: [PATCH 54/77] style(pre-commit): autofix --- .../include/mission_details_display.hpp | 2 +- .../include/overlay_text_display.hpp | 2 +- .../include/overlay_utils.hpp | 2 +- .../src/mission_details_display.cpp | 2 +- .../src/overlay_text_display.cpp | 2 +- .../src/overlay_utils.cpp | 2 +- .../src/remaining_distance_time_display.cpp | 2 +- 7 files changed, 7 insertions(+), 7 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp index 7479b1d6f614b..9798373ea7e4a 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp @@ -82,6 +82,6 @@ private Q_SLOTS: const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); void drawWidget(QImage & hud); }; -} // namespace autoware_mission_details_overlay_rviz_plugin +} // namespace autoware::mission_details_overlay_rviz_plugin #endif // MISSION_DETAILS_DISPLAY_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp index eb9baa4d30ca3..d69abfd48266e 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp @@ -151,6 +151,6 @@ protected Q_SLOTS: private: void processMessage(autoware_overlay_msgs::msg::OverlayText::ConstSharedPtr msg) override; }; -} // namespace autoware_mission_details_overlay_rviz_plugin +} // namespace autoware::mission_details_overlay_rviz_plugin #endif // OVERLAY_TEXT_DISPLAY_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp index a82b9397a30da..af3effedb2644 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp @@ -136,6 +136,6 @@ class OverlayObject Ogre::MaterialPtr panel_material_; Ogre::TexturePtr texture_; }; -} // namespace autoware_mission_details_overlay_rviz_plugin +} // namespace autoware::mission_details_overlay_rviz_plugin #endif // OVERLAY_UTILS_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp index 99c76edaffbdf..bcee60d290543 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -236,7 +236,7 @@ void MissionDetailsDisplay::topic_updated_remaining_distance_time() }); } -} // namespace autoware_mission_details_overlay_rviz_plugin +} // namespace autoware::mission_details_overlay_rviz_plugin #include PLUGINLIB_EXPORT_CLASS( diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp index 2cb4a39938047..8d0d2173f421d 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp @@ -550,7 +550,7 @@ void OverlayTextDisplay::updateLineWidth() } } -} // namespace autoware_mission_details_overlay_rviz_plugin +} // namespace autoware::mission_details_overlay_rviz_plugin #include PLUGINLIB_EXPORT_CLASS( diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp index 3f7debacdb210..68813a5f1140f 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp @@ -264,4 +264,4 @@ unsigned int OverlayObject::getTextureHeight() const return 0; } } -} // namespace autoware_mission_details_overlay_rviz_plugin +} // namespace autoware::mission_details_overlay_rviz_plugin diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index ded4cf377af62..5808229addbf1 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -173,4 +173,4 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( if (remaining_minutes <= 0) painter.drawText(secondsSeparatorTextPos, secondsSeparatorText); } -} // namespace autoware_mission_details_overlay_rviz_plugin +} // namespace autoware::mission_details_overlay_rviz_plugin From 59cebe7a66863ea12077698f6a95e3fe865886a2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 10 May 2024 19:30:31 +0300 Subject: [PATCH 55/77] remove unused headers MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../src/mission_details_display.cpp | 7 ------- .../src/overlay_text_display.cpp | 4 ---- .../src/remaining_distance_time_display.cpp | 19 +++---------------- 3 files changed, 3 insertions(+), 27 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp index bcee60d290543..682990135624a 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -20,14 +20,7 @@ #include #include -#include -#include -#include -#include -#include - #include -#include #include #include #include diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp index 8d0d2173f421d..99504c63f4a91 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp @@ -60,10 +60,6 @@ #include #include -#include -#include -#include - #include #include diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index 5808229addbf1..1e637be6e1037 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -17,17 +17,9 @@ #include #include #include -#include - -#include -#include -#include -#include -#include -#include + #include -#include #include #include #include @@ -65,13 +57,8 @@ RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData( const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg) { - try { - remaining_distance_ = msg->remaining_distance; - remaining_time_ = msg->remaining_time; - } catch (const std::exception & e) { - // Log the error - std::cerr << "Error in processMessage: " << e.what() << std::endl; - } + remaining_distance_ = msg->remaining_distance; + remaining_time_ = msg->remaining_time; } void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( From 7920153ab481087e70dcb52a7bc62ebc92feb098 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 10 May 2024 19:47:38 +0300 Subject: [PATCH 56/77] update the images MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../assets/av_timer.png | Bin 0 -> 2010 bytes .../assets/path.png | Bin 0 -> 1461 bytes .../assets/score_white.png | Bin 100 -> 0 bytes .../assets/timelapse.png | Bin 2972 -> 0 bytes .../assets/white_flag.png | Bin 131 -> 0 bytes .../src/remaining_distance_time_display.cpp | 5 ++--- 6 files changed, 2 insertions(+), 3 deletions(-) create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/av_timer.png create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/path.png delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/score_white.png delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/timelapse.png delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/white_flag.png diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/av_timer.png b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/av_timer.png new file mode 100644 index 0000000000000000000000000000000000000000..f7f5db12495113f6b0afacbc182658bb519a9059 GIT binary patch literal 2010 zcmV<02POE4P)Px+lu1NERCr$PoZC+0I2eF`r)agicO#%fuC_eMlqaEm65vT-o@BaDLPlDt(1N&H zt+Y$y#Yqz!C;!2*LyOej%pp!}fBw&QqTuigBA|lqKHLlkfPq4A0C)fxNFea`y_CS^ z@?~PrD^0&-f%6>f_PqnRTs_ScsN0SiZz1YTfhzubNATd!1hDXUx;?2( z0W5X}bMFBn&@kD^0Cc9cTBKi(Zv+Aq++^E&6 zU@_2JKP^CC7z*Gn-y}D&J^JSZ=xG!k(3##O7cn751GrqRX6bkw98wTrjIYq4jz(*^ zi{)gZ0DM?I{Qyu?t>HR!U=%>}d{Fvl0_vLvm;yi};PxRLW2~mXV1O08YVe^0BLRY* z+g`QESd#owDVX(xnJ>=9rx!lp-L^phU3f7d)&M(fopu1)lPT|mOQQ)sK#X(wIzFEJ z++(-x4X_2znQ&i8BqcD>^YnyH-HcSKQT_v$NR!Jnr`>m~y;XSm_(YzmTf37+{F>*)TbXLjm+tXT3NZpNQf^5y16&J>3W#hY^1b zMNmurD2Q%3-+oYx99HTCrBWyYD3QJj%8(%rw=mM{!ZBuN!nlS?V%*@WC1>|o^Ls|>=Jk3D#Oko67g)6R3)GnW5yP;03TM* z9s4-%Yfrg-A;c_ZdC5mA1*VBrV-ldGHpdxT6r!CwYsfUjtI&{bcz zKq3+GB7BhL&O4DrUJB`uh6Ko|uf)jK*}$GcEQ=S339vE2CDjFTl&#)woM17G#Qqg&+0kpU@#7}v5)%Ocy&X&4_v=x{nVIF&(@f=X3vX58uERIr zBnq}hkpLTYKeuF0R4kB4zg4hAAvXK+g4k8M;x^UoaHeA`#_&QN2?dZ0pf%w@2$hgS zY?^ctM8+YY5Crj{A3%|3LI5^))hY;$rD!{!SnABBotQU8=WB`M+4#6q*gF4H0uXy3 zHwjD~#1M&+JGb3{dDF&xyL8x?#@FtUEjmDnhsEG?5IM)i0i?Vsn=~LA*BhYT{C=LM zzqQUTbM}PWbHE^S@Qk(K!V&BlAsQ$5!cLq{+Y`Lj#wF)P?(CeCmcX-0_DEKN2maim zn`e93K+$S4Va)c-N?lZat0`vSvF}#^YzpB zRg!chl|&|=jTSm_wy!v_qBMKVjRj~+AyTb1O`=GLL@Hv0PLh744pIcrjR~=`cc>~$ zlKL0`x&0m^5z>A{0EM=&kVMImun@aMZ6!#|M8ia&Dka~t6$9LE6y4LIqXq>k=*1P< zHpwT}1(T~6R`*DyPvnK|f$)a6Y#mZ)z|Zc5!Q(0})jWM2qF4e=2R^6W!yx`MfzjVn z^HO1M;y|;n9PkRibm9A$ATNLxL^4ONrPdr<%j3SEE3tD`8|g{ZKB{X;tk00jwo-N2 zJ~?WjEgh|ow)l8mw|{R5tXG$>7utQ5pC%dLm3wzW_sf^bujMPS*F@afxGluo^af}~ z&}CbgK^G?sAWy!>&TFlAhuOpJP3U3HDF|TyK|`h>S>&(@`tnfKe-Tay-X3kMe;7RP zFb1o-Jg?Pmr_p#7l2u_$%h zeLPHR`un!q7B&$3;r_Qzpv;XZ8bB+=A>J0}hBNr}C`FG!B+!n%+)Z^kmiB%`<6go; z*_XPTh1Pt*;FVt{UfH z64(N1oJPx)Z%IT!RCr$PoLyGiIuL+IPB+j)o06x}l@wOevJzk=(3Rk>r0&B#2`M>u1C8fi zDLB}&tr=MwI|<5LPc^diX*7S5P>_B>1XPf85{3jYPze&i1Tc_5pm@^21Tc_5pm@^2 z1Tc_5pm@^2Ljbs3{(AxM{$4CTe#`^Mb9CZ^G;sOn&n1-ESEcY0KwVn1E&#AVg?DcO zs24z^X<7MADZB+n5~Bbf%58SHSiCQePPLc=W&_k(r!aeD_FHdOAi~4q)7jks*@G8h z0Stgw0Vq(F*QdCpSpZk-%`X7B=u-#X3DUZ9k`PINtJU)(WT2e|jfiZ4`T6|A71`{F z8aSy$*t#tgsLHET+R9FVPwUM+0(_6F5SU{IKcF1gt3u<^4`mUY04dw2CxQsKP-Z_2 z4in-S;Jx;8kBwzGwPo!cVxa)?67c6@{^4QZas-P}0G+-;$9bRTXV>*nET1+vO2O^$ zkvXAR-R|2?=Ae23>Y!Q8O6`4nf4I%Q*g-N!Zs)UOIHktWCW$w_0NT5*&mpYV8%9*) zSQ%=2JN{prlre+$=v&z7cqlN#_kBZhOo#-)=f{1qpnLLW+gMH{!2U%d2r!yWbjN`$ zhtO-gbZ9|)Uc(1-1lW0P-yf>aRRxGv=5d1dqYR{9t3pk0&$ZFM>*i`ty27}@bX={V zGo`rS>jFsvd=h0&u4}op)+zCLS%My{~sB z;xYElrc}yhggkTWzA=pjZ!`_8+pAzky&dc_k1-s_;8bpi7E;E3NS_Uvddw%BwsnnF z)C*H#MlihB4n`~C+hZ05*shZBsy8%P)6d}_tkVzJ-~uqV~g z(9Tbrw%=Rft#-L*qiDW@j~(AdH4{h$f;PT67n zL-%X{H=R#2!~j+Sthpv!O-^i*E+wNqu3et8uGc!9i6}q=G4RrPgZU&2pidI|-?qpD zWL*d8(ULx31jwPByX6pYJ8NC0ue4SiVD%wZNuM_NGA#(=uCwLQ09H2f<-PICLv4)_>T(Eo+kfTlLttFD~zcYg1aERGnPpK^04q*@gDi``!o7S9L}E&1rQ46OnCd5PH-%|{T)Yct6jPb`1Cc(?a+u!*AeRKgHf8XKc zY+xOUUrFEGENMO8rIzue0XBnpUD(jS#vckYuiwpkzpVT@5WnH~+()aC3iK%X zOEAQLqfQVGS60+nx7(ex%;(bK7fu5%uExKpC^`Ve^lzUC)b89PKn5xd2RobH-`%_O z*TX^paQ^vU2ciDwb1?c4Q+w!ddWAhrFzM4M2;c2K>JDlii|xKu04^`Do<}-3`No{E zWP54=vlRyVWNT~lou?j+yJ;K%vg`l(8a;p=cg?OgbDb#8haEkPbZ4Sg)M#EhNz2q!?S;YYVKfU6z9MG`f&)DN zLp;8{x$5m~ZM<}xL+RtS0FXM`KQL;NIGKOWpdkHFhl8!HF2(THpUcbfeiR_D(CP@C z{A}6L5Dxlj9S+(%02%Y4`unWv-{-~+e(mekuveGujeXJAh%}PGNHjzKsRabD0L0R! zB9eTQWa>t1)mvW+dv!=y5r0WY{{1C74uaS`%7KXUhVYrIR_1B)20$wLA5EAKSNv{$ zH9T&L@$+EBKzxmQV8ZhSVcXJX z&H#Y$?N+alFu7};1p&%0gxtH?!W*}S>gw9WFLuYFME^}E0GxliK7kbdR>dlc z^O4!^o2a`v>ysxe0iZ|4)y_0?9;v&(e&-&1Sbj%5a z=P@TdWj-(;h?tmQIRL!+H7@;*PPhnbw!V`V9!Ge%R0~YZuowVH+8BdYWxdXI5mV{E z1Hj)Jv&0`1*1zt@;uF+}x{~>b0Fb2RNXH-BrsEPq%i4G}LCFw;cs?z|(Ar1oM_PUn z0U)S&o&j-LIogHW1!x!jS09aKM5Ly@Wso!c1aEp#0Se5)?i*y3h z%mctIIZ7N>qX5|Nfcu6_E|STTvI>P_9We_4>OTW4&;6~`);TW8xq?%d4Ae0AQa|l?*H|&m>!dy#T-!;Mz*SGBCUXFlS3R26B-Q zC3ReRn$-Yqf}EqOL+bN=a`d^3AAx~CGWC4~DY2@Q?Y`#t^VbBxz)^DyG=3`uL-Sl`&I0`U%j;+%s6kktUhx}&Pa=r)|NH|8_y!8u{B zDk=ex2Y|@~nhryoVt$+lFmXJ$N~lBR0h=}F0bI7|YJ>C7H_3cSBF53f0Z3!88o;du zaM_|S0JzEe8Yk%|Nu)U866}$3FGVauF|JwW-$BVa(0nnj(3krt#&LEI7I$kfJs$$9`Iy=)l*(uQp=?h7&`wcoCP&c(a}RWp@-@64Al z{fiw$dau6R&b9rNnjy37sonaQ4~at zxVm>dbx+$;yi0x&>ebr7N`I1oDQrtAKOw13rP?}P|g5|PYfCyUQQP_=x#RK z8?B^}WbMw7w;W2h)6XADFB;7DWT>$Q#AZlxVvrgdN<^Yv`UDS_YC~~eE8c<_Uk+t* zj7p^On5s$SW9@|V53>6r)5cO8oAoWa&Fa>)2+9nJABnF+LzsEO?N-juk@ZnoV?pJ# zOhv6UAl8E9{xv$Jz}jwUTAn8|xy@>Jh;5N{9gMAMI)ec8)>k{HCX6RKB;}Ws-W!;+ zeW^Kf_5t}042Wd++gBNJ0^`eUc0kur;)?nMfI{2h=RqN6PhblMbiL(Tr!z2RdPaj- z^2y3N?v1t9fQ(qSE|QBxR&j^u#@5E0DrUF+9p*!qPf0J8a;|?l13(NDoR_-eE21M@ zS@yzKI_m-`y|V0W{t6yuEVgbWq16ijX^K7&+v*lB$*y9?XGC=~x>S7rtsLbKox!0W z_z)s501%y$1Iz^usE>10FMUizB5m_+V&C#LdW|6VNcy~OykFM8HvnjWbe)tmfsKrE z1Wo7?rL~ptO;bR`jGsoof|(RyiO;tY^YLDqL!So{y#kQa1i3l7Ln6Lb3?bbc+mMcv z;xu$7Crc79W_;SOH?xzc(>nl;AY`<~m+j&B>jzh9OSO`YSP|2050lrze41=60AyTb zLsU*=lkXAR>p>6(L!|q|j#iWD3U)2ey_yt(e3s1rjkBSm2;?B zHO*Q9pn;96oo3rdis$C1jD3S7>&WF!P>Foi4ge96zQUx(UVN8Qd=G<^nLcolFeGk+ z+74b}f>O2YQa^FO1q~YkARCvesCY@++$GuKN~X&^MbEZzsd%FR+&buKbfhCi_xDS0 zD;F`)wh=Kt2=N-Lm9XDbD4fySH~@JjQPB& z7iQyCh5?eeqD60iPT&UJ<096uZ*$YFl(Euw3jsi$*feT7z~AVf?K;5x{Lk^#LU6*+47el6`rnsF6*2UngFu#COZHC diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index 1e637be6e1037..92ecc79026075 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -43,9 +43,8 @@ RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() std::cout << "Failed to load the Quicksand font."; } - // Load the wheel image - std::string dist_image = package_path + "/assets/score_white.png"; - std::string time_image = package_path + "/assets/timelapse.png"; + std::string dist_image = package_path + "/assets/path.png"; + std::string time_image = package_path + "/assets/av_timer.png"; distToGoalFlag.load(dist_image.c_str()); timeToGoalFlag.load(time_image.c_str()); scaledDistToGoalFlag = From 30fc9f4cb5eb826ebe37ac3fed12cd38ce8abb01 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 10 May 2024 19:48:55 +0300 Subject: [PATCH 57/77] icon sources MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../autoware_mission_details_overlay_rviz_plugin/README.md | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md index 28b0c4393ab7b..39ca706d4b6c1 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md @@ -48,3 +48,10 @@ TBD. 3. Enter the names of the topics if necessary `/planning/mission_remaining_distance_time`. ![select_topic_name](./assets/images/select_topic_name.png) + +## Credits + +### Icons + +- https://fonts.google.com/icons?selected=Material+Symbols+Outlined:conversion_path:FILL@1;wght@400;GRAD@200;opsz@20&icon.size=20&icon.color=%23e8eaed&icon.query=path +- https://fonts.google.com/icons?selected=Material+Symbols+Outlined:av_timer:FILL@1;wght@400;GRAD@200;opsz@20&icon.size=20&icon.color=%23e8eaed&icon.query=av+timer From 8a4c8e9e7778ddc1cb9bc7c6bde41a6d24060407 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 10 May 2024 19:50:52 +0300 Subject: [PATCH 58/77] simplify readme MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../README.md | 13 ++----------- .../assets/images/select_add.png | Bin 18359 -> 0 bytes .../assets/images/select_plugin.png | Bin 48546 -> 0 bytes .../assets/images/select_topic_name.png | Bin 13679 -> 0 bytes 4 files changed, 2 insertions(+), 11 deletions(-) delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/select_add.png delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/select_plugin.png delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/select_topic_name.png diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md index 39ca706d4b6c1..ae50f9dd4cbf7 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md @@ -1,4 +1,4 @@ -# autoware_overlay_rviz_plugin +# autoware_mission_details_overlay_rviz_plugin Plugin for displaying 2D overlays over the RViz2 3D scene for mission details (such as remaining distance and time). @@ -38,16 +38,7 @@ TBD. ## Usage -1. Start `rviz2` and click `Add` button under the `Displays` panel. - - ![select_add](./assets/images/select_add.png) - -2. Under `By display type` tab, select `autoware_mission_details_overlay_rviz_plugin/MissionDetailsDisplay` and press OK. - ![select_add](./assets/images/select_plugin.png) - -3. Enter the names of the topics if necessary `/planning/mission_remaining_distance_time`. - - ![select_topic_name](./assets/images/select_topic_name.png) +Similar to [autoware_overlay_rviz_plugin](../autoware_overlay_rviz_plugin/README.md) ## Credits diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/select_add.png b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/images/select_add.png deleted file mode 100644 index c5130b6092384e5477ca0c52e856eee862f69431..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 18359 zcmX|p2Rzm7`~R`YmXJM8k?e#dG7eFQP&V0nM|O6E;z1EY2q8OroFWNHcIK(j$;#fp z>m1+z|9SO1Pvf}VpZmV9_w|0iuj|v}+gfVWr&v!R5D04Z8!Ea81fekkK|nxG3csT* zV-W=ZBlc2K*CU620?Dmo;MZrpQTM#>xY>I9T6)?b>|EVkY=ph6JZ)@Tz3kn*SBP5W z5eROCx{9Kn-^;&~hEJ{cP5HN03_Yj&l8jwUCxgyiXIQu&|6Yll;E{C)O$-Y!mCER) zSz$j3Oti;yU$rl%YqS5-(LI`Pm*VUg^&{*;obniWf-qzdKq5_FUo2Z*S}uNjF0Jb4 zmHL-*C0v!4-1L2Ye3$CKZ=W6*nAER75Y#sKEq&axLav^K_J?q`ZW_1x%wqEg9Ry-enU2s$@r*A?$+z$u9rLQ!a*TZ13mWe{B) z%Te6q7U}1ch`;)97#mNBX%asT!wYF-Y9u+%M8LOyNA61SC{o5t{{7VASRxA8O zRoO4AZszks?QRQgkHj;ixZs&HoBl-C341E(h}&x>wd+kDm0_R$Vnj31)0c`W(mn0@ z^~ymOR+y6svt)TEW~JDF4d7I&tnA28~kUw<=_ar?hhw+2;8 zhLn;%m=J4=4msAmDjqZ~-VNkT)fkZ=I?qLf<+czUKF&-6FL61E!kC^ae}R!uCD_VOl=d9v&_BgwtdM#n{X>t}Q?RZ&%J_ zB+|x^C9%tHN(6riLWZe2MFQFxdZa8=r0y@}&nI{1-po65nGy~>cfkIYnHz6%cSo)8 zt@FwASzZa4rhiwu@ZbAFX5aNeZ-Lk_fmjQ}-(GxlDrpdQw+62#At7KI%9I&V@5|zD zou@V}S4us%;cqIVb)3?FB}$l=*GN55iJ-=a13gQZ$kkf6;A!6rSBhS+lz3s`R%M*tdnIi$1Dkg>#fuB+yIuv^KnE2V1M8=Yw=L;DP}#7Bv;|GJNh-;~P}xuWFPONT?t zun3m-3vnshKI#zevKH@J@IKj%h z(G*E>yIlGeRv)SES$3qR(pGI}TyGKup^2i18i;gYEpM8VbfNXUmqzD`*mf4vMe?=MIhF1sfJc5)u!4gz@2?wceZJ| zZgyYZu|~FdXz`OHr1+45Y zhK7eTMWNgC)fAJF?S66{vzC;pHuvr3Ii;kf2V7y*)3w3efB_6Bdglq%LN9b`B0pvG;*r)76uR73tc1IR37z@TB$RnU(Wp_g})nz#avf z?l2gKE4c!%2JCq=dPN$9jNU2bkZTS;>$aYc*N8^9*ChD&N!fWfa>V4yTyxm0nUsaE zWOz|Jl4L_sTns>TFLn2amUshOK_j*PjU+(*85xM$mCoh<%3F{m`ug}|3+f$LA`c4% zAm%2A3=f<(_jd5UsawPdc+474jTkg78T1K~E}yOg5XPTVt5#vSjMgg$Ru!EOYinzP zg)F7~fWKOH@LO;zqqUJ*h4HiQekDFK33zbvRW2VvC4G2f;50fl)t=0s$Yjbe`N~8j zdTEJ6Pw*6{LNM{5B-8NERLY-^V;1_}xv({x(H8ypWPh7Wq=CJGCtvq0K!2`)Wk?8Z zs*Ui5Ga>sJ1nX7I;rT)eJ^ilbWg>`!m%1jW>rFUQG)TsrX%uJjMzEF=YkhL&vo3R= zphiqysH&xl8c>$XP^=nLk%i(!ef1ke(QB}IrmiE-gE zh(W3gq-eY`z{X%$3LM%z_HK%&`!L{6and1EiwyBfKyX6oEx95cq%TxHfRdSg`K|42 zA=6Lk_=0k^d~lIFmbW(Y9{p}0L4z5p;$EnWv5btpaKr1gIl_m$yu651n;iI1ibjR- z2ZoXn?E8>odAK_oT3V05!0Lr0v&XpHA|JeLQig4-r214DF*!;06sd&}PIjz`(m=KQ z{cRWXXQBELxz#T#Di5EH$x5$@L=Z!?N@i$6fQh7=iy3O=7?kAc3AX!iyf35dXXB%~ zYvsa$dy)YPOBO(NM0b;LgahmITj%3MminF{DWF>Y@+5(iD#O10`S=6wh+?wnQS?;k zQ0|!9`e)RWpw2^)U--8C1mMoI{)q-kQ8qKo=EcH;#u&`6Y^gvd{Q8uD_%XQ%)Bv|S z!-Ue0B!`ttBsE6V9xrERUXhIWFqsbLdpweZjokE><+zvn=zc}a(o!ZW&5Iw(K3rec z{OpWHNPaj|+cT&bxpyU~h%8wYM@rzJcp&!N2F{go=rHPt+|5d`{kY(rFe}ri@mDJF zOai1LeX|mK7t}JUJW9h<_v0g?7~W~6@;ITM+l*(nmzR`q<^0;leo%xZTs4#FRLa^5 zB^4EK8Xd-V4-=NCNAO^!r7qSIFHmVU|2*s20e7HGV`S{>67Lp-3_tW>eFl;9GFKo1 zvjN4z+cdgh(V5bN1gctbF%%06F%|%bCtZ0pEWNV$i(DWqaN+TXG7p7Ko#9?;cbgAE zk>06AZ_abVOQk?B@MQGPO*QYwiP$;VNSt+ccIM3%omp6*gSA>hqzlZhR075DCh=g;o310c zRmiw99TM8y%+EgSFPPDrtCybjKrKl{&VPe5Fr-q-g`+PVR~c3AGDh+29UcwV(p}Ii zxqO46>k@=@@sO-{bF9EAi0z13_fT%~1H{twKZTMn4P-zeHh!sPT-JgC{0=OwMq82v& z-?{Af2}Oj^;|NMF+tB~6rN*+cy*`j|*PKxL0Hp8Y*;^_)DpDB$I7&r&oqlp*!1ZXz;zV2=a7>kc zGE9sLYCo~!%eqK+Q{VhO_wLFkxin+3O*&Y;5+Y5EDyNtgGJ=~tPGs>MaZGLu z07Q+EGULb5i2%ZhT9)d*$M`^@{OVW(g&)cfvEse)TDo7JX8|dJ_q4iUW?n@i)rTF` zera0a?%XI8`FH^9128118O@DY+LEY=q`NJWR?*xX4u7&(ZE1LZPR7jJ@?ta&HSHBU z#8g_{`U@B5WFA?vP@1F9sY~FKbXATvVK5r=_V;qPO&gB{tr z(<`R!!?X~mH(w8pclpUh6&K&ur%pmnE*$py2M;;=yw;VtHE8{{!4_9Pd5t8ZqoYSh zM?(u7=um5&I2sTG@&`^Yyq&JV0VKlIr=Uq2d=TBV9e2zL7l{3RC!niqgzde=3##SG z#zZ~A$hNobnxHlZXMz?=FvLY2-s1-WIw06e*sNKr<^7 zv@F%6c(U;4?V!OFyK=l<1#(w0L>xT?sNmP^8yPWx9G6r`DBC)(c`k){It4@g}G?btA zdn{D=w4eEQ$q=xpuPfWY+Rj$H(yQT+(%{3?)M;lI7iE2YpzvrhvxcaPc#yPDr$NZb zIp<8TOdHg1FrIw)Q@bK1oDzgtsX@T(FWn+Z@8&2nT25Z_K)^AP@Zm6bYh3(%1n~Xf z5ut&)QYEZXaZjar>bksnTQa{kFip@$Va4b0(QxLH6D7gSVt2{38|6vR3uvqlE}J~q z<~5}~`NYqCd7&N^P(+d(Nk}La5Gp&th^|FTNmg-tVSA zuJVyz4!)`6_&kgS@&a`NQ$eQAKyU+|vZa61uqOh4XCxqhb&Dd5N@)zWX7{H<*nkv4 z1urgct`sJo(Oln}_pgEnq@_)4^L|VgwW;nFLG2-;|=-(sB4FP*+ciaF&V#lB};U z&O#*yKiFx^&b|zsj<#e0*umG!jr}bzK1=U)d~r;Dilb+rfs4Gj#e`X7=>qV%H-9FI z0AloAO${|l2Z1;Y&W_h|JFBgt2`O%^qN7xCFQV+Oj!^21j8vA~L+_kdKHne~6zSlB z-xQzH`LC@0zW-VL6P~+MGW4!7fU8mn)1BM}=-u?s#VD1+F!igmlupS|S&oLRs1_e+ zQQ>F6baQVDw0Zm}yh@YlRBt-sSrYE+uw-`rkHS9gK{?OJ91Nl1#WE;Z2C^ z5-(^vD!)X&6q8M`+SsR=lW89wmU66NB_QrPf*Qeh*bG0^Ev|I^?M&_$38R|n&7(^c_&a{Ja64d4>l2*=Fo>dg4KtjUnY z%-q5Pd5eN#vzc1nz&&qur^rDZJV*!f_>U z*`@p2dWFo>Fd%1@fUu; zx|M8Qc#^ESCMK=|g+$>ozJYY`RZ5prc@P~)BZwThq>IeeQ)wVY>}$5hnC4!#3_z;}z;WgCleBDPvJz|=t4_lf$2BSnDR0^v=DQ})?10ii8 zcAdS8vdncCf7qs9-|pIhySJhZmLZskVHQCXd|$?u5Z6l$)bc6_W_BEAVwsG8B;gCX zEWZvTfH}B-IS#T=1T0y=&VaKpP|+do@}NV}*VfkFF4gkAKtoETLQgaj=iZCcELR}- z1LbK=%X7@i!3_bjy4puv`eO0F+&DB^8L$=nO+XSI>(_qtSIEOqBiF0-!nm)qM9r*_ z4(u=QHLxqu%UQj?hQ@iq@E!j$Kl+vH z#BC&~NM|AOVkXmf%Fz3Q%1w~ylC1Hlv3 zHId;&V(yuWN6)x+pW%0rgj7sIvNQ1ecbdwX-Yn9KDp>q9zwT~IHt9;H_>S|is!RSt7rij2Nwm+3}-Yu}kxazk~cUeoccXoCTY8UO>OR|2lmH@(PGQA$e z1$jdV3+S4}_8Hg6@y-1=AU-z; z7rj}Fi$Sg{rrLla-q@Ft>$m#azyokpE6k$GoP@mZ<;4cVJP8Sm+Zc^g#SN!HXfUD_ z!7pS)fj?j10FQi?hn(`gU>sOS5;6~Pnn<4&y9n#4yBy zKXpxd46=QE`w}jtb8C=27wprcY`y%;TDlUs+CBEb$wL63)9Eng4cJ>)S)EpAP`LJR z(;x3y)+7TLEEa@NqKYPB=i;)IoU5Ld5P!l+Oz^c@P)e#6!CvO_zs+CF*QEf?CY2Fx zxnYq$=z#XgDlkHUF{B=LI_Ui{uoGhiI@t2_TAw$3kl14GCx|w@+#6s@{0KS`mg${E zwRG5Fl{CD2`wgJ@e6pfQT6A$S6s0Ij3mJCEaiIn|f0F5KOXztZ!ESoFqGwWAONS#z z)s^rSvY9v?12oNEGRo3hoSlZ*l-2Y)-46I~Kd#eXcANcvjAPF36#>cB8 z@0Fjihk9f8sq%?H>{{Q|>1dl5R7Os(2OTgwJ1mt#mQGG&`MM7W&Y4o+IIjIUYEor5 zP98wNG^G(CoS%3?)4^vZKwg|+3On(y!`iy+KSZu#|9BgdQ-BqZi>kLb@%$h+U($)v zGX2`?!Lxv;dV)|1MSvT+<4lj3)RAi82!iXO#g1T3*1D8_*zk}y4=uZkH;U}*BQ0^3 zeG*b>q~u1Db&)g*;KeYtqN0L8kq%$)?JqY?Gv&gn@p*aSsI(1s9Y&ze%U~_Ew|yKK zpdZ1>)PX+>-s2F@AMXXDMrLttAAM;8G#}DQfsW=1 z;DmfhP3uDCZ2?Bm3PAS0x^h7&_nTq?^uh7^7z1zsz!qZfQk2SoLR|5+mJa+myk*no zV+ynvESuej9C+hHZje(XAK*qa>t^ynGaQ46s8`cn*lhvz0G9Xb->AT1m3bt*#>S1{Qv$wN_}r zhhtoI3I|o$yFj8pwK+>hR_fGz=q(GR2hJ3n6JW&RoQdWSuPsBL15#AXiE>~Cx)7dl zR`so7wIzbG>}zqqRi+ zR~NhiGB8dN2IeQg{F`D~w+R0!+{tlg^g?$MIs>D%)Ps^D?9~VyYVjJ~!Jq3ZgA%Y0 zyg>646V(6M&s>CkI`15P1aAZ@ADsgO1c1ok2}7d| zdOuWozD1F%q8<2M`bMqnueaqF3#xdq0ojDqm0|CYjQ8@1Y$eAFih<0zeR(KyVpJ8N zKfw0Ml70kz7rFjfo0F5vG*?AsX znK-2f{Njy4NjZ>8Lwpc=+kr{(-O&fSYHmT;47|6EYw($rHB}3Lu)%wpG0VjI`XKRU z_D_Qdhul?9f@UNn#=X?X&}IdL)~VV2)y%nQ^(1PRww-2C( zhrFZahjbzRV}K;#-ae0eLaDa}QvfreRYIFnHKljzZjjvcA^M@iI@16ip4Uj7! z)_*o-0gU&8C<`1cB_8fRqzS^I9$bELamP0Q!ZwG>z^{|;4}IwwD5c9{Z*z2YzAn`c zEMV72*MXG!iDyc}9rNveZ zED%homHik@Picj}0ZSCLQaspm?gpcp+8excut_(20Bi zO_V?^%oD`eR#AXeP0qU)#O4vWbw6+mXI15Ic!c>k z)9CA)`(44i^#dCAQW;-2SwW=h8&mbdrmSl)j%*Ms-Ori8+yiIYKOPa7%-u; z)8-$7qCtS~n1qb7FR9iTk(C9FTK@AP=lGJ9wZwJ~7HqLjiy2RxY@rushTALA^xe6V z5N_ZUGH@=_m?g?@rI`y_0pA@jLt38Pg~;~uBuL5#%MFphZ}T>5%Z&=p>mp|)d2wsJ zgo{qQ2*CXa(AHaaVS5SM1?K_+65&8jif@Irp=!mw4iM9L6X_9F_GUfZ5pRbWEO>H( z9*~@R`pVD>2WJ=z9Co`RqpK#7^AAr>fMv{?33wKWzLkA=q7FYfKxt5AMtFrcP}*ZH z0fz}qj_`H_a3)Ds5WQ@8%SWY7BMAv)0it7~7W`Od({J&3U7c%O1C3pSCn8%2TtCCz%LoXyZf(=PZpAf)@_bS*(+TgIuvx+rBw35~dx{v#VNVL`JH>vU`7%LMvixi*ve&BU%(s(~Z<20KsbCj z^@Q&*!|)3*0ZSHMjAKiYg=lVXD1Ss*|)8#msnP6 z`Kb7r8{@T(y~)v2myVB1w%u0qwvmjLZDgzxoKokSg0)q}1G?v63?gSv1_!@Lb$~W- zWB@Z6QROWXrq8*_Zxj~xYWSFT*-JwF&NNUNiB>*+=kp_R?KnuGtu8BK=d;3(BT;l+ zHfcrj_TfMPL-3zyn?Ucoon)-vN=JYe+#Ou3u7LR+oZ&>wqMA5pD9xSL18jy8f?;Sp z+HwPClHdUx>zHbfmepg*0~J1`9rIi-Yz@>ta$7-ZD~}Ry#)gjg+8lhREnF?)GKy_i z;N_K#HYkY%jlIx7qn-p5Qxw!9j8DOE)?<*YM@O8X8(Admn?J|%KNbz_>0)l-_@b6< zpjena)8ER0`}dU@{c3iwY?`zrE$Qb00n;DKCv?4^Cb{hCEGb{Cy z?OgW>3lwZu{n+*3T%d@xY3J2us=v>utdO&0%~YL_BKYPHj3b(FcbH!j#FTTUtgU4d z9EHtPzVo12?? z4|TH-;$X|1VxfMX)@|22EKvaw?0vCaTaNMerx=8U_OVHMRq&TtWV>;6+jI+M;5K4` zy6^7($adV0Yh$Q+5MR4!OK@)_kRW^WxdQqUpO2iq7;crIDi(qVa_xWa1$mm&0ueL)fafVfE*PvjpA6u*+9W>0b4|ZU;5H*QOfggn-Anyggm#jo zHHLBq0Nt|E`p&nLE4VSijs3s=12cn!)uMf=qeEJwHex8&85jJ{9@v!=xw$Z|g@lwm zu#JloZ59UEcrdPZb-f%KG0?_c;%84{!KZiVf3ucpiatk9sF4r-N;Lppq0{Kur;6D0ZgB2s zfcSyZNmd^9q#FNc#^^iiH-dVQXyWq(QXGAvh~3Oup-qG zIl;37W42YynL1h-EKHChMS8B42Umrul)(~%2^Pat^Bvm`jK@_iPFfwthjL7Ro4Tyd zXcDDS8>YhiDtp%>Y(osD@$`EzWa>>6!E1*xS@87w*+d)O)|?{@oqq@rn=X}E9<RL+jM>Vx*BW{?fqZ(~ zeD4CZKL6{n`LE|!$zF*XCSg*tnjwL zPas64^u#cPM8U?E0fZkWLhpZVu;fL&FWdj-#eTRF6125_v@2?}W|WEE`6#qHefVc= z-s0e{InBTWEi(Ns53>d|dR?wexgG`jKYuo@3-cgemG3B6=-FM4M13aIY*URQcu+;& zTe>fNpdMu{fBFIADFco*bSUh@z_ji_PNyx0--d22XL1Kaj<5<1d^3ge+*uDZ8{e1_ z9wlpc@7y&HK2qP0blcr2R5(0($YQ?vJoCU?T{^MLs(#f^D9tD2B}S$brY!G+=>$v( z#@wdO`@N3OoI>HwAh{co3OBaWy%%pJl6NOAs&6k}wzBW&!}0XNecPoF3ei7Y$9arL z2NOIE%Zue90ix*&2FzF1q`9Uux-bt| z`$=CKBLftwNY7E&{7u@f-w%`=r?;ssf2j!5O;FX)Ab)n_OJ71&a zH@>~w4CgvPWbb~la}{zX0Ez^Uw0t&kw#39X-5M-{b-4&j+^iXSN0YghNE!@ejIf60 zf@+;qtucZ@59mO_D96zMW2 z$)b%WtSl$k*E*6M53`ou_t;i_vaNEy=+SlS{Ardb0{l=F2p;?>i_f_vWPdmlH+WPq zHahZvdP*W-dFXJA`CV052N|n$qXD*8diul4;na#{Kmc3oZbs{4?ZCOyqRj^=wRqRc zt^Lg^qRzT4-azm9IngQRqM=G57_fqo1iqU|$lf~Xv>uz+gNt{kzn*ivl|&5u8R80@ zaPXUUJvgaIVWtIUc%j)bqPH|;^2_d27y{hu0*5{})l*@i&Qg?`gRcZWUpDZUHu>eZ z(~{WSd=1&{UHDEQ7C;L>WK3QEV=TkWK4|v{?8;u{&(&kw?&s8Q7xEe9-?MrebWyW` z8yM?D7|NC7M0*ryzXjK=f4%SEY`O6)$%`4(V6~{%3#0X2IX(Tz;$m_%UDkZgq-)-g zBlxwH#l=dDA9oFwlbgM4vme;<2~{0uzn!&i&9qZ46NrU}EetbALKfC0^b^j!jT+0g zYn5&^V??cEgktBKYGo4U`53C`o8q%_12#kQ5JY9-r8&elBR%9Vd!|3;hM)b=ziVF+d% zta|pES}n>)!d)id1dWYXvc3NPT&I41G$ps+cqu?6%Q=%fcJ9E5pKE(8C_C`SoQx_< z)Vh`5Kk@9zF2j+Gpq01Nc_r@?Xm6F+gRDsa&r(y)Z&`SSSMv4K9#lPCz zS!2!qW`k<-X03Rt{#2X4Khtk_%z$)caj9;)6GkmoJK5Y|JaRT;`T#d`5oir3jWIvQ zhQurEgezPJ*%(enyIQ5NU$x#wa!bvxWg}m7)+>9T9lCI=M@%dm6MI)#sd=>q2i_ztnye;W*ucNGNKBO2VN3Ose)E21NplhMqza6yDkYH3w+T{T@6J3|M zp8m(Jt*wIx*I>9NeVzU*jO+rdW{ks);|I6mrhj^Sdmm=Pv@W!Cgkt7wlimOacc02%$)aYwu*ugF%Y+ zV29yk(-AN};IZMp4y0g$0}yB48G7D~D0frlM9ynUc>|#?6VS6?WGjf3Nx*$uZgTLL z(tE+QB!s359WhwnS;q;#)*pf~A`t7D-{$iSQ{f8EP(otjyZQ@YSi%L^=MTHVU=%pF zxOkTZCq!9B4I547Ll818dswsbw@W(pU+Ze5D2yv(E@kghfj~Z*6Fnj{-ya`YUDOU? zMXaiYY^d%0OKW|i9kMsLQ=h$m1v)S+t%nn>*N(rR?GkT+FQ3sq-q2p7Y+a??`D>>T zw>=d=+q&P_8s}K!kKr@!I;=tuqof&43i_&4`)#v5DI*EN^o1Xu^*;_O{2!>S{v5&C zKw{VP2Cjpmntuq#Kt@J3Iyo8SYV9O7C%%8|E~8R->6*gNzCIf8pE|@|lJSD=hLwf! z!6YQGnbGO#E~s74dTn(?v;(HTsA6ri7bcdZ;6wydPSw`o#^T{4`AD7x_18 z)|Ii}ZN=Cn4&KQDb>LQ~6twtV>)<2r8XGAs#xs_>llfr}C}@EJs$iFvmmyDKoE`WD zFq2R*77xP9av%aYir^iVjq70{vBvt3e|P0IRL7~JC^`?M>)274^!Nm4G@xL z*j)TH^Xx1-8gdC@E7hjAKhKw~Y~Al=;BsHsu+S%jUqfI1aW%zHQec%1>EJLal^Q4~ zApspNS)f@q(;iL+KMx2900>-v_7PHm_Dj}$FIQJGUlNSztv5Zqq|;OB4pDQzLPnvl zs|#j)7w<2_NMrhWI1k(i2`KWF?O7QbV#S&78)t4wn=fJD9T>0|7am-_=<)3jba}0- zu8eMN_=a$>eJjhoEAq6}{LJch>7aSYcXhGV0zUH*n=Oi^IP(Ku`GZ+n44Ugm42LM2 z~tw4xCO6gAVOX1;#PuI0)WD{ z{=3*37O=f+X=g`felW)@{^FLaoO969?T_rjAd%tL`|{ahA% zq%fKDwAU5~I3lbreB@!wW_DXE$$1j_x(@Orm-j!&8E=TFe+!(vRX&1-A?0$1B;?|E z!d-Y10B}dEFsE4X+v3I`hYAW_Tll%Y%VumJZ0fe0fSGCDo(hK!`KAvfPw?4^+WGnZ zm+?#>UAPWr$X4atj@ID?GGGw9F-y+hFJ|=iNyE0Rs7Q$fVkO+BWGO4Fq;~;92J9oC z;6TNj-UbtH{_3r8ZV2ym^9M|%wmCsi5ZC3XqS3~apWIEm@+Mu;l|qQ;iCY(9Jsn>M zJ|Nu1-K)XUgMcF*MB9M`#1D+iB)#74uC&Yh!Y_@INq{|S1tACv2ETl~?{W0#p{Vm-4=zAyv0rb_3>+NvL9Oi#wm~}K95#b zr2EakckK$RG-u-M{*fFp!Ag0C?CvP^iQ#+|XsSYG*@WS>5>}c*%0T{P3SvbWAG1Et zr_dSzUD~x4__@c&l<^b^An2z`Ia)eMu1Myrtxj)O8 zf26H90sU7z!-Q_9A*{>F0r=s(c>keE~kA$_Me9cu) zg9)Jx&?!`;;k)1GoqGkDcgz#pE%q8gK87wjeeHJmjmqdVVT2AbZp3csfyIPW*vv<} z$efAo&yz83f!Eu(0)OrL7$48yJ$-PX#_+wo_Lh|^P=WrVzx^`}B2)fYVZ`91{YvvT zC+9W)2pm46vE{8ah(abEq7~7FtY(?MDSIuERk?bLjq|FtQKtz)R)?yHI{HI?&QWTb zp9$*=I2>!e)_>KjV&m^hl`7io@*kgJo9yOE!}tDMvV*~*hw}wrZKngIoUa8;@QaF) z6M~M1=@@InmS>oNA&ker1}MZ(!z+c*9xr#R`-MU?QH&^11-qogi1m1ael51_z^QDL zcZbE<{OSeR-vCx7BbjxoKy3?$7p@s&gnnkSXVyE6c*un=_UnqIwXqwwFvVFY@2o{PXjdUAZxTd4Q)?$KRH$!+JaOjBEU{ALmLr z6MaTjCT`>x2phrFy;(Wgw0Yo+M&TgLnG2*94t@j%ooeH$;zV&xI)3M`s9h=f!M9fa z8QRvZgOuaKezhIuR?khH3}{=eY_I*!aLXNYp5r>2<$70FM`qDr22*V_>)FS0^8cPC zLX!r3gkI)biK=`}>wQ<(`S0fILU$ciHvw(Q zj&d)2K)$FAgE?*}3<{2wH0aa0m8}idVBH@Yc{u= z%zN2wb>0(V0`&b&nOimXH}JGFY!fi+_*NBtlAUirivUt#e`V~=PiM!Qz|C*WzTJe$ zxAmeA@Kz z<1k({SzA@qG4|h{VcnJeaeK)QsPaGo@^xRBht$Tcp}PLQrM<#`tUy_hgY?UR!(?0y zto`fI4Am(g$q^6?oK`FM?Ud{kPOsS**o67`>m@a`BR+m#(!Sp`R`_!8EirCKdiqHg z+vMIp(MgXJE()7+DAy)Od4FG zF~)t|?f1_-npezg2)D@g3>DO1?rb{@BfmukQXs0OjN+Bbx$!qAG(xc5GQi@l-sEJeM)L;kt3nNZ?FrLb z{@0vOjXuZMrWu%4PntbY{Nre-tM4+FFW7kQHn&W~(+{@J{14buWwtgfvMm2T3Ax2E zk-QoxqScvY-hb)R%B7WkxoPPXcx!W{|3y+=bX1gMU%7tbYmc$EworL*^+(Gc9br>> zHeX1RZO&FzRr#-?F-lMTE%-=C8BaTIS9pAnsIk*LsAjV^G?=!)G-XG;p=>{CXU;p`B^Dozc zS8A@LJPR5f(7W3?3>FglvVALZa@M_Lg_fIz3L3puuC7eG2g5J>JxabBoUfSswi=Em z1m62+h4T%eTXSnm=uLh7C-L!?{aM#!Jb&JZKP7kVOJCNtxQRM9%!kLP>6B*XKE}Ow zpCycnj`sLFDsEEmi3)kcp%BatGt)ony<|d;^3|?u#FmzD)9AW@Z)_7l(PM4McHEPC?Z9OfBq?CK`?2+kGDNZJLOPh&)mW z=;n>{$^K@v-BW2&%SrSYc;6t9)8dBt!?4wDOTSKe>b($gthrhi{5wU%WVr z7*geDc)Xx&wDgra4FmDkMaKl#~>P+(^mD=&49~BEDXvyO?syM1+~}(e*o5 z&gOA3q6W+b9o}aUNB0t9R40nfRh7TN_L7s68{S5AVFqf@!y4rWmUbYHV5TH@fMsi$ zqrKD^^G2^Bn;#g*>^7O0LTl*Qn40Odf)xkw#%ktA8Wi6wQBG`GU_{L*E8Jg zZlDueh2LGYKIAqqFt{zmR8d_WaRXWTr#I8v`bOr<&%cV;vNei|WJ^s%uo5JQ4NitX zsL_}Y19NvCnIG0X=}-QRe&cG077YW21ynLBPl(2vO-&;vKnrI>n2Gbz*{H)Wa+BIu0S%W;$1v&NI=`XIT z6NB&SJ+7(_+&uNtfo)T&oVg9T&z2bdlj~1nN*~&ua(v!DQnH(C!_&G`buYZk9OGlv zRQt)*yZpJSTibdEm6aCq%rlk{}Igu$CxZiVJ%#nCkd5WUYY6t=U|h z`aL9(!XcmgKf2ZNo(^5nG^G0KZeW4UXT57RR$VkfXE$S6#LI3r=w>pAAFh(F7KRwS ztNtPLRrc`rpX()q-%E_7(Jb$uTT+eM3v@fPbqdN>b=DdZ{peeh+KW%|s-cW`)}qc^ z3p64Tv7IO~uT5Q&GV0&qAR*7l+{31cRq2#qd%tjPPPjs4>TfXEFFkG@YX0IZ^k2C2 zwQDfQnM)qc*H4_9?d=UO1V{KCIJwIZOPoEkdq7BLlo3-4KsokzTrE)P2d&P3yC&Wg2FI*uZP9 zwwU8D;Xc}Ibh3qyk59(ukDm6HaKv?Py1-Oz!w>&F?edw}6aKs<8VYQ^-~aF9^O}K5 z)(TGewi{SNw~((gGrE+7g$jr*)aAgHr?rdWWv@>KdMnTTS^AB>13@@Z?sS9LlGUDI zNug<+BKYcKIzrAwwGrpaeP!QLXQq%Qfp-djBPW+KZXloDK>7!{viV8mn|NL^87Wx& zsEk_S`o8+-(H7^9}6SL<={6WS`2n4AGluc48F?8VGF8w|R8a{FKRFCF^VUAJl<-#j`W6P86GLy*01f zb|l?}AJ-BJ-Ip}#)hs#RA#JWbSUi}2>(;IBx3rv8&CR*M{sw0uP@bz*{{f=dGw5K) zqo-JSOKsjVWR&vakp)Y^W!|(Nhl>|4-Y6Vwh}|@@lL~pifbO~@nsd8S{;Z3=1-<#U zE%()%e(VspEzZ%M(l-4hx^3k@5Uuu+r)T0R$GN7;b&)Nist+F})0q8#F3 zn2~igFw9&x+>G}4M#Jhh#aZ9Ml3#>xE2VXnu3zAjyEn0ZX1%;kxO|zqF{4v8~qLpu7ati+-CnkI;=W^l6qbQq1DyEjh~j zjbvufc&M$!kheM0y=Ul8cXD)1SzNLN6}-e*<+Gsi&IW0Ukk5FtilUcmzLZw6!G`*(^3dST2x4AN>Z|DMA1FCl@k?pA`bsl1>x@h`{O}H7+xO5 zT3O)s88udUL)vXBqQE0T4!@&Y{B*2pM!03rVjP&`pFOPq8p(pFWl>1p>i^!a4^^~0000^TufL20QhtZ0DNwR{tP}dm?n7*euHoj6jy?Vh6ZlQ zZh}7|I*O<{D%u!3y6D*(0TfN0937494g99R0RRL5abW=^*VWTCCoR+y?5~$D#>wZj zzmI+?prRsv7f^zfM{U=Pc0E0}XvVu+*7x-dh$KQUBntDTARuh5k?dO>e=`t3!Z=BJ z^yK$E=cQ{$xfp-n&vXfLt1+3%;`Mq~QdMpCdb!uH4IzMzBR~WI{^;Td=|OLy!UXA2 zQpz$hF7!sa`kgIa~YsxmVx#>)Lfh9nXJ^mIxRrW4NsVHZ|&x3e5Rt zZ}-F!&`KwXE>&G$Uqch}W&7~%8w==dwa63m`w&fsf1<@NGCp5jUo3J8b`F}o(NKzU zB;A*HmoEh5D}=ON_o`magjPRI+ixDosjAY`P<6SomQ__%MNM@(vXD?%620L{YYFQBm2ySKdz%Xu^oH5{h6->?Sjt{7PXF z=pn`c#9q`yR0dPyOGOGwN;eO;(z3EkS01|P;);U#x$^d~x@!z+NcZzim!MKLkLN~{ zE$~kSlgR0gmGa3g@yTWs$bbf82UcXy}6p!8mqU3GT2w1h+`u;ovkoV~bBMV85x zLe&{*Ct!DdCK{+OwK6{`2-l1I%7O|LC|EjW0+T3MDA(l(Gwtw|_EXdjG@+FIhFW-7 zNL>ayn$uHjAW^^^T%=N=p`+D(XZn<@K9&lw>I@FY{m{@#M_l>~Ka$7B3C$ zm87w;5rbZL>&o@m+#LMc+e1sP`n9mQ=>3i=78hXql{VC`tF{T2NWy_hp&kY@q?d{5 zl>s>mbUF-AK6NU{Kx9Ly1I*({_7oJP_kM2+2Q@XtCtBw+9|{owuXI z!?m=$G%+z*x78UJyg0HlF3b>a5t}?dx4-@vE~Eb%m9EdMkc#w((F|6S(gsOkdrK}B z3=I?|qJ%w9@^Yn`$>k9Kol+Xzn>Ay(z|(>GPrw5ovS?5yzlfmtGP+FH4cE{{CNgKK zhJBNoSqA;gJ-Rrli^D^Q77O@(jh}(w@dvRtL5iDOarXL=q*s_!wkn8M0Gcp>GOgv# zd?Mf+;qfXBG*y+8GrhEQAW8mt3tj^=%$QnoqTwa5psf&1v+2lYWObD4Qz#-gV%W^AV1Lw@MC1Jw0swwWULUGsCtCgf4EG8AJQ|SR_&*~;0PO-ceYRi!-$;Oe4+s1k z9`NtNqfk%15%~C@3IGBS_{N`Lg9CVE`~Ba|ISnkXO|W3I#Id-z_)nYZ*$`o(e>a-? zdXL#+bg%9J-K9*wJ;9MBw$3Tq^tWOM1R$t5*=IQApIa0Qqi5r-v|V&bF`g;`{%jC~ zzFE)CeDQBz#x`eEw={U66KdWlf0AWJ>*}!G7kF9{WfqyT*dGnWWvQ`QK~@TX4_Ae6 zPJUTM`)g_)ukyZ@DeapH1Gv1A=U*YDZEq}ixD;D6I}vJfVO7OI>u!1QV^Mshzp0Sq zY1t0hQuh&Utd=%$+o9_k+-MoYyw%Hiy+ zP={fvqvCR2Yg@7S-TQSc!^5WA$=VvhLOWBZy&k&X2e-At$KyK+N;n&@NtRgR?b!() zZp!AF{?h39@baRA#w9ghS$i|(@6oIAg2+w{U?Z+KN$}5-=cmxrPGDMkibm5(GYgaC zwCTOy*Rj>qNI09rz3=f!&CFPKN%2?CG^8)Daqp9rQjw9;l^HKp?TX@g*D-(H*FM~& z=Vdonb@%DY@j?*=w^fTx?oSSX8(CYa_R&4lZ|pN{P!%KUit-!L+q$5Jo`)ov8a95{J4C&7OFQGM|51q{+;~Y=sEv) zcLrMi;zqR)^hg~LRs$*R@pPelIWdS)l1*f3v^m|&)6PUBm@^r#kOUW}Fj`rd9;>aW z=At&ZT4x=2hRScyo0WVKRB5D%a9Hfb%n~L^6c9sj1bTv*63}S~!t36gTx?a9UL5Kk zAD4>cZnghYc`Z8m#a5bnLtXTO$1OFhVd?JaLnWI!iI0Kgp!LXGLPBD6hnw4zrO}K0 zey)$-L}a~@Bo>3m$uQLN1l1ROFa@Qnm5C&jt4i1->T0(G_}zWRV!}ynzI{8dCvZJy?hl2sFeP!)^S3l zGD+A@id($Xs_Xk^R9?ltI&N~=wb6=#5*%P!iH~K*SH;Go*}r0`ezs{2%}p>Fe#qMf zee#7%N#ku>9eSDc--WX4i7xm?Lb-4(c-&?1h1_6AjvTYu2e#yG14z~=f4wV0j3?NV zjGfPnAvyB{dLFJr8C|p@i+&}cCL@Q4KV7;E4vs(1V_=}6-&Dyqbz<$+zWDc^ zdZPV~7;>(06qMmrV4wpEs9EPkW(ZL*yOt<&(o`ahLoB^gy&Eb8MpLx4Aw-A(U64bl zK6iwH3hi9z3*fcF)`YwLusQ_RgU!l!?dwDA?`5EA0fV~KS+2)<^#uWtqQwD03Kz}N znc=jqxao(wz2%=i^^pT?Bf6?VLn;lK@D9dew8B=AORRbCv(Ov*#%$r4=S;g8k&>CU zpp-PH?k``TC#b^K*sOO;;EL?1X>EVRLdx^MVbe7S%?pOmgr~4Oa(8iU3;wD7JlM@M zV?Hqil|MP5c{^`%u}~E!*(Gc}O|DungA|-QAjoI~18o>U955W#!LBT&ioV`30k-Sh z>Mgcg#az)!?cZ)Z96qpk^$zYZ1{OTMoy3jpuTPGPLdkY8r*%o~`|jJnIFS$q8l@sA zhJVY;3y?fsU9lJ;RJys=GOUxkHde>hCVV)$VM2~2DP4ApksYXA2*yu>Mj|?q&>`#I z?&Nohm~r@Be0!Pr)%p+t^Y_#GOvtco>qnblKnzVEXz-^x1tI}SwaxIbgcJ=ralrAc zpZ^XdG@Ajw zR<(tA|5SUE-jq=Lr_RVNba6lr!tF@xC#|`Q?C)Q{D$tMLG_n6aN#S^&;CwGQ_CGJ{ z*m*_KTrH%zHZ80+`8{KI8pQ!GV8yCGV>)x5h1=%t3cn(9f6W{VnUMkPcax!H&XlTr z{g5V~=UsxLU+iXDn2?fP>S=mu$QhCju4iPO`kPgqzfA-6jMIr9D|~f!=bs@3J3&*? zR!NWFVH8vk8)wFD^){VmrE|vR=7yl9JzrQ&ibfbKVc0n*V z4)Y!Ve8awy&a5s#}VFW<4{fP#YBAOMvrmF4B-MMS`| z&;bCiT9`o#^PVb{9kS7_eWqX+{>sJ29M6B^M-?#$PEhD)9X`fgde@l1F8%Yr9OM5& z0>FP!$A6l#_&-Y*#igc#vzw7U`&@x;H0(%lT4QW#3N8H!@W{E9m6|G^D+gLz%Vq7Z zEGQ^gs@BE9!V*vf>nGUqFTJVrL9hZgb=vLx($Ueeva(WERvuHMG%_+GB_#!aTW zkqf{_t|gv7z&!+yiB%h9pT|?1Y90}nQ@DDC3;4=IHG+>6K zwOd+OXK!y0Lj@}ooTd1%M*s4BnRnSCigU{qM|OV2Q+qSvHotBU(G{deGYA!M+__}#%u3<@#_u2>gf$0uBzMy zytGhr!%mqSgf$^H9XZt?N&1lvB7D?sw9w)Z2q5S^^`niuDpr9kc? z{iB(_C@6OD|846%s)gz1_=-C5ysIhaJ0k2;yG(3 zf9j;VRaY*~!zNu>YguUKWeypnh2c8l=^^nc_-5a3If(F{3R4jJ%HUok&02b#mQrHf z+}o@7(rT*zB3t;7BT~)d$jn)9D<5uf>7b%jDp)YZOi% zvfFN00gkR4@nc@b$7Pko#6+^shYv*2x(hH{K`sGro!{bbPU4l*#!(ApzWK6UNVCyI zI{V&2^L~>R^UE*kzAYN#CjY+i<`2|P4j%8*ZrR!B2wP{%4VxhpB*E8+kUb%;6-^Db zRVP?APqNBiOs{oyiq&YM?2*UE)1%{gkq;X~*~&}Z>wonoX$b|PV-sa%#&0fuTUq`F zjk@)3IWl@y10L&pGkx56G{N>lN1)Gs7q__aifgV(H?bl+^Xp1Zx> zq!O?3T7?uGCg+ip_m=qTJt!*fxU_d_aq1atdmIRm(3{Vcz_sE5ZMwvK+)o~1@P%Oh zXT`Lu4&GnW($d=6Ml-16$C91#TshKz)@u%zmJ5CIjDPit;OPFGiUs^#pGVWLO5Pl{4((0H04A4r(YK_ZC8-lxy<`uRsX zE-?mKuxOG?HrGh(FA-E$U@Y_V7E=XN_JsM1PmRK>GS9M2nH0>$R!M$ESSXA(?`bF2BAJd;RCktll?{3<+d#?muG+ zb5~7mYF?&viLI+lM#WJ`M5|5v82%05jmv{~ao|b%r7$`gw?kuPbloouv3KR&pq&rM z|KchWjnui`EgW3W>jC6n={}O^0>m!R%f6wcEfkDNcDN<#q`(yr|wSC4r$~fqKUbA!af?C0jBD%#j-I^S&CX%&9OHT`BS zPfjV;Zf|+O(yCkq8&gnh!K=hYy+2F{0SNhc$g;AW0wtXo{~SRqNFp%WaI}%_=5>(u zqJ=~>nhj;eO@4f~Auy|VFod_}lT9s{7x#$!a$eWw(dhz}GoKsnv6ng_AUi57rj?nT zqzvx^1L&E0=o=KJM0eP+IA8-NR#%{=!C{|MeQZ@5M!vC&JlVLvTp-1LFlVBTf&JLL z@%{igGye|?WD7T&)pk?h%N6M4w*Y+rqF`I+lIWez$34aznfGKI#j-TKcoyjJi=B~C zX3<6n-tqF#L3m6>>{M7iA9a`R4GezOkzoruVSwR$B=E_ahh<3IK0i8RE~d+HS|FL1 z7gO3svtSiId&Ob)*qY74Nffu0qx)=J2#1|64LHHp9VFO%)X89KrivC20Ig>^HJRu0 z%(*sJuF`PWslQ<)7y!-kR(0n%zUa2E6DJoc1M6>2DVqUoJYy=A6we?fX8LG~>4O+S7RE0v?s; z7Z=}m$9@aH$9{UInG;w7S^}BZp+B^f3hrNp4T`)U2nJ{S98QhA_oTJr-A(5>2Xgbd zsopntNC2A%SV^()Ced8+%*UFtcWakpE*i*RvO7~VIyVfvHe}Zp)Nwyg-K?BDxO^B9 zL$q^&17h8odjA8AclX^+Hu6HN_i9Bmp4ZQSKUv(5DjMtcKDpHY;^&`4v0^mV^0F4b zV6?3lm%xueL#;)~*Amdh&X@fG#%+hT=%>0d(8JO2@i&N6Y01c-n&<)e$E%Ge)yU_Y zFLq8&fxiHoQ%HDt@6tuY$e~>VEhvz_h+$DtL2%#*UAI!R*?PlVVS@~`0Y>ZnCcx)x zL_|eh&Q|Zvcx@(lUlU12mY0`pICN{(VEgvK1qx!82Sb~Y%^~(|jQg&NDgS@#*GZ>t;j*eE3* zg}AVKy?M^Wt|yAlF3G`GA0}k&Bp~s)*Y$7r7D4TDB*^0LOp0+Aj$GQ{oI+kcRxo#y zLq|?dPD$x@Vz%({{>p<($UXfv=?huNDK$CMX;53ePw^b4p84|8b(K)Y0%HJ!d-4%Z zqm!eL+zB;D6tG2NRz--PuWPLyvr!mSqmVJqFVgLclrbIG86^zG{gYV>OyRjJz> znZ1q;xr3J#l=R%F$3P@9GNF?5yy}9J!>>19Q9nro7AthpZ*?+JH#(lo^o9kkx$-9~ zjGqI9ZRqGP4swR3bIj75f3%m^RCCcycZBju+dhL2Z zWY-BEKFJJcPlbm?vbHqGw5YxwT!b<(Fga+fs=SeJbZ0}!eO$h3=8?2{RQ2gS9lz-8 zo|Tp5sEtiMKyGbJvEE&y{)nZmDe>UeV5+QeipVQIeJ>zWGnfmTX<=an{!_Ys>m6E6 z>lILx1E&^~hWDk5x*82}Rt0jQi-&gzm{eJoBg}l*LggEcSmti;YLCGz4Hdsu_L4Cz zB~b5B8vdeNEgw94QF&}=X}V~mo0NjFo4@KN3h#?ZBynzux3AxyH!GJ9q&@ zwB9nA2bJ(D+=^Ek?tes0LTTcg{AV+i+ZmYU7N5BEZ<0chMhhMzdmUuaPe@wW`DUCK zI$nBqGo5agj>pAH58IEsGQS+1+Oj$~>hi~U#y{J9LqaASZ=BC`mHvbHv2E%+r7Vi! z3Or_3X^83-J~H2S<(1$2+(B z8$-IWY&67zAqAThq~$!M<*(w-Pw}VM#VdQV4pi&!9mC}$NGszgCALK(Q$0BW5uau5 z_XI!_HwXo+51X_g+u<&V9ceXxKON&v?}pOyipQsWMUE# zVG3*?UK&15mO3+ul+Q;Wuvq9t-RC;q;^&p!p;izk+BEUc+JlXjFZ3{83EKT`P8D-= z1ClamtPhFBt5Up;YuRR8q)fcj#Kyi5jcnFt8$E{25R@XI?RgYFtedxeEekS+{_1Gl zQCz2Y(%^IlJGGUdKUlFwBt$TNQrYVVGAJba(048}5>V zdPXB-IA4cW$71(XOW><06wzcFP}al$>;}nW=ZjAjm!! z4}w@6mbMSR6|9++LJ+%45~C0l!pfTj&9{|$?z|r^6Ulf zbx=VCc1-tEID4rsT)VO0n$>Xc@FsUrU(iZ7uX3Ti%?;CO#fF;>Yvk@BLAr zIw|OOM>~r?%ZnrZ4L94JT_q=)(=UycFhOa3P2m!ZoCp8z61lHvU< zdJ2=7!ge%iC_O4?olM8D4OH)QmtPs!*w-MdL4DaKn%;!*uk`69K6{se*Y{bthknoQ z|H}m!y#RTWlG)Si3_GXuE>IrnJ7Q5vMTIJ!9_xvSgy=8l217`q3tf|~txa&ceTl=0 z^E?p;nm8@0Dk~Ip@i?%wYH#M9TVjz|O#67+T&prFC@9$D+0p@vd7IAtm$2E=RO|g;55!|(Cn~K)ue-URK|TzJBikg3c-jOIEWU; ziqHjZ2;=3~@sPnAZoq_7l5glDamwotA2Dr+g!A5^mBPTHI5d4OYqh(jak})oYNFz( zTD0B{S(GKBGeVjeFKjI&52wrQFk&+k_c8ba2I}4D)3*{(9rwXuYybtBzcGBh(qL>w zl`OtVLSpQOR{HNzK1nvX1|teesv38=2Rd#XPuV|+S7bCKwRa(Z_wivnzhznBHz$2O z{B^TRYwZzd#D7%fC;kGf$b!%1L-HciA6Ykbs2i>;9AM;_##jA4Jgh`&sT;zhL~KQw zu}yX}p$QvRSkLkHWOR6B7+r|Ocf)MF)2_v5GNoOPLYO4fAO%)r6hn}N>`72iDu!cS zsv&-FL{zn!+nu@|Isf-UYpXuL83JPRGaMQQMpDUfP2w@R)Xa=Qd`2EJsjlqMx8iej zcyhW9`}BEWx`XAwK)TU=sf#%mtxJMP2^p>9+p(8?sg|E05-J}?qXma!S$dk8L{#>6 zZ%5v0N-Epx4QZ#60PU7CsqmryIg$L2_5+`E8S;+O0ZKJD<3i9py}CQyT-chNLUixq z+&(#ma*UX~gwU2FS?Bw-%)+eR!aDt4c=&brF<#|S332I$aM*E)6*cw9gDPZbSa^$+ zg>!zd7bJam4%LZY_4>@SQ)ND;a~VlY-Fz!c`yS_)fso4bNOoA6ljE`kRCE-v?}QnJ z6Xvd&5(D4-OzD18LhTR2S(TkK=2hEjiGj>b{HGP8wMB84hGt%d(BJc=cbZ2gqThiU zO)KY9?W{SbC#JFN5@TWoGp9&p-eV!07iVJjG_=_FdbT^TRue%s1c?%akB|{#e{3N7 zYVaKe?i}>rtXjf_1!4P+A@zR{`Uw*;Qj&@L5qyh74HNStK@wDg8N@(T@Hl@>4}aY^ z9B;uxvn&q!ZeY@c-76|~ZK!{3MWK|Ov>0>RtUD6)T3}k2iWX`^B`ypuuxzt)x}_M? zqX(`G^qK382Zod#;0CpqTO{8xX*v+{P_YAz9KU`caqrOET&BnlKR|H$EjK{F*xKN+ zToQ-_4tWL??z9u|POD#Q7s%aAil3}^Jy>5ama=y3ShJ z%s+({v1P`mlM6d51t20H7#)mRn3YQKLn4cO8GuyyizL|Fks&AoB^1>=Z#dd6EfbYi zu=dE@`}&aeS0R4yMAk^p7 zO)xOX!`>XXQ2QQp{WSGwsK&)4|Ju3_V)wJ4{$OgB+tGV-wsE}KJV=-KT=)4J7(c;( z%}Njk69#P6e~u89Lfl5NA>swYO|D)#%pehQB~ENq%TEGSc0au5Q)Q= zam$=`M<*ZELnb6xpmy{eOP(i_hldg)}w-^=2rYY09o zbAbVjPqkbZSy^E!2`BJEhkDY*E#^1CU>bWltj*q}ExN|3o5(%q-xKUr_mTPWd@AAl_zl(&Bh^5~51)1q+b#qn; z2ZYp#dZ=WhJ|UcxEstZ$%x+n!f|aC@U9H{vG02=P+DT>nE=7dpPTqJxmEi(sa* zwsudDe14DBy!%$K%uy^BoBltXkf&;%kuKmex+f^Jd; z$HM54=*RwKrJWWd5mh$s^8*tG*Pc(o>gsAsOUvWqV*pfWXz0WFTD!}|`rFF`K8u)y z#Pi!As2f!P@v|==*3ezR$PBH!PKM&HI8Q}QO^5uBqXcB}{_*1?!t88%vURK=T}Ft9 zm%Zz$6XSFL)HBK-~JzM{YX%K@$ZLhcM~ zr?dR$zI(XEK`?0I;fTyTWqo#1>Pslhcyv^lkYs(jRTWA|0JAigS|#N~vwDcFYPWj+vR|$xWJ#w02g7#%oy29HM{Pg0diD z^C)GT3zfURoZ;QK7@VHIz#Uh!HLq{R4zgX-``Y)}=>DNTr@U-7V(kOojnJrHXT{5E znGDE{a*7o;x>_~Y>i{j4ztlARft7`CHKm{|zvP0|OfSyFKBNyPJx; zM{Ig+?mrnwnYJ%gjB&cF563bqFU?)EWA?cX?d)^9d|*H6r@b)~^=PVdIG^`2*MIS) zW4a4Y{6fyAu8pHVIm_ah8o$t%{^^U~xokmh?$+_~@%HvMDCb`Qz1nE8RFxSYA8+8_ zWCiqoLHU9g{cz=iijHn>YARPck<~ib-~agZ1kTfa;zi%1uvteJ7VgCA>P*PFeN$eC zzrhC~xoqo#*0BKG)5*xiHue@M{G9}jF|#)O$rqvj<;Cakw}UKiAB*3Sg{4{EHHm4A zGEtOHC&BUlAmTG=?oMqivnpr z&bpa<13vCD?3;Giq?u7ObH5VpbI5h?K|bK?5#A>H=Q>qypCh49?mMdcJ=i|ni|yJ^ zBgf&s{_F;w8=q`C9=E~>?xtsKM|Z~;QSld6k6nNsQO8P6;)}cwQYmhiGnRMy`0g&c zc1AhqyWVZDT(Ss8zCS+`ySz6lD?;FPl@cK;FMxI~P)^*-ey;z)-y2$^y?HYJcw4eu zX4-fu(dXjs$_pIdYxfpl`IS|T`Q((XeB5!mI%iZxf>C`-(&6LRePr{?;5!`JaoXVE{F&y1!_Evf<$pMe`@CkfWiG|B#0VFr7_H(??H5$DtQnTQibkh_)VZS1?X_G#ABOB!w3Qbk>Px^cD?lILIYbzX)9 z8Xoqpu^7cVp@#vZD=LoCWRdVvCeZ94>HdeQG$~YH%R#?jq+W%?cl2=AyQBBHA!E5A-}(; zU+%bu6}69urR=V+i|+I#%e3BPGXB^pLkP0yGA0b|wV;0CJgmobY-@5GI@+5FWpUTDQb*MaRjBPg|lKrP7CF-nc725D(34cKoZck(at2LjVQ&_te z#2Y2?UCb@Vy*>#-Bef>mP}8^GwS~mnEs{I@?b)ln$aIU*ZH$o^;Wjx}RkNk@+0kZ@@d>LR-!Uv!U{RniaulN9F?QHoD5Cg>0j>oi>>o3t#n+%eyY0 zE6UcX*v!WbRhQ#q-OqbXaC;SeOM{q;LJ84VSMvOXi4aNv^&h?+Q(PI6UhoLnhLnH4KFMn_s{ zm~#6!*E82dQSR+_p*~%3aZzzONG@1WQd1!qW$CwRj)DxOuUaI`&kzYtBN&#nAA-<& zqp)p)ZztC@(yTi9b)LGNF&rNKp+M}9inV#5ep=Q>#+^lR3j@K%r$1RQ(T1j`92Sce z2)fyf20^j0GZ@lgG_d^6XeYC4;z6Uc;A$591ZBeJ7s+=@S^_H}e z(L-`mQX!+M;oo#JgZW54a!Q>xw$`85rFn5o=L?k2O4vgAbvY%u=y5F(sscm-h*dj_ zBMhw9ujPZCS7GT}?84UPGId}kj|v)w>Jq(zm7W0SS*P{8DjkWS*vPoadamXXJ(yFs z_>k^UirvNk&uW?898B?F`UZZ-0Mmc_7XoFgPk#U%jx*V)RqqQ8m?njSOMo2U{?WeN=Gkn)!bhL99u&=)pc z-!F!))E-%fVup_4y|uq6yiG(Y1(#AkqgCOuJpHy*Y5l1*B;MKKy<8x-#wq#2OuF{E zn$pR=Eh#KEF1_4z(`Ia=+df!qs@ohRd^OjPQTQ2I-n6K4!jz~BQ0DiKI3RTS^jcC< z@(fT^z~;2yU4EdXruLcSkm}X?u3i?AR}^`XM{VCHOBy6w7b5^Y!cC8`v6IF#ms(j= zR<+`MhyhQCJBbuvUnVBiXELef|NR{b)?Z*KoS}3; z(g;Wkvu=sYJD>4u$wjmGjDKCZsEfaH&u4RgJ%Gj_5J7dwXl2191P%@T393}Cu?eIl9Q2v;|o`J_oRdbOl)i_YH9<_q^v9%#Qw2ldMisyXulLL zr(^tv(!g&HRxhfjnyuR)ij!JBCwDKlY6}PiUMN6s=a*Q+XZ+MtXhP+W9IX$6 zW#Fer{~mF!|HnQ4kEnC0_!Ca~A8+}?>)%07HmrFGxXmQs#b!IXBzF`6CvRroM|J>u zK`YC2zvZ;+5GbYk>gl9;_xFHL{Y56DYeZy$f7id*BXq8*6$b%!zb9Vr-)NPd>DXmV zOxILt=(xev-SU^&?awe#J8V_hrsA>hz-pSmtB4CCF3wVy4SMCHBg3WUK*#Ks8|#@N zjFh|$kFCL;$p-qiy^n5Ma3N`^mjSGnx7eVYP})z55>J%wcGauJKc$2NAB^)1Me(|_ z)M!U$&#a_s8;c6G-JDB(Cgjxz`-iH9XrKs9pjY|*qjS1feuigrBtOq$iuZ^bUd zAYFBGbik!U49PcErF1wsEY=-s-+b;%#q7NhFnxz>b*kG|&(1}WRpcb_L1b1kE6(V_ z8P;ijLCyrT0k`2!J~M+v{po+9W-#Ay7b1R*R(%v^6jpIVJNm*~=bMV2%45bkx|CB| zQ{d2e_?J7)$YB_bCRrA~!$YZRm9$Y938@=vA6zarEMWKTZ!%v*LCnJQnaRI0gR8J< zGU>ixq}_0CD-EH%*V~F``3W({iKdIhN|6HBkTAoI(2ux zX&bYqhb{6#G!a>PORV2#_nf3^14r$mQDO7C=}P?*9yM!J=OCexOD`kOaUtVqJ{g!u zV?vV)pyYv_lqD9Jnr~sPwHMKSS@$R2!;8r0qzCI@17AH>1?@imducWfi;Kue$YF*8 z-ND`3n*&cI#U<}&aD*2O%l6icUDn(GWijkpLW=srh*AbfZ*`>rZV*uD$7}NrY)%b| z%hM`th$}AG)afVn&R+42I_8L5IA?S43@(~ltc>DBDrL}ra>S74#3H4YR8*PcmM>Ic zM??E1!qbq|(j%)2zeTl}U;I*U7l24a)nY`Fxv)Eu#gQpa?p7G*i-lDj>*F+2KqOVV zaM=B#P$k^|eO*)DOj(b=F{ULbwRLoE`b|$q)7UR8~AML2@fMr! z*NmaXHYqfrR%DfLGI}yHH0v=pN@0dV#4pu8L=3`=LDOMx7{zdThwg@|nbQK5Kr}CN z!dQ*!HJ9jf?QXr2Ga9rhGYhuy`+47PIEYQvlN~|01$vILzqLUb2`bm9LuRmzvwlGy z%EMGT>hXe(E!h4tl$Hubx6BeX=F_ahd474%(MWqBrV$^ic1N?mR%E;GrYo_r{9#GA z%64ZtFlZIBiE4MuPewO-K*5B09f_biTh=@3V-9Y)sB=G`dvCqwd0X9J3WgxVrT6<@ z`R@l9eZ65(;=P+g(YQ+)XLSJdNA5D3+JQm-7Jgy9;iEad>p!Xu;hu!A-FiT%8qlxI zImI+OJVp6;^!$8|%V;BL?CGT4E~Q5yhQq+h6{6Vntj7M-gJ?oVFjvzZ}Wo4d-UgpsEbI@s;u@kv;B{r zEjchf^hJf>R0h03yax&8%|{dqwi^izvsP!ap0TCovf7n`qZ=%lw0vuyFJLl7`B{6U zv;{;q4BTLYA2X0EP;a{Z?pKl@kY*u)KgPZM;J@o8M5MY%3BWDzhi>j$a(_S!+|rH7xFiLF?@0ni6N{JRK9k3uwe5Xz`F{Ec zc>R=vjPn2A>QhOjSeP-e{<<8%_f++~+Y!@=i8epLGulV?_K?T|56ycC* zuV}qtv!DZ9j2AUAP6cHyy7jEPblRKwB#SJZ9d1mhy?@^q+RfDL#5}Gsb%Z#m6`+5N^V|ik zG0iTdR2Afu8L={Pbj#ahSBR-Cj7(d(X>o?eaPXTacKg%C=b9~BFE>5s%}t={Rz|MZ zFs<9YrAi9{am*>G%8nXwYwqXw;U82gyBDWD$eH}f9a)z2W*aKp>02|%t(mllI~U6- z9IVU}?COTqb_k(^_nhZe)R8LKu>s9s@%%!$1W{nw8ZMvQP zo0#WDNzk!}KRT(NgQ_7MtoV-M=^+_)@tk%4Gxd~1c(@{4npS$}vjm)=@MP@Fdwal6 zuTG-!E-yzjNb<#MY_Z@J8WZ{4mB2H#9GlGhX(~of@A>3>FL`(UIenSUc5#5Iu64US z@1XhI9{BWR%DyUrSzeqi`E-_290%n2a)mMLp5+=hL@A~<0*l4BHJm;uBqr?Jpi!My zoDLC`Z9p3_S-EL65IAmIk5_lm1Zq*>lW z?DYv8EIhqCz$u%}Dc!5rndQ(5iOXk&+0quDPqu||dLfG_vH0Un7#&M@Jtw%i2ip{z8BXis3jLpV@Wx4R5PAim4Fzxau4U*SqT7535Et z0x@AhDWZA!$REPC)+uC>^q1~`QhYufBP21IcG zR>j=WQXI8I_6h5-u0Tfi{o&ffTbQsQGYe+8VP}9hKX_}_%fXIE;^5^|jEAnanTzh` z6A=aqCUl`5K9Gppi6ecTo3YVwP1w!SX-KIsipnjY#}J_%r!I?3HOuGKja&EA=q;BJ zQxd1|3bUAA5UJ+eBhl|1Q>`m&2&lF$BupicF<|3q!ZI;u6sHRoC5n7*mZ-j?+C~MJ zf{xfWaEsL@d3>ZzPTB^vRitb2+6;Hfww$M3zJeRgy8Uc)h3>2x)rmYd4nGOhDax#M zW~U(fn0b3(i4QWF8Vbbs=0g)cP2%8@SkLn_n!6h!g(BuLG^&+#z094IC!srxN&0=I zU{&=@TrG1Djr7pNz?My-=|aV;UR+sIu~#GG2)qa@*hkZIG|u;Ky49#w;)+*^P1ap= zBZkSig;FImkDzgC(OH;jwK0|aIuoyb|Df5 z*k zPg(P2EtN)l%{uh;?FQAM3-!_!u&kLejFb0){_EuUuN1bUuTM~Lfj8lN?#5l4%*i3cK<;7iL zd2MdpXX46+`4MOBH@|-lcEqMD98)CC$z~qvHVpR32`MM)9o0VyHeC`As8W)lOoBiQ zlopacnniw}``R{wRI9jcvaoCvd=R*;S-b^?aEL7%O*JN|TZN)7aG%zPW58?91b;L2 z<20+bM?_LQR*!#s`1_~c$RL^wiu!7lbR(`id#jnqL_Ty_xTGZOb~Gd6kIV}w<#fQ~ z890(j3jROb)64ac9Keq@FZafl6GTNMj(nwS((!kGev60#;KNjsyP6lGu;_TN_M!CG zZjce*2~6<^yMPY<0`NL`%hQ-3oh}0Y*r1B$zP2(bM~{CkE9ZV=#on3Bu4QQzc+*FgV+E`BzmJ-B9T8qCiKI%$Zshv@RY zd;>ElR#sLnXo(V!x3>NoGU-`-x}1wu!h(LNo&&+*#^F49``dm*>vVgsb$NOC5s*CG z69<%)m4O@0=W>ODpS{9K?0%RqrP97HVu0Jls|pH8xVX{;pVYJ)n$;hy-s}zj@s4QF zZ@~S;$(kA(8VU+Th|q|Fc6N5P{|Wd2%tbH^FpJ~FUn(y$^$>+w^W=NzF%>+_%k3~6cF1&1PD?w| z-efs^>fi?Xng35+U0rCXczJYPO$`G(yUi1?%Rgnp`}G+G5aZt4#YhyCl@q}dAD=Hr zffiJsQ`ZT z#jX=mi7u$m0mr&TNKrAChR04pY1N6Xm%v5w?uIjOO+|v^0eW^-9iM$6@>4iqoAvUQu4sRP9Mxm!Vex zt~^YGg<;nFV-mm?gosRPjd@9L_4dBrs)>&4sYEo6dH++U^#yrMFEK6`mX^HSkCM;OZ(xKp`Hhro(pbx?9hLP{PXwIT9R; z=($D8%{06ue2HIEYdL&cw|klY>=lmi;X$hHahq%PUMD`(e8HQoKoe)eeV>hfXhV8- zMc*56=ik>bgw6M@^*t{jXXP%PZ}9Q2FT|2U_z9{sPchANc{~}Nlp20bbgSM6CUeHi z=5kXf2DtPYR%#xkO-A=p4v{p!i^kqK-)WGf`~_;tzJRE1e_?>PUGUsEA$(80Nynfl z@;FDNGW!T}?tlu#Bg^f1b24}ZiBlA2=49>Bxr!(?(V@If;$8qWN^13xWnuGzI$(d zuijVhy;EH?^G8otSD(|}d#%0p+M7TvrN2%%E=nhJ#c93CEc$gnTJu=Dn->p{N>A3a z9-3754&qPZi8-H#(KuAqWXY$VJ|BkXlwZ8=S4qpt>@Yta#Fq6+Cufn?FzzsD% zSOmvP&Cg2)GxL$IEyTtJSU>do#tJ{#SYXwU4p`#~QBP#dsbIBTF}=BIdOzTCVH^`6 zxI`3c)(;Bm%X@RTR&1`)~=YN}^rYimklgs5?$DpS3HE5MatWTV~MJs#FgRQys zToP2VQpwlp#tFeAMne#0T?&-@nxj)ot!T5A{pS*+=h!dA0@opej>CRMcki%3>l2_s z3hAeRw|deKw@WD&WPvuTZMR}+k{X}fd3$wAGZ_*FC8Wh`+&^&{(Jtk^oD<>E*?!?8 zYU+ti!fUd=Hkd$o&5q`+?-cQJAIJ_VH-9J(Dh$_N?S2s=@-kPTS*yKwp->-!3X%{s zS^N~c%AQpsLaUE7%3ARgbw9|i$B5e;;#Rn9%)=n-m}!X~9=*$oicM~<;m7cLfpi@f z(`6(R%VRA}aWd-qjo=_XA{ zqZMSL$8s<$tV+<4o^k8$Q#%+AZQ$=$Js%%>NN2pZEKmZYpz7KIvZ&#{P`%w~Ci2^E z5r$qB5+TID-OisQ@+i;h)L)Ap8g6)f)RqCp-#|W+!yl8+ZPs$DIRiD!Qfi_0NHO7p zUBl$Z>$_n&z6pg>_JoFrfp6wbHyZ6 z^J^1Gf`>N!p#v139v7k+SKjok%#^_=fKRz+q%YTY?~XKMxaR@GjQ2X3=thIF^-L*Fg9Kq_$QdvcN*ufVn3ATvJ zG3w4t)sUsPPA4ceCF`2;9CaI+u0_li?~KM~lbHWS#J<>iwcMy4_my^`$cW4Zhj`Pv z$sW~u;9gQSSuvA@Ow002q_7e8gNnND^`%SvRcQodO1FIq!ptilYY^wVtE*~=A}Kkf zZY}xSyeTnS3-A8!ppY0y=4`3nxU-2OO1u~S)Y0lgK60d`GNfear>-2eSz6ta>X^{f zEw>sL!EWD*89e<*tv`*CUuTjb z1X-bp%?bEvAiL2Lp21{4|L6B8f7|uCc932#7Udb~X}1!)2S$!#IgV`iL12Y-seDWu z{)dv`iqg3hhazQGiFk4F5zQ6loG*r)8^MeZA~+ z)`{d@6Pc@B%X9KUfK~>D^7DZ#cl%iwOwjusdV1%n*Az5DZjO46_Nh#vb^$c$l9Lk} z_{?}^#DX5kTQ`H%x)6FgAhq&?0g%2U(N z;DMjDx5VJ5qcvH@M6{h*Y-?4baY~|z!&Ft5L+8|D{lUwN3z5}ed8M_rFh+by+tilC zPBMA|00Q^q(U#$bFQma{kSV)CFeY#dPWUaUdzR za4C2UUTP|wnso-hHlN9x27epPDVxI3I48X@#`upR=rP9O#k9Kq0ZrP8G{td%zI%NmDNEU6!Q?Q6j$A+l$T*Xw%xaqb734Lm1D z42|F^Cc&XJb)RXyS~9lP7{jK=sa4R{;QH)IT|U9PyvPJG4BZOwpGQeP zz5&je-{|>K_3TKTAO;buU}OAzOI`o3vtF%UiBCu3@=?P$dx_C*D#jSkt8herSAKtC zJ=%AHVuzBe#7U&Gj0`i4jN)1B%R3_$<$tmYOl8Cz+sT2v9oYID=^QmTkxp1)ER%eB zHTtaj&MG-DPE%K3pZhyHCXGSMUyv>?wM_*c4OO8mhQe%%Rf&DH(X-24-Zu$X+0mqT zDo+d9c8#o{_35}v{!jEhgH=g{y;sW(o5BMA)NAE#NLK*v)Iem_ zU8jF!cwDdsc)PA=U11WEmxsSX#rJMSR2BC9eV^%K3o)vD>e&~5%F33H^57_06(z6o z$EBd<+$&2^u-|%VdsZr@Fe})I^kJD#PC{sCVmr}Q!s)|f1xXmX9h6tsjMH_G_{cEp zfW=xAIV3r4Xx15!rb#Ov-ostbsh%V&D>>b{6(`196IC)lh9tn;)p&kV8buz0&kco^ zgVBin=zsnRr@mBM_Z_dM6UK>>Fd>ODhn2&RH;1%bRJNR;S=;&Y?-;D&o-Ys9Cm1qO zVaz(8+ot*2fe+zeq0qggV88SL|J6y(sXv=HGQiY83duz`C>br3n9ec=3w4>-_lYl%&L}Q zPkWaC(pJ~Evkf!VcF)^N6)#%-jnTYNNz5l_V34*_SK?CvCl-QkvIraMs@HTKyMd)2 z6B?s%Jh{hq;nMf(I5)eQNAbi*zvy!OUBb%4M3z>E)uZRDq@>J5rCqmVo&hhuScoJ8 z+)~`7W?Ewh(;xmjZpQ6Jn07U!jprjY>3HRa%HHD1Q4>fO&bum%`~^m1Tw_C^M{PDrL(EPk!@W)*m! zEu1xaM)x|YxLzk;?rh8uuzcr?D(bg`3Ympu1=;sTL$yi4_FXns#ldDA zuIGutD@`$%N=%6uM}tgolc_d6)tWJUSz+&2*MaQ5o12D4woP;Ogz9L*dXq5Jbw@Ug z&%V(^tY>b;yJ?k^VbIrvw#J!OvP;;FlAGpiHHaJ!Lkynhr1guN@^<+MDQK!SiP6^i z74OLeCn{!pAI)k~qBKakq5T&ZddcD&HP|MJ*j9|@73{2tse{? zEh$2|d}p~9082$x#DA&m*X8Rq*6M;Gwq)0t!xHl!pG(5U?>EY;NSk$@EM4P##X{o9BNJvOHI7#WVIM|Y%{?BcwLh7fdr^lu{+06Oq zp~8g-Hfwc-5+?S!=K`?;*K{U5TO2rR?}idrqV+^(YWuUF?tKzM$9q4pee{b!w0YMV*KWaK#nA56Hj)fe6k9J)t@+`l5vGj`7@9aez02-y0{F|b%hS_iH@DszT<|H z&1RmT39@$g)v0=0=$!GTM6w~1XO`uGhr2q@Ha^x2a&^AFcbl5gZ3>e^B@*!k3m}Ta zQ>ZTvPGkzc3wmr~`;u>T_7*5{4PbF*(YmSZcncfD0iXHt@6%f+Qx`uDagx@q049Ge zHjX62PURkG=$;WDnZp+q>QuQ7O%hwaMkt>cxJz7Ke1Rt>)@dU-ij6I0Dr=FiIY*~= zO*X+pn4wbmE{V!;(c>iUTY1I}YnDZ3OhiO0zMJPYuhzpwzQ_xIijs4Gju(Wef~vaoouaSd(QaqOhF4+?F3iJ2*W) z1_zAyQYh^xN~j;zB8V?!3AaAQ26p<~-N7m>c_+Mn7c@oY>NL-iX3Rcgh*~5_5+e`! z$$2^$b143Jb2Lvw`}MRnmP+P^ZL7v>Xx%R|m1HhpV~66*EL^Uu!F_o+@Y(zE;UQMn z@xso@?J%xELyywhEboG z9DKN}t3%Iqe31XRIT9sENcZFOEeRI|#1p zb}Rj8D3t68bA63RjxKeQj;gHr7&s1QIwiNh%ah4lv>$5;FS;I^y!RplZZT>2JS!}3 z2O&pAc?}&#@+f&qD+0c!O2NEepY<6r5Ru@C)y&y|yM;Y|c36t7ySGNlCG>|g=Zi=WHUY8fZU*{s7PI3Sv`tuYcR{F znMb{smCE!saJ7ZSUZm{ggWzXs5ONt z6u6l$?u2fZq$NywW6rOZy!9tS`WelrIfNcDvzvlq5B$S zZD&R|hOx7;yiAySV&K-5i&KInX_$)`8w4yt?=OG8FD;oUjLB){AP+o7*;v^mhobO? zRfvn=;(WaFB60ejTwh-0%U>XgmyK#u>~^i|zJf8Sn|lfa6X(MRJdEyV-!_x-f){$k zzK^Jzvm+wOIU-Y_YucEl$U6`@fKTM{OiU-coeuVNqt9a?M=pAc*;eiddi!L)3ZFu3 z^n7A8NljHKV!{0LHGJ&`CXY5KonNyCp`gcobG4J?Kn+V5w!PKS9@vl z)xREJYchm2vsf%8r&QZ?S^m(^&DlyMNT!`Rkm&HbD1~081~O?k-sLf#9z|4?nWQtz zb~)~t#E3s8<2>b5G-eJc2z5;4kgU1|Ll4Yq-tSYxeAX={^h?>dP!-;FW3CcHLRZJpX z$q)Z1pHLK)@%E6csb*jmlNF!po#gwnOPRB0dr~37_&MC_*!=$M(l4fnPyKFxvpD7x zqWl!$H5~Y&4&9+^wzu)>uT}~Kj@EB~->RGmsvo1@C&U5Ito7WJ-_2tCMyac>`p169 z4+qc3g?vmuUR?UWYwCe-gW=4Mm^ShrYVN+1mZRKDVtYMh$7KrJi8(0WOCJv+=4D z-2H@MPugq8ipXDobGYhi|YEdt>c?5U$Da@KW0FJmwQU zaDDbZ?*me{C;F}JZE_}{hX2o>;qmdx`r*#uVfcyk>*w7LuS-B_p!ozlm6% z4NvC~E7UtXAFjRi=!c_PMw2q`#Yu(U|LilbF}qL#uF2H@v2x253P}BChM$Lut0+Ew z3e_b4^eKOD*x*wfcKG2gmY`;cXC?f(HtANaV85wk_BZD2dTbIoY1B|_2?8Sa zk(=Dk4^l-15K1fm1Gg|zHN0hrGE~$^A%zQ}NS;+LKkRsA(w|aRkblNvvT^P&IbbNI z8)BIBQKC5Wu_CqrA*HIoVcx$#`H_#4K%leC-w`Nuh96mDbm&ucT2BU|1IwPkY+EoF z0(O?4U0HWjV_F<@hRu?fvqT*z8_jCX$_#Y(o(Bu%8ueIMxvn89>Vco|*!g+_FxU)W zDQWwlEw@IJakL5vFX&@yI8XIFFeA^ZtqF_S?!~LClaCJW;%{;xO_0fSH1Xyk5@!bg zE`Lt-bGpDCtg%01y&O;D%huE_pRf=r{pDSAa=OWu&BPde&Bre|^g9|237v^|S*!W} zB&;aAtYJfjEM_9-wg}N#0O!W+zM5PL7ppp1v9XlZ`~8&b6#$SACw@p9#ea0Vx+~su z{?VW#N5W01ia5(6Wf*XZa&2i|S};(1!hY`A(Q@&Ty3%R-N+?zDVI30Om0m4z7a zxW`x=50QVPJH1;aF_|1AAAwj%2^-itWiWwlfGT23csD6vt#EHPyn1lsE!gge#CgL| z%v*D&^<~M%9O}`G!duj|8AyE7`pM3t_|l5ghMuAxXzo zC)?R08HW-3nDwON6{&55C?`)AIiBhLQ{Dlk;*iYNp}X*7fl(Hbr{AZT_mvnp?h_^( zxtbu!cb8s9)M$h=L|Lfq%pQ=jc5HXeDkH}dXAhJjsNNbiF#LVn+GEM5L@57&&Q++p z>L_NcpM&R4DlLvP^a*hqphcD3I-HvkKi{lG$bwbB6HMK>wKi{lDGzEDe{ej8_MT6l z)jP)*!0lCMwVWd$>LdO^V@;(NGH&p9IMmDn8 zvXanE%X)caRw^ul6~(6pwPQRHxx7g>4@}c*)T)rZZQL)Gs+;iUQaU4h-9u__p-;p0 za?pn$$@c~nuXo^CB5h&nY;~AW;h`?jzQT(BY22Wl@2Hlw(DrbtNLJIjtwT%~;yWH% zMxwwquTF6GB79e~ActHNI`Y>^JcMDIa>x2%#A!8(E4*{)O6Pcypl74Ajv z=|`rIq|<9#$LQC8oDpY?F-R)bn zkYU7{S+g{Pw+h*Dx>h~!r~1Puw~*$1g>+xf7OQ^r%%$Dhn|j}UCDC=f(XH+~&X6Q| zv7QhsJvfcPk#{%r%~HS!q1?taMzh=lKESL>>_D!mQ$>9p)WMm6+%XJ0Ci?R zacbXqw--tCg!mYQUg4%3;5Su(=i( zJB0?ka{-e8M`CH$)^k@tjUYjkbS#zjfb}5N=2c5~&$;ylo?K_NL><)KPMWtevTD9C z&ryP8*oq3xw@Y2=JfGpfz)MKT3~Md_c(FA48w1ZLJ9_ze)NFW-(Zl|-MUa=t;bWdn zZpop5fN*7vcl4vu0g-cEyjsz4HlX{in=9lrd-qNOv}EV_P4)BLe4J)L_c8m35}9~m zb|9(4Vqi0ofM)u~uNPTWGiD0Qj>{c*uwmvT0??3NN^ZqgJcv#+JZmQR-s_`-yno`h22sZoV9`{H#u zTEy>fK-=)`7mDgPpP2-*n=f6!VlA@G_EKQ*iSORQvVD@+i;9h4~xjBzo&!zk~_EnG^di+W+d7E$R!G<7c%W4C`sfZK}C1 zGSS6v^a5WBB1R-oq}ck{uaC8xIFo|yzUC2oY`ddIqi1;pI4qiad6c=Gta4rcJ=!Ld zLys>uT5~>#z*aPcxkKsC%BPKx2(siC7BbTQILQ)6|FnZ6&mlpD_+6&+aeSc40o7r1 zvDl!54V($vHpViQ#+*kKhQsV(w|B5yI|OmP{kC^efeSI&sGJ_pBKdJuIhccmr7#%w z{k~+`j)yIxpO!1WXOE`JIC3G#&H)*aH92`w9q3!Kc)*0=vvnEL<9zO5CRcA zv-Rwxjb{E3Ov%McF@F1_OwPFUr|ymFqec;DPd_+;fo!ieCr6f5x$Tdg-CkC%dqaMK z+7ZEo4O&Qj)3h8td(i-`nHwzHAv=vqeB&#(BNxLj_em zE?3A4yzVF`j<$9>k9^2*y47XJ5ObAU9L{DS)o3aI(mF2CT@;I|S<>#chLh)TsawRJ z4FS#C?S83L3>T5CS$iILm(kN!M};ZZCj>XcF7fe`_!I@AXI;?M?=iV?CJkM?zhnvI zSaQGQNN)$2A(b}xJ!cm8=TblOgg#G+W#6#k|Jv{QM%IMakU`zN=>no^w+3!~zx<_R3lo=511zQs4c zwI=Nk{wE=)aC&6`0JpW~m?-49bHsHS1{b4`@;^*3 z51sFEvV!P;Grgoa%wO2y9|r|VOoJW39*3PvF$#kQjAa#jBU@SmHa93Nm0k?#0gK&n zL&cs;-8R-`rm(;}5Q?I)gvC*xhMXyj9xg@CnCzt%rF$Td=IkFBV54SdRvcfP=Qi|8 z5|c8rDk}X1@1d;wtGS(Bkrf{>kCyGr)d|bJf9+uY+1(uB#IK;wH46t4{l`7OR-VxH z>QjrdA_R?mbasx?T~5{2!}rx#KfDSqfIG2>5qT6<|LE!AHu8M0HHYd}QTC;E>b)`yHG2~p4}F&~3qRa8GoV$V#g z*Vl4xIW0Q-1)MW$7$ek;E728Zc{m7=P*I@-Q!{r$s*)IX`42jz^X+JZ?SeGV z(jjdVTfAuyj5(j_9udD2P>b%eR7@Zd>2L}`jkTWcsSNF*b`x3C%lMjM#MoYl2K$F1 zc4nrNZOihZT}R}Mh8+AjMe;)cqO5#}YHwIL^v;`P@T09?pN!>qud?9)(|YUuU4Q9= z*LP&c5#*_ekN6af&1QBujRNYWn1LTJZVqMJ7dS_U+z!xv$zr zJF(io*{TsaS^GOQ_ra$%-FjdkKBzZ7q<_5dtFf-Py-FT0lR^J)Ck-l1)nwN5)1hBk zYS?%^)_nUHjgk{NOgDAbJKVPOMLTlM)J3;S64>{lik3yu6ja&ZtLf?-JjZ@sA@RXR z6Rhx!rrYE3=ft0s;*oapHlaP!X7UnVIQ=9%w$`$10&P4GX53ZAdzJ=!3?&e+IWjvp z{O}$-5x;n!y`|Fqqy>dn<{@=}0f8K&xhr@MxrZql`~qvoK3^#4Cg`a%T)@hNO+}}OB+}eh&TDfu6$J_VRIhdioUKLU7?vAVB~OO)y1qHyIaKG<%3o;N z|IrEFUe81x)}6M{bp^PA>3d)Q!(c8~Q8{O3z2=|~R*f213b4_ZUXPX%ClTH2?gXlx zru6?F2G<(v0=zt$8YVjFhxBX&JceCLzK`d_H?mv|?Tjy@5ywulL1J_|Kb?K{dsgUC znV5w4nY8Vmd{Z%w-MeUW;}`|p$Fh&Pgq00D?aK1YkvO&{9SAptUd+e7Bl)=eie&TD zKOxEskqU{?h#KTCY;l#MYi;xEBY6`sJbpX|Hex$D)a&ssiXj13Tpv=e(v0mn9eb%*Ir>Lgy0Bd*xL>okdWU z-zumTRufwB(?)tCeXbUEWhT-q)n_)N4j-i9r?GhsXXmvGpcO_c)Kwtx)HddEcc89V2%}RI!O}pf+ z-A|r34%|Ycu>hfY#u*G_I;TtdRTf2qblFl8P*>Pnfs=MUG%k?X8! zYpbKPlP)s9bVj4e*~LXETX3mDi{&1cQ(>Fe-q!ZVwjU|=|(hO>ZUCIaENO5#(MetPl$fd@RR zmMgj*)`*%*e-1rPGtE@Q(jvIH>k3LF^w1$cXkI67W;M%fNfIdkeGhA%FxN*oMr$ zkHnj1@^bOCg+q$r9_sILc#qr0WB7Ib+Qfa`Q{!%X{qnLGLT#CZj!C0Tvoo^~?QF)Uzh*S&IDV3S z>DvNccWw<_`-g{)5NeX|7Ldrrzbbpx&j&Aa^&l zDY?XyZ|0V*x)I}b(b}PBdHvBEa-TG{O6x2?necXCaQV;R5aJ4bd1aQvE;i~?ZKU*W z@vkSimB&)wc_vusn2E=}`T9X^$$G-{4UFaR7IgpL(7NP_oMERF;|wg=kH`l$JlTI+ z3#AIAq~l^LW6qawI<*%+!?%l`b|-Ia4g7X?aNr7A&cTd1E~G(qG>joM^I)=G3IE@=w#L|V{%I`CnT+QcCJqh zyp{||rZH<2{zhKb#B*@u)YNrgx9#`>77<}L)M(M(DM`js z7Bs+3Gz@OxpDwjwU1pEnTES``TPqF-WI**rO43-nsC|P?GlOw;8XihE#wMyjD8C7-n0@*~!>ND6%bQPT zW>zjK@sN|Vu!0&Dq*_N!2d4qa&@qA--Te6T&Z7t%zIlgQBZ>lGE_w-L{2qnqoI}gc;Q|pp>9>~(NV5E9#(Z34FmS` zcdyFSpbli1C!YS!4wBYx^yXcHh2(Y9<~&; zC8k>OC2HIxL>o}^?M5LUIFFGN*E}HUClvH;l$_J`13*gMUNM>vsdDeJN_}S1_!*TG zsok?eKq+E!d3N=}@;>M8Fb#X=H-^~EoDxB~ezj_&o3Ey$S#!@Dxi_0y(z?&j)nk+* zew7zuP)W4pACSrWSgpF9ep@ zO2Zxm_;j<{N;4BO8SI;{w^g~+G&VSV-mY6_m(KZx3Rfm&zpkuBA~?V=pvEq$DR)>}?Ma_)z1yiFOBjTg1}V&m#lV(bTm{ zLPpRl`JBU)ff{!kFAtN4h!^W_oB8WPnl~FfTmJ#Svx&urv0{jQe=b9=(wi9>8LjNA z3l3PQ&dwku=}k7h#wvWV&Gz9ElRoLs$0SLeOPKf#6}=Q^sk*m~S}E@4^P7`$XG}Mw zx3L?S1;OuGEN>63V%CM}2lh+c(+Siz&FT8g#qNyO_4Tu^C}Ci_zj=EUFaIB)uV(3( zRSIr2nrEi!XYx>UtXo;>WFMQS<52X8!PiU6r`S~;^LD-zvZ=B$OpUgxh*M22=hwa5 zZf4+$03bF*jOH2Rq0_9?Ei-`5-v4=-rI-H7e$7G4&F=)5XzO>C=}17-@n4Fje^JOs zsGE{W`LC+moQN_pe5-$pfheX9fVrLKFMof>Rs0vaRUUnz{_e0^M|S{7q5#M$y|g|1 z0R(Hjo?2pRtGxff?9<*QU-0`^C5ur((pu``@TZ+N>=>X?5kQQ7tD`YD=OExs_=p~@ zuFZH^jN3SOo9|JQf_!Q{HmhpRs%CuW=-MGrzk~IgC!r9!8&Erks?2{4$#HmPDUgyRa z&`H(b!fe3xnAZ~}_9im;NGWFPFQg&o7fM9Z78aD5n_Bg6|Jr?c*)k~K`t3fij2L0B4YCs*1-8`zcSPyBebaJ!dv>K!}*Ab`^;$Xnd` zK{~_6cK;C^t#97iHv6@{>)j&8BTI581-*~k!N+x$UkW-?vrFLQhj#4@g2TGjW-dN6GZU5y3dnzUa7N9tWYJC7=!Tgc ze{r*M&3HX+Va2d=7{ma?LL3$k17o0Ex9grxLSUc491i$n>p3_v!+s^_YcUDRpO>e` ztIe4=YXXDaWbZL-odihYpxIhfV z`Pt7}^I^4&K1>X}nm}Vy80!(n_R?{q^3gY-aIC`W%_YP8S75ch7B!4RQ35~)zfvm7 zH1!$jXc=W?#zAtp#YOwLIFYk6lE}nb8YWa`2w3a>$SZu3wJk{O--rLSaGI%ln!v}7 z?K-!@+K*+AB|sZi5>Y6!kmu($=qpiWyZEt^=E%RATlfKQ@CFouGmUAR#6i%zF#c7( zze4t4Gh0gmb0S)uUA7PuHuVkTV z76sV}jvWBZFanJ&a&3~Vknp?p7@7**jPY3M1O)}XtxZbHE{juiij&ZYxaMXOuRe(e zx#CQ@*`gAenSUL<)@XcOepJd?GuqQl)T6}Hgp}55Xe3zD3ouBJ^=o&I+sys`b)lfC zKjmNvPJ!!POIWhFF{mRV)SkY~2XZO*J%*EtigqilS1ZKQ$q~ZEle@`PZ>p><3zHbe zi#L9LfZ6CyO%{a*(1^3&E!482xL;MxB*Hn;5!v+1U44IIdJ+kF$R)q4_0@&v9TFQ* z&`eL9UCS0*pu71(Tm7doX>3wyA1~!aD>)-U>;7B@C<$X-|Ir7R-*>Zq#@djww$DCn z!SGI6pECo`?N;=pbH&&+J!wohYib{FI4TcGHQr@u7Zv<(POBQm@gCNCT5HQO$7VoU z5hE?<7k*nSvC>US<)TX%V&R*Ahw4N>*gU*v6nf_5GLlo-g3KXLYl)eMHpZfz9SzPm zzh|c$^K0|7am5L8SlQUDQhUC%b~W1?(~r^_`s_FZ=K&BEx@m_2rzNS? zQ^`aY)P(vO+olsL=Jd4_tK1Q7H?A`kWhL5n=3!M!Ygy#{A=O=0Mg(OVRSH0T~G9A^D!g>+&i4r|AR;U zY0OxHLpgx9at@zpXi5T0oPa+sx{UqPo!-^Fxji_d8h2+{FZ|2{bak-9$H)IY3pgRd zphN@R;r=n1-(cbYBVGN^$6o>EGyBqPUZ<_=V=zv)F?*V*s3@QuVbulx(p}LqG%(=x zziCV$5J&=z5+G}o?|P#EBxHz)h_-q4-GP0dsJ9gV=}UlaaTm=^JE}40k&%({HbP=R zFSn_lo;>MT(sli)lT&ZBv-Sd$KDYxDN1!V=%od>1F_4R=lvLS$nA~(sOiBU_s1SmF zI|&L20jnuMi7CV?R;MD<*7fs0-0Jj7H~f`7KGCj~nGQRp+dmdiQ>X_im*HV3{NMB; zO!K9{)4VZg6M)hE&wAni8FyRq|4TMN_{k$eLiJ;@7U=KKM^J#F$@l7p<;al2efuaC z<&dkjD_o9Nq9MwuoTk^Z`|v;==}X*Bq~nrk@{qz?i$#yvoJVUf-5N~~n&O;;sc=#U z5ojflq@!%L5_{Ber~!Q2;>T$crkK(MJ*IZG-uBz`+fH4(t#Zl(x(y*GEocUp!!AS#h#dOCHK+tLCeS5TKJ@c#<#wB7QhgpD{3TMpw_%ASzq2d{bBh}|`{kG>H4tIi3vz?D3O$*neb zC;*V^>CV-IOguY4CRb;knS6WUJ+g2a4+AwH3(dLW-B&FXbzcj^v!68f?KzkA97be^ zX{@sj%SEbTsOP(OB}5LMKa;bF=To{DOIEnE2AYKtI7~~*!oF8`GF7c|yH2J>_#<&V z=6JJ=k9anWoDY_+MUh3y2ei|HJT{{xMBSe@6>IiFpz?3SsDVa<)&HLmPBW`*c5Ba+ z8+2+}URGRgj)y(B^Dr$V9IZTZ`WL=z9bIXHeg!FCe8|vowIQ!YbRN^JMk%!0J*}9&N|pUx?#Q_L#?~-2Z8Wm7}|OY09OYO3D~P~GCsd= z?liK1mV{6e5CbLfPjd~R*5ZKkSi+wp{~KO&PxznIJS-F*3}nxZ_?2E22|PQDsV$fUF!FGDF<3V+bu_9J{X6EH;3hnW(HHi!sEI-(ty^ zT2pwapR=?$t$zXEKPqsrJ!;ycYKV*rC}C6m1e4WOZ0redjbu zvitlm72WOMi3@~uFtQS&>Ofjr#@>%cUO`Tco0V3<&$My)TYwpn{>o<~x>Gg!@1DG3 z@Up7$^{y!LB@D>yCqU>E9vLau>4O&jkC!sWA05RiF-xH|!znVyv)D=e8rdHt7*Q&d zZUh$vchq9VcP+3wpgKw7a;7kIOLcU{|2>n`f5 z%BB!iZ`dtMk!A;nG9%J%G6ArprI3=9WMZmE)T2sWkJa2|H%pPjxT1E$9Tk~$FPGg> z%ix!Hx*VISA7FBEvGMT00!}5ga-ZTprpG8v;o*i~$`>Mvcn!=TtH|1kYlBt<76mp> zP>w~PnIhx@;?~wXIQcKPyFL^BhvgZY9LxTx;Xmn`d4Eef6(W*_GN;~(+Vi+B^D}-H zk|3aOGStBOXOj~poK?@;J37Uj#Qk0IZY#fY+F`^u>NeYFTvM_ZTM;%e0!aN0Olf2I z91q$&;7$RU3ZDezL#KNTKNVCc*?hs5TJ3n;8!U#wmjoC|n(k5Y`L(sKwa$Kt*(+)C z@5TpSV%`&axVXujJm9k9BaU9F8~t;chkK&rv5rfK6L4yFapk{}dq>W{ zt7bl-cVtN)dwi-7)?$Z!cO!@oGX(hY0&qkApio527$9e0y3n+_@PP0CO1u5zLqGp( zQU0whaQde^?2{Jon=rQ}_!VHrKflAi&Driogn?0hwNid#+xl7#qE4tmGE!CT-E>4o zL8+>&Oy{<Q|@-|0D_6zpRdG7x8kO z&lg}f5xk25GDiSz(b;+Fe5t7OSfOSfBgOO!aPx5k`gV;1LH^(ZJbA0gk^O#m`#Ngc z@u&d-he@JIv1hFuf9#|W(1R$+Zv6M=c{Rn3OrG@5GieqIuuxYOE&bq~ zK_fLzT-$)U0o{zEWEb<6^cjPk%8ri4a6n;oDG?e9uGCDK_GH=PVPhx`OOG&z=LFLm#~G&hgqp@)?SVK zhbz0fmX`7S7Z+U;{O0`@;|VUue)gL*p@nm^oqGw^W*~3b|IFaK*{ypWOimf6idm=o zs*yQiTrmCv)VfpdZshZNIQuxJALSgivm8Uj)kJ@-S|srVipY~S%TV*z)TpigiPrm1 zWfRE%Un-lA(Eqv;3=cJ*2;(T3l2r#xbc_+w^gd27#77pfha4O|X*n5&DMlLtWZ*wz zT+sJE4(>fCbrFY%O|#b*TNnBg$R75PlZ2XC_561+pa}B5_hXh3;j-Fcj_Oxp15`l= zptdCZQLFUbt43%a*%&NN<&I-7((nBvaq>+<&1buIu>WB6zoQ|&YJk8NW6>N~DAg0^wR^N2NsD{- z84?CQ{D&HcWxxUdp9+YnWC*gJNXp%aqF_^X-yGVi2U)r$ipRgK3pre6`PSQgW8m}AmEVCsuc-Gv(+=iqL=VRvh_mwR>_4!Z# zS8Hzp6xXx80ZxRVL4#Y6gy8O$kO0Bm9fHf?u0Jfn6M_Zz5M*$N2_D>nI|LmVTxS^e zlDGfediCCaw`yx|rBYN+&D`$3eNTUV&Uemt$7%&^JYVSE4dVDu!@t!K!~rMv*NgU} zoEIkLMwDx*k3g%k7Ut#?Io-FU2ng^#{Kf;YD&^P48StG}A&VXmj0mPh6DtE=zJGTV z+`pbn_gL~DynnrrUPo_$SNbY&FH>S*=EL^sH90x??(VLwtu3Jbi;)Y|XZ`i}0{(a# ziF;omU4^~60oKBYg)?}QtP@or_)?%6qsh2yz8z3X5vEBt6zKaEaBDCJWi|l3>sd>S zeJk)?rZ&O0wBsFxFF|*Md2acX4Ow@f{l^bL^p~_uaP=>Y%uy_tO zRiUh`ER+`Q?{9R9ena}3AM!(Q6O6puJ>~_>=kv?PBX~+C8Y*bszQ~mPVoLkFXNPGR z%2F;{pOAVAQBJ=|+h`4b|U5Fp(sY^w9KIk*#ZCpx}tkc&#`9hvsSl|9uyBO+n;vWUp4y-_wx$PVnP5>Fz@l z_mDJ5JHopR=U7*4L|jQVM~HvCb#fr}2-E2$#ohtaEhNqO4(g^brRy6M!QXH=K6F`{ z$&ZL2rDu$zS@~@k_gO%pr0Yre@_T7cyf|BM$M_b-!Zpf+Aw`emcyNM)V-IFiHaH~+ z=C!$PqxvQB}@J2ZE+Dj3|-_spXD%=Q*T4&Xcsrn^A- z(4>~L&4v*xJy<2rc$^fV?e;X#r9FE~r#YWFBK0+i`hRyn%#j*>_8Zfgv{aJXU4H*B z;`BTEu>Tt9*XxN%U<<5EKc6j6k7(B2v$uCGYgQCaVtk9CMxH`)0mKnET!kW(=2c?e zqvsO|i3`l9X6l>Py(BCH!t0?y=id_(+OIEPIW$4kqw{GndocjA`3D`yuxpnoY0iAoxtB}gAhrRPKbUbY)#qyde&PeFHDE_YJ*jN9)V{;I%Pn?#Vd z#>`GuLy2FDza=N<5(s+X!zv?Kxw7YLSb7U`0;@o^qj)f8kY=qn5Jr zoVI=*p}dfAZ0uSrKDPkHldvV?S(yCzN!JRM?>lC#vQ$pL6xL)fC@W49@s(Y?g|A<} zyv19m>GZqg{2mv6=tAHP2O0)+*xZJuO_{D0A z(|9^HDG=w*zYs@sk-bmT^}k%k!D9o{lz* zesAe|H9q2iNvWTyA}I#-Og|!I^qV>aMlCWo(S<#$rrxO&(y`x@|XB5|1_IxQ!o2%gLo}*N(9V#?wa$e2crrfAQPr1 z%G%S1VHiCUS6Z1nHVc?yb>ytzA`&+s7g{$Ttx@wcYQmXI-yCtI8I10B`NmPB_o4<( zSaYgav;Be*@7{qk_8$H1M~?S$BbI`tAAbG#IWPre(z?0Vg_Ha1?T(RtI$=DU5vioA z>lL@&KOkrEuXPMF$+q1(M)-d3V15j`8?POL7UKG=mSQDU9IjRzqO$7F^L$iQPX|uP zliW=gWAH+~*c~8h2ajzIHo97xUC!A++#LJ9&AZFUM+ zf;lD`fW1EYm6u@C{{FF7aX`JF>3k7!o`XtGdi!Dbc32^wR}zk0%PlA<2-zBcrky@# zX8*14G5`2lYV+{$1??vNs2%=)(hVm_*GK--QxrWIB;Ie}eQ_Y-9T)FNxieJ8 zlV6KmF@z3<$K5$BD#;G*Io6a>my{%7;gpWm(0GBQunhpo7N zD6JZ{`A&_Fa{h1J!QKcmfIR4N3Qwm@e~60Sc-bbnG$IL}j69$zJ7i(vEQ{YIY3LIy z;``@J81!45o12@2goK5Kh2Mc8$lw(4D;c$T#(w;`1JvaoZi>ywpnCKu^c$?Mp#kE> z$$e{1t0}_Z@L`lVo+WI6EyZWM;q03GusYB$G4Dw}_{^fvZNsTetp@Cv+mmntE?f2= z9&?Pqd?gCvIWco7;{n6e`Pg34Xxx*#I^hr0Z@<=Mp5q(=~r>J|v7f$XZhy|9yGJ$S&><1BT* zPH#W#P5{;QjX%`P%~Ti})L6yF#twfZU;uO+%q%QwtcJe5cf(~bkSvqs;SxNW4yKO9;Z74E(kP1hHDStun}3qX9BptxJ_v|2Rh z7P>6N40I`AZtmUyy^xmVdDu?Iqjs5FokNPr_9_X3g|XbbBGGuV z5`YQqmQ(!Z=MN)`MYi);Z!No+cZh&{swj=JZ>O*sez!lc#PWhj;VgtGy>B4Izx#>okx6m*KA7QL7#R6wCn z7`c&nv@9IqH)QpfYLRBBIMiEFv3bf1wTjW6hOO&Z=z{q{Ta1543lNYJdNtnp9Utl= zCxI}=IK6VQp1!D||9)0^cfRzGQah5F^ zN2949WuQ)=WI?&^o zMqi9lL&d}{|ImaXN=tHbg7Mea*52G_N`@uu@9!UP^l=)udM`G*08(DXw%_tz;o;$J zkSQl6k*N~}4#UM?%Dl$*jg4wT*dr|;(Y*`uJX9bJJ{*Pa1!|nhIh!LzRUBf=VCK)-0TjSe(i$v-4S{F z^cEsMn^sHw)7{tE*=o+C23ZWHe9|+`4n@OrRjG( zSWlx6(G`GVVaC`%-T;db7Vl|OxOn-`#Btt0E>l$G^P z!iIakqbH52zu%(2%YVBG%ZPo!-`Q*h0pH|Q**nylk8ScR#cM}!aeJR0w_cCKH#w|a z2cS&nw-J{CC%I-%%Sx&by2Q66_a-ELwBBfcW3v3jsf1zXdbp)N!tpRGe{8sD{OpnS zc6gFOSk$n@%hduO_2jFuF#P(;*Wq&_AhKj1X<*+RU0g&0dASP>;O%1;PGKd~4Gi*$ zi0LI0Q+j%O%Hg17jCQ}I{iOhzL~~t3@n@A3m$yAF(@vjL+m5YF(#xZv!t~<=+HQw? zO2YOFE~cZMVQ8$Qq+}Qx{+D(|Q6JZ3Jmm~T{3f-C-(nc}9-f37^lXa2drA)CJR>##;t``08rdAA8k< zS$%OUBCINqDSO6gD0rAs<0?*Z^@br> zf%Ie8lGn^Y^exS{Rt2$qy&l8hqL2urtEZ^+<0R!E4)@Rc*TrNH6$VQGZlSQz2ijSE6*g*u;pY5#z#%^*%M zK)Hv&c&z)1f62+8Y;BLx>7*mvX~S241M=W!SgWi3cN8#6X~+3mIVB}(0f*V%SV~qX zNtLc51|}ZfO1)z`1OmaNmRBZUS+IWFz>5CTXJh`=&(a6>->1p_{1AZb+;E1l8?eBW zf>@tn0Zh;}fWNoCuD;ng49h;ELS=x0Q~$6BNz;!*peX(GJLYFodD7Ta9zcQUF4#YW zF^g(^gg}*sFw+-6{N!F2{`tLEbIH5(&FVTo(@L zJPN4y%N*H~&p;P8R!bho2l~yb?^pt~grm`gJtN(a*#xOV$N20A)|_nRFzB9i@wWDE z*F~^^eqz5?dnvw!TJ^+L2}%#yuKn8vYfVS8@{wg-7}sl+SyF_IM34eJ*Hs&zyBsDR>ymp`Ue3j<`zkaTu^ zVR{IxC>3^pa43S*{$<$F4}ESeFX!U|qc?*U?@vz;3!M<2HWs2-*5tr=VIC{>#-_+yJ zH-Vacvy@KTwke%rz^w(yg}$RPN?zJZDVcKrB`bO{dMwG`@bW z4JoJ5oJ7aTp@$zfCS7+zl~u2u@2{41Nr~$<*SSz)4N{X|iT7%y?|!Hf?^7Qt5e;y! zAB+lSwtM(E!W1T#^_}(OiJpRtg*0$3VKbi+HI93t4U7y${`?ubyk?o<5R^?k&Ae&Z zS+~h!Xz7Q$e8@P&Tp0+swVP4hbe~C%zs<8j-e^fe(j9C3&+=*tHIrD2s)b3Ftw<;^ zxV^Ar&uS)N?n3>*azkamU`!ZO^^xlz2@VcyY7!V3=^dt-rkUI?Dx59cu?_e~gsz^i zo^uy*Wl?JK)?=dr-0N?V+U)CFfClaGW8H2kBNxB3k<$WhF!2a`{U4*pPV}Q&*`+cl zo|>l;&#^(AS#ssM14>zn$(&H7_wul5FtunzKF~fhsQY&?lv^<_jV6Js?bvfh zQP6L%Pte)sLBN1)$ez;=O% zx*?LBQ>I-0RnBh$QTcd9s9L0T#sgq|20h)MZ*v>XTH;SR#s?||U1bV=+Wi7LTAUK= zr(QE=C1Q%D z?Ci|vbgQSYkBN~n1`udkX%C2ur~1Mt>D5gjKhl1`SPiD;lKb)ed~mDN@kt#Di^oHESMkpTtRYb9l6D>9i9wp3AT zV<&(FZJEq|$6ci3P#Ebt@Mo9$hRIjOq~5|~MwKb_&t8A2;YWUDb&$7jeSLkoe%-pz z2-&)!R?Nb^?o>mIKu1Y}iT`mAAfX3P&V7+r$AIP(O?-B8vVhC(r%wth%7&h<6V)1t zDcL_RI)>_qX(9Bq$m^L_2?Bb1UN=9;cewaBA+@mKIh343&2z99DU(@O>L}hTA*uIs z6>95Q*aC`&Bzqjr&e*X=ss3gQLs@27BNq=>>JteMxh_{)H3a>~=u~&sS#S>o7><+U z@H;>F&j`3~jbysD@Hsb@Sk-yYrN(-i6Qp$nVZu*S$?#Y7r_4|EvAE8rLQ< z23`h9la6W!<#rB};a}L~K*$b~Gw)Yc(}ez|0{tn~bgjBhrsq?*urNx~DhoN1)qtHm zWa!tGx@alK+JMF(?gx49*9Y3|Or>GXB%x_Z=M)w1x(J$tN>(t1u`Y_X9U}c6-SsEP zO$Ivp?6;Xo7IB9G{VY$vA-Y`4S~#gWO+P9v1?nQLDgXM}@Z??+j5FJgkD`PRqH-7* zhM#PP^Ca^P#LT_WvQT;|!Y`yXn6SA;Yn+XwgSwgDormG8(Ys4enrf;~$HU34pKez( zRSlx5!Gx2`gVjsl@$#r`&F6A-8pe;J$p!!D_0~))XCoKWi}L@do9Szxc4GI~l({NELJ^cm61tc^1%S1^&J7Q7HLW z`TU)x8F~NCCp7V-6!Vpi3!avimQ;O!Qv^Q_-{`Y;CPaI{CbdljLQ;l*3P zl6ic#I|;Z3BsLqmfsLW3CwJS}pyN%hd|@@vs9&y4|G6=`J4J)D&Su=TFP_1EhDMD@ z64v1I`)97_paku7eMs;#OB3kZ@W-qlq~mgxLaA)b6KED&1tWJ=7p#Hep6~8ddPfn3 zeS0p$hS&Pn=d5U*JEoCQ;b)`9lAu-^-%I$gOGecl4Jj!pCFP*_XwaAv`yw%xw5@Fk zp#7#@I%QWkJuSeeRBqJp!?iylAwuh-c4xQA{M3a>CNY*fE>n#m@Q0MYvmWY*dDy&aggK*A2())!@dO6Jr1T(NFv2 z!?1+y%>C}}Y1K?2TQR!snZ6Z3RT%(*wY9a)TMDC%AuSOPex4?0WGn&-ba1&>Q6hmz z@1=@dJ9Y8PwCo`X*Rx;Y*xP(CN8Nc4i2C6@7l1-(_(iOS4G5%|Bp2RNT)dso@iqd7 z#vJ+CQZH`9TZ{&m7ue~Q(3LDkF#kfF)u!AZX@W{>zfT(*^;6c`y$+43BtgL^7l$i% z6qk#DfNs=V4A9ZuV_WJlKX-S&I3SskwGg*+X?dCE0Qf+@!yjPL{@;KJ2=Co*0}UH0;CMO+b_>A(qDK4qASRc z-L#EL?7ytAJ$QOMY!p=d%(adK?;hiP(wiJr-j*x$Y2bukyL>!dBj*kcY*yFq8%^SL zBA6NJ%Znhiv=(6dsG{al$Nu*#S{_>uS4iHHIO;F+BKo91@x?+>>EXmN3nZe&xxUEYFZ$@s^x zNlGSntn)MK;}rQipO4_hJ*s3bJyvslMWdRNwh^@s6e?CE#@I!_|8q63!V@K=I1Krv zap$`g0}-4DZ;+^SEBog9mPY9xNs~ziSgLisp5-mG@v99hgI1k#8HrVRdOPXVtqS6Uw+z_Wx>A5nj1PL=C* zU3Yq?rUIx24*zLFY#&}e0gD7MY)ov0gb&J$-ZqT2Ue|`r9hBu49SC`?IUq3(WjSMq zm&A56y-zP24CP1PFI`uiCRc4tukhgZ@OlZ9L&mD!w3xn3r}(vz}6JQVZen zY0qR|90->};Qh`g1>Hms4i#Ys7IFk`@fEzw@y)e921VRU*Rhd``*6!QuN3Z#m%4s? z!M_Vh`JLao-s;@?1M0}Ya{Ku_g{9mmlbyWeUD3P*9Sh&z%eVK9wuye{MBbZH&%il0 z`I~2>3iZW8+**~h@vA=Vq2*5O^*mb~&qiTWQ!}2P zi=9hppUCnwYKe&xCXu^35rG#Oj~o)+M6Zf|9U!efKyZqsr#!C3$*iE;q}f4e@D1Pm z*WhP8VNpGNbs+Yi)S0$T@A@Lr^;CCVfk;Zo!^x>iL16}6&ty2S4g}h1lH6xZ8JPGo z<1ciyk@&gBs#i$ON@<14v|(exvhQ?2sB>3Kk96V#n;Eg~_5`*&)fy(U6N#pn7PohnG$j1G zj9#5!+44H5RbT(CLl7?8n#y2Q+1$8vdJSuAdxHOL!&WN0Qa714+18>)AT*QhX0KIk z^6Muj=Ys@`Tb^=bXIGoq_LXt^hWYwDsi(Yyx(CD}^2-)HNbk67eNdu>@ZbjNuvM! zeal?w8((J_!1^Q#b4CYoy+O_#%bg-$BK;`)0NW`J7}Ni1U4MIVaBz5V5%auwfu@8B zQe^^|JU1(>1fSk{@Q$|mUBZQcoQb>fac4G$`WV z-w3$={+C;z!AmZ;p2tVEHn48)?!$Jdo_2*+c;0FIQ zhJWkiU;Who=wz7aHz1zzU;A<%nxB9FiK(3?%ZvYie*0(8_B#DLU}jS(KK~-R|LwmI zph$+k|IOdlaH*)j3*dep?)%z$!bMC7jOrSJem^k9;c^2(g8Qj_QUl~;D-!)bPNaA2 zF{}V6(sh}~41ASkFp>)d%;2$vlVbTly~5t~f~$LY!e zDkB&Z)D8V%3X%ejbvAqyaT@>`@)Z_4Ht0zGW}m9hmX9K|Lsf7MzPI;7^_9GWf{z%@ zJSk}P#l;+Xgo}qqdAf5$ef`D7g-p#uP^-j}Ki1y?#Fmzl{heY)Ld^g7DGv6ffPX6} z8K)-A78IKbJ!8%m01KVx;3@%N`lK^+@a};9b7D>O{WZqh=mV*WZdhXDURIs0K0ZQo zyFqXJweV?objWdiZwgjSc@vrLj$nG?b0==EagC6DDs6C7C6^kI z#~48L(15-9!}G8tYNVBSOXW{c(A{d0xHbGs^}Fm7+vti@0e|sYk9-h#rLux(1M*c& zn=TQxEql8l!;f=viS2j^|AGDDo!e3VQ6+PK;U%`smtsCUA>oqR^~oc00lyso{+RQ$ zqzxlKmxIRCWP;p~K-8KM(=BIP41VXL{&N1ctbHKO0&`wSJXm)IPtZiD<>IzN?M?e~ z2zw;tJ@Xb2w${kH-Mp>%9P%I}b{+?@mGjK{3Fvo@_FCPP*n;qpX4VuHF9ebC;BLR!N}xviH4>U&QyPy~bBVb)K-bNqKY`L=dl zbG`GpB+sBg*GlzLn=LeoAuM6N>(ib7nNLf(N4TtuC2}Wi1@DW$C<7hrxQfipC9y$L zMJ#|{{PybMO6Y03!Zg{6G~8j{8$7$^M!ws(?%ob;HYr)ayw25k`wNf zCo0A3QH{(U7^NpzEn zP8uDh?74U6=@#900p{YWFSlYR_dbM?Qyyx@c+Ho~6&IPaemhzc^}wB!dlBAS`Uv^G zV`IKK4S*XQM)cl+ZGC4)wa;rc2A#mOe-_*NoTJ3kalKeRb-PkkNlUQ6au32z7#~VcFN6a!l)eZ@W2rY3 zFGHT)943S1nu-g3G}j#KddT7!#O^}6@>3j9+wj#8=1-ArPXYuAB{H9ePJLUKw@^Om9=R`q)>}GFpS~Dn><@X#I1;+GIVOlNw)a zuCOz`MSqI%-IF8E5jLmrWYPGn-->x91E8}Ahz53w-tkh_n2m-M+#*mJghp^6efx@a zv}d>{Z?jmoVxR?!kE!CU)1O#Y&{Y)VILBPV zn2zx9@VP8SEDBPnjqV21{2y`uioa_-`B-TUk%@0!%P4wovN8SrQvtcn1MADJ*>_W#uF@Y-0L7$d>7^fRlM^skKQB1jl3d{2u}2KN zYM==fUDRz_J%okh(3Q!!p7V_0fV=}fy~~>qYoXhmv~uF8SpS(E3VqK*TPtyWsTM+f zb6_~$q;*)2dGQnj*OvcWKk{(0%mY8^GHXe5ur1^wjpb?O4*-bY{Fy?eKs3Pfn14$pAwZtwXjub$45Xi4ld!}_-eDwgdD!e8X zw;@!n&6+Y8;O}q8!G@2KMFsblxIbMF;qU^42VSOgl<*m%&gTY!AaVLu zuH_ux&H0{yR*83;W~v#j?ore8`>ptXtNk}%p_%VQ0t1Mes-;sbNmx&@Ku0)K)YQ~e zRLI*~lU(P~U%$9`dF>|(FmdsKAr1mO%b_703=D6rPNQ;duiXhWbl@&fXIEFCy2Ovt z`90Hrb;2VLcjFl;Ks^8d29y4+i~n={{yUYv)bO~tI2&0|unvnd?D-(Is7Z(=@xIE5d9n2bk=S`c@~2 zlDT$VWPB7)`&{me^@b;-fxMXmJmWU_C}KNIzo$EU0ooF;o&lx9#c1#j0I)%b*asec zbMv%PBTxg_&(AMk4|tXgsX)Qt{{(nbs{n9Rd@Umrp? z0M9ne;OFx4^29`SvIZS; zddVJcZlz7S@7_K3g@YjCb^3skCE~^z4`Azl?~26JS+1C}>+0;>dy9Pqa2T3g3k6;P zhz-()L?Un8yr3+RS-Bl;wf9G_DY1aa4D<@0D=j1~)3A-}_s&7vAQbJ-G z;N>C_k;V{OVOK_A@fjyoz<|gnG>dC)aoGtzLEFhdKX51iGBN4v*Q@L6wi`&*mRC{p zL2Icdi?y}2fx*HFWleRpF&v6f7X+4Re3bgWdWK45rowP{bB+37tKIqJEB`{n{M;OQ zLlB~ebmoHg6$^V>ovZYu)v#hCS{BJ*HK!@(D4s<3V^fheiFq|oP+@wS7lW#eZT_)wZ8p@2w{b@+nlCUNO#GV$on_(oNheaGAt zCse=fz+2xK(~%R`NgN(&Qe0Qby{pYbhI4#;jMK$u_xmG$-sJ9?@2v&e05tb2v)kd; zfL4$Gquk;0{mjL-wnc}lF#Nof!pszrcM;L-m~`(T1I@{LdlZE9^*&~U=D<6$*Hei@ z_owUnR3JdC7&6;ZoZk0)JbyzB`OuL{op@rSP}-#2z{1v6ui}Za$5CPh7<~S%n$bmi z8$aaDH_sai(huhu5sWcYs0M=gI|);B#f!?yN>-hUN;U&sU0ro`smU`7OB%SeNrKCZ zn(mGTNw(SP3?7^4KVCHzMY|LNXO+2_YmMlTk80b7qpwIFhc_Bbayl!b14i-OTsLB) z@#C-eg*9)@(jxGASosDJe@bQGwb0h(bXE%SxXkH zWnrn}ME>9ZF`9hBkr2P)?x{dTsg)ddQJmH)$%JEUd3!!W`KWcOpZ1cBzvHw!yK9N2 z2cfXrM2QpO0hVdLNr{DFpF8RGG`wW|&?y*?~iepH!T zll0WXofAMk6_lXs%mGOW?ZRW_mheI z>v?#2{Vw*ek1qJBEKD)7MHjjbNWsBq!lR%@HG79=I=a^1nqNs?(7WO7aR>52*BJSiGc64+#Wdo)p?oUZp4aIWPm?K1d2O!M z_UJEAWW9sHjMHklRa;wHp6`q^aB&@tbJ$44lb!h{vt}Qb8H01K#iBNJ0Yn>O@|N4} za{j=85cWKG6IZtnI7PmNY7OB-qLi|IT>}`2W%gO z6tTVDC1W268*DZMEDX$l)SHXXGi0}kZ`++h>Z!%tSAVt_K3d#Cd>SH%(xiH}B@|cf z<+?8C29N*Y2CU}Vn$l?L!O?i@55U%FWwqR#nBL|Q!_-3n-;8Y{k^+o7P*Tcc3aD7W zKVN4L$W4Yvrp?Xk*=WkM8=%ysKUaU81uSGx7gtT?YC5JrGQ*=Ot*K`SI}7WRGdkC? z|LDj_dpl=SS|UukXHmR-jwTo@|{Z8C0rUoIoo4SQ>3sEyLLN52V0P@fz2y>1qw5&n3fSA#f=QbvZR3 zjpjR|nh|i29OVY%F4&08mPDL>8~Ev>xZCzSTCc}p6Dx~-CQFzD2n$hCP_QJ)KPBEh zzX51r08|ikn5~@9sB$I7KJ!Uy*t9DTu_SMkN%Df#PZ;jNf3eeTf@u;Qy{;f+kek!FOeUCRfS7+x+loHtmxjKja;&$Ie);SyzN>Q-&EC0JybF z`6*(xOAqF1ti21dM`WxXu9yZrC~nO3+(lkvmk7E|k*w#u_JYZm$Qxkawv}mm!T-RF zS6MsFseyeQfJ!vtzM9uAKKT#0t1S1{XWu-ce2lJVV1OOo`Q^(Om6hzVg^m}cs>EEr zv%kjkO`>(=C(odFsD(m>l)ieCHeY@op6Upa@8pBky%je=UZK-cvn3bV`uaLB&45?M z_8Wk6ul<2{O(J`A=F|b6R_8Bpu63~ z($x7K`0^{YEmd#AT%li?;+iDg8hLT@CwIRIf-7cVoQ93BF~)b@@w%3DYmWPL>d|OI zfu(or9JCQD$b#NosdnhT2MDHa2#bnJUd*ys`y?_cG5Z8`Wfs|PY$xd^A551U046?G zi##zCI2H0KO#)9R?3k`sFnI5sv^0SDRtpKDdmvUHq2AA=$=x#W&CSe?yH7?r+hJIp z)IZPs;6-OV;}0>sfEqN<@hjOB)PD1tsQI&x@eNlyB)ydp5D+*oMsskm^RQPA6a8rq zB*)XSv$HcYcGsqiS?CF{vkwF5@+S}gy1|!Pw&8H66ZV9Z6rI3LD1|8tV=(i36%|ev z7M=r1>yX#0tE*!t!VG) z36w)mjxe?U7dPwwpyy!zTz{1}F?e{rxWP z?zNSbuUJ@sMt(6BsgLr7^kJF}E0J~Li^kV}tgNiDG8*j#E(#uwC#&q48^^kWg1L$> zJ=~uGjIzNG6Ol>>JFiqrzG?+(EcKq)y)s?2*gPyPgAUMQ(!F^@XJyq2@U|&}9OkOE zd~cM(rPMZUHLlls*=cC9nwo?+8(Ny97zxwT)8DfsNgO-G#KbU$0ZX;Sd^lde@rU)v zmD=}V3s$fo&C2{&zAWM-1&YzAJsJa4!&HDtlmBLbmPDfcvd*J5*j)3;`A!761SsNQet70sx$;ls{J9X~|Tdc;sOtTJ{CzD4AxP0k=I7&f zFg_vt^r4d!v*G!E(oWiy^o5)!0pJ)NQsTA#Rn%Y7^VOCA3qr^*z{Nb%n@ksIB7PR; zQ!jF`{-Z-;QF?`r?GK=e=?s1^@(j9`SLMC6a4#|u+!e8I+@UoOs!Rts%ENaiG*ar@e}Yu?^HKn>+LB64J6BBE?p?7EFW7K<;>6G)L6<8`-n?kaePeYA#dn+Y+IX;xtRn3{h#_5llZ-`UWZU7i5KgGu}Kv5-#8H!^Ee{p7 zwM9T3@DNyIz32PJFhPy<5Xb0o(ZkphB*_(-GYjMrFk^YrO3kY&i>xR(6mX)7V&D!9 zo$L2mtB*|d;b^Krm5HTjD--xVqxGAPs3OohlAmcxrLR51S1F4!LHgXBc`0_-g!v)C zLicd=V)18L)Qq1CS*55G<2x9}!@Bzz^wp)$d|Ychn2jZF5QMmt=_RB6H28~r7(}{B zi=E11beu;(Qq^2V$gjnLQwPzAsiNg}f)+{v?w>OCZ-QeKOMmPvOyX1zza!CB)F+~j zLW{B^-r4FnJ$Oo4+5(!+#$dOw)WaX@Pj}^TIFs31S_Bch)_ylN{<*-5VER+84JK>g z6Z-gR04gMh7(+c{_;+X5uPRR#9Z6wrSzp7Tys_;unI7+YhfNdCJBTx-j+PtaLU~W0 zLT~TiB{b}$WE?~S*05448JJ|H2oun#J&n4?a3oiLbOofvYX0Ogziz-gFc?MJ4smrr z$H5V>2Rs<;JjBVkx9{I|qRrTpn*M`Ku2!zk&({4I_E ziEz0|=}6PF&N)Nu45EfYlh)Yf* zDf%3c8%*}se^ZLb?ePk%0ocis9%9L{Tb3%$MCm|DP4p~eySPQVw#h*<5y6PX$tX!4 zrxF%j@ry~a3uP}A=}9TXy~<7h9uYGqnraL#?s7v6kYQStKZ`!{_h@ zTEkxN2FFeVx73qW+MY+#1NJgVThOF`YT@chdIEX4bmlEZNUg zy&f+s^}(Z;*!uC&1u?q2Up}|I*-sD{YtBR)q;IfOo6^VVp)yJ)CC#5Ex`ivijRSwc zAk5L@z8!>$gP*2#r5mtZSs$kqdMFbSKLUy(4I(+zTH!u_&b^eB6IGcXq|vr+`ohA^ zI@5?J_P)74N}PI5fPA>u;>%0JwmH@)OOxkO#X1x|D;`MUohB`(-|Q!oKuzs@Z_q<< z59fsFl1|RbH6zyN-d0roRKHnwBZ6|^K!9V1Bp1r7^$2C5_`Yz5U?oDR_O-|w1o5#@ z7IwJrSds>vMlA1}3Z;obeiB96;SwLnMO=PzbpC`-7|5W3kO4g!Gm+!m+84i%AmGFo9c8 zMW<5s`K@~ACHV}APXdDaVP720=eQ38#DrunRZRS;FGM@CiwD`Gd2!shJl#5 zbN_stFKns=G#xkj;(X+`Q`@pj_9BBd~j;HfG?)DNVdK0x;FKeOZ29`gtSC;A}e z+nC-uQsjP*aydNuNP1lry-j3xNz5hCwaH$!wlLb~KR{G%3m;3CeqnPf}Ee`Ynscwzw}IW8)(RB+TL*=obpR% zr~Cd4cI1#IR~yZ4FaNUiF-c_6`=f(9Zu;A*!?AhBFMWE=9GZ`Yz^(RJu*{#y-8E2h zs+G-Fq+_s4lbZ+E^IFLR1@knfZFofW*hrKerjw8TRxBK+$QSAFO!#Yy>l;u)uz|>V zET!QJ7KJF_ff*wM=CWxSj)5iagJWvb?(@sYW zdY#j?7RSWNs{L7jpS{<(2Xop+%^5WCL1Q}}>4X9dE{+(b-_wtFhNoWLibB4~DFg=f zgk#XF9+=Bh13G;MlKZ^oQqkm3TE~#@Nq9*jiw`V#E1Fcif4j*W^6>KJ0s&r>tbA%n z0Dy`I^T*@i*XFj_hZX=Z;s0Y}F8{H95zzlUjClUB-*+HB?9c<3h^uK<$aR8a|2cmp zC#UjZ%T38v@4;lLE$?MJIvd-+Dpdu>1>K;wPPXYjog5jhB+=0nE~b%O{RO#KsFLd0 zY|y?MmYW*i(-qZL{pG&x0i9mWCx%#&teoYx*N6q|wsiD(U0; zT5Yl*=)Y81@}4HvFAYz~wAaP4(M4?@(&?JC!k%ic9{vGQk-2k7-oN8AfhIN`=-Ok! zHUPgB7*yx9M!kq+RvaM?kO2L;$5nEPq~!gDaLSDBzA_S@ENW9G{uC$Su6Vis2*2-3 z>q#GHhgAyZ>a_0}X8eUWMp#ZTU~VEpEKteR_S%;YtVopK>~I`xcrPI2>COj?9?Om4 zdzxX@_RQYjD>_6wFh$bI;G|$tPfB;Q(6Z^n!U{sB!)x^(eDElI^Zcq9NATI%;CtXu z{qMS6`h%~`j=GsR3e6@fPaz&lH-I^d1h#{%^?vTzHiW-aJ<6e%ScqqI5pn!A+F;VgS`t3NkN*i=iFy_`&PAB1=IV_6}z`}fhSYw9{4~v~{eYVslqtycZM~rvWrUP3v zC_DZrzDjG{>S(8*^4{n#xOz6NliA0DtP7<#&#~*FF(PbzamaI~zR>`?ry1eNsp9_0 z9d>L7Qr^;BHnMKpkz>DNpTtF{F+ZDCmJ*GsZ@*e>>Ey;(VDXF&$_CuK__$vZKD198O<6|EE}i#QJvF_6rp1Y2@s zNkZw&L!mMi>%?A-Jz}zUxpHz4SBWZ`V?@hEkRHIodVpAmJKLmW@r}zRV12%c5rI%^ zrB}`4U~EAO>BRZ2(Zkfr0CnD!{1fn2iNnW5PeK5OTh8BUxxEmhu`=m z=Jq`M*PhN6h8bZBHvCiu2lFMhGmiodAx(|7tW1U(+Xy+y@Hyv`dn%$KiaW5PCAeJd zeLWt2cDha$It3yVWq7(AWUqU!H!EQrxZ=?N5y?IiK0Kz4hNH|M?W{SQv|OpZNCu+S zM8~uICemL=^lKGFupCtht1g$sOC-(NR#cGsld*Gz6H#GwR*} zD{*uFUc#*$YMJyXc=r#O)dC9JGI1LP{k`;2LDP*Z9lbJnUK!JO6rzyqwJqGG-x;F@isWXb9ujjm0Q&HP_o=prSym62D;T!c5>`>>LfTlAlF zkc0Bz$*nxcUw4WS^Cll-EvTMXI+f@*Rj&YZY^6)Ds60^H)4rgNjllnAO(Sh{=vWsI zo9L&n_-cA!tHTuv&KDMTz{VU0ehqFLyqV=AXHz`MtSk*2yeA?S(huuA2_B9b?J8PW z%WDU4{Qli`F5E112#97Z8VqK$7#X^~{PKbMj(E`^2{qm!T1n6qTxYlMK9hUTtHu&@Fqf{NbRCW>x zhv=?W%4%J1MXI>b9-|SMKj>SkgIcwn7;SHpWWuy)wvbxOsCN1&3mPLMHmYJvc9hI(jTKFgE^qUt=WOdZzm(@EM{w z97_&Oc;Z4chVP;8`m}rrq_L60;bncwZD=WK|~jNaBQM56N!R|aExP+UD%b#4w&1ISlrN^8<}a3P+2V~ zP#Z0w`^zi(e71Or;Lb5&%V=*De^@etHR?mX(c0V=0t>Ja(KQFkl?%N2Xs*ieZeCOOrZLYq=WAouPs1h1+W8%X&R`;#_J@<9@_*a{RuaXf-}Dre_H)CGi$ zL~aA-VY)^R!QkB#x7|50$sa8MH`EAcQw7dUu{-)DPTv!LPOiY>?TjVQ%i1f5akH%h zDJ1PWUJU`l02+(gi82)}v5;^QL6OrP5`;W)aSwpSwO;;kOg9-yw^kHolFTEMZvfMHLTWpA=1u_!wm>pqN?X7sAh zJD9%Lp{<;QBLvjeRqtJ+)YQb{oZ%q~`TPmcfYC908iUq2 z_$=}0CH5}9nB&ciGmG3q60mTN7spnV8fdv<5$d)3<_syliHi%^`*oe3Sx(2ZwBZuJ z7+?v3Xy<|Gw?aosDngYghzEE8;SH*V#_@OfkhlDZMxHU&hFfv#&$HIV0sg~Q??q-C zGb3hkvSV4S99%*&2JrU1>!U*Z4LQAJUjTp$U)TV+Q3!x8-q<{(JgOcQ&PSX7#V7p# zk(z8C>^an9ODe30i45fVp`Ow|aq$Muosu8yOoJ zZtgA{1x{btC;-lQsgBNjuC%A)GNfP2zVMphd+IniQug;+|It_hHuHqmP2Qjm7lhmf z*Uvh7&Lv+oe>yP{S`;1LI^Y95unk-W&tX(W@M z+}&*d?rBCu$cgr3WOgHeykOdDcnF;|0q$EZ1HX&wYB448;vfz((d?ZpHX51s?e`{% z*Ae=MFYj2Uu;2F}iVd;khHa{FmPgi=tt@7nH@2^_ND>{{swW?K>6wLsxmVj{ms@?N z{5GL4)1NscPnqw!MuNe0;fr2(!?1XG{lbZvw%uZ;~B@@gXY_f zvyfcmfw-Zp@{b46x~`cVMac-LhTKn+c!pm)&jnEukp0+?yUyq1v7pJ}m-^Hl37xC8 zw_38f5z_UpzgykR*j3iP*}YEmA>bVW%?qOc7N!UB>#Rq7S^ehM8UeN*$dG}24VguU zXKw2t`^o6N3bfR6Cgtnx9t=`=`ljZ(x;t2d9YFPOiegeG#KoRt$MsIjBbWlVLI93O zII>2f9!@gA4_*GZ5e#YO$)Q3tRax!u*Y*IfI>HS-yC3`u{kM*Vva5ua+?Bq>h7pQX z%D>0;lh<+nn}JTFE;+)j^QjaC4*);#M%;u{Jyb9M?ENht8~-R3t>tpL=3!wuSdbSo zc@8~fE?K16KF^QWyK^`Y!HIl6IH=Dqpl(48QNHM;SKZOB*SWmb~R#DOw zOdrR(pP#q&Ri=A>7q$8ETe*PWJtg1G7c)A%?^pTZV5*03EJGi3&KXgD6dV0Sh8qPr zN}h7)pxin}Yik&mOfWoKC~*C%IEG~xtb>PZ4hCi8AfUS7tlT~}CKl;hQaaB}qqWVn zBA$%}VSkcOXV!5wjp7bb`L$}G&SK8%bugTL=zHhN$jFAy>GtkLA^ZAfX_ke$|7=Wu z$G~jc`5o2=3EGb#;;jK?g;mnZ}*L;5o8^bc7>m5mE zyF2u+hqc1b^kmD&{}tmo%7D3o2r(cz5Ia)z&qpGuI_{m+uAF1*;s*aLiHrypjy>D_ z*&qQ(nBT@c+A$wt9sYv7{QFUGb;0n>tK4rK<_B2J5Jr>sHxI^A+Wj56Lu&|mPl69~ zk;jF7TJzrY$K?OuE2I@5zsQ`m?(kq&2U7d8F)~lA_+~a*3;6`m%Uy#a2t?Ce zZ#`43#6PO5dh5K46FKLLG^-YYc=$4%29IU+6{USofzW)Yt%HkWrq!39-Rul7_ZT5I zwtp>WWr@mK652A~R{x3iv z+=eLrDyrao-HHazR7ZeDw-H}C?)9qx{?Ja2iz7;u%tZvefFgIOA(Q9-`NwUT{LA^z zA#!%9#0Oj;__uffj>QL>%=}?tb7}#8#~;VliOUNM(a)EV3Kj2bMsgjakWPDbRc;NFjF=bf5V4POC|4)1|FQk5qb`fArI>}Isj!=|O1V^smF zB1g!<)0hKs9$8>98TyYlFV69+lrd2r3k3&+5%n( zSadCohuv_(Z19tv96uP@p!q=-ySKJt^Sjjh)e~BQm?^srxXrWhSWpjS%)TKbJC;95 z5K^eDa(&F)caF);y1UoL3sW&HM_Bfps`~s28v2-r$g>@|7$GBQb+F}yJoB5$no$=C zYUpmA7_ZSxmIP=&VwL$%&@{%OZ|7<4t1H#{0-qt+GRL#1_AE=T>R?CzD%+)UukGgD zDPW;zm1}B^{JlZHI!GY(_VnhdUuq%kTzy65p`hu@Y^k|tnPfWJYNyI7eNCG>(sI40 zfwxxGn7a?V!9h~CuX~FZIB)XF}u)lP|W^JW7(bE6``1bzKU4V_! zntLCm6tMensw_!Ral{{fIkzQZBXw6p_+C5s!D=cC9q+)=CG7)IrEfDE2v-|Jn)Q}> z+z9#{QNANSR|Ra0#j!&Do~E`J+|Zn_ro7(>&F6Hk=vyzAhQf~#nRz2RrQfeblK+BE z5vWcU_$}C}m&Zwe0DeTAKe(U@7Ioz)> zFihv`Z_cYkSw<(3H0cO0mqidZJkqYFd#>cP1CoD`w11D1ibOui;q2Ji4n|$qEcc&! z@G0%TPOZa>iN_;j*HhAP$yClTm3It`Jr<;$Gj3}SfBW?ADjVIkOLqF`TA zbO2G=ub$2C#N{9geH*RE1pDQni`a?7h#RyeY*Z+k4IM~-1fazdlg%hyUTgTiVgEqMWxq#tW{zUn~NsKHFZw6Hlz7$!wkFS z4sXk*SG>#$wyB4iDAWTNX`S2Wqk6BW`tvBpj1XwrV^ZmtLn`U?^!0+O{g;~Jginwg z1<(1*@hhoYK!vMAL(Rs__E(DgDuTtpAw_~E;)}> z#dk>Cdw)(85RZ4TnLP%p#VJeAegU_;vqW57v05X6i^h4Lp1oO)&@SlXT+ zR+6g?Ymo&P$(m=@+B!bOJAEEsu{>SF;ypbC5^6s+Xj{5whEEnXyXf@#rq1+sYQ2YU zarh(W*}?1o{to>0k>>k*GRn<%+VYKhc1C0ZFXWA(vuqA{l>M>JvA9!Av^VF6(hafo z;NN}(p7VyeP3bAYELByf>&^FqPHDf8Igqq4d1erT?{!@T&li?G*|Z0jwvAS{%t4)J zbDDVWFFI+zOs2i2>ixPA*1_J6HrBcw_o9ljxoO{8A7!4M^PxfYjwzcDr&EthG-%-3 zN7q@?yQ;~`3;R+EhphJ_leWb>j3TwUTKMHAmzSD7D=P^7?QPz2^ZfNF{zWdvZo}<2a6!(Cdm%gsZZK)2_ReH`HY>$MtUEX>2_N&O?+!l(UWTFgbaOu^fgK+?+GE>T142 zXUVUUg{vq&EdXPyb`z<9?}_qdctMnIi+dQ7#C4*)!E>IiYK&J^1pF@90^a+Pc-^ZL z1L(+tMNyr`v(UEuJ>u~%HjI$ze434$;(}yp?5Cf4^X~Iczn(q;>=g|PwVkZQPZQ= zyjA@AWI`s=n5PmW358YH{nhx!$~!8w;!*KD?ox+(XM=z2p2SNfff>@PZ+|XLJ42Qj zhBvM$$bWb|9Rx13Paze9J<)Ww*&y4Aa)zB6oT$L;we88)=Di^$UO^yZ-))Q&J zaC{q?=K4nMd*yyW=tebY-iP`=L=;zhS>4{K_wpbZ3436E=U&Ta-G_$9>cHp(I^9Kw zJ`Y*N&AKtxsgtL1Dn_ch!z)ex=XQ>qUcO9S`?BrBS+#M5{9^7M*S4^&t-RiooD zztH~baD4t}6+PO5u!pLAJ-ur;h5atGk#5)Q@KQ!7<)9JQv#_d}>FMEBYGJT#as?IL z#SCn>@S1*cXQk1t*8Z%W5DqP`NX+3X*CCm?BZPSyn z>P>Bv3&z)4XLNkd<7HIIPd1RAxD7Q@TM@MRa^>ZI3|!otNL%jQ&=B z)D9-^y_>X&X(rX{rY-X0j}9R~xKhC1K)>81YJ$nBvI z_hES8UO7UIc1Fv$6;(_t+5gH~8x?025gZRZP;@-32#EpqgzTq3}3b<9}K z%rO_3?C@E2WO~{3nw$f-(Tz|9mY#N zO_Ivp4pBRIX!BYeUjX(-lyf1T?aN1&5Ul;wi%5`Ec?^-ZqD7db%LtXE%v&;%b@_#a zG)1NHIn8mB(0U9LXsF@d;G%47^i3h*^e$*n)yJ@PacA1hDzxG=QdzTyZE|^=Xrb-zJ69zlNLY+4KcRd{m59 z`iG1rZFG!f{8d4o?}cP6fi;;=k4=MT>k;nv*mA8h@g^=j*gZ>#<2a$$jz**in9Md{ zP!%(h7zZdf8JeG)cU1mpXYYWWf1&nFC%oo_cWg8viXkfCJO|NMwn*^`Cl=|n&84wt zRCdbw_{3OLthwt?BF<>D@wrW-DCR)r;)qgQdaO#PYqyLw4IDuhuP?uh$VEABg*zrw zZ8hU?JD&ZKd1De;wIc&P|D)V+9vxrf8FOC1XH+4lS=9}sQUU_^29`v=+A*}b!hS6|OhOuA6na%0NL8 zL7hQD*B9r6~(3&hNK&}NjrNs^{Nd7RR zqSL!2pVe-?y{DkGffMT~?a;+h;_8XOX>c+%HrR8QOD`*GiQK5suNE;`8XGQx z_d?|o{GG73Z%JT-&#UJ-+&FJJv~S@pVFLS^bQO)*uIKk4bw@gnfZp#saacm3yADIo z=nb!|szLkGi-z_3y=P5;VW@EVOvi`Z4tu)bfX7G!O1Tn5d}oNuqmZObJ`sr=y`z$* z_^Q0)Hyo3l9t{VzN3OvTU+I6+Opb*6=G@1nME?%6^SbtU9;7Bx<`*vfiybbCI4&Pq zJ%)aeq;T7TKwjZ?-Ntjg%o6%eY|T?$c)MBWZe~+M!njzlP592i07Lj z43wyG{29jtD_sRJYUekR1T2=3`=f}fniqzO!=~`Dcw=x(3@qF)RysvHs=dd^Pp!&Gg?RQEf1v$Qz9IqLXbe2+Y-k9zUo2RCLKj zr$dIRj@!V?t)&wiXuZ#PES%nYVej}Vi>#%y9Ja|J+u<32yyh}>rFS_E$?dz|rn+Lh zyUWOjXw_tInJk76tIqu>H`1_pI83~v-hnk7|JnWV@Gp}dZfKzP_xSjs{hd**?qzRB z95|07DB~>YOn1-q&7nAqIE}UTny_+JxB_LggpMmFRq%bBgF1v5jn8Z^P#Eoo!6>&K zIbM8ZBnnO@@Mrh4{*?eD);T`8*T{qrdzLpmKB zSHcntr%mS@uXd41`;Hz{YnXc&e7(qP5kZ&LEyC;7x)FY{5ab>z0%1kn!gjOn>zbf_#>u`u~_9Yu7)wTlqd)&PYsp!e01<`FiGon?`t&^X&H}h2P zS6({3R3Z5U3h`68IBViY^ai{tsniQ8!LH&Wv0>X@19uhM=Yc;+knbOyH^e4;RHl@L ziFSUS;__0Z$}{eMy`UcXugRs0DX zr1nO%poe^imz-`I6lhnN~1o^ zpLbwCi{1&T+TxkNPXI)8o#86-PqP(|qwg3#Wl>Rr%0qIMC0TE$v)~S}uPIV#vIR{r z1%E4}dmDYh@dc&4?eFp3%(~!5^s)~abGjRQ`}BV<*At<<;p8?_!E*zrm-#Y>Y%>{^ zt9cCFg}Z;F`+G?2?WA{K5n%vJsF;`-lTcB$kRBuHPRQiwz?Ms_oZ)e#k?|Hzo2`IK zKlySUQe|X@GIIb%;!XZJ?5VW!OD$T~Hlyw|Zpv5Cwa&E?Gmd<)5dD}k@cJL-{gRm_ z=w!%8d?Mn25=1d_AyMWhq2cW0iS@SFuSNxn_062VF08B+Uxk9+;3wzmHH$UTFM13rgXm@R{v6V-+vN@%ce9 zw}Z{tluwX(-zIzSby@1~FDbA(EeV1N!YLWP2fSSR8zM=s)Kd~1uq-0#h_VYJ^2Q#a z6bwtb(}q0L`ttT8P3RbUxH{9iS`|g}JD%E9;wy{9NS!+R{XQ-?*2g%sjMP8pA?0Ty3+^YR)BFg9Tepi#rClGg|AL-d=Rp zhUzpu`;WA@>>YRo6I9=r-c%HBUEb2Dx%C$dBai-|iW!E93zsO$hKQ+Di>EZZ;|%8i z4p4CS5Jm%aI&B|Ao2v7xN{^*Xj>~xvGJg-7@m|rW=HY5o7Cu9eqG9^3n3)+@S?mHa z>UxyD)ZyjxGJj_Oaj$Hr;mxOc=Rw;SY>hYN(AD$fbsul`H5u*DE~!Nml#RiiqH4HE zcIrKN6Se-fvt)-Kelpb}M1FFjYjp{=KD*xmyUyXf`6a`2er|C#GV3NbAYw73$c6XU zmQ&-<$Z*}xjZ8qh)jBWb$3{oduRF6VNf}~ao;U*^3RvMj0*IJyB%e<5rt{Ss6&I96|vu{DAf5oI7P6LbHdD6JjmqJPesKph>!_&vRJW1%4nyqH@6XuLBn(}n!5Jl+Z$`wYFUU{K4$-zFNW>#U2dLw3|odY#u@Ve7L zxvJ3MI#7qzh9}vQm&(e_YzAI>qiX%JvM@O7FHe{s8Py)aHD-I` zzGxToh;&bvjTbM*h$&s;8SPhtVE!bw$PO*iPSJ-cozyZ|o&9oZm+$78v&HKzF`XpC z{Id8hmIf|b$N&0SeFqqu4IXTK(SKaZOjnCqO|2lp67;NMy#8e6Ht%MPkd(R4Lt|G< z<2HPOicO4)aekL&GK?0O?F`a2-G#EooOR`t*XLG+jr}5F=?}y8(*Cp2eY8j4ci;S|u!5}e=ceZPrhtg^uIeS98- z3nINw>Oi4;=6~w&pgQTBG(3C8*I7sm|51_muej2l95iHFH`e_MH8b<zgucidm)6dlQu!wz#&HnOzfwvL#T!Kq|aC`>Xw|DHxR|2(?;x)YSz;yCiKj zl7#MTc$rFTF`u`vspb7rp816s@dh5?M>V|X;Qs^gPaL}Cg)vH=8u{r#%NxPuU)KcR zhzUmBQZzr($AC^5Ry)27{4L~`nI0^@FGq9Xbg}Lkrl2K)cf^+0LE|I-v9sr From 8ebe0ae6c39c7b078478ddc52f25257a11b7c72a Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 10 May 2024 16:51:01 +0000 Subject: [PATCH 59/77] style(pre-commit): autofix --- .../autoware_mission_details_overlay_rviz_plugin/README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md index ae50f9dd4cbf7..d7f27cbae1050 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md @@ -44,5 +44,5 @@ Similar to [autoware_overlay_rviz_plugin](../autoware_overlay_rviz_plugin/README ### Icons -- https://fonts.google.com/icons?selected=Material+Symbols+Outlined:conversion_path:FILL@1;wght@400;GRAD@200;opsz@20&icon.size=20&icon.color=%23e8eaed&icon.query=path -- https://fonts.google.com/icons?selected=Material+Symbols+Outlined:av_timer:FILL@1;wght@400;GRAD@200;opsz@20&icon.size=20&icon.color=%23e8eaed&icon.query=av+timer +- +- From dfd410b4db6d524a483b6865819991bf355b4383 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 10 May 2024 19:52:45 +0300 Subject: [PATCH 60/77] remove unused fonts MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../font/Quicksand/static/Quicksand-Light.ttf | Bin 78660 -> 0 bytes .../font/Quicksand/static/Quicksand-Medium.ttf | Bin 78948 -> 0 bytes .../Quicksand/static/Quicksand-SemiBold.ttf | Bin 78820 -> 0 bytes 3 files changed, 0 insertions(+), 0 deletions(-) delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Light.ttf delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Medium.ttf delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-SemiBold.ttf diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Light.ttf b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Light.ttf deleted file mode 100644 index 800531084fa6cecc3b7ee732bc66582d0f889aed..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 78660 zcmc${34ByV);C;Lx3{E|kbO_n*#m))bapn$%Dzb0L<9l}VF?L@u&T%?uH%9ZGA@XW zGA_7`-74hKmB7jSgjJmHhOOTl6hKx%8*Qk=WeN=+j!4!KSG)s(zLFa z*Ses6=UnG2Li7p|B60A%w#IogZMR+zdfW^9Ch5KY8Ov?B71HY!U2qjzj%XEjaffiw zUBJ&qR0u!nwSjk?x1nRcHT66ip=C3b9ygjplZ9H`G_#$VDV<(Q*@HO~Qj<4_*Nojb zrAyx*gr*%O{3ku9AdfF^&i=RcMfP)p~c8fwuiJ|&cP8J@S z#}tOQUI_01;lA958!>W3jo2na&nP_~mIq}ow~)V~aQUO!f{R;dkWvYh5dR|Cm%s`^ zyixinQBbIpS_0@a^@;ill6#Dhh6Jc?P z9S@f%+Tgc~U%|glY=QrpOb}8g$x`^`uqi30Nzll4NGRpq@{jPJlkda-vkDecIaLJY zh*2?syQ;46A5o9N->5die@guU{&VUj_%Ex?@JUh)lKu=$J0T6_Nr)slgz{_&f)3&} zmjO%RLa>fkB21k!U`-UMtp;ofps|WXwZXvKgiGCEzz&h78Voon0CtN0D$Br!1i+y( zOJ^wY=y`K1P$`wSWjO7a#1w!-4C zHQ)gGrCp?nsRrHw>lk3bK_WvW8*nfnAubgQ#Vj#h%n=Jjy=V~)qNk`tZE6N|v9LPP zDCQ!@zoHoqng-A;1m(qej7E49LYt9do5|^X&VgLUBgQPmnF-4qWW*HlS(J7j7 zoepVQKu@`JBOj!-MsRe4ekLG_Js5o5;6IOP138oYehxiAHI8GGY?QiN6hK09?f}U; zr|XlZUMzxql&5+z4L+s4822QH8#qe00%bsOJ9Oe^4gSwH>@sEbfuSdu*h%K3c#6oPX;{w2Z>^${bW?Gd6z z^tq_bk=Awl>1=%$rtA(#xeD^n6HD2K^w@6ULCOW99J(aCA&p;*$0)>U6|)gO9h!GT z2Mf7W$nwb2axN%|CZpUIq9lEq>&1HX>8|HRwcP6>>DMA2)zW6jo`-ysMRXHnYkun> zJ&+Bz!G?58_FMl5j!$_@y9oC*v>V0Xzf@c=?iRlnFNn9q$Kng|cX3XJ$`sjC_LGC< zSXnRU%BAvpxk?^YHR@7zg?dtL(lo7B8?8;&W^2o|8??K$?b=7$=i1-2A1%rfW=XVU zSxPJ|mSvV3EO%KRvOI0sYT0c$VENY4VGXv%TGOm~*51}y>uBp0)@JLK*1gt4wg}r) zTeEG6ZKZ9MZLRGw+h_I+d%nG|eUQE0{*e7C`zHIF_TBbR?1$~&**hFTj%bJ5k?SaN zv^bVJ9(6qDc+GJp$R3mvR1|bc(9oc9LDPa-f|do{5_EUapMpb!6M}~aUl!aLJU{sA z;G2W*4*p&67r`fk&pCsfL!2v|w>s}}Zg4*1+~(ZlJm@?TB0@q!;zM#m%0j9`MukiY znHjPqJPspbs$3xDBUKYAB^u^FOLO%#S6nZMGe^`6i<6XLRY3MSq z%T--&>ax1a`Yum)*%aO-JSjXkyd=CP{L=7A;WNYA!&ii_ick@QBU&PsMcfc^SH!xA zjS(+Kyb#h#Pei^F`F7-ok)KEYBWhq& zUDTAQ)~Iz+Uq^ix<&Abm$3>5ezB&5t==IT0M86dMX7u~fe~ms8eKICBre{ofOij$C zG55th67$EHZ87i19Edp{b0*dv8x@-t>xr$19Thtzc6RK-*k8ro7JE}lb@iXJw<5$G5ieDT5Sp2Dk%MuzB<|ka8aC5@ygbfMbB>a#l5U>PX09cX!3U{&Xm}c)RZ16r74vu!&5F#nUT_-a!txDDR-wlmhxQ6 zIhVr~K^Z&=5BE> zbzkqk)BS+^u={(rH#InQWa_U{Z%e%=bwlbisjsEJpL!tm+thPujv@}mz|Fj`# zPNok^zbk!R`s3-F(%(+sn|>&xN5-OzZ5bys z&Su&(BQsMnb21Av`)B?pb6w_BnVT}-&io+rv&?TYf5?(q5n0z|ZOM8&>%*)AS>I%R zpDnVT*|FIb*~7CZWKYj-$zGbhGJ93_+U!TOpUZwT`@`%nv%kwxIbk^oIT<;HIXC3o zmGeN(lR5jlxw>`lR?@Aq+lX$rcKf8;SKUr@JJa3XJ*s=x?%lf=cOTGwLHBFA-_m_e z_lI(2ZfI_NZgy@-ZcXl(-08V3xl40z%KdHbBe^f+zL~o__mkYOa!=%*>0#>;(PMRw z2YWo-=dJ$v>n>si%vM9+ym8+*?0d412{_55SccY1!(^Q*k{ypeg==e?A7pjT?I zCA}W+btZpM{=EEM1+fKb1;Yy#7Ci53gtWYQIPO z$M(Om|KUr*FNwb-|B}lux$%-C1JVby4mdR6SjE7K2P@+$e^dEjRZ!Kusw=B*tlD4Q zR=u|-v1Vq?Gqnk|&9!?6P8#^ypu|D>gDxF()u6iv?Ha5G_Z&Qb@b3nHFeGY7-H=s7 zP7ci+S~GOv&^Lx94;ww~iD91(4;x-PeEINqMud)7JkmC@-^jru$BvvjvU%i^kt;{8 z8hQW7w?=+8vSU=&QJ0One$;cLKD*R*sprzBOP5~y?4^Gn9Xq;m^yQ-$j9xo>!|2VU zkJlyCRo0EEYp!dryQ*$w-K}-2>(0J7b2QQsC>29Pvg2%tiW^BAQ6fYTe(;+m&-fkUGf3>JNbL{T8@^d6==oUHdm0Vi!08R;!1U8 zx^i8;&@%LM)wwQr&2r6mUFo{sbqCsr-@4Yh{^@q2O^9(Px?S!xca}TfUFh!Zu6EBu z`*5@SckT`DN8OLRpK?Fze!;!j{c37dYHVs+YF27q>f|()W=rdm7MT{4mYC*B%S{`U zHZ`p=bJrP#XI6onxG{?8E!G=3Sug(}x632)m^>waR^3&;nUh!4R<%Rz(}ZS2P9l(# zbS+EkY2?J=3UNicl3i|BhO4_P&sE~;jaF`=YqG1^wZyf;b-U{>&dGYW9XW|~$Gel= zZX+kgx)N{oX7e%{Z$2fTZ|?|XN9cX@Yu-|83>5crGWmuZK(QsANK zK9WNvhaNpN`%v8>%NM)x-+0K5(9lDeMG)ePlkDIA#qD1#{o?U279Ko#@B<+Zz5(|r z+#e1;d~n6VX+nG!X6G3Mu>u~*3w`x)mkkKvR1oEyPdevPrFsSU0bEC)gIBF z)-i#;_L#O&dq&%=ZPB)B+q5?@w%MV*r+urPu-Gi&mRO71LSrX^E2OdP!?@;<+f@UerT3~e>JGI;EmhOitEd%o)dbb3 zCaTNTcJ;b?Q%zBKqmHErm&in|sucqQIq`#xkdZP$rsBE3x2%x0a)O*Br^s1yj$9(w%60NV`6!2NN-c|!th3Zfr ztKX`6El6FWqSUX|5H(m0RZ~S2T8m)JMnqs%B1xo*{-{qy82e8aW5on9QDkF=;x4gL z+$bIrx2xC0dhtHmk$1(P#Mk06`7EB0Pm2y2Cap3=c9AhMA5ZXE7`a|52g#vwxJ;Cb zH@*nCHn5Lu5ZONcIuK@O~r)ncTq6w~E+Q7^}eadNPj zCdY|Ma-bL^$A}s7axqh0fmxzCa;j*N(?zqa7p<~EERZwB64@-Slz2jsEpo27RxTE6 z<(=YsxlG(A?+}m3`^6J-y?9DKB%YMN6VJ)V#3uQacu77fUXUBb8}dc*x_m)wlh2FK zXH+5WnqYkMr)Zf)H^_4m* z(qyd2l`hdkb`{+)4_PIPMWrkfg)&nNmjlFTStCZtDsj0SA?8UuBgrN)S56ZP(L!7$ z=ZmW`!?i*#6w73*cv#*eHpqL$I?Q)HAny`?kQ>AwUye^vruT&F>%H`Cv;|m{=(6EM4}~$7BM0gGn^Nr z>GB`Yg#8CJq5lC*$bUfN{10e?{{xz!|A5AE5t=YA9nI8XXAN2qN?O#Z{F?4e6<=T9 z+%7%S>lZZ29@D4KohRMwhc`6OYLdYXEv<87YatUi7Kbw8n1#E_9LI{_@zMj8OhP$v&YbBCaP2kfyg+$#YKZ5;W_A}vY z=&h2`?^0MI`x)?Qm4N1QgV<3W_uUg+Iw%y==GbkvLDqHFGW>;Q2mXDv1KKY0{|rVS z?b-}&0%q?W>ID9W)JLdO&%&RrCgJarXVDYqp#|Q7zI`;fQwk37A0$#S{`{LfF8?mS zmH&_@P2 zj0grGhd%xidBp5L=JR8aJ6dZYH<7Pa=-!2XJW_-xtPRL1Dja^T!n%VjS7BIfDF-fu zueAZOlR376zHO=tXve5frWpe~)*|5h@-{(qQ%!27nguO1tA%QjTCA3j*IaouPtL6$TwSbUniMm=iFsiu?YY}&2#1)A?=qnM0KItDKUY%5@MXLG< zt1a2cl`gA9YozPOLMsz;iJCyU!5p1GH(^L65~CqFU@dUhLFY@LVX~79=$W3M_QKIR z5XDP{uf%nrp%7ZN=^P@(4@{@0+~0fL;FV?YibQCh!K*7cN#$1Ea8KN*6nxxV99E?I zF|AaC0=U||U*b-x#sFMCYKbpj5;Y8~K^&88BN{W7{yQ7mXi7ImxePf-R)y4+Xp|FK zUR`>!!3;=5Ic|`oJ!nY!BoW}F>ujvSUB~#epV3L8Smd9ys&gi(!r-K;2k%&fNX)EK z>5wnblSny*?%5YCgD)=Ca7yzS!?RQ~ z!HmgdnoM!Z%)7#hZtVZ4#_1NGY*=LmIN>>n`PpHM1Z{<*ve(;G$t#9Bg>Ek;B3=%Z zm;H}YRl!VDUhA>?N#8sJG zPoRf^Eznb%K}q)P#$3cRVgpteSBV>76>V6Tn2eQ;Ay}8|OH!d_pfzEtcd&a{z7wro zBdkQJL24FOW}DFNHADJtn1AV~1_H`a9@SUDo>jIgP<>Plpe)R3^j6h?GF2~CuBrfK zs617sDgmWq_NG)-07_FmREZh@C{^XEVs#00(G{&tcU7eNL;7P%&zoMFTg2tKZ$vxz zGM*6rKlWX6q@1Xt5woJl4m1F-OzjdzwJA)YL34^-Dtq|I{Xz{hnG+` zZ{Tkcr_qaAxfgY@^<}d4W#P$siO5D9@+6)!UqnmN4VvjEx?^-b4XfNU&=VDNPgKG^ zQ7QLCW!w|>=ALK(_e9lf7d32cL)hBt*xD{bo1LR>7HR(*PJ37ckyE#b2DL_be$nj_ z4OYxfs6FU40UOSQEl-LD%TvIY{uf+L0M8d8<1abLr42S^V;RxbHK@x`zPO50-XCza z=+65wu2#d1!xfIhd*Ipu_m%h*ds|L z$OWf9h7RNOE5R2!@3-0)0r+naPayvPvQvMCj^Qpy_XzN#A>TmA6$bbo!2il+iFEa! zy63^`BzTTNoPXus1>Jwstri*DZjpYzQ^T=0C0#`SNA5b&SDo+1qh;jx4BXCVZ*#A#-m}y8*SD>$00k;+IcDUcdJq&jT|3OwZN9Cjt{uY?YtNBKOD`gAj9x^ISFX8=C~_-BCs1Mt@X zza0CNp2pfn6xKL;gQhp0EM5ohQPis~OxF|Tk;kr8^boILM%}<;RyqN$C+080wD)1_ z55SI^p`#E{pt*6)Kp$U)JePqF#oa1~Vy$T?W~4osT`s08;ug`kj^oq#P@*kagY@AK(vqLjkXzeZ7C3VDgA75$Az9)^1Z z_mB;`WrydAT8ypI5ig&d{0aCoa4&%F8e9*HKCsyYZ9eSuOO*Q~kcDKp8gXFf82hDj zKNl}XDa5ms0hfvL73^|wB}ex(V?u5)9A>MOW1zZMPEgans zF|Gvr;`!)Hd|_A#7$qJD{a=t5w-_tO<2nrPJ>U;x<)9pCy#jrY11<;dI=HLglECvH zrhLQ~!!>aU+)y}Qz6tyjhzlsXEll%vHV*kc{m7sp_y-8eZO zPluPuiSlx+z+Qn>!^zOj9?Z^6#X4O*c4SYN4YCpSyGb_5nQ|6ZaAso$rx`o+T4bx7 zC+EvHxd3~%7s^FgC0dMCtR-0eT!y)ULh*N$Ua`CqYoS+T@5ME81y+noudS{YA9XoH}O5 zz7>o0d3CHK2F$Eu#gXUM#R!^R$7=9-^XuYEv>sM*sehIod+0+{s0u@0v_yqt_HL<) zz&yy6DoRCTrY2U!sd#afN>GU^Ni0*zDn+??7A3XwtcLiV>L#wn+)6H5z&~Pa`z>aE z#$qle4|6p6n7i>{WHb)*3&r9qRU*z}j;0KAH@#IKakChYIi7y1Ki1_3s0vl7sxUrX zuBtKHvjTHJzru6cHJBk9j1~K#YM2_XMyQc$6jljGt2*pc7^}vK%fv*i7EVx?sfprp zyt{B5?d4{yQCxw&0aMge%r#wsIgPK?bnIxr47)jlkNGCdZM5(z<9yYo7N~Y(PM`KW zEW`eStFT8QaDIO!Rv>8|l2#;d5!=v*J%B#<{(!Z=c=T3@0&6qaV{ogw4ZA4rFjoau zW5#3+b|Kt@Jqq`!`>{9S0qkOU5Nn#h!>Z=PYJ>Vc-eGuDJ%-&38+m>6DXeb(0c)MK zzWE&H+rP&g+G+JXRy|+Ds^=zpvq8Orxw9?Uo3RyZL|u3%#uJzwco?(b4~aLiZy^-( ziIL(G>}1-89UE_8&&GBUj@8j;#dBEEd0XuimDoqI3;moEvvHHfRP2EmfVI>=som;* ztf>B3Y{$Ob=dnBYMa(MEUXHEkU#*x+{s8N&AL04`5s{7+r<*YE_iMaSaI3gZ?G;nR zQE{#Mi+Drr!p(K>VmaR|he3bck2hzfwmqe{@t_uf7p$u(JL) z%zFMqoDiEZt9XY)niMw zmHFj+@;&y7x%JcAT3hTDtxc^hjdOx4+Ge#h)lXm8-e|9=(XT98ewnjs`mDC;3+K*g zZd?*v)zI2rKYe;*OFO4fP*r5Bo?cIkn7Y7&+qTwv4lSt3H{{Fb{N)$a>gg9$729e! z`?i|E$Od(#p^YjdS5=1eRfaaIbZvO@i-K!9iBnKhX(*u5r+^ZBjge7ZK7(aJk-bLG zxGr~Pm2DtP;vDGDte!)UCwSm_sd(}&gQnHD=}|ou&Ox2y6x4W%)Zihu!Db1gTLU{$0mwxFn3=TgLFQBYH4 z2vE)z3PCE3@G`BYrO7rjKo!*mdQi1dtks49)kg7F8!W4JmLA=R@;x4-ObdPHV3w*-N)mp~DJZ)nF#PHFU>KXDB7-}jpGEq`v8yi?gg;YlQ z9@G=AH#NR%iFK@B*EL4MwT3`7KHVEkYidHrUa0GW68qRdU6)qa$LgkT9ZQXnZ7dtS zo^WZIZ9J>TIo_|1pz#f}8rvEd%vxX@-_%yWsL^?uKTwZXW)ydAk?k@j(b2U=X%rf& zt1YulWcI-m&#U9*9$USs5R^aHUo{xyak;IDC2}_Tb4RT63p|CvP3NWNDX`4+H_4UGnVsXHNiMd{GRrf+ zKyQ4Ye?v-7ZP2Vd+TnwpUAp|f7OaXXKv}6~&9=`nvM|eNoM)M~n(rwr)f?#&y^)^X zSp+n{r6F^g+8P^Mn(JE{W=*#>b0ONA1N2^~XTG4Y%F>J+>XH<)reIr!tcAX|wb0h0 z*Nv8XdcnD^b>7TITT1}DB3<_ddh3i<+Sh9996hC64Zzvgl$C3ZsDQ13iZW`7*=id? zR2vphZLq91SnBqL*4ilcLZ8JL7FAViZS}Vx)kaooeB2DGYQyeo3PM{iY(ZeVt%0Ug zY{V|+w9r~tI$JMjtqsmay4`y`)i&$}!*IveW-1J=wULVgL+WB97rxq4Tx(kpQ1wcT z%$Jlp7o1nxo&rNrB?hY!L&%bHOFOmB?E%U9!bC9sdYH4G6%-iYmlhn18>7?E$&8+ZZ-Tk|V6cn7C*gZ%Jr^az zwk93b42jYmq^>VAc|yZUG*wT6C~+7EWBy z30r0v49WH|5a&S)u3Rl}<%SMdHac9na^cFA3RfOF;L65{D-V8fE!SnHjiD?v10*v6 zhRg)&GV2h@%yc9()9ErZsLRZREHgp6%*N;~zmltTetxCie&_3>5Kn%oA#hJ>R3`l0cAuN({qpC*hBIFya@SwtK)E{W_^YuqeJaMvU zxK>8ZYiyg<+Ca~W7_2qq(av1ww1v&hjqMBva}&*A*tGiTbNsil=f$Lc8GEynE{P+gZ#ZyQm=@|`o6qJM1B8;JJEpt)$?e%R-Ee)+LO_rL4 zZLLPQQ3WchEzPsq>J6k((3Lz!zyoTDZC>L7#5aPC>Ql+R2}Vgq`RfB+kI@a{TI^_? zJFk5yVsgX+k8Ycue0@lsUs=qfr^5Uae#E8n)ZzR9e0cy|XuxRu(EjW61pDX-_R$l} z^%_^M1Gtt3af>>=b?&qv?mP%0*$`G~@T_5#2&85`GvZYaMgRnLXRQ5hqVp7 z{>WFTkFxR$3%TOwdwhe|DlRG?NW~xEIHFXh4S{Zob3B0KayeSF1 zso$y@xivxp_28)qU{I(h z#%1f#Z9d=QdxkOEU61})1iY?(k3N2en#*X-i1yzFV?}3-;P*^KnEsv#=3()}dknOy zg*}r(o733VBC_Vzx6Ki*xpU^u!P+6MdFk&#(3%uc>HKWj%Pei`dzFK=i!jXL(z!dd zCz*Ci>wBfKcQWh6tQRRp)-&u7n@{HPQPUpc_pk~lWeMhXGqKL(lJPPUt5-IN{4?g0 zzr{T5A2ecl5AK=g}?6+xIz|7au;g8iO!GDDPnd&g$7c?9E=hdU| zH!|nf)s28($NP8Sj9F#Ss8#SEP!GX>3}+Wf%mP0HzfIi$f4;g4{#Zr3-M6b&`0r!y z1kM=JQpv}Bu@o<12fY-JV}@6X-)ViwXZ&OE@rFg_AvnA-$!;&M*dd&`3vN5yR=7=Y z&%!+k_Xym2xclH%!`%*d6Wq0MSHUfUn+G==t^p2fisCaZY_e~JCrA(-{=ydS#=t15Z0&@{H4-+S){-9~Rc z{Oi06;E(Z=9>#hX!{5gK3toDw;t_8d{8px!=q+T-3ixBaS0D|Mfi>8S9&lN3ZUcr* zXJDs7`qTP-`eT3}f?Er>2D$j<^P#MQa)JHCSg&jc<#Oc2j&&*hpN~~lywQ=kDg8y- z%MPl|L@zhPYEFW{hMl55mJN6mhO5s?4fgND2ooHWB3qiXmz1`sOJ!8L@-yxoU zrWCI$ryqu_2Mo6l*AL*{gWCbO4Gt-%KM#jIo|iw7z6!Wo;8wydhg$;I2Gq3bWWarK#d>;rceo5V7hF7CBwPrb4GyBF{R{`0)4qi}3I{7q`&7s@yrn@r z)Aqpag4+(a6?w7;p3ueTa>envTuE52$Zg8pb-#%-^VanvAFk_e6WWRG1aCm;qU#nPq-%q5F9P=r zLmN$Kg9%aSIx|#okN+>N*boC=(iDLe(Zjxc*F6X5u_1M7SOtnq}hLCX{GG(I({Q?1xAeolBTW=P)6^ zRLX~Qoi(A;CUnAtj+xM5AzTOG_PIWQ{~qPvwZnwAnb2kvBD&|9&L8@;8TuHYhv3$_ z*1%r{cZ-W~D;c*Oz8*@rC5&r>-|U(Je=6KW*BJOCOxz$7sx+a#CRAcV{?Po3;3$pm zoJNKj>M|jJ8u2DB5>SZC1|M0~(96{;5-cVFrh3Ha+^@12~mt_juF-g=U|*a2GJ=K z$57H)93^=g?nD5DwkZI2*bF^jLi_O=yh? z`9q1zD&}&F8M@MhE|$i>jV8#xCsTD5QSRIP=*pZe4zgl;vV8%$`0 z2`w`rl11mzZsPoDw3xV=CIqW9q@QF$<4kCj2@Sz>!ywLaHE{hIDl;LE3H30cEE95@ zP@)M%0}6w4By@%p;o{E*hQ_1JfjfcYgpb7^hJV0>_LO?J%KjCbZdvo;M*s zXM&#QG#)cUA2Ok}K8SJ;m}FVw!?9GW72!qaPB^#`%%d`%a2e;(xo{uP;RHo86oPcO zGh{O%+{XP(xVZ049ML_?bb#W%<ch)!Rj-kT?NuG(oYaQ0B)NI&MNoObDT|2RU?qATIuC#(flsi`~t*orv)U zLt9MfMH70)gf^NG#n`|x)^)<&!??RT;chi?I&?$qir8hKXpj9RsKpGOX+qN&n$#)o zI5Tt?VCX#)+F?T5 zOlY$Sq3w)eJBWEqZ>e$rkO`rkq_!QnH72ymgb*X<77kr$;+C7x5)*3kLGd#XqnTs) zp{XWrq7P!aF-$iCxIr#G(rj2o#`@6oXdpbO(@cYLQKeJLWI+~_&Gxi zJ&ov}O$cqLf&116#gL>NH~OfFGdV{e^5LS+Oe+?h!PrxSuq&TE- zb_Qs0&If2hfcb*>0JEI^1Ms70%>bc28H3dV8LD1q_*u}O({PdnLI*PD41DEnVi>Cn z;PWo~YvBLL=_>YvC|z-kDQ%P&Y2$Qlylz3Qx0DI$1@@6&z#oJDB&}!2PF%y7=jLcA3rk~YvLuOWH}Ec&Cy{fMNF{<;B-##NjN|rN+^K~2Ew~*o+j`fXh103t`Yy;nL ztZ%doqG5aZM#CxsV5E*S2T3R2FrOw)eG}zHY$BOO1M}I$u{JUNCS4oscd!f{4Ck^f zigLyla_F1sm__} zm%(Qla-F~{VOMfnq@UZ?L@SQ6jO#@i>#dAhB-xkkzl^n4#^r+6lPEcrM>xMJtn(Pg z{Gd_$mZDXV&)iZtM?bKIq%h|cqoz~+%2xZCK85M2^kca!QrNCiIrUho3*bg2n8Gro zu#KH$ONeE8Qdp8aDm9tM9P+5VAx( zUCRDCSi)JZ#gR-CNh{L`B}?e1jUZT$#Ws-5a5lq#=2%}d{ntdVBANbcrumv_hA=#Y z;X5tVKFpw%a=gt&7BvGW8IVts%+OF4@JY5A8l;k=nEwoxYKBJb!wi;c2B$cK*4pKr zlp@aUp!{NV1vp5(Ofd8BPV2t1J9FqxE53lK+%vg+yEC8eax&pr&h8v5is_@6K8jNe zWBMrVEGVNmR)6hV!2LPDQ5-jl;|}B$2eNDfna@C$d?0fh$Z^{^)mVw&07K?>ErBuduv z3fA)q*7FM1^K91h3NDKkEbR*IDAON-|5pubta1hAMP+OEGoEZ?1?Oc2=ky6qcLiw@ z@9j}ptY8^#0=dga}ux944PUdil%wcY8n9m%JJBMRE$dnH<=0V1|n1hS) zF6Q9kw)Z}cYvt0!7#K2~CVJ7zv3f9N55|vW%q}k3A2?Pj<99LrQj!xRD{3K^5ne1d z@UT*`lr$!$lg7kSl0j@BO8_4B2_Kq)KZ$+VCqiML;uv$gnN#_ax$S4nQs%#u<(bJj zn#oelq@4$H#H4`7*3X}={rOWucTN+p+O zCCf0EHQd2gF@RIA+LGeBfSHUvnZMJD&}?v^IyaK?_kVk=6pX> z-a(X#wT-ur5m)J2t>HY@XqSUq4d<(d^VN&)H ztHv^bI9O)G?`4T2m?fWQNhFwaI*;U0gE*%(EL9DpQhahEM*M=l0Tz#a9*b~7;1aPM z&IO?N#6s*yW;pB7_0){1Cy`g zedQQ=25%>Km1h;c1SZeXm%wmv9livH6GrhRFq|+-@5=^>QX!NDD#6%}-A}k;+$@j7 z9f3Otw;%2!xZQ9&;ogAT0*7ZMyg4rLF1a8}lZPY`Ey{^GRG z4{ymT)F$SSlNJ=-P?dNi7Q}c@mwY^x!5_muo&SJ+TVxs7T}A#iG;$R?)vw{d!I;(T zzrg+j*gr#itfs-=!XvPOYBk^++2>Y6Ji?S~a1J{54KaV-XMpcx$P#=u9_$l=lXgrG3t>1&ckuk3`{5s=TGvx~?14zQ~29z0gdog7jWA0^tERPqr zv;P)9Wxd8UuQB`*`!C?+4eaw`{A0ib?x^~izhLLa`^E}8kW|=Iy(5{$}9nR$< zmlx2H3E$6)Zyox6-aX!LyeGXUkh}AK-ZR(%c#`qKfKH2Og1zs;!QSZSea(CL!gw6= zz4vD(>EwA&`ft65yr=zf{g9sm5OSdZyl1?h`Cz2`q4&5yHp%JxvCMi-V1F#{Y46uK zYfkv6@Xdt{-eW#`{}m}5_R{k%|8U1#{BrprlO{l8fjOh_&anez4T$68!}LZTSbiFH z860#PgB$Y9A%+$^OXNN1{R_16u`ey}5tQp@@7J(}fS(twgZFQ6n8hJV(jy0>mg*Yv z9?{7uM+p4^n)u@U+!++7`AZ%qcTlqAM(Cl7$MU6PM*F`8{HY_S=X`8nu|Ii#_I__j z5nvmH(dm${llULhX@LC^|C^A1I?38^DbNgA1ZjxNmE(eJ`w;TURtmpUF1_d#yl1`Vy#Mr~ZwUM$-^aY$5vrFt)uY|s zLxB`J430;cC#8cl;PxTJv?MRJl=O439@pY(a0IRk=va?{Efkx0z@g3XQE@CUG5F7Z z7i#Q6Odu!kT9oEZUi5(8n@DQpd%O2FP`GgC&&7uv0$P#`^d}km4%T!Ur_32Y)PV22 z??7@h9tCi2@Xa2-9Gu4=!Q-^QbwTdWQ9E~$xTd}O(g81SgAt#t3g=%^Isq*v-=pXE z{ZPaIVZxnkptC*rXacVnr|8tiqW(gbPL>tO;r|I7{(sAb?9u3jF!nHieKA7v@ZUr+ zprHh441)dyWpW%fhxJOnZj%?uCzrR+Vmq@t|L$US=zJRA{rMa(h->vx`md)lt4#Mlb zSYSEnFzOqRdwg+m^-FAwRrIin#QldamXQ+0HBu!E^kC$S^XqG$FH#Pif1jS1nLjl@ z1S)@vtS5P)uW-^7%{G$kn18@2I^o!}9*KV_dYBlzyODx_xX8pm0^dmLg^&XLqi`Zt zAt;JPZ&3BaKM5zF4Z!a8N>PP2wnhvTZk+eqfQ{cx_-Ek!^I70=9sXH33+GXs_D`qr zXzZ_e-=mPf#f0;i zFgso}hM!nbbl9VhV+PULzN-?@1X zr*8coCv4&LAbdyS3$YC+UVVip5&E9x)^A$?& z2y|p;9obn&5v(H#9YqKSo=zk2EJm7AtRp(tzFb7%Y_{Gwagj9TU>(JougWc-B_}^z|X0^*+LrX`=iXx=VuY_T!Aq zze0mH)?f-w3p<8K#R+Nx&YdMaLONI!S?Dk8kt`JN2jL&Y7HVY+wX%g;*+Q*sp;op~ zIxn&cCqUKUZ^a2{wXk$5gD@_GE^MvgY^@PSd62b68l|!kHXFrd6U}84!)0URvaxa5 z*tl$LTsAf?8ylC6jmsvM%O;M?CZ5a2!DZv%vPm$?hDs%oOC_1@*U4o=UjQi=DO@%# zE}LMs;;vjmZZ4rzE}=9oA!nx&qEbocQpw;_$>dVW;!;suD%o5rIb15;xK!+1D&5(x zgSb4BP!d;BA1cbVJ^1g?R%^FtE47K*0DK=LTnom@SRdg0t*3E5*fQ0i?ZL@s18|aB z4!*ha6V7`(DEH!>t{rk4POjU4)9+TvWtbhAh|~Ng%Klhs@ZjXYG#Sk<7-t4f#8)j& z=?=a`Yej9yqvA1?$7|wqK9vx)8u_K~tUZfU@II3JAupZ&#wWiS=f2VTYQ}kLY8uW` zqm$I;^4V$aI2AtdWHdVE4Cj&IyfHd$Y^TCJ64s%pef-?J2XpkNyZXZJutqbNB;M?FofI3NB?gN(txO0FLz5kYtZ=}Rxq>6Ol z!%n=ff#R5a*84Lkjv$2&HN(3B=in!L4+8r=u=swB_qb{VRss7p>QuDO39%33jl9os z#&RO+AE@|l2dEAq-XX}52-zhljw3GQL#iY*e8_!BSZLKvC3_F43BX(iDv7&&s9P?; z1L3ZNdmO39;v7%PX%f?J2kma+gZZfhNP}7oI^u>`mJE)>fwXfR9KS}c33?UbTj93B z?Sy*=x~80-R`r}i%KLG(23mHIM(+`Xo>lGM7eR3bsVx<$>S~1C zAe`z(v*dKI}p9d*AK^KK}ewUB=;m+p4x03#86@nH*k zp%|Q5C+dm{Q#~;e(dnsa#ZhT-GPa~Rq9|QP1Dh?gY%w|M^4awCjuGjlc8grEEY^;} zR{4P4(ov6@%6rq(&)t%quCBD5dmQJFs&UqH*IR9BJYZO98d92pGEYSRCn_|XEj=wO zJF8TdloWbmky1=FW29D^8Yc&yQ^B_2VC+wjp<0mL5sa%039>s?$C-^`vN~AZd~T)9 z9&ESR)EbA?ZaX(yvjzp*ZE9u5pqw0ff0fhIM%%Jr^+MRO?$#l4O#ICzK2og0n8~2G zxD0%@#&{#%_Z043tY&Dwc-dMa+HT_e@8XAwt%BoI{w=dF;2(>x;@xScKj4D!XtaFq z`NFmNrrZ%|4f9R>G7}#T{6rJ~kjannlpnc3ETM4Dk1w7-Kb_<6z94=m)!^eI1s&G3mvxLu1Aclyggn`Gjh0xL&8dDT`E&-yp{_{*8}?Jwtb zCOz~l-ZJTjnfQ2dPe8i02HvK{TwOp`>m7*GGq++?ff@Lkw5;Ny{;D+2F5@n0!1zR2 zOmr;XgJ+|LMcX8-S@lmX?ULXM4-V=$)8!(Dt(-wgJ=uXJ9u$+>(Vr~*Wl#6G zELXHuv#XVk^NrnxN};TU_>OOg%@Je`jSH1`!R#%D)nATwA_*hW-l%D5SrD4#p(Q)pcl^s)l0n=)+F{!O6r+t_!$|A37MHm7s){9n)zTtZen6?g6_LB6B0RM z$@y8hczrzy{l}a2^=-4f+RgGJ`=MF+Ag@=OkCv-Qh{dV)h&V~jM{yB1D5)N9PEt!F zvM&OHtT-<9FE3ai z%pce*F2tc$J3?}zI^K+s!-n=A z*s;~tvC}bdL{Vi|=+c8eq+RX6Q<$iTjfE9wXTe0mAd*YrbcfQC*tl4m9pa_sDXIZz zvDIvcvRb>?yH770&^jhRe@yFuvT5Dz;a01%#}6LeZP4_u2)(zh(H?Qjw-3YZp4V|>Ps@9GnRsNh8}`jDtwQ}#8b$p!K ztX+!`Yni&iTNXfVS3lyEThh!ga6wPt=WR#NMr#C+$@}Y0csI_;Wjuz(%hVP_Ry-}J z_f7njCO#W@&VxFtl|wr0T0X`|T zo_Se;$;FquEW(m*QO2+SVkk*~eF7-afjBRG3udnTeY&qc|0~Nx6L^0A{;uA)J31aE zyZj}K4GoFRN=l1KvRZ=ec6*eYI`_=PC~JgntrxRnDdRHZT&YgG-oKl9qMlIK50ztJ zy+W(C!00|Mnu%!J5~?1CjQ403*_Z3m8#bfTkQkPZgATenI-Ylg5O-=77ou+{BVC!z ze_X6@z)n2{4|_1~DJiuV$8k4YQiwhx1_KUsCh}gi@WsVw=}TwiSS?{zi%rX%P;kW^ zmtK0u6`uM`OV}GE$4(?}?J+mFxPIk`5i9G9lajO`YjCh8V-o9DU2(;oqq`QJvvrQ*MnsrJ;RK_N245$p_+ zU;ChrEHs=QacJCv&b0)EgaoO($oIn?+wjn4;ac>Sky1C&6KSFBF>)}9KC@F=7pA;~ zRIV-~|J-3;+80P6ztQy_HqU_W z!wTgWTyMJepHgJx5nHLLovTA0Y+9HH8o}4G1oqq0^P-N8+)lI>V2`t1>ez@+$tra$ z^#nRL{8Q+N_AW@FQTwc8H%&JPVNWH@EeW@*53Yv>U>5oa9Y+#e7p zB!l9N!|td1xy*D#O&j*an*di-`&k#xs)Me$vB{MH#hYad40|s8_lxH8hkThe!&nLg8HpYA_^)IX+$GQ;2-5u z^4aohw);ELiy*nk9KCIz2MaVJEs?;MJnBde=|xZP z8027Tbp&5c(z%q890uN|eq5qs@s$u0YuA#o-eU6hr>W|p-BB#d;!gC50<(;a?~U(Q z(D;>7&6byujF=HUq`Dd5zYd6J)7;qNsjvnmR2p;>&f{0I-_lZUOQP+t+$i%w(_dcI zP|{AD)oBmiscduYa+;|<^sjP~(-CT$pmnjrm$G9!_qx8}fZh_~9Hgyy7NA}vPNvHe z>U7a^Q3o4QDD@dMS?I$Ql`OVmeB3o!c6B%%!J&?z5NF4C%5Jp=sgA#gQ(*-o*Vc}) z@(HJsPRF@s5=b?5%(CDoA3TT0ToS+@s%vR6rH?XbC+%p7wD-@Di=MmrS;!|3?A9*^ zHMi1^imfIGK@3Zf){!6PbOZ&5*enh_YdbJG(J{XT@p|^}u z9-#v8TC$7_;6KSnuZ751gMM)*`b5GD>HXGQPI!FnNQ}2pZ&TV|8QqMo1*5;=X%%QG zOtS=sIPI}{Zc`n0zna1m)3bJP-p!TySw9frlG;xTf;tUSTp61 ztQmS@YyRGl``4Z1c4HpQuSaSfSudEEdz|uv8eE1i#%#grtUfk|jicWzjk{XN-rxq1WT{+5kow{n&s8v(hhc$6pY)v$)M6;v#?w5(D-do2EQ5L*OBA44#SqZ1VGmhZy zAptgF2{y};@kUu5^p&M0`hsw(dz*aWTE_+9WE0=$BNvVK&S%kFxqn>8BXHm2;(1f$ z>6lR0CxG$Xq^;-n`T2%l^-CMrf-joUZO3}6Z=U=;n=RRHd8209C9aYMm-DD_%7as@ zmrpOJw%^k6Ii?qaoVJeF?ZN6Qn`ivIe&cSdgIpN>;T!W?u=0qtx(W}^DA;Hk)fnR7 zQB9v*MT^gqt24{T_UbjZ{D38t9+@2{@+vYiD)K(lENV;sxbm`zMfQ%pde7nr>3F!? zpq_bES=Np>Y0o^Rm54VuL#a<$>`wsWT8%q6>Q>UT(Vx+<7gF3xGLs8EU?dZD!bm=v z)7ZjVaOtV!=;;f#&&#zG)T|85m<&SAqH(m|h0#0-PmWxoc)}m)qLyj@##}WBky_F( zxzD8))x9E9VuBnY&fiV?jqFidF(f~?EIcf#&}X;4YbX1y2y%2uNeD|yPjX_|9%3!C z{IkLflBtSS5&LkwuZn6pF*bqoa2yCvOK(5_{>?R@C za+%oN#00|S(f_@w?w%Q026q4aByLT=uC9Ld>eYL%UcGu{vn%e3qN?V$l2>g`3A-f6 z66=>Ag$tMF6D@P?$>psMYr|}JYg?&`r521q*%}(@Z|SPGJF~yAI@xw}{ZwoJYBl=+ z#sKy2DSXU*NgH#B?K9w{uLazPzof5e285Ow@JiFGT;7U$NFR#wL7d@6a(gHI75U}M zv1Y*G{JSK#Mfp>)2*zo$ZpUSUt96D%{`DHc;<#S0{#3t+Oo+4Q^F+E2R;Cs5g=9jeA`+ z$%&5SN}>|SmQ(c}K~-1>L{$NQ39Tl099~zzA+em0H=i(`6V>UtBKt1L)%K1CjS-Z; z^Ig*&{GEM78SSYm+q5+c@h!5DL|xts$gYYktSl&9iMSx@4^f)z7J;!-ld+M70|n*F z^WoexB3i=X8dky@eqH(y&IVk~b)?Z@#PeKiP>=B?v5ZO`1^=)tgo|G+lkr}pr87QI zv<`fvuDd0`uqtM@naf6MY%wM@q(zy9GBk0N*^&i2X`{>Ky9Rat|nB_dxl@G@Z^1~W@Wj-AKh~H@N0|oGMlbE?i zu%4D*f5`L^e4l1quj72r{24W=39$}Leiw*X&TBNIp0_zB&YzszKjE<3oIN{w`%dX~ z&^lOl6<`zlC)wRxEv@R?(c8PDkM6jXqA&1q{0MKco7D*E$l)~05%3~-v2*2V{0g`a zo)aN8sU8}O0`3J|cykF(Qd7W#H2Od}-ZDPA1l&RU?Ku1Zwb&?Mj;PdJd71@?@-9SA zaw*R7q*;J~2TX^>iV@(Cacf?{%dk_DW&!lw$Bg#E3MV*vI@j(4dGF<(=i{-|`}z1h z#=W8R-Q4?yc#)-7_`KNk`Mh@0EI{Dxf%c$TfS?y?69F$Z-Je&UW&r|Tf)iZ%8W^X` zUySc?INC{c#;$qPH_16`fJ-m#am7GB5p!vd3QbxSM6tlc_m+pe5u4whJY!8SZu0l)fTrZ{g!ejEyoC&EH&e##OEEn_>k-PP>0R=$N?RaivoFc8N)TT53X`0w z2jL1%W>KXF?N+mL>?{Q?KBQ!a`^w=xb{&(>$MOVpIn2E;!$Sw(IILIHuEhk&ZTb)K zl|az1`h`yCKjd3r@H`_qEC^?N!1{pfP%U=cdoUr9eye_4!i2*ieaH4&$u51@X2 zR8)9&AIsL`k0RZq$Z(t}$8KcoQ9>-+#H8~SmFUMY;(Y&vHqP%5`kFB1<5s}E@a1tW z%HgCf1>Awi@1^Q-v28qhrF!8QPDlPe{MBXjEv?mYf2Sp_NAQ8R5Y$+Cfq&GG03)fw z>a@HZIILttP76D1aakRfY$*&nIP708{gD#1YD1%5OAWHfa_5N zeV`5SG~neFT>yKa9Wu_0eb2Szfu|N|)5DGopE&Vu7gh-wE;5hC$+-yGD`FPs4Ry^l zjh^1ufBHybraR1G{>=cMcDq+KUzojP3-cuThIJs}$N!z#rA%iuCL`3B9zuN`uCvXFt%v-}#>D zPX6?4v`&8~E**vU&W`w=6TEv-C*FM;vi%OD=ILC`7e(;qi)Wu_JUcb_?2=l%`8;;F ze^Y-djJm9>gw4t;Mp_sO|8DuTUEhAGMP|r8ekq>1|m2b|Clm zUV8g!(;KGUM%`7pryqC+PhT`0GmRNfE48O_j?pV<<@2ZR(Vt4>9i^U7q?h)_4d@pQ z=#$&97>HgYEM*O<3Q8NL?>691Yx534i(ebHym;|DM(H0L(3j7lz0jiUM-Au;JK~&k zC$R%UMl9wu`CWK0U(A@y(cpu}O&MpE79moEAIH+b^G` z!Q;|%rhn38!Aqu5gFZUHq4#zm7X;NNPlG-crX4i05dm4E!fC)sq>`0_@r=b3nQUR2 z6Nl9fZH}c`#2Jix(z}{T!{^P_QVk49J(LWt zsEUjyu};AL%Wmmjm8c%+inMN@tnEvAtTxqduG!u@eLlu~Pvfe=IA%K8$nt%|bsc3* z^MlSnQU3->c2%|3UC9nKC4H5RL7M{xfLzfQI`(RKIMuy8YAfoPidJOSboK8Z2*v_< zu3GB*hW5{{xnQuOdu^}PRoT;2mnu#4mxU?@n+2Ufk#8$8<`I&GorLv9$utic7{Q3q zWguq+S`~?BxRW3^SBMYD!MwH;Ia%-MY5kCU;r{l7*X1Dp5xB$UZtNVW>0X~sukY?! z-`2KXl1KN?OkX%r9PJ3ZFXcl20j>ycQKMb4;+PPBeWwl$@9ZYMg5G0)Lhm(lsZ1E5 z$71oE=oRiQ-b1+#VyWg?_;v7kkGn0}v#q=14^i&1f}qGa1{1T2^su=F2M@mM+^?#N7x$WUo+jJ zl_$7fPh8?~l5L0-BaJOu3E8H7=dkH2T_WPW>kar*rpHiP*H(v&o_ZH;h3VW0wN*{` zOw-8e)N2jXJ+;tQ)KOepwQZ0NVX+3JyH z)w(CLP5hV(v8e--9Vd;)o5!O{=FH8*P6>ND9L%$F&$*{Z=Pz3p8`#~KIiYR=nBZikT6dy7(Ie8wrRP9-SoP?sKVx1mda4WZ{g46w8|9JF%J=2L-(n-| zWDX~NkSl)_yY|Ry(2iMp4z5UVo~_k_Sd&9$@l}d#UC+OM1oo&t8s5NYKxCevuke&` zSrmU4!NuCA_l@L+nUImB8L0D}h5}(&2N3m4F?=g5Ic6e}}AuA8<=2 z|6SM!`n#tK8{sdyjeweABj``}3mf5e-A2Gu*a-U5i@1fbO|ua2Ragl887zd;H46by zSO^;Q$&JE7cpXq0(}HqOQS6j~Imr$I=a?ImhUK8apVs_BBs1QSU^!^Dzqn7c8~}yo zpg~_gO|u*Th2@|@U)XHmC-2apF$qwuC&|~%>zB`1^pw8-fQjVtBx;mRGdd^IvR+OA zlmCu$Wk%ylBX$#u5kgom5#@Skps~_kROU68q{|B#cDKx~b&&Qxg(T?^=c?6NKPyj)%-eQBNVLxo9 zj7);ge9X=3>o%klh5Is7LVFj;fmvWtz>s>QK&!Lcl8CS#%N2`u~m22Ypfu5t}*>oaQglm~DsT6(OY8uuo zC+@TrlOwK&xkL{H`SuO$c5%z3oXLth&N_%Suj~!OEU-BS&t6u)y3=O0`vSI_rizo# zvOAN#!`0(w4Go<&*|VjiV@prZ=FZN|k{oL9tBUUA*1_D0y?rI2BC9=MlkMvMtvgtv zFX|IIDJFDK_pZ^=U0u42F6A-^>q+3~XR&%Mq!6`-w6K65F@4&Q>7`s|2>4;sO`7(l z@=qA$Uorg>nKEc(5S&J^DF2k{X>9}(oJJYJ73qZoaq!PPdhK!OMTFC0UTI7$eY*0? z^&E{0p9*uGHTTWNskbWo(uuha`bGcB>UyWxo9!DqvVSC^u)4%VW8*|Z+(}}k@N=oU zk+v$L0^*G5yTAs$2P(X^@C+mG-~7TUd2mH~V<$>eb`JJ9`EGb=_#J*qeuw#mv-8T* zY~~@Zy~a@ERh$BoyroYSEr^zyE&;z#RION^(84Y+(ObaRG}#{rd(^%h@BV=Ihp6Sy zYlO)mK!3w~Pe7l&2Ytu0hx|UT?2(^RS(=aiiT9i+d-(rALoECj(4TT?ETAvl3u(82 zl{eELxHJ~fCqD}4O~Q7luXZYNiCo+-$RmmY@vtklx~0pAn>8u<7^|M%%~5a z5_=&iI}P^k5T}WEU-$xMf(u6x`T7azda(kp$G%d89A_+qge{)rk^f8#VTz$&4)1GK zou5{M9mQ4E#fY+Sn-vF-vaovn#aILO^KgpFV#O&IM6%7!BA>saI4`h5HWj(8?jn9c zD+$xT<@MY1UqCC7W2VP+3vcB{JXfTrYQTORdL^>dVMS&=t&R)qa)E9oS0)E5;cHU^ z%{3%RdYT8YaY3?bL2Tv3R>T!l`+rDxfjXl0LlV=V&q?#vQ=89xc!Gco0*X)l|zI@RpINNiMbS=FP}e^C(oCH~${E6hS=vj7v^9oR-GL zVMEiY{icJw{foxz!GbX>8b-LI{9n18IGK7*c1Kr1QxFxMn2)cy*fxP6U5}Xmluc z*Znfw|KOJU&B{KV>TD}k-YjbnzyMt=tzlC3KI%@<4?@<;J>V6tnFB!;qXeV;U9^if z)hg6BC0yIocWv>xEUw|zvA&g2V(zN`R;V5NRne1boNd>Us;=!`#@_57w)w;DHSOy& z**_6ZtfpyMBC)I~%l9i3Y9+yhXSGE}Izpf*^a)`N&Oe<~@+dnG*16D;&q8y&KOHHs z?i`$r5@J<@ZB1)3I*Mhn0XTco>pHRs00wSJO-KHU-|-=F3RjVY4Y>AME}PEa*c>u_ zi}&l}=tk_MG{>at?*)&uGq^roT>6N%PjP;s3$>8lPPOP!Om{CkaiPU;Zf8JVBX-$H9X{8F-~9bytQW9l|D$xRZ zmDa^W4?7SNEdqech&+NY$J6e^(bkYxp;0xz(1Q#tq@4(Rj0g#ScG64INkln3zdEng znAL9O&;mNcu0Dyxrf&-)4Y~y!JPQgx6mtxkVD~YUfbDuZ_%9iH{h+sZ-;VkAE39N zHZ7R;>bS^p?J4=jFGn63iv2a4RvOP^dC#xFt{wF9*%bLJ+Wn;V6f@%kw1y<0G)ot) ze)3dW6BDg)Xi(T{{}oN4wz^~WU+2Y!d>G!EnY`g^(ON0F^5*LP$a7QX+q z7W*Y=Li72;=P#Nr(`Fsi_lv&|I-fyyqj>v11M6o{YpylF(%_2p@&!3=yupCJu*c{X z@~?9Y;1Ae?y{>5A{d_f0^v?c8Pl=j8!Wc>+2B3`rJnIpvxq=;2_BN5AfNm z0)5DhQbR*3?6v$M_0MAEK`wI}LoU6ps}ykn#Wv(rpaq9_@INQY%1NkbS0xbi4#KV`yZDmCFlATP!z3e??z)IC+!Hy{SxGmXXh5ht|5}}%Q zM@jH0BlzIh>&P+mt`dT9`U>cKvmqhOM$eMnN_>I--edG2?K;!?3Q(=DD2t2et9^@} zK507D^fTk>+@hy6&R!Ky<$sf8$awmm%EAmgSp3-ID1P*;qoP2**oa7G^X4#vU zK#H^pd5C2LC*3#i`=6~OzngC!2EFwd&rrbDEq2b|ilyX8p>JN;S35XP`7<0{sftAv z9#)8-rwV6-ucCdr)g7{16`waW&{j>x6gQvlDvz%kPawwAX^RamkGv&fzsRoH!KKqb zaxOhIL0mez2zsP~pbfB%fDQOhl-+12%Luj~pyWdp(3i~Qqr_~xpsbi@FXLs&%PGpf zEJFq^{0`Pfe!Xvg5yc>xUT6P=w!fkjllu0t#VN8`sQacrQg1Wu!Ki zQJHG-Ddnp(;r@86FB}<6RW{C~OX20RGF5R~%E#m3?m8(x+z{?glr_(`wQpPH^jIuR zjV1$4q1uL0t1TEwh2sMeXH~i4LprId%0MDqQ(x||mV{Dujs4+9v{hhA5*~B0AnCO!7K_*B3i+GnIyzU^+p%OBX($@#Zt9D8B>QUekoJ?W6ejZTBCDsG9yYodGNPzjm_*(Z7$|(Zju~UTE)`7h+e`(1|0R4l_Wet$E6oFDAu-M!N>$(*hlyo zrC*ySz9@p7p3H;(tyn@&YaKki=1<%4AB%AD z{HK{!t7hmo;md2~^65d2*&*aF%fV^Air}!ncaf*Ku(To_`G;ItvRXyi!xzv95oJkk z3Fu3^Np1-!t^Ek-lk4e6T<;A_^e@5NXtVEWk zDE$|9kXxt%PV$4`WPt*X+H?yQv+un3a?f=ORlKibk$bLNsN%VfP42mFp)UP>-9p7v z_5`3;iz7Ow>%Dvwy) zi2M98V|EE)p4oAg{m^B#BA-^a&ZR2s4_L#;h!J&5520>&^e7$<#NzR$aT(#3qHb;V z#~$j?BL} zOZ?NweSwJ6YzNzh+w4EGpYt8!Xe02r2^9FX7`aS_hj)S64)|vb_+jh}ebRv6XuzLD z7Nh44`0WP#Y11Ehe$IO2JN*t$PVpexw2tVwRE#N-@hRLJj8NEkrnBF!u+z;5Cb4F3 z!8S3~Y5rR2oeJA#x5?7iO8&*lvbJp8qFRyJ<1xgTI*(=1GRxC7f3Ql3yOmY>xyT42RBUnNUfCVrkvDhm+w+${Yt8T4oUDw09xVZfBe{y|WkR^~bP5}afp!4>K7ejx)1O43e1pIj@X9YIOwi#nb%J;ZH<`Gtt&mdO4P z@T2Tjob*Ctp30N_5%8x?2lKv3a!1tu;yFSJQfZP90{X%RAt4B=pg!cxN+K45V~YG2E#@g2KEme`0T%ac*CwAI06Df@j-j8v}2g4{yv zAuIquxm(SuoE@?NfAJOi_A?sIZsPbC!l6x0CrSz^QAd=1in47H92OLCHQ+}PhbdNL zUzeO{gM-$k4&>)oB<2vix!?%qW{{#19|4$i3lq}_*?=eUj9WT7GQVbIaNW8@`%FXE zx@Oq;F57%>a$``$trhnzi?yvrNyU zia5}DXe0gUf!xz=X*_)%r$kXabYUCNk7wpu@B^a-hj$S#i0@Fe2(=3yxh2d- z4=-Avzmsc0{=2c6`q`VDySE?5-CUCg!O!4YFmEBV$7n(6UASFW@i`6u*1(FXfsxteZwlX1 zNu;L8);bo?%r<7$r>eV?PG|jKG`U(I2VLW_)aq1_EN`o=#8Fg_?dLq;gh#uI;gA`A zTys3Bk(#pF=0N>Kb9yr73k7{Qrdz#vqoZ_aAp2Or0Ylx6pq28v!rW_uVn+?yJh$JV zu1uOs@DiZJOQu_S#^1$U`TUfEOiwuJ5IYgcr(J>A`6=j^<9%A7oLCW7AraytZiFaF z1cs={n`HT+^EBz9vU@sD>h3xMQ{hm^@ZR(PbOkK2mXs+IAv-(um zY!e~`TTa`hLaErT9;=m2W+;hgCbKq`TH8G_H#adpH+PxU5wx8$(=*=`ioy5bwYkf} zBdNNf2Ii_Avs+zu)j`n$qD8RO>4Z8O?X6^~3n*l+20gNjWUGKeOKH%;Ixa`#OpGBs72dIKhKyqZE=LV`T)?qH zGAZ3o<*-76nKzYN=s}ul{r$z|;-Va_tjK%Bd-7FA{gr$zlD@0Ir?Qi&eo?Px!LBh z^b)4*S-SRFs8N>eQ48>9Kje1;GQbP{&|=Br7uwJVJ?Q0afGv`X;S}ER#X+$wHhWrI z+iA0_PHk&Db=Aae_&0B6*z50eNn{SvS%e@Re z{VH~X3!`$3!6^87&WhUJm5HmBKU#qL?zJ3QYo za8i0`?6)?a$HC@=<)w_Ck(gXpnXJT$w`x|^a91R?uD9*N<$raO1qUzQzf0eu9qk7S zL=%LV{`HK$#|Xw8%~w>4(Gy{ER3y#?+iJ5_2@J$D8#{V7B-J7hL+%Lke<|7T@{Zc% zvdZTFEDqZ{b`6i5HI$gEk!9y5SuHJ1t;-ByX;E_8%~s11o(tAzHml|%imaqgnI1o_ zrzR{Tx3-&ThPZn6N9=~e9x}eSILPu7cZuxLVg|}iLo7-5DVcqYQ|lyf5gWBQfE9Jg zxz_BZaR1O|D655iUBUJMN~eV{3?onf6F5H|Ztw$o({elf;o8*b5~F_789AI$<64{m zM(2^lT&)>f?NMA9V1g`qMJCcBWL1oMFtfutEZd`|CCjg zkP)uE<5)k`w?0!|*)e@`23g3lEv$L{@^*W%e{eRDn(nB~Y#(l$ZH`WN_pfbE%-b8r z*Ee^ZfBva+LCN7%Y;y7R_A@(+VqG=y;nj)mU4!+>)t!hO?O5N|yt<8edLawx_bnPB z+S*S6>rj4|FTrqNUT5|*oG&hLC{p%W$$_;ToCWYfWa37eGpk}gwijC>Wg69p(|-^V zL@mUj!*Ro3$>k&M+Se^~Fs2gK_geE5>3)%Pn>q|~lI@hi`I(b@d$(q4yFyY$OLg0Z z4q#r@lKorbcsxGVI6pEvf6Mgdd;x`@@>yCR8xqG`xoQ&R@|x4`YXA8!#68?d3d6DwAhz9T(2& zU(`GOd*@u}oRv+3n_IQMndzdwnUfyoopbIvJ7$BD$BNFWIQ`1WqFAPS=HVXV{CxADYRptrWE!<= zQ&VGOQDa|DIn-Qy0H=gO3ob1SqgA>ZJR(&;gm}#64hpZIh1j3SJC8BjMgs(!u zW?LE25))(vG6!-GJ&)sbv8UFqCM=ZYE_+OPO)#r7y$vj(9ZB|L1_q(4&&f1FWe6om zC~ZnMfpKqH<8LglD6Uf(vQIinlJTmzzbxz?xA4^_h$)+La(PR+x2!a%fcG2?;Xtjw zsxji9v(gJBcbajMNfsyNLMnhlar(Yt$mvK3r1J9T1_K@`Cn&E8wD@eO9%3Qnt8R*v z+sYkwmn0*-Dvg92Xd-OgRvNYk6P2MhyVnKl%&A(;j=J*la%9?bVRb`31I}~oc17sY zR*P)+#A>UPa8WT+>B5`PEm7JfO5?5raZ7FJKivrqQV~6%pYBtgmfh^je*X_ueESOI zpn#afm;P+M!X|kU-DXzI_sU4)l6{+e>s&vW7Fd`(DJN(-5uZAPrwoRXg2P4P{Ck{% zZVaZ1kk0{gc~96IiiNBEWgvqKYZ5lcerotW)nDWahpHL_vg|F2R#w#c zirn@~DZ4S|z`HCSUsXzVHE`LcoVOc{J?OkLk9gHN3Be0)r z9#yR$an?IqD_Rm|iK<|2S$R#U%3j@4Ry#dhkB`}9_hfxEQr{mfYbc9V2ZMEyKp+fi z)PoO>B4Z&e0irW;VP1#R*Wt_C1=6y;_D@jj{>82`c0h92?N)?7y^57`=o|}D9%bK# zfP;j?=rg^_+Mv-IapHs4md?&hNx?W&5ZQuk34-?(L5D5fB)xkg%vZ{I^iTsRbBWn=QSm*+zd?AgUohJhl)*xxbC%(1DrXeR8o+?I1LDJ*4~m$3vv<=;LIV_ccQgD)Qy9vsRBPl5e^Xjn_#CDtTE$kNm+AdC zrE8=g;Qa{ByW;Opi|1Es&tI1|YwtJb)n89>nf(3Naf(^N`yKRtJ>oU>=jZbGc~295 z8S(ss#`7)wdEDe;w;A}?BcCL?lzgA2GfiuWHl!sxq@z= z&mD9X;f~AEE4I3dia-N2zG3P16nu2~l8vKY1gQ_3)*_B| z16mo!_1pNXN*mZE_^Y)YR;z=kdH@mb+zKecn)af0&$^MN#N|>g%xkp!0WbR%VVF&N zA1G*bdZ8N>eNEJg)f6q>+25JbdYJl-dOWXI>TXU_*5l14srBqv-UoQ!^STLJ#BZ<% zu=}Zze$C^3W78E>Ddu*a!a^o+pL?6VqJ%2t78J}qfZzhL?xTSMdTz#;;jWbocXe#;na@Ix%d z{;0h}MulO=eyO&rR{#GY{Rcs4th?APtQ7fchWQwP1r}3PzS$Q)+vB3+g26y1eo}>a z7{HSN#p9?-F`f|3@KC`|<>N3v6&(6Dr~0r5z_v-2H`y$R<51@$GakV0s6Ds(%oasF zS1cfi_MF|~vTc`Tsmo%vTD|53GqZ%nXT>2yT}+a<+mP3NJJx;ZF-{KRkIh~ymT$Wx znI6NlO8HOD!l-EKVbyQC{^jw08w17OqNch73iPpM$R0o^_|-sR_Z;=!X@k-IYN;g@KzZq zjkKfm*bz$R(kn5$&5NvWKa!mvajNo#m;oTMj`f`@VdL^0Fa507bSb+5Q|Il7rp4|I z(@Wr`KSS-E!s8z_Jn?)N*B{zfalf12o8WyMVV|S-ADV@GawnTz_yYU989O)@>P@SF zXCGGXrr0ccML(f}6bi=QEXB|KnJz3&>_Pv4fmR+EoCR4(BjOOw4YkwzG$L|6xSF5O zu!*jR?9kEpKkZmRdFd_WPguIVbQ3R+#6V7*@<3}LTK)LmIlM*M`?%jL?gjoid=|Dz zb2u*^^>gdN;HWvOl08S)JCNQ8|M5tlK4fB^Vjtq~r+NDVXip#ip12PI-)a86KEfaC zEnB3A#Q6j~xghLijW@J3f*?P=j~q#M`}7&znKM?{tp7)@zvk}ETkg81 zMMjndrT)YJG(Z2j568@y45IGpg#k7w{YanXwTs}am^K~7Zc$W>`ANy^kuWmwnvFwXIW7aaT;fnNm{KumYo@`Z7}T+~U})7lUH zp;-xBE08G=B@CG#q*e2kCG9N=32>#g-Cx~47WaYcN5@K&O;Ss9aD22#X0{)*qRtiR z+4xivUNU=fDn8pj+EC%JxGjihC~oX;ogUiZV9ry9r&EKCeoK*A1%@eL_-Xi6;5QXL zN6iOAA?q>eJp>(Us;UiyAgqiDDLH^heIX7J>mD{0*t8_1WHLB5RwPRZBsR0va|L+& z6U#G9{;@;gGmx4d+G%Ib9YfQt1BoI_kwsy?jNSm%K@EtuH#Ag2Ffg25Fv7M&j%jm5 ziZ0NG3}wO9e(od+aToXFc7^ZT{I1g~W9u6^CDnJn@1o!bs;wTib&J}DG4L>jH~NGp z`Q<~3MUShFvI@TQuUdWb5b6_o`TG{m0e`-Z5q}|cD$TU^f~Wq5`-}K}*}@+1!P~gM znBS*x|7qzB++V`)SK)p;)-M$413br7J?^{t{Xg*g2<*x0O({IzXeNsmwi?4;6xd1| zArAn(kf8O5cn(Pq0eU63oUYXN{1gFh=kTjI{3?PI6<}}Qgi!^13KohOPBha;H_VMj*2q!W#R)Otq(zfzuW0RYUw!w)_Zp?)5;lx)_@4MKIA6(j6l&(0D zg;-`vv+LQvW1eu0>0f!fuX&!@-3<6G9Dc3on;d@a0<|v*oAOEa@8m6my+{KZs+zM3 zTv^c67;HbYSwE^MAB7TesvpAP&1O&9b}#PKd+iXO>es#Zz-jKZFRBf8BIPiJ#wQa9 zwFY4rV9<=&)kU?jf4AKWN04<9UGqHY zx@N#{;c%iQ!LMB)ILe!T4tQQU>|>;RJclLeUburDk#0mBId({CIv~y2NXzmk3?m3X zEP%uC@C&u2ZT}w+grOOVZ0&vOD#yx6w;#?ei8&pxc{6?1S?5Z`Z#!-8&}Ey$0|#PH zlKpaQ9w*_#9)K^1b+=?&asL=u#Ad|Cf(#Ny&Q|#|kZtp(omdTm9Xp6X9`qQxiu<+T z&*NMVe1NHLpp!nShPg``Ce3AV?x+Rg8MhQIC>xL-tZpopZSKI-+C(#D-`>zZGGp@v zB|Fr(l(vNYv61$wnX9*+{*5bUVyiCQm|4*uvbeD@k=VOt*L52k=WqPs-t%ssjr7lD z?~TolHq`Vsv@CD07|H}1DppuKXB(5#O)a}Nbgt@b{)EHn@?;;Xt?pQVR%Y%46N49h zGlnz1 zX+?B4x1vY6Ft}_-!!(k(Wte}^w3@QTs1XAOeywN@9>>G)6g%hhX%QpDoipI%AvVXLHbiBGfoY=f+E)1Wn zeRNMxH5{P(d1-(ca*7S3-;AkHxGAK zPt8PIH%#{hWt@4;*R#?KKa#Nbl-2;ndKOfKA%{du(7o{Il0qiIM=}8=*kA2-|Hph4 zZIRkmvNILc=L$9W8n>O_mifTxUqDoV%Pw8%a2&g>roE=zi=%3gMl4zLe1+7sebt)H z*xz~V96L-P33*8O6+6T#72le zMi9J{W;(m|AIdRrR$r_Q(AdQ4c)$DwaRp zwWVsXwXrH$=Lt>>l{UvP6D^)-Y{-P&wZ%wB;x_xLikoBMWTn?!I(oaarlqVY9q?4O zRMf+<&-a2#FQGU5Sh2<`|8@!$=i`qoE4LKqBuHXhih-9g)=H?se6FmmHF0SordqIz zZkW1sduQkNOQ)tTr9)LOof_J^E|prhcS!p?Kd_;tWy8Q|yCPf6UbQ4uk)Eupn`o;@ z1r)CtXRVeEv~T&)%!-3s+S|7rTru;ZE$y-7{CVSJ=dDR5*PJ&te%^fY!uIvFmQ`m) z)-7gsd+W!WnkMRfE;9}g@+n?F=2vORprg_c5#LF9N3a_p-z%dTb2wC(D;usXVExf- zUvur^cRXmcn3p;(+0hIq*&_0(+;l#H2*4BA;hF$rk#a>-kS!J=Yx^gda%2U{CRi&@gzEQDX?)R6tTwAO! zASa2)j)iNiWlg4QzNKZpE3>AB`j4%V9>@B;3z-fEMf-BbmkcrPqtllB;OAfj!h@Ph z_7s1B{v&}AZ_AzVH$g_#^K`k`W{)|Z!0}917T;t>+HP@X@MYp~rVqHGtB`>}x(z9B zpc_<2_F)7oq-mox+iJGF{4#c|&`Q?#sVe6G9ZqX9Kbd`o-wolkCXB)|b~md*-|z?w z^b4tI(*HEH3eJ4KJ=zS6=2SbsD+7>o7Q$NK0W*&CYf z#_Z%eZbwbSXTA^lOlkI`wHy?JOxZ^Zuk`O5gqHjjx&kjMe?BiymRG?WTB39po4&zTVw}-TpL?80s0E1r8S156pM8ZVK*!>VgY72t{z@0= zOGM>tC0$vY1C*zKM8yuQWL_C)fR zT6aEG;Oiz&+==Kye#G~n5+~KW(CZe1aI~}TuhNv1It#wvv$;3-q~KT66{WKULl(x`;I+@w6eXs1_tRm*g;~fLkKe*5~dx6mVfA%aZuW^ z-;u+E>f>{vg&)eFksC2aZ$^vB)45GLUv9^_DkI=x-iUt5M>Acts!H;e_;cFEumCm3 z9_ejeX$9C_`dIwI`#tRY8XBipmPof1@k71NbROH|mo9%l2Y}P~gFVfDCw&!|55bCE z0(0=K(RbWvphO(VJtc(&u#cA^$9! zL1>uT>u_MjP*u8}&TiFW&E8AEewTAV`AoxDef?NNBV8Lq?KL&+Ay}<7?d(654!1j_ zDi-)ptrkV?aJ$--?A=Pc+tmT%0?T@s)v4VscbDR7oJfd_6u4H0yK5ulIgiwKhoJ={ z3)|SMSZCBu6_GxRo%i*SFZBxx?3>U-A#m;hW!yWE&!2H)UkJ$@Bk;1Ik(waZ1WKXu z`e~A~wD=YmPuGu-BlSykIj42L4Te#;qq>sS5jP)u zhJrRXTf=?PSZt)BVK^2WZm1uL^RqHwB|D^Ea_*4-6+B&rS<}^+HIZ(eFnq2SlG{oI z6D1NO+MPcqDunu5JQiULlB+Mth21P&vtQ5s?jO654hOk#EOT1DVCLwi^s38OuDpCz zdSet`eps%7k?GfsiS9>@U)jq#ahx=cmF}zy>AXAl@sqcHVy?ClZ{b~E$WO8n_JMXb zIog65{#(!f0?_orMw|kTNPTcHt-F1ebs<8`V)AR}v0CAmuRwGh#b0rar6lyOVeffH zE9-xh+W2VtY5H@NjlJuUt?VZ9Lz6!`d+Pf+y_M|ng(K4GS`UrESFy-1uJw`5QW%e1 z^J;Ptx|bw;Bu3^7=Sw(12P6tVq@!Lm>jvE^#H-Px!Z$q0d+#c`W)I|k|F&_{+S;0k zOQn6TcDXDQ3=IwrhN`*~2pOl)Qd_JmGhX4U4tk0`9ovU-Op(Rnv0=Ma#fHv~m5qP~ zqR&ujVhYvSqyNZ0S6l*!>_Uu@?DM&NF6MGclEY=eMmc+tEA6$!`l6BXsrlArXY@8S zs16z2W{xCUH}<91E*}j?`a$vmT`MLB*+1EBmm$$3Qfk4O-XcFO4I#+(3N5KZJZ#pe_~QQLFSac-W|OT2D1u5 zt%w(csr?-07{KC;dlT}}wqb7w2ttU=&+8lda$LLS*e(W5^s*X-g&Zwfxk&>-Z?Sldk`rDLm-T;>aTJ2gVS8%Ix8>9y-B}B%CG~2A9L@LA@@5?+jLISc^fB&|NoKme;3)#X7z^rU1U0!LGs;*UEp(^rN$J=pkngA zqnG3Fbs`TR^=B4K2aC27NA4{?cC%kP_I^+4$&*kx@cMn9*8^!q5esyp4cS^)m4x+} zXI(9_wYULx{E0UZ`9V7JrjujNb`bvA&(Kx;&J>=6gX9?eC>+_w$39;_$eC5_Q&`(l z{CH#-Cs2pW23m-s~LU`#o zhbpHNn{~0~}aiLS|u6=9ov zmYV(xx($A2s`^g53+?iZmjCUXsfAdKselG(Qg4r&?=;ZWXlG#MiUMZg)wE+g+^x{b$~U zPw?w&o{|y|9%b*>%6w6$i)h*J**DlXm!hzx;2VNA8>q_coxEcHn_a8dcCY?}w_+#z zhE&aKZCXs_!g~1~qH(zOLWA}MAIknG?7&|ucEx7FANFzmYsP0Urbtcp2^-DqlLyFPoS-ky*1_MB?AGa3h=60SdUsy^H8@~8Ed-67EU95bIv z#I@s;L4m<0U@(ln)G;ukUdTeuYcrR+dXsr<4*NKLPC|>b=MV<$lb{1o%bv?_!k)8D zaL!_blIq-SX8PA9#IERQfdn)nu3-;j{a-|OEgG?fQb4mXv{A8=b15IqU!1T%+kEeSXP)g8UW{(>QEynmEy>W^LXChUKfLm_Z1OMp2h8 zVH98&RSt~~mU{xKge5ndFIrVKGKPD^w9v*8e_h#<&#M*wxRIUbE%Ew;aDrGpu_|AQ zFIa3vVve$S;2#$~NDw^Q3jR#9Qg%7}AXcm28-LbToNR3_%0sWDHI*#V(Q8C7#8TfE z-!Xk!TEYIAEMANQtT@8kL)wgb0^>mHwz<675{lzvFF4$ePrGc7LeN_gC-++{Br;Pk z`vSXDdV|K1(C1osUJ%|&yl<%S6;_D67xs6C`<@#D3Uw(|~zQtzMrLtFqp!O<% z>DV+HjgD^W=-5P?xHfel$*7(k5ot%PDti(;k*sRAMpf!3Pwwj4Hd$Xkxvi_~bqi2Kigf_fY0MNEBg-sk`AXLbuaW4#FlhNhypQEL-bHK2krKNG*%C zE{{D@(pekoio`SJRc$f*ugk~6k&co_V#`}&%TkF6xXQ|ZZI888m374Z;Vtv;ixGUPf4np7JkJZLnIlv3Y6p> zogV^0J*K%1$Og-J$~@?61U>XxS2a^HM&sJ*vB zz75L->Q`~z=Mv?;^{cC(9%p+;x1}R}Nu%0Gb!x@H#8QW*)Jw9fm!DeGc zZgw`!d9qi#8O5_^Usl-}1n`wQSXVJiIZFA77sc5}RIiG&yh#k;dl8VXLHaWB)OIr3 z;ke~pC?c7RLo`XLf~VMWm&bB#h!J{7e2G9Mn3xl4q2h7Mt&Mr`gEYP90 z0W+K^mow=co7JsYRO#5wE+2YHoQw1yLLQ8BE~fF1Xhh>wBz`6mE!-C}Sm7Z^&Ze;~ zeO9Z>$&Wy)8^YO0xigURPdw_`y}H|lG(&LZdzS6kvokt)+KR@4Bac7@ijVshcCl!& zMTUJ#vHA9Acxpe(( z&%o^Jp8l2D^Ogih7VX|KsnjNnto%03n|5%0b3)wTqg^L_?|C9T zugUV)%;vjg*~cK^UCuW=o;MtBmm~WZtF6y$e#0z3DdYc?JvS|_XLT|%3E>nNkwa*d z=MbuwW>~qr29cf5zTN}h{L_eV|2)dqOWlCaa(En`{1>06oI7biSIcJ-)ES4z=XsOK z^c}$ar4jZ~xf1Zhm_>?AdzAH>;9YXefKvuNs%IJC*UMpoBS?|5_S|Ng0=x(CjdByg zAqJ7J$9gd&$13d9>5}dgGp1n(Su%8lokJ2UcgF(S@f`PPf29q@UaPlw(STADH) zkZwSo-2Tbcu~vU|DtCSdFW+eT7wK+_|HrsQrw}Uw3Eo-Cr*K%qq>QPx!zm9~6sgf} znKk2FVZ<43v0@JeeQ~W+i#W$SwHkO|^HxBNOl>lUQZ za4D*Jg@wmUq@_j{>lf7>((M^5t+Q%oC+rlGW8o3v4T^Bitz!Mf<`yv%{8XNj1W^u3}{nT%E?g z%GZ%)=RISHZo($viso|dT31(I7L7`=vP5}#qD)*v(Xw(57nshl)zUqr*TEwkxx8r; zR&4l!6rWd(VEM+DEcHg}LM}1u@JO;HSX1P#jQ~Q^CTXU~7p~OiK7LPWl~bFO@ILHh z%cYZ%eI8%xXh+v!3;RTI@hio}QfD!yAtushAKmc=lY!MdNI$7$J%$g zVxn_F6=ZNSojLPL6-0F zvhwykQAwPQ-B#rbzZCMi@C_nF?)^6wiR*)l1U0{$kIVsrJvpJ7dGG~LHB+GnC% zcMywWK9tF{smfXlj&IpiIjUZ(!W^@leI*u82>VH#Ywst!`T*~3ZTgnKOe^HifOJh5 z!o?pit1Zc8H!Z<&P~{=N%#doKtiGf=3?V7b=%rL=m6(9jH@eW`dq|qC&vEwuK$@Mm zv@m0)PMlIkSqva|L`$i+#7s3OcfPiy-1+PhVu#~;H5*#En?~*W{89Vo;^O^9em@i( z+Jh6G-(nTi;|EBoh(KnDc2mPaIX!OsMd>5CdU2*@EcF(mZ?w{uOnl8ls zA^kaNHrzj>-E-}L`@^s>V5Lhpu@6975YGyHv}w^!+WN)dPqR5BEbZH|Jqdd%fKexQ zE!>8)YZU2v5w#_B0`8CSFC_8&20Wj{Ibjc)Oy9?J7jLB{F6B|`Sq%>^qjCS7cF$!i z?qT`x@>~Mq{soR_&B8v@r;g*xksM!Q1v{TFzX!gA^+#g_Q|3&DtG$>u#&iAqF_ED! z4eec=K-xVQ0vwUF))nN(kd^ys1`ByvT8}Jxk|bj-%T3XsY1s)IZnGGNM7P|?d-riD zJC_`Y;0wf-9^f_de#q6QTTS_IqTgg#|2N8wIjc#$p(*$)uspKejkMqn^CmOGPad*J zEmp71W06Nm$#bh|5Hb(fG8Z-CL-@!y(_={O4p*Sr-BLSRA;W2{ zO3pFa*$H>9)m9rB#{hJ+A~6ctH-}8G%Xj=Q?VCd&WZhI%mcg;hjho7f68L*Ti+1T{WS}ZB zY@0CIHp>G691|6gUM?yw7IG5S&CmY_)=l^SvvuQ@USYlRCX6UC2SAq>jHw{!f&$P@ zg~M#ot@PJLqYgV5jvIw(={J}?&b+&I^JQV(*d$^7YSxWBQ<*F$>!zxvri!fJ@?<6G z`@gY54!{a|gmeJO%j0FwRXL%>`S0&*g#hQeg_SsG>SugEuQ3;bItCBo2;EvGqG)|_ zMR84$*Ns3(2Qn+zaWsO%Sr#a+II|chw_0)3y(D=(2vYE=?&1n)5lw4gDHuALw2H7; z;C_6aYn3$i{M3OH-_-_KdhT)ciEV(|C2W8n>ox$e(DwZSi|aX7+MZ76I_v>m{2bIt z!UD#;o0RYv*dY(q|*pZ`jTw7bTKQht}a(>3V!g}5~2yt^jNCO$}8~^k3~om x_$CEg?lPkDfv*TJo~(9A7mNX9!r;J-{vtV;sulG{{p{Y8f*Xn diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Medium.ttf b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Medium.ttf deleted file mode 100644 index f4634cd7c3f16e8b1ffd01f2ea4a824b3b25991d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 78948 zcmc${2YggT_dh%{ce9&bHp!-MHiaaVgk)0*H5CX|I;cQMLMOoxs)z^{^ilLtA8e?o z*c)~qMMNKLsMr-15wI(EL`BHH-*ax+4WK`N@B4rL@9t;jo_l8I%$YN1&di;eJ6A{{ zL^M2`5QA&$>Z@O>dP@kE4eZy0M~@o&PE77BA%>nNMCFx($BwU77i@S(2-hJY!d8wN z+uOV5;faYt$Q_73eeAfZamz2Cdk*fWc+-J{T(6Mal+yC4n zL?-Bj-!Q+esWJbEd-u0qQbZNecg6~S~D@Uv4a zgn#L?gZ5b8h|V!V-H(eSv|Ns*r;X##RH2s6n%%*~lpbGd67s~4kea-3b>zmvX;J-t z5t;_M3GsgZv|V)FvwiA?z7f8#pzgL+xU~yKSo~}%4HSYl!*-+W?Gf?{3YWjCt+;rE2ELRy%}C?qs{~dEqK(=| zjUtBnQA(NSz3m zEZX6Bh;!ht6$C*TvO8aO=yNr!v$rpfF3!h8~%8j;HI7F%i_v*dqWp<8Co{IFUP|*C7_7 zB$c8!{)>{*-MS$ny+6L?_gpU&SVz?LwKIS0IgS$3JpaalYKr;a?`8%UYT<)_dKu_kb8;*E0mh$3)E z&J(~{*L+QG8pRUuM`db6&Cln&m*SrI@Bl~oRzXe#cR(f{miYf(LZ)1GsV;?7mV!TB zTiTK9Qk1h15+yEM0g=>N5u*tuS^y46LV7%p7=4nMC)Q-X2(0PjB~%RBh4_~VKh#%@ zguF+JI??wen$eZs|D>OuF1gpB6br?2)+AkLJ;ICJi$ottl(dKH{KPU)S=*6zF2b82 ze-9+FnCpi0kMu3?g!-6e)ZSv$rzyYQEKO5_`6rci?~~+Tk95>h=Y#hG)DG!IcR?EG z*AbEgX>vO>N!Mq88yLyysce}ip`HobQ3~42#JS>1u~|GUc8IsdK5soE@UskTKQTVq>qyTNvs?FrjX+XuF-Oppz5HJL6d`K2Q3YHBj_W0 zn0<ae57RQs07aVUoK5`s%{2Hu+BZ8BH zvx9pF&kAl2-V}UK@Z-UULPSVLNPb8~NNvcdkW)iug)9nL8?rv+`A~bPGqgT*Oz70m zxuHu!*MzPQy*Bjy(62&&36o(}VN1i-hFuzVUD)kmkA=Mu_FmW*VZVlJ;Zfn~;l0EA zh7S%O8$K<(E&S~8OT%vrzd!uR@E5}03jZYh=ZMh}H$~hV@$ZP2BHoYqDzY?kUgV}I zd(>%Bv!gnqR!3bNb#>I{s4dZs=-BA2=z{3}(Lj?Gzn5{A2#{BLKa>h8*oZX$J&MM~!=VWJ#bFuS0=f9k{Iv;U9<9yZmzVoZt zs@M^+lVj(^UKP7P_S@LsYn#O>woj7P?lt*14{9-RQb2AvPgB zp?5-M!j6R36O$7sC$=P>k$6_(C5hK0-kSJ*(uAZLNv%mMlFm>1XVOhcpC|p4bSya} zIWaja*_&LIJUV$=@`B`L$!n7@O};Mq_T-0>w&vB#&~plvtG!0H|s!luk0n++p~Yn zKHAOE&DkxjTVA)~ZUeeq*=#_ZZM)XpfaW*7dle z$BjMi?it$C)ia}KVb6g*NA^6u=lq^ad#>sE&z_rl-rsXu&sTfy?)gd2?|UBU71S%b zS4yu2(;D+}K($}B1?;W_i781g$tvkpQd%;gWN^volF21AO6HYxl$=#^ ze#z#Nhf8*pyj}8X$)QqPY1|3_g3`&Q7nHtG`d*n*S?7gxd%OlDcm%m(oup+7= zp(4E^x1x7NdBvcLNfpy8mQ`F367q zdH-hy6b-m_pc+^(ux#MSfy)PO9;6K#G-!R5tO}``Q?;YIU-i?~FV~dSTwilX&BL{h z+8gU+U0vOVx{vCI)!#5Uc<}nczYG~YWaf|yhCDdr<)LC|#n7gqw-4Rj5Yo`l@Q;QU zhjkxz`mnQx-8byW@NvU08vew zAN9(p-J{j$u_UW-NjD2nFdt*Ny``b7%E_ht*xRh~O<9d!O9yfH{igBCA zZ5{W~IN$iP@h#)882`lh&nF~J=sBTz!i^JlPWWWP9}}}Dj-EJa;`E6ZP24zf^Tc~5 zK0NW`Nx_pmllsuG9#0wq<5MBxXq3uVo8vI9FJhc)7ehn@#%+DXD!B?h%H{HUd6V2C z-Yn31!+oavJolyUE8JJPZ*c$a3G+mI;yuY8w-Gb z#OX=&qOe+qt* zc_5tv4>Xxk4wN0Z{lMG1E(AVzJ?$WksPiR}UZQ6G2S#5{*y!MLro%VyxZi}|LY#tkpodmAn#s2$xS?{V1>Qc2#EmuwI zDYS|OYLaSEQ!obGp`KCyQPb4F(8kj6+}I7Rs$LAn_<1bG>iSr537+q77k7%g#Dn5# z@q+jmqr1<<=i&#oQq5Fnsh3rUIwpRRG14iMWCou7D`l0emy_gaa+;hY=V9EpQQjbL zl(*yge=Az)JMshhq5Mp(P&cSE)k|u;nyPMBkE=V?6Y55FwfaL{qnwx(*{NF9wOX*+ zs9sQmRF&#f@2IO(qZXnDs#x_8)u4u|VQRXFg|!I9j6@7(CQ?L(7=ZRvg7N=UF89U@ta=Uz1?t$gmD_k-ZR_a%gAj3quj1^fjL1fEB z;la#Vo=g!vWSXdw#iB@NiGG;lsg-4z>&X@kvcDK2`-P~+$(Pu_sE;XL-G#sxV%?9ChrlC$h*X|@=@`O zd_-)Q4~viFo8o=BOS~kvi9PZS@g8RFK9sMcO}r<*lpl$&#EZWa&7+r$&{e(|K-A|94^ zibv($Vk>6Do|8|A=jD^)Kk_lLSH2}az}(oU@_n&izAHYFyT#Y?V{u4+C7jYO;$$#p z-+UqhGeeP>VTz)eAasj1@f&)>Bbf9212aHJF{}8y=r4PVfwD-{VJ5Cr=8AIJT~x>( zqL1t;%4D9HCdY`=hsjw)lr!EiRVlhzsQ^@h^FixC-;SSIbMp zHFCY!ApaqD$^VGg<#Xaq`GR;`z9im}JH@;5W$~7LQ5=-}#W!-F_*Nbe-^)+cDQc{m zpvI_)>I~JU7NQ?sr!G|Is`J$a>O8ec-K=I{hHs0yTiv7XSC6Rs)MM%a^`LqbJ@xDA zP4sh5s<+VBJqKHcVv10?7ju)Uwto0HdEflTj#fxvl?bVtQsTkq}{2Os1{zjbezY!lC=OvAVZQi| z{V&-+!2TZg-(~-G_II+sgZ*u-ix;$u$J^SQTg8?|b6RJLyA~}fEE1a+EuOJR+^}fz z!bRfh6)o*;=qE@oa@eQYatUo9KbL*z1$2gHLI{_{zFxivhNIZ0^%6-dC-7;lLZa=G zAH#kq``zGc=&e%G?^0MY``PemrGVyhL)cLpH}5H47Gfxlo9D3GhXmaaRDr*+J&%7s zZLhY|`ftJLqeGjiO~MR*u=)Z21L|$GsR!ZDRj1+amPgSO7r+8PkG_2js8bHXpg%-p zVEp-wJSe}F-^uUg5AsKhMt_!vpc1oWTN-Cu^Wm7@Qt{f^@ zg^c0kekBSAjsa0e%vX-71jsjG!+fMUSaJ) z_EC{oap?nGIA7}nQm1li1$o<56ylCk5gcb6@K}$4Z&EwN_oG{;4ikSEyUD$`GzaXptCeM`N_@)MB+bEnahJ30k6-1gWNIsal%m z=Cu*ztQyq}R8EVUiFJ*6Y97{67N`Xxh%6wuTBgnt!5GzCg7t`hVZ`M`AM}}sMW6J& zNK`+n!y-fdh834wluGAS!W!wavC-;;T&5;bX)s6UFHIzJabh$C2doWlEo8n75+*&# zhMej7>0LNl3!-!x@ReALI21xFH(f)d_=V%?IS=q1G-%}*w44YnFleQNl2jhm9rr|y zYQd!D=CBggpW{k3B!H^j_X+N#Y6-v>r zUKMgzqD4+&es%6i2eZKumAF}w^dKQ=aw0%Sm)UrOx{fiWpWTHc7s^jk)hQEKk#JHq zg0>4G5;Ln*JLC)WBvMYJd-etMV5X%OPWe8DQP({fcLkO#gwv2_o3TeCb}!^@L-|~= zDxqo*^y?e-A^dOE2k<{p@5BEzAjUq9@iE8P%P~IU7?1<>?JH0;sk_l)Rzjl|V&vA0 z5%VP2f#G-t7=(V3tQSUg2x${%@R-gcXUYy0%`Fq{klLiIhd&RpMO$S*31dPfmJkfO z&G6?iJV(tZm@(ZrPB-zBRd$6{UDyAr#pxQJYG`FPDB(GX={cZ_1Z{((y4P*0PzOOzU-=3sSp7VO@9aNiyCFa6bEKzYim`YGtM%2h?Guc`x-gE@^#RST$_ z>aF^y8bH~qKvk$}Kv|f*DOXj1GF2~CrUn7ZP(4+t8VFgW!`k#vC29b;|61u~(`$39 zI2HFTu!H}`6T<(;zDtghQ&gD! ze+BFC80zL({B7bedeI>6Mcu4@-B|l_@MOJAUN1qL1PhT7c3!Q!&$KHUNOmbAMlm`1y^OzEXDOP@c3u$bumdR z7xfBP)8UD2k^bpZZ5z(-Nu|J&{Zb23p5JvkBv|zjDtb-hb0wFEX^JMe^}ZwW1vT zFmC)i?tD>*_SMzR6a}yg|L0wcL9%PeIe_~!N4!+St=H29@@A_CuK$16 zVV)^XEk+)H<_3U&^fqv~`o5#9_y}{1A7P%9o$r0|k?#k%pW*I@`&4%v2l0I0B3>k} zpJ1+#?%#x?_%F$5jINLRoyrnpOecQENDNLo>FPTQxCdr#2sc#z!nlvbA>SeGO3^?L zwpw>Bz7H+f#L>0Ew^y4K5RY(FSN}KN6!cAhlAm@6ypXQwt^jkF4FN6#a0uKWxc>5= zzPIHEm}C8$PAw8?a-N9!pBzRQ4gXb_ialh%oanG_lKOY^#Y|h?@eVrE`@iB+L~$3o zdBUy!#A%vH)Aorp+kRXR!%aiGBDWZ_pN?6~(?y&*9X53`=DwGq@9&MiEE;w;OGKz% zq6#|z%kj)!iK|z60aLuwFc;v%T*L^#gE5=gBs`c8FOmhqjoHnfau{UMAMXFBcnULx z>K&9}ugKSe!1o8D0)2;93kB|=D8X8QP&pXa&BUM`Pjqxo4l57(?-lG_`Up>`yD`50 z0wcCM+`ogB3pn{R%J(hy2E770lTpUOm?gLldXg-n;bO3#u$1ta?TChp5i@8t(KiA! zy5;2Xh*z#n@Lw5sd)F|m7UaVv$Xif9w?MX+VW#^s$aW_1GlAa({Efh$4g4z9#eR{4 zI_QR3;#9aa@im^)KSKS!ff?%85f+QOB6q3C!3s-`g~!v1ROq)nB1YQ@o*#f7wTqq@ zujFbj+&e^;mWy?hM$o0SAL0pgKh{QW7ln{RZ_Gd!;<=*0_8j_qN>AfM1zU2S$i+NU z1@-OnL*OqHAs8Qp@wn`IJfqAN>1wp_a6gUpGc^(Gl;OY!G+qlw9 z4AG$QeB(M0SDKromGrCN8sI3LoSDwd%fx%-RmkUg#Q7HW9gEe2btv0RxG#a<16`bq znEg^JfRDjls9xuccdS92FFtp|9l&nwtf@fV?Q{R_$8^ZYukqPJ-c*ZCFKPfB12^u zR{J7kBv#m>uqqbK>zA=udyB*F+{+ZUf% z+ph{W?+RSFskjOAZo8WR-YLR?8Y$E9)@dkdK*)Ay{D>iq_D8RmtI4 zmmGv!dQSf5)Y-^cjl46J1Dksryu@?*JA?#KGqQ0VjT@)P-~ z{0zG|zQD@vm+~u`O~<_2d!mEp)G<5uomi^Rt79E8U}haFjy$(6M$+s$R)de5Ux$?% zt%AfU{#kbHqYqaRDiVFbGW4fo#Bvp*oZ?K(3CCfk#-$QeqFAYtRI*ADD^#jVQ*NF` zIc`=%+yqN^7UouZqBnj3>;K9ih&i7AY5>;d2dOGmjTxOuVwI{zf3_Mn?i|bnosAiyp;)mWriQB#Y9w}mj>anC z7_1YH!}|XOFbj&rKjya7lu!EtQX4tJ6 ze9Skg1*(--8P8DdY7urL=yUqC-(dyz7p%k{g~0j!bFl(R>yWe}d6C#Io)OoJ8^m=1 zYk!Hbp2@T}gFOZpt4pwp;!;7ZJxY``vrtFcGnT6G=vCR~qQ3^!s;^Cqln-l8_E zTk#&l?dlHfX1I&jH}A#j=KWafr1i~*FyDR%b7+Uv!&vov6sw+()7uT|Nz9#X#oml< z=*Oebue!zEnDw~@R_|uZ@v(dJQY8Z(vvMbK+s~hBaC={RUfN; zm^nJYE9;-B&oO`Wr8p0>%Nww={tcdZz861;$I)wDDl#ye|1azhz5+W*8ZpCIh0)RF zVk73SzZ2JrYs9VMYRq&7qyPCg)~WQl%tJhz`Kvyki9I1l)iLY<@nMCZR`)fm?+0OR z-=PI-Az0z>vQ{J3qsOWdmte2TZd$hy`?WZXDLxYKix0$JvG31Taj=IVQ_I3Gf^OJ5 zkc(Yn-L)QCPpudBSQTi!wL-1PUNxh=Wl4);aqFC-x~e+;T3u#b3yrJSxR%hhu&Ab1 zzpvtZq^mLRjdWEN#(fpX_ZAv-s?00XEA$q69aRe&o7&r29aU|!+FD!Yg;urCX`R*B zw78?iQB|j3nYF@-u$rbh?M;gp%$(n{EVQP%t)sE2sin1pb114QvDY>=5+ROV|9si|Y0Ki)u>kbzFRVU0`A(cC{gm8lzM-2KP0FG-`BdcneEH>$>@TcdLa#S;@Nv0#3vEMYG`8zW zy;WgDx~3_r^OmTg4fdf{4Ws7jnVPrIV9;xpkr^$jt6@B9rphtYV0fs`pnYh^ocYZy zVWa?sB~^vRg+*ZvT{A2!D&}$_n{xYbt~~qj0KpcsU=gd@HXKFK`L>c692Fa!l$do? zWgn@N8W}*UL>FvPNvTeygzKWHuEb!V4{InGsW!qZw7S+=_E7<%s4dciYK>~GH5jNh zs<+l4S*w%u>Pl4T^%`|rY^sByE;V&Qqh`0Y8yZ+^6r;|hX2hyB1YTDdF>3Z=sCxV2 z1@jvhvoIj`I>)F$Jt;L(mvUZ(XlY@i7R_&5G&`VWlo*stbmjJXYwTlmfsL^QR#;SO zl%mMsy3{B|k(ooCeQW^HGNbTiWnp8Ft7LDHA*eEgRGC4d%)s~287Zo$w~d2(+Q$X3 zVa6@j3*;>_#8hS!qO8t7KCq68sg4T0XeZom>db3d(0ISB>x_)+4TkDW*&9Ub>LSLU zDC?p!$M`^5msdH)>#80!o{W%vJS)7Oae0M(B8w+%qF)>#6PxF>w6`ppv&cSiR(s=; zmaxhGKs{ZBQQh?=_Q@PYN7oy*QEZ5=zQR6*$%jrku8sHc+8Zr_p#Hi2!oZa4gsKfC zu4X|2&+P$vZ{%BLw2vy&VjJnI`snGaxP3tJ3_4Zj)ewAPv7^xtQlnv^8~ql#u_Zud z3j2gL`HLUgWEI5TY$-rdU6H|Pp}|n0Zjg#<%Iqy%PJ2sWY$H~+QS2In{ThSK8iQJm zUTkk+X=sa;uOT6$q}66g%N;F&)m~(fEGl)hbTP%c1@V^lvCm?T!e;qPN2Cjjyv3oj zj?2wkWSi|b$<<-AyQYCjF163G>a(y&H$ITR!KJr8WKIF?@WIY5oqyAU)o={NtX6a8 zI_4Nfm}3~{IhL*#dW*|-BVDE&>A785fcY&CpEs+$rKNR#V{7xACi{G@MEm>zxfkn& zFDkCF%|{7!PKsGl&@F@4V$-%3+gtUv(b`BaIk&ehoZVt?4Io#d%f3jr&al#^)z&F` z%efhVvT4ftXf0@fZGnO^T8d@04JK+04X8Cp)*2*r{erbNs=e6M7(=6K>Vw++7NpiF zN}Wl~h*fLoU0qQ`+ldwgy4x10N~K2XQqBw3x;m`w1Z!#en8FBpb9_I68P zu+~N?iVUtxjZ&Dcr?lR_D4^+;8HFz^4_kCxZF`FhL6sS#$_ysU`q(M7YEi2TV+^jgN-`#S{}66FXK9ck$QuXI#cEb(YpGG#V5*` znrEPl%aO{k(u>(jFSazlsII(^eW|XAOZ{R9S!!A7rMi_~?hn*8yTYjE`cnJyKr3z3 zLa`yT`abp*Og?nQam~I@vAwZ?HsFOdas&fr88IBr-B(q8z)f{|;7w8BO>y8&sdYnU zoo}KW{UxwM(K+~|;-)q*Brvb4K7k?C)(!Ond=uGdO3VraJv}U}kp&bO;O7<;j2olV z(4!eW2j7Hp_rYM4zbE1Qutu&*hV8R-)GWUUVSj0W&-my7Tg(WOFBxRMiSk=zD-f1f zFMu|4+RPxhX>;uC&*hu>HX!DP(2mIh@^pwcYX;-7q=12rrELs^cFczLWH4lA+v0Wu znzO`+w`k5XJ>DWbSheb4%N(4#phs+-V-O_W!$6z|Ex2;Cz?BUhuB>#pa^u348x^iR zbikFB6IUMm;Mzy$nKp(p&kPXH1Q}eGH*Ch@`SV*k7!G9< z&0yq=#-@4xTi03&{IhZP~lK=`9LXDyxs z2`p&yM~byj$3?^T;#r7m@WRm;<&S1x)Y8<}+RP;_Dk=_XS=506N=J){DRVUH1<_?u zT^iBUHovWP0V=sL^?|O}=mv2u4Q^Smuwyw=a>637uAAOMeMnwdUCN`U;=(e1#HISw z;lcoXp8&YnfMNS!|MmC;oAC)Y;}gv78dq)uxR!^oMQv(ZFe8LJ4}yp{gjE~#Y6`Ha z+`#E=t=M=R1#bqvDum5vKOEqy*I?eu(gt3C$^vhy_$JblPGDFG-#EL-DKNY~;HIc3@J8n(CQxPp z!CsxPUO;akJ6^rCMo6F>ymbKtiuKI6ZoRtB7kbTS7{l&*^~WOMb@6-k@iW9s3vRss zE)**|;{?BFA|mzoOfV0NAJ$eij-!M&ucaM(a27PS&lBzi^A^m*PE6XxslNw7Yf_Te zrLd$R?0Gg@yE>#Yv33!OIb1q>hxR1XPHBCwH1VLzM{*QuZ2KZo^NDelGU ztP~Hcx8UE#p(`*S4*KdD_)Y2-_^+rN;qS%_H05H4|D^gF{@bV&!q7hXC)FqLpGIDI zw<4zuk6gaHqjdfEx{m_2%qa zIIOQ{qv>a3U7E{jmN6OkdO1aQFkrOJtfO#;;eLRF=4I`LL+i+T6Ydqb?Ql=PJ&f=> z;BJQ72)6<5GPsN2&V^eAw+s&YnKd77Cfsy5y#10j4vuJ!gu^=uS^eP3P$oy=Do;(Z61eD4+7occ{LM_NaiJ7%mxX(gASS_7{80L{2-%wcDEuuJbe9EfwjjdY!11oO zaF<&U;V$OT^DW$J3tC}89TtQ(WaK;Bf`}KL$_xv4ngva;pwSl8U_rGOgw|(JuCO34 zpk8n}=^psWRQ~ih3yQR$U<;ynisHGCnmG4i3;F^0ui-v*?}fh`?oBu0USZtx@byr_ zZD-sQ@E>;HCq(8(KzF!rhEEXV+#4+DG7GxMg3h&|RTi|&g4!*J@|aI~xMy0p=@vA_ zg2q|UNQQ>MueNagP)f)O_hlATXhA)I&*o5q+zch+e28$|+2NdwvEw`(1Lw9v2}(Oc z@fbQ}LV8-peRmucO7SJ((hdlbwufjl^e#iM<8CKIJ1l6M1yShZR=fupx~EI%ZH(Il z+_hG`D;ZjE#`Cz+*5Q<&m1#>np(d2J(1biT6H5Qhgwp1k5aXIDElvwEsH9D@pfMIS z+=A*YXpjX}nh^7%(ad_z3z}^~lwt;_IIRnA0^>$^!8KSo9jZm>063g2 zWkFsGB3v&kG{=HG7L;s3aSTPK2B)f&qd27Uum$~KL0?ZnmI}CY6*87Ic{fU1UP3ktydInlc}5CPULLXo>}mv!Ia{1lvY^DDGk5Qu;9jyJkRz7DRdIq1hHhDcHiL zBw9G91%+FX-GV?q`3U8ae8_^nvmjV9Jv4=49N>6+P^0^jVb79buMB9X1?{jP;BZzM z#e+>V;yq|V_gK(v7PQHNuC*ZG3@TSzxb+sa&Vtrh&`Jver$*W(7H**h&9$Ir3z~`) zlbGi*7H+r&)mzXY#H&m$fnQ)jd4MumLaBgU3`JW|s0C4|%?f2GsnZNi`ptxrrzZWB zJPF%Z4|au;pc^OP_L;b(4+w($iE>CfnDjPyUY)cH@QW7otOaegAmEZ7<#<~x++7v~ zT+(I^y}`m=Z9$h?(8U&Xz6GteAn;;PSz+NiEU49jW?Rq<3p&k$CRosD3u?e9r3aU| z7I_R{sKSE07SzjvaxBPWLCF>rN0f0FnbZYJ3TB)N3{BchxWuF2;Q7SEI9T`xxUU)d z)PnX}&~6KQ(}G^Hpyw@Uy9I%=L64v(nDWCG?mi2;!-S~xfQgrzO&oKzk#QR=++~0+ z;<)Ep&?*aBW^4{#_- zq^C`I7ja)_+|Gm@sRI(WB|M(+patDyLAP1ZCKF2DVL}POC0xsCue5OMEohwut+Ak$ z7PQ2I7FrN^G3d>;aLp!^ya&)e$}RbI3j!{A8{>$c9!m6dsNRGUrUKGSImv>?SkQ0_ zq7-_(K^BBlEe%|W1r=COo&{xEP%6sdf`lKZn$az0LNx9}xjv=>H;H9$!+GtU1i5~* zpr1@AfkF>*=;vK<`xy5@7u?&7+XdW<3_WW>TP^5O3)*5ql;SQO$aBU8vMl{wV=Zm^n(R`Z9$(} z&|VALjRPp&B$>v;I>y5;!ryK|Pgu~y7IdEl-2n)e4-y&;Xd^=vCKSKHgj~rc6n~is zaf*vLMWlrbHlg^#7WAnFoeO9crHEf_{Jhq+j(*aG19|wP=1r4zv*i9p} zAD}XhS7_m2360Qf3vydfq6IlEh;TX;*hwQTtfc`F-^@!Ktfc`RG9l)a)5d*g;^Mxv zAlOYK#U2ZK7Y9|o9=8+z4hy%owF++Qy{0+VmnAMa$6i!!>-6frd@{78I{cG9pg#QQ6{{MoV?-Y6id^)WW zFy8x;GJ;kGWR7+h!$&Z?i`oQC=P*g}yV4l{IQvK8+wpd##QO;^G3GYFo$3p~F_=XL zH7%U+m@5Zm%;HKXcDWP03%&zy@PTJ78NP;H>{2HBa2kVD>OS~3TEjq0f^*cv-~==0 zfT3rM2Pfh?ijOxVZf2iWY~mHo=tGMLgZXKxl6(Vz_fQw2&T7Tmt`!PivAM&T*xpIeQP~D|Yc3!!9oMjapA& zUg6b+UA*3~i`N?-6rB{4(~eRkha1&8_}_A>Z&_9cIn~dUJMgXKYYWI{PV8J3J4^Cg zqJvZBDEBis_m>n(2bd)P1eHRxF}0UiuMTjkGdR^tEGt+)@SjZDrRd!{_>A|`ikI|i zi{KB_&LNoAqU12Haj!fEI81SA`9yq zQkE&q?*orhevs-Q`CJR-Ou@@F=v8+EKMe0kB9x?u)kBhbmC{oY|FC`VvzhZEPL)m4 zkl9SFh_xk)>qRhyiWMx|6)e?dEYB5Or*~?X zP^hdRpW=&;RR_Ubx@gW3HW+lAOy@kV(`&dER!g){yjeo2R`aS}8?O#7WK0|Bs%Ycd zoXuJ~nAiUnF%RpsQ5*_g71OzvJD74C*K!-_s#wRlwCU71_oqm1ph@kqUE2h%(s?~> zxf)FvuHXLLM*6eF`qRpytl?JBpC#6xTLG^x;q5$<%vSPc2FpB?F~4hzfvMD{GoD&p z29-i4b18o3wwA&4Gq|lexvh2M8qd&d9G`4dI@dymIsiDAc}S!h%<&m3pn2rreL9MP5n&fv6ePV1&MY{a}6{s^X!!4%v~p@RLboN6D( z+($806vy1hG52wtQ4C*U%Lkoi4Xqw;e-RJOwn)Yh56!gt4xcQ~Z1x+8D_P6*XE9e- zG38lI?Q{+u#G%a`+RQvOYwMW~@!ZU1Z`QCvEU%!n>TIsZW~QK9{$}RHORLDRKV&zG zY5f>5*@{%w6ED;8;@wfQLZl~NPL8 zbh01EtYkW)81o3%>8G6P5stZ*c*gtwWKq``80fHAOVSf7xiw8AiD5?qf&c>dvr> zHD`{EG^dg&SF+|5v$nWcTPiuPO4gG~){{!spJLl8q`F4)!S79FQ9&B@6qU?R61Sa7 z=Bko4XAVpLZPpxmLmn}ihYGIW3YJC%>qa?C@*FOE1;;Gsm>tZ?DyF}T>91n?_cG=6 z9CH=N9L(@wg4G5NeU&hH!3khf7_{<*nuN)@pws&R&gr zv70oEjU zY@{(aeSa(w`%9MKWWr@)6`4BnHDmw(``=ydEu!B@!SG5QJ_4$Q+>$Z)bLzCwnRP3b+| z5K%4!PW=#g(^_C8ER+qR>V*3Z?kBi|aClCV``|u+dm9d;U-=^3vv6DC9)-iGAMdgY zxf$*TxU1nVN4YP?xpwEnt%h3x*MZkvTXCHYHv{f8VUrUO7q(G0z(F=RH9%lQCdf{c zC6qaE9=K$jm@56a6*fplEfj^9&0B>NwiQ_-T{+&1@ z9lMs8{&Va@LcsjSJS=B;5&KWE-{gayAp-gPnTO~2>EeC)B`}*9^BTi%G5$J^`5fv7 zJI)xsPf5VHam+?~su4FczKO@Fudx3%jeEpX9Or3$kzHto*|e?Dv#&bM%*905O^B4z!2ulv68{pkC_ci2K107@-< zzcU`%hie?czL(*kdGzx=?fdk^bR2TXcZ8#K@qF~WZTx%(e24vM{g4^XSCl~i`Tp>I zWWvbzE#E%=?XH&iO*a*%cbqy7A*Ybks~d-OCu z^bfwHzGG;+=p_PwDEHUC9SAk}^gWK&a3C;-4uj&COq23KOMu&r5KEJMj~Ho!!Of4p zT_V_|2z(Ucu^a*0C^gZ5gUv8wajGu5W6=AP%ZU;@5fhlyw-L3u4t&8v5!Wd94nUZC z#GStsZ*j;*-{r&^;{WJd2k2*L(_!CUlO9^Y&%T$yxs{GWxHOnY^Yg)F{1r3~`>hK~ ze~j$hNzz*SYUTr4Y=e=WwaWJy=M!Kt`MxtC{^!2$%{$~2paX%h8Kdj<y3~i{9|!8S21GXgkZ$#kADizUmJvd^wpvUHntAu zT6yqRK{L+znT3D0n1g>eJTI-qj{Dp3&*gK0^2CGq_YhCx-&4GRC*ofCQqs$!0B07y zirikqzYynGy@x#C$KNYH6nl^}eH98PL*d&%<>Daz{qSV*1Gu2?KMaugHWW@hPQnRl zQ}9%lf^X?$$Z~ww2;YjrIa*aX>ufQfYmHOmC^BkO0 zb|y|Kn}=`i;CoW|>JGjrg%SJhIEQXCp5-3G*MPQ4oMVJ9TI?6warV|{ctWACOTUCO zr6%LO7$wSBvNo2ijU{Vi$=X=5Hb}`0nGeQ4ge4Wm(g}fF?gWP963%joV7UabT!L6G zK`fUbmP-)JC5Yt`1i5^SI@^bT6r}SRYVLE$$iXslu#93@Mp%Q9F(Mext4=(fk)#yM zh)&q=BVuv(cO}kHBuNFcjN(~F!7QU-mQgUvD3oOs3K=Z}g^iGu3zE74@QsjHD9bC6 z<&^|^y@jXCxABacEZ>3bQXsnza026pkf5CqU6LHZ9W;tG^v~r; z8j3fS@DE`P4Pp%qVhs&q4Gm%q4Pp%qVhs&~hSrH7oW)iTO{Y4D&DJ?W9PcDbKTgvZtPq)cCH&c*NuzoCV}fFk?SUy>n51% zCdsH9s+DA}l~mT>Fs>W=7D*qReo1xX=DG=GEl%ee@^B4ha1CX04TW{7A*z)uu9a-A zm2O-sIb17>YbBR!C68;RJJ*VXYo!P4bqLo-3Tk2{^`WAV_AdUfXxHMKbQfvU@vXX4 ze5)iH=W^}FDPIrcbh6cIuJ*1Pt?F@#TY<{Pms@_r33Yqqn>g+6d7PPdm)s;b$kq79 z!*rY?I2|Vs4v-bnixUl#*+t`=yyJMrXP$;8WZ>a6WzD8Etgl8cs&T$!E{v z+_M*HZCAO_^O1iLCI8s>rA+o6mT&vMSIdD{z#Ntzz;bJAxQLBL|D!ER z`I8aypzjc{oxmPeEx;;Zzd*~PF%Bpp^-sv{W8Xo{%7juZzWW5R4j>(^=q8ho7?_m- zXAb205_kp&;QIjHw{qd@2dTaTY7$B@86}svJBSwMhCdi?E!>^HgNT>UB~9VDPb2Pb zrgK;&fg7}Cotp1Qm26NX3M8Gwpm+$SCg>^5ZEb_w4)-G5OVBVX=^v_*OGsrutTsT( z!NC5mrs2fX>BzkaXUetsenx1g>cC0V8+@JMeYwa`XW{(c^Kmxo1+Wbcl=%;;Bb@6O zs+y3l#dip4{y-YcLMa<~BxxPyT<9&bP?p>EICr%P=km?ONrcPAT+nO=&1%pbsn&}D z>N?tSfD&U~2H(+3>yl~+Qne!0Dx|`f$Z+1^1-M@?W+2rP*gN8eN}zM}BRKj5-0TE@ zQ^ChHyhk1(^tE@DpBumBtn=5nd@p)PD!K|##ky+&qo7|*qL7hW`BRM7#|fClaH=E z{Mco|!Or-|2-UB1=E#v4&2w(rJbMmwUI>R4i7(g1S@?@Ayi=SlPB-zkd;_10)j{Bm zbnkI^yK2?Ubh+5Yv7hO7P2c;3^bvSVR!@)8+ZLV>?!veG)>!!uIw3p`U(WfD8Llli z!W~+SxI!da__Hj0wAdgnvhZ6idW@&?VD`6#!>K%GI)8b(rvLtg^bs;oY_RAbI3e66 zPZfu(@Izg~mm+^E&r&PgU!DZ?GV~U-UT-Z%I)@g9(sTzreziy#4ij zpM{5<#nV>&B^Evry^BBJ!3N&0#h-x@l1T9NLtn8SBMZ#S*Fj%P2B`7`2fon7>YH2A zMSbzXwD>p|-pVg4EB2B;+a+{a<#ZpIoY&i>(hs>vtK*`f)ymLn6fh#YI62xG?1*+m z#H94>JS_?Oy`#9uQ;^}ZyFyiiBvp@z4hdF^byZ*Mu!lz4Lh@4*lfpwBF_DpJvGVMZ zBWXmhOK&oIoD_^kE78s}bHFt7!wltm%SuafvNDNLqY!`E25VD`($b1jQw!bh!c7LwCm{#CJaaZHinPdF-v2xR}Ur)fVb-#l*yi{1KIa zOL*r`&cvt~S7OY0k>HxSW80IWmj>s4)0dSd!PZU(*U1>u6rpZ(9dYD(-6}pVQo-it zz}l7-CuD(l9P)sg(z4293@}HYH)&elhzga}Ffcb~;E3GL-(wOIVt#)wJZyKbft5W! za0Kt|J1lRY+Is5PUJboeYFw`&rF};9j!TSD^I{T4Ie(AnQ{gS|eAm(WM@YYcMWuKQ zmLea0%Ph46Phq0U<$?z1=0H6n!H`>lh4M02g3ImzbD0H-v>%GCM#lt&honYk4DZo* z#*n-oLmT^aAD$VR8X9hoP8w8~HDvXSK4p#P3@d3;>qD}mB9tR8p?ky30oAjI=D6Y= zw(#hz;HacX@6_|gj$AXnEEN)CE?8pd8`w(WS<}LkmC*4q7;%%;%lEYs*A_kmXWmjP zX1qlw7yF>-jc&4ff%M4g>GYz->ufFc{73@5Lo#%(`nTA>i96Md;9U! zI&^$Eo^=@y?Ln?D)AE!4o~5SC<%I)2Cs4L>fFICzNk5dAsn;UIr+9&cLRztT$>z~g)NyU?rmC`{;l zh?@JKscS-PVvm%R=s1Vn=?ITW?umXqwU@``=%(8OR}8ujQsStD5GXN}IaaeJX2c~X zn;pAZBF(IA8bQs3H1swVjIzLzEiw$!NsAC?KgUTdPUF_|oIOZJF!ZAX{T;O!S4^}k z_?NH*=3;*g?WiGpxEj0VDo9S2;ZJaxgLLX6c(8-fPFcC5G=WSaEFukiFz!J&BCi^; zwyC_lY3+#OX}O^x2~qYid-{;PQD+Sqa@MH4@oq=-H6*x4ovyHu`~{)qGu93tv35pT zLSm3JG$zreqGKCYjUIJ&16u!Ek?3O+5@WsyciPjkAQ9${+wovX!hx~+6Woql>yGlB8x z5t|?rVu_0?e1xDgUw$1Ig(%Tcv2O;l5D0@E(o5gzm`S1559Uw{>6oE0TkSHIwvLZR z?XcB>wFr!#ENRt)^;q1^r4mamsgWYx%~FDZy8C59eKKZWj&l5-kU*Cdv3P!DJ;Vd0 zi&T@IUU@8z8n8cV(rfA8l!(uv?PTnb5aIrcgF=8H>JYKuLHQ26iEt zdD#Q=NG?(vp zveuYI5;9gJYpusle3oc@0&I>(Z9~V#Z%Gmot5*F4?dHK4Wg_V+o}L`J{wjf;V6$pH zFEw=^n3&r;!Jd`mj7HMT$_2S zM(i&i&82J)pyI&D>fZ+SzW7pw$z!gZOgv%^^Z>ptqUWNCnVl3L$YLeM0|8&qSKj}bkH6X z65_Of6;DIs1oc#CaA%v8m&Hoyavu8^ThjEP&TAZ@p$<7K`PeIrnHS9?D_Cgck2>fe z>1fGVcQE-{3pwyJkjW49*3Smab%Jz22x@8!o;O3BL7n5`;$x!Y5~4$5gXC=y@oH;) z^sy^q6C8F`7JlsA==k_()#h|L9LL^_R=LsfdMzBbJiSc*_+Gf;pZ6IDtm6#i}=##C~>4eKLBYu0A_{oHa zRr|)*m+g9s*#MT$FiLRKuo-y{$F(HX;6hdR{@_}$t^zI{H zjEjzONmq}w5pI#eC&f@70=dV@lL2(*wApsph0IeG%T!=Q)v)cHe>CGk!u^v z${N>>9J6Z3kX2(&IeW;EvmqPKi!}+ee$-nA%nQ86eYcKx!fw#4upXaAlsZ0eMEM$9 zcO4%%kMNrIq!FK<%rL*e`Rw3X*L<`ve>yz*@osSR{{iz5uW2;vN_73{Bd|yJDvO_A z&2aSvtoQ?{`)~18Ez%9<*Jd}vt^DI)H!n29xy9&wC*W&6q#JrUX@sHU!^E=z_#+lQ z#-ltm@_ofh=MN7z%Ht15d3l7b)8+D7>1f2E<0CMePQ8Q92aP#&yh|M7Cqy0J%fctg zbHsC2d>V;S{9KLkUFwzOZKm^wpPUbW_{sV4hj-=c{1ftz6E|UhoLQdpEWV?#Zfrim zyvAcFy_|`#T>g5XQIwA7Ck&GgKlAG4)SopY8amcd&e`tFTI7f;re_Yiqsg*jY6y+RK;Px&xtkmf{4Cqc8sZ^c}O zkx5XSV`pz|t~lJL*zPBifl@l&AfF7WdldB<0DI<9@cgmXL# z7rJoz!fKLlByN4|#|K}%u6gnBg497jD-U?QOyl34^|~kg-cJv0D$e zo4x*EnZBxjRr#M~hewr4fwuJr`xmcWAZ?0tHrhcIA1pGfzlQa$N!D~fb)|NfET(*^=B3b_)rDt9%FHRXn~{>sDT z=;ZIpW6!8cGG(n*DRZ-s#7Y*9^=dCZMly_KSKynCy{S}h<2Tb!^zZKL+ueUuSf6j> z7T{cVq`7%0y_vs%P|)Y19Kp(Jg0EyAD~rfdh%oYyaJNVq5u-AE$9OT;nf%`@FzI)i z)jT|z99g^DB$kRr zeEtY~~`>t9(ji7PyssO0w{e2MKa{ataC0ci0^wjR8?5%-U;1b#OI> z2Tmz94m3qG{Tb};4)`^%&mE0=j8r(BX^s9@AnbXrzBfJ9`;`! zIzD9Ugwr^!k90x-PvWG*m3BzN3%F(b%XdRkuf9KllPOp3C+k<-AH(T$91g8(_5F>g zi%hz64%&?Y`WWS0H_xMSy*EYt3dK;P}D1YW&$9??jMT8mqssiu&YdI!GAINeR zeK4>Ci~L79Sg@<_PuhB|xSzClaesjJ81efrU2}h8HJp1!#8^1o?iaUqFk`n#KXq*3 zGX{6TaULa_Gad>nTR3z+2N5a@4i*yOF+PtJGJ|U)TAjiNn`Vcj44z(h&>fq}Gz~Pc z++bsRB-c2&p*3suj1+0Rn3%Vrf^aIdk7mX4_BJXV)QXTA(7BeS87`Yfd*9}C3lD%@`s#6D@DN|bS zKK7u}KE1QEZ|`iOWp;1h)Oj6&R6vup@=d#EkL)j%PCer5+I`J@#IiQ`?3ipSES^0+ zb@qI&t;^4R{;WD&9ysGw>({^Pi~-`;@PtTH;5;5j)ZsXtq(Lw2Cz(ucbc=YZJIlJw z*pAp=i4U_M65}Tq2l-2-izBeFB0-ZhNV_FxUiu5p4edp3i7#<#;Bd|t@Efxo#BM&K z(KKQ_cr&O+z`ZyvlBg#Qt7sJ*Hsq^p`1EQxJQ82C;g_y~Cy*5=+BvcY-pH*l_+60G zbQpf16`Pubg@`M1>v6?@Da{9?b60Ozx@Oi28S$PSJ-s_iVd)DH%9kx2nVUPZ#BSz- z`7$ix?ww`&MQ`SB;A{EoVlA_{;E?oYZtDoR2@XlNj<}!Juz&}lISOlS%H)_wVTu&f7sfw?MxEFNo^D1(Cx#tS~ ze2Du)*ItieU*k%@NZ(s~Jxr3IhF`J;=(-~7u-wQN5cndABH%Hc%erzu*#ZI{alFML zyfnZ&=f&bZ9FFz~&mSU>9&~-8tTE2NgwK_0A}1v-+f`xnt2MbR|JX7fZ|SlYd?6pF zy-*ai*SE6|&WmVWxg}n#PXv*-5~RphD=GLrxrBR^v6E6HQEU62MN7{V;<1F^C-PQS z#`({+afXl+z5=h}lj2@)UV(G{S&W~<`8>xRzrgrurC$dxTAXW{!br&Ga!6kjjNA%k zL;ccr1eq#-bw>jJu&eT-B-N>PfoH6v0qF~opvQOY9jeOIfOMYI>k37Z#~zSI&>TbN zhC{wX`V!BU;06ftfD}qv`{lppZ2cqsfJs)*P1OABf zCsMs0h&u1lKH>_ifr#^ifxDgX;zq-Y=h)i=c)!ZtE>{kVo?PH@hb`o}{hYlmKyKd4 zTv9%u5uSLT_&WcUz0Tjk=~cjK-3qwDdic5(a9W=N?uWgy(hjXd0auaXNLeeneGVOu~934ET@ijmB&rs8(wLg82x3QG03HW zvf})-V{|=^^6ofa4yH*AO&G zjG+ck*xpESKjB;4uR*6JU}!??Ep9EXAPd))Sw2tS)FJq`1gD4+j>V9g}8%BqhO&hEjcVEz=i_k6*B^ZL!>th~C?? z)Yi7t)4kN*wj}uw(VL@j9+0Aa9rbfZHg39RCfPMq@4gTQWq;qEf%2Z-p5223d-~8* z(W4)sr#zzww&l06kEsg(fem*{kDnc_Lgm9YG$%cNSqfgdN0B!{`5DFKvoX5rGkNJ* z$2YMvVePXASDw8hjb|TmyxZ}CTFY0jTs@p5{~vT6lF7W6@}(6*_1fRjI3TO%YgZTTt9i6}Ep}+Rr6>1YQ@tuZW?ywnzuiXb zMvQ`duQWq$>7mnz!UV2O8>$Fg*Y19x27d&8T5&&7-qSVs(~dV{hgh}s|5t1MnX{`H zN=omqL7zG`3~jc!T*is^CbBTslLv;9#8!xtb4iMWo}89#c?{KCL`GM6=5nj3_m{#8 z*K`7jn?cJT%yiWmUezT;bKAsfQm#Btsih4Ocf(C5A$u%|5`ss*7RYF~+fFX6jsC?N zR-S+^Qp1+~VH=*8o*?a+WHI(2E!Ljwt#D1?XL=5z}E3ePhw?*6Mdwe-#bcbYWjpddboaeR_G^;71hcrc161|Pb9?i`3mDd;4NXu|z zq;s)vXm_t!r+LF#P;Ka(zG~yHYbP_4dk2hYyd#xtHnTmEf!I)s;Dm$|&==DQgIHzI z3xTUeaKZs_jw&Z4QwS)6#kSgU25bcLW3shs^n_5hK-};AspiR2lP4MlZ4g`3m2B^L zTo6;whW7Rik~wqrrcFoYEQH=QB;Hx3^e%2ue8&^-Y>qDW>>e06rLXUlfq~s%$Bb4Q zdkpi}%6T(4&M;N^6&e?wE1(JF82DsJu1wrXa`2!?ug^l!Ly zeDZS1jOJo$%xAb2Paod8yD#AJg`%G3EGfl@kLF?q9dJ*-u27k_R^D20?ojfW#0#2A;(;oPn-QH2h4OOm)_Wq#;e;7V}h+CWgtjtt3 zZhMk-jzH@9&^f?esT9X z^hMW}@~-)77Rv|bTDmqCV*~r=dsJscGh&i4ciM%Q^z44s?55rwecju7ySMiB?dWAc zc6xO!ET_$+?A7$J95HNe@+0ESuw-ebej_#7GdTdB{b&vTyzNOMiE!#F_+MBrTj1@G z;#ar{pZ9R*>{W0mE@t3a#NylpFtm2pSesCj7 zrO3Yw>tchOub!GYJXYMft^giWxx!>O8qUrsVn_9z+Xu3JIaLklAtQO3Z#CL@y2FXHaUDC*B!xoFkhv@Sk+!c(*=L|aEM ztIEMJX$l;gla5{>G=5(&10@%BP75*V ziwE4gr>>)`K3a$TS3_6pYxt0$L)ch)awFAbqP1_uWq#~&c7WRHnxP?b0xK&_l z6;P&_YprN!Z!jy@8_r@)3&@tLTEJMz-M0X*c^iXPJtAgiblV{# z8a4h(AJW5~aL|bO!|Cv`pAom03R4?@9WjhZR1b!QtQnBnFwfnNNn3;B4qQ?LxO%{) zak(FiouW?2=FnvBU4*7|f{u_S+bBfJ!OZ3JsrdmI#~yEe)SK^)?bz#gHTvlmZJ z9^TZurK4j@Z{Ox(akFIB7ki?CU8GP{7Pnr|Z&(3e9C035^Y2+W)s^gOjtJqjD1;F{ zfi+IQ)N|rRL!3uF?zkGemPo%QI7x2-f6Vsw2srT$0Y3^0N~|5+FVo5t@ZUN1*(;6O zp_MG)55sFHRye_Ftr6TUJ#|qSR7A$|A0Z#H3zAb&ZMJM(ruLgFoIzzwX4C7I(iGv0 z_O`c77w8+!Uf7lCn~>DO14EVH(u^@PH`?4hniIby5k34#G*N1eQ*R{kUi1d@ht>U; zt^ls@{1DK&4UB|m9=44~$k?+!MXn=m1b8YeN zr@s%2k7u;HIL{W)XYL}p8(SV`uarImZGfPn^*q~yOmphl!-$7bzkdXTdpWg_XJ~8FBmz>UHwSd@Uc=P8|$}HAMTOYgA`gKqaoA@vQpY^>r-K*U#Lz+ zq+iH!D;|qmF>=GUr9w&_`vqT{3t{AK)YM2&{{2YUKV^fb!3tLW*I@25F> zYI)f489vHA7?)dmm{=T#ehd*6#AtR2HbcEzNq&obtYf-47zyiEqe(QC>76gY+R#m> zJKmCHPt(F6>`?1};*=#?f3)FQ8(QJiBA`cqgdO&dt$6XDu|idcMV{SiR9bL4Ml2OM zv(4~5=JRD9c{^eXLx&9;mQlG^X5m0xQ2oisj{`|CQoayLg_b;VHK$0ET2MXE8XLOI_L#Pl{?T6?8q965O5C6nxXTwYM1FIF|cHG9teO&&+ zZPiSLRe1^2Z{SIn--do4pc#|3&Jl1Kg6@QONTpoGwRsTGPphUj*ZLu?6g$`#t-a%) zGCc{e8C8v7P<88W#fL)sb?L&YS7+)6n{nCg_E>sAcRF2~Kibemv;5-n0A`sm$$KO{ z|1DZ;t;>GL=T|}ZD6g}7zmx0Obgv?vj%eH#z!$KV?^<>Dvlj8UtyqKasNGGg@7MgP zhZ*=P-u#Q@S1^6mQ-A&hWG2;7V=iFSbTqDH^K!n94J%NRLL!Q5FUK&pbAH3=bLm0V z_YIf#^;N91{+K`F+b2nuFA#L%Z{-hMLUY0r5=CAFm*sL9xt&-Yu!F1VpvV$EUa}nj zoA)R}l4f#xho&omp$#qTHbCTnM{|)wk~-4UURYNXK2c|ygwM>lne5999vH4X!$pvu zA8&3R&sTnbqCgV#w;`73YfsRuEH0l-y~bRf%Q5*ZI~y9hkdGC~{2S#X@AdlWja)uj zrDE%B>xz7A>R%_B1N(<6M|pQFTRuL{fAQro$HgP{1~XOR{Na4wn@1f#AUg(CGaM4? z<~noIEik>@?EHG(cYZf%4&v^|95-=^zqmYrR!Bo2I5NsF7bEqrf-2G;$7fLmuKG@r znWB}4iK7e5thxVL$9;sE<^aQ+HHI+yNhe*CnI6Uj3I-W=0V_>w5SA#k zHGR#}BBsmcnGnVTF(=~ggT>*dpiA^}SbBl;YwA5#goIoql1I`Zdlau&H40d^-0Bf{ zCe2!4=*j)0SrgutF*5k<`Hpv<4}2os*637>G>S~TC6NM62|zYp3X54xaW@$}}Er>~}`A3+v+)z@F* zHaGQ!eB?JSKZom2v#evO+E;m#{j|9L6xP9$2VYse%5@%k8rJb1iY5tcAXdf42Os)b z#BW7ErfdBG6z_Qo-rIX?SLbW*dDtEWUH>w_PNSrCC~(F{S$$6Wb`AarH2&J#q-SgJ zryXx~$hG@P7ZmOM9=bE_wikW=kqysF9FG32L}=*!)#p~O^QcShdD0059;?qk;&=mJ zJEDEE>DOL=+HrHuwl8rFYV~#Cc@OD};^_x#z5X@!2(OIhzihZ$dgek}$Kvi=YtX08 zsLhJ}1{(^Gz!})_it+u>@rmj)^7Y4EC2Zae4WJbs0TGKBfsIp@KFCZWKRW4`v?q%P zv4yXl*cMhA)r-Ox4G9BoDlMa+zM zx4`PN?TMQr4a1#vkx(S;uj?6af?`VaNK*bru1$T2bNWZmfi7i3Nox|&$C7k!8rBbb zQ-kiQkZ$DVEs!Tw-22<#kza0N`Rq0KKC2P;MxHC66vqJn~ zZ$tOC?&RoD)GKNJI&Wk=7b`Zf%uu#*xGUMWqq}_mR<+)*NP%>oY1#T@I^ywK*;1}! zU6a~S=Su}Vk~dzbrR(c55uYcLDHV!S*;c}g=qpK?J8d5DM($hZaQQSFo(ES39P9mI zWO03__8j4vo^wl&P1IWBUR;9a2+E&%J+cbuT^A8vYR^2!HCNFC(mg~=N5@ING-1Y8 z?j?Qp2-j!D-K5Wo{yuESx0^6)tM7jnaGEy(uij6(2;g>~Xg$|M7h9126SY2(7fV*S zo$V^51#-hlYG6(Pp+?nVYNL5Ov#qOkpmZ)LC zr6FODiG$5buZOjqhlOabKa7d`&m9hYRMmBfBw*Nz{ZGtivm64K4MGum5ZM|q_Z`;C~Tf8^Bh7w@x+d;GxgucGG3i^CXK>cg(-LscgGJhZK(&q0|q=%Lt1iexlXRo>Y z+4G4ef>^a@tZMns%d~12mtSDdNiIb1S7+wbyjY}I5MtPO&FCeE&b)+J*6jG?j3v2% zgl7&NK75FAr)lMx>Dk$7`cC~7t9pa$XRmPR;;n#JM@hOU;C!?qn+We;_1wz!s;(;9t@dN(dR12y z*Q@|eT4vA`s+CtD9)uDIJM-$|bfT>{ zw&=40tLTdyj%|^)R66W~Ta;&|wtaP^tFgCG=UJ4b6UmOqvAnxJP@k)hrxe#pwu=}q zvR(KX6lAr$#Qz@!yIiX{Jw_e-BNEGE6zWvN!+mElYAwwUt+ax@eO zJO3_ng|AKvI*-Kv4iYqKI=#-y3|@%Rv?Frm>v%hoGw<su@YjQ-iy!A&j1BS*#ylliEGSYTzt z_QU;#>aEjFO;O^7rNOy)Low04YmgPWcKhh`Ow)LdC99m1dPY12{xLy$Hs>TbaYKT; zr7AZhDDgc3eQ3MjoCGE5FWPw6-j7O_h42ds__OR^mVd=L0^Lu1NWdSlD@6$`5&seJ zr;#%wI0)TOyn^6}zS+EjptPO@lvWNSUnBdxvv2;w_ROxv6|Bc zJKI9c7Ag@Is;y(#u40QvfvRdoE??H9%HZtm;K1CRRo>V#ytk`svCG{x*VVkqLPlH6 z=?S9DUwL;Q(>>mx>Q(zQ4LK#Q_stHMik*FZoyF2j$NKj2hJ4d-rs?Yb-iAgU^_X-| zG#|@snD}!r=-0GZV|y}K-@(_h=sofKCv1xPBx=vyJwB7; zRQPeeW4#j+EiP4`A-(dSfgwCQy7KIKE6+}~;MqqUXFKkwwS2?M)yXDYecG|t@z&Z^ z%7ma^;=Qxv6?qc-Flk4c7z5enbQSY>nx_W+X$^Yx0QqA0z4BD8rK7v}Izpw>gZwIu zp!&?p2v$G4ZROc*^z0*!-@rRmZFy|v>ORVCdD>Co)k?&Bx30SS3?IQLw20~merI2W zhpvw*C5mxxg_&PJR; z%%QV}pC>M@VOS=uRnR7&nAu0ML;H8tXShE}%*vBPGHSP`mP@E%PTuZ1oNh1=Idh_~ z3*17)h-uSFUMLd8J;+2M@xEeqg&_L~1ocW`KNvhXHhOSq=-}ws!NE-%M@E*GMn*Qi zSBtsS4L7}c{f*n!?dvoRBjMMk^TYc}Z3iw&FM5JL9rE7eVH=R1)4O|Uh-z+(4$sXE z56{ki)Tebx2R99!(w8oV42yObC(HTzo<z9X}H@@V3d2t^_UF09y&mm(& zyjQ-1$0_N()%F#3fZ7-B;!wA0zwln_7qs$+8D*kU6lb$&Pr9Jmo|Hb}e)N;>x5tTd zpljniz}u4?CQc(9MMcgAs%W%LPz%up-#kHop*WHVLZ<$5qnm&8-8;%vej;FtQMh z5b`xcda4x2cDLu!T{-r5#ie5VeCxzSZ!Tb(ffo=#541JK%lV;!p6-F6){b@H6k+x{ zwt#)6MAa`#(QKhG*U>gxD9pBX%oWykwG=u#3oTtzbH`ju%UnlszO8M(*fu!WRu~w7 zmVjIU_+(|W)J0A}HL;461DD`52&+z;0RNDL+1GmUV19JUDoG+qT041BbVj7IL|T zQfVQdU-0d}{j76t+rR&|bI!Vb|CZ_NcJ8`vYU;XOJFkO^z>wYGz-jScpuc=P&|?d5EdWUHR9`5N~7_IAX*E~V59t-#)Lv z#q{b)^j5`0+toBrCv()2SC{wVb-rn(U>ev}LCbi?$*$zc+NQ^SY#gnid<5nr>#lqw zK&ocU(EaSaUd5giykT+Yc~8H!wr*Xk4#+QjK`IzFJP&`aO;NN z;!F;8!4iHZt6`M=jCdc8_`=%oS?d-q!Zb;aGUjX-WxTzPGCOc6Zs&A&HeZx?C_|Rm_WG*w_jtv)0Q@*yvecf&6 z9X@MIRD$0u;?f6~_H=pbx>C7`Z5^X$kFU?qw71N*wa&E_rdx@oVfzvGus-aV&>GUA zN-&={;y5NCQ28RKi*rrOS^2#yB1cdUO@h-2h_W(P37v9U9Un+F?QiOy92{(-@L<;Knz z(u3(tIWyDWKXdKarrbn6H<8=KPS^ClseJ$5e*Ej0?$Qi@+i1R@glvDyXv>?L`WqVh zoBF1vDzW)e^I$qX*j$1-K(q54X6GB&h1pA1C`|*Vq`H<6$6KXwosi~f9XC7uXDkF_ zM&C^9?lvnDV%>G2LeH_|u6x*ovE>N#_g$Too#8IYi*h0 zzHysBLh44iygD8G+1k+G6sTzo**To|W7dx6n>DTR)9n*Y*@=$gM5bw?y(yn-Zp!C< zU7NdmHg|Px?&;p#H9pbPy>4B1&jctTjng;2$Tn0dArDR|Pyqgh)fB;M_@HJorRWN{ zbi>@H`tZw?L)w#Sz3htmO<%XdSjeb6uZ4(DAzXzscTOSMNSqfuvBoE>Ew9i4I25q~ z2$*eJ$fInsTCAv%Qk<$s4>p$4&0SV3V@|t{sHUl!s5#`>n&?hoCt^_X1pUE$5>=BD z?YZ!*7fuFp#yU#CQ9avK;|i-4Ie{Pead@Yy)-T>~p>EzPPWi#QPL#=1-5!rS5lpnC z<7!+F1ZCGb+U3-bw`2UwcQ7bNlyq03dB~^weP#gV=A404ofY#+Ea-Qu&Qm>R0GV8x z?%OHLZmXlAsV_-AY{beNW?Ss)naCwp%DupVEpG`~He>vi8j4*de?FD^xgK>o->H~x zBV@{^_I%(LgC*1 zt!gp<-=lIB_8teXR3njiSGKhuDhg5UbIf47P%8^ozo1&qfidZMNKQqJ_c%@I-T87d z)ic&umoyTE33r!1l_ZP-8Z5zk3!JuYJ@^DXov3INmX3IcBESgS7 ztTeFE296YF3-E0T4oA{ah)G^nStO~wA`q6P%l+?Ck&t(rX-U#$&Y(+IU0&ylmZ7Oe zOsB72101e^abz%#6!vNLS4RRjin3-MDtQs`U#<38t5m={GJ~0D+K{5ThEij?ub~iO zsg}$@Hr$YkMC((LcsgrY*|Z)H~Dwz^c#;|X-u1OA{D3ddsMkoEqQ z6-^{i69rhN-X+-18kRxg7CMJi1TkhJDo~jwl~;A+jsf_(wYL%64HxtE04Ij)x6K_ zVziTHmpQ&D-46)*%&r8ahh50(q^|>lKC=q}DdDMl=}Um1&-|%IoZU8zo#?#J>@e=> zW@odk^m#zgXLbo7^ezKFT;696X=4|$F!pHkKC{blPk|j`8U8NxnYT=k1pI-#&m59s z_pmWJ1xO?A`5K-|vu`@SD8~SyK2!C;9`+ShC)Wc)ef|m{C7e!HkI0wkGv!M(visOD zhXBv)tAKRlB(W?kLeb~@0ZFmDQ8hUU2=L6`)yBTa!g2r*;F-5vKz}m)UDRi4nIH-N z6!6R*zzVcbo7aI#2eA5V9Ybh7P%eg5%gt^J1XW9^><>t$;SEUF1Wm)|KlWOKY_ASH z`!VT$)SXG=T&64GkD6Z~8!}_tW*y7Nq|dIs&b>@cxR;*q!S$a@U&8ZQobq)sJ%1TJ z-^4z^uMglHs889?TcZ6ET`#aV+Rr0$v-bG|;`*of^$tA$3x2&Bdgvw8{)OT?qBnSd zAFh9iU(Y+dI29h(XT^2AAGo2j4d03S2f)o$WGcenKs=cw;lYSyMX(lwH{x)- zUsBK$SYxne*Yrg`?)N#hzIkfj*t_Eq^bmcG#4G2ldR=!1Q^#(#>g%n_fx7Rk8Tat=6592OcDMCd zp(u?Mh6u&IX^x30)104o(stQsUFASDm5Q=k>%PPB%3G%%1CQ+c@Xxf8Rk{r=)HY>7 zxq=ZS)CbP#l}vwiPqTI0aPGE(?XxXNW^SIa{PlWJR?`Q|qi2pZ3@oAgvWT2hLd6zBrhHfv}Y_jvrbzeDtz_xa4=FdeO^67;kN_ zIr;~s5`6^*poc-p?ssFeI!Al{IOMPqE7&&I(mauGo{aiZy5UsQrw@!C8g3X^pl(t! zG|SOK;l%hLirO_zh;I74et%leQ#aez4`yV>2&u=bU6tBDwJ92daNBfrJ;q+^Mba|O>Mq_ zjw?0>KC!}D&OrDT)tNF%Ngu;Adgk8_>q0k9{Y_NbXB&=lBMdp zn|;a^e~spo_d$2mP1XP6?Ow0WYrB_N3+V0LPPcSA-=9`+JOo;L!tIt0^7w+?Ph3C5 zrHK7j{633*BlbP(ID`E&J^$^^__@U9mOsP(#fcpr%W=nMjI_*jwgo#x;C~@r4lI*c z!3sP;vFk<9{Q6zJvcxVm#;Y_le(WyzgTEz8>_yV|kjLB7K>x zF`OMBoD{Z$rdo24(8mUR-mMo63?1I&^%P%MZ<2zJ!qKv6g4=bhjhH=!hylV zn?3i&0zrSnio}1}A=xEw*pgz=Vv|b?g*10_M})@ELM2S1Oz`x>c35En|BMrCiV( z^99k%Mri(T0S2IBh}k0)YKq?$BpVQrwwQP1F4Sr4TC> zSyvx3`}?Uw0d#+9^KsobTj$HN>l;z8Pj?2J`wM%A7B zg)}vUQS5CR=*WfXeB{l`>)55>XSTgaIS19w@H6B1D!P8H?7hjU!OF&*|C`u7#U|DJ1De@`b%01p}Voa3|7S4h8twj!7= zXuevF2dV%tlgVXPZ;UfsD308UeR0x!YM{0o&JSOMy&Deg;(d-!+U=fHkA$Lu>HFmB zc2_psNr&qPnghWgWMfoUX`3Ai#x-_h9AQ{dpJWfhZg`{PD;R-WdgC8y+&RGSdh}2F z0|DPBba?&M_Zc5>2izgq59*VMDyf0@>AX2Q_dCZv#?Ir~Eqb?&lQVCQdWbHH@8iyNgQ>bEJ@JVAOa9$G z>4_n2>V4@*@F($x2gM&6E825>gtxb*HMG!Zs(1=5RG;FQyqbMdO4yj3<(Qo1n7o?Z z%i)Acg5T^Sc-V2B<3A;Y7l85g{J!fPzvaJgcCE)~g3I4SotV3jm5-fNwk+t0B0JJn zEJ#6uODUHD?|=qhRX{{gH@jpto0`}3WDD-~flV89_$_rfEs?d+(d}7Ox3~?Q(X>n- zJqDBpcV83x`1}?o%VCw=eZ}_5DT^D}hr_xNl0t@#HBMUYe)$843vF|piO3N2Sxizj zM$cVbaP4s_M0e29s-{l5aEj^(^mFwNi(%!21|k?uYR0|L4|8^nCh5+`p18}SnG@@C zEmMW&$z8qWId?QFnK%H$+2N`WWkxy@bFbQc=BHk@(6s)l?d6T54XDHDYizrC`=K}O zY2Eg=`!Bxq{hPAuPN_W5INH-7`6GSV+*q5{TShI4(Ln!9W83=9&O^KVXZy=HtD$JL z@@OX2v*oPb4VO)hTz1EKgNOH&jHK>%t1%>R!3jFE|S|72s= zL_^#3#%y;#@B%-z^lsp#!Ley2zE?&$DOj@{4>ndb8Hylet}S*!l48Mt;6dw{M!FyA z=>p2kxr@fLbLH~-;oPR-;oT!S=&>kND|>pjUdf^!zjN}k3(DESOxK>#xidq|6$;{5 z*YH@+z)*8J(Y$^8`Z{cj@lBpRSll`p9xyib6c&rE^Se6&S~4_n!LB~PODgR@G+vmW zZAMX@UQ~|q1|nWpeP*CNH8ok^vSnd3;xYU_q#lxY@hegcYoWuguZx|j;PJFp(RGXu zeZ~yKyGx>(7$5Njigvw#qQ#eJ>49urhewfoN*D#1{K-sYV*7br<*N_ehrm+MlrG1a zVxKCM>w^JL4Ckggok}kKcq41uzqsktmY{mFfNj_~)M}NucS}e70 zn+l4HK9C>_4%5zjy>z}2haxIPmY+x`dT$dUfboHP1s`VRgJgvX~ zv>P|9$5E{V9a}D(n7EMYfQY}R_3a%Q*jG*|DZfv4`~0xbTgI~iuiNSK*LyUWoK8m; z#~nWk%`eBRm244uK53LhVM5D8##?PL00GMYL9vU-R1GP9;!UUf3>T8RVLYc*bHWf$LU~&k=X9X?9lYA z$p`sN>r_5J)!IIl%TKj6cXl>6b#}7%pbSdObW6)rOJSyExZH%nHD}9Q2NCidw#%Ei zZZ*5S-|2;EPU+d zwi_d9E8R|(eq{?aRw3z1nK5X!6Y-2MNgqXI7XA`gIPjKXQWfDaA<0?l>$A~HSXJC` zs}aW)lz>}h&hfY%5eZ|f^d`4Qa~lncOVhOm-I<&moSpC9JLYW7Sy@#}1~e%Uow_tr zO4X-g^?v`(%{fJOd1V|TuEiC_^f6c8xqZd0z1zmR&N@(#oZH(wf>@+}wJ{J*voq@^ z*EQA`5-rg?J)qq#L{typEMMUpISwmCyS3$-B~RnZuUl(4+DJHhj8ODg?VEH5N7DqM zjK!LuzlP_4);m$!t)JR9G3 zWP19@wvAWMIhj9D+3S`XcXW)M(X4pA0ax+d)4=@GJ3BgdG)Nx*#@BAydeg?~Yc?x} z`wJ3E+GYAieSWXvnHpy6o$q9FwxJ;-$?r!7i_-xgtn*EfndE66cPv3-35i+jT|T%8v1g+Y50uMk<*8UP9GUPV|X)oXKu8qX*7qj4KGgeW7F20 z6Gr(OmUKI9H)8Yr^FJmJ4I`~$@~okuvnJc8^ZDs^{>jwZv1+SN5UU-!cI=x)Ll(nsp2-0&@@w7bb#Bo|wEv*t+8kmvVw!Tti%~vSOgEbsohR<(a;15d$_-S=(hT5WO1&f9y{U+* zSov1n08-7K9lSQmL<9RwW`u?@oUBaMS)zC))wYa#QMJd@w|97WZwX#c9FT|FmRN!L z<*TI6!Cx0db_cTlxV^CEoFm9U*lKG|KKdJHVZ9M{vJct*!h>$}ZF}9y~ItR<72DJ&`EBX($WF)DVhRPAC9Os8(@PXBTN3U7eeX zvvr-x`eI#Ou|C;ZM>ZqsUmJ3p+djKQ`XJ&xVQ?ObQGN@YrxBcajH>xvwTfb`RVS!| zbfL2gF}-HkHk-Cx)@xb#{e`(U93zt*Xm%y2nheo)C_NNPw#DLYb;(xCYQ2C28|$af zn~9x&mOfrr+|q;cZw;kvk~ukN&(Y@`ix1?dQ$6(!bU;%>vN!b|C{ZCeI87-XhF=Ko zPIwDshZlC%WzaK7${@IiF%eI}JkuJ)q^|lET45qJ&5+ARk%v`dHa%R-Pta%O%PZeU zr?1&p>e+i_u5(XQ&>iq5wd7Ru{N?MWFQ08*m(=RLs$xV3$9_YV%_Tbj`j*S| zzh>J;XuHWom6qqO+qUcasc1xT28^snkMp|welQzk3}Wsu7I+2z^6ylQp=0?noHgAJ z=p3Mm^g*UUAEb&g;@npcR(Kuq>v|zgxI}ZeRVRo2w`ak!?cb*{e*cXhBscX(*_AJM zG%R~Rxv92?lhSzmgQ!S0SsSp zL3-leTn$8!M>41k28~l|SePxVa8!pvl4tDH^ZwB^O*ZTec=V9pSNWR9o5$}EYw-pY z!;DmZ?(zDNd3rgK#Ibjzf>}E3iAhO4KU;3RFX0b)f21hUfH&y=vD^KQxIgT@Us0?; z*#8wbJo9v(Hl5>=#+<`901by`&K?BmEBH$DR@G#X#=LD~DNEdK?wZZ0q=iuZx^;do3mr*Z-S(yCuwa*H2Q97wRgX zifp10Y!9(bjWYxrZ>Zd5J^PYFc`K6Cf{LPrbZ7@xYsk*>`E+FLxm=%n`LW>~C~;Px z2ia?F6f@c;_(^YX=)do{E&6P_xr_^kiRWLcmlx4M?lckaV|9djw*BS$_8Th9$~9+D zENDP-Vg|Tva5|S*@Y7U#D(pG?mrW$uDwV99rU!Pg)-1qj$qn_PNV+Y01!4P*a7az{ z+{{Z)V9=1XQdYD+y0hg-^)wC`dd#168y^NBYx%cv1|TE=LBJ9 zp@Q+VbV#-%zWK7+7gxznJZlGnfbS&le>L@=P19%Po|W$-bOz6_HJoA>bN|xq(xTo- z;Jcv*+~&=YzF{d0G5m(wH}=VspUmSA`9hVS%dE-ggWtM`F~?`w4aiKY@;BbMOB1j_ zJEaI}=Mj#o@2k@OidckYzn!}@-b&Gj zJC*;$E=8-ywRs9(wU_fx`)M7k5Ic?>H?zC2yNTzx@tImx1FOtWTf$Tz!HdN8Zruv7 zR;0j01C^hu%avdFElpQhCJ4RyMSTX1NJ)vZmysvD{tTp^Y83Nfn_~<4~7O-tXq5(TiNr{C~vj> zcr34Nm;XWt4&p&9-IsV#uN7{ zsmxKXkyu~lW~-U|8W7gATwLaos&_gn#RS;ta^<~VpQU;XFWco;eSyjy9%FA@^J~gi z`@ZYe{YH#=TwisE18PXQ->J|WQjTrNryHj?90JP`jn~vjXqI{L7M$V~^j7YIi#Wix zVlyTVcy5-m(h_E~+JhQZfDVrzb8X1yaVmKWiE_UuoPjnDodQ;`BD~XF5$Azek#UE`kGG%nj@k_<9Wp&X5z&H7 zHUoMjQEaH2o*R#7I+KH{7LB*nuely8rup@h#4q=f z#NGUYZX^;`O9J1Ub@&iEX=i4Sqr(1`y$Nyem+XIuXAF|&volf}>c++l9N&iSMT^-; ze;L1Z{`yXII%?`cEf|l+TVnVg)af#WFwcCrv04{CbFLrP-CcZ!BxZ(ctONR?;(UZNth4yREwL>D`@ z$T}ns9#>3}Q{G$iaa1FHJcyaA`Z;FwsK$PzgK=t=qW;U$sdI(=?Ee0~Q|AzA!Qagt z2toC1DRyr5S&03x2ehbWXq6$obpfHe)8fTI ztm~|AD8`~KS@quTDPmUkhxEb8+8NiZ37U+%;8ynkEBZfMN|bmazU{= znS#%lFic4sI}pVwlTqyV$+fw+7&~WTg+wHxhSa*|uxqov`)nl?3e~yGdG;Tt?uFA2 zX}PXMd!o{O>Rx&mvB5XM3j&MY-em_b2A{QRQWP*knQ_&bvYi@L&0i_vOy@C)ZJoY! zduKz>KwP_#;v%=HQIBhS>+reLQ|FH4*0sBQ5%nYFVS8;jKG5CJx&1QffsU<*r~1x3 zWvL!4(}-cqb-=y-quYdszkJa}18y9K6XIurrh=W5dgZZ}Qj&T2&y8f-j(WmfO=c!8f8K=F>p~>zd1OL-jmM$ekl70l zDmZhMJJAwf6OD%1{F2v%mbb!d?=DVev+Ih*$xPE^d#)+hoNLaruXRi|0oX~vj(k%t z2Vmv;Kup0-9|IeHu+xX(SSp;i+>1lA@o#dbuQWT?TbikyeNynyar=TC3XRD*wPsA) z9B2Hm#`S+cW_Ha<5OFNOX3Nw63=xxm6ME<*z!#;c^h(4$8YyZH9t8U7>FNls(~YXL350+C4Nk2pnEtvv4c zpXzk}#wq_l8ULIV?d*~^uq{-rNO~L@DO8i?OkSs`O zZ>zx{K?NzQ5Hu!@u@A`u1P?sR+y69bjbWFYG|aA-w-UTbR0VQ6ZUhgR#9pAC(mh-= zg?>eO2AoR?jb+s@)@;QRmKBSA&!U4tVlioVG@@GJNE9FV2K=G`9Or~Rs5A0*=`(1P zYeFk6o`GW^@nl@u9FAxa92|lVaEwN&2fGg+puGiHpO_pXNufWW8@J=Q-5q{Zl|#nL zqF0l86z4hxo1a4gWrxp4b~ba&z*hSibT82Y=3J;4RMiVQ$6iHukGQeHB8*-A8by4)xZnw;Hq)02X_0jwnwtLlpH{f(l z8g-Ty^o-%~VIM5VUDEBd9dCcE0I>SO=SGi`l_aS zqGg~f`{6o$+>2_1;f2%sSLR@$;e25!$F@j! zi#92E&ZnPik76c~!vE#$aNh0GvDHEG6zYfZ|qHx z7SkhjF}L(0=l?XPFUjfNpX^Gdx{}H6`ugsqm1>Aa8yci8Y&Awy6%kf^=}kqfWYUVD zUFa3S?zNy5NP4u&JIKu_VTPcql(Hb~tS!i-a+TU5`D~-gt&k8*6RVIibNLKP&B9EP zmg?e-ttJ#0q+Qink!;koOepEdq@sD8W9K5r9P0nJOsNkkZrCWlBb)twHY?4g8yjh# z_c**Qzn7lj6%1>NH6|Uze>^?8-N5Vyy*ZZ6L%~z?)7<_9=$melMKhT1S zCL>s3ieHJR4URSRcCcttq*UJZS3f2Ae z1Zl%7T=QTIj2EXdeQ*`iB`;yzP}g}mFlN4;j+daVj2Fa>g>D zSfW-zl@1tgq`g+OkG_5ROT^W7i7Ce*!RjgV^Kas6m&_`@0JikG7bD)lg5q^6I4NMB zx4f5aTYiRUi$;1<{&W9J@}E0WAg$xr5B2sH?9AnRXzlJ=y>_3`6_mUHwN0I(gix6RkY-x=ddWi2vu_Y~jKg@sIk`%um;lFLUh~JOe z_j4(S-@mqhb2)+EM;+9kN$D`VlSd?pvr&Jl-ndZIGFgOtVbWpvO~T<|C_?&A8}>we z3}@)LrCa#PF}8HT@5lHX>^&3CIq4S1H*hQ(j9@%v^LyO&xZMxVsqy;>{@doT`2D1P zo%2Ebev0?AW%(kV*_G!+O`pqEu{AiWTYYP5>+ftmAzAOD-YXGMn+ zPuR=i18%?TjJT!yOl7y*tw}#|$~_vkGI-tdSPepl>V>}WD|r|Bzr@^El_;SAZB#Y4 zYq!VrY0$(Dx&qRVH9YB>cY7m7AnfjeIxImJ{fJ#8ALLnQTw<+lqZjL7Eo5uR)8|4? zGGd2g-pIQ`Ui?zEIydyCi1Z`VuWs^cVU$|LRTSDG^+`89D*eKkTcvZbqxcWBzi``X zesBUq`1~%v;endto=2jUs)fAsZWq*s9PVya+G(T4}xE)-*%+s)hQYm$3-;d9GzV{AA?kLIy7AD8GAL5)7X7b;UR;!8idZsUG#{(EgHP1oSAsp@El_-Ga zTq4GqbzKLHL-c7{U>w&8t%`41cNoX24q%+(LO*BA{QYe{&>JVD@Oeq%tS6uYcQx;!9hc^A5Kx^=|&F2 zjZvKO5_^5WimESYm`t6F>LwqT6*Ic@D`AobhN$|LBu|k!IW>LL6>%^g8A7;1B%z4f;&ph+YGtZPWGiQ#F zLWpR179sjp*VI?k*Pa08IQFqDBGrz(8B;0qJJg0tM|LYn)5hC)a5W%6->gUe`J{sZi zxCT#~eaY0{2Yr+&#LDZ1cy!G4#`-BqEtcL0$Gs?-4n**npq;qyf%~lKb6OTJ7>J^P1+j z?3okxtPouxv$Oxa=Eix`t=C@x`f$+Owo2a>k6LcPt&l#Sh{9E99Ym9`i5o>Q-39!t zM1}D0eOB-u;j3uv9n|?O8lmMfl^!>qLsNuWG;MkdGgCUfw5T!6nUI>i=D{sdyDp0A z@vG3Z?+O1&my6z_>t{PBUW0TF2X(fr#;sK-!s2I9so)TVa=Vr}4b-o4qVURmokaK7 z3*qY{+~fVY!9xbuh@B$hl+yEIxmR{|3wbkz%iq*?T--u~luAr6;>7Y*0xJaZh9*&> zpin<+NublzCkhszzEejKBD_P`|0)g++5}slukEX>JjQumr?Tgma2! z_$}fx_$$SB_|MBEA!V{Ggc5G;PFfwu~m zFl3fCks*2*_+VH^iUEhT7lgJO_9F80Shx{94331ZMFV_FdlBwQ4mWU=ZUyvDa0_(eW{v;vHRRW;uGK|IV-e)jEu|T$ zEv__zMLeoIvmtvvN{Vcxqaf>R zvlr3^S#>k4O1JH{`Y@Q|Q{FPp!#x9SNHJQEMd%G~7WawA#f##7@rC$NoRVSa74l?v z*;kH`7s*+2kz6TP%WqU4HAsz7e^>uhr?g($0Bw}kpfzjDwQIHQ+8f$O+E>~U?WDzO ziM6;a`Iae`d6uP?t1Wj}Hd>yr?6&N+d~G=vB!a?&5`(gWJV8Bz`UQ;$Y6!YG==GqF ztQPAC>qXXC)?XZRxfywsPBW+s(Fhw#~LDZ7cJN)n_Xj@~{8RAnA{#5v`@VCPEg&&R>7_l~DQ^XSyyCe2Sd>xq|IVJMW zNMBT4)TF4{QH!HiMXiZi8?`CQ7abOz9Gw$g99-QV%lmXw5u3}do*Fe`w*Nv`MTwk~jrsbx2(|V;1NE?~fm^Lr%zO+_%sJq5J%ss(9-96v^ z7x#7U+ui%zhuy!YThjZdUz&bZ`c3KU(l@6+lm2S@$LZgvpUBWMA~RAmx@44R)MO0H zxG-Z*#?$gRvBoI5smN^Vo`lH4nD|C)PG?t{5c=Dw8sLGCxXzjm;6i0+WwA*VxehpRi> z(&63?TRME+F{`7eV~>vgI@Wc(spA(Nf9!a?lk61HDXCL-r-DvBI`!?eq|=q1{@UrD zP7me<=f&rx<>lw~%o~(9K5u5;g1i-ZH|DL&dpK`<-s^cE=6#v>Q{IWrTIa~lNuBTM zys7ikop*KV+@-WjWtR)OjOj9^OH-FiyWH62A6=g9@_v`Ex*W;xl0P>8#{3uZzw6qm z>t$UZ^Jt!-p2eQ`3S0%93Pu)OTCmL<>MiwN?%m=2uCS!Ax$x4$RfRVc-d1>T;ikfW z7H%tivG9$;4+{4ceph(3@b@BB6jl^plv17?u3d*{b4KEv4)?9XN*-d44m2D{7R<^6`wX*lhMR|VtW#u20w|2|vmfx+UTd!`l z-3E6X)oo(8ncWt4yS&?$Zl84frrXcm6T0{6KDGO@?$>m`wfjBY|K9y@k0m`0_3Ya7 znO+@x-P7x2@0{NGy=!}4++%T-E1fg{o+%c&@Uza%<)8s{E>3tJYUNRMlF2 zTlH@>-D|F|*;`v#duy$)?-hN2>esK|#D0J2x4GYo{Z91v^dH~<-u`b75CbX(Tt49W zf$o7L2F@S2ap2E`1`b*==#vXVFX(Z>ybB(@;Mm}@!5fAY44FA(;gHLRtR8aLko$)` zHe|<;*M=M$8a}kk&>=&w9s1PJuZKkrD<9T4?5<%C4f|%ed-%ZNi-xZmzG?Wo!#^E< zbVSC8AtNpsaovdfM*L&M<0GCO@#2WrN4!7c(1>FrPS@G$qUsXr(&}>Sde+UYyQA*W zx_9gTJ+jltu_LbKM{d3T)9{-m&+UFP4XW3H~FaC zE5DOJ%3oBn>Y@r&sT!-A@eHwDJ+IzSpKBH^T#M3TwPY!9Up1zNGT(-q>1awWJ@ zUFoiDSDve@tJKxgHNrLCHN$nW>r&ShXd!NP-R@fF`rRGoj&|GKPPfaQ;m&b;+=cFL z?rQfu_a*LY+<$X#bU)yJ(EYIcG53@1ZSLpNZNb$IQvIYKMAReXI%1 zik!qCCz)D~*2Tz4uq)gZ>q>FCU0JS9u6$RCtDCFRHO@8BHQTk=wZgU9bra`gz1xPI z#JUsRDQ>rslXA{Ui+crfa-aKtbgq*}6CrM^brXVMH5?57t z62mhk9$vdj)%qnt`meRSe)VOve&LfC2L=3mU-lqd&~ElZ;$V#*1CYeKLo$Z zIFLqx2PXST4wM{t;K0lSBMw-;d<*~02W$w9IDi=iA-?>X{ncNt{_>J9AN+E`{-5{1 zC&d0;a1X#evj4vQEA}@C@p+_;XA{KBpg$lDIW@PI0gI{DYGIJI+SM98)$>ogUR$lL z(bj7BYg_!dwyU;D+pImRZNr#mhqhDOrR~;U#^~m-b`&FalA2Zd5mQO+TspT_2UcXx20oHH^<~9AQ>ePj5wVHzG>JQaz>PEF#U7{wd z=TIx=VD#0f#;NgYw|YUns4h~sqK>8F`7s-{s#f&HIC=!e?fO`8Ax3r&hzG@H@tAmC zyn?aae({a?RvcAJ)l{`iy{=l+8S$%(k+CvKrehAEo2-zva*UjSQQr)V`xeW!a-FwzyPN_RpEM`YuQ*+f_TCiHH zUcs2LLba+7)a|NX3sJpQoVrd8Q2o_FHA%#wwFt$`L=0vql0~}ch5A&4=YWY~q!=T{ ziCoN9+=S=ntHcJeT0Jk;i?`8^ye{4p--%7~F+43F7p*c<2FY+4CGFB9Gh~kJB8SO- za-h6GI^{xnmAphQmAA{4YA5D2cFX7FPPt2dhL&faaNt>56TgWB879(XoXC_3B1%rD@w5C^{9Ar6ev#jaTjVw3 zUHP)e5&6=M+I_K{il>3U$QBVI&WO>Nr@2yIDqfS%i~g7)yjR{Ll4OKPkhkpl3oR@cAr<3l+;Uu1MV(ugR1Jq8JFsG$ zTO7V%$RM|PZSbIKx43`!kPF=6a!h)=#l*Vd1KsFp1u0w}@8tUVjk5FP$#dpOH~Z03X3v-=L#NDbnj*4Je#OH5Ka{v(zlCr_51vL=d%rkZQ47CW0}lxdH1Ew_?NDfThN=S%@Tz}|iUM?ZHLYRpnt)I5ybreMT8 z2JOHgJOlJWKS`|@Ms)~j5*PEB&Ml|P78T7k6ZMelq^yNM3%W&JWj_gHLM0Xw48Bv~ z&tQ0lnoTfcvY94Z{9@)^VRhH>zp8P%g{K%+nFUUG4q|>b*djqY;Hd2NHdXTKp-!RO zONmIt-1ON0RjNu@@oZBIHe--0$#s}?dPLZ`4o7nxCVQZkdj<5_33fttBe333n@+ZJ z3{?Iwf4$KVW?{axK6?c12el1Y%S78ivmum&0icQJ5~5U)8_@is{;hsh$BB;CN|`PL zVY&v0t1`JBMGpg8pr%&y< zVE3^6Ftm1!uo9*EsTo+MorZRAHl*)}`InxmFQ5*}t9mHdv&vNks=KNIl!G~qZmJqk zw(6?NRTZEtm9NTFC7?{q-ju2eKpCpDDp7p^rK>zuta?KiX=rUasUp=2(jQcM-t^Mk zF2>`&5$)hJctZI9*>}kya-52jTjW-xmkvoXAz?No&qaQtpY$xF_nyJy9R-iK^KyYS`Kau(gd~Ya5F;yMwx1ME_UZ6(UAm0p8@0 zhPFZkkyES1Ftt?V{h@n93=0|onm1r?fDLEDmMvnK%I?tl#O z9mVwn)m0Rj?l$lv*8%w*tzQW?U8)Xi z$nXDc_XW}ly#pueK)k95WSXE(S$y7TQ7-}ny0{S0>(+~>Mu8qi^^ z`weCozVUsG86CQR3y$btkTJePGPupDd@i?#jBy#>JJ?%JTAzRU19_A@)16+dK;QJl- zJ>g0KzlV8O*PnH$11`)bM*mL^qm$bIs>>B_b?RJ)*;M`wSN_0hz*~}qE69N>VC_=Su7Fz$-PdEjZX(*Ok=SoHNp!(%qg@q=GCcq1sWOZr zOGJgr!dN8*>VEr%SU1s^9IbT&%iu-U*HE|#&#Nb4aR)?|06oc zYuBPho)!+*L3lCf_Gn#k?S*?MW{@#=q;fE>n~Fg@p6KYF99ACm-vLpE8C*A>11h8y zc^{AaqoOxCg}ENtis#@Dgh!4?zQ>AG?31Kt?F4e-4IK}?C6E)%w3_Ivz|3tiIi*Cg zM&m!@%D5-mhsjwY2QCit=#g*dQjp=;qbV$Oae zX0CjANC!FloLGHJ3@5ftt7CS>}B363^W6Eb?7YooQ=ZFj~2KoG5 zq-cp4?<@c>ihEF0iJwJZ%#P=)5X{csit9p=hn22j9G}LA8rqVjA`?8iQ{Rr6avG~j zRfwk%8kgPX`weZ0T}^?0sGt7acU+D2{i-{RGxJer5KjFo^`%(9@v2UkiRp>B{b6t4 z<9-a>0K-LLJQprfAV+t&KFR|+FTxbuy>R_8;%*X|S_AC23vBv6k)-w@pRXWJIQs0r zBM+kx=K?WQ%M_WGRgirY&!o_73axsR^THJyt_;^MaG0@XJXuZ;xB@sg9MKX?@d?f| zu3d4BgDZr46>b0=g_Cm|*AB*&XgN&Yi*)t^K7sYDaI90UM?GtX9*zV5G3p@d9m+JF z%0l)59y-QKh8N@1F0vE$u(hRu89&Yo$=?ai0~aVG$%Xk(-!}$6P(I2Z<(c^DabQQV zyEL*V@j0&K$Udq-LGu{+`POnC^qT-5brL($v5uvrCM{Usvq~FQQeKfEG8DVh!exYv z#0py!R>h)u{W1<~Z}DOaR+a3KFbC^bKFk|AWCB+6a%GbE0c(NDGDW6Jv`dn9?lsDE znISX99+@Sxv1*trJIIb$?dpWpme*xxtRm*iu2@klkY3Rd+BhK#WsxkFC0L!wlV!YG z+8r%f53F$Y#2Vn6vNu**`iPUVLcA?2WtFU!HL?~u?koF2^Zi9vIRLAYgRm|+7*DA~ zu}V2y96(zz0_9aFN6JxhG@cH}%5ic$R$wp0sv&lmW98-|ISK1@_1K*~Sx%9SSf!gL zr^)Fk*Z1X2%;3zHbL3pvBF)ERl%avHWT7^A-SI8@|R(iF(MqZ0Gqf&Xjya9XuZj@`}U$GumhLxk6 z(ZYNHE1HhgzYnpZdWXDI-X-tG8u2~6O1vI>IX1}q^*#3`L zseD%c15dmU8wr%D1p4*AJ_H z@5pztCfY3D=hf>Ekths(7KgDY2zpx7Yx!fneko)DA=$ZSYzWpx0l3&Yju#4k6 ztn7X-f1ufP%&UDQT4+ukvtx(FB7I&R>xcm}>sWE*xpj>1FuRT?!L#Pq#aCje3PNjU z&az`aeYlEHk(l*fjJfjR;t~~ud5}vnCmfHN8iz_yiDIcrQcjgDmZ%iGh2Y{@l(S|v z#NW`XEW_MN9(w$LV*URxW`0IuE+!vyG#<>|c+s+s!u&$9_y+y;Y0S}-VeY0Io`>VzDlwxoMl4s=7}Ko4xcxHB1pNgwME$X1KM;FAFHnQk5H%F5gu}5; zSf@s!9ULphVYP4!b|;JzP5p?RQv${RK<0M&s$?svEb+7sWZzg1l z5OFo;{jL+&itEKn^`W>(d@n9nABkP+W4wj&DQ28kVea`k%yfRP_KDxr7ivFdjt=n3 z`ZwxZ%pZL(uE6Z_ZCF|V5wo60Fpk-Z9_L1pjyC&NaSL_`KY-oD8!_5Dgq60nn7=-Z z*~UA?-^Cr6=?um?)H7J8(&sXd@oeUA`g|t#gq&7qumi-06@H1;eGTjTL0H?jX~9|u zR`}bk)ri&NGxQHPV6V!@v~DB5)Z)dz&~tnuJ{9}K{y$p9!5)GPEfc#4vaxp{7rVqd zYMrz^tuyvm54?ZhdlsWcQ& z=~qCBt;WcxE}y}&pvYFEXIz)NvdY?*B?;@>mRUWAUT_&IbTSo)H;X@&pIeTv4yNyP*qw6AuGDvW)wrBLPL@we;HL+2kWc` z2e2yA6ny#x5qZ2`qf86^=3tmhRZY;4=}pas1y&o`sPS_%sHzQx*LWg^OkV&~Z(cBGcKrfY z2Gm|-8xm+I#YXI6PRoOu7B*!5?E3lB18PQ*!MR8`Zm+k>I$T%Sa8qHPf?^{V1%}kc zMlK5cDb!d;1TZZzGG9^>HsY*8_7)h5Dlu4<7%WN*e7P=2L0PS(4(4gC3lPIkTdHTs zTVSZE#K=TRjdf&T85L3)dAz76TyJXp*OH)-ZMv>860S7_s`2aIU|LfXG4fnp7nImW z2I{)B!ZuPj^`Mc|2w6w6!RrZ^mRU!$dcsDxsUu|clo^f9jq_*Bw~n6HT)(g}Y;0Sg z9jSSHcYwMJV2Dd6b+g?v` zXrq~~p&=uumHwQT+8P6ky})2uP;6^#*A(k5h_|@hI*la?o7R>)V(lsL7KTncD>ZL{ zWqMnaTp2dKeH=8&#nu^Sd3p-;#s~U0r1aK?%*dx5KG@l%%kOW&s+a7=}C6W>aBk zt&Ln17*ZD-x$xJX;#%wcfT~wwWWJ;{Z2noL?JY1ARbsFzF@!8Bx3o~}+!BziKde;G zfVaRA1!aq}C9m#;vdC zN}39}Dfa#po3FSOR@(+0e-dL}Sn))B+u+4ftE#041~5!N9)O8$ke6< z%?31Mp+Pr)#$ugrJ|3**>R{sxoW7tF&YfW}B-_J4oChtqa<#yf8#-Ls=y2uAg)3Jo zTzTk#D;p=SJov%2T$h2T* zC0A*Wr&4dfJ^Cob>nSy4E;VE>HDoR|WG*#iE-ep%b~&Bt;jC31o*y<9k{NI~i)7rW zs^Pi_9)lGgR9KDr1C7U{KVssElSRX|GHzaD^Ngk`^sI=%+LV0SnH$!yVD{|B7KTH) ziDodep?>nLwp+(pF{xk1-t6S_qnQH<10kwIr_PwR0I6Z9uFI#lji_Osu<4hef1In! z(Kwe#40w(SN6xEnM*rM6RTnXeZ=2bMNc_kK^cjt9!F<~m98LGL8e2?)7z5Ep5<6|d z3}|3ZQyWp7i8_l6+l!}x){uqC7}Z8*o!>aQY3>xxX+c3@NaOq#3{YAc{g@J4y`B+W z7nQ{klbdEY&7Fh7Z>ev-#4@F6?leoyg61Y8+^7N-)t1>an(GauQP7nnVC5Xup3%t5*dOiA(+*4W1qo+bo2|wae zdFrqy0AC&e7aB0yKD7TjJ;8o@g8lRabG^ou>j18$A>5))Zkp2&!kq^}Bpbpi4SrSm z*i>%d^tx7PJdQ#(178us&1XRDqKN5DO|$A7niisXOrH9{qfj4Ocnb9gKwK-s(Wx~w z&Td-NM(pK^>?zchgsa{o7J3cgy{v8E^+&!!eU#-XEaZys@%jg?Ra|(uujGarnP-zX zZc6zk(o}cLwRz@Si1jLX)m+q}o?e}*yIU9bLF1iY?(uReZ;nrWem z_uqwLMW;^idnO`Mf6oN-u=rtZRbv_@v{{YKb4AXa`sP`}HD}hGS=fn5yEygtAZSfW z^12k36ofT*on^5)i9K08Fdu5g?p-?Jg(y<+r@fijJDKxo4tDVhk+YW_V)H3Ierno7 z{082@lClKU*;r?C$wV28)hjEKIEne>!NXz<*MG z4F4JI^OE9W_LpNm8k`wFQ#}LtZAH7JKUaIBB= z-2%57?rOL}aJ6uK;IKlQT?B^}%WSMUW@o^qz+uHU8}ET+hr+>*vRYBj=R14JU)Gd^ zhw!I8{^6MQKYK@Z5!OUIU{!!@XOC|_<Z~8_7 ze$q!fx|cKMvexeb@A1)I^_jklkdnw63Wt^0tZKudQek4}sV5|kJ0D#og13v#_2`LSVjO8AL8k!O!10z7HU@JX}IHXN8t{_eGNyr zeQ+Pcy$6Rpn)%xX70*6v92lJrVvG6B=$pgG`8UwM^H? z#KFRixJ4!eYd3JPc>~HYA;RfgQcN7`gFzQ=t6 zmbbKT{kXLKCiJNgX?vkyk@l7e?E$olaoYhs#n7WBwAq9xbfX!nL+i}YJ51;%K-a@v zNwoA!yE4thrLFLXGH%IPp+whW;^q>>ESO6hlr|k94QUhLk20a5CN#i=2v^N?y-Zx0 z2@%fAp`A@!jtRL<$Z10H=YdETolB${8f-$!54ld8&~XzwYC;E1=xY<&Cxq)`xc6Ld zz<-(Y@7ifX+f3*Q6C%1TOt;CzZ7`v=fNq0ZnM*`j8)&YK9V&dOy)IwB8Tt zaT#~lSzIW_Eljr>{?*KzpvxIr3TPoi^Gs-_2~p@2lWrnIW7>rdXWSs*YE8O640SW< zic<4aJEUf$rldMdDB6TVO~~ShQd<2`DsU+$C~nFxeq72S6Z+PK_M6bBCbail2LXt@mNH4{QhX5iW&im`)ZY&An4Gogn} z=zbGg59ltAaf=C|y)tlDn-I})8|GXJXrUABmvg2GO);T~CPcU~OgG%b4Kkrx6Y66^ z-At&+gb1f|$v1JRVTJ@5CX`}A4ih3t^|;X{F4Tl9ekiHcgiZ*N^b5(HbjZYgYeM@? z=u=SaO?nId9uwMy5=5N=4bn~8PEgWQe#qI!gbB& zY7gCU9^6eP?s|gYHgfvwlCA{2B54Wy789ClLeou%a1Bg1!NiR+A;Jyi&;cf{+Jt(U zP?-sNO{lX8kt{lw924g@A*Tt&n^2?)1)GraLy4zN2>MJsN;ytE2>l;m=xY<&XF@0+ zBlJBJdc%ZXHldy1v<>cw#P-k@#%*dBx`Ah;K z&|?H8?V=Gf;~p}h`%!LpF>bvdM|25{V+d^^GrLO=zzPy=6jsOlX%0Z8xE(Oz2S) z+H67_A=Nr)cp~XuZ!sNrV1)BAm&XZ|$u9&sZi2g>p({;jg$YsU5)MVXX3!CCF5{-R z!?C?MCIE*P4gOFQ8el?b&5Y1qCPXpHIEJ?!t~29u+Tq+LPKTU06EqSO!Hz$Ilt0vd z+Jw-KIfCs+1LN8cnxSaX9KlIf+V>@`utQr(EhaSAgr=L&1QRMVA+HG$m!Zrh$Hck) zP@=H!OE^iP2^K#@I7cht94GuZ$1f&y$Pd}y^K(gZnoztSvcF+MFZ-dy(|!nNsv3E- zZ^JPZPmoUSTl`~c`z90GU_xt6=r$8V%V)oq;!^KtU&UOO`=KP1s*X!SsTvSU)PN|) zVvdXQHR3k=p(ON7I*$4tBXl;Pshq|n6B=hibtXh~gPE=$BwJyx#C;DFDls9n&qin` zKtq`>%fz`%DA9ysO(@)itR_S_oeL7zIme$gp<^a=*o40KLw1ssWTSI-Z#t;3l-;%yj1^L(j(e9vX5& zH~2}s333#^qLY1OCp8v+S3V8p3{JC=;*5Hjd@TZaO})dIH`u=sek*YhXCzh;WTg5O zev!6|V9W$d8KlUMR8O#v8B=Ldr$PTM&He+w4e$xV;PjM(L50uB4W~6!__+^T|lduZA?WMerc;fvU%m&MNPBES- z`)juXlSykQGEnZ> z`q`$wBbd3p%PTs^Io1M>^)BbjNu{g?5=ISVOtE$?_!nzy;E$u#DOpVGMmUq>d4{PJ zBDCuXqhYQbp^vjq)>5p#gx?wOFG!g|`iE_NOc;_!4(C$n#P$%uc2%q)cSvg{d>7tc zz&e|Hk1%8v@G%cBi#cvFTU2+v`#|`Av40Qzaq0zvNvl}tqq3;Ro2^8n;G@-opR4DK zrOGw9Q7Pw;W@Ijv4(LhF;Y>N6<$QxF-(U`J5MHcc4X+@)SixFd!6o|`ui>r0Nt3`6 zz4!@l=19DI^EG&OW)7X1a{{NBz}&9q^8E*C6(>a!|2sME6>QbbB(0dwm}d1T;ASq_ z>AV6rfJ^fdmgEj?0f#;Xe*%~ICCs^*X`0pDz~8~;j{bxwIjudUE1XKt7`FKg=C)X) z(#+shtHo*r?hJT z_t)kzp15UFzGM>T>lE|JWd517?kFQDM>31rC{X^!KD8~GTsoO-GaXrmOsXlMp>oV* zN%~W+RWMrxE%5-)@|06K%5vsV&ZWOkVLeri<fZ8H$9P`}3 z_(!-s?8eDmH9{9~DO58}wb~9$ z7Og$Qp9J5jJqZi>oiQDJO^m;U{afLWSMH8{WWqZ_t(??#&bnZ!%N6fgTqA5xm(2m{TvNRbI3|WG!X1z6+Sz ziUhW_V!Yc449Ci5nru!hmnpM3EgMs2TLywMo6{X-=>m8ZON&))>vVdSEt26#g7J>p-@u37+=b7f-!c3h!^u8OyxN;^tUSz&~uk8EtYI zeVmSGubQa#M2u#Dwdu3n_LEL9Vy)x=ur!J$2LJnO27Q@@yX z)x@RK#QfJY=O(6aV*0z8{%*$H%@`;1bTU4bIXJmJe}v=4vsCd!iTw~{;Z;mi!5juM zW;5sLUrbNuQ%bp+>8~Q0#lI;>*#7~%xJrXQ;lqZ-GOk$@nC2=d3 zY7Jo2Q~0n|v6WI0eTXMcJwYpt_u5IeW1PxWdMYf{bk5OqmTfxiQNWwNWUIHcgtzN7 zjKRnf`00$fj3ktou|EIGIlYWIT*msmjLYjrroW8ST`8#Nbuz}u97?#PvKbCzTbjnU zRKlD~*p@o8{e&@P38z)UmQ!NM05|$>7v!|q;pb8=RHXJC;1ZT3m}^rB%TvPgOk>UO zV9Uv6NlG~N?p(6nSr6UWDvDW?t2o!)nX;HE=dlb63|&zVvVi&D&zxDSasgBJN8tJo& zC8=T=s<_=KvrsFP$Z!?ssKt`cl&}ifLXxOz)<6|YSOs|$pRPzFX8LAWB6fi+#3_P{ z#d1I^a3c4mIOS}+SjOKEdz!u)`Hyy9w@kIEMVWHJZN4F~(BaX!u>5Hc7}2_a7F{Kawbq5U&Q z;SQod#r_z)!Adyn{Q;d6uW;Sl!0;0GXR`k~*@SqP{WV~TyM{5avOkk4_ptxC>;ODH-(mL_`%jV&iK&%Y&KPJB@JwGTd^8gX zb#dx%(r6fO@c#<`F2;Pw@Mny_mnd=i!7=zxGWA7;w2{A_bS<7cw}Hv6CPli2g@ zKga%0Ouw7`XW4%N_`qFPC;5waZoHGMus=yfPJ-+zG>i7kgufiN9H(fwkb{7q?~}G0 z-#fk^d_Vh+`i{5ZbjXJ%JKt%>hXOh-;tBS>4hNf~pYM6!*XPFLkYm1+Ow!K7c~a)j zcffbNEp8iR5)gnK=s({noIz#&eDC`XwZ$em{XdqumG5AGEbnpOcfJn*8&vo%!$#jh zKYiO3DSYkw&3}(O)<>IMZIDS5ps~Q5QF!~<0kQ_f@$+GNzjUPY@7g%%GzK^1nL`XM zwwK7a-}e!;@_|1s-?u2&ZQzBnYy0`oI{1Es!Wvhqi=%lp}=x3Qc@@ zcJ2&{<8(ex+Ygj1xe&;XCO&rr-NZ-3(3|ov!HCaR#b*fx@Ym_k z2bn+A@FV^kq!eHSfv}&V{q_75?b=w>U&s=`wLORb)m_jZP)Gj({(nSM-8Fh4j6KX> z4~&p-g4H=^Cut}Fbe+_nKvRcMbGY2d*KIN|pN5XPy!{qyrf^>1e0Au&gg~Cn@tnBl z(G_a*LBE8M-sqdoO+lyeQ~JaGrHJxGT{pBw?bQK4Oj7yV3Ro;!GJo8*Yak9X{N5IF ze#m!>>cKg=^XuD4fou#^H!zR3azk(A|8Y$-tPuS^wIqLFlYYGa>gRCo6*=_tKnsUo z2c5>(O87tQf4|lB<&TSNo5aRgMGp%sV;%M#@y9Y!qPRw?gh2@#Iph5L+voF?1Lr@` z<^wG1+;sKS{=io_jY{HAvWMUrCZe&UJr@56^e}e3-;s)cG~PSN#wkAZ4cb_om{x#u zg$nVH$Ej}JK-ClfWSsEV2YcHqMHSlE8qrs{vD1GFwt!E=KTFKOKbud1&JhpbpDXCZ zo(_1Y<1w5d_B{T181?VL8EdcOpO2CFn@H_#{5_b}{|IS*g1=Y%3-5#!3i@6X&TJAt zptc{vzXzTrjzS9hGD9zkuQrJ>_-<2@7>8%DWPIf&9Ve4bpmWJ^!c_%MAzQ#FPUAdx zIRTD;0sSP@ZF(VI7e_Ped!6`!@;+n#0H$&^#Hzw^EgiC z`a4eH!U;q8*2I@$Cr-us25)K5_n%+IX-{ME6r)55Yu3V=wXkL_tXT_d)&ecLp!2@? zhp?u?SUVxm%Y(p>Ucy-~5v-RW)=LoUC5ZJB#Ci#0y#%pdf}oc#P-gq_kAil-LCJj! z9obk%Hr7!L>qtUJF(MdGr?GhMB26jQ5uJTsjx!RwK~wRpsbJQToplt(A}pvAMsz% zpp`Y4iW9{S;!$yo8iVrePv4sY)g$A*O2C;<(v4sY) zg$BVwYj9RnE&dT)29aC_QEaWzY^^ayd62cn8l|!sHXFxf6VGL1=d!VK*;u)3tXwu$ zE*mSCjg`yB%4Or=vPs~wN#wE#=CTRqvPm+^hDycBrINz-8^&crUkNG4S&~#XE-sr; zw&FA{Avc#$I+suemrz){5~5PcCB_Tq?O-Djm2~I&!JlxKui^U59Xa zB%>sjQXeYHwRiA;S-S;axLu`<)B4~WBGFnXPS1J|XLN1B8DdM+6zv_Hj@AdKt#!b6 zSx(?gxc%}&y!Z98+=iLwt$8b{KUim5Hr4!=#bU5Q|I68yPICD)k;Jh_D zZEX&puhya#;~P$Gr>D_LXgISBXOhv0WP8-Butx{_G4c-}=U@1aNvH3)+>4VqFF}u} zfH@^U#fU*uNxt1G+4rGxq5n|0`xIJ)mwkPGZRn=1tftiZyZP0Hpu&32U;5iAWo=(PTr;Wao2=%EJ-(gVr z5ORq~SIa~^R(`|ORcIA#$a5=|4$j&ORg)ogqwg4VY{B?mDhp&}ZRt4ZC6x7ckLZCE zQm}e83Or|m=M?a)1kb^0wdjRauyKez7SEg#-?qc^PC%@Fh&30nmLnFv4u&%TufqLm z(STSB(bADLlOTyM(a(_RE9Brc$Ttx=y$E`ltKqr$)k0{HjNE7L(yM35KGgkyz)o8%5(rA?8#aLZ-qW=>W zn$?<_k&|0g8dp-1;B_R#IqdO_(X`U^1Uc|aYhskcA+=Upa&(l_ddiX-8fSCg zIYxCm^L2D=Qk*SBO^rdL8GYuy&`?KmT$D;`T`*}9EP~V07FlypvO?IjNX$Kkn)qu? zd@M@lIzQf0Y~XV>#vAeWaQHlRvF4ALi?>2)9?hoHneofci60^E!kdYPJeK+Aggfx< z!X;*SpL4?F#Z$E`({SQ5Mz{WQn`y+e zX7+RAjBe5rAMuUsP?iu86@u@&M>$-c)>&z=?pF(ovI;XDHg}lnqLHCH;=|B} z>4v^0*cKXV3G0N-h~c3&dt8*;E@ARCj@NB|3|ggRj6u7hj%DOPWR`}-$@P{L7v*GT zkeCVoL;b5t^`@nHQ+3~-oEm3ONlE>Wb#hgzC&lGSP4&1^JgGgC;t~>*9C1lk{i&L2 ziGt=6&6?`B;ET1(&5|O^p}F`V-)U_m+N&ZV78TlJ5~R_LNaQn})t;GNYR}b6ATtx7 zAB*xUPDtNzIySC#U6dm_RfWmFhbBhI-uBc~d+S%BAx8)}8X6)~7_-%pn$Y^{akm^4 zdgerYqCF-?jgJUPvD=*?U&YWR;p8&*w)DlaVQ66|Lt-b! zFa;T;*RHVjchQ)-~lX~=W_ggWgytw}I3q0f1En)d_QI?RX z*zB5#<-O~x(xan8f}-qsVUh9So(Wfux?tr+#fi`uOTijLkHD=Hb{v^_YVCAy|n%>ee3U?sF%Z; zjkWV@3di^D7;@(4P?8x|5!6{*YRQ3B2#f`f;@dx@gBWcT=T(CskO8t$xK*8ew?vPn zHgG>cSn3BZW$IzRvH)ru_Pkuln)w4RzIlPv=*`|`>S4Z%+u_}`UrJBavRZ97WX00~ z&gS*wZ&aW9^8h^OL4A+@maL2{KN@<>!nnd;3)?E>S#=XtV3i!lHSaytLBWvCCi57$ zAL>=xsn*5p4^45P4t^J`S3a_GLo?BA16^4&k$CG&8t z-%yV_3^o>R(vvM+!Tj3CBU{qrMT-?|OT=%nw%fqx;!6s^vkk5hqnYnK@b$-|9v35E zga^itw#akhN5~{`lV4uT>T|*!;sJT98J>7fcsx#{rZMsWDho4T)Z;e#%Mf_#arOL! ziMauIsv9~!9N%c*GKcM;OieuJ!=JuJJ+V$7ffI|{^iMspj)%P56YKh?o><2xidg~a zQcp~H^u!anR7iSDvVqMZEa?_yyv3ik#dTIFNw9^i5WP5AVV{6L+~4N@C#yvBcXoe% zC;IZjZca<Wcn6&6Am6%hy|i6nkt+%$Km?7#D2V z>99M3tO@QoyFDyS@6U~zg;Js3PuC8WqQ6FkATMag<{QmXKo-nSFDBl4WnwBM9PUU> zb+mqFv!bg?b({!x`DKVp3H>5G#U7Uu+UNxv-LUu%Wa=b0dn$jn$UrSY0OTWy)$-&Vp zNr;E-snMZb=7g3`zI@Q2%O{sQ?6!n3dzwXyjH+4Kzu%&on8@TEktq%b-h18`?Xaa} zpoCdEw%)#6YhrQ!H`QVtPqkRb$B0*qo&vey+NR^9F;hdMiacL$%B4x4f^Q>`zI8ri z?K*w9ObEb}HR^af=7I3NR&G6L4^srjTJ+QeCB*Op4fPOIA}9f)zmVy+^sD02WSTu8 z)g}Lxn39@kccrxs#tHqc=(STFXEu{ss2K}{TR)tHF&)O8I2S`trz3q!VuY@BqtLV4 zrF3?>_Vk9>q@-9iGcGYP?##jXG`Bq=1tKIs1l+VEB9)F_*th?Oti7Bpx__Vt2lT$;} zqazYSC$i?}lz5^d>?u)U&gAs+4EZ=ATQBH2wWpCsnZdow z2;{-4MRr5mMyqu)m#vbpcpCI=BdeqpX&J}8v`!uKCfYEX<(ILnC!IRl_b%zlcQ^2f zCKs!g@Dx&{H5r-8?Xu1zY^NWaVJSoz5H?2xmfOK@;uUCo2yoA9WW{=%aD3DTSnP3n zp36+6wbq2SX%5UX;JJy`bFhn*T5Fv;aXazAnv(3Q zQSH#N_D939N#>}p6tm&mY1}fJtd*Xba@z{U|CnSxB~9v5mFg)?jwnb=OmKxp<(4Nz zMnuO(MA=h4{zoB?Q_bW;x-&E`D7*uP0g+Ms>_bv~04ch0Td7MCzZnQo0GpxRL8&ao zf3T5XyEnK(+|iK}E?Ge6+OIXK8W5?nK zYArBV)r@`VA(%r>r}i~hE9LnP4Hg`4!+!b_X|(24p{-U09sGVlYj{?4yfdnGm{rb= zZM_i9M`A(>KG+f`D+aed86B6HqISAtVxwB8EtCy$XDR|45lAx(Z5>iY=}coOQ?SZH znxUQ-!&As28Yz9N`2<3V=gPf2;Cj@7R$v8@xs;I{2HvWEYt*s51F$wN1$%K#-fd~Bdg&EI znajL(^iF}DZjA4tzERI(Y)Yx-%CRIPW<3um?CRt2iv!|WH8+fh=46Gcfo`IC%u3c< znyo+0+k&jtgurJ>!=i^f?8!1RECgC={lyZx&MLD_{n;JKGQ$<=3||zK7LgpjNU1%c zsg5>v`b*<$%!VRm^dbpyumx(@{QU<#r{`L8U@(46QOOnIPFri9)S{E((^3)=Q{A80 z9N}RJw!MkT5GGAM7arESOv%d<(1<_CE!-(v>pw#xu=zhk4(M>^2g0e*c9*V)c?#*H z6k13>no}0ws$0o*&;&mL`Q^!#0b)SR1ZjgB)WrCtR7YrnwY4$98E;Q=*~5~o@~=_Y z#F`v`=6*+Nuua(`&YX!$PL5OK6H-D#&K!@Fr{a_K^p9K68=#yPQu?r^&&~3_j%|tY zn7PU@$CKA_+p6PZ@Es6+++Kz+oRBp!9#25qjB@TBh=)D>8o;00N}W%*3^M5FwWD_u z9Fkh~^-@Zl zGr?+2>6oal2vAC(%AWD`&WW??)~wyd)=bipHA72m%_j`0FK#Eb8>4L2F6{X_ZX5Mn z#^XyRT)KE(ycfCYWQ>VRN~z~8O^}6cW@eTz=ZxpGjwHHL?5?aRX>FYro@%#ah#6rI zmTRM2F!lT)dlKX0Q)Fy*^1u{%x;35648xkRursZ}@(?%Rn`(Lw&7zt{Bd)hG-i*Ua zv8bSV5OdV&QnsRY!_5-)ws-u}0sWVbFDMwlwEuvm<{M=hAwx4c!;e-&ksHO>G&|zC9)cw zpJwu7Jmj_G+cvM7;TAJI+{h1wzsBLnFORZyzMNlwJRWoC_y~NXjd}=O4jOgnc!xO5 z&xks{vx!f_cl&mm^fbFq^tl@2+m$Qn+aIqj{QPpXg`Z!Zw($0H(X)8_^yBeOpf)?X z&6GO|Ys0ao+%$^P^O=Z|vZ-$#N9lOdqsfP#di8V|Z{(And-Zan=ic_=l#eYKcjV#8 zm+Dvw_EPj|d-_c<9&9nqr}u4`ss0}-puDF`m8)x+GbO8wBO%fjZVAR@AO>jC@gFND zjo(VL6N8I`Q_}H-8x#~4%)>U7>#wN(Ye0n+Ecw@v{2R=`{eP^z2Y_Tnoj>07Ug!9_ zU%%HmrK38)0EtKvRaDjRRu)y1;?$EiQBkv`_Mh5U-=_zs7YUD3p>`R_^$`Pc(P&Qspc z*Rq%8R?sq8?qV*3CX~14YN0h(9B$0z&s*igFDa+B_g}4Y^6!YbZoW@6f%q%kmneS# z9KA@M@nyY^>)$Wq7|+3dE}XuwoaBp0Z8`qnf$P>3He9e)N^&jcK8N!~`r}2Xb;g`jDa-xd zq-?^ES|^>;(07G172KXXQ_t;x#lXNT`oC%?MJA~oi&kQ>O7v?^xIBhV9~(PkMEOlq zs5Cy29n53~GQP&|VMvN^bz*<0hvdntmp=f4k-1q&A|*$00RxNABs4uva?5q6_{^8v zjt%S@sPF23LYSXd)2AAH(gW#CfAS#zK7uN=s-|QGt11s)$pTgtk)#k`ok}LC#EYRHdBd)! zLzUQ2>2a5^CHnV_wyhoXs;>5WF4Z2jIolMs&0=vDrUxSVkSqAKp1`$^xzS?RRJ8Fk z&_BnNuQ!-?eBIcDK1e;_vRc6XhyV(GaDsY<^&;SL+?K{QB3_?lzJP~lJ@NLBtg0Wy z4wdEl#Ir^HFe0x4e&MS6X+&O0vnoNaNr5`XIKM?$g`8wPP2U8FuvC?epj?PXIhV!2 zHeG9>q)bbMwJjX!b-Ci2;w^3)Y+KXTzHy*u^I&rF{Mm`~v*Cp5bt(g6@y^L?X|A)r zV>CT;fwQe@54qK(E0>RUB=WVC%aQJ$=^WeHRmy1LK+5iq1tOJ1wj<_pCu?(kqp#?p zUT|#rs6rCasN!~1lE@s+qjCf<2{_8#$Xfbzvz(7Qm0M;1xiseDtxk*;L5l?C@BF*z z2fXw=8X2S12G9EI`A7;JNUIV!D5eXzR#k%iy0U)U&{{-&(%eOTH=;wLFGp6@kFJDs zuL#vA&pYZHcnMwjkGRe7C&aA~p;1XfB)UiLugHCNoyd4XrKqM{2{J)%EqHl#F13l{Q|qZt`HJ zSI-4YBbit=8XxLTj-KvRi*YHcs5zTG)*dW`v+Z%8(mvT$TT_Y1JwDBil%Bq|wZ`Sd zr`Y-97o6H1QbKKh#cHu@`9!o3b-Ut~HNE{i`$3naE8GXV?4n+xOGK8LP$miHNK2X1 zAY3!(J=Y3EY?8fh;ib{v1mUY^`k={{w;P@LM)J#?_cS5W+NVCb6d^H=Q~ z=-+pxv%3A&YeUK8!H#uro=}Z|n(|RjPy*7BpHS5=3a|RsD5?PhFJ@XFi zS<+3W10)N`@Q}&iZiR7Ke>ib&>d)NM{!J1>WVDh&EA57Oh{iNM3aT<%GMA)3Vy(>p|cSVSw}upeJ*z$aG1VLxI=9kmagenovy zm57O@5JOuDPg6XF>}ljIT?9KHcufiWoMiUj7fsjoZ|>~ej0>( zUdbb19DXH6LcsmVt`nS->eG4@a0Tm5_;Xjc6EeMxkA(OxSrMYX3-^x-e2!3$Tkxo< zX{%B@6e$w*J+Rc5@gyriz;)9PMWhILJ|b6J@CbX_^bMoGkF@$rS~}pEX)iK=MSDk9 zytiD={m`xVn|LgjdrV(x;qwUhg%Uo?*(@)kQE^M<3r4X ztN<}yBvAxBY@%H#O*nZ|1zbZrt@$u}4R{Gw7~tq9jWeA+L-8%5tZ~l2gugZWvc$!W zdB~WPM7KW6b^O?FXVA%MFBB8B7gzOYxVJq~jfA{LR7<#KhbwXW7IspCBw{V^+87Cx zN{A0NLtCw0ex=n*)pXa2-jm)edLN{?YqP$Y^k#yWkU<1EpJfgCwG7$jCg~bv5=O+j z3fd^K1zcQiN?tXm4oI7|q~*9h=JiHw$0aGNq? z%^ZI~N~2K(prP#D3a@R)ik58%H^@A9hJS*~b~x?uiGdJuCR7{#kk1Qd5e%Vsjqc+p7uhAg0Auj*-ei}U!hNqCD^B&lHpbybPOSn?t5(1jR^Y2vz-e^~xQlk@Vq68B zs9(T6te0o2l#!)(3ink}4-|Tk4JZ^AMr<097fOJ_U`WMa%=LqzFZ&yt z!+!QPSJod^8l$eXTaCJZRR5|X-HFcl8pk#-g_(BzR*yd%)ucUMMNb?bi~0S2mRfB5 zcL*aMz+4XE+lX!wk3>qYR$9e#|cZui+6 zcZ@W?$HiiMf|XpVLyw0VPsz+nSttA}d<1_ZMi4pM#4iM#Mo_>NaBkvz0!|}HaI5Uv zP2(q^q=ksuZo}UgSh|4v(1J%Pf3H=a##_|)Aai5+tHkvLTnBe1?jqVJZXmv@Z6IDC zptMQ^G&oO`3ZJC3AJP=D4nA&(C{QdAS_;Lv`|2#j{~hR+%4*KlIP75ObL(zIPr2Dm z_69<-2@TF#T~UrdZAEHXJf(sR{Z^8*_$qIokJ#^w5qqBFF5o0V1iYD*DBv_U0`4|+ z?{>&c;Msyl2~M^vbdwUYg|pb_(Ugv4NA-ue<-}JqlxXNAHV~f7^KW3y8S!ZLoE}F; z2=s%VnbPd}lasGpQ&~HZNF_d3TWD)rs8#3N+vg=1M2#&(5({#mqdhi%<>tksbMcOD zT|P}qHb%R)_4aM;>e|}ZyR8d778v~om_A26hFy6t_F*;Q-!tG=>9NyYO(>U`RJ$lW zc0qu@^N{HpUV0F{Yra#Gp202=85un*-#yo85$|3U!n+T_iuuP@%Qr5U9uAY=4-$iN zJ~)cgX^EBMM6efvcVe#~?wc7BQ0`sA&xZymezMd}6H zVLFAEQZJfsHG5%$FLL?ql6>a!+ZWT@4>9)&OxG-zUV+^y@LzVC);2Mf_Zy`pw0SvV zi`0`-O|NT~OTRbDtM0iFGs7;J^tM>O>@P}|SxTsIG z_d*N)B;nht|4^&-r%!LRpdV^Mf4hrz7gm;PQZMM&XIf9b7oNh`B2UgIDF%9SYBuC? zD=NCeC)d7$e!nODZv!tOayT(uO4|UOavn1hPRJ>@btN%3?(gd@^kj8g<%*LKJ{Cp4 zL$kO`5ly#Rkx&{?(ps~hvZFOBj~lw4ptvs@@RIa6xD}Viremg!&G)4HTjTS@Ho7II zbLo%rxfq|A=?q%mSjV)G#R|5Orh-+Ca0*6>{(=Eu>nD3eSXAV^sT+lUNOfaZzANMQ zdDXBU+t;`4==8#clifRK+LOWKKk2MTqb0R-y5j8gjc%8szU*-2D$D7mqDRXF1G;MW z+haYMsvd0y3-Ny>w#$7?B$zwUbUt)yQdzEhDxDu%9rX; zXZ3oCs7{Q?NdxExy1cN$K%dG3{y zljqG8XZkYc7`eBIEh=)ldm_{|-_|zYRhw&XpOd0!YkP0sB8)|DIkG1)du7g>g$lsU%BDe%krmRxDc88gsAMaA9|IFI z&;9jDEH`^(P1~ANItI3MJNl$p&$=Eptmz*2_~~<1ea(^C@^o8iO}TxhRGO))3A0%Z zTr_x|_+x#$ec|Z(!2@gCySMhHhfkd-dn~a)ASL_PoObRd!@I7TJJ`9YR$JfMvA(Oe zsgr$Cb_N2PIj)6dmp_0FWqyN~JVSW{$bh7o|BVDqoWlpfu^(>1pEvwS#GB4v0sk}W zVB@?#NrdJ4&mbBjbNHnz;8y8R2Mu{(?vfrhi?5d0BhoAR*B_PsAO017lo(b6^76=A z#Q7C?5dyinOzAH$E;h35iZ$~WfyK5=nCswxG?ua$h0(t7-4dNdH&T;3X^hdy-nLwe*LW^pF8Z{>!ON{UIhnf8e#P z(r-7mFqGeIK#K$wv)R%CW8`Px?=(y4`=2xsJ=O_d(}pHJlB%)HhDmE)MVl+cr4Xto z^90`lk31F_Lyhjt>_>g;lz$hJINt~RMw3)#KVT0&QR4z7bFyS^3b%;mbXVSCN$ zSVhfh6x5vCyhg}MXUb;}I`ncUm_BzBc+>jws6vl0#_5T9I)RB+xUu$N=Pb)cQW-+n z^+9_VcwB<>G()q1Ld9IviHj$@cFnXgDG_9^4>zt?&F$lvu8Hlnu0!iqEN55Ntukkr|ozl;W{Mli}H z&Y;wXneH}C8Cn!sLrs4UITOL)(OY`rd9GGA)|H+nN-^bO`;~|lW-@Fgg6su`!Vb+5Il+CB*g{%QNwpufj72~ za}WVPhFxQV?*J~BTlIfu${MSU>eFf#^&g~jz4)pnIITB=W4)b2XL~_5vL$d!WQ6gV zYt5G-3|r4)bZz4@+dR7=MKh+>%JAbib*q3a(>*GMMh=cPp6BicM{YQq9nOg-NkkBz zcIwq)2-wi+JoH^)gBipq{CVjctQ}a+E$v(Zw@NRZLbacu+VaiK+Oo3rRnu2^?Sm_7 zlZEqnF3+fkALC;HrvUo;pdAfR+~4#8iOzL6Au9R-QVyvjJle@_C;ZVm)&C=xDWa8! zqp*8%KB5UH$I|=>=wlzm>_KCtx-@$N`skMk@81LZET208J@#eH+|qji{WIsy0{YbT z;CyuI46}3IET9kEMlEnC?>Rw>5}=$PMos?=3{TQef-W62eX`a2BJaIbdd3Gyzw{7V z`2gqL;wuk*2VX(1naOlFS$+ogPu_>BblMRMaK0_-KK()B+rvwv?C&Z6iq{pbm)I`T zchLrN3b7A?@WvC)ktS*r@Ba3Eunw1=LO$#_;nm`i`Bp}3Da##FqbS? zp&nC+GG?2RX)=6*Rz^$}KCU`^kfl zq)AIkS_%3ak6!$^a{TxHAI|;IkN7{)!luSk^gZCVo6qPj(|eXKY~i8&-{8SMA|~hM z@W5(CzfJ$f`+dS{{Wp_xVr*KLNjV?iLINw8By3oM>60U0t_yOGcOF6v@Sj(Sp z)yFE~Fw-w66zo;Z+hzP~eCQ0*O4~b4v#aYs|}GK9bL{ z(?RpRHQiCv^y8{;PO1Gqzu+ygHq+!moW zyJ}@SLOd&2Imz5pFKb&`dBJSQ%gsM^^L9!N7M>Ll4ZNu-=x2go8Fn@@k(w(BxfbLZ zl*Z>STfhFY`FZ-CJJ_+lTHVmmv7uUB-@$BKj?Tf=wRm)X{^(+Tu~u8G_iwFMw_;?- zk{FjB!x&s<(AqB`iJI{LGT^YB&-S#SWY3D)L~Fu>K&||;1wUrG#?U$em$w^mSjR`9 zZNQVh$F!5Tc5ua8WF3DSv_+oum2V$fe*1EI`yrg$)b#3)%d z#8p0HMfufB52O4E(`h)trP;$j80D~$*HK(ajK?=y&hvNj`g&qY3Yx1J(5ao$Ys5LMQ@r|!!K|)tx3_Bj~Z>kPTAL*75Tje6qf%!#Qo8~ zUzl!gz9YZ>gi;#KPh%d6@Cyv{RWyoKbi%434U_g|Aq@a#qwrw~dm0k)#7(b1=~!Q@ zuJ7zzU#+e0I9#1gb`M1(_4vBW=jSh9hozUF>L~R`eO^a1C)l=Ptu@XZ7;GOdMeX6L zw!9V(%m>vJPB%rt(x{oDZhDnH7A)H8Ks^`;-}3P<=382N-OOlQ7V61io*Kfw8S!Wnm6W{c=j~3j*~V*&D zMvl`;>xL$ZlRPP1Tn{l2)Wb>w03=t7}8Qi*rvgK;eu@#vM| z{O?3Q7<3zUBiE;H0kv4AhcAOR#eE+*vjLPQppV9hc99){y2Psq3jGMDB11!`vpxYQ zkE*Es)Nf$5o5q$7uBZ+D+(rC!fY&9Dr>Oh1nQY1*Kr3Hv89K=ONncK4cjo8Od)V@? zF2WSiDM41a?w0do3239B1V%!*Esg9-j7`ZQ1-&V6e6~ASPNw^k>8ZX<|0z9*$x+=Y z2i#egI$BiQ$C!2 z(rKwS;UhAsl9;uX^`8Np=1stx^+_KAy!jqhG}^+a2sn`m2?ALbAt#YBZ(>qt}2d zbp>>glp0Q2!~I?CNBq1JkXAZ3YxEFXUqn6C88_{93i2;}S=K zwY?Jhe3qz10bMLZi7s|=y5L`wH?-P*0Cxerk+*$tMSZO1R}xhyShtt0_~M@=TDNmJ z{Sem-AdhK29)$wM6Fubk)B9xP;QQh{D@Y_e<Vz{P*k%6Sr?UyxB|AHvva` zO?{QVzx>{Ec~f5%?KbgPE^q3qqP&UEa(Po<73HL_5?;;nroKw0Ch36|){mI5bF$TY z;_CEPGma%{f2ai&aV!p%Uu8g>k*Wtw+j*pF4jL)Z&IpfGi9A&vs3MA?rRC>-(B-FA zWQu%MV(nSkt9uqwJ)`jh*xI#%zCdTG4y~Grt9I;73yO1B#(Oh^ooV|XTtV{^vLkZr z-<9^HN(n8-GhgT^wPt@Q^Tn9G#|`c&dfXg6jM_YD`J%^PYW0}nR5YXCrn`JhY3wzz zNvbJo?CnN&s0aulNtFbfNNL>ai&<}0Z}FyrF|&N9C+SPrza*JslBy_;cRJX`85Rjz zJ=Vtdq$D9(@^-Vw;Y%8={~WEu$A>5em@uWjme49vGDYjciHtqvDh(gcPL)2cCM4-S z)})f~UKl#toA9Nq?={ClO2qQo(Al0$AZR@&_ByAeCPEgcxv?FGp5X}B4yo}IsUzSI;3S{_ zZo$9ZffKa*BVRCxd+k_v2!fi-dg2Y=z%z_(!M~|<$a6Z2f3I}brY`{O5@1Dsi zO5c2?zPU_1a(JjXm`+FmQ03O0=l6Qt9BG?PPtOd@hBF=E?j3`a@`3VarpMAlMdodC zPQvUr7_Fa+QOD?VEstYN+>qc_smTqgHt{_HZSp;W(oBdpnvrm_E)Ge77W^6Z4V>*k zG*9)34~hEA{E*r-Qr#nJead3Q9Z#!^1F>Sm|ANf0MAhu_t> zmG(=Euh6JHVvO1?eAEP-Bn!czu}u?Y3n-0`sQn<$mEv&dQ^2(ae+GU7x}B#3`cfLY zt;;mSvjMsG!_Qn?VQYs<0&F8n5?T_LsIG-L4;0LfXsnKuHgo^@L|@O*naN2o701 zmJiBt(M=uT-p;y z>65UC-_t5Rx?DQwLFp6Vg_Jcb`tVDm6!W;t+=7zTE_!h6G}eU5r?y%;ww+}B!)yRr z6SYJ=Xuh-DgO%?dUVeA0&<~zif#dvg>8>ZK2grz}Oi7NTd~msR=Wloq`c2n0OQq+G zQh4d|-WC+6x*9!rU_$hZa3q^S%ve)z5u@;pow?j!K!kGYetcaA9 zM3=E1+Hn*nov@nG?d9%@Gf~#6n|kUSN}Y3UBj*-6f-BZXVR7~e#ba0edfaJG6_n+T zEVTZ`40>9l^Z1e0_{z=oQ(MpPKr-QyG&^-#Wafp6Lk(5@DBJjdW+D9WmzWJLt5xf?nbX{oSwr(1c2#GN5GLz8&|CG+TaetM+e8 zq@N*6NA8p!g6C|AxEW5;|3}Wd3I0F}UJ`IbQ08TvxQ6+9P@WL=mPXBYy==Xbs7H|( zvqijTPPf{BjK?bJyUq4(Y#+7Hu^p9*E83kWyr7dmNcZ#cNREieJt$q*Y!BxWHTwZP zd41qX^+i9WO|9?YJG@*nd2!$1tn^=yrxhOkZ2EdNh##&}gNjH1_18g7E6)dhOJyjY zov73Xd|_1$Mf_^m7wfeo%f(!>oMUgSZK`!FlqaSJGag;@{!vkbzG5jd)Hc)GS?%jD zRK~z30_=LW0Xt5Ks{bNIvkmPFot>1L+}XL%zSy46wYTT;?NXtWc5ZZ57b=y7YO$xM znD6R>HU@24>c%~Iu+&9f06&=(-GORA-N|K}xwtsFTs+(m2qFJ891gIr(QnKW4gm5) z3qfATA2^`#8eZph77P7FegWiZBeS3S0F7ih-&6R?PfVa?UE41i8M$Qp_KQbHFWz2T zQz)#d)n@Yf8Rwqc&OUtG?%lT?KKr&kXO3R7ZTlsoqnB*ocF8E&)Ea&=*u4`n`U4%7 z>jcd>HPp?=LrKpbw?CMQzT2TWLh%%0&*8w7Glk<&&$ODwVSUurAbuLaw{xZbgdITO z2twZg13p3HfHGw(vF~wZ>Yw$f_g9tL^gyWA?sEnmYAWE>C+4!#2l}Um|IxK4M%ie3 zQ2BlJ71{cXmJ509v4A(~ja9;ZdnX63o%pDeus}3}JuH2W_Q1b-6>B0to}us5n|qSP ztN{nkw3=+K#C=C++XJpZZ>BKWRvgW!(XdxVdi@vl#`9d)8;wR>_Af^4MfcEYz0;R& zD6WtB-LcnN?249~?C2ayAegGU1Fmlb$r+Ojx`K{-VrKjBfw8sc4r@VY$fah1tqT*K z!1#kF9KcfWhvXA>PYL4_)4;CQ;(_}t>^weLn*(VN8^_UGI7R}VsN>egZ$0#(L{Rmy zw>WXq7oF@#<1w}LC*1P+Ihq~BHAL4|oe5x!OOa2xLB<)JnrCDYU~N8K+Lmx(JGr6- zJHve&+KW?dnVvR(G-{J_GW6a8N9kEt+UKa$`{6XV>-Z;pelUHk=mvWhvz#sMQX{x{UalL2h&}@OZKFaJ&EyJ z_xJ?^YmpI%yubx^dcfB|ogds&ukRV`oT>VBS823_14sII)ypHrH>JAb@vc;DbhI%r z)s^W>Ci^m7Q^bYD?A(L>n7w3y(llU7nkxx$JXi@>R=fi*N%f4JFgx9QXWS8Ab+SCQ zzfa6fa=1iuGc4WHv3_4~>CE%bTGS;yqDHNO^@m2xT1R5!>^0+OPwdWPY9{i9$zpM= zKvKuxj*z+FVUU^!ut&EHe8~g7$j%X*AG6k!I(%`jlro?1oNX)4Rco__(rjlYpUdKZ z&YtakecOA)?}qWN+W2^_YaEnNz!&eueZvMN^n*{f7$vz?ut5J+(XAD$*A`HKf~-kP_w7{VtzYHEXAHk+o;p+bZI_KvY6db?6Pn&rh06Od51Nqc!RoMb#ApwmUt~y zs>gv}9&2PLJ7k=l3D<_L-ix_2`>%RL;3nXNZFbQ^Y4Ng@A|@9jaB z&4vRupY0B}6~q3xAJaysaz4-ckz)r>3g?6`?Kw>;|AH~(xM*ZWum4f&_N%^t)opbo zgVB649*6`SVXqXF6wkYrU{JXs?oBJ5nM8N8ea_+Y`a)g>-Y|DE5=^_?arX@lZ_uj* z_1E}uJwZ=fbr`A%(d%=p9XU{O%6Jm=$~iBziBb{bQ3!w&G^7udN7M1HsbV1$%(qR* zeg273-&kQZk24wda5CZQm@8EmM>1Lvp$FDKFy1>fQ7MjOr&3`plh#9Nj7G=Oah7MN z!J{R3+W@vx3-QR0RVK-7wZ73ClI2&q-s4wQ|1Ek-l8;z4IiO&(Ivk9uUkSuDtIPUF zHzj{94=3H0`P})?Bme`e*M;@ zu0^oBFo|)_;SQtfigCv5hjc8xrcyxi26X0?a2jC?v7?2omTMoE`xF{rU?IlciZKoc z(+Rh(`a>3}e_*0-aJ*6)$#%|`YFkD#-%M-abULi1xwc(ri>8lTZBiQA@)RHi^YXf5jl%250S;PzN}(J%HqKgVs*mnZR*o zrvcKAU(LTtIQ#U^FIMH$llF5WC?W$=UV~Eqs~qU zIDzx~0qMs5>HX64fDq2_10>1b#oA>jAcQl0tAo7O2 z0I6~a;d~p`ApFXb8Rtj%j5W9-=VZ#8bg*~(R5;`tXZxg3!0nX|2X)ouJAPA;(jS}qR1JsAzqJ__)9$6F&CtqDfl@e zH8g+H-mLoO#V79?<`JU|>c0v(t~=4o5`MqLXK5$99REtV!O(==4RlKvjVaELE^-eK zMB54dzAS+o@RHF;O4g+;_1qc7|NS`4-W1K}qm5Umf4r*S6H7bLt}5Ey)`MHPxcpUl z)LR(SV$N5!OHDedaW;`@To%jcW9<6OkN8;f)(K-;%l9ExTBaP2ZJ?Ug#w^G*m_Wiu z#ksxB+S5zlLRUg3bm!vt!2Pe;+NY&R7l9aj4k>pF|2U>z9 z$2tomz|rIM_{#oL$LOKy+Iqr~0ZXJ-J-T8j88UL8!QG?hpKJx5Nz}&){25NwoW5xV z=AkLq*<;2#tMu-j^A4tFSL#4^W$y!gWgN9*RyeOL##Ed0_b5ys31jb z3&x*)B{6Lw$ZY({3D9QMQKHjjK~Q#4LS9D{TJfj#cDKUpxCU;{8MfIS?oG11$!)jU z!p=F#i~_&Mqev*1XI&_Fx;M)5Mh}&{W@VI1e)jr+cN^GSkKN+->XsZcv%DqjcAITI zk|b~Q2B=t)x>4-WEqN5@tRc7CV(*b;Du!n@4N|-w>xS-WXs6p0pzYI*b6{Z^Q>Hin7A0vVYVg^4W4&2}R9kOOZM^H6NzmPZ2~8`$G{Fgd6YXC6CZ=HZ1M&Z*u`ZM%2U``^QEj-@F!z4RG8!#-T{o3;SYekQY1*;$yC=6x21vVVxy z=pFpTH*8qaakW-3jxQSZfx#=m2l2k?S@vDFo!%#zv^;}n^8~zJYT((Jrp4%gqQ2b2 zPI;O7(oMWR&bg=h{ClE(eD4C@Lwt|k$MX^KEbw2(XKBCmnx#)t`_Q;o;IlUn3I*5; z^!xshpZ@VvCP+WD;8WS#`1=+9oJ4=F=HC;~8GP>={=H7%UtF4p4tFQnW3zNzB)%|U zIA@y24w7ljsvhU&bL;i-rDu+;!{qJ+>sQpN>o3I6r^= zrR^TwN4B1dwr54#9Cwkfg(Xkj=)qo6G;Fn5$Ed+=<+g2TFyMCKGlS=Da(*G{)jXoX zSGBv*ptT#H+Ibs3Mf2o^zD)P$!3RE@<%ri2pC}RIMB^k8N}RP4^3)OR#j*9n0Mu zv!mc=hQ&y^2FB8%^K*?qFDF9#sXrX{f5hs%o&LQu6p-5l`Pq*L-9(1eS_G}lh}Ncr z1H~}$d+BC9W14UyAzJt;z5NlJ>vsBAx+4^L@jjzH>9?Xi&~b6;a?t7Tu<|d1X1WC0 zx*W7c&zJLO@6ut=!yoW`1%D3V`OVVr@qCm&Z&^AAy?YqXSDM=Jegw}m{P`;WoPn11 zP1ETp-^ED##WTAW&qdtwOFHW=(wYF**nRBv(w6|g{*V6+`1Q!gq}-AOyPsVn-39oY zz(;KO{R-zNDRw`0g5E{C6*LtR4n&aL$4478L6KaEP37tdr_Q&8qJSRT@o? zVKQazic-9_-;6iFTQ8G%V_uHIwY+z{jQU3x0B9*vWU0}tRT(j5}WK|#eVc6 z02}Iy>^@ixZ|3_?t@>@?Tj{s#KJuGEbEJh0kJcfFJb-mDPE8#kaz0zVyv-<)cg*N8;Fj$9Ad8_hvo7WZ!K}XEu=J2byRtwy= zaZ={Z5q>~W{5@oDONRW`HO^Q}{tf@zHtmc@W$EqhQSC>G{15p*Tzf%#rcdzpR<(u} z(jmWXjWZr=y~W4zD)vPwXN==|jMtlASkK4tD)v1Nr*S0s4R(SDkO}s%R0j3E`Gsw~ z-gVgLOwTvix1l$IrH9$0@Kk4M50xPYdUPTnp>WVplj@s=lVyeSVd2!4+oHGWe!FUm zC9DhH&6~Xuw;o`6z^2&SI_z`aZGO7S32r-F)fC575~`&u#co==D9PrqFA!p^z0x?c zaUHuZ5>UhNa|Up;JJ!rz`DR3ew&9L*)0xm@F-c8NF?VpmvDegvfM`=gCoMQhX9z&Z z5FaMuC!xb%!IXQY0_s9HEE;DtN$*P!#4Qf5e`G#inrSag?da{AwS;jUcPOEn%a)j$ z9;}3Cu0G}TkG^IhyY`aB`lj)uH)M5|Do3`T`IcSfZEwHp$VKnloL{rA@%=eGp~skNDoD#nE}ns3Fpr0B+^W>l|^ zV=~|ezy0%Sf zGs;{oH&w38@2Glx+3@fMr}aB6^3cIE2HR$)3tfvn-39n?ePO318Sg8mCPyNL%?qO% zGN)Z>TJ@!+yO0%f2Sox!R0{$^@F1X${sCvqFnqh{3@uwBNGQnlXLrnZ(48B}>m4q) z!)XuWZe>>_8D78nU~TZy)4rnw;oO$ajrfm$zGFD%cG?p@w^=q@vzfx=n(3XvG8mFVj`R?vg76l^e z0$o7YEg_wI6Ufq_Ny92QeELjZU$Aq_X#1%PP>C6ft2WK;Ee=)ug_PR4sSD>?q{n*P z1LgLq^_ihl5Uz>YY>~-)yfYT>sHuB*Hy+*}DQKzG1!`L~#q_oFmf_S`e`tKTq-AwC zjxUN>y}o3?>Wc@%*{EAxoK(8H3+7sAuDy3{XOPJqMSC!il&sN2AQK9ub+0+N^@(+{Y*N&dE*x9*w&gj@-{JZ6xO@pV84V^wZTvMzrd))2I zs-^KfY{5WQamVd$n=jIDs~@;_-GDKSUo#?U0YtW>BcVXR?+*m9btmX!xyJpzAlvKo{pwdiE1ebF_$9T+%s;g{ zoR$X~&+@0N!dGR2-2gr9Zg>Ys<9X>=w|wtkG%_$K52Kpz?9AsnJJ}7D`SyPi|^MBz4Vqf8wA5W2e@r&Gm=V=EpW{ z>NsuAjPv_5ZhubkOG2D#QDN={EWJm?8V2y6L5kW zPB|pzz{iO&g8FM!;dmuU zxniarPUiPPYEr(>glXeR^Og)j#IYP;&l(;+YkHb8`lj2)ve~gV zoDGp3WA4_aYAf##YhAf^{GX#5HK0XlowhCACEtuwl&sP_p&1e_zg9XRSCEN>;KHm} zY5lM#Y2Gmj8jL}8S@yKlLqqnEG;gVg?1Qu5ic=F%Fy{}U2=khB;9Is0Ufd1 zJNQYJ8wa*^g+lIt&*dwpI_Apdwbfjk*MnifVV3-4lwoXp>>QwO)U%E4`M5a1lFqkG zIgny)>pEp<=+thH$E7Cdd`qqeTrGW4&cWZ8gIDY%K0io7*lMe8J^CAGVRImAVef$c z<4af@ue53JqUX08&*$4THv6|u%sElN(<%2De#Y;5ykR&~oN|W&_@T!m>wnWUS+Vcu zG|ZA@@SHks)ZGEj11l096tYSO24D)&l1B=TakdXML9YK;^tjikF$+d$E z1A%F0H0+-CD-pKAgVeqmXC&-i<5vTLDHnE~Px^h4#;06Se_$4m&Y8elyXoxb?jHUd z$pwSCNTi^u1xdmS$TFJ>1YFSo7_cYcp9a7=tu#&xOv0h>obGmwIR$_Gx0l%vz3my_Do;F#*b;CO($Av&>7BaT0R`k z1p>MAdG2E`{r&^lnxCPccXV#&wM{{D3kTFBX zlMRbg=r5uhG)GmL^cVaEeu@|2IHjCLx=jX8M6j4k!EIa9DICh{c$j34JnoGzbICSB zzn>~^-JA<{cpR!-3#L+9uNIw|pVa)hgj3NyZ~$xJzCQCtPY9Ras`WGHI~U_xB!$FI zt5(mK2IFc-4d=fZ36eq*j2w*y1K}u?kne=UK8M8`3uq~q)6QTscr8}h?1h2?4)3;% zX|`NnrnqiyCOdt`P&njC;NEt-RgdI{bBXEM=|pJ~31c!m#gq+v2S%$(l4b`w-IV-f zwUGz`?RsUdR^sAVL!!{tu>>l%Km>WZR!BhKbSBq~cYCZcZzRmjL%T1yTh}A3+vc_g zb+4!KeVenW>nzGjHaA?)vBpnrlvpb5C$c#HiM%(}llOWUY`KMz?42oZ*!?lHCE;~x zR{VQQ5?-WR={f4T)odn7DefN0V8-DWz%B!tH=_%rso+n-xv3xH*)Y4wFYr#GbOVVe zb(}@K35P-?=zf}w)f(=nfg%Ky*c}`(H~u=hc;&*vm5Yt*IQ*!%tA?I{$I>71^Atu> zquc$OmJ^Qf6r_cF+A=mYXsGF{6e=Pru5fYvej>-dQkkVMtgAG}lkA0;xrvqy(#p5l zXz62L!|P9~B(+p1%=OZ9!0=jNNcYLXpJ(7`tOeZLOmvN0^OeVPtH!=}x)rU|Mo39* zv~C}Hxm)enCy4=ZPUQN__uH8{K9}$jtH9!b-{9n<#z_ypoYiBA?IM2@zB@u}DnCa! zugf&<3~#4Cyh3L~#dQRmEi}Fwd+KF7^Tr@D3|%e-29nQru@cn$KA&IHaAV9}f3b6B zlLcc<_XOIJw^pHO(Kf+PdVAHsj<_NA49Yo=D`UM&FNfttWXFA+lca|a{N}%e+j9{e zYzbEy13|h6Mv{Rgw+jw%c?B;`6H{T$8BYe8YU(-W3=0&h~kY$F8U1MUI zYVl(GLNzvnJBwjBrqzI%M&?bHJ{K);P| zapLQz-wC>f=hsRy98TJPYPYH}cSQMm=!>@SYaxFThJYZxfuu1bam+q_^1FF_A$O?p zbJ*c-H~iK;rsqv}BR|g7!kFWBWwN6qnXFWv=fBA$79%r-mySxRoH=>M#2ogw+sBuA_4$cyo|ws^Fyt??ONr&Rjq)jhjI3bT7pHo_K+@Uphq92+#;xY`&e z`p6Z{*6xgB7dP@{;-Kvw(^@GkZRD+j6jqP&>UQ}PLU0feV)4GrhZwvAgb;4E zKH+0WU-H>Y6vgglpNrVwdv-V0LMAX|6zyPtkk%t}+*n`rLa4w!4Wy@7IQJ)I?@T{- z@31}A#`|23xX+=v*e18zm`a0Qc2+gEK+{B+x$RtMUTn>Mi@ zOViZ;nP54hX|6^N@D*z*iEprvIW%|UQ)tr7*5ke_f70b_+-70>JH?YKWXuew0CZ%`RY5#fmN%a@L@TtAqXoyTH=8*5%gx z?y!d)!l4D8#!W~@<8#MJn!{di$a1~e_IBEqLp$_=!K7(D z&gkBTxol$4vOqwEEBnm3Z?nr6lCc94#INECdmHa@dt4rN*d2DMfn?(!tn4a}OIzQh znYZEVmXOyQHsk9tU&;lv%$i4`jiBHHJEVYgA*UwthOVMZ>UUGi2ajA;wwts!_6GX> zS}2tYgDc$68O4?S_f^<95W^|{(b=`*0k224Xg)O->q_x* zk5`n(dUL!yY30Rrwp&l?enr(&(L_%&lnALlRZl15UGaPH5KvUDkc*b1p=2l<)KlU9 z5#n{G-?8trchM;cXA10alhDiH&kkur<9+a<;d6mlq`RaI4flH89%czDYP9Ql zs-8SQ(u5r5+aM*zp5;FfTQ+<4aMAR5Xo{XyCwDd6CImloNE`Px*EhkjZyVS{d?Dz+t%V%)xGP=?eqHvyVtc<7P>mu zRXWyr;(U@q1-lq`fwdLuI%pKT~pVJ|!eyP$>-y9~T6_n@IkoV`EqMrb>OG_@Pi& z6waSmIi%*(zK`bTI-=eBhl&gJj*Z>5jh+2-xsQ3%`Ji5jMJu)Pj_Eb0mOI-1B@zmE z7mM9tWQzS;p}ajD{+ISj`P4PjJIa;(zxi~xC?&q?TDl4+_B}yVg^}c9Vr43YF=yQQ zfLXgJ(v?id6vdayS{DPS%|t=xk$|Rzl0M7k!0u}u;ZQhl8_2Q;4)1ed|4PyxD~B8D z!~5_hQtkf^J`mXR#?CtUF!-#|PGb5p#-lkzlpkQYG(;H^rK-5jd0b*!r!U&xmFljC z)mPDemz#Z2hk4DW!TqD72kO|3YIa7Ho9QZttE1t;?o`()7fIi!E?&5%cmIxcu{62k zu*uqM-g@)m$lig0y(0r>pHsKs=I;yd_n;c)PX zo;)voPbw_?Uwk^8lGBNh76UIyy!dOt(l7oxoWi)5G0hK1x0y0LCzmo)z{OgOKLfun z9Kp?vxaTCYO#QX_VU=YQYy*9%aj)aYZud`QmZzs|O?y^-POoLd*lp!`%9HXu=?WoA zitki0T37R|9Mb{#{N)w9t4Y4m*+^oMLjA=E9CB;6_oQ~Y96>#P(Cu-m)@$7VVGVlJ zsDz`%L(GSJGNrO5u0%aGtK@Mv{vb(VFZSMwM6 z_9pGv*%K5yd)PwnseJ>d_Vu0G-?yW8!&Fz#g&L2!d>&8ZVYmBy zv-y5m{)yTA6Ywwi8fG`imk~VV#Oiqh9;$Z(-Y;!sUzJY<{22Hpwf_h|Er{S} z$%k9;hj4;5#RvwaQT8EuhTv8@A@oU{gR~CtPHB+6O+HBQf;jz0GF=A_GA!+6XM&!1 z#=;cXtg$+Urn2IRb;cv{C@ui`c{~z}CZjQFryhaJ06)lsi}>IaisCPls6Enl6WwNP z*rdxX9!^B#ae8&T7E$Pi5G5K!eO($beOvlIc@eNaF*!t%LTdmTAF+5WxWPB6cy#*~ zw<---E&vcXc%Zw!<(>6kGX2L zkWWe2?E~)MO)kY%v#N?eWwQ^u@ENbu9hiq705=8O>PSpQ;^KnK?bmQ|Fdl(r%Y#Q>Blt!3JB0)oq`NxV$rVm(AgEIoHx?cT1btkn}Us zXSRtfUs_?fiJ~RmpeKAVqxQQ3iZ8UF&$v~eTd~^v)r_<$GU4&MJnASLaXLLttJg8X zt=p>9#m+{i8gG*V=9~by)@aP7SNe8-tm3f4Ho(ao`B*fMedYmw!0xDwN?kY*L5ui( zlt$z8hl8maBmit4sh{CO1Zc{CCHv_8iJnxdCn0{dcv20<<5GX3D~>at5?wG$5@QkM zFh5@`y;zS;?Ilr%UHYRjiQ!u-&}lHQqD+uL#&X=c%+ zO{sXMI~e9hNGhh5qKG(oJON#-r7i4o>1GoY|83d+KIAH6bNrr4<@c3}w1w6R=A$O{ znVyvX#Lp_^Q$VweNyn~+6X^+RcX41+$w!N2pWEedF&rctu-hGq=JjX}JF*$=(l0zp zwB+|kyiUd8L@u=>=ydDYKIXDn7|sQuaaE;_>|)#pz}E`6#))edpFI)8wya*q|Bj9I zdywSlGnVy6vw6f3atA{mENhp?f5Ib;MK5^XD{)RO(Fm*tVZ4G{V4wwwBPjU&!f4sy z09oixXFeLsJDj?z1Z>XonDm=SEfpjh(REHE=_+W1nZ6~>vkQ=sA~Lp!?8N9nU!fQz zqHKH^zr{21qb?u6s77Su7dxd7rAOO+Dl+ozL7xjqo8d++BGAN4>)5ThvFdEj1^a1} zxzV(BUAd~`a-_m~cI){0{)-$2I;}8`DQE?jorf8W-vl*lc*be z8ul)U%qk-yNLdorQN50g!t)$)&AB)>?0Sb2X0+#=f56}|{s(#ismV6#L&dJ3W6M$zFDz2J@L*sPW8bds<=y7Pj}$9g z?J(}Q0CiDMPs)M*^JO{EM2m;b(q z|Kqc6dXY_IuRmt})tvh`x7nOYIxUX%N$4-OVndiCLts z;?IU`#Ph@a*^qO1e#Cg6OA0(6GZ8++(r)%8SY(Fu2H6^ZIG&ftl7x`7n_`?0{`^L( z0`@}uKiryQm2TuZks%-O{3!oI2Ia8v%=6NXw2R~`Fo4kygX5#tV+J0aSL69{{%r7A zJU?NSb54lo-*P-VL78{Igfb5~V!CT_lqgemucS=Ve}gii71GM0onWg7beTTi4I-=! zMr#(ACtgj2ydIlfv--4nC*6BS2l?5tzZB#NCy=Hg-BnY)i6ECW$Jt)_9E=*4!e7** zim@27?S;?N~Xg^h;Up_2Z5=mwhc*vCyMBq@SA}m0wA|FUU2qvW%5W z`p#xWwOMyKbQiQS-$9F8`nlhOch}lop`a&X?={202o3aUc7=Q$&o$#R%TUIMtD=ow ztb^5%En!#H7W4%ZcH5x)|Lg4hU84x1IDWh9?e6W){{HFx+Qg7VJ-sC6Cm0b)h+r%t zVz9E%MvI{7QYl!8DH70Du(L=Z*b6o(MEnCRVk5yOq!Db_@0;EGl}jwr95>wU?Cj2) zd7t-q?@jzJ22gpnHON~y{K~LzG90170ZI=H@RQ;CB^x-Ub9&b>XBnP5nE7;7Id4rD!!dlbyHO|^)@7iEte3n3BUU+dLI|}geAOD^5wN< zgr0)@HEj(SMLVmeUt(raUC?94bYgu`LFZ0+RT`QvsVEYumzE8{D*BdHs8!t9^ya-ajP{#MYvLMckC9~sH zy#jt$ALVj`(fYu(DK`V1gTdOsL{dkk+;FhsjZ~7lNti>L{ZM!zUG1fu2aU#GP|hJV z{3!l2EY1~v9YZ-;!W_wJo0>W0OmoVy83W~b7LHMGQI6s>4aWd>Q;wz`LpkX_>ZU)G zUUw`49y$m`manK;E(1M_?0N4Z`-E~ikCIxx=3L|-ic?O_i*)6dtSg429J2bvHzUeHxIR8&zuw^am#3kTXP}Wi+I?ux%pQ}9agY^9G_pk6XK&h>pX@`f`=her4}%=mnIy|A19%5$!G*F{Vp>tKOr{Ef9fo-=F|Ikz$gm8u7-h~a zvMeH22={HKcZA33{(ni}WLxB8x!Grm5J#;GPt(tRB=Eb@*a8TQ&^Yp(LX2aJk1Nj= zg~ofu+daQyoC#`o>`0gR?nI2*4u!)cp~=&gAgw!==_0bfK3O#!W=L9SR|4jU8_c&V zqcIE|msxaboa04qSFc$9JXSw5MO!vG!7)Kx;%h;<;!6hebX35qPu46;+%OTn9fgu< ynRaG1aen~M%_w~3l9ZVwxiIwRX8a+tp!dHZtQ9`+Six3i#?k)^? Date: Fri, 10 May 2024 23:53:30 +0300 Subject: [PATCH 61/77] fix the messy display code MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../remaining_distance_time_display.hpp | 8 +- .../src/mission_details_display.cpp | 8 +- .../src/remaining_distance_time_display.cpp | 191 +++++++++--------- 3 files changed, 102 insertions(+), 105 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp index 9a1c34be910b6..843b75e352648 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp @@ -46,10 +46,10 @@ class RemainingDistanceTimeDisplay QColor gray = QColor(194, 194, 194); - QImage distToGoalFlag; - QImage scaledDistToGoalFlag; - QImage timeToGoalFlag; - QImage scaledTimeToGoalFlag; + QImage icon_dist_; + QImage icon_dist_scaled_; + QImage icon_time_; + QImage icon_time_scaled_; }; } // namespace autoware::mission_details_overlay_rviz_plugin diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp index 682990135624a..81244c5de16ad 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -93,8 +93,12 @@ MissionDetailsDisplay::~MissionDetailsDisplay() remaining_distance_time_topic_property_.reset(); } -void MissionDetailsDisplay::update(float /* wall_dt */, float /* ros_dt */) +// mark maybe unused +void MissionDetailsDisplay::update(float wall_dt, float ros_dt) { + (void)wall_dt; // Mark as unused + (void)ros_dt; // Mark as unused + if (!overlay_) { return; } @@ -146,7 +150,7 @@ void MissionDetailsDisplay::drawWidget(QImage & hud) QPainter painter(&hud); painter.setRenderHint(QPainter::Antialiasing, true); - QRectF backgroundRect(0, 0, 225, 100); + QRectF backgroundRect(0, 0, 170, 100); drawHorizontalRoundedRectangle(painter, backgroundRect); if (remaining_distance_time_display_) { diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index 92ecc79026075..4bf04ebdfc7e4 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -14,6 +14,7 @@ #include "remaining_distance_time_display.hpp" +#include #include #include #include @@ -45,12 +46,10 @@ RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() std::string dist_image = package_path + "/assets/path.png"; std::string time_image = package_path + "/assets/av_timer.png"; - distToGoalFlag.load(dist_image.c_str()); - timeToGoalFlag.load(time_image.c_str()); - scaledDistToGoalFlag = - distToGoalFlag.scaled(32, 32, Qt::KeepAspectRatio, Qt::SmoothTransformation); - scaledTimeToGoalFlag = - timeToGoalFlag.scaled(32, 32, Qt::KeepAspectRatio, Qt::SmoothTransformation); + icon_dist_.load(dist_image.c_str()); + icon_time_.load(time_image.c_str()); + icon_dist_scaled_ = icon_dist_.scaled(28, 28, Qt::KeepAspectRatio, Qt::SmoothTransformation); + icon_time_scaled_ = icon_time_.scaled(28, 28, Qt::KeepAspectRatio, Qt::SmoothTransformation); } void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData( @@ -63,100 +62,94 @@ void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData( void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( QPainter & painter, const QRectF & backgroundRect) { - QFont referenceFont("Quicksand", 80, QFont::Bold); - painter.setFont(referenceFont); - QRect referenceRect = painter.fontMetrics().boundingRect("88"); - QPointF remainingDistReferencePos( - backgroundRect.width() / 2 - referenceRect.width() / 2, backgroundRect.height() / 3); - - QPointF remainingTimeReferencePos( - backgroundRect.width() / 2 - referenceRect.width() / 2, backgroundRect.height() / 1.3); - - // ----------------- Remaining Distance ----------------- - - int fontSize = 15; - QFont remainingDistancTimeFont("Quicksand", fontSize, QFont::Bold); - painter.setFont(remainingDistancTimeFont); - - // Remaining distance icon - QPointF remainingDistanceIconPos( - remainingDistReferencePos.x() - 25, remainingDistReferencePos.y()); - painter.drawImage( - remainingDistanceIconPos.x(), - remainingDistanceIconPos.y() - scaledDistToGoalFlag.height() / 2.0, scaledDistToGoalFlag); - - // Remaining distance value - QString remainingDistanceValue = QString::number( - remaining_distance_ > 1000 ? remaining_distance_ / 1000 : remaining_distance_, 'f', 0); - QPointF remainingDistancePos; - switch (remainingDistanceValue.size()) { - case 1: - remainingDistancePos = - QPointF(remainingDistReferencePos.x() + 55, remainingDistReferencePos.y() + 10); - break; - case 2: - remainingDistancePos = - QPointF(remainingDistReferencePos.x() + 50, remainingDistReferencePos.y() + 10); - break; - case 3: - remainingDistancePos = - QPointF(remainingDistReferencePos.x() + 45, remainingDistReferencePos.y() + 10); - break; - case 4: - remainingDistancePos = - QPointF(remainingDistReferencePos.x() + 40, remainingDistReferencePos.y() + 10); - break; - default: - remainingDistancePos = - QPointF(remainingDistReferencePos.x() + 55, remainingDistReferencePos.y() + 10); - break; + const QFont font("Quicksand", 15, QFont::Bold); + painter.setFont(font); + + // We'll display the distance and time in two rows + + auto calculate_inner_rect = [](const QRectF & outer_rect, double ratio_x, double ratio_y) { + QSizeF size_inner(outer_rect.width() * ratio_x, outer_rect.height() * ratio_y); + QPointF top_left_inner = QPointF( + outer_rect.center().x() - size_inner.width() / 2, + outer_rect.center().y() - size_inner.height() / 2); + return QRectF(top_left_inner, size_inner); + }; + + const QRectF rect_inner = calculate_inner_rect(backgroundRect, 0.7, 0.7); + + // Calculate distance row rectangle + const QSizeF distance_row_size(rect_inner.width(), rect_inner.height() / 2); + const QPointF distance_row_top_left(rect_inner.topLeft()); + const QRectF distance_row_rect_outer(distance_row_top_left, distance_row_size); + + // Calculate time row rectangle + const QSizeF time_row_size(rect_inner.width(), rect_inner.height() / 2); + const QPointF time_row_top_left( + rect_inner.topLeft().x(), rect_inner.topLeft().y() + rect_inner.height() / 2); + const QRectF time_row_rect_outer(time_row_top_left, time_row_size); + + const auto rect_time = calculate_inner_rect(time_row_rect_outer, 1.0, 0.9); + const auto rect_dist = calculate_inner_rect(distance_row_rect_outer, 1.0, 0.9); + + auto place_row = [&, this]( + const QRectF & rect, const QImage & icon, const QString & str_value, + const QString & str_unit) { + // order: icon, value, unit + + // place the icon + QPointF icon_top_left(rect.topLeft().x(), rect.center().y() - icon.height() / 2.0); + painter.drawImage(icon_top_left, icon); + + // place the unit text + const float unit_width = 40.0; + QRectF rect_text_unit( + rect.topRight().x() - unit_width, rect.topRight().y(), unit_width, rect.height()); + + painter.setPen(gray); + painter.drawText(rect_text_unit, Qt::AlignLeft | Qt::AlignVCenter, str_unit); + + // place the value text + const double margin_x = 5.0; // margin around the text + + const double used_width = icon.width() + rect_text_unit.width() + margin_x * 2.0; + + QRectF rect_text( + rect.topLeft().x() + icon.width() + margin_x, rect.topLeft().y(), rect.width() - used_width, + rect.height()); + + painter.drawText(rect_text, Qt::AlignRight | Qt::AlignVCenter, str_value); + }; + + // remaining_time_ is in seconds + if (remaining_time_ <= 60) { + place_row(rect_time, icon_time_scaled_, QString::number(remaining_time_, 'f', 0), "sec"); + } else if (remaining_time_ <= 600) { + place_row(rect_time, icon_time_scaled_, QString::number(remaining_time_ / 60.0, 'f', 1), "min"); + } else if (remaining_time_ <= 3600) { + place_row(rect_time, icon_time_scaled_, QString::number(remaining_time_ / 60.0, 'f', 0), "min"); + } else if (remaining_time_ <= 36000) { + place_row( + rect_time, icon_time_scaled_, QString::number(remaining_time_ / 3600.0, 'f', 1), "hrs"); + } else { + place_row( + rect_time, icon_time_scaled_, QString::number(remaining_time_ / 3600.0, 'f', 0), "hrs"); + } + + // remaining_distance_ is in meters + if (remaining_distance_ <= 10) { + place_row(rect_dist, icon_dist_scaled_, QString::number(remaining_distance_, 'f', 1), "m"); + } else if (remaining_distance_ <= 1000) { + place_row(rect_dist, icon_dist_scaled_, QString::number(remaining_distance_, 'f', 0), "m"); + } else if (remaining_distance_ <= 10000) { + place_row( + rect_dist, icon_dist_scaled_, QString::number(remaining_distance_ / 1000.0, 'f', 2), "km"); + } else if (remaining_distance_ <= 100000) { + place_row( + rect_dist, icon_dist_scaled_, QString::number(remaining_distance_ / 1000.0, 'f', 1), "km"); + } else { + place_row( + rect_dist, icon_dist_scaled_, QString::number(remaining_distance_ / 1000.0, 'f', 0), "km"); } - painter.setPen(gray); - painter.drawText(remainingDistancePos, remainingDistanceValue); - - // Remaining distance unit - QString remainingDistUnitText = remaining_distance_ > 1000 ? "km" : "meter"; - QPointF remainingDistancUnitPos( - remainingDistReferencePos.x() + 80, remainingDistReferencePos.y() + 10); - painter.drawText(remainingDistancUnitPos, remainingDistUnitText); - - // ----------------- Remaining Time ----------------- - // Remaining time icon - painter.drawImage( - remainingDistanceIconPos.x(), - remainingDistanceIconPos.y() + scaledTimeToGoalFlag.height() / 2.0, scaledTimeToGoalFlag); - - // Calculate remaining minutes and seconds - double remaining_time_mod = std::fmod(remaining_time_, 3600); - uint8_t remaining_minutes = static_cast(remaining_time_mod / 60.0); - uint8_t remaining_seconds = static_cast(std::fmod(remaining_time_mod, 60)); - - // Remaining minutes value - QString remainingminutesValue = - QString::number(remaining_minutes != 0 ? remaining_minutes : 0, 'f', 0); - QPointF remainingminutesValuePos( - remainingTimeReferencePos.x() + 55, remainingTimeReferencePos.y()); - painter.setPen(gray); - if (remaining_minutes > 0) painter.drawText(remainingminutesValuePos, remainingminutesValue); - // Remaining minutes separator - QString minutesSeparatorText = "m"; - QPointF minutesSeparatorTextPos( - remainingTimeReferencePos.x() + 80, remainingTimeReferencePos.y()); - if (remaining_minutes > 0) painter.drawText(minutesSeparatorTextPos, minutesSeparatorText); - - // Remaining seconds value - QString remainingsecondsValue = - QString::number(remaining_seconds != 0 ? remaining_seconds : 0, 'f', 0); - QPointF remainingsecondValuePos( - remainingTimeReferencePos.x() + 55, remainingTimeReferencePos.y()); - painter.setPen(gray); - if (remaining_minutes <= 0) painter.drawText(remainingsecondValuePos, remainingsecondsValue); - - // Remaining seconds separator - QString secondsSeparatorText = "s"; - QPointF secondsSeparatorTextPos( - remainingTimeReferencePos.x() + 80, remainingTimeReferencePos.y()); - if (remaining_minutes <= 0) painter.drawText(secondsSeparatorTextPos, secondsSeparatorText); } } // namespace autoware::mission_details_overlay_rviz_plugin From fa796825d8a9bb2e50e11f19411c6297d0722354 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Sat, 11 May 2024 00:29:24 +0300 Subject: [PATCH 62/77] fix anchoring, update readme MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../README.md | 41 +++++++------------ .../include/mission_details_display.hpp | 3 +- .../src/mission_details_display.cpp | 19 +++------ 3 files changed, 21 insertions(+), 42 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md index d7f27cbae1050..85fe49bae2b43 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md @@ -1,40 +1,25 @@ # autoware_mission_details_overlay_rviz_plugin -Plugin for displaying 2D overlays over the RViz2 3D scene for mission details (such as remaining distance and time). - -Based on the [jsk_visualization](https://github.com/jsk-ros-pkg/jsk_visualization) -package, under the 3-Clause BSD license. - -## Purpose - -This plugin provides a visual and easy-to-understand display of mission details (remaining distance and time) +This RViz plugin displays the remaining distance and time for the current mission. ## Inputs / Outputs ### Input -| Name | Type | Description | -| ------------------------------------------- | ----------------------------------------------------------- | --------------------------------------------------------- | -| `/planning/mission_remaining_distance_time` | `autoware_planning_msgs::msg::MissionRemainingDistanceTime` | The topic is for mission remaining distance and time Data | - -## Parameter +| Name | Type | Description | +|---------------------------------------------|-------------------------------------------------------------|------------------------------------------------------| +| `/planning/mission_remaining_distance_time` | `autoware_planning_msgs::msg::MissionRemainingDistanceTime` | The topic is for mission remaining distance and time | -### Core Parameters +## Overlay Parameters -#### SignalDisplay +| Name | Type | Default Value | Description | +|----------|------|---------------|-----------------------------------| +| `Width` | int | 170 | Width of the overlay [px] | +| `Height` | int | 100 | Height of the overlay [px] | +| `Right` | int | 10 | Margin from the right border [px] | +| `Top` | int | 10 | Margin from the top border [px] | -| Name | Type | Default Value | Description | -| ------------------ | ---- | ------------- | --------------------------------- | -| `property_width_` | int | 225 | Width of the plotter window [px] | -| `property_height_` | int | 100 | Height of the plotter window [px] | -| `property_left_` | int | 10 | Left of the plotter window [px] | -| `property_top_` | int | 10 | Top of the plotter window [px] | - -Note that mission details display is aligned with top right corner of the screen. - -## Assumptions / Known limits - -TBD. +The mission details display is aligned with top right corner of the screen. ## Usage @@ -42,6 +27,8 @@ Similar to [autoware_overlay_rviz_plugin](../autoware_overlay_rviz_plugin/README ## Credits +Based on the [jsk_visualization](https://github.com/jsk-ros-pkg/jsk_visualization) package. + ### Icons - diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp index 9798373ea7e4a..ddc91e1890117 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp @@ -53,7 +53,6 @@ class MissionDetailsDisplay : public rviz_common::Display private Q_SLOTS: void updateOverlaySize(); void updateSmallOverlaySize(); - void updateOverlayPosition(); void updateOverlayColor(); void topic_updated_remaining_distance_time(); @@ -62,7 +61,7 @@ private Q_SLOTS: autoware::mission_details_overlay_rviz_plugin::OverlayObject::SharedPtr overlay_; rviz_common::properties::IntProperty * property_width_; rviz_common::properties::IntProperty * property_height_; - rviz_common::properties::IntProperty * property_left_; + rviz_common::properties::IntProperty * property_right_; rviz_common::properties::IntProperty * property_top_; std::unique_ptr remaining_distance_time_topic_property_; diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp index 81244c5de16ad..d0a3e7f6414f6 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -32,13 +32,13 @@ namespace autoware::mission_details_overlay_rviz_plugin MissionDetailsDisplay::MissionDetailsDisplay() { property_width_ = new rviz_common::properties::IntProperty( - "Width", 225, "Width of the overlay", this, SLOT(updateOverlaySize())); + "Width", 170, "Width of the overlay", this, SLOT(updateOverlaySize())); property_height_ = new rviz_common::properties::IntProperty( "Height", 100, "Height of the overlay", this, SLOT(updateOverlaySize())); - property_left_ = new rviz_common::properties::IntProperty( - "Left", 10, "Left position of the overlay", this, SLOT(updateOverlayPosition())); + property_right_ = new rviz_common::properties::IntProperty( + "Right", 10, "Margin from the right border", this, SLOT(updateOverlaySize())); property_top_ = new rviz_common::properties::IntProperty( - "Top", 10, "Top position of the overlay", this, SLOT(updateOverlayPosition())); + "Top", 10, "Margin from the top border", this, SLOT(updateOverlaySize())); // Initialize the component displays remaining_distance_time_display_ = std::make_unique(); @@ -56,7 +56,6 @@ void MissionDetailsDisplay::onInitialize() overlay_.reset(new autoware::mission_details_overlay_rviz_plugin::OverlayObject(ss.str())); overlay_->show(); updateOverlaySize(); - updateOverlayPosition(); auto rviz_ros_node = context_->getRosNodeAbstraction(); @@ -150,7 +149,7 @@ void MissionDetailsDisplay::drawWidget(QImage & hud) QPainter painter(&hud); painter.setRenderHint(QPainter::Antialiasing, true); - QRectF backgroundRect(0, 0, 170, 100); + QRectF backgroundRect(0, 0, qreal(property_width_->getInt()), qreal(property_height_->getInt())); drawHorizontalRoundedRectangle(painter, backgroundRect); if (remaining_distance_time_display_) { @@ -200,14 +199,8 @@ void MissionDetailsDisplay::updateOverlaySize() std::lock_guard lock(mutex_); overlay_->updateTextureSize(property_width_->getInt(), property_height_->getInt()); overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); - queueRender(); -} - -void MissionDetailsDisplay::updateOverlayPosition() -{ - std::lock_guard lock(mutex_); overlay_->setPosition( - property_left_->getInt(), property_top_->getInt(), HorizontalAlignment::RIGHT, + property_right_->getInt(), property_top_->getInt(), HorizontalAlignment::RIGHT, VerticalAlignment::TOP); queueRender(); } From 38ae94fdd5c697c951c85263153b6173f9ee1bdb Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 10 May 2024 21:31:27 +0000 Subject: [PATCH 63/77] style(pre-commit): autofix --- .../autoware_mission_details_overlay_rviz_plugin/README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md index 85fe49bae2b43..3a4040a7065d0 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md @@ -7,13 +7,13 @@ This RViz plugin displays the remaining distance and time for the current missio ### Input | Name | Type | Description | -|---------------------------------------------|-------------------------------------------------------------|------------------------------------------------------| +| ------------------------------------------- | ----------------------------------------------------------- | ---------------------------------------------------- | | `/planning/mission_remaining_distance_time` | `autoware_planning_msgs::msg::MissionRemainingDistanceTime` | The topic is for mission remaining distance and time | ## Overlay Parameters | Name | Type | Default Value | Description | -|----------|------|---------------|-----------------------------------| +| -------- | ---- | ------------- | --------------------------------- | | `Width` | int | 170 | Width of the overlay [px] | | `Height` | int | 100 | Height of the overlay [px] | | `Right` | int | 10 | Margin from the right border [px] | From a4c28ddfaa046564b2ff78753cd4ba2344642fbe Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Sat, 11 May 2024 00:52:39 +0300 Subject: [PATCH 64/77] remove unused panel and dependency MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../CMakeLists.txt | 3 - .../include/overlay_text_display.hpp | 156 ----- .../include/overlay_utils.hpp | 14 +- .../package.xml | 1 - .../src/overlay_text_display.cpp | 553 ------------------ 5 files changed, 6 insertions(+), 721 deletions(-) delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt index f689e6d613bcd..8692ea1bb152a 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt @@ -6,7 +6,6 @@ ament_auto_find_build_dependencies() set( headers_to_moc - include/overlay_text_display.hpp include/mission_details_display.hpp ) @@ -21,7 +20,6 @@ endforeach() set( display_source_files - src/overlay_text_display.cpp src/overlay_utils.cpp src/mission_details_display.cpp src/remaining_distance_time_display.cpp @@ -63,7 +61,6 @@ ament_target_dependencies( PUBLIC rviz_common rviz_rendering - autoware_overlay_msgs autoware_internal_msgs ) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp deleted file mode 100644 index d69abfd48266e..0000000000000 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_text_display.hpp +++ /dev/null @@ -1,156 +0,0 @@ -// Copyright 2024 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -// -*- mode: c++; -*- -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2022, Team Spatzenhirn - * Copyright (c) 2014, JSK Lab - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/o2r other materials provided - * with the distribution. - * * Neither the name of the JSK Lab nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ -#ifndef OVERLAY_TEXT_DISPLAY_HPP_ -#define OVERLAY_TEXT_DISPLAY_HPP_ - -#include "autoware_overlay_msgs/msg/overlay_text.hpp" -#ifndef Q_MOC_RUN -#include "overlay_utils.hpp" - -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -#include -#endif - -namespace autoware::mission_details_overlay_rviz_plugin -{ -class OverlayTextDisplay -: public rviz_common::RosTopicDisplay -{ - Q_OBJECT -public: - OverlayTextDisplay(); - virtual ~OverlayTextDisplay(); - -protected: - autoware::mission_details_overlay_rviz_plugin::OverlayObject::SharedPtr overlay_; - - int texture_width_; - int texture_height_; - - bool overtake_fg_color_properties_; - bool overtake_bg_color_properties_; - bool overtake_position_properties_; - bool align_bottom_; - bool invert_shadow_; - QColor bg_color_; - QColor fg_color_; - int text_size_; - int line_width_; - std::string text_; - QStringList font_families_; - std::string font_; - int horizontal_dist_; - int vertical_dist_; - HorizontalAlignment horizontal_alignment_; - VerticalAlignment vertical_alignment_; - - void onInitialize() override; - void onEnable() override; - void onDisable() override; - void update(float wall_dt, float ros_dt) override; - void reset() override; - - bool require_update_texture_; - // properties are raw pointers since they are owned by Qt - rviz_common::properties::BoolProperty * overtake_position_properties_property_; - rviz_common::properties::BoolProperty * overtake_fg_color_properties_property_; - rviz_common::properties::BoolProperty * overtake_bg_color_properties_property_; - rviz_common::properties::BoolProperty * align_bottom_property_; - rviz_common::properties::BoolProperty * invert_shadow_property_; - rviz_common::properties::IntProperty * hor_dist_property_; - rviz_common::properties::IntProperty * ver_dist_property_; - rviz_common::properties::EnumProperty * hor_alignment_property_; - rviz_common::properties::EnumProperty * ver_alignment_property_; - rviz_common::properties::IntProperty * width_property_; - rviz_common::properties::IntProperty * height_property_; - rviz_common::properties::IntProperty * text_size_property_; - rviz_common::properties::IntProperty * line_width_property_; - rviz_common::properties::ColorProperty * bg_color_property_; - rviz_common::properties::FloatProperty * bg_alpha_property_; - rviz_common::properties::ColorProperty * fg_color_property_; - rviz_common::properties::FloatProperty * fg_alpha_property_; - rviz_common::properties::EnumProperty * font_property_; - -protected Q_SLOTS: - void updateOvertakePositionProperties(); - void updateOvertakeFGColorProperties(); - void updateOvertakeBGColorProperties(); - void updateAlignBottom(); - void updateInvertShadow(); - void updateHorizontalDistance(); - void updateVerticalDistance(); - void updateHorizontalAlignment(); - void updateVerticalAlignment(); - void updateWidth(); - void updateHeight(); - void updateTextSize(); - void updateFGColor(); - void updateFGAlpha(); - void updateBGColor(); - void updateBGAlpha(); - void updateFont(); - void updateLineWidth(); - -private: - void processMessage(autoware_overlay_msgs::msg::OverlayText::ConstSharedPtr msg) override; -}; -} // namespace autoware::mission_details_overlay_rviz_plugin - -#endif // OVERLAY_TEXT_DISPLAY_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp index af3effedb2644..76f63e5fb74a4 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp @@ -54,8 +54,6 @@ #include #include -#include "autoware_overlay_msgs/msg/overlay_text.hpp" - #include #include #include @@ -90,15 +88,15 @@ class ScopedPixelBuffer }; enum class VerticalAlignment : uint8_t { - CENTER = autoware_overlay_msgs::msg::OverlayText::CENTER, - TOP = autoware_overlay_msgs::msg::OverlayText::TOP, - BOTTOM = autoware_overlay_msgs::msg::OverlayText::BOTTOM, + CENTER, + TOP, + BOTTOM }; enum class HorizontalAlignment : uint8_t { - LEFT = autoware_overlay_msgs::msg::OverlayText::LEFT, - RIGHT = autoware_overlay_msgs::msg::OverlayText::RIGHT, - CENTER = autoware_overlay_msgs::msg::OverlayText::CENTER + LEFT, + RIGHT, + CENTER }; /** diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml index e2b66ca469e8f..1054ac4f516bd 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml @@ -12,7 +12,6 @@ BSD-3-Clause autoware_internal_msgs - autoware_overlay_msgs boost rviz_common rviz_ogre_vendor diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp deleted file mode 100644 index 99504c63f4a91..0000000000000 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_text_display.cpp +++ /dev/null @@ -1,553 +0,0 @@ -// Copyright 2024 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -// -*- mode: c++; -*- -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2022, Team Spatzenhirn - * Copyright (c) 2014, JSK Lab - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/o2r other materials provided - * with the distribution. - * * Neither the name of the JSK Lab nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -#include "overlay_text_display.hpp" - -#include -#include -#include -#include -#include -#include - -#include -#include - -#include -#include - -namespace autoware::mission_details_overlay_rviz_plugin -{ -OverlayTextDisplay::OverlayTextDisplay() -: texture_width_(0), - texture_height_(0), - bg_color_(0, 0, 0, 0), - fg_color_(255, 255, 255, 255.0), - text_size_(14), - line_width_(2), - text_(""), - font_(""), - require_update_texture_(false) -{ - overtake_position_properties_property_ = new rviz_common::properties::BoolProperty( - "Overtake Position Properties", false, - "overtake position properties specified by message such as left, top and font", this, - SLOT(updateOvertakePositionProperties())); - overtake_fg_color_properties_property_ = new rviz_common::properties::BoolProperty( - "Overtake FG Color Properties", false, - "overtake color properties specified by message such as foreground color and alpha", this, - SLOT(updateOvertakeFGColorProperties())); - overtake_bg_color_properties_property_ = new rviz_common::properties::BoolProperty( - "Overtake BG Color Properties", false, - "overtake color properties specified by message such as background color and alpha", this, - SLOT(updateOvertakeBGColorProperties())); - align_bottom_property_ = new rviz_common::properties::BoolProperty( - "Align Bottom", false, "align text with the bottom of the overlay region", this, - SLOT(updateAlignBottom())); - invert_shadow_property_ = new rviz_common::properties::BoolProperty( - "Invert Shadow", false, "make shadow lighter than original text", this, - SLOT(updateInvertShadow())); - hor_dist_property_ = new rviz_common::properties::IntProperty( - "hor_dist", 0, "horizontal distance to anchor", this, SLOT(updateHorizontalDistance())); - ver_dist_property_ = new rviz_common::properties::IntProperty( - "ver_dist", 0, "vertical distance to anchor", this, SLOT(updateVerticalDistance())); - hor_alignment_property_ = new rviz_common::properties::EnumProperty( - "hor_alignment", "left", "horizontal alignment of the overlay", this, - SLOT(updateHorizontalAlignment())); - hor_alignment_property_->addOption("left", autoware_overlay_msgs::msg::OverlayText::LEFT); - hor_alignment_property_->addOption("center", autoware_overlay_msgs::msg::OverlayText::CENTER); - hor_alignment_property_->addOption("right", autoware_overlay_msgs::msg::OverlayText::RIGHT); - ver_alignment_property_ = new rviz_common::properties::EnumProperty( - "ver_alignment", "top", "vertical alignment of the overlay", this, - SLOT(updateVerticalAlignment())); - ver_alignment_property_->addOption("top", autoware_overlay_msgs::msg::OverlayText::TOP); - ver_alignment_property_->addOption("center", autoware_overlay_msgs::msg::OverlayText::CENTER); - ver_alignment_property_->addOption("bottom", autoware_overlay_msgs::msg::OverlayText::BOTTOM); - width_property_ = new rviz_common::properties::IntProperty( - "width", 128, "width position", this, SLOT(updateWidth())); - width_property_->setMin(0); - height_property_ = new rviz_common::properties::IntProperty( - "height", 128, "height position", this, SLOT(updateHeight())); - height_property_->setMin(0); - text_size_property_ = new rviz_common::properties::IntProperty( - "text size", 12, "text size", this, SLOT(updateTextSize())); - text_size_property_->setMin(0); - line_width_property_ = new rviz_common::properties::IntProperty( - "line width", 2, "line width", this, SLOT(updateLineWidth())); - line_width_property_->setMin(0); - fg_color_property_ = new rviz_common::properties::ColorProperty( - "Foreground Color", QColor(25, 255, 240), "Foreground Color", this, SLOT(updateFGColor())); - fg_alpha_property_ = new rviz_common::properties::FloatProperty( - "Foreground Alpha", 0.8, "Foreground Alpha", this, SLOT(updateFGAlpha())); - fg_alpha_property_->setMin(0.0); - fg_alpha_property_->setMax(1.0); - bg_color_property_ = new rviz_common::properties::ColorProperty( - "Background Color", QColor(0, 0, 0), "Background Color", this, SLOT(updateBGColor())); - bg_alpha_property_ = new rviz_common::properties::FloatProperty( - "Background Alpha", 0.8, "Background Alpha", this, SLOT(updateBGAlpha())); - bg_alpha_property_->setMin(0.0); - bg_alpha_property_->setMax(1.0); - - QFontDatabase database; - font_families_ = database.families(); - font_property_ = new rviz_common::properties::EnumProperty( - "font", "DejaVu Sans Mono", "font", this, SLOT(updateFont())); - for (ssize_t i = 0; i < font_families_.size(); i++) { - font_property_->addOption(font_families_[i], static_cast(i)); - } -} - -OverlayTextDisplay::~OverlayTextDisplay() -{ - onDisable(); -} - -void OverlayTextDisplay::onEnable() -{ - if (overlay_) { - overlay_->show(); - } - subscribe(); -} - -void OverlayTextDisplay::onDisable() -{ - if (overlay_) { - overlay_->hide(); - } - unsubscribe(); -} - -// only the first time -void OverlayTextDisplay::onInitialize() -{ - RTDClass::onInitialize(); - rviz_rendering::RenderSystem::get()->prepareOverlays(scene_manager_); - - onEnable(); - updateTopic(); - updateOvertakePositionProperties(); - updateOvertakeFGColorProperties(); - updateOvertakeBGColorProperties(); - updateAlignBottom(); - updateInvertShadow(); - updateHorizontalDistance(); - updateVerticalDistance(); - updateHorizontalAlignment(); - updateVerticalAlignment(); - updateWidth(); - updateHeight(); - updateTextSize(); - updateFGColor(); - updateFGAlpha(); - updateBGColor(); - updateBGAlpha(); - updateFont(); - updateLineWidth(); - require_update_texture_ = true; -} - -void OverlayTextDisplay::update(float /*wall_dt*/, float /*ros_dt*/) -{ - if (!require_update_texture_) { - return; - } - if (!isEnabled()) { - return; - } - if (!overlay_) { - return; - } - - overlay_->updateTextureSize(texture_width_, texture_height_); - { - autoware::mission_details_overlay_rviz_plugin::ScopedPixelBuffer buffer = overlay_->getBuffer(); - QImage Hud = buffer.getQImage(*overlay_, bg_color_); - QPainter painter(&Hud); - painter.setRenderHint(QPainter::Antialiasing, true); - painter.setPen(QPen(fg_color_, std::max(line_width_, 1), Qt::SolidLine)); - uint16_t w = overlay_->getTextureWidth(); - uint16_t h = overlay_->getTextureHeight(); - - // font - if (text_size_ != 0) { - // QFont font = painter.font(); - QFont font(font_.length() > 0 ? font_.c_str() : "Liberation Sans"); - font.setPointSize(text_size_); - font.setBold(true); - painter.setFont(font); - } - if (text_.length() > 0) { - QColor shadow_color; - if (invert_shadow_) - shadow_color = Qt::white; // fg_color_.lighter(); - else - shadow_color = Qt::black; // fg_color_.darker(); - shadow_color.setAlpha(fg_color_.alpha()); - - std::string color_wrapped_text = - (boost::format("%1%") % text_ % - fg_color_.red() % fg_color_.green() % fg_color_.blue() % fg_color_.alpha()) - .str(); - - // find a remove "color: XXX;" regex match to generate a proper shadow - std::regex color_tag_re("color:.+?;"); - std::string null_char(""); - std::string formatted_text_ = std::regex_replace(text_, color_tag_re, null_char); - std::string color_wrapped_shadow = - (boost::format("%1%") % - formatted_text_ % shadow_color.red() % shadow_color.green() % shadow_color.blue() % - shadow_color.alpha()) - .str(); - - QStaticText static_text( - boost::algorithm::replace_all_copy(color_wrapped_text, "\n", "
").c_str()); - static_text.setTextWidth(w); - - painter.setPen(QPen(shadow_color, std::max(line_width_, 1), Qt::SolidLine)); - QStaticText static_shadow( - boost::algorithm::replace_all_copy(color_wrapped_shadow, "\n", "
").c_str()); - static_shadow.setTextWidth(w); - - if (!align_bottom_) { - painter.drawStaticText(1, 1, static_shadow); - painter.drawStaticText(0, 0, static_text); - } else { - QStaticText only_wrapped_text(color_wrapped_text.c_str()); - QFontMetrics fm(painter.fontMetrics()); - QRect text_rect = fm.boundingRect( - 0, 0, w, h, Qt::TextWordWrap | Qt::AlignLeft | Qt::AlignTop, - only_wrapped_text.text().remove(QRegExp("<[^>]*>"))); - painter.drawStaticText(1, h - text_rect.height() + 1, static_shadow); - painter.drawStaticText(0, h - text_rect.height(), static_text); - } - } - painter.end(); - } - overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); - require_update_texture_ = false; -} - -void OverlayTextDisplay::reset() -{ - RTDClass::reset(); - - if (overlay_) { - overlay_->hide(); - } -} - -void OverlayTextDisplay::processMessage(autoware_overlay_msgs::msg::OverlayText::ConstSharedPtr msg) -{ - if (!isEnabled()) { - return; - } - if (!overlay_) { - static int count = 0; - std::stringstream ss; - ss << "OverlayTextDisplayObject" << count++; - overlay_.reset(new autoware::mission_details_overlay_rviz_plugin::OverlayObject(ss.str())); - overlay_->show(); - } - if (overlay_) { - if (msg->action == autoware_overlay_msgs::msg::OverlayText::DELETE) { - overlay_->hide(); - } else if (msg->action == autoware_overlay_msgs::msg::OverlayText::ADD) { - overlay_->show(); - } - } - - // store message for update method - text_ = msg->text; - - if (!overtake_position_properties_) { - texture_width_ = msg->width; - texture_height_ = msg->height; - text_size_ = msg->text_size; - horizontal_dist_ = msg->horizontal_distance; - vertical_dist_ = msg->vertical_distance; - - horizontal_alignment_ = HorizontalAlignment{msg->horizontal_alignment}; - vertical_alignment_ = VerticalAlignment{msg->vertical_alignment}; - } - if (!overtake_bg_color_properties_) - bg_color_ = QColor( - msg->bg_color.r * 255.0, msg->bg_color.g * 255.0, msg->bg_color.b * 255.0, - msg->bg_color.a * 255.0); - if (!overtake_fg_color_properties_) { - fg_color_ = QColor( - msg->fg_color.r * 255.0, msg->fg_color.g * 255.0, msg->fg_color.b * 255.0, - msg->fg_color.a * 255.0); - font_ = msg->font; - line_width_ = msg->line_width; - } - if (overlay_) { - overlay_->setPosition( - horizontal_dist_, vertical_dist_, horizontal_alignment_, vertical_alignment_); - } - require_update_texture_ = true; -} - -void OverlayTextDisplay::updateOvertakePositionProperties() -{ - if (!overtake_position_properties_ && overtake_position_properties_property_->getBool()) { - updateVerticalDistance(); - updateHorizontalDistance(); - updateVerticalAlignment(); - updateHorizontalAlignment(); - updateWidth(); - updateHeight(); - updateTextSize(); - require_update_texture_ = true; - } - - overtake_position_properties_ = overtake_position_properties_property_->getBool(); - if (overtake_position_properties_) { - hor_dist_property_->show(); - ver_dist_property_->show(); - hor_alignment_property_->show(); - ver_alignment_property_->show(); - width_property_->show(); - height_property_->show(); - text_size_property_->show(); - } else { - hor_dist_property_->hide(); - ver_dist_property_->hide(); - hor_alignment_property_->hide(); - ver_alignment_property_->hide(); - width_property_->hide(); - height_property_->hide(); - text_size_property_->hide(); - } -} - -void OverlayTextDisplay::updateOvertakeFGColorProperties() -{ - if (!overtake_fg_color_properties_ && overtake_fg_color_properties_property_->getBool()) { - // read all the parameters from properties - updateFGColor(); - updateFGAlpha(); - updateFont(); - updateLineWidth(); - require_update_texture_ = true; - } - overtake_fg_color_properties_ = overtake_fg_color_properties_property_->getBool(); - if (overtake_fg_color_properties_) { - fg_color_property_->show(); - fg_alpha_property_->show(); - line_width_property_->show(); - font_property_->show(); - } else { - fg_color_property_->hide(); - fg_alpha_property_->hide(); - line_width_property_->hide(); - font_property_->hide(); - } -} - -void OverlayTextDisplay::updateOvertakeBGColorProperties() -{ - if (!overtake_bg_color_properties_ && overtake_bg_color_properties_property_->getBool()) { - // read all the parameters from properties - updateBGColor(); - updateBGAlpha(); - require_update_texture_ = true; - } - overtake_bg_color_properties_ = overtake_bg_color_properties_property_->getBool(); - if (overtake_bg_color_properties_) { - bg_color_property_->show(); - bg_alpha_property_->show(); - } else { - bg_color_property_->hide(); - bg_alpha_property_->hide(); - } -} - -void OverlayTextDisplay::updateAlignBottom() -{ - if (align_bottom_ != align_bottom_property_->getBool()) { - require_update_texture_ = true; - } - align_bottom_ = align_bottom_property_->getBool(); -} - -void OverlayTextDisplay::updateInvertShadow() -{ - if (invert_shadow_ != invert_shadow_property_->getBool()) { - require_update_texture_ = true; - } - invert_shadow_ = invert_shadow_property_->getBool(); -} - -void OverlayTextDisplay::updateVerticalDistance() -{ - vertical_dist_ = ver_dist_property_->getInt(); - if (overtake_position_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateHorizontalDistance() -{ - horizontal_dist_ = hor_dist_property_->getInt(); - if (overtake_position_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateVerticalAlignment() -{ - vertical_alignment_ = - VerticalAlignment{static_cast(ver_alignment_property_->getOptionInt())}; - - if (overtake_position_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateHorizontalAlignment() -{ - horizontal_alignment_ = - HorizontalAlignment{static_cast(hor_alignment_property_->getOptionInt())}; - - if (overtake_position_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateWidth() -{ - texture_width_ = width_property_->getInt(); - if (overtake_position_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateHeight() -{ - texture_height_ = height_property_->getInt(); - if (overtake_position_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateTextSize() -{ - text_size_ = text_size_property_->getInt(); - if (overtake_position_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateBGColor() -{ - QColor c = bg_color_property_->getColor(); - bg_color_.setRed(c.red()); - bg_color_.setGreen(c.green()); - bg_color_.setBlue(c.blue()); - if (overtake_bg_color_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateBGAlpha() -{ - bg_color_.setAlpha(bg_alpha_property_->getFloat() * 255.0); - if (overtake_bg_color_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateFGColor() -{ - QColor c = fg_color_property_->getColor(); - fg_color_.setRed(c.red()); - fg_color_.setGreen(c.green()); - fg_color_.setBlue(c.blue()); - if (overtake_fg_color_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateFGAlpha() -{ - fg_color_.setAlpha(fg_alpha_property_->getFloat() * 255.0); - if (overtake_fg_color_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateFont() -{ - int font_index = font_property_->getOptionInt(); - if (font_index < font_families_.size()) { - font_ = font_families_[font_index].toStdString(); - } else { - RVIZ_COMMON_LOG_ERROR_STREAM("Unexpected error at selecting font index " << font_index); - return; - } - if (overtake_fg_color_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateLineWidth() -{ - line_width_ = line_width_property_->getInt(); - if (overtake_fg_color_properties_) { - require_update_texture_ = true; - } -} - -} // namespace autoware::mission_details_overlay_rviz_plugin - -#include -PLUGINLIB_EXPORT_CLASS( - autoware::mission_details_overlay_rviz_plugin::OverlayTextDisplay, rviz_common::Display) From 42611d60dde054e5e5c758cba7be5e25c8d5b854 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Sat, 11 May 2024 01:07:26 +0300 Subject: [PATCH 65/77] clean up more MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../include/mission_details_display.hpp | 11 ++-- .../include/overlay_utils.hpp | 12 +--- .../src/mission_details_display.cpp | 56 ++++++------------- 3 files changed, 24 insertions(+), 55 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp index ddc91e1890117..ab5abfe3c3d83 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp @@ -51,9 +51,7 @@ class MissionDetailsDisplay : public rviz_common::Display void onDisable() override; private Q_SLOTS: - void updateOverlaySize(); - void updateSmallOverlaySize(); - void updateOverlayColor(); + void update_size(); void topic_updated_remaining_distance_time(); private: @@ -66,8 +64,7 @@ private Q_SLOTS: std::unique_ptr remaining_distance_time_topic_property_; - void drawHorizontalRoundedRectangle(QPainter & painter, const QRectF & backgroundRect); - void drawVerticalRoundedRectangle(QPainter & painter, const QRectF & backgroundRect); + void draw_rounded_rect(QPainter & painter, const QRectF & backgroundRect); void setupRosSubscriptions(); std::unique_ptr remaining_distance_time_display_; @@ -77,9 +74,9 @@ private Q_SLOTS: std::mutex property_mutex_; - void updateRemainingDistanceTimeData( + void cb_remaining_distance_time( const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); - void drawWidget(QImage & hud); + void draw_widget(QImage & hud); }; } // namespace autoware::mission_details_overlay_rviz_plugin diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp index 76f63e5fb74a4..a0344f872f524 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp @@ -87,17 +87,9 @@ class ScopedPixelBuffer Ogre::HardwarePixelBufferSharedPtr pixel_buffer_; }; -enum class VerticalAlignment : uint8_t { - CENTER, - TOP, - BOTTOM -}; +enum class VerticalAlignment : uint8_t { CENTER, TOP, BOTTOM }; -enum class HorizontalAlignment : uint8_t { - LEFT, - RIGHT, - CENTER -}; +enum class HorizontalAlignment : uint8_t { LEFT, RIGHT, CENTER }; /** * Helper class for realizing an overlay object on top of the rviz 3D panel. diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp index d0a3e7f6414f6..4139c24748f78 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -16,6 +16,7 @@ #include #include +#include #include #include #include @@ -32,13 +33,13 @@ namespace autoware::mission_details_overlay_rviz_plugin MissionDetailsDisplay::MissionDetailsDisplay() { property_width_ = new rviz_common::properties::IntProperty( - "Width", 170, "Width of the overlay", this, SLOT(updateOverlaySize())); + "Width", 170, "Width of the overlay", this, SLOT(update_size())); property_height_ = new rviz_common::properties::IntProperty( - "Height", 100, "Height of the overlay", this, SLOT(updateOverlaySize())); + "Height", 100, "Height of the overlay", this, SLOT(update_size())); property_right_ = new rviz_common::properties::IntProperty( - "Right", 10, "Margin from the right border", this, SLOT(updateOverlaySize())); + "Right", 10, "Margin from the right border", this, SLOT(update_size())); property_top_ = new rviz_common::properties::IntProperty( - "Top", 10, "Margin from the top border", this, SLOT(updateOverlaySize())); + "Top", 10, "Margin from the top border", this, SLOT(update_size())); // Initialize the component displays remaining_distance_time_display_ = std::make_unique(); @@ -53,9 +54,9 @@ void MissionDetailsDisplay::onInitialize() static int count = 0; std::stringstream ss; ss << "MissionDetailsDisplay" << count++; - overlay_.reset(new autoware::mission_details_overlay_rviz_plugin::OverlayObject(ss.str())); + overlay_ = std::make_shared(ss.str()); overlay_->show(); - updateOverlaySize(); + update_size(); auto rviz_ros_node = context_->getRosNodeAbstraction(); @@ -78,7 +79,7 @@ void MissionDetailsDisplay::setupRosSubscriptions() remaining_distance_time_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), [this](const autoware_internal_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { - updateRemainingDistanceTimeData(msg); + cb_remaining_distance_time(msg); }); } @@ -104,7 +105,7 @@ void MissionDetailsDisplay::update(float wall_dt, float ros_dt) autoware::mission_details_overlay_rviz_plugin::ScopedPixelBuffer buffer = overlay_->getBuffer(); QImage hud = buffer.getQImage(*overlay_); hud.fill(Qt::transparent); - drawWidget(hud); + draw_widget(hud); } void MissionDetailsDisplay::onEnable() @@ -127,7 +128,7 @@ void MissionDetailsDisplay::onDisable() } } -void MissionDetailsDisplay::updateRemainingDistanceTimeData( +void MissionDetailsDisplay::cb_remaining_distance_time( const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg) { std::lock_guard lock(property_mutex_); @@ -138,7 +139,7 @@ void MissionDetailsDisplay::updateRemainingDistanceTimeData( } } -void MissionDetailsDisplay::drawWidget(QImage & hud) +void MissionDetailsDisplay::draw_widget(QImage & hud) { std::lock_guard lock(property_mutex_); @@ -150,7 +151,7 @@ void MissionDetailsDisplay::drawWidget(QImage & hud) painter.setRenderHint(QPainter::Antialiasing, true); QRectF backgroundRect(0, 0, qreal(property_width_->getInt()), qreal(property_height_->getInt())); - drawHorizontalRoundedRectangle(painter, backgroundRect); + draw_rounded_rect(painter, backgroundRect); if (remaining_distance_time_display_) { remaining_distance_time_display_->drawRemainingDistanceTimeDisplay(painter, backgroundRect); @@ -159,33 +160,18 @@ void MissionDetailsDisplay::drawWidget(QImage & hud) painter.end(); } -void MissionDetailsDisplay::drawHorizontalRoundedRectangle( +void MissionDetailsDisplay::draw_rounded_rect( QPainter & painter, const QRectF & backgroundRect) { painter.setRenderHint(QPainter::Antialiasing, true); QColor colorFromHSV; - colorFromHSV.setHsv(0, 0, 29); // Hue, Saturation, Value - colorFromHSV.setAlphaF(0.60); // Transparency + colorFromHSV.setHsv(0, 0, 29); + colorFromHSV.setAlphaF(0.60); painter.setBrush(colorFromHSV); painter.setPen(Qt::NoPen); - painter.drawRoundedRect( - backgroundRect, backgroundRect.height() / 2, backgroundRect.height() / 2); // Circular ends -} -void MissionDetailsDisplay::drawVerticalRoundedRectangle( - QPainter & painter, const QRectF & backgroundRect) -{ - painter.setRenderHint(QPainter::Antialiasing, true); - QColor colorFromHSV; - colorFromHSV.setHsv(0, 0, 0); // Hue, Saturation, Value - colorFromHSV.setAlphaF(0.65); // Transparency - - painter.setBrush(colorFromHSV); - - painter.setPen(Qt::NoPen); - painter.drawRoundedRect( - backgroundRect, backgroundRect.width() / 2, backgroundRect.width() / 2); // Circular ends + painter.drawRoundedRect(backgroundRect, backgroundRect.height() / 2, backgroundRect.height() / 2); } void MissionDetailsDisplay::reset() @@ -194,7 +180,7 @@ void MissionDetailsDisplay::reset() overlay_->hide(); } -void MissionDetailsDisplay::updateOverlaySize() +void MissionDetailsDisplay::update_size() { std::lock_guard lock(mutex_); overlay_->updateTextureSize(property_width_->getInt(), property_height_->getInt()); @@ -205,12 +191,6 @@ void MissionDetailsDisplay::updateOverlaySize() queueRender(); } -void MissionDetailsDisplay::updateOverlayColor() -{ - std::lock_guard lock(mutex_); - queueRender(); -} - void MissionDetailsDisplay::topic_updated_remaining_distance_time() { // resubscribe to the topic @@ -222,7 +202,7 @@ void MissionDetailsDisplay::topic_updated_remaining_distance_time() remaining_distance_time_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), [this](const autoware_internal_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { - updateRemainingDistanceTimeData(msg); + cb_remaining_distance_time(msg); }); } From 5e98a6f3f51af3bcb9fc652f3c5920468f6d2f65 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 10 May 2024 22:09:31 +0000 Subject: [PATCH 66/77] style(pre-commit): autofix --- .../src/mission_details_display.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp index 4139c24748f78..bafae1727b2f1 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -16,7 +16,6 @@ #include #include -#include #include #include #include @@ -54,7 +53,8 @@ void MissionDetailsDisplay::onInitialize() static int count = 0; std::stringstream ss; ss << "MissionDetailsDisplay" << count++; - overlay_ = std::make_shared(ss.str()); + overlay_ = + std::make_shared(ss.str()); overlay_->show(); update_size(); @@ -160,8 +160,7 @@ void MissionDetailsDisplay::draw_widget(QImage & hud) painter.end(); } -void MissionDetailsDisplay::draw_rounded_rect( - QPainter & painter, const QRectF & backgroundRect) +void MissionDetailsDisplay::draw_rounded_rect(QPainter & painter, const QRectF & backgroundRect) { painter.setRenderHint(QPainter::Antialiasing, true); QColor colorFromHSV; From 7b1901ed94da92aec471362b45737c973f8c0faa Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Sat, 11 May 2024 01:38:00 +0300 Subject: [PATCH 67/77] use max vel instead MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../package.xml | 1 + ...emaining_distance_time_calculator_node.cpp | 30 +++++++++++-------- ...emaining_distance_time_calculator_node.hpp | 22 ++++++++------ 3 files changed, 32 insertions(+), 21 deletions(-) diff --git a/planning/autoware_remaining_distance_time_calculator/package.xml b/planning/autoware_remaining_distance_time_calculator/package.xml index b8c9a3056de5b..4f0324b23f299 100644 --- a/planning/autoware_remaining_distance_time_calculator/package.xml +++ b/planning/autoware_remaining_distance_time_calculator/package.xml @@ -23,6 +23,7 @@ route_handler std_msgs tier4_autoware_utils + tier4_planning_msgs ament_cmake_ros ament_lint_auto diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp index 9140fd8b4710d..43c6a846a48f5 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -21,6 +21,8 @@ #include #include +#include + #include #include #include @@ -34,7 +36,8 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode( const rclcpp::NodeOptions & options) : Node("remaining_distance_time_calculator", options), is_graph_ready_{false}, - has_received_route_{false} + has_received_route_{false}, + velocity_limit_{99.99} { using std::placeholders::_1; @@ -49,6 +52,9 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode( sub_route_ = create_subscription( "~/input/route", qos_transient_local, std::bind(&RemainingDistanceTimeCalculatorNode::on_route, this, _1)); + sub_planning_velocity_ = create_subscription( + "/planning/scenario_planning/current_max_velocity", qos_transient_local, + std::bind(&RemainingDistanceTimeCalculatorNode::on_velocity_limit, this, _1)); pub_mission_remaining_distance_time_ = create_publisher( "~/output/mission_remaining_distance_time", @@ -84,6 +90,15 @@ void RemainingDistanceTimeCalculatorNode::on_route(const LaneletRoute::ConstShar has_received_route_ = true; } +void RemainingDistanceTimeCalculatorNode::on_velocity_limit( + const VelocityLimit::ConstSharedPtr& msg) +{ + // store the velocity for releasing the stop + if (msg->max_velocity > 1e-5) { + velocity_limit_ = msg->max_velocity; + } +} + void RemainingDistanceTimeCalculatorNode::on_timer() { if (is_graph_ready_ && has_received_route_) { @@ -121,6 +136,7 @@ double RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() const lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, current_vehicle_pose_); double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt); + remaining_distance += this_lanelet_length - arc_coord.length; } else if (index == (remaining_shortest_path.size() - 1)) { lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, goal_pose_); @@ -138,17 +154,7 @@ double RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() const double RemainingDistanceTimeCalculatorNode::calculate_remaining_time( const double remaining_distance) const { - double current_velocity_norm = std::sqrt( - current_vehicle_velocity_.x * current_vehicle_velocity_.x + - current_vehicle_velocity_.y * current_vehicle_velocity_.y); - - if (remaining_distance < 0.01 || current_velocity_norm < 0.01) { - return 0.0; - } - - double remaining_time = remaining_distance / current_velocity_norm; - - return remaining_time; + return remaining_distance / velocity_limit_; } void RemainingDistanceTimeCalculatorNode::publish_mission_remaining_distance_time( diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp index aeab5bbe3a331..b941006e9c4e8 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp @@ -24,6 +24,7 @@ #include #include #include +#include #include #include @@ -36,12 +37,6 @@ namespace autoware::remaining_distance_time_calculator { -using autoware_auto_mapping_msgs::msg::HADMapBin; -using autoware_internal_msgs::msg::MissionRemainingDistanceTime; -using autoware_planning_msgs::msg::LaneletRoute; -using geometry_msgs::msg::Pose; -using geometry_msgs::msg::Vector3; -using nav_msgs::msg::Odometry; struct NodeParam { @@ -54,9 +49,16 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node explicit RemainingDistanceTimeCalculatorNode(const rclcpp::NodeOptions & options); private: + using LaneletRoute = autoware_planning_msgs::msg::LaneletRoute; + using HADMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; + using Odometry = nav_msgs::msg::Odometry; + using VelocityLimit = tier4_planning_msgs::msg::VelocityLimit; + using MissionRemainingDistanceTime = autoware_internal_msgs::msg::MissionRemainingDistanceTime; + rclcpp::Subscription::SharedPtr sub_route_; rclcpp::Subscription::SharedPtr sub_map_; rclcpp::Subscription::SharedPtr sub_odometry_; + rclcpp::Subscription::SharedPtr sub_planning_velocity_; rclcpp::Publisher::SharedPtr pub_mission_remaining_distance_time_; @@ -70,10 +72,11 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node bool is_graph_ready_; // Data Buffer - Pose current_vehicle_pose_; - Vector3 current_vehicle_velocity_; - Pose goal_pose_; + geometry_msgs::msg::Pose current_vehicle_pose_; + geometry_msgs::msg::Vector3 current_vehicle_velocity_; + geometry_msgs::msg::Pose goal_pose_; bool has_received_route_; + double velocity_limit_; // Parameter NodeParam node_param_; @@ -83,6 +86,7 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node void on_odometry(const Odometry::ConstSharedPtr & msg); void on_route(const LaneletRoute::ConstSharedPtr & msg); void on_map(const HADMapBin::ConstSharedPtr & msg); + void on_velocity_limit(const VelocityLimit::ConstSharedPtr& msg); /** * @brief calculate mission remaining distance From 3b2957f12d18b152757b10205bc8d3bb7d1540cc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Sat, 11 May 2024 01:40:19 +0300 Subject: [PATCH 68/77] rm comment MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../src/remaining_distance_time_calculator_node.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp index 43c6a846a48f5..6aa753a6655b4 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -93,7 +93,6 @@ void RemainingDistanceTimeCalculatorNode::on_route(const LaneletRoute::ConstShar void RemainingDistanceTimeCalculatorNode::on_velocity_limit( const VelocityLimit::ConstSharedPtr& msg) { - // store the velocity for releasing the stop if (msg->max_velocity > 1e-5) { velocity_limit_ = msg->max_velocity; } From 2d80db81e29754fe27dcdbceba4a69b96d65b144 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 10 May 2024 22:44:04 +0000 Subject: [PATCH 69/77] style(pre-commit): autofix --- .../src/remaining_distance_time_calculator_node.cpp | 2 +- .../src/remaining_distance_time_calculator_node.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp index 6aa753a6655b4..05035946ee92b 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -91,7 +91,7 @@ void RemainingDistanceTimeCalculatorNode::on_route(const LaneletRoute::ConstShar } void RemainingDistanceTimeCalculatorNode::on_velocity_limit( - const VelocityLimit::ConstSharedPtr& msg) + const VelocityLimit::ConstSharedPtr & msg) { if (msg->max_velocity > 1e-5) { velocity_limit_ = msg->max_velocity; diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp index b941006e9c4e8..3515b3ffe1a56 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp @@ -86,7 +86,7 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node void on_odometry(const Odometry::ConstSharedPtr & msg); void on_route(const LaneletRoute::ConstSharedPtr & msg); void on_map(const HADMapBin::ConstSharedPtr & msg); - void on_velocity_limit(const VelocityLimit::ConstSharedPtr& msg); + void on_velocity_limit(const VelocityLimit::ConstSharedPtr & msg); /** * @brief calculate mission remaining distance From b4770f8420d6b1cadb9f4a8f0efdc3fd178a5d38 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Sat, 11 May 2024 03:04:58 +0300 Subject: [PATCH 70/77] proportionally extend the rect to the right MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../src/remaining_distance_time_display.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index 4bf04ebdfc7e4..86395ef1918bc 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -75,7 +75,9 @@ void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( return QRectF(top_left_inner, size_inner); }; - const QRectF rect_inner = calculate_inner_rect(backgroundRect, 0.7, 0.7); + QRectF rect_inner = calculate_inner_rect(backgroundRect, 0.7, 0.7); + // Proportionally extend the rect to the right to account for visual icon distance to the left + rect_inner.setWidth(rect_inner.width() * 1.08); // Calculate distance row rectangle const QSizeF distance_row_size(rect_inner.width(), rect_inner.height() / 2); From 56b432fead50e99022f8d1477de17eb9c5ff1a60 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Sat, 11 May 2024 03:28:48 +0300 Subject: [PATCH 71/77] fix typo MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- planning/autoware_remaining_distance_time_calculator/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/autoware_remaining_distance_time_calculator/README.md b/planning/autoware_remaining_distance_time_calculator/README.md index d49847b273c1f..10eaf63c21d55 100644 --- a/planning/autoware_remaining_distance_time_calculator/README.md +++ b/planning/autoware_remaining_distance_time_calculator/README.md @@ -7,7 +7,7 @@ This package aims to provide mission remaining distance and remaining time calcu ### Activation and Timing - The calculations are activated once we have a route planned for a mission in Autoware -- The calculations are trigged timely based on the `update_rate` parameter +- The calculations are triggered timely based on the `update_rate` parameter ### Module Parameters From 68a8be7b0d137d2e4aa95d08a2cbf5c5176f5038 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Mon, 13 May 2024 07:03:07 +0300 Subject: [PATCH 72/77] feat(remaining_dist_eta): add checks for calculating remaining distance Signed-off-by: Ahmed Ebrahim --- ...remaining_distance_time_calculator_node.cpp | 18 ++++++++++++++++-- 1 file changed, 16 insertions(+), 2 deletions(-) diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp index 05035946ee92b..00fa0917ea6c9 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -113,13 +113,27 @@ double RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() const size_t index = 0; lanelet::ConstLanelet current_lanelet; - lanelet::utils::query::getClosestLanelet(road_lanelets_, current_vehicle_pose_, ¤t_lanelet); + if (!lanelet::utils::query::getClosestLanelet( + road_lanelets_, current_vehicle_pose_, ¤t_lanelet)) { + RCLCPP_WARN_STREAM(this->get_logger(), "Failed to find current lanelet."); + + return 0.0; + } lanelet::ConstLanelet goal_lanelet; - lanelet::utils::query::getClosestLanelet(road_lanelets_, goal_pose_, &goal_lanelet); + if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal_pose_, &goal_lanelet)) { + RCLCPP_WARN_STREAM(this->get_logger(), "Failed to find goal lanelet."); + + return 0.0; + } const lanelet::Optional optional_route = routing_graph_ptr_->getRoute(current_lanelet, goal_lanelet, 0); + if (!optional_route) { + RCLCPP_WARN_STREAM(this->get_logger(), "Failed to find proper route."); + + return 0.0; + } lanelet::routing::LaneletPath remaining_shortest_path; remaining_shortest_path = optional_route->shortestPath(); From ee08bc299d49237345bc4b04dc22540e73c7bae6 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Mon, 13 May 2024 07:32:30 +0300 Subject: [PATCH 73/77] feat(remaining_dist_eta): handle cases when routing graph is not able to find proper route by maintaining last valid remaining dist and time Signed-off-by: Ahmed Ebrahim --- ...emaining_distance_time_calculator_node.cpp | 43 +++++++++---------- ...emaining_distance_time_calculator_node.hpp | 10 +++-- 2 files changed, 27 insertions(+), 26 deletions(-) diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp index 00fa0917ea6c9..cf8f101c37395 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -37,7 +37,9 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode( : Node("remaining_distance_time_calculator", options), is_graph_ready_{false}, has_received_route_{false}, - velocity_limit_{99.99} + velocity_limit_{99.99}, + remaining_distance_{0.0}, + remaining_time_{0.0} { using std::placeholders::_1; @@ -101,15 +103,14 @@ void RemainingDistanceTimeCalculatorNode::on_velocity_limit( void RemainingDistanceTimeCalculatorNode::on_timer() { if (is_graph_ready_ && has_received_route_) { - double remaining_distance = calculate_remaining_distance(); - double remaining_time = calculate_remaining_time(remaining_distance); - publish_mission_remaining_distance_time(remaining_distance, remaining_time); + calculate_remaining_distance(); + calculate_remaining_time(); + publish_mission_remaining_distance_time(); } } -double RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() const +void RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() { - double remaining_distance = 0.0; size_t index = 0; lanelet::ConstLanelet current_lanelet; @@ -117,14 +118,14 @@ double RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() const road_lanelets_, current_vehicle_pose_, ¤t_lanelet)) { RCLCPP_WARN_STREAM(this->get_logger(), "Failed to find current lanelet."); - return 0.0; + return; } lanelet::ConstLanelet goal_lanelet; if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal_pose_, &goal_lanelet)) { RCLCPP_WARN_STREAM(this->get_logger(), "Failed to find goal lanelet."); - return 0.0; + return; } const lanelet::Optional optional_route = @@ -132,15 +133,17 @@ double RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() const if (!optional_route) { RCLCPP_WARN_STREAM(this->get_logger(), "Failed to find proper route."); - return 0.0; + return; } lanelet::routing::LaneletPath remaining_shortest_path; remaining_shortest_path = optional_route->shortestPath(); + remaining_distance_ = 0.0; + for (auto & llt : remaining_shortest_path) { if (remaining_shortest_path.size() == 1) { - remaining_distance += + remaining_distance_ += tier4_autoware_utils::calcDistance2d(current_vehicle_pose_.position, goal_pose_.position); break; } @@ -150,33 +153,29 @@ double RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() const lanelet::utils::getArcCoordinates({llt}, current_vehicle_pose_); double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt); - remaining_distance += this_lanelet_length - arc_coord.length; + remaining_distance_ += this_lanelet_length - arc_coord.length; } else if (index == (remaining_shortest_path.size() - 1)) { lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, goal_pose_); - remaining_distance += arc_coord.length; + remaining_distance_ += arc_coord.length; } else { - remaining_distance += lanelet::utils::getLaneletLength2d(llt); + remaining_distance_ += lanelet::utils::getLaneletLength2d(llt); } index++; } - - return remaining_distance; } -double RemainingDistanceTimeCalculatorNode::calculate_remaining_time( - const double remaining_distance) const +void RemainingDistanceTimeCalculatorNode::calculate_remaining_time() { - return remaining_distance / velocity_limit_; + remaining_time_ = remaining_distance_ / velocity_limit_; } -void RemainingDistanceTimeCalculatorNode::publish_mission_remaining_distance_time( - const double remaining_distance, const double remaining_time) const +void RemainingDistanceTimeCalculatorNode::publish_mission_remaining_distance_time() { MissionRemainingDistanceTime mission_remaining_distance_time; - mission_remaining_distance_time.remaining_distance = remaining_distance; - mission_remaining_distance_time.remaining_time = remaining_time; + mission_remaining_distance_time.remaining_distance = remaining_distance_; + mission_remaining_distance_time.remaining_time = remaining_time_; pub_mission_remaining_distance_time_->publish(mission_remaining_distance_time); } diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp index 3515b3ffe1a56..2a88cdb57abf4 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp @@ -78,6 +78,9 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node bool has_received_route_; double velocity_limit_; + double remaining_distance_; + double remaining_time_; + // Parameter NodeParam node_param_; @@ -91,18 +94,17 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node /** * @brief calculate mission remaining distance */ - double calculate_remaining_distance() const; + void calculate_remaining_distance(); /** * @brief calculate mission remaining time */ - double calculate_remaining_time(double remaining_distance) const; + void calculate_remaining_time(); /** * @brief publish mission remaining distance and time */ - void publish_mission_remaining_distance_time( - double remaining_distance, double remaining_time) const; + void publish_mission_remaining_distance_time(); }; } // namespace autoware::remaining_distance_time_calculator #endif // REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ From 8e8954b98a003ab627512a858bdd4770fd312986 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Mon, 13 May 2024 07:55:46 +0300 Subject: [PATCH 74/77] feat(remaining_dist_eta): update readme Signed-off-by: Ahmed Ebrahim --- .../README.md | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/planning/autoware_remaining_distance_time_calculator/README.md b/planning/autoware_remaining_distance_time_calculator/README.md index 10eaf63c21d55..34eb2fffae3bc 100644 --- a/planning/autoware_remaining_distance_time_calculator/README.md +++ b/planning/autoware_remaining_distance_time_calculator/README.md @@ -15,22 +15,24 @@ This package aims to provide mission remaining distance and remaining time calcu | ------------- | ------ | ------------- | --------------------------- | | `update_rate` | double | 10.0 | Timer callback period. [Hz] | -### Inner-workings / Algorithms +### Inner-workings -### Remaining Distance Calculation +#### Remaining Distance Calculation - The remaining distance calculation is based on getting the remaining shortest path between the current vehicle pose and goal pose using `lanelet2` routing APIs. - The remaining distance is calculated by summing the 2D length of remaining shortest path, with exception to current lanelet and goal lanelet - For the current lanelet, the distance is calculated from the current vehicle position to the end of that lanelet - For the goal lanelet, the distance is calculated from the start of the lanelet to the goal pose in this lanelet. +- When there is only one lanelet remaining, the distance is calculated by getting the 2D distance between the current vehicle pose and goal pose. +- Checks are added to handle cases when current lanelent, goal lanelet, or routing graph are not valid to prevent node process die + - In such cases when, last valid remaining distance and time are maintained -### Remaining Time Calculation +#### Remaining Time Calculation -- Remaining time is calculated using simple equation of motion by getting the current vehicle velocity magnitude. -- Then the calculated remaining distance is divided by the velocity magnitude. +- The remaining time currently depends on a simple equation of motion by getting the maximum velocity limit. +- The remaining distance is calculated by dividing remaining distance by the maximum velocity limit ### Future Work - Find a more efficient way for remaining distance calculation instead of regularly searching the graph for finding the remaining shortest path -- Engage more sophisticated motion models for more accurate remaining time calculations -- Handle cases when the vehicle stops during the mission or Autoware get disengaged then engaged for the same mission +- Engage more sophisticated motion models for more accurate remaining time calculations \ No newline at end of file From 650eb80bfd55bae9bc9595a9e77458a7a15cc709 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 13 May 2024 05:09:56 +0000 Subject: [PATCH 75/77] style(pre-commit): autofix --- planning/autoware_remaining_distance_time_calculator/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/autoware_remaining_distance_time_calculator/README.md b/planning/autoware_remaining_distance_time_calculator/README.md index 34eb2fffae3bc..91552a9d49f5c 100644 --- a/planning/autoware_remaining_distance_time_calculator/README.md +++ b/planning/autoware_remaining_distance_time_calculator/README.md @@ -35,4 +35,4 @@ This package aims to provide mission remaining distance and remaining time calcu ### Future Work - Find a more efficient way for remaining distance calculation instead of regularly searching the graph for finding the remaining shortest path -- Engage more sophisticated motion models for more accurate remaining time calculations \ No newline at end of file +- Engage more sophisticated motion models for more accurate remaining time calculations From 8a9b86b784f18745227e92a4aea9857f5b7c3abd Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Mon, 13 May 2024 08:45:13 +0300 Subject: [PATCH 76/77] feat(remaining_dist_eta): add check for velocity limit preventing unintended division by zero or negative time values / update readme Signed-off-by: Ahmed Ebrahim feat(remaining_dist_eta): add check for velocity limit preventing unintended division by zero or negative time values / update readme Signed-off-by: Ahmed Ebrahim --- .../README.md | 21 ++++++++++--------- ...emaining_distance_time_calculator_node.cpp | 4 +++- 2 files changed, 14 insertions(+), 11 deletions(-) diff --git a/planning/autoware_remaining_distance_time_calculator/README.md b/planning/autoware_remaining_distance_time_calculator/README.md index 91552a9d49f5c..4f331da45d962 100644 --- a/planning/autoware_remaining_distance_time_calculator/README.md +++ b/planning/autoware_remaining_distance_time_calculator/README.md @@ -2,12 +2,12 @@ ### Role -This package aims to provide mission remaining distance and remaining time calculations +This package aims to provide mission remaining distance and remaining time calculations. ### Activation and Timing -- The calculations are activated once we have a route planned for a mission in Autoware -- The calculations are triggered timely based on the `update_rate` parameter +- The calculations are activated once we have a route planned for a mission in Autoware. +- The calculations are triggered timely based on the `update_rate` parameter. ### Module Parameters @@ -20,19 +20,20 @@ This package aims to provide mission remaining distance and remaining time calcu #### Remaining Distance Calculation - The remaining distance calculation is based on getting the remaining shortest path between the current vehicle pose and goal pose using `lanelet2` routing APIs. -- The remaining distance is calculated by summing the 2D length of remaining shortest path, with exception to current lanelet and goal lanelet - - For the current lanelet, the distance is calculated from the current vehicle position to the end of that lanelet +- The remaining distance is calculated by summing the 2D length of remaining shortest path, with exception to current lanelet and goal lanelet. + - For the current lanelet, the distance is calculated from the current vehicle position to the end of that lanelet. - For the goal lanelet, the distance is calculated from the start of the lanelet to the goal pose in this lanelet. - When there is only one lanelet remaining, the distance is calculated by getting the 2D distance between the current vehicle pose and goal pose. -- Checks are added to handle cases when current lanelent, goal lanelet, or routing graph are not valid to prevent node process die - - In such cases when, last valid remaining distance and time are maintained +- Checks are added to handle cases when current lanelent, goal lanelet, or routing graph are not valid to prevent node process die. + - In such cases when, last valid remaining distance and time are maintained. #### Remaining Time Calculation - The remaining time currently depends on a simple equation of motion by getting the maximum velocity limit. -- The remaining distance is calculated by dividing remaining distance by the maximum velocity limit +- The remaining distance is calculated by dividing the remaining distance by the maximum velocity limit. +- A check is added to the remaining time calculation to make sure that maximum velocity limit is greater than zero. This prevents division by zero or getting negative time value. ### Future Work -- Find a more efficient way for remaining distance calculation instead of regularly searching the graph for finding the remaining shortest path -- Engage more sophisticated motion models for more accurate remaining time calculations +- Find a more efficient way for remaining distance calculation instead of regularly searching the graph for finding the remaining shortest path. +- Engage more sophisticated motion models for more accurate remaining time calculations. diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp index cf8f101c37395..327bd0ff3b582 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -167,7 +167,9 @@ void RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() void RemainingDistanceTimeCalculatorNode::calculate_remaining_time() { - remaining_time_ = remaining_distance_ / velocity_limit_; + if (velocity_limit_ > 0.0) { + remaining_time_ = remaining_distance_ / velocity_limit_; + } } void RemainingDistanceTimeCalculatorNode::publish_mission_remaining_distance_time() From cadd17cff8b75a9e8ec02f39e17228af0ccbf389 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim Date: Mon, 13 May 2024 08:53:30 +0300 Subject: [PATCH 77/77] feat(remaining_dist_eta): fix type Signed-off-by: Ahmed Ebrahim --- planning/autoware_remaining_distance_time_calculator/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/autoware_remaining_distance_time_calculator/README.md b/planning/autoware_remaining_distance_time_calculator/README.md index 4f331da45d962..694c6764de91c 100644 --- a/planning/autoware_remaining_distance_time_calculator/README.md +++ b/planning/autoware_remaining_distance_time_calculator/README.md @@ -24,7 +24,7 @@ This package aims to provide mission remaining distance and remaining time calcu - For the current lanelet, the distance is calculated from the current vehicle position to the end of that lanelet. - For the goal lanelet, the distance is calculated from the start of the lanelet to the goal pose in this lanelet. - When there is only one lanelet remaining, the distance is calculated by getting the 2D distance between the current vehicle pose and goal pose. -- Checks are added to handle cases when current lanelent, goal lanelet, or routing graph are not valid to prevent node process die. +- Checks are added to handle cases when current lanelet, goal lanelet, or routing graph are not valid to prevent node process die. - In such cases when, last valid remaining distance and time are maintained. #### Remaining Time Calculation