From 0836cfb53b5d4ce2c0300c0ec7e9400e18de83fb Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 1 Apr 2024 15:04:41 +0900 Subject: [PATCH 01/57] feat(run_out_module): exclude obstacles on path (#6703) * WIP add check for target object in path Signed-off-by: Daniel Sanchez * WIP exclude obstacles on ego path Signed-off-by: Daniel Sanchez * use lat deviation to check if obstacle is on path or not Signed-off-by: Daniel Sanchez * delete unused methods and variables Signed-off-by: Daniel Sanchez * readme and comments Signed-off-by: Daniel Sanchez * add uuids to dynamic obstacle type Signed-off-by: Daniel Sanchez * use lib funct to generate uuid Signed-off-by: Daniel Sanchez * add timeout to keep last run out candidate for some time Signed-off-by: Daniel Sanchez * add time threshold to maintain obstacles that enter path Signed-off-by: Daniel Sanchez * change logic, ignore obstacle in path after some time passes Signed-off-by: Daniel Sanchez * readme Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../README.md | 8 ++ .../config/run_out.param.yaml | 3 + .../src/dynamic_obstacle.cpp | 5 +- .../src/dynamic_obstacle.hpp | 1 + .../src/manager.cpp | 6 + .../src/scene.cpp | 109 +++++++++++++++--- .../src/scene.hpp | 10 ++ .../src/utils.hpp | 7 +- 8 files changed, 131 insertions(+), 18 deletions(-) diff --git a/planning/behavior_velocity_run_out_module/README.md b/planning/behavior_velocity_run_out_module/README.md index 77f42822a6b95..7c79d1c288a0d 100644 --- a/planning/behavior_velocity_run_out_module/README.md +++ b/planning/behavior_velocity_run_out_module/README.md @@ -108,6 +108,14 @@ You can choose whether to use this feature by parameter of `use_partition_lanele ![brief](./docs/exclude_obstacles_by_partition.svg) +##### Exclude obstacles by label + +This module only acts on target obstacles defined by the `target_obstacle_types` parameter. If an obstacle of a type not specified by said parameter is detected, it will be ignored by this module. + +##### Exclude obstacles that are already on the ego vehicle's path + +In the cases were an obstacle is already on the ego vehicle's path, it cannot "cut in" into the ego's path anymore (which is the situation this module tries to handle) so it might be useful to exclude obstacles already on the vehicle's footprint path. By setting the parameter `exclude_obstacles_already_in_path` to true, this module will exclude the obstacles that are considered to be already on the ego vehicle's path for more than `keep_obstacle_on_path_time_threshold`. The module considers the ego vehicle's closest path point to each obstacle's current position, and determines the lateral distance between the obstacle and the right and left sides of the ego vehicle. If the obstacle is located within the left and right extremes of the vehicle for that pose, then it is considered to be inside the ego vehicle's footprint path and it is excluded. The virtual width of the vehicle used to detect if an obstacle is within the path or not, can be adjusted by the `ego_footprint_extra_margin` parameter. + ##### Exclude obstacles that cross the ego vehicle's "cut line" This module can exclude obstacles that have predicted paths that will cross the back side of the ego vehicle. It excludes obstacles if their predicted path crosses the ego's "cut line". The "cut line" is a virtual line segment that is perpendicular to the ego vehicle and that passes through the ego's base link. diff --git a/planning/behavior_velocity_run_out_module/config/run_out.param.yaml b/planning/behavior_velocity_run_out_module/config/run_out.param.yaml index 6e28b230757ba..628b8725149a2 100644 --- a/planning/behavior_velocity_run_out_module/config/run_out.param.yaml +++ b/planning/behavior_velocity_run_out_module/config/run_out.param.yaml @@ -3,6 +3,7 @@ run_out: detection_method: "Object" # [-] candidate: Object, ObjectWithoutPath, Points target_obstacle_types: ["PEDESTRIAN", "BICYCLE", "MOTORCYCLE"] # [-] Obstacle types considered by this module + exclude_obstacles_already_in_path: true # If the obstacle is already on the ego's path footprint, ignore it. use_partition_lanelet: true # [-] whether to use partition lanelet map data suppress_on_crosswalk: true # [-] whether to suppress on crosswalk lanelet use_ego_cut_line: true # [-] filter obstacles that pass the backside of ego: if a dynamic obstacle's predicted path intersects this line, it is ignored @@ -14,6 +15,8 @@ detection_span: 1.0 # [m] calculate collision with this span to reduce calculation time min_vel_ego_kmph: 3.6 # [km/h] min velocity to calculate time to collision ego_cut_line_length: 3.0 # The width of the ego's cut line + ego_footprint_extra_margin: 0.5 # [m] expand the ego vehicles' footprint by this value on all sides when building the ego footprint path + keep_obstacle_on_path_time_threshold: 1.0 # [s] How much time a previous run out target obstacle is kept in the run out candidate list if it enters the ego path. # Parameter to create abstracted dynamic obstacles dynamic_obstacle: diff --git a/planning/behavior_velocity_run_out_module/src/dynamic_obstacle.cpp b/planning/behavior_velocity_run_out_module/src/dynamic_obstacle.cpp index 0af59417a23b2..9b94c8b681942 100644 --- a/planning/behavior_velocity_run_out_module/src/dynamic_obstacle.cpp +++ b/planning/behavior_velocity_run_out_module/src/dynamic_obstacle.cpp @@ -18,6 +18,7 @@ #include #include #include +#include #include #include @@ -373,6 +374,7 @@ std::vector DynamicObstacleCreatorForObject::createDynamicObsta } dynamic_obstacle.classifications = predicted_object.classification; dynamic_obstacle.shape = predicted_object.shape; + dynamic_obstacle.uuid = predicted_object.object_id; // get predicted paths of predicted_objects for (const auto & path : predicted_object.kinematics.predicted_paths) { @@ -418,6 +420,7 @@ std::vector DynamicObstacleCreatorForObjectWithoutPath::createD param_.max_prediction_time); predicted_path.confidence = 1.0; dynamic_obstacle.predicted_paths.emplace_back(predicted_path); + dynamic_obstacle.uuid = predicted_object.object_id; dynamic_obstacles.emplace_back(dynamic_obstacle); } @@ -490,7 +493,7 @@ std::vector DynamicObstacleCreatorForPoints::createDynamicObsta param_.max_prediction_time); predicted_path.confidence = 1.0; dynamic_obstacle.predicted_paths.emplace_back(predicted_path); - + dynamic_obstacle.uuid = tier4_autoware_utils::generateUUID(); dynamic_obstacles.emplace_back(dynamic_obstacle); } diff --git a/planning/behavior_velocity_run_out_module/src/dynamic_obstacle.hpp b/planning/behavior_velocity_run_out_module/src/dynamic_obstacle.hpp index 5217193c9673e..f020da2abd045 100644 --- a/planning/behavior_velocity_run_out_module/src/dynamic_obstacle.hpp +++ b/planning/behavior_velocity_run_out_module/src/dynamic_obstacle.hpp @@ -22,6 +22,7 @@ #include #include +#include #include #include diff --git a/planning/behavior_velocity_run_out_module/src/manager.cpp b/planning/behavior_velocity_run_out_module/src/manager.cpp index 9ee467feec758..e2ce3822bf86d 100644 --- a/planning/behavior_velocity_run_out_module/src/manager.cpp +++ b/planning/behavior_velocity_run_out_module/src/manager.cpp @@ -62,6 +62,8 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node) getOrDeclareParameter>(node, ns + ".target_obstacle_types"); p.use_partition_lanelet = getOrDeclareParameter(node, ns + ".use_partition_lanelet"); p.use_ego_cut_line = getOrDeclareParameter(node, ns + ".use_ego_cut_line"); + p.exclude_obstacles_already_in_path = + getOrDeclareParameter(node, ns + ".exclude_obstacles_already_in_path"); p.suppress_on_crosswalk = getOrDeclareParameter(node, ns + ".suppress_on_crosswalk"); p.specify_decel_jerk = getOrDeclareParameter(node, ns + ".specify_decel_jerk"); p.stop_margin = getOrDeclareParameter(node, ns + ".stop_margin"); @@ -71,6 +73,10 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node) p.detection_span = getOrDeclareParameter(node, ns + ".detection_span"); p.min_vel_ego_kmph = getOrDeclareParameter(node, ns + ".min_vel_ego_kmph"); p.ego_cut_line_length = getOrDeclareParameter(node, ns + ".ego_cut_line_length"); + p.ego_footprint_extra_margin = + getOrDeclareParameter(node, ns + ".ego_footprint_extra_margin"); + p.keep_obstacle_on_path_time_threshold = + getOrDeclareParameter(node, ns + ".keep_obstacle_on_path_time_threshold"); } { diff --git a/planning/behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_run_out_module/src/scene.cpp index cd15a3fb0629f..48fbebb8b056d 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_run_out_module/src/scene.cpp @@ -22,6 +22,7 @@ #include #include #include +#include #include #include @@ -36,6 +37,7 @@ namespace behavior_velocity_planner { namespace bg = boost::geometry; +using object_recognition_utils::convertLabelToString; RunOutModule::RunOutModule( const int64_t module_id, const std::shared_ptr & planner_data, @@ -103,16 +105,18 @@ bool RunOutModule::modifyPathVelocity( debug_ptr_->setDebugValues(DebugValues::TYPE::NUM_OBSTACLES, dynamic_obstacles.size()); const auto filtered_obstacles = std::invoke([&]() { + // Only target_obstacle_types are considered. + const auto target_obstacles = excludeObstaclesBasedOnLabel(dynamic_obstacles); // extract obstacles using lanelet information const auto partition_excluded_obstacles = - excludeObstaclesOutSideOfPartition(dynamic_obstacles, extended_smoothed_path, current_pose); - - if (!planner_param_.run_out.use_ego_cut_line) return partition_excluded_obstacles; - + excludeObstaclesOutSideOfPartition(target_obstacles, extended_smoothed_path, current_pose); // extract obstacles that cross the ego's cut line const auto ego_cut_line_excluded_obstacles = excludeObstaclesCrossingEgoCutLine(partition_excluded_obstacles, current_pose); - return ego_cut_line_excluded_obstacles; + // extract obstacles already on the ego's path + const auto obstacles_outside_ego_path = + excludeObstaclesOnEgoPath(ego_cut_line_excluded_obstacles, extended_smoothed_path); + return obstacles_outside_ego_path; }); // record time for obstacle creation @@ -327,27 +331,79 @@ std::vector RunOutModule::createVehiclePolygon( return vehicle_poly; } +std::vector RunOutModule::excludeObstaclesOnEgoPath( + const std::vector & dynamic_obstacles, const PathWithLaneId & path) +{ + using motion_utils::findNearestIndex; + using tier4_autoware_utils::calcOffsetPose; + if (!planner_param_.run_out.exclude_obstacles_already_in_path || path.points.empty()) { + return dynamic_obstacles; + } + const auto footprint_extra_margin = planner_param_.run_out.ego_footprint_extra_margin; + const auto vehicle_width = planner_param_.vehicle_param.width; + const auto vehicle_with_with_margin_halved = (vehicle_width + footprint_extra_margin) / 2.0; + const double time_threshold_for_prev_collision_obstacle = + planner_param_.run_out.keep_obstacle_on_path_time_threshold; + + std::vector obstacles_outside_of_path; + std::for_each(dynamic_obstacles.begin(), dynamic_obstacles.end(), [&](const auto & o) { + const auto idx = findNearestIndex(path.points, o.pose); + if (!idx) { + obstacles_outside_of_path.push_back(o); + return; + } + const auto object_position = o.pose.position; + const auto closest_ego_pose = path.points.at(*idx).point.pose; + const auto vehicle_left_pose = + tier4_autoware_utils::calcOffsetPose(closest_ego_pose, 0, vehicle_with_with_margin_halved, 0); + const auto vehicle_right_pose = tier4_autoware_utils::calcOffsetPose( + closest_ego_pose, 0, -vehicle_with_with_margin_halved, 0); + const double signed_distance_from_left = + tier4_autoware_utils::calcLateralDeviation(vehicle_left_pose, object_position); + const double signed_distance_from_right = + tier4_autoware_utils::calcLateralDeviation(vehicle_right_pose, object_position); + + // If object is outside of the ego path, include it in list of possible target objects + // It is also deleted from the path of objects inside ego path + const auto obstacle_uuid_hex = tier4_autoware_utils::toHexString(o.uuid); + if (signed_distance_from_left > 0.0 || signed_distance_from_right < 0.0) { + obstacles_outside_of_path.push_back(o); + obstacle_in_ego_path_times_.erase(obstacle_uuid_hex); + return; + } + + const auto it = obstacle_in_ego_path_times_.find(obstacle_uuid_hex); + // This obstacle is first detected inside the ego path, we keep it. + if (it == obstacle_in_ego_path_times_.end()) { + const auto now = clock_->now().seconds(); + obstacle_in_ego_path_times_.insert(std::make_pair(obstacle_uuid_hex, now)); + obstacles_outside_of_path.push_back(o); + return; + } + + // if the obstacle has been on the ego path for more than a threshold time, it is excluded + const auto first_detection_inside_path_time = it->second; + const auto now = clock_->now().seconds(); + const double elapsed_time_since_detection_inside_of_path = + (now - first_detection_inside_path_time); + if (elapsed_time_since_detection_inside_of_path < time_threshold_for_prev_collision_obstacle) { + obstacles_outside_of_path.push_back(o); + return; + } + }); + return obstacles_outside_of_path; +} + std::vector RunOutModule::checkCollisionWithObstacles( const std::vector & dynamic_obstacles, std::vector poly, const float travel_time, const std::vector> & crosswalk_lanelets) const { - using object_recognition_utils::convertLabelToString; const auto bg_poly_vehicle = run_out_utils::createBoostPolyFromMsg(poly); // check collision for each objects std::vector obstacles_collision; for (const auto & obstacle : dynamic_obstacles) { - // get classification that has highest probability - const auto classification = - convertLabelToString(run_out_utils::getHighestProbLabel(obstacle.classifications)); - const auto & target_obstacle_types = planner_param_.run_out.target_obstacle_types; - // detect only pedestrians, bicycles or motorcycles - const auto it = - std::find(target_obstacle_types.begin(), target_obstacle_types.end(), classification); - if (it == target_obstacle_types.end()) { - continue; - } // calculate predicted obstacle pose for min velocity and max velocity const auto predicted_obstacle_pose_min_vel = calcPredictedObstaclePose(obstacle.predicted_paths, travel_time, obstacle.min_velocity_mps); @@ -823,6 +879,7 @@ std::vector RunOutModule::excludeObstaclesCrossingEgoCutLine( const std::vector & dynamic_obstacles, const geometry_msgs::msg::Pose & current_pose) const { + if (!planner_param_.run_out.use_ego_cut_line) return dynamic_obstacles; std::vector extracted_obstacles; std::vector ego_cut_line; const double ego_cut_line_half_width = planner_param_.run_out.ego_cut_line_length / 2.0; @@ -837,6 +894,25 @@ std::vector RunOutModule::excludeObstaclesCrossingEgoCutLine( return extracted_obstacles; } +std::vector RunOutModule::excludeObstaclesBasedOnLabel( + const std::vector & dynamic_obstacles) const +{ + std::vector output; + const auto & target_obstacle_types = planner_param_.run_out.target_obstacle_types; + std::for_each(dynamic_obstacles.begin(), dynamic_obstacles.end(), [&](const auto obstacle) { + // get classification that has highest probability + const auto classification = + convertLabelToString(run_out_utils::getHighestProbLabel(obstacle.classifications)); + // include only pedestrians, bicycles or motorcycles + const auto it = + std::find(target_obstacle_types.begin(), target_obstacle_types.end(), classification); + if (it != target_obstacle_types.end()) { + output.push_back(obstacle); + } + }); + return output; +} + std::vector RunOutModule::excludeObstaclesOutSideOfPartition( const std::vector & dynamic_obstacles, const PathWithLaneId & path, const geometry_msgs::msg::Pose & current_pose) const @@ -909,6 +985,7 @@ bool RunOutModule::isMomentaryDetection() return false; } + // No detection until now if (!first_detected_time_) { first_detected_time_ = std::make_shared(clock_->now()); return true; diff --git a/planning/behavior_velocity_run_out_module/src/scene.hpp b/planning/behavior_velocity_run_out_module/src/scene.hpp index 090f76ef30328..c7702ed15337d 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/behavior_velocity_run_out_module/src/scene.hpp @@ -25,6 +25,8 @@ #include #include +#include +#include #include #include @@ -64,6 +66,8 @@ class RunOutModule : public SceneModuleInterface std::shared_ptr debug_ptr_; std::unique_ptr state_machine_; std::shared_ptr first_detected_time_; + std::optional last_stop_obstacle_uuid_; + std::unordered_map obstacle_in_ego_path_times_; // Function Polygons2d createDetectionAreaPolygon(const PathWithLaneId & smoothed_path) const; @@ -148,10 +152,16 @@ class RunOutModule : public SceneModuleInterface const std::vector & dynamic_obstacles, const geometry_msgs::msg::Pose & current_pose) const; + std::vector excludeObstaclesBasedOnLabel( + const std::vector & dynamic_obstacles) const; + std::vector excludeObstaclesOutSideOfPartition( const std::vector & dynamic_obstacles, const PathWithLaneId & path, const geometry_msgs::msg::Pose & current_pose) const; + std::vector excludeObstaclesOnEgoPath( + const std::vector & dynamic_obstacles, const PathWithLaneId & path); + void publishDebugValue( const PathWithLaneId & path, const std::vector extracted_obstacles, const std::optional & dynamic_obstacle, diff --git a/planning/behavior_velocity_run_out_module/src/utils.hpp b/planning/behavior_velocity_run_out_module/src/utils.hpp index 54aa3395a0050..823dc81b2b72b 100644 --- a/planning/behavior_velocity_run_out_module/src/utils.hpp +++ b/planning/behavior_velocity_run_out_module/src/utils.hpp @@ -21,13 +21,14 @@ #include #include +#include #include #include #include +#include #include #include - namespace behavior_velocity_planner { namespace run_out_utils @@ -60,10 +61,13 @@ struct RunOutParam bool suppress_on_crosswalk; bool specify_decel_jerk; bool use_ego_cut_line; + bool exclude_obstacles_already_in_path; double stop_margin; double passing_margin; double deceleration_jerk; double ego_cut_line_length; + double ego_footprint_extra_margin; + double keep_obstacle_on_path_time_threshold; float detection_distance; float detection_span; float min_vel_ego_kmph; @@ -187,6 +191,7 @@ struct DynamicObstacle std::vector classifications; Shape shape; std::vector predicted_paths; + unique_identifier_msgs::msg::UUID uuid; }; struct DynamicObstacleData From 42d49368b4a516054b5fb710bcabb202f200e5f9 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 1 Apr 2024 15:18:22 +0900 Subject: [PATCH 02/57] feat(lane_change): additional debug markers (#6529) Signed-off-by: Muhammad Zulfaqar Azmi --- .../utils/debug_structs.hpp | 24 ++++++++ .../utils/markers.hpp | 5 +- .../src/interface.cpp | 7 ++- .../src/scene.cpp | 57 +++++++++++++------ .../src/utils/markers.cpp | 55 ++++++++++++++++-- 5 files changed, 122 insertions(+), 26 deletions(-) diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/debug_structs.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/debug_structs.hpp index d8ba7cf19cfee..37d436f9949a2 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/debug_structs.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/debug_structs.hpp @@ -21,6 +21,9 @@ #include +#include + +#include #include namespace behavior_path_planner::data::lane_change @@ -34,7 +37,17 @@ struct Debug CollisionCheckDebugMap collision_check_objects_after_approval; LaneChangeTargetObjects filtered_objects; geometry_msgs::msg::Polygon execution_area; + geometry_msgs::msg::Pose ego_pose; + lanelet::ConstLanelets current_lanes; + lanelet::ConstLanelets target_lanes; + lanelet::ConstLanelets target_backward_lanes; double collision_check_object_debug_lifetime{0.0}; + double distance_to_end_of_current_lane{std::numeric_limits::max()}; + double distance_to_lane_change_finished{std::numeric_limits::max()}; + double distance_to_abort_finished{std::numeric_limits::max()}; + bool is_able_to_return_to_current_lane{false}; + bool is_stuck{false}; + bool is_abort{false}; void reset() { @@ -44,7 +57,18 @@ struct Debug filtered_objects.current_lane.clear(); filtered_objects.target_lane.clear(); filtered_objects.other_lane.clear(); + execution_area.points.clear(); + current_lanes.clear(); + target_lanes.clear(); + target_backward_lanes.clear(); + collision_check_object_debug_lifetime = 0.0; + distance_to_end_of_current_lane = std::numeric_limits::max(); + distance_to_lane_change_finished = std::numeric_limits::max(); + distance_to_abort_finished = std::numeric_limits::max(); + is_able_to_return_to_current_lane = false; + is_stuck = false; + is_abort = false; } }; } // namespace behavior_path_planner::data::lane_change diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/markers.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/markers.hpp index 8863cabdba008..bc4413e1c69d3 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/markers.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/markers.hpp @@ -20,6 +20,7 @@ #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include +#include #include #include @@ -42,7 +43,9 @@ MarkerArray showFilteredObjects( const ExtendedPredictedObjects & target_lane_objects, const ExtendedPredictedObjects & other_lane_objects, const std::string & ns); MarkerArray createExecutionArea(const geometry_msgs::msg::Polygon & execution_area); -MarkerArray createDebugMarkerArray(const Debug & debug_data); +MarkerArray showExecutionInfo(const Debug & debug_data, const geometry_msgs::msg::Pose & ego_pose); +MarkerArray createDebugMarkerArray( + const Debug & debug_data, const geometry_msgs::msg::Pose & ego_pose); } // namespace marker_utils::lane_change_markers #endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__MARKERS_HPP_ diff --git a/planning/behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp index 46b65a3ef4e79..523a5349aaef6 100644 --- a/planning/behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -85,9 +85,9 @@ void LaneChangeInterface::updateData() if (isWaitingApproval()) { module_type_->updateLaneChangeStatus(); } - updateDebugMarker(); module_type_->resetStopPose(); + updateDebugMarker(); } void LaneChangeInterface::postProcess() @@ -97,6 +97,7 @@ void LaneChangeInterface::postProcess() post_process_safety_status_ = module_type_->evaluateApprovedPathWithUnsafeHysteresis(safety_status); } + updateDebugMarker(); } BehaviorModuleOutput LaneChangeInterface::plan() @@ -196,6 +197,7 @@ bool LaneChangeInterface::canTransitSuccessState() auto log_debug_throttled = [&](std::string_view message) -> void { RCLCPP_DEBUG(getLogger(), "%s", message.data()); }; + updateDebugMarker(); if (module_type_->specialExpiredCheck() && isWaitingApproval()) { log_debug_throttled("Run specialExpiredCheck."); @@ -225,6 +227,7 @@ bool LaneChangeInterface::canTransitFailureState() RCLCPP_DEBUG(getLogger(), "%s", message.data()); }; + updateDebugMarker(); log_debug_throttled(__func__); if (module_type_->isAbortState() && !module_type_->hasFinishedAbort()) { @@ -300,7 +303,7 @@ void LaneChangeInterface::updateDebugMarker() const return; } using marker_utils::lane_change_markers::createDebugMarkerArray; - debug_marker_ = createDebugMarkerArray(module_type_->getDebugData()); + debug_marker_ = createDebugMarkerArray(module_type_->getDebugData(), module_type_->getEgoPose()); } MarkerArray LaneChangeInterface::getModuleVirtualWall() diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index 9524d47e522e5..08034d43feb43 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -567,15 +567,20 @@ bool NormalLaneChange::isNearEndOfCurrentLanes( const auto lane_change_buffer = utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals); - auto distance_to_end = utils::getDistanceToEndOfLane(current_pose, current_lanes); + const auto distance_to_lane_change_end = std::invoke([&]() { + auto distance_to_end = utils::getDistanceToEndOfLane(current_pose, current_lanes); - if (!target_lanes.empty() && route_handler->isInGoalRouteSection(target_lanes.back())) { - distance_to_end = std::min( - distance_to_end, - utils::getSignedDistance(current_pose, route_handler->getGoalPose(), current_lanes)); - } + if (!target_lanes.empty() && route_handler->isInGoalRouteSection(target_lanes.back())) { + distance_to_end = std::min( + distance_to_end, + utils::getSignedDistance(current_pose, route_handler->getGoalPose(), current_lanes)); + } + + return std::max(0.0, distance_to_end) - lane_change_buffer; + }); - return (std::max(0.0, distance_to_end) - lane_change_buffer) < threshold; + lane_change_debug_.distance_to_end_of_current_lane = distance_to_lane_change_end; + return distance_to_lane_change_end < threshold; } bool NormalLaneChange::hasFinishedLaneChange() const @@ -593,6 +598,10 @@ bool NormalLaneChange::hasFinishedLaneChange() const } const auto reach_lane_change_end = dist_to_lane_change_end + finish_judge_buffer < 0.0; + + lane_change_debug_.distance_to_lane_change_finished = + dist_to_lane_change_end + finish_judge_buffer; + if (!reach_lane_change_end) { return false; } @@ -600,22 +609,23 @@ bool NormalLaneChange::hasFinishedLaneChange() const const auto arc_length = lanelet::utils::getArcCoordinates(status_.target_lanes, current_pose); const auto reach_target_lane = std::abs(arc_length.distance) < lane_change_parameters_->finish_judge_lateral_threshold; - if (!reach_target_lane) { - return false; - } - return true; + lane_change_debug_.distance_to_lane_change_finished = arc_length.distance; + + return reach_target_lane; } bool NormalLaneChange::isAbleToReturnCurrentLane() const { if (status_.lane_change_path.path.points.size() < 2) { + lane_change_debug_.is_able_to_return_to_current_lane = false; return false; } if (!utils::isEgoWithinOriginalLane( status_.current_lanes, getEgoPose(), planner_data_->parameters, lane_change_parameters_->cancel.overhang_tolerance)) { + lane_change_debug_.is_able_to_return_to_current_lane = false; return false; } @@ -633,12 +643,15 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const dist += calcSignedArcLength(status_.lane_change_path.path.points, idx, idx + 1); if (dist > estimated_travel_dist) { const auto & estimated_pose = status_.lane_change_path.path.points.at(idx + 1).point.pose; - return utils::isEgoWithinOriginalLane( + auto is_ego_within_original_lane = utils::isEgoWithinOriginalLane( status_.current_lanes, estimated_pose, planner_data_->parameters, lane_change_parameters_->cancel.overhang_tolerance); + lane_change_debug_.is_able_to_return_to_current_lane = is_ego_within_original_lane; + return is_ego_within_original_lane; } } + lane_change_debug_.is_able_to_return_to_current_lane = true; return true; } @@ -679,17 +692,18 @@ bool NormalLaneChange::isAbleToStopSafely() const bool NormalLaneChange::hasFinishedAbort() const { if (!abort_path_) { + lane_change_debug_.is_abort = true; return true; } const auto distance_to_finish = calcSignedArcLength( abort_path_->path.points, getEgoPosition(), abort_path_->info.shift_line.end.position); + lane_change_debug_.distance_to_abort_finished = distance_to_finish; - if (distance_to_finish < 0.0) { - return true; - } + const auto has_finished_abort = distance_to_finish < 0.0; + lane_change_debug_.is_abort = has_finished_abort; - return false; + return has_finished_abort; } bool NormalLaneChange::isAbortState() const @@ -706,6 +720,7 @@ bool NormalLaneChange::isAbortState() const return false; } + lane_change_debug_.is_abort = true; return true; } int NormalLaneChange::getNumToPreferredLane(const lanelet::ConstLanelet & lane) const @@ -860,6 +875,10 @@ LaneChangeTargetObjects NormalLaneChange::getTargetObjects( const auto target_backward_lanes = behavior_path_planner::utils::getBackwardLanelets( route_handler, target_lanes, current_pose, backward_length); + lane_change_debug_.current_lanes = current_lanes; + lane_change_debug_.target_lanes = target_lanes; + lane_change_debug_.target_backward_lanes = target_backward_lanes; + // filter objects to get target object index const auto target_obj_index = filterObject(objects, current_lanes, target_lanes, target_backward_lanes); @@ -2043,6 +2062,7 @@ bool NormalLaneChange::isVehicleStuck( bool NormalLaneChange::isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const { if (current_lanes.empty()) { + lane_change_debug_.is_stuck = false; return false; // can not check } @@ -2062,7 +2082,10 @@ bool NormalLaneChange::isVehicleStuck(const lanelet::ConstLanelets & current_lan getCommonParam().base_link2front + DETECTION_DISTANCE_MARGIN; RCLCPP_DEBUG(logger_, "max_lane_change_length: %f, max_acc: %f", max_lane_change_length, max_acc); - return isVehicleStuck(current_lanes, detection_distance); + auto is_vehicle_stuck = isVehicleStuck(current_lanes, detection_distance); + + lane_change_debug_.is_stuck = is_vehicle_stuck; + return is_vehicle_stuck; } void NormalLaneChange::setStopPose(const Pose & stop_pose) diff --git a/planning/behavior_path_lane_change_module/src/utils/markers.cpp b/planning/behavior_path_lane_change_module/src/utils/markers.cpp index 67594823eb112..9e44e51d8b72d 100644 --- a/planning/behavior_path_lane_change_module/src/utils/markers.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/markers.cpp @@ -17,15 +17,18 @@ #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" #include +#include #include #include #include +#include #include #include #include #include +#include #include #include @@ -122,8 +125,39 @@ MarkerArray showFilteredObjects( return marker_array; } -MarkerArray createDebugMarkerArray(const Debug & debug_data) +MarkerArray showExecutionInfo(const Debug & debug_data, const geometry_msgs::msg::Pose & ego_pose) { + auto default_text_marker = [&]() { + return createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "execution_info", 0, Marker::TEXT_VIEW_FACING, + createMarkerScale(0.5, 0.5, 0.5), colors::white()); + }; + + MarkerArray marker_array; + + auto safety_check_info_text = default_text_marker(); + safety_check_info_text.pose = ego_pose; + safety_check_info_text.pose.position.z += 4.0; + + std::ostringstream ss; + + ss << "\nDistToEndOfCurrentLane: " << std::setprecision(5) + << debug_data.distance_to_end_of_current_lane + << "\nDistToLaneChangeFinished: " << debug_data.distance_to_lane_change_finished + << (debug_data.is_stuck ? "\nVehicleStuck" : "") + << (debug_data.is_able_to_return_to_current_lane ? "\nAbleToReturnToCurrentLane" : "") + << (debug_data.is_abort ? "\nAborting" : "") + << "\nDistanceToAbortFinished: " << debug_data.distance_to_abort_finished; + + safety_check_info_text.text = ss.str(); + marker_array.markers.push_back(safety_check_info_text); + return marker_array; +} + +MarkerArray createDebugMarkerArray( + const Debug & debug_data, const geometry_msgs::msg::Pose & ego_pose) +{ + using lanelet::visualization::laneletsAsTriangleMarkerArray; using marker_utils::showPolygon; using marker_utils::showPredictedPath; using marker_utils::showSafetyCheckInfo; @@ -141,6 +175,20 @@ MarkerArray createDebugMarkerArray(const Debug & debug_data) tier4_autoware_utils::appendMarkerArray(added, &debug_marker); }; + if (!debug_data.execution_area.points.empty()) { + add(createPolygonMarkerArray( + debug_data.execution_area, "execution_area", 0, 0.16, 1.0, 0.69, 0.1)); + } + + add(showExecutionInfo(debug_data, ego_pose)); + + // lanes + add(laneletsAsTriangleMarkerArray( + "current_lanes", debug_data.current_lanes, colors::light_yellow(0.2))); + add(laneletsAsTriangleMarkerArray("target_lanes", debug_data.target_lanes, colors::aqua(0.2))); + add(laneletsAsTriangleMarkerArray( + "target_backward_lanes", debug_data.target_backward_lanes, colors::blue(0.2))); + add(showAllValidLaneChangePath(debug_valid_paths, "lane_change_valid_paths")); add(showFilteredObjects( debug_filtered_objects.current_lane, debug_filtered_objects.target_lane, @@ -162,11 +210,6 @@ MarkerArray createDebugMarkerArray(const Debug & debug_data) "ego_and_target_polygon_relation_after_approval")); } - if (!debug_data.execution_area.points.empty()) { - add(createPolygonMarkerArray( - debug_data.execution_area, "execution_area", 0, 0.16, 1.0, 0.69, 0.1)); - } - return debug_marker; } } // namespace marker_utils::lane_change_markers From 46e3ad42d62ba51d36b0e8a8fa34e8b0f252f18c Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Mon, 1 Apr 2024 15:50:11 +0900 Subject: [PATCH 03/57] feat(ndt_scan_matcher): fix first update map (#6699) Signed-off-by: Yamato Ando --- localization/ndt_scan_matcher/src/map_update_module.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index f29d6261fc02b..ca56a93cec859 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -48,7 +48,8 @@ MapUpdateModule::MapUpdateModule( bool MapUpdateModule::should_update_map(const geometry_msgs::msg::Point & position) { if (last_update_position_ == std::nullopt) { - return false; + need_rebuild_ = true; + return true; } const double dx = position.x - last_update_position_.value().x; From 8c02272f86b3feb67e0b8020129fc0df62abffe5 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Mon, 1 Apr 2024 15:50:23 +0900 Subject: [PATCH 04/57] feat(pose_initilizer): set intial pose directly (#6692) * feat(pose_initilizer): set intial pose directly Signed-off-by: Yamato Ando * style(pre-commit): autofix * fix arg order Signed-off-by: Yamato Ando * minor change Signed-off-by: Yamato Ando * style(pre-commit): autofix * remove blank lines Signed-off-by: Yamato Ando * change types Signed-off-by: Yamato Ando * add wait_for_service Signed-off-by: Yamato Ando * style(pre-commit): autofix * fix default quaternion Signed-off-by: Yamato Ando * rename params Signed-off-by: Yamato Ando * input quaternion validation Signed-off-by: Yamato Ando * fix message Signed-off-by: Yamato Ando * style(pre-commit): autofix * add std::abs Signed-off-by: Yamato Ando * style(pre-commit): autofix --------- Signed-off-by: Yamato Ando Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../launch/localization.launch.xml | 1 + .../pose_twist_estimator.launch.xml | 7 ++ .../config/pose_initializer.param.yaml | 4 + .../schema/pose_initializer.schema.json | 18 ++++ .../ekf_localization_trigger_module.cpp | 23 ++++-- .../ekf_localization_trigger_module.hpp | 5 +- .../ndt_localization_trigger_module.cpp | 23 ++++-- .../ndt_localization_trigger_module.hpp | 5 +- .../pose_initializer_core.cpp | 82 ++++++++++++++++--- .../pose_initializer_core.hpp | 3 + 10 files changed, 143 insertions(+), 28 deletions(-) diff --git a/launch/tier4_localization_launch/launch/localization.launch.xml b/launch/tier4_localization_launch/launch/localization.launch.xml index 7f2f446ae1bee..cfc09459a5cb1 100644 --- a/launch/tier4_localization_launch/launch/localization.launch.xml +++ b/launch/tier4_localization_launch/launch/localization.launch.xml @@ -2,6 +2,7 @@ + diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml index 3042774d16fd3..c09443be8cab6 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml @@ -21,6 +21,11 @@ + + + + + @@ -91,6 +96,8 @@ + + diff --git a/localization/pose_initializer/config/pose_initializer.param.yaml b/localization/pose_initializer/config/pose_initializer.param.yaml index 88acbfb52611d..90ec78257e6cb 100644 --- a/localization/pose_initializer/config/pose_initializer.param.yaml +++ b/localization/pose_initializer/config/pose_initializer.param.yaml @@ -1,5 +1,9 @@ /**: ros__parameters: + user_defined_initial_pose: + enable: $(var user_defined_initial_pose/enable) + pose: $(var user_defined_initial_pose/pose) + gnss_pose_timeout: 3.0 # [sec] stop_check_duration: 3.0 # [sec] ekf_enabled: $(var ekf_enabled) diff --git a/localization/pose_initializer/schema/pose_initializer.schema.json b/localization/pose_initializer/schema/pose_initializer.schema.json index ced4dc78b93b1..d5b92c45d3038 100644 --- a/localization/pose_initializer/schema/pose_initializer.schema.json +++ b/localization/pose_initializer/schema/pose_initializer.schema.json @@ -6,6 +6,23 @@ "pose_initializer": { "type": "object", "properties": { + "user_defined_initial_pose": { + "type": "object", + "properties": { + "enable": { + "type": "string", + "description": "If true, user_defined_initial_pose.pose is set as the initial position. [boolean]", + "default": "false" + }, + "pose": { + "type": "string", + "description": "initial pose (x, y, z, quat_x, quat_y, quat_z, quat_w). [array]", + "default": "[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0]" + } + }, + "required": ["enable", "pose"], + "additionalProperties": false + }, "gnss_pose_timeout": { "type": "number", "description": "The duration that the GNSS pose is valid. [sec]", @@ -55,6 +72,7 @@ } }, "required": [ + "user_defined_initial_pose", "gnss_pose_timeout", "stop_check_duration", "ekf_enabled", diff --git a/localization/pose_initializer/src/pose_initializer/ekf_localization_trigger_module.cpp b/localization/pose_initializer/src/pose_initializer/ekf_localization_trigger_module.cpp index ac9796b687637..9ba424f8e857f 100644 --- a/localization/pose_initializer/src/pose_initializer/ekf_localization_trigger_module.cpp +++ b/localization/pose_initializer/src/pose_initializer/ekf_localization_trigger_module.cpp @@ -23,13 +23,20 @@ using ServiceException = component_interface_utils::ServiceException; using Initialize = localization_interface::Initialize; -EkfLocalizationTriggerModule::EkfLocalizationTriggerModule(rclcpp::Node * node) -: logger_(node->get_logger()) +EkfLocalizationTriggerModule::EkfLocalizationTriggerModule(rclcpp::Node * node) : node_(node) { - client_ekf_trigger_ = node->create_client("ekf_trigger_node"); + client_ekf_trigger_ = node_->create_client("ekf_trigger_node"); } -void EkfLocalizationTriggerModule::send_request(bool flag) const +void EkfLocalizationTriggerModule::wait_for_service() +{ + while (!client_ekf_trigger_->wait_for_service(std::chrono::seconds(1))) { + RCLCPP_INFO(node_->get_logger(), "EKF triggering service is not available, waiting..."); + } + RCLCPP_INFO(node_->get_logger(), "EKF triggering service is available!"); +} + +void EkfLocalizationTriggerModule::send_request(bool flag, bool need_spin) const { const auto req = std::make_shared(); std::string command_name; @@ -46,10 +53,14 @@ void EkfLocalizationTriggerModule::send_request(bool flag) const auto future_ekf = client_ekf_trigger_->async_send_request(req); + if (need_spin) { + rclcpp::spin_until_future_complete(node_->get_node_base_interface(), future_ekf); + } + if (future_ekf.get()->success) { - RCLCPP_INFO(logger_, "EKF %s succeeded", command_name.c_str()); + RCLCPP_INFO(node_->get_logger(), "EKF %s succeeded", command_name.c_str()); } else { - RCLCPP_INFO(logger_, "EKF %s failed", command_name.c_str()); + RCLCPP_INFO(node_->get_logger(), "EKF %s failed", command_name.c_str()); throw ServiceException( Initialize::Service::Response::ERROR_ESTIMATION, "EKF " + command_name + " failed"); } diff --git a/localization/pose_initializer/src/pose_initializer/ekf_localization_trigger_module.hpp b/localization/pose_initializer/src/pose_initializer/ekf_localization_trigger_module.hpp index d1b8eb986105f..901e4ec4414b5 100644 --- a/localization/pose_initializer/src/pose_initializer/ekf_localization_trigger_module.hpp +++ b/localization/pose_initializer/src/pose_initializer/ekf_localization_trigger_module.hpp @@ -26,10 +26,11 @@ class EkfLocalizationTriggerModule public: explicit EkfLocalizationTriggerModule(rclcpp::Node * node); - void send_request(bool flag) const; + void wait_for_service(); + void send_request(bool flag, bool need_spin = false) const; private: - rclcpp::Logger logger_; + rclcpp::Node * node_; rclcpp::Client::SharedPtr client_ekf_trigger_; }; diff --git a/localization/pose_initializer/src/pose_initializer/ndt_localization_trigger_module.cpp b/localization/pose_initializer/src/pose_initializer/ndt_localization_trigger_module.cpp index e1285f5c31c83..436b1e2df3b21 100644 --- a/localization/pose_initializer/src/pose_initializer/ndt_localization_trigger_module.cpp +++ b/localization/pose_initializer/src/pose_initializer/ndt_localization_trigger_module.cpp @@ -23,13 +23,20 @@ using ServiceException = component_interface_utils::ServiceException; using Initialize = localization_interface::Initialize; -NdtLocalizationTriggerModule::NdtLocalizationTriggerModule(rclcpp::Node * node) -: logger_(node->get_logger()) +NdtLocalizationTriggerModule::NdtLocalizationTriggerModule(rclcpp::Node * node) : node_(node) { - client_ndt_trigger_ = node->create_client("ndt_trigger_node"); + client_ndt_trigger_ = node_->create_client("ndt_trigger_node"); } -void NdtLocalizationTriggerModule::send_request(bool flag) const +void NdtLocalizationTriggerModule::wait_for_service() +{ + while (!client_ndt_trigger_->wait_for_service(std::chrono::seconds(1))) { + RCLCPP_INFO(node_->get_logger(), "NDT triggering service is not available, waiting..."); + } + RCLCPP_INFO(node_->get_logger(), "NDT triggering service is available!"); +} + +void NdtLocalizationTriggerModule::send_request(bool flag, bool need_spin) const { const auto req = std::make_shared(); std::string command_name; @@ -46,10 +53,14 @@ void NdtLocalizationTriggerModule::send_request(bool flag) const auto future_ndt = client_ndt_trigger_->async_send_request(req); + if (need_spin) { + rclcpp::spin_until_future_complete(node_->get_node_base_interface(), future_ndt); + } + if (future_ndt.get()->success) { - RCLCPP_INFO(logger_, "NDT %s succeeded", command_name.c_str()); + RCLCPP_INFO(node_->get_logger(), "NDT %s succeeded", command_name.c_str()); } else { - RCLCPP_INFO(logger_, "NDT %s failed", command_name.c_str()); + RCLCPP_INFO(node_->get_logger(), "NDT %s failed", command_name.c_str()); throw ServiceException( Initialize::Service::Response::ERROR_ESTIMATION, "NDT " + command_name + " failed"); } diff --git a/localization/pose_initializer/src/pose_initializer/ndt_localization_trigger_module.hpp b/localization/pose_initializer/src/pose_initializer/ndt_localization_trigger_module.hpp index 91e37c9bb90e9..1c820557fb8ff 100644 --- a/localization/pose_initializer/src/pose_initializer/ndt_localization_trigger_module.hpp +++ b/localization/pose_initializer/src/pose_initializer/ndt_localization_trigger_module.hpp @@ -26,10 +26,11 @@ class NdtLocalizationTriggerModule public: explicit NdtLocalizationTriggerModule(rclcpp::Node * node); - void send_request(bool flag) const; + void wait_for_service(); + void send_request(bool flag, bool need_spin = false) const; private: - rclcpp::Logger logger_; + rclcpp::Node * node_; rclcpp::Client::SharedPtr client_ndt_trigger_; }; diff --git a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp index 4585414c20b0d..bc86b5476dcca 100644 --- a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp +++ b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp @@ -57,6 +57,31 @@ PoseInitializer::PoseInitializer() : Node("pose_initializer") logger_configure_ = std::make_unique(this); change_state(State::Message::UNINITIALIZED); + + if (declare_parameter("user_defined_initial_pose.enable")) { + const auto initial_pose_array = + declare_parameter>("user_defined_initial_pose.pose"); + if (initial_pose_array.size() != 7) { + throw std::invalid_argument( + "Could not set user defined initial pose. The size of initial_pose is " + + std::to_string(initial_pose_array.size()) + ". It must be 7."); + } else if ( + std::abs(initial_pose_array[3]) < 1e-6 && std::abs(initial_pose_array[4]) < 1e-6 && + std::abs(initial_pose_array[5]) < 1e-6 && std::abs(initial_pose_array[6]) < 1e-6) { + throw std::invalid_argument("Input quaternion is invalid. All elements are close to zero."); + } else { + geometry_msgs::msg::Pose initial_pose; + initial_pose.position.x = initial_pose_array[0]; + initial_pose.position.y = initial_pose_array[1]; + initial_pose.position.z = initial_pose_array[2]; + initial_pose.orientation.x = initial_pose_array[3]; + initial_pose.orientation.y = initial_pose_array[4]; + initial_pose.orientation.z = initial_pose_array[5]; + initial_pose.orientation.w = initial_pose_array[6]; + + set_user_defined_initial_pose(initial_pose); + } + } } PoseInitializer::~PoseInitializer() @@ -71,6 +96,47 @@ void PoseInitializer::change_state(State::Message::_state_type state) pub_state_->publish(state_); } +// To execute in the constructor, you need to call ros spin. +// Conversely, ros spin should not be called elsewhere +void PoseInitializer::change_node_trigger(bool flag, bool need_spin) +{ + try { + if (ekf_localization_trigger_) { + ekf_localization_trigger_->wait_for_service(); + ekf_localization_trigger_->send_request(flag, need_spin); + } + if (ndt_localization_trigger_) { + ndt_localization_trigger_->wait_for_service(); + ndt_localization_trigger_->send_request(flag, need_spin); + } + } catch (const ServiceException & error) { + throw; + } +} + +void PoseInitializer::set_user_defined_initial_pose(const geometry_msgs::msg::Pose initial_pose) +{ + try { + change_state(State::Message::INITIALIZING); + change_node_trigger(false, true); + + PoseWithCovarianceStamped pose; + pose.header.frame_id = "map"; + pose.header.stamp = now(); + pose.pose.pose = initial_pose; + pose.pose.covariance = output_pose_covariance_; + pub_reset_->publish(pose); + + change_node_trigger(true, true); + change_state(State::Message::INITIALIZED); + + RCLCPP_INFO(get_logger(), "Set user defined initial pose"); + } catch (const ServiceException & error) { + change_state(State::Message::UNINITIALIZED); + RCLCPP_WARN(get_logger(), "Could not set user defined initial pose"); + } +} + void PoseInitializer::on_initialize( const Initialize::Service::Request::SharedPtr req, const Initialize::Service::Response::SharedPtr res) @@ -82,12 +148,8 @@ void PoseInitializer::on_initialize( } try { change_state(State::Message::INITIALIZING); - if (ekf_localization_trigger_) { - ekf_localization_trigger_->send_request(false); - } - if (ndt_localization_trigger_) { - ndt_localization_trigger_->send_request(false); - } + change_node_trigger(false, false); + auto pose = req->pose.empty() ? get_gnss_pose() : req->pose.front(); if (ndt_) { pose = ndt_->align_pose(pose); @@ -98,12 +160,8 @@ void PoseInitializer::on_initialize( } pose.pose.covariance = output_pose_covariance_; pub_reset_->publish(pose); - if (ekf_localization_trigger_) { - ekf_localization_trigger_->send_request(true); - } - if (ndt_localization_trigger_) { - ndt_localization_trigger_->send_request(true); - } + + change_node_trigger(true, false); res->status.success = true; change_state(State::Message::INITIALIZED); } catch (const ServiceException & error) { diff --git a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp index 014c8e9bf6e04..623cfe50307f5 100644 --- a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp +++ b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp @@ -58,6 +58,9 @@ class PoseInitializer : public rclcpp::Node std::unique_ptr ndt_localization_trigger_; std::unique_ptr logger_configure_; double stop_check_duration_; + + void change_node_trigger(bool flag, bool need_spin = false); + void set_user_defined_initial_pose(const geometry_msgs::msg::Pose initial_pose); void change_state(State::Message::_state_type state); void on_initialize( const Initialize::Service::Request::SharedPtr req, From a808ff0b5e96b820cd67502da10a70149abb9fb0 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 1 Apr 2024 18:44:18 +0900 Subject: [PATCH 05/57] docs(lane_change): update documentation (#6544) * docs(lane_change): update documentation Signed-off-by: Muhammad Zulfaqar Azmi * update validity check flow chart Signed-off-by: Muhammad Zulfaqar Azmi * explanation for the valid paths Signed-off-by: Muhammad Zulfaqar Azmi * Add prerequisite in the requirement Signed-off-by: Muhammad Zulfaqar Azmi * update diagram Signed-off-by: Muhammad Zulfaqar Azmi * Edit the parameters Signed-off-by: Muhammad Zulfaqar Azmi * Explaining lane expansion Signed-off-by: Muhammad Zulfaqar Azmi * fix lane expansion document Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi --- .../README.md | 404 ++++++++++++------ .../images/lane_change-lane_change_phases.png | Bin 181969 -> 33850 bytes .../lane_change-lane_expansion-with.png | Bin 0 -> 25187 bytes .../lane_change-lane_expansion-without.png | Bin 0 -> 25525 bytes 4 files changed, 280 insertions(+), 124 deletions(-) create mode 100644 planning/behavior_path_lane_change_module/images/lane_change-lane_expansion-with.png create mode 100644 planning/behavior_path_lane_change_module/images/lane_change-lane_expansion-without.png diff --git a/planning/behavior_path_lane_change_module/README.md b/planning/behavior_path_lane_change_module/README.md index 8eb791ab4f5e9..874d542b445d3 100644 --- a/planning/behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_lane_change_module/README.md @@ -4,6 +4,11 @@ The Lane Change module is activated when lane change is needed and can be safely ## Lane Change Requirement +- As the prerequisite, the type of lane boundary in the HD map has to be one of the following: + - Dashed lane marking: Lane changes are permitted in both directions. + - Dashed marking on the left and solid on the right: Lane changes are allowed from left to right. + - Dashed marking on the right and solid on the left: Lane changes are allowed from right to left. + - `allow_lane_change` tags is set as `true` - During lane change request condition - The ego-vehicle isn’t on a `preferred_lane`. - There is neither intersection nor crosswalk on the path of the lane change @@ -60,6 +65,89 @@ longitudinal_acceleration_resolution = (maximum_longitudinal_acceleration - mini Note that when the `current_velocity` is lower than `minimum_lane_changing_velocity`, the vehicle needs to accelerate its velocity to `minimum_lane_changing_velocity`. Therefore, longitudinal acceleration becomes positive value (not decelerate). +The chart illustrates the conditions under which longitudinal acceleration values are sampled. + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam backgroundColor #WHITE + +start + +if (prev_module_path is empty?) then (yes) + :Return empty list; + stop +else (no) +endif + +if (max_acc <= 0.0) then (yes) + :Return **sampled acceleration values**; + note left: Calculated sampled acceleration using\ngetAccelerationValues(min_acc, max_acc, longitudinal_acc_sampling_num) + stop +endif + +if (max_lane_change_length > ego's distance to the end of the current lanes.) then (yes) + :Return **sampled acceleration values**; + stop +endif + +if (isVehicleStuck(current_lanes)) then (yes) + :Return **sampled acceleration values**; + stop +else (no) +endif + +if (is goal is in target lanes) then (yes) + if (max_lane_change_length < ego's distance to the goal along the target lanes) then (yes) + :Return {max_acc}; + stop + else (no) + endif +else (no) + if (max_lane_change_length < ego's distance to the end of the target lanes.) then (yes) + :Return {max_acc}; + stop + else (no) + endif +endif + +:Return **sampled acceleration values**; +stop + +@enduml + +``` + +while the following describes the process by which longitudinal accelerations are sampled. + +```plantuml +@startuml +start +:Initialize sampled_values with min_acc; + +if (min_acc > max_acc) then (yes) + :Return empty list; + stop +elseif (max_acc - min_acc < epsilon) then (yes) + :Return {0.0}; + stop +else (no) + :Calculate resolution; +endif + +:Start loop from min_acc to max_acc with resolution step; +repeat + if (sampled_values.back() < -epsilon AND next_value > epsilon) then (yes) + :Insert 0.0 into sampled_values; + endif + :Add sampled_acc to sampled_values; + repeat while (sampled_acc < max_acc + epsilon) is (TRUE) + +:Return sampled_values; +stop +@enduml +``` + The following figure illustrates when `longitudinal_acceleration_sampling_num = 4`. Assuming that `maximum_deceleration = 1.0` then `a0 == 0.0 == no deceleration`, `a1 == 0.25`, `a2 == 0.5`, `a3 == 0.75` and `a4 == 1.0 == maximum_deceleration`. `a0` is the expected lane change trajectories should ego vehicle do not decelerate, and `a1`'s path is the expected lane change trajectories should ego vehicle decelerate at `0.25 m/s^2`. ![path_samples](./images/lane_change-candidate_path_samples.png) @@ -89,67 +177,112 @@ lateral_acceleration_resolution = (maximum_lateral_acceleration - minimum_latera #### Candidate Path's validity check -A candidate path is valid if the total lane change distance is less than +A candidate path is considered valid if it meets the following criteria: -1. distance to the end of current lane -2. distance to the next intersection -3. distance from current pose to the goal. -4. distance to the crosswalk. - -The goal must also be in the list of the preferred lane. +1. The distance from the ego vehicle's current position to the end of the current lanes is sufficient to perform a single lane change. +2. The distance from the ego vehicle's current position to the goal along the current lanes is adequate to complete multiple lane changes. +3. The distance from the ego vehicle's current position to the end of the target lanes is adequate for completing multiple lane changes. +4. Intersection requirements are met (conditions are parameterized). +5. Crosswalk requirements are satisfied (conditions are parameterized). +6. Traffic light regulations are adhered to (conditions are parameterized). +7. The lane change can be completed after passing a parked vehicle. +8. The lane change is deemed safe to execute. The following flow chart illustrates the validity check. ```plantuml @startuml -skinparam monochrome true skinparam defaultTextAlignment center -skinparam noteTextAlignment left +skinparam backgroundColor #White -title Selecting Valid Candidate Paths start -:**INPUT** std::vector input_paths; +if (Check if start point is valid by check if it is covered by neighbour lanes polygon) then (not covered) + #LightPink:Reject path; + stop +else (covered) +endif -partition selectValidPaths { -:**INITIALIZE** std::vector valid_paths; +group check for distance #LightYellow + :Calculate total length and goal related distances; + if (total lane change length considering single lane change > distance from current pose to end of current lanes) then (yes) + #LightPink:Reject path; + stop + else (no) + endif -:idx = 0; + if (goal is in current lanes) then (yes) + if (total lane change length considering multiple lane changes > distance from ego to goal along current lanes) then (yes) + #LightPink:Reject path; + stop + else (no) + endif + else (no) + endif -while (idx < input_paths.size()?) + if (target lanes is empty) then (yes) + #LightPink:Reject path; + stop + else (no) + endif + if (total lane change length considering multiple lane changes > distance from ego to the end of target lanes) then (yes) + #LightPink:Reject path; + stop + else (no) + endif +end group -:path = input_paths.at(idx); -partition hasEnoughDistance { -if(lane_change_total_distance < distance to end of current lanes -&& -lane_change_total_distance < distance to the next intersection -&& -lane_change_total_distance < distance from current pose to the goal -&& -lane_change_total_distance < distance to crosswalk -&& -goal is in route -) then (true) -:path_validity = true; -else (\n false) -:path_validity = false; +group evaluate on Crosswalk #LightCyan +if (regulate_on_crosswalk and not enough length to crosswalk) then (yes) + if (stop time < stop time threshold\n(Related to stuck detection)) then (yes) + #LightPink:Reject path; + stop + else (no) + :Allow lane change in crosswalk; + endif +else (no) endif -} +end group -if(path_validity == true)then (true) - -:valid_paths.push_back(path); +group evaluate on Intersection #LightGreen +if (regulate_on_intersection and not enough length to intersection) then (yes) + if (stop time < stop time threshold\n(Related to stuck detection)) then (yes) + #LightPink:Reject path; + stop + else (no) + :Allow lane change in intersection; + endif +else (no) +endif +end group + +group evaluate on Traffic Light #Lavender +if (regulate_on_traffic_light and not enough length to complete lane change before stop line) then (yes) + #LightPink:Reject path; + stop +elseif (stopped at red traffic light within distance) then (yes) + #LightPink:Reject path; + stop +else (no) +endif +end group -else (\nfalse) +if (ego is not stuck but parked vehicle exists in target lane) then (yes) + #LightPink:Reject path; + stop +else (no) endif -:++idx; -endwhile (false) -:**RETURN** valid_paths; +if (is safe to perform lane change) then (yes) + #Cyan:Return candidate path list; + stop +else (no) + #LightPink:Reject path; +endif -} stop + @enduml ``` @@ -165,6 +298,27 @@ First, we divide the target objects into obstacles in the target lane, obstacles Furthermore, to change lanes behind a vehicle waiting at a traffic light, we skip the safety check for the stopping vehicles near the traffic light. The explanation for parked car detection is written in [documentation for avoidance module](../behavior_path_avoidance_module/README.md). +The detection area for the target lane can be expanded beyond its original boundaries to enable detection of objects that are outside the target lane's limits. + +
+ + + + + +
+
+
Without Lane Expansion
+ Without lane expansion +
+
+
+
With Lane Expansion
+ With lane expansion +
+
+
+ ##### Collision check in prepare phase The ego vehicle may need to secure ample inter-vehicle distance ahead of the target vehicle before attempting a lane change. The flag `enable_collision_check_at_prepare_phase` can be enabled to gain this behavior. The following image illustrates the differences between the `false` and `true` cases. @@ -333,45 +487,38 @@ The last behavior will also occur if the ego vehicle has departed from the curre ### Essential lane change parameters -The following parameters are configurable in `lane_change.param.yaml`. - -| Name | Unit | Type | Description | Default value | -| :------------------------------------------- | ------ | ------- | ---------------------------------------------------------------------------------------------------------------------- | ------------------ | -| `backward_lane_length` | [m] | double | The backward length to check incoming objects in lane change target lane. | 200.0 | -| `prepare_duration` | [m] | double | The preparation time for the ego vehicle to be ready to perform lane change. | 4.0 | -| `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 3.0 | -| `backward_length_buffer_for_blocking_object` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change when there is an object in front | 3.0 | -| `lane_change_finish_judge_buffer` | [m] | double | The additional buffer used to confirm lane change process completion | 3.0 | -| `finish_judge_lateral_threshold` | [m] | double | Lateral distance threshold to confirm lane change process completion | 0.2 | -| `lane_changing_lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 | -| `minimum_lane_changing_velocity` | [m/s] | double | Minimum speed during lane changing process. | 2.78 | -| `prediction_time_resolution` | [s] | double | Time resolution for object's path interpolation and collision check. | 0.5 | -| `longitudinal_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by longitudinal acceleration | 5 | -| `lateral_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 | -| `object_check_min_road_shoulder_width` | [m] | double | Width considered as a road shoulder if the lane does not have a road shoulder | 0.5 | -| `object_shiftable_ratio_threshold` | [-] | double | Vehicles around the center line within this distance ratio will be excluded from parking objects | 0.6 | -| `min_length_for_turn_signal_activation` | [m] | double | Turn signal will be activated if the ego vehicle approaches to this length from minimum lane change length | 10.0 | -| `length_ratio_for_turn_signal_deactivation` | [-] | double | Turn signal will be deactivated if the ego vehicle approaches to this length ratio for lane change finish point | 0.8 | -| `max_longitudinal_acc` | [-] | double | maximum longitudinal acceleration for lane change | 1.0 | -| `min_longitudinal_acc` | [-] | double | maximum longitudinal deceleration for lane change | -1.0 | -| `lateral_acceleration.velocity` | [m/s] | double | Reference velocity for lateral acceleration calculation (look up table) | [0.0, 4.0, 10.0] | -| `lateral_acceleration.min_values` | [m/ss] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.15, 0.15, 0.15] | -| `lateral_acceleration.max_values` | [m/ss] | double | Max lateral acceleration values corresponding to velocity (look up table) | [0.5, 0.5, 0.5] | -| `target_object.car` | [-] | boolean | Include car objects for safety check | true | -| `target_object.truck` | [-] | boolean | Include truck objects for safety check | true | -| `target_object.bus` | [-] | boolean | Include bus objects for safety check | true | -| `target_object.trailer` | [-] | boolean | Include trailer objects for safety check | true | -| `target_object.unknown` | [-] | boolean | Include unknown objects for safety check | true | -| `target_object.bicycle` | [-] | boolean | Include bicycle objects for safety check | true | -| `target_object.motorcycle` | [-] | boolean | Include motorcycle objects for safety check | true | -| `target_object.pedestrian` | [-] | boolean | Include pedestrian objects for safety check | true | +The following parameters are configurable in [lane_change.param.yaml](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml) + +| Name | Unit | Type | Description | Default value | +| :------------------------------------------- | ------ | ------ | ---------------------------------------------------------------------------------------------------------------------- | ------------------ | +| `backward_lane_length` | [m] | double | The backward length to check incoming objects in lane change target lane. | 200.0 | +| `prepare_duration` | [m] | double | The preparation time for the ego vehicle to be ready to perform lane change. | 4.0 | +| `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 3.0 | +| `backward_length_buffer_for_blocking_object` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change when there is an object in front | 3.0 | +| `lane_change_finish_judge_buffer` | [m] | double | The additional buffer used to confirm lane change process completion | 2.0 | +| `finish_judge_lateral_threshold` | [m] | double | Lateral distance threshold to confirm lane change process completion | 0.2 | +| `lane_changing_lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 | +| `minimum_lane_changing_velocity` | [m/s] | double | Minimum speed during lane changing process. | 2.78 | +| `prediction_time_resolution` | [s] | double | Time resolution for object's path interpolation and collision check. | 0.5 | +| `longitudinal_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by longitudinal acceleration | 3 | +| `lateral_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 | +| `object_check_min_road_shoulder_width` | [m] | double | Width considered as a road shoulder if the lane does not have a road shoulder | 0.5 | +| `object_shiftable_ratio_threshold` | [-] | double | Vehicles around the center line within this distance ratio will be excluded from parking objects | 0.6 | +| `min_length_for_turn_signal_activation` | [m] | double | Turn signal will be activated if the ego vehicle approaches to this length from minimum lane change length | 10.0 | +| `length_ratio_for_turn_signal_deactivation` | [-] | double | Turn signal will be deactivated if the ego vehicle approaches to this length ratio for lane change finish point | 0.8 | +| `max_longitudinal_acc` | [-] | double | maximum longitudinal acceleration for lane change | 1.0 | +| `min_longitudinal_acc` | [-] | double | maximum longitudinal deceleration for lane change | -1.0 | +| `lateral_acceleration.velocity` | [m/s] | double | Reference velocity for lateral acceleration calculation (look up table) | [0.0, 4.0, 10.0] | +| `lateral_acceleration.min_values` | [m/ss] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.4, 0.4, 0.4] | +| `lateral_acceleration.max_values` | [m/ss] | double | Max lateral acceleration values corresponding to velocity (look up table) | [0.65, 0.65, 0.65] | ### Lane change regulations -| Name | Unit | Type | Description | Default value | -| :------------------------ | ---- | ------- | ------------------------------------- | ------------- | -| `regulation.crosswalk` | [-] | boolean | Regulate lane change on crosswalks | false | -| `regulation.intersection` | [-] | boolean | Regulate lane change on intersections | false | +| Name | Unit | Type | Description | Default value | +| :------------------------- | ---- | ------- | ---------------------------------------------------------- | ------------- | +| `regulation.crosswalk` | [-] | boolean | Allow lane change in between crosswalks | true | +| `regulation.intersection` | [-] | boolean | Allow lane change in between intersections | true | +| `regulation.traffic_light` | [-] | boolean | Allow lane change to be performed in between traffic light | true | ### Ego vehicle stuck detection @@ -380,9 +527,20 @@ The following parameters are configurable in `lane_change.param.yaml`. | `stuck_detection.velocity` | [m/s] | double | Velocity threshold for ego vehicle stuck detection | 0.1 | | `stuck_detection.stop_time` | [s] | double | Stop time threshold for ego vehicle stuck detection | 3.0 | -### Collision checks during lane change +### Collision checks + +#### Target Objects -The following parameters are configurable in `behavior_path_planner.param.yaml` and `lane_change.param.yaml`. +| Name | Unit | Type | Description | Default value | +| :------------------------- | ---- | ------- | ------------------------------------------- | ------------- | +| `target_object.car` | [-] | boolean | Include car objects for safety check | true | +| `target_object.truck` | [-] | boolean | Include truck objects for safety check | true | +| `target_object.bus` | [-] | boolean | Include bus objects for safety check | true | +| `target_object.trailer` | [-] | boolean | Include trailer objects for safety check | true | +| `target_object.unknown` | [-] | boolean | Include unknown objects for safety check | true | +| `target_object.bicycle` | [-] | boolean | Include bicycle objects for safety check | true | +| `target_object.motorcycle` | [-] | boolean | Include motorcycle objects for safety check | true | +| `target_object.pedestrian` | [-] | boolean | Include pedestrian objects for safety check | true | #### common @@ -391,53 +549,51 @@ The following parameters are configurable in `behavior_path_planner.param.yaml` | `safety_check.lane_expansion.left_offset` | [m] | double | Expand the left boundary of the detection area, allowing objects previously outside on the left to be detected and registered as targets. | 0.0 | | `safety_check.lane_expansion.right_offset` | [m] | double | Expand the right boundary of the detection area, allowing objects previously outside on the right to be detected and registered as targets. | 0.0 | -#### execution - -| Name | Unit | Type | Description | Default value | -| :---------------------------------------------------------------- | ------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | -| `safety_check.execution.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | -| `safety_check.execution.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | -| `safety_check.execution.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | -| `safety_check.execution.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -1.0 | -| `safety_check.execution.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | -| `safety_check.execution.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 2.0 | -| `safety_check.execution.enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | true | -| `safety_check.execution.prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | -| `safety_check.execution.check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module include objects on current lanes. | true | -| `safety_check.execution.check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | true | -| `safety_check.execution.use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | - -##### cancel - -| Name | Unit | Type | Description | Default value | -| :------------------------------------------------------------- | ------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | -| `safety_check.cancel.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 1.5 | -| `safety_check.cancel.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | -| `safety_check.cancel.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.5 | -| `safety_check.cancel.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -2.5 | -| `safety_check.cancel.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | -| `safety_check.cancel.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 2.5 | -| `safety_check.cancel.enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | false | -| `safety_check.cancel.prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.2 | -| `safety_check.cancel.check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module include objects on current lanes. | false | -| `safety_check.cancel.check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | false | -| `safety_check.cancel.use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | false | - -##### stuck - -| Name | Unit | Type | Description | Default value | -| :------------------------------------------------------------ | ------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | -| `safety_check.stuck.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | -| `safety_check.stuck.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | -| `safety_check.stuck.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | -| `safety_check.stuck.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -1.0 | -| `safety_check.stuck.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | -| `safety_check.stuck.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 2.0 | -| `safety_check.stuck.enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | true | -| `safety_check.stuck.prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | -| `safety_check.stuck.check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module include objects on current lanes. | true | -| `safety_check.stuck.check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. | true | -| `safety_check.stuck.use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | +#### Additional parameters + +| Name | Unit | Type | Description | Default value | +| :----------------------------------------- | ----- | ------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | false | +| `prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | +| `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module check objects on current lanes when performing collision assessment. | false | +| `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. when performing collision assessment | false | +| `use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | + +#### safety constraints during lane change path is computed + +| Name | Unit | Type | Description | Default value | +| :----------------------------------------------------------- | ------- | ------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `safety_check.execution.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.execution.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.execution.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | +| `safety_check.execution.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 1.0 | +| `safety_check.execution.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | +| `safety_check.execution.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | +| `safety_check.cancel.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 | + +##### safety constraints to cancel lane change path + +| Name | Unit | Type | Description | Default value | +| :-------------------------------------------------------- | ------- | ------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `safety_check.cancel.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.cancel.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -2.0 | +| `safety_check.cancel.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 1.5 | +| `safety_check.cancel.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 0.8 | +| `safety_check.cancel.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 1.0 | +| `safety_check.cancel.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 2.5 | +| `safety_check.cancel.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.6 | + +##### safety constraints used during lane change path is computed when ego is stuck + +| Name | Unit | Type | Description | Default value | +| :------------------------------------------------------- | ------- | ------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `safety_check.stuck.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.stuck.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -1.0 | +| `safety_check.stuck.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 2.0 | +| `safety_check.stuck.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 1.0 | +| `safety_check.stuck.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | +| `safety_check.stuck.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | +| `safety_check.stuck.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 | (\*1) the value must be negative. diff --git a/planning/behavior_path_lane_change_module/images/lane_change-lane_change_phases.png b/planning/behavior_path_lane_change_module/images/lane_change-lane_change_phases.png index 411a72c30b88a29add6202a6de3916d202bafb7c..efd1df086544dab24323fe247b38d1591119d9dc 100644 GIT binary patch literal 33850 zcmb5W1yojFxAqN4hlHeb2~sy9-Q6kOAfZS%(%mVY0-|(>bazQfNsFX(=eKVE&w1bH zoacOFeBT%j9RqLn-fQi(=Dg-_Uh585QIf_$eU1tP1A`$eBcTQZ^F$8@29^^U5&Q(( z;0F2+tdp9w7)<#X$qoz*1&pkOsJgr1eiqs{jG5bhBh~n38rp^gdD$S9a?1F^U%Iv^ zNsf_uI8CyN>T(J446|~%&e(Zzcln>`DHA*s^@{Ft4u=-nz3aWl(&jllFVfQvKV)ae zI9dGoFuRrIap`s0{DWU7hFsW3e@;!wxH|+xt;u;OaZ&V%j34~J|M^K77i>CA8mHt* z#BH1Dy!T`D9k)QvfBT3`2NoQzUI(( zl<+$q$9X}PC;^^HHt7A=_lQsUYu%Yp;`~U#-Tt|xKLxh&9a;kSJud+m&Rw6eaTxVm zL=^Zqm<@TDtf80jFeuvKPL?RoFy*LVBg$yH>ZUjY{YiBn_*@TuHaaf3%nsfjwnJw1 zouXCyAiA|OyE7$p9F}8=8MaM>^owt!Ji#+RywPd>;BpN0z;hDuImp%B0*87Xa0_*u|mZ()j0$ja=s#lG4ePBS4^6{@ZKDtW0o47km z%?$+I^UniKhw;lrNJp*+=-qA{*`e2s?pzg?zB?TkcD%cCIR8_KGFmS9_;6c+ORpkA z=5^E=Hpgy4wlgnMWnS&}vnKi&tgF_N!5l$V>+2~yTkX-SEkwzSwIHxyo_%1+CayI; z8sk44IG;6wkb52ZkEF7RTa0HjBVm#y%0pV!vps$j6{+Tjr!FSw(_rS?$g{YDF3)n&~B`^VQ~7rE}&%o|gw20oG%g zyw&e#S$I!JIA(CfS$VcHoz%(6z0czHz0YSN23tH%f6ZtaB|SlUD%0q=`K#z_b^@Qv z?q^Q~-Oaq-9~pLSFIRjYTU)NyBdhIJggE=cu&JkU#FyAJ+J&CF3f=D4oOELfBllRQ zv73L^sxX{v^S+fa()8L}|ATi^9)NFz5q}eW)g#xz}->z)nzHb@Zm=KH|+mx|~E3UPlQ9F{W+@_jraj98)AiS3UyzkLX3o59x;iz6nYt6A&1=GUJg$ey)KZBC95{=MIFrGu84T^&1jrw zBWeK4b_~skkJ42sTR_L>_768+4)_!^rr=rJ9e4rN7NgHOZTH#5N`97JkjEMo$R$l% zijQXtZu%pUsW_l3*tT6;5D9sG%lxogBx@4t9!B`o_i(vY&wKDkrHQ!5dN>^w8_5&? zMl$wh!z;J<@Pv=04(qCe)FM?$0`>JDp6ar8JbZqkm_Bg5l>=#5{!ntWy4dF3{L^*O zM(%92^Namjm)zCrlilKy@&wb~h@zZhKYt`5f$a*zR$aj>eb;&OU08VXgY9Qji1Uz= zjn!@vOjRr#cPs|OmT#r{jcVsh^)`Co4Md!1NnMz^KIDprnjNqA$_cFdmx74~A@kk! zuaC-;VP)+PH}Wj)caGP`{p6eR(qz~IOvXiP_m?XW%N+0ebPlp*d=~w}Z^j4O>2p2Pryaf>QWRtL zQ-n|~caTw`Uc#0?o;|;LKam$4K^~UEr@0nMxX&i8(BTd4(q23_TOdzh-rs!KR?_E3 zC}u70*^ z?i(1r`M!@2Lpi#IO@mLJdI{cLp}*9vEwo;!l|AmaBryFpwMRMeK65Ke!S6U$OR^Y6 z#kyeO30)tiE^Df=ZyOG>`%y=?pDo`lhvP4q#;t5mni~`Hbun&%)KA7wgkBv}d|o`; znJQ4s;9`IOgX!GZ)P+QViD-jnnQjphB{I4IVS#1r%qh3sG83(QvN|T! zhjC47e{^JiUiPv&T5Eb7!}K`8LW^$0{_0%1ELr>vM}ZO>o5#kxeTACin!t+7zl zsWy}S44H#5DebT1^A+%FJDZf3!!fO2?85;>{(-!2}@HY@H+=#?At7XtEB_wK7FH+l;r|#jbm1k*`Fn5aInUK#t z-V6}h0?|Wu))~2ZN?F(-yoE`px^N?IM!K{^Fc4BfQEx1L)*1_Wb+n1yRyyhWjTbV4 zlt%645Tt?B1ZG09_czF)Um5FbTZtTMrhEn5k6yBS4bZGdzFfj0KIS*eT1DfY7ey9_ zr$!66PPa{^Ypd+GR0QFU)BrQwa6{nG3@*yIg+Wcx&y;b7jEBwVdw{>sobSW+)(m$` zQ!Wl+TdvJ~bpejrjfqht#9ROJV9EUM>UcM!dz+RIOY&;9f2BW)=oz+NTJ*>4jQGyZ zKooYKE2&q4o~7A#lGdU!ikUpBK9Bd811FManEnBnZ_O%?+-%T(hhy3;#k~}VeTu9c z*6TjX;>(oZv{&9tWw3*8B=u%>Romx?x=m3kx!i80ZP%ZsUgx}wvcZC41XG6v=@mWlQW@sibSd6_BhLr5u#DRQ}QmdRv4l~W+Z*#1GsGRr05 zdf&{hNezUGm_Z~ql%!sjQvVJSSsSQF_dR7kdx)D{7Y@@9R+DV zc%Qahf#~LL{y80{SF>2q-t_Jh!jt>TSUa<-3d*LnC#WkTK38j@*rNXC5beHv;^fKI z#ouSTr@u#Mgjh>9K9QS+QZO7rw%_-A4{t)^wXpGCG3 zRAH=twwfunGTgzd_}<>%hGBNS&RL?rA7v6u?k=V;PQS7C#K|90^-K0pvSwFL+;&tX z6}$E-q42e7FTMmC*#LHAB?K39;w^aRUz;o(Nb?J{^kLikJ?7|w%m=l}GF2l-kG9{O zH|9%44^<}Q;PHR|nsF+|g=PwO%d4u&*+i+AHNh^%c(Je}Os02*Yt&`3W9i&YVDGl# z-QaaGZ|T^Jr=@+8OX^B*7Yo6t3c@ymF}?QO`%zZ#ZtBYrI^C>z-YoZcq%t%pNd0?I z_>Ot&F4E8bZ962o#~oSvIO>e-;@CfUAN7H(!sL`^s8Ej-DI>8e7LJIL$tb9@YZAwc zg4zj}vEFor-~8N*(G)G1wGtOOt#l5NYc9~QmE1K*#adXiQJb`T_pXj~?p5qMxqDb} zPJEU`Jf^^z_J3PoRi{1fa+%CI z3*@cV9k4B!Ee#{c-22@^q1o{wd#>w5re`9GUGI1q4WC)<&sh%mks*JpvK)CJl_34d z6SmL*1>2f#o-0QbMhq;wDt!`3|H=gzMz~CUuqjsrVof7w{nCKWML(ARP8Kq$*B62* zsXo%xja+PAa9QcwPwF-R^3Du*?QwG6y9OQ7uTEQI#Q_AxFs4P>wpU;9J)_v4>1mEP zP}NrwpnB$+ZiT=RyU%sAi+knUY9RME2bDQi@rBG>_tzj;A4dxpS9h}f_kgBr4R*bx zTq1q$#ZM9Ioe%}Q>Ppw%A7fekGn4F0{gQ}FN>lP<6w^ltakg{gL9`+CYJrcX$cPPF z!KI`erd6d(l~}=e#1f6ah1YLO%|^Yg!$m+`^L+E_6)7ll@7PTuE8O;+@XmPL8M5y)BgPghCG+b z{T|SY8lDKHF@asr2F4^HOWjXm%2|=)gA{-7%)dGJy8je-(tf$*mc!0pFA~CXf_^)ghVKgHWu5me_+eAj;;S)4P+A8xTJO4^?*ygw{v-n8BNWo|fZok06XvZ1&? z`u;``Pe;{TzP26OZq0prPs9Eg($_}rYiQ3(xxQmmoOM(;j-Z;ECC^ubsO{P$f(ZZA z=Lg0G6&dwd{#AI!e%sYLn#3rd>B+a{nflBxe0XO6LS9W6kk??$#^B=T3dvSCzfm z6NmF%lh2smcao?m5%n9l!*YER7cqsvaBVkJ*5hoFGuD@mk!v7Tc_B%{RgOQoT|a^e zKzf!q5&|i^`4Okbfo1Vm*d)HK3ij3+5Tclhu~q}64uX;Usyyty6$-9!Wz7nby!kPU z$j?VC`!I*AY6STtY)hHknJgzE)~@2#=6$`pgqmBip=|b& z9v{rmRF%j#t5oMPG>~0-Ss4GD=x`m!m%zI?|Md3h0e>QUXh$czk=Ym35u_?uHmVvV z7n^58)f+-m^A4|=YQ**Z{Dw*?$tc>)&(z*9x_%Rc>_dXxds0-eXs)Ob97rlYb*M>u zy$r#xc%F;rS#|-9SOh#xI1KEbSbW+y=*dl=+wpQE9?Gh_c?#XbHn7K4X`Z}Ub%Dh) zvDL>+Gl1MRa{?jpgXg&L7dBXyWO{mnNX&$9s|r$H&jpxl7+3UFnIvF`CPZS}vi602 z>Lqy75%LpjKe(%n8#i1=s%El1$?;*ZGTQql6x8{?UU=&AfCL;{1399Fd21N`X29HZ z9^J7jiUAi1k-06X>m8yZ&ahv6YZod)R+dyBCZ0(=QO`=&E4usF*1VMDF-}B}U2B#f zEoH0B!`uS!(OW*uU0RWdvpgHNh>J8=&*fo#drXU~#PK#^?lCBU(!D}G^eO2yT4I$1 zCPJi&BdI*?|Nm=QClrqGd^mes7mDG@M(IfL?Z}pmTQ?6pQKP8voHy$O!eYBmDk-2F zhNi5nJ=m`T;o)Tbj%odrHWL9bVFJ*hCMX<9I^59NP zChMZIG@wG0_~zPV!CEOE*`EM|GDq2QW%|!0k#S)A+9^Dya-4GK*n8~I5dk@}h!cT9 zVQqu|UX+OgxC$+}Q!?xECmI~EGN|cZ}j%cE%f_ z6p0)0$zO^@;RiSg+_t(>IJ`^;xRbDas=Epfs2pgq%d^Uf(Eo*fT#;GZ{&mR!z;_@r z%V%5q(Da$H(`h_YtfAKEXfFPC0t&PE;T2*buD`pWx0mU73N8ugk2O1BSG0jvaNg-; z=n4%G*k1y{@M7YAmv(RUN5jE@d$5e}HfZCmKx!(w=mk_ksm{5$X2gLtce^kQlXDEj>SERj>DP&b7(}p zB$f|Wi~vQ))fTMT)6S7(@^aXzK>wYK>(2h#cz88Q@a)9{PWm_${_4++@8s){c!W6g zLiC?}L3%RvhodJtd9+ZiAi``oSuq)6WP6=yMxy<1FiJt{GWq5#J$QCQCm`-up!?$s zBGzVr`&g5~?yM?Di8g^EqJ=YK<7#h4&C+{e@P~1}GSN&Sg!nEN~o@=`_Z>+cH;R{djj8i~jtT%nRjgruO@bjGJ3f z$0vo|0mNZGn$Ec^!0+06vs-fV(`kG#1cR97{g2X!!SA`^1%|C3uoufBm>Iour`(o3 zq{+O`RCStN%hr9*XS9YZO}c-9Ur9Ri!W+%A7)?I`#p56t3Kgha!{=TlGdF1a4`*M~+^ zJQHMKPFJA>G+X(eiy9t^xotMdevsx&S33 zC2bT`i*@hm0HM;L!Zuxhd^mheOckl2sxQ4j5MtJ?jeB3wsyS-1(&lZoY?%R?}NuCQkYp7@zT+uZk^R2(9#8f1Df`JIV+FW&gJ*MaR#+Xv`FEKLqDnG zZqe5vz-O7Tj5qpYQ&1YY~sUn6N8iWYl-E^5qkA`2o*EqzhU_|l`cIg~_gI$UfJD|nF# zkbwkH!h&_&=r&7DE{?~&1dOmjOz9d`=5-Kc9;VKq)G3{!G!9ESkm7!U_ninJn~Z>w zWMobjzndIDI8Y{eGW}XvQhRj;(sq@%KUXDgj#{>mIPXpfBP3asVAp=HX$~_Hw-m5) zdAI`6tG8BduNhj7iv!6ckNWL15aqYv6?}Y-Nf40~Pyi86G#2(y0Rd_7f)`H@OU%76 z#;`sF>3!HogJ#zP2hBeVbs9fVeIsWdZuTIweR0?stR?|NV-lAoaz^$x!*|gUAJP*|~*3>t4f9P_> zH|HQJ(D8s-uU>r^E553$t>8zQp8V7oMd~eyNM^GdilMm1MgZZb&h!AThOUDJgvF}q zV-Qu;=PANOUNNQhRP!*!)-cqUp4B;S%GIsdOc$yWX=;xs+;x1>GW3wNZT`chQ)iU~ zrJE=7mN_WNo~DgPfW0LyX zgDbn9=IssWL1^@Lk_mo5j?mu@xqmxAl4ph!JOWFc4wGhSDuZr-T=ZK_ zn`)~1IPV^u-sXcQc@5hrTP!1bhH95RO%0UzH0Ba5{#a^g8_Wqg_3qB}DXngT0tVcrN4_(D(1QLa2Z9pK9 zWBpVrko-(4vg}QNOi|u*?T}Ea=S`!aTf!_H#T*x(hJ5!s!w%l`nd>LDeA^G0IPl{= z;m>9&I7+16eudx;TmeX(Br|!)AZ}6Nu+hivva7Cf49TuAEqT(#LK4dmL0{=ln+EN` z=*EOw^uJ)-5Zzu6o-2e27qoec6`rE+7(S#@Zq#mgA7eT!C9;tVR1J+WGVI43BXm&- zjsyiDDF^+^T>mEOHqg2mya|G{*6 zO5s)LP{2Sk#mAtLr$gU1vh?PNlL4XqxLgzb2Jpjtx!4u^Zj4=?JK|o>O6M^p3$)v6 zxn!o7mYEJA>As*$Od=F?-i{k8HPN9;-ZZIDvoIZ2G6H2`GPCJ8UJ$|1Z)$!dY*bI6 zGqUFb%8s5zM6X)f&m_V9nKLsNu;E@F4jv&1!Y_A27C>GGJ-BewVJnIahrfd({5v>t zNv8w}FgRJ`Kd$fpsu1Oe;JYH1v zy%cz@5h3)Hm}`OS&$P)xt-`TB5hBeKGyh&69kepS5_jjuBkcDqV!MgiDseYO>!*4a zB4|sm=1(9X&0WG}f?~X1hixZdM$(A{i4E!KHRKID-OhV4Vm%*iC6Enm=c*}#t&}o7 zm5X4A^=a-TpgNfCuh6uFt%6{7qNP_oqV{sl$xx`mwfH`x?LP&-a;F43qlaW??f1~$ z>35**n!H24v6*mGwxiCM0Odn{V#s2aJ(SE`!mfVBPmDq%2SjGxFLyE!{Z~*}AFh`I z9~yE%{v-dZqJdm}VU5V}C)XY!LezQtyXeKA#jnX5xw>S@w5E{f|6hKekNpWATopG8 z5%a#U*fA<{d9g+b-);)sM<9U>pMbY#LJRu6n&TN9cF?lj1iZH;A@QFw95Nj;U|`YC zXwjhMd*la1D^eVl5sfhos0XB)f~CO6+(p3Kc``skB@V(% zh(5)C>3C2>M$vTK&dM}=rw3sO6V!elFlpjf^41uneCqhjx-{Aw+6}e_MOqcviS(*s zM^E!8xc^oP2-gd%KV>>zf_o^ToOpp>ZpQ)TOUYKin+DaiGTDzWUYc-voS5;tAAK6h z=W`mo%4P2+1@Oqpo8*;&vn1B$Cy3+Z*`Qg_Uu9yPL#6amYY8NmjGCY``{^R zd42A_r87Q6Zw3wG@M`)eGwG;t*({iy+b{M*#a6>OmwmPf z93>UFjKtV)bx=S}LQ6ITP_p%fm(7_6UU6U8Ls4td}shf;m^s0Vo{v7 zKed;AAHD0&>_Kb8aY~VUu-<0zGqgkMer)RElf~yUeGUFn>(9*{4@M&>_N_2z)@1p% z3OC>A^py`^O!<(yn|A@ffzU#?QkP&SV{5C<&P>gw} z|IOZnw(UDb;StA;WVgqF@mdS#`yT^^s`*rTOgds{8~+rqMBGTXH2$BkR_}>%l^w~z z@^l67W}dchW9fx)=3E!N3nE(D=WRsFAar%-so~q3vmNT|lg-zr?|%)%pZsZ9`SP+D zHaDbwXETfk^N~fPIB~jE=d}wFV`Us~cN?2oy>s%g4bt|*-))q_)Lv%ldaGWN=G<@Lo&zryyrDl}O+FBo+N!Zu<=i zBQZ*<45+-r4RaO25DlS~cL00;K$xFh5B>|-c!ag7PojYXlcHJCU5?_dpH;Ltqq2Eo zBJquMD@_hl4ATj{(StOS7&NAFr0#q`RZ<`Hqs?v>^?`AwIJ$uGpYWGV!Ow%d-VAC3 zE0khGs|co-<#k|b6lc4r5+HRSspH6?`d6;B%lZ!~ffeT^3brVLEoyCi8;+jONl*Mz zv)R1&ebV68k8);newV@TUVk?p?dd{?kQj1tnO;LNZGm_QdU#7Z%m&p)uy?>9 zb=BeOGvw2IVy{ET5HL0(P>OAw|Ah~-XC078p?JIgHVPf(aTXoWlUH&6y8$5Kw(9eY zX0>sfJ^ZV26A}2DSGOJhPhQq1?7(0A2@^>@G?HF*X9tV%5V}*BgWGbTl*u4$|Hsz- z?a)f-(<0UCtauKC33KQoZlh^po8)BIud|v_ODo$RO0242JnF)a5ruOF(Xj4+G8-No zJ>jv`7sQrIms=yR-*Q&#Uk@jLJP|xdCb7g*Oa2F6ptcTzR-UtmA)(B%gUxJFn|m^+}~=PkDTw# z4&Pm$&XBP#ef4Q{1#5oBV<0d06WT@e8tsyNGE+P-loZVpe?q0|A%7l2B>18BhNxY7 zYKBww2;s17${QbIC~!i?>&;T^(3K2qIShK|w|`oUhuIS3K|FW7u6Bb8K`^~(dl{A5 zQUIDMzZw70YUdhvSw`X)pQOLCWD*+u{XjPWu z*`)LR!5ihR7YhToD@P1)`%gf;N?SnsQe)0jZrmBb?(|!Mv)reFB*Na9BohfcD2KA# z*<6A|57f|5bHmLo$G8Bs`z1*b(K2=D>2W#F{Y?-+18OK7xcA?OsgHFLG9!7#+)dEy zjiE6DUDy#HEV2t|jIiwE_z9HvCd>G%R?3p3&BRg%4xOs*f8t8GZIp9a3byGuKD+Rh zo3jN9l2{>>A04#a+Mah=GpAEHes}IehLgAKwts3U@27>n%460@(L>=*5qHE*lHZ#$ zRw`;O>Lp6ErhTW^en#vqssP+ITDzB5nEjvL<%ZjO=B=CuYDVd=f|UD*`F7jd!BY8 z(+=L)9)a?N5?E*r;EgpZCf?7}#+{7(fSOsRr<8}^zy2~;m(~AO{FBDs4|d~K5#Eg` z4*fSh#^$62K7(vMNrqpvs!V%jq-4=3%|7N4S6gVO7pB08A+N0%G&!r@mgil*-*NNI z9YCzM)J8>iKrjhz)t##ejv^QfC7cR?EW0uCGyrIF((_E2-pQUR!p?p?*(E2#hX$Y{ zL5W*1LkW_g+SDc9{GHn0ox5AgRaub!}x*gW~^VANUEdZdkfJmE|wD z-kB^ubo)J`s;3$Uji55xeQdv#JlDZ^p3}%V1gFw5GdJL z$O$fp5&Uo#hTBTWVWD7_W^!hI_KkiQ7TfLiPs3M_*wpj1Q<>LLSUbZ}8wtqHJRmy> zimCUOQWWN=l8c{dYZv)9bmwBJfvzoUR!Om-Yr0%%tFQJ@)SEH&|LC^1v<}NM>ghUh5)$L8o zcCQ_+b+hju_iI!|sfRH^vH(V9Dbg-V`03M63TPJIY>45}alfNhESZ&TF7Yr0Q7O9{ zM)C~?36Bc1fA4T;zL9$7_52RGe+tcBNUKH@a>z%a*A52@Y~!*QHDd`>=jD0ZCv&i1 z+ar#xLAO2VHCRS5ioKVS>-kZWFFlO*rf-0EE1MBb=$dA9vhz`|P7Vrg`F-v+cxf%i zGS%9=JVam6*V`;tOF~_2yp_JbY9wKT=5Mc0x3mtGB5Zk`HWR!&PUQwq$5X6zY8J?R z`^U1XKb%`#Z}hOsA&>8+bAAj(#KcEt{rV@z_aUCI?)`A~QgeY_yU%2q9=EgsyEboE z|3^vqv@+$xeU^F0--+vr>1xg%?ixoA=U7~!py*(Y07ZxD0dfJ`OKd%6z1ldtwri<_ zomu53sc^p}My;W;EWW|2H~lnj*#gB97i9)bg{DuMD5rvlf;qk@$L?Rs6>O=vw(hvh z%7(^}YKX!&|H;P`P8|IBVlc(Xr$`B?$l54kVZ+wLfp?zA!31V!9OH#i^Y86i)(ZI% z8Ktk>Pf*~758IWW-c^c%#QvHlQpMTB*&I9|@~cov@PNQ_o8!QOk|hcr5N{|&>u^H1 z(mogWrJ983<9!G0yPw~x_Lpj;?`_9gJl@HrMxQtCF8kD=ROvLN-;ozG% z5+-Vd*ESqE>*^Sp;OBk=H`yQX>;?cB)}xcXl5y}~4d4;;N29~gKqdZBQNi=DvOA;H zgaduTgb(cOQqrz}|F$k_m;Sg{eDhY zZ^{newz#fN(#lT@kuuE&X1VN6$5(Ci72UseUF?e{-VA}t@1`bIYLAP?t$kOA$z$Va z+PL?#Wlqxsfl1U}vVtBf4e!l2Ms{RLyGO@N?3{JWw4*6280I z_?Wyl({du0#9ORWl3Z+6p)MjeWkc{Iex?%0D&n?C6nFWdj72f^bv5UU*H zbS5(wI6&6Vk=cSHj|{r><6u;;A)$Z0~mkn~(i$jJaf^o$Aznm~GNvytZB9 zD{|g8_@=az5=~8=&eI&T%V~#apKTiSo~6f5eO#a4 zs8!BB6!iCA@nHng^CKKVQVN=G-NmvWR_r(HpRb7K{*+@qTb%}?63mJzqgVDJ@H>A% z7%$bSiArt3HZ9Sa`ciGujkq(_P~i;PGp~%x-%ZPK*)7nx{q*>H7Qql>0^iCb^=XKz zm^qL6dcP*9MsJqOmT9gV&rYWxt5Mwg&z?*4{=r1Y*gHCM{(~p+w$YjAoi*TwYU0K} zk<{`QF&z3?D0!7`yis^JKCj@#p7MKV9z1!BakI60F{%naC?lf1%J_+(6AjWr(Xiy2 z@rl9RI)4r)eh!WZcvOZ<)K&2wm%a9w8^3vZY(R+SP%|bh+OEIoI}XyK%-^j(!5k<} z<0x30(JE=x3+IX`lNdY}z(K}>jcsQNr|S}V77z``EHaDtRSZsuqGLpJH#4Zq;p#B) zwNf~tKOa)nVR_wqN-Ke1!zs#u&k$TL)#B=L^(Nz67*!Y$Yqc)8s8q-HFPB9swb-E@ zf`&u0tC+ay4o$L3GJ}TP@3u=rG4EBHh_axGV+kDOr?9cTnpCUn;gx)9D$YMj%W)Mx z>t&0BUEv6*MYsWswu383v%_0CzAR8D?b+dq(LvK5OXscaIPVq-ls!*#Ff0JmIRx5k znJLj429{LD%b!lM&VLp(5HZP^hLf2;Y8iQJJSE}z)H9JlD{lsBH^;MW)t$wL3aG0b zucJh_u2=y4&hELid!1Uje&eq!x8-<~?vOz+LXA4dGpDs+0y$tB-vm@Pfx}YC<7Ve; zf!;K~r-^duTsqLu0uNUk)gGr7oCHyeHI~Ze{J-nm4h?4>K}*mas5fBW_VhRzq?=jc zsD9>4&S4QHa6bKdsLyF!Q0p8+X=3!sJm`3+ht73Atn_Xj&Er?Rv|0Dfxmu$fo`?N+ zikDjD`guzQp4s(jro%3^`*A>JV8aPv>1lpBUt#YhVcdl9j24p|3-!)6Hu%D zThjSLfERtYpVlCL$UKc#=4t*>3vtlEK}-vu6NwDXEqR3rx!tO{}ChoDccg3(z;BmZD#?l(x=Y0qgu_hD#upn1hhnf$<_Z z007TP;0#*bsn5~6SgHAIEXP^ScV}M1sgC1q^lB<%2G4!4TNc<^{2FWO4ouqe_aPYO zeP=t>zowM&;u~V^0(XA51A(1iBgxoe)`0RTsO0K#BR@Cu7P{G{J})uyz1Ki#aJO0S37`C;NK9K# zaTDh)CT@YA#vaDQZ;ICSR347)>x$2GHY1iNrtIeiK_1{Xqq2AD52>^2stu#TuJ+ zvqlZRoNCsMeNm)TR2LUI3(M{Jg3TR8C2CVu4}ZYF*F*CeU4qe9?c)Al( zsu7MutFDUL(4z@j!@tIbAJx;?Ua4b1)INt5uf?U!iTz-p=C2Axzu!^7uYL=JpQh8U zlc}V^+n!_}Ev+p*yCl!UX5|7b)oXaMy};|!%>-0DvoDblp$&GiTW+p#&=!+{9x)19 zvx4p03`L>-6;2bU2HgY4;;-~S>=ZEU1<|@gJEpH}7Sx%0r{>9UoBcj@2r=Piikypp zwGd3FVuMAL3wE86q0hB>owFT?q0p|j1$}*-tk?vaS=&(JOX^0aEhUb@ZL1&vq*U=R zRU2T}ku`8;%k;h`^O@QXd?-kn511PoP*UfW(8QGFSE0r3<*5vP4_d{OV0VNm<_=i5 z^1e?Nuz$R_n#|&JO9r592!Klj&&JBn_6uh_YHO47e~hAcGDWL4pUb&|GhM5QVA{Fq zrEdIS_UI+k?j4gD_^JJWfrf=#6k~+YCqH-z)Cf}wPZtoxO2(FbZf!KyNn9{hib>)2 z3sMZ#@_L8Z#m@XE|7<_G%{t=fSpq2ZGpJ3|Eb8M}MQ4Q7af4C=Y$lj>t#eDEj$@6@ z?mWrJV)j4aoX~5rV~}k$dpX!~^oZuenPo8rj{Jtwb29}a?41vn4N$&quB?e!W(z*5cC5Ka<^V1HT0wthN2ha=O zq&w*@0SCw4CW`G-G2rD=vHr)))!|;{;*rE)bvmD6*Gfx}0?CoUJ#fa*GvQbm;a*WV zRpa2N7P#to!v6lZ!aMi#nG+xz7kN2HtF$M-Rm^f$H%kWw-Kx-ixT^d@uANC_eQ(`@ zo5bt{m$51H8!31{Y}9csm1uAG!vtcd<&YHSq0t*ZLSy6_Lqs0`7eU#86>dZP6Q8ge zTJNmm|5Zo3OZ=N1>>Mz4H+tFbu!{-fLXqkYgZnLW?M92=s;qy0Qzd&YpuMoNePzraOYHQjyt38!u!QZ5u4!hR#yGG@%!WhZmEA!6eplYoSK zq*+KQN0YpS#1hk460k5i{T_>M8C;mJ{piGHxccLNN=-!Fe@RV^H~$FDF$HTK&bZDY zhL_+rzp;;Q9`18sx>I-`%_WZcQEML!h?@owFFcMT8BPy~ba6@G4Ex(x<2Dq2QW*!$ zrSn_HoHcKeX=Zr!f}hYh8hW%EZ$ljbRd)9&Re1gdh33QSqF;z8x|lWj*W6FoR}dcPM7R0oUc&{ye*V2h6!` zDb(qbN??>YrNlo1dEL8EWxr>A6tk0jzvaH;qdsTqC=`vMBj5T72eP*LT#MB zE-ED_hLBCn>PKl>RPLN53^F|B140KzZgv2hX$h#?b`iSW(N00pHb7*ViS2-HSkCpY z!tJ~nxUb|Mfl|rPtyjN|SDQ~}(a8&<2oTyYef>2iij-R^oVFRmvsNXKY#6)3c3LLe z`+&FEAk$f(H~CG_K7jDb6x*1@e2ia$393yW!)u-)hX2ar8(yPTqYmax{KH!?(tKmhHYg21=!knA1Nxt*Wk1zxJ(*SA>15n{4^DMqQbQ2h)RFZI9nroyncN}I7 zP?(*1(AE(#pMUhFRo+qT?~JCz`VH{NGcj9$ zNAQc!bFEec?{8#hZI`H6v>P1@el8S!go-)Gt-<`Z)}}gn0{_BE8*m(weRD<&Dp1}9 zDHY#^ZAK|pG%N8r@6($PC)e5ZNt64~f231PfO6w3y)Ozx9y^;U1>gW){cVKcS}%d2 ziac?NdQo0a#>YP6%^01m&V^7HVJCag$1OhX4k_R*qao2^hq93>h;diimnE)3coE>et6t5WI(Wjgrsc z08sVDtWnbIO0!B};8QEruKJi+>oJUf4SH3-Iv(z29aayPnl;)7vU^#yB)FK3mRrb-1 zLc|hi=L&~45aw`Y@3Cg-5R1`{;8PFa4|T-q1Dp)WTW&t(8+H8{ruGcl(JsHWDfq$L!nXDrrh+}GPq zNredARc^2mmXc7LA<@LKgMRvwXhn_Di-UVqc~J~6Sz_h4o!tZO2A+TFpofm#NX87| zKnDzhWqWo`qxPcyDJdV#`R;W1e)ETaNa^S+dDPd6_(^x)e-5B~uo2*5`?I#5#_&(u zgHx07y+B{aknoaVjvH?hQu0&yCt?HE4dkwQ=-g=mhsi;#Sw%lZBulFTRxhgxt~mD{ znP&^X>wfC*%Zq{I?N6XsjzWXocJe|<>Z_K$+v7*S<2U~BBmgc&mB`S6Qzq|lyhQ+$y83?H&q0M$^N%kR^ja?tO2$b*)WA>n4VIh094n>8= zxk)e8S8sr+wV1vS7;a~7zs!|li(FqjZVt(gF4Pr(l5f|tfjBT}QDUAP#a$Y-)Z9up zqT!DbCOCEKzgRcsmK%qeKEL7}!4ShJ1E&W~`moX)IUa)hX8M$-39HPRC}Yt%{x)5u zZP!_8R^`DvA9WxOnpM%M=+R=({XX2cH$ouSz2U6~C>rlO@|5LUPO||li(WMc><1;%gYTa4+53x{pwpQSOy0htsl6I|Aau^Az z@`JmGuvD8wt%1c?5hSuAAIaR!*xL>pMxw``FNPlWp>>2jlWczm)O`SvwKZv=!9oV} zb-&f8jz4phza20K)fQ3DIT^}pz{x=-XpK6IcuYRjPYpV~2G*S~K-92)yfJYFeh&A+ zf7xx~E#my*K||pA4!*op0sG=6_XI*`o%t}n1}-(|1MYffVZC-Im<0@8;|H1;8nfYx zkpyw~xIaZSJyjh3a_IM~lr(&J$7YVrT*Hf!&er8s>0y z{k8$8?Nziu{PDO8AZM(?oU+_@8GS0IGm~Gr-wrHz!_Ke0~`sU@J(>-Rhu&e$9mA%l~x5ucxaP;Twp5 zj$(A0zx<;+qwF6!+&pPyO$WT%i5{oFi)e$d8jV1(2WRL#05$&Ac6;!VF56u!E1;c} z&sk=7wt~FKEEP9!u80oIf`h-PpY6eAXhK=m5P|4t(Rl zXhN5EZZOjGJ<>{LIWO;R^0?xCPCYfYgEFaoUIF)g1;{VkN*c4ecz^epivmcRO50 z8IPpLgvk5PdTOTX49hc{>dqc@wODCo(CU*aD0u*8F-zA#=2128}pB`i= zLHoc}I=t)!R5eF5R~#m;@2l z679{yYM}!3=3ptQg=9a;`MZ<~{_&OlyG1P$Tgts0 zR!nDtSYmh%uaiZO@|6M5Y|6!k$R;5Lp-|5|sH(q4j*@`v@cW9YG#Pqm#^XOHA&Q*= zFAohOrF2GWV93lott1D@FYv|mFE9!tsqjO*2oWs=T5OQMJ+zasuN@3=pH~fBiTr=L z(yO68Hy2)Jg2SZkE+OXqEiscQz@-Yk4L|_+2sOnp1cRKV`Oss?vVY&zp1-mbyb?<$ zsGHUQn;EuG*v`YL_9F_7q_xdTo5Am~tP-gb{l@AWOdHS&*%f|xFnfxOxN62gu5R^V zzp8&*+HkzZ*PF24{qe-9|6uDd)2=Pf!S|kiSZ*t>wXx>K{k3dl`JN`J!nPCZVm!6l zS;max&AYF%Gr6$?O*suOrj@0}>D=o(*+s+XkF2K)G6SuGu{1G=xe|c` ztdJoT%Mh4*T$ad$jC7hS6n)$B$jh!LD){n%eJugED(S3{qytvr@prHDEu6coy&TQz zbKrC;&qX(o_R%%m)<~8&f(J(~;sLFeE)NIrXds4^e>$5bF|_~j_G~Ag-LzCcwMj4Z z7~-LqLFPv1%CxL1qqng+Fw3aAJ9P8pA0ap$xq^ zWB31ZapKK$&n6si>6Aqs7Tn(dr@b$arm}6{MrM_5CSjX0&mmLhAydda6Ooyc9TGBA zhKwb1$!wcKlzA>m*cxO=3K_~&rtiEx&-L`>|C=oD$3t)D3EwjxTTQiY&bmR}Ey#;c{r{$X#1@5tc^797Z&k@$UOp4`#-c+#OLtO{MU_+TC4C(zbO;{649){WJP5* zAI;+w^qljv{d1Qe>@}=d_1_-pHYzn?eqQ`R*7jwhfTe5xvDT{i-De&%b+<(4ay^~o z+nr&%7Cxp|C->KOJ@9BDS&0$w=!rWSud+BJ=+o%}*_(AOEHkNYEiaXV%*3e#olaTs zhWLO@pl(er^{!^q4(Nw`6*DL@BcvfK2v(0Kq}h~Ht)XQgM%&$2hu573bb3GF$L@YMMBT$g#~rNC#j z%5SFK-FuCyi+=0s42unts^6{ONa^@S9u=570VN%dpqIh3euYC$dlCaI`DYPH&9ft% z^=}F|YT3dTY8(Ap>z9IiY7HWmPu0xCx300rM;;pV8%P_ACQOY+GVn}5r4>mzXTdi5 zt&&cfXJ}{PjNVonDdbeuo^sEe{%efextCK22@u7fy){!z?2h_%=Y~4e{Fm)p&rM;E zA4s+{P@03BW1OHs(Hp;rUq$x;2hR6TErSTVW*CU-M=L>uPv4=K3xxt4cx<*WRIjs) zfs=Do(vV-mJ^*TeH+oLO2*(1g$hUK}(SlM#kq^LSQdsD4Qp+k(-q)?nw zu>KnnPc~%mWdCnwDgTKb{0KeWE!Vv9wnN|O-Bw8DhHcDo$f5V4Wu6C~D8UT3HtZvQ zCiSU4P%T)rel*gtS`hDoTgl`p0%}Ds1;-d{OGZDCb5veQLJQqUxKmAK{h9dcm3XJb z>*-?`Dy+X_a&$_1sOnq%Wt(zsY95OVodi_;?a{5IwC~Yd$R>nZ9dw zb}n~Ucd}3cR@@eb`-kga1N=&CIg^k;2?iK1n=yqC)08{-{cXqTNb>%$yNUyfnu!A? zO~3j~XwH1tqE;J+G_A372W-(=52gBVwbytaJLW?$XNQ;l?H3<%)G3YLQI_9D45W~f z>GEW4FDi}$ITkRd3*M!(;UCu- z48{080r()U-gWGs!i!u(Q6=XBV0%5eNfJF4@<|qS8bT?to7X_|*M7S=+fUn(1t&jP zv0l)f&O!qx2_J6wP2JT?a>bE9&0{K%gF2&#!?epi7)Lt)m@4x^P}=-Jxf}bITmI?2 z&oB*G#SjLk+BY>$uSyRR=Oc>eUkmx$9aK#dJ!FD=8Cp}#tjGgl)b8KpyJDpx#ojiis7}0zT40KU%nUTrrU-5R9Y1OPgfFa9j*F68uKu&=`uR~qL|9=S)w z2~;KpZZ7g|t*2AnW0KJL?FuqPzm=v1ey_C|6EmB~%YfIPH?I`yX3h4wR8xh7vmvEz zTUubroAZHl)sLmuNj|ID8yC|H5+>NQgtZigsR&GsN6UXh9^IgNTCyMI$inHCRwV_CYax{;iHk8d7_P z-16ft>h$~S(g{Q(VdVNK_RqJrA6Z{}C5g~gH+`zg!1WJTTY^p z+f5cRoqberQFud zaVu>+6n6k{tKs0q%QsYPXV7RSohea z(E4klF&?k8Tyjbdrt(!u>H`*_)SZfmS)IcQGL&a_+{Q{DZ3yi%*ahd;oPos@@6`Q9 zv4*n`Ju}1VsA=ZkVI<{bfF5|0jRV^_Gi?|jXI!;IsYnbXDPzJ!v%kCZ#X8XgpkQ!$ zPqk>P^{hM_b)*RP5q=OdOn#327zy!H)5o=_5jR4V@$*5tHxn z9+;eh=G96zY@m6r4gS>q9DFFxK0X1$XxNbG#YoP-DWKTac;@vzwkaH%dctJ|DpOP%<5w55l` z?+jZNa%OA<%7R_6>JDSuTlG)kbA;H)`2_Qjr_6gX+<~a`S+72=U`DQWrx+wqh=I}5 zibIpV#}x>D{NhMzl2KKtG}LFynBKUGq2<@h?>jcbmrXqe6I`xr)4n*Z)PIHMRE^c2 zQ_%|cG498=#kE-s_?8XX!o>C7W>07J8rSwcT_b!IS~84J ztlMvf8ZC43XqA(gwnNz2I2p4Md?-GDxw^f=aYUHheGyioBC z$M0xXTZiXfAah9v)wBkg&fXq4AC@@Z%aRmoD2SW^%G_AZ1svH8?2!0egfDgjHOSz(((73hF9j)hkZLD$i#i7+s<-eK+O6Rwur}8e^`D+Bt1BPtC{+HpQXwh4Y<_# zJ9!%gk=4eNV`43pbXbxjmGddj($gir{cJOXF0`d&ACM|A2vx+Wpw^6;QhGqO(6{6blM*A!33Hvdhx&=A7wc(0h|rr zcY}Dc{zu_ZPy7qkSUaB6BzDr>+;5gX-8nHBN^K} zrMD84PR}ePbkUPL)qx6QD)^V)Ra|vGe|9KIz_NdMXq*>DRFmoiDTT3=+PoaCQRwst zk$8cf+iAGt_hibk3Z}fq`1t_~j{-^+Ec>Ru5is%I2=jOayKEKfB6b<2^U9!zv-v7E zauHKaMR1I}1sg!tGAjl{m8oPLMihZCh>0e-1usOfE&t)IT`ySp1x9DQGqK01OC=m{ za;1|Oh&z|#RPZSU#kwRT3h2yL$Uo=jX#!`*#DT_X0nOo~H(4(y>mC3A9; zIhDR6Wxeq=BbE7Mq`tqYKu+J=Prn>GiQX)CNE5c$T9VEHh5ca`0%10EGRq5aKVzS5 z+9nKb8Qzq6gj29Wv3j?xNAceaon^dxO47*U)N+6O*F6}d<(?Nj#{6A5Y=Yd+f!s|L z)G#Y4-%?n^&Og8|5hh5~0|p)JfBYPIY7%f&kj5E7_wvw=7lwx(4FGMt|&>!bGaiRlXm%Ya4k<2>NpCCw^ z825-ZZ#;jIv1}b+J7s6uJF9cIB4yUsffH{eQjnp>rr!f)=|8Xgomc%aQ1iYTEX(1; zk|9%?)o0oH&*4>F|A8lkFDQQ)Aa+^?1q_w!yo^*hs;XQ)b;7 z1P}1oq%cAeS)pb+6zz;iY07Z$_~a1yk+?*$b$AeUn`X8SH+?u0nzD!qpzorqxoF-K zbL$Gm`#!zBsoY~+jdonG40l`fiDJT=FFuoD>gx=yIc}<4t7Pm^ycSGls>9pRv3T>f z96LdulY^HWwG}E0LZ7f6IC(lfql(3?qoWYCwS%X7W6UQ@pll7ErC98 zZt(*|ix*--Cv+&Xe)xS6{=g&gFKI-B8=8nb^a&Mw@m1D*g)`JzY2OGaYz&TBh@>Y5 zY%hY+DT61d7Rj-km&j2@KKz0MM#ZivzUN71=)`W5WAUJN)QT-$!tIrxPTpIPUqw_p zaCNOVGYHgX1Oi6PRY?U?6y92xQb3XBL5PJP3t!*9&B@cCQ-MeGkAx^)fN_!x@mbE) zfm{CiCn`NlPf0{5ThQv#nPw#|imH1?se{KoZN(FAONFibOu$u|?xnJT@l8^w1zg1; zUD5UKA!#N@b3r77gzY%wNfh0)F~&cUgE>(s=nOJ^oTO_GoutxlV(?IJ=4W{Zhf6(z zOPR%Oxw)d1FxW-_CPa~1056QJaK6bnrN#pTBuE_@}>vJat z=A(Enky-6of$@QHrS)W{drDLcOez20Q%d>)=JZqlcP0&V8uy%p3YCpL4CtO*f{@3$ zh{vzZPDwrNJc-DN2HX|3k5VYxi<8sq#?;kXZAG_ih648!m2k6mxUbBsmIxo%1JWB{ zq2j#0qPGIJHvRL1QwS{=Jx{nZ^U#msO(=>=)YHx^u!AC~^b==1n3WfabHdhaLFa;n0c zmqk6+hvR>F+Xs7oU;3!}vm}ZU8y-ZhfM~-0 z!Dp2LC*sFYPk#%fR)33`1@JTG^=)wKr=F~JN!)`#>}|;<9>i>U9&wK0$qhDwlqMIr z@YK=@SsDWf=RiD35MKDtudf939-K`s&I!~8hn|hbIZeBlSVsZQ4@i6lXJ8tr&@Mrq zS73L0H3N9J0zq%?u_}}<=Zam9+5_JJqk1=!n-B&SUH|@earJUfg5eD$GyGa%+uDEG zCg4-r*Bi6q9ir+%uhU>IQVCP`XPC90W}hYF(rVjiwfU|$Smpe+lm4(Ja}{b?2o3hg zEpuobTy%=S^cu0%y#Sur&Vbb40<{&$+rz2nnpR)zegSvsONZWLrD?Rn*5;K>Ur)(E zNTB;rN{GY9wA?&jjq$*?!cr1(qn6*oUDn1a<0*H+vtDrQO>DhV*ll{H;RK_oQZ?6l znwf1fuwn-gUC!62(tAkBDrmLU%zgrKSXK%n`1!3ck^kY#!-F7;f3RVDj@YoGBBWj5 z1Iy(|-)$P+o>B}%%A`;`Qq20y5(9nReL`IhdpB-XfrRV+s>ZTiK`(S)g+vM++!Xt4 zj)iGH?1Omp3q(_~*0LyOP%|X~9JfKcKDn4H{7}j>&M6-K7J}{K8Vgt8RhC`{pc`8O zYEx}M-)WhnK^Q7@Yn~ z<0iK?Z}-))Q=}^d-9S|2)V7eZOWaccYn!XO1-Ke&L(Fkxk?v%MGO)ck-=jKu0p6Vr zNTk;EGVDGVCwP*RBN-H6AJE=U;v~fPoQk+mYEz~sLpur z+5<8QtG!>2FZ#aZp?koh81a89J;eqDB~fBREwJq!t7(Hxw`4xDFA%`{v>ENoP_3JD zccqQ}RhB0#ff84w)H9!9Ck!YvCxK1TwweS~nzoDT-6&V=96)2aSKM?q=*v)sZ15b- z5(3oKhk?%;efwZ?iw%g!na2?o@ zi8nX*%i*#o$G5RQw%bDAZ+mG-yObrC6niwt@zmd*Hb=YNK}jHvGkmcRLl>=q0yoc=PXZM`A?GARIFpQ!?gC zU}2m8P-s<$Q?Uqm-k=^YMEgZaCSZB6V>rV$umsow+9o<`*aQUUId7mD4bg;yZ0y2? z%o0`?PEago|84CNPx<-Xa0-2r5{4{-dnwIA<2W4^d!IqJ>MG3#(G{Uh)~D5HUv>qN zK0%DkO*T~T_;jYIkUqGiFT-uHQh*~*m6KsY&c<_Dp?2qkzstez3xw#Ff^IYO8e67h zRg*5Y_g7?6`mWv^4m+gw)a$KCm-)o1y>Wf`wQ2)d8U@yjBIr@I6QzhC2<)CI)V7y} z@iw$@yz)Id*42@GGGR_>I=B9WX8S8^-1_+D8`_2hND+EN6bm{#~sp2&Prm@2N~9rmKPQ=HJRV3l}e zoZ3v_aVuw?T;N5LA{C{$ax9%98hG`1BlE(%4c5d1D@UI?3!i#&Gh!=AsgbN}Fgza} zeLv%O)WdIwS1w|mr_z9+@L!)+3w?pGK%Fsa+D~makFQ}_LT8H!kj2Mv;W4(!B7_biJzuQYiLGpF{m%{kUqx004*J6mDLX~$HE_9HqxOWEMB|en z)A3ihwI=!Zlu{zjqLxqjsH)hk-YN^q;Y(P1rZ_(kNSdd$r!RRLA=H3 zGGdG@1FZ-=#bBEJo@+1_;Yw}#dw2RCoV}VtZ3$u{aj!q|^g`5o(un(`XRU19i{|>EwTF!#rvIlUvX}($1=cUdmqVe8Ul)L)G&RFAFxX3LexzG@C4+wHkyCNn z?^7~Oc+BcpI{O7bH)K!1BiLJ;_lI9Vh0E0a(lr?ld~Pd!|a{kQXIZ_OWaK;UP$Mg_w!5=d!=2nQj&k-QPr=jPCFU*1=M z6CZa5*T+h4SEi#QR;6vAGfLnXmIj%8(FCQyb#I`kA`;2|WX@E!!TAKKC49R-Nc9t7qz=@nC_x39Z8-~=Rv`@M_MxFd7aC=N z6;om9>G3L18r|OaA5%n>uvPbZ8z1Xrq(dss7+$1;gNDn!C%@ycg~8CI1IX}VCa+lr zS+gd8e%^#_QZaYL5t)c;bwED!!mO~SP-ueh-HI*uOM%nGUrQ&HXE0B>+lV;Tg43SW$DksoQSewL8T4xFCu!vV@Q)7`G>2rN{_7C)IcAC<`X+M^DT02XP%^+%${r8+uG z=+Nd70G3}&LPz;3D?mXWGqdfmBJeqqo*sEIrZTDkoqZw|PbGHe+t4_K*+sC|z*a$@ zMh5Y2)`0#aXl|tK@d-0`*ALkDq^^S}SQQ3B(s{CNu=eF*u=WWnw|b`k`xcW8 zg2{5kD;cE02QOPC!p7YK4|i0b5bH$|52Qt;rcgU;>1a8{43u)!CcL^p@5r>2PFxo^ zV8E9~ta3Hq-IY7CW+*KwmCvs*Z1dK*?8N$1z`5N|3$3fqKmYpVzCZD~Drjpm==N5~ z_T=YZ$9YO{9rao*V$dbXUs-KjnN-xgFG=ed(}`pus&R3y2_^9pT~T6J23yBqkfyS+ zh+vP)9?TyHNf|_7Y4mXtWYJn_ElfQR@J9TUX&D&YPeTicuJyrhydH84PH^@L@L?ghblNBtVLz5CIsh1RM`nrHbaB#F=t zrTlE*`|}E1^dwcx`vZph_2z0?z6R?|?yaM3PLOnM#vMP=1U8=RGpPD~5w|&i2LL!t zqB_e*Fw7kC)Dr}(Wssgdr-ydiwR_jI)B#74pF=uM^XTPAw?$VG$(uq}+vkDOyRDZ` z?@mM_E22XX`xkar4yClCz?5slUU)X_>5ton%vBV~Y(`o*vK?)B;dpE>=-12<40V;j z@WWw&lq~~205yu*uJcD}VIutV!9vqm#QJZPu%O{k-LpklP(MzH;Y#eSBdkY35WHjA zcG(1OsF+O6^DzEB#>N~_nD7ww?ol8>Pq?#IAKF_A1EEjzkAXP%-!~AU-w(Dy2BQs@ zW?w+lo(@KGOo{L!tr(RUaU<*@t6iS$f^5}apD^3+jP7QKSSbVlpv0MN+YV^q4tQO7Xqv#MZ$r= z!$RCZZavMo7F0Dj`gai!t#pr?cd1k3o}>LUIL1OmYT@%cV-BPgqS!T;?Nq;?RH zQvVrO;h3uWLJ!SzvXMiq+Y~M~UpK0M zA4#?x9)K@)pF=duli5<83}H9?hk#D%u8wLPzJR`fC18~g{Dr(PpLJb&uD3kdUfBE! zr^iqhmKec6=hV@YoeUiAKfm-`rbq9_H`;tE}mt&{q(_oPM zl}T8NK-%y2?M=Sh$j^ax5;j37pQj_#DrkJg5+DU?n$)cj580{XA|z9`YP=1N$6;-0 zp@+%3f_4HqD7>#20%pjSFGhJ_Xsz1MIWO|R#F4-60pb-ObVW>q|65%0s&&f1>!L4D z@hJ-eyP&c3E_q^P`u%E3@gr-9Aq z0I=-8BuKnQ?QKKeZ;Vc?+);L_`u+SZYM@HaE&?_|hspCy-`?qo6YL_=%@k$-@$BjE zC}C3%A-fmW2m&H0gB*EZB!lf!F-FLeR<%I)wNtrb9yrmP&@^ivUV>D}ZV!UnM)8U= zFX@wLtJCFYNdq-?dw^-i%V+Dq!1?|6d&;_a z=><-W1cM0`+J_-e$Y-~oQ=No_KGNt;W;*oPyD_pB)VIX-LPWwm@fK(UoSLV7BMx?9 z)+$ymox}9dTL*xvAZfXaPiqJM1~4mx=QSDul{o{x^Qh-KeQii=fX;tSuV{AGQE$}7 z+?*FyeT6){Ko4T@mRe!sc@TlOX=rqpeNx_uBVYN&epDO6qcNL__s{kmapph27lb!1 z7_kS#Sp;eb?j;vct^To6D~Ok#!pzC#W*y?uEIo7xe>ukC$@Tw0bRN)GZUPaFQmGB(y!P`NW^#_GB zimvURC%u%;(S8Ddk(#TcXXY``#`NkkZTOT3m>(cazRjeUo*$$TW2ldTOBD~omSJ_L zmsK`vs{>U}?`%UM0Ej-hmMt6_Y@B>2m$QHBSq-KN!UT^Ws-wZCBTajZRy@- zur>oPTW3PEGD^iggWqU(D~}=i_gxsfpdXUTQH^|;p13{&a(^F`gz70#4(Fy}!WY7i zi9|5%u;)AhQxBvE!P1QM7-PyS)iczmB6cnfXIVLTV#GpF0=$#dHcw_bw<0OVf50BO z@puq$j=zw@BV~`)-(MfTZSb_RamN^j`h%D?U@<3bGZ2!WOWqFPEdM9G2!tu83L`&b zGtifz1?&U+LSSJ3nWb0?gw$^hRQ8G`bDzxVl~I|Ba{%Ivh-bKu)O>;nQP~O*4Zo3F z2~@e8qYzXY^D_f?XB-yz<`0Q-9bQ1uwbP${Lc?(#4y@rM>8!MkbnPAC*WZ9-=}l+r z%M;e00iGKDP+6PBi>7_^G&;QVbh$GMgR(+NoNLQ(qrMI=@c@igUOMx`kTVpsy1SYT@ZD6Fqz zwO?Sm8GJ~-%Xb~Di1+sz2Y0RDSD)<^kEh7i&o!}4kM!5Rm? z2$wy#dJDa63ufH4+;`8mdfYy_yA{0MN)GR4h&Qrr#axg7jv4ig-VBFLh5U7#*%2nW zPbfb~Z~fN((|hpcWhF4M=WbJ0cocptZIC<1JVC*A=B~s^jq1ESCC2F!QjSLG2GnuN z_;fSWL;M%h!S4(;OVYR-l!B*M4+zANH*^SVu6v zB{=E5#~z57A4iY1ZcjZ=#fAGs?s8byi`oHqBf8-bUf&X*2%Pp=;<{v4))tw#XJ2W! z&-(03r>v|pFEM*nPMtp%pt3B9S-&(Mi_z^S89)BET2(hPnU+{A(nndNeG0Grq;wZL z*6!_$x9rsQ_x3CjkfFWOf`J1aPAN^a)RjSzX4IXI%!a7 zeh~@pc$H2Uz2lRXW85pV3|1&TADJ$EMU(ZDKVwf~uqB`O9VzhtNbT#=cd=dc$WQdS zn?Pp;CE(I#%|D8G6eENu*Sp3qT~v7NW$Kf-K|ZzE>4p;7lvAU%#vhT2IHkrRsEPH8 zXsmK+4R@w`3~sA#{u^DU1!5RSfhqaC+$=5EBsb5-od8nnRF62p#D}pvq3Vkj&!&vx z-NEWumZ92*Q=ev*oZh~LFtnTECDp~ytSO1H%`ED=gw8w1Se|7BSYX_dQq%UMYHBx&uWNz2o zV9-_Lahv6YSZBrz3}XH@Qu#c+=6JawN#S@0{`g6*-cTT-qr?d~x-sxXrt9lQgu|S| zWM1A{#^HBdTL{+iXYk9ItQmd1&DoNT(cr){lzw#3Jd6=))N}~0?n8QK(y*iR@vPVE z=i`N-@@!b?^C|*QJ>^6rbqHX{0er74lxK`U7o)ENHJK7jzDmmqG%~J5cXXqE*Z{2- zw8{*0T|UVXJK?;lQZnz9_sqnxX&$WN$#2j*i$nVYo}=k5juA(J)0A#`R`u!yES;3$ z6vPmrgnkJST**kW%itbWhwrcluYD3GRih@W!9j(+B1T*AhW%Sm3mla*DdsLmSQT;R2ybA5g{+mKgh$*TdoOnP)lZ&TSJpGGc zCrPX(c9t25l~W)&MDEBr$ieagwst1YrA#C`nCnI?p|#p%AT*Jcc3u{R$VrP(cU#d4 zYXXwc{mg67{dptE7nlvB7unCczEQg0?bMukPkMBJW?vl;F!|pIcx~q40?p72Wc;|e z?3)iKV=4d*d?)D#p1RGx)D#4U!f>J{fk1$H7_|cBZkf5jCv%csp>zolA~A7ZCOR6) zco<2qR}4YW3joCmk3$LA_cltmuQWC>IT5P2imvw(?<1O{we=Oy=)3bk+eZN)A-wY* z7<+1{3T)>yprOq``otI-CX-h{0J%sq06W7O$it*DU8OOb!^1n)bwN$pSmMgJ-bQeB zW=F^|WfSmEh)l77a1g!QmwR$6s9=MSb(!}jHV#^*5G9t3#5e-3@rxmUu=MUawibd{ zc52a2hv)_{?k``52Fdj);BeLl^h;+jpa0XoqUPuh^2_jH-s$@!InM3?Wc;RXE~J?^ z5T88Fi#YAUWL*HguVjNe0P{sJ1muOgf-pXt)NSfRq?a>EZ7NLZEB~Ha-3|uy} zEj2&VJ3dA97}_4}U&)1|OFoiHd%oua`D-dX;q7 z+aN?FD4dOidElBp1No9q+0t7NU@_-FDuRUlI;0%P7xOV*5nv`~8h;690%-|`kd^l3 z)FvV6XA~!7O(ER@na&HKq}3*F0GCWYUfws2!r)f+`*pXRfyex8dG$r)0w@mr(N2vR zyq}HaG|Sly>8hU)OqMZ*`@6l#Q$|$qNI$VU_X&L(i=rA2 zd;)5xp+|CNh)M^h{66$F?gJsdGr-pe=64(g%5=Cd-@WAFd|b#IlFCX1P0DQ>)yd4Q zS45CE?C6;$8htP88Q{B*Ayy8H5gRLz^Ba4Ogkhu4=9ta3Ca0h(z@!+`0`eePXDJo) zegklQ&TS@J;bkc2^`(QRb-1$xV0<~u$t)aq*nJ^-r7=HE9a;OCy)|}(hX8@k5SP- zHxsdZ_O&Upv!LVu&R$tqTZTP+f+J6eV?e;`>d hA>;m!pLVi63K=(hN^+Z1XYt^_3+no6l`8h({|oq|a1sCj literal 181969 zcmeFYdHCa0-8VeW4GMz@$|i2$f--Xpw%H>B)3iz2G;NbMP13TNwN2VIP1-CCJ31~X zFe;$3$}$5Cg6y&gqxi7NrmVuSxS;GH4*N1ZC*zGg@AW>{^*n#P*Y*B$Usr#>G$$wL ze9t-GLpA5W5=yN2wL{MarFdTJ}_&u)RK$u z`qa})mf&yAX?5;aem^=%KRF!X2hJ>be75JZnHV;=ew@D;RszUkPGW&Z0K zRDhtp3iw`7Q7XWDz@;Jt{=x9x2#WXr)n6M}lm8kB-Mat=*i$VQ_kbzzjdvzd3a%-E z9fBdt!MD=a_3tU*s82R}tW~e25J3i=M zB=;`t4TGlgF!Vjpi76H!(1aEW=-ycV;Qf`n-?^jNTIl>Qv*nA7t#Iam6>nbud*kL0 zthqM$ua!&OJgg(*ZaiWkq^kD^3-Mnoo-d}>zxtR~>==L$uqiayThq}7q2_^Mod4Rs z?q0pArnPM;8WoU8s5@*F{;NB#!|Et%vIVzKGGlRCW6{j1=%iQ zJ(GoW&TdZnCXJZ$cv7_M5$L35UBL+!VG=c)xHW}}C|+=hu?}crG9_+6 zu_rVe6^q5v_6$yDxYD!;&_9-xumK4MJuel_c@g2t;dEhF^kF$MEE@$}M3o#o4f{A6 zMln0D^^n25?9^w?8e!&7?dHITtdtmaa4?mI0(zN=YhwkrP;Sm5te;s8UKS=|tzYwO ztlb{XsQ#qf6TLvSTA;HlPGNFD3UQGPn@PQuR;#p88x3kUE9z*0w--#Y<_L(`wL8Nq zVYYms0FR)tJg{Bxx=X8ZtLT6SIJ>b8~$83_%5 zCZJ%bix~4Lo)Qr)fP07cGqVu%<8BO%Dim4E?8T^*?~Le92g9;mpZDh7LcDMVuhZs7 z`I#2cF?e2aWbnTR?x&4Wyim=C5;>8ai*f!sCOB#8It`-9EWkv}q>;AALN<3p%q})2 z_BitsVwf{>$f2=4E%VbDHvtP#x?G9Wrfnw3l%&B9F}<=4J48BDz(c;8nWYM97k{yGWS`%7Gz$0*=L)9xWLR9JsNXf<|0m;Y&QhL~w7*yj< zj|Peg5J5UPjgLIu!5}oXYW}1HnmbYtsrCDvI@&=NA#OLSZn@Db_Y#Ldia{Bx>w#e# z)BqkjDnd^uTB#hn2Fzz|LMwLKxojxCDfmx!F`5%PW>R#DP!GbqzD3VEncL|WeFmE} z`6w}m?93s&44qg=Y*QfIPJ+agt8eK`eTV z;`&azg@paVD9mUG9}{B(_sZx3SOBW8E3&X~!$JcROXF-oXj<7IFb14?>~pm)%e&2i z8afT6ti#ZlANagiqDGZQsIZC`f~Ou|B;rXlYB@Lp1{^Dsng@AxFaX<)TP@sgGqT?) zW`nTpOafq@QnB8umIBs|WwlerYzqo8g|kBgup$$6p*G-BstgsBc@yqvL&j54s50Za zdO@e*#$v)VdbiF`2XdKFWtG*Waw7;Ub^tGGHQ(YQc)`{1(9u<*MTbPtgj=YejQo@Z z!;)0Bu*foMJZ%RIBKMI(GNiG&Jje=AC8F3w?X(x8`J_3HqC$C)RvdU-nhIlqCJF=9 zlxKFkOb|3W=NhIdj|!IGYF64f495+l1jv_}Mi&S~+>$V&qZ%QX3=GF6dQw_#>#>O} zAX1*`eI)4DMxeVSdBaX(m#h3dEzGLATTl`nF{X=!M8;ENrfSx3&b9@h%OM3Qb&g~d zLf{$IDx&j>f>>RoS6XyCHqhlvXUt9sFOA)461(gOuE6+Qj-@QuA&MRc22tmtB8dkL z*YhhziFe&b--4=gh6y7-=7+dhN|b)lW~<};2wI9+9FD_wt~GtSMzV}k0IG^gC#c|% zhUjxWs#Ho1na))q$L0EAC{k^;JOd`4Qplnfi)}X|20-OfoD`TgTo>Z z6^qD(L%OxG(#!Qw*z-%erWcE;6-^f|+f@BN$GWZlhy*g^F@nrclMaJ7P&cusvadTZ zhqaJi*UD`#LvgH;6FByxZX~ya;oOCm?#P*O_5@0 zGwqFWRELy>YX+p(PiO4{F`K2DRnK&HI-wC24aT^p`7LiY@8N0_FIu+P85R_?o`Ru9 zYL6c(Ov;6Ey`(9NQ5D8hKXOxsSGoDv^=YP8YIZCr5kY*7S19faz%*L zofu1$SwPx7S1u#E3Fc@Ib(}RYx<8y0FsY-#X?GR@ZO$MCY@(GV!Us5zlKCoCn~917 z`*o>1thBjqY0ix$rby^=kB}XC&gcCq4&OzZv23!IWKeX|3c>{#Yg#tqaM7UuhSc5~uPA+E-hmT$Vbm+IY^;b<$WY zN@A)5V_RrQR$%*p9LAyw6I;PC7ION9c;Jp&2`X14zfadXJ`fTrq9EKzl&+QAmZrs& zs`g|$>o+Q1gaUq69j@Yta!Z;P)Sw`XQ$p`SJRA8qL_`5xp4CKKt8fKc8Q0O&PH_qz zn2Od$@Ok+NcX z5}2dJjOP%YV3ZtTu@orr6dbiEH@R$HnH5=#i;7c(#UQy1%+#2oSJKN%N%v2i6TLA%Ia|00H_li7Ao~3JrNp_GE*C6 zlS&6;UWSCZDB&f(A5~LV10HBO>9^d05QSk?o~WG#>19+Y!ph}EK@MF$^`gJ??6Qg1S6wFMF`a~ZR zXv3j+rozKrcU}Y#E*5AN>KL=!w<2H@8`&j!QDq_^Isq#dQ&c|aw?I8pP%qlSq;=^+afCStA@AvtkF;5zEjEy3{9C?Ny;J0ObapK z^%#cMq8c;}FgR7{7=&+wFOko8c!{Q_i#}&?K@)2GrZ31kV_B+R4iHG3=a7ZcaJ=P( z`VjUCQPY@A`v)YAwL0YDsr!5(;}pi^`(9 zEHSNSW0s1zMZ<*0HcM$ZXWCF;R|2~{HQ8oMXmh?YpY;3r?xVI+NTdeDk|RCSTRpO_ zHAuZa8Zir^4qJ0d(`T|yw}%mqyGoxo6@O6bT3&$7J1AM{*1Dw(DhuOsjcklkDB>W` zZ;cSIMx-b_%R(xkfr=U1CNq3bBwN`Z#wY84ofj&aL!id5lSJ;0-FRd3{)& z*Dw&wC<_Kp`#9R|$W;dCO}8D4xRB*7wVuZ-=rpz`Rc^Sb43wTD)W{i&GaZp@2*cbM zjY=KP@tRyz8>>BiYH`MVk&Sgn*3+hnOy-STC`QS&S#l{U9QA5w(QEi^-&Nhxs33xH z4AqI}N)7IXv?R8ZLT(f&J&Fb)G8fu3iF#BMI3!Tjon~DdvDk`ICwvjZ(&l6y`$D*(HksH%7EDbcaq>i%V0-$)>=>Peltr zY_SUlWR*#;D@X`zvpMQj(@N1R%}}kG`3hz&konA1j8^ECM6;2M8pCoP!?3%fI^|N6 zaWco_Qf5Xhl$*v;EZqekiYp7TskKQF zgwAZMU$LtM+^Bli$O2nI8IH^XcB1Sg5oc=Iu4Ja9>-u;`<^E;6(M?7JxL=+kj5bE` zY89)dV`JLN7!HZcL)D3TC}T)2Iv(cRj_EYzVQL5~)lr2sP#NI9NGY~(v9EU13Effw zWhn>s%yu$n`@Rd}K2|ZxV@tUq64ZW~$W074nj1An(l;YL+DzwdmR1Y3Nnl{ZIyKXR zY1|?QAWoLMfepBAP?H8`CySV_l;mDpZDDd&Tc{j2?1~BqrgX?`F>1CKT}LW4B&P0^ zI(-t8V{%rg12e{Sm=Oe(nohkI=DdsX5zF>VF(#BkKu)=isnUq`3}lj)ODvr5K`ZWsGts8} zqN|MzJRv7KJgLWRxQmy_qyqq{FVK1w9cxy(Cp8MX!J$JOW*oQ$IFRa@Ucv0yjjlV= zI{kiCh`8burv!VxK>1OdqyP-7>Gq6} zaT!5D1s<22YMh5hs#s8mL8qxibzof88Uv&V=MS1?0fn2g)o6}qT8peFPRVpr(@VXv zDfN1Vu3E3OU91suo+b3$mI(!uaxk9*d0{#vUC#N$LU<_5YJN{`L?J)`a0%>KK+~QL zr=_+bc_EgCle!}mI+#|-0T#{$H3A|UAOMu5m5wwtCj>mwqDGCc;<{*8K@@^cxtxEe z2*-)I(;M;a{$PrmnKy{)Ls4F!2{UJ_-8Q!ffKF%H0zE93XsbSE?V>cG6WC=*Pqf7` zS1Wl{+X8+ILIn%Ht;;^+xA7TovreZPS4~DY)x?}ZJ_yAr7GKX?0)}08+An$F)KNi> zo4Q(nWfX)$Vt797^h8dVgLeWV6Fsw4BJWre_5^qoyOP&Zj7ij#?C<)^uqRI_*#il7c;)1#PU^ zXUJluW8pZeQ7~{~y3x!E+49`sd^IdN!U8J#ZdiegI&lBY$sE8MI#NrT2N(PH7=b;- zELFy0V8yzepMR??OVeVrlvRWY_piu3*6L8*<`hyCZB_umlQ0+~*&gCXHct2)dx^d#2aKm>4M;9Pyq%lnqigz6?!1CpvmnT`YL*dW zU?48kk;_98f;0{UoOBDBRO;~zU69iz+R!l|WUw(9j>cta1}wjtA0gImw27Hq5UCX0 zmF0!R%Jqy+DovIy`I(OaqA3@0CV0!Vv{9if4_$+cvfd2O>eX_g5AXp+whPk=1~LG3 zXvv+w<|;D^Lz+mNo-BG(w$|W? zk~fljMwRQ$%bY_Sm+Fzn(Qr^CtAta|O58bGWbPMaVD(`!_xFf*x(#cr5rU6=)su&zQ%W6>J)tDa3xqe`h+ z<27s2^G(hL8ko#8K1{VtwagG}8eX4`O%89*gUJxCR=sYGD|*FdIrrxh;H zXWD?$JDTYAB`PMhE{1xupfm9Cm{pl@T*QWhAT$stc)WScWF=Y)Wr zl>|x!0b|rs#VL6(RGn7zo(5sE6fc>A zjq%k&6Gsd;PI6x8^`&uj(wSSXpz2a)%>%XMWLjM&9jd!vLC|{^a*9xjA*6sBQ>ols zjF=kBXrs)lI2_JVbt`R5<%O1NS$~EU5u@dElI_(+tidonlCZc6$Pg+Wg=b8u(23?f zzc}%1faw|EWy)SD#buhNfZ?KCgPfA7)p6WTv&`8kRL^pt(NcsCH=WA49})tsoQ1`H z)hV(Xav>)0ac~js()M|6i8E65jpPM+UF7=v)kRP^vHD(%UAuQQo z49ccdUdVh$oyBf7@7U{uFz$So5mrCfi#5}2)%z8<#k;vzQHT=Jc4fEUYxaibs5MPn z?cUf0c?B+j=jmn_epqS>IauaQ1BMx-PPkQQ=9O6tcHG!3hmPgd<38bZ31n(ZS-VLa zJc^EKqSk650s}cs-R%v~2G<#?8ttdSwAIS>FVpICrBQi=4hw1lH_;9-Bur%_6uE2! za$LlGPPl?ROdVMiE7&~k)yDLw*UuU%MvTf@tx3TB{;U!+M6K?_49E^pViPamlafgQ zmvUC~Pzsv$5}N@z7O0gVdG5eNTQi%=eH!3NHyEp9=H3<63t^pXs}`wA5?{44I>4LU za2WJEy};lbi`u-wC$*ZP2n^4m3oXD*oNZbr-WXSXuStgbyxJ;<^CoXr+C#iJ(W)qK zl?SNA1i;fTSCvuR#6-D@x9j~DR+N-ZZ#bOvsbXVV3R(tU&%KtO#4d_(DwGInLgB11 zW$fIZ*9Vgv1JtpZ(&~>xk`=|ern(#e`2s#2qeDhh_=)4SRnzSk5J3PeI4_I2zdoNN z`oa@pc2aHOUPuGT1X}e*Tj0=k%*W>s7?$PO@ss%b{Ro2|`3H!P7AS{514XN4d#*@#lwZ7CeHQoRuL3apGb zdu>0Q+pGl#qXMWx=*zmm&Ye!zw;N56+@8z4T2+Z8&5bQuhpzSqs-Cv+MK@o$(s0M4sL-mK)nSbe+?uOGQ0hT(lklfC8Dq*=wM+)G zSA^NDRaH%>hAfm3Ix*2Uk|HE9!jRb;v|Fu4qoG(LSr&CJH}#yuXOzNP3&|=?bi^ws z(|J=+AkDG{AzNAGo*9c9%5af6{ixFk948btZ92&}sZ}rM0Emt{!!T;`mJ)Pxzk85o z^0?dM+P+r6+};#rIM|v2J7zN?E0#)~QmN7bUN;C>hN%fRrA4uvB5;c)3nblX1?7~* zoT@PrdiHc2wrDySkLM}8nR|BRd2_~@J)KIU{k`~otn_FbE6SYv#=(MD& zHIm{Y#g({jp!%p=@UeubHq6$P80R{tZjPpPI%_qMcHLEr7L!iuRSf`np-6Q#zv>Qq zc7e|NaOTazR$j0X0(qxsx7oGGBt)Ws8+i2^)N5qQJk_S^oawXxeab`(Wg2W}NlAP^ zQOi~Zsifi9%zW7FPr_-jEt^F($;fdYkF}=V1%i8R;1dLzW7Q)u(7RB=YBHa-x@dc* zO;Nn4s2sy(CaHhZ=zU}0+Y#&lp14DWQ!m;IU=2+m5@?k zc|FIO7u*?Kjf(J~j1Qy*S}7RKmbO4elkDaY45@L80$q&MRz>e&frT)=-Yk!SmWyoJ zG}I>Ga27;A+G!W_iQH)Ez{~EkX@3TzNVi+ZGiq4LwOeZ>K&}3a2WtgI4z$v#BX!^< z)nSedVyDn&dsA#ySSUdFN)!P|D9p8TFbYTg?cxlq<%V zBj&ZyoEVQ3cuFh7xG14Tz(b*p_G=i_D1ksqsM`~zk4ybZWLluILF&?8I$*gPgxFye z7Hcg`CH+?47oj?q#`QL@)_7gZ-T1nwd8j%A6Cu62QsQR`mh&C!!8NG>W%7XRRu`Gj zcf*mQ^?RJH4+;x|j__88sK`7BBQhZPAvuwm^g+rg;gA8@Fv|-Wu|U0+R;_kNI1}il zg1GQ1h9O|R79oJyW)lY#tc~sJyfGjqUbWj{HLgYsF%6F(nW$CfnT#+khDzxf)}7g% z67M@CUuyUuKxA+tsB=s8f~(D8xdW<1fN^5_EeY{63FIR|_6kg4Pg1KoS3F*6X^`24 zIJ^(UgzvG79B*eQQ_RCUsKC|ZLa0|A8CS2Kk8s)yWz9?URS`dWW-F7baxmcuibutvSLuNRQeq^i;p1>P>54S2#Poa=LYC&#c?2AHf*2!^F_s!M zqkzQfWE6;eh6iD1NM!;Q(%n(c)xKfy20G+*S*n7$Fu4e*X0X)af)M~Ya)q>$ULkij zIDttCJ*nr4ItKS0FRL{5h?bo!MiFzN%%a99FuMyU8X9F#_6mY%J}l_zB0}OJ5P2q5 z#-`$tL?$hoFo?8hWw$4mkb0M}vr*ml6=|A{xdh_awCQ^W9u2xP+MQQHaHi}*ngOD0 zWh#~1xE&x!K`xbms-kN8tkBgfGhNOiX9(;UF=Vx(!xZLOcQ(+~nOGeL0PPK;xdlOx z-0xIShNOBj6Pcuqik>N1Xv6^Bu7Cne$rV(bjxL-rK zSs|CYenBZhEu$V<}o3j$IC{bL8>Em8d zH`Kl~X-r|iCRk`~R!exsNO>Aem=565Jc$P7T($C`jEX2u8@ekYATpFGEs~w1bFIll zsWwyV1AbB`8-`Gv_4&>)YE7oLtMMIqVc@eGOBM$>mG~*aRsmqc*t%{+I&h^@t>GI< zx5c($lc}gq363B%OF#&D06f>&Xk?_^_aPKys>Wnvf|_Dgk|!XVw!pKj62t;G=z|KC zMZnTi6C{POG#F3&YD2YqYZ{6Jl7-dzxXf5}-K}&* zXuhx`k(lauk1=?OltTj?)D(5vbea``38I`DUFg7*iro&&vut8yDl~&@WJMKb7~CJx z3M@Gz1_|I?PUAqY#d=Vx<#x~=4U)=`3KgA2;+Tc(j#AL(Ce006fl=u#EZTMwQR$Y$ zfTFnepfSV@T&$>m+V@#b%KgJ(&ji(9lG_PTb!_zbYS_|80gROGMr7p^`g#Vmxy$%r320kEPiJc1DdlrLkMu6HJm zIs`D)LFyLNNkUg#K=slTD-8t#DK)aTTJ6pw!LI_6;C?jM#u$z_DmXiXviSrwW+|HE zK4n<4tGGjBnmB9bDky4%;At9GM_IDDP-WKRx~&kFkdn8+a};4RAW5Dg<@S(jw>c^X zQ!qUyK?d?fkWe+70k4>u8$cT~9krH`1nLVoP%fKmdR0*1iZHZ4H{u{xk|Y*&qM-Ic zKoXWQlks!SV-#mZK)M(uz_Yq%<5*A`iF3P|LcL-J0m#K>YB|GXJ7|W2X?G$lXPm+e zR6>HQtqccEdST{9G1S7oniB#5`l31mg$xS>bO{Jh6TnD>8CNk~DiV1ZAAG8kjSfM* z1qhxNK(&=s7D3$90$nM4Dv;)o(E4$)X)FX%G(eqyAP_MP>`XC|G5=4O9XZLwOTO=Nii##}zzl4T%Ut&3K|F z-FCMqgR&T_RDo+^Wt1P6>dEZ}JVgjC>&zRlY~pooh8eqva;CXpY-S?TM@$e0LWCuVuiKbGFx&Rva{e z{D1&y2g`kDt}bN32vK6!D$Uc)^Tg9}u2fjuZh{U1EHIPOOd=*2K&%X&*r++m%l@gN znYBSnQRZwwYyPZ(ZVqx`;Gu4EYzzrgfiMQSY=EQ#l{1r_>0GS{!jL%^<-3ME6VOhP z0#c}o4&>JDNXy*>hA+3s)_?)oW+0fQNGcXAosVLYv(yD0j!B|u4g?z+CYv(=jWo*{ z+G&Bw841E?jTFWO3>mj-I@uA>xfR!{4X?o{)g1H%Nt_=`2^ZbO4fE1|rnk8$B`t|A zS|er)rpCAVMj)asqgof;Q9J2Rv>rFA>y$%)ie-}VYHb0lb+u9|_R1y4%gsJ-u`0mn zF4zvL))SptL!5$?Iw;05Ne9a}iE8RFIV=g?Xp!p~zSI{GH|?}a?ucUOGF7c0RbdE1 zJtC-R6i4(l^~$wcj#W^!I3+`aO{|GsZHYimsR)fxJzq#R8iM~~nDc~UdJQ$jt2uiS z$t;Gn!UQUS$0aLiMbinWkm_Z?cVY#lpH?d#i);BoPvcINbl}FAk6q6W^7uvHHdMoI zS^22e#KZ-V>mngAasI0bs;76`68H`Z!g3oA_?M}*6dn{OfM3!iK$S2(!mAFrT)pMs zvoaA%4N!Vb<~?KZ2R;iSQL}g!kA?j7_)Zndv=%fkfkG}A8RqkX&k)9KJVMMI96%Yn z*-9d|9wP#3l>6lxBBbve(}&BKYWFA?-$Sc>`_aWZngXW<-aFRU%7m#xxkDD6zkc_f$KT!QDer{O?EAU<4!!o+f77)+_JO6QcIrpp z{KmhV{;gVoCXFHd3r-r%El`1-!L zANM}-+wbv#2Yw-*ve%pcUhFpyIciDo^(Vjcna_b_EZyq=U;WVA<*CQ6zwWq?7jHZ$dF)q<2QJZm`}5a6 zJKp86zn!G~+`9ebiw}74;6pEZ<;BPMA0Kq?{#!k1cg|TIp#N6ByhW;g^m_7~Tk;zW=vwb${-`g1GWpDdD|bKq0}ovO z^r-AHAe^+ncj!iyv-%$r*op z?0xh1ogXfF_Q5^x-1%_&J&SnbS5_YN<+o>*?LNA4$AOZm;Ox4brb z*8V(u{1pfI*Wdr<%TMp{`Wv&CzPZJ%VIc3?*?X%?&bV_`&;0PeEy|{?E;-`PGq17F z{dY^gZmay$Q7-U{-G9B!_rCTM^IP8mJNSj|&+nXf{NbD4cyfzd@40%PtyZr&`lhqC zGR31_8Si}QH9P*>3az|!OLhIur>@@NeY5{M7&F*s^Zgc|14FL-IJtFh!j>Ps+mUbo zVO{sazrV?EdD+>mPk-RDvkwTqu=JrFzrOFO4e#Pr?;YIk!hyh)-L%saZ@ow7lBGxF z=6Ji!_ebYjuszc}X60kcp1bV!y4g9vhO!4}bpLA2lyK z`1-7O(u(fK?rPj}{HLG4;Jh=!Gv9f8r;|Mpwk zUUcYdFFbISx8cOu&sUzjY2U+NxnFty^1JuD{Qe7-4G$dPKTq|)dJFmFX~ub{h1`v^ z@zbxL$NyA6Vc%DOa_6b|-SWi;I!A7L!1C^C)l&s3ito@g#9P}`gg9n?a#khzbSm-m1pk1e1|6S zo4v38)6xyvw?F-{BYrt~^xCV^m-Nx^e|Gfs?{0eQ)fd;l`|$bVIpgR4c5(K zg{R*8+mGyX$8qOH&pvR#%Rhhmz-v!__@-SB8GqwL+g5$v!EHZbKC}L9%zM~8 z^!Y1)e5HH;?=HUKO*eV`Cj7{wp1b*z{`|G`*Im8u>wo$N7Cj@q_38%yBI$y*d=9hi zK5snnql=OkAG_+_=00nl+j#OF=e+w(uygZGcYkf;_xC#R>H_wm4gUJ;^G%8$32x~D z9QVlMohy^a7PmaK{-v8gd6xlpb@G|*_Iv&7$-B=!wr6MU9Xr3VagQyay?&ix_uhEg zZtscd%H6Agmr8E9_rGO1=cNDme{s^DC!W3gU1uEnf;0R39hd(7&Qmv>cjghN{NA|m zqN^@rKePBBK+xnr%~oCctJRIW&)D~%>Qno_`^E{|ynO!h`*zrE_s){)XLnn5(ht!s zhdWl>d)MA+fBXFHfLPAgA99)b-Gh#N=as!*KKbXT1L|LW>YNk$Pv5f!-{%Rikyl)P z*H>@f@{jE+JFR{1U-iIW%EZ&hA9B{$w*1rlQK|8p3jqZW-}&7KkNNQGi+Y#e{MGqW ze>$df!6`Q`cK9NH2{_y%F8}RE_I+76;F7N&z0LK9|Km3wdfc56V^p9Jo3<^-&ppt^WpEF^5)mPhmn1rSY2Lr*mK*hel)n{(`z@~{`E(% zjkdn~oI{nnS5YUvbP=)fsnhF6Uw`sm2YmIn(naHkF2m+e3A-%&zQ63)`(b*~g`H7_(z@VSJYS**&e_v29*g{<&9{IjD*kU=*Ue(53xpY5q>5{K}`Jd@O zcm3+p4{UYc1)W>EUvIBD`|~G!?Vf`VeIDINeSO^xuRNMOe$CGw*rD~cKVQ6d$;mhF zy@@lI9lZRxHEUO}ZywnF)sEj6_xMuxpY1O6iwmClBfZN(PaJU{I=SHu@Y8qxtlbWJ z@r@_X{N)kvym^gq0yTmMcU^JL3Hx39>)}p6d1=!-_oCg!b64EkoIR*K#s2w>T@Frv z^TPG7J*HM0-L-pP^TZFAJ}K_sJ?rTc_TMx$Iwzr9-Xy(IKk3fL4u9>S>z==A!*k#? z!pA#LJ^#XWFYY}(etyg2SB@T3|Hz*7xU_Zs43JgFR=xbi#wkx+eAcn%vRfA$x+_jR z?^y6NaJAkz;+Kzv_3;tET7BTUW#+maANY9>K6T$iuX^jTKYx3-$%6+ar@wXif!Bn4 z{{uhb?NoWX{$S^*TKA5ReC;2#p@pae!Vo%|`6|>8PoA!C7w9`G(n&$vN2k(d*4u9>@ zM-NwTIP8r-u6g?d5a5M9*L`IjvUY|0?%Nwr*ycv(uI^`Bjg5a>wbMI??|s+TvL~Gf zFFyUk2hLl2>;P=iS@-|Ecke52y!GPxWT%&2SpV)3%12up*A-4(cg-88E}bs>#JZ;s zzTxS$r#|7-!i(6?Nax|$1S7pJbj-B zx4hvm8{U3n<3+U}eR1!%*X*}$#VKz-iEiobc*Q?Y`Q@jzw-@)dw!HnmE7qKK)vKNF z+%|gn6TjaE-(#O!b~)s*KVQ{)8!Y-!;>b7tw#zPeJ@mtuF8txiOY6&~%L`9>FYWrc zf8;8(`@8m@w?2Nx;ji{~xu<>ID-RrSQR~e8PTh6wvemaWzvV9b;qvp(U9BFrakulf zKl3W~Wqiw%kZ+&y^zC0+f7(Ab{bA>yEj#yuI2QItwjZ>*ZAHK13G_>k<>FGO;e0R&@312<$m{XTM zb(?s=ci#NPpI>}?I>)LCVt~lq@$s@s~<#)jQYwy8M+a&z>-P0b!zW3(o$9T7V z=FstTM)#EL-FIF)=&9U7&+b3-V^;!IP`v8?b5&CT ze!T91#hu%%e)`FcckjQyywl#B4t!?)itz;(a0hA|_PY7V{r6kBcIACQE1!1B-Rr(~ z-t&9ie?0m3k01KZD-RmCyzw9A!^cXm9k=47J={%~K7BP%8~eoS_8ZUt$ImF&z4pv+ zZ~MuUFWK$QH8%@qQCse^pY+rnqvJk_$G?HQU%K~^Jx}}T_%qKw_=^{pes6>K%hNA> z`Mj@xYTKhP0qAVo+xg#b_iwv&^w|KO?RD(OZh2pM?$`w$ytsz=NPZleBWr ze?~0bwB(_0ZoPwk|Mx$3`n}s+_!NBPcUJ7Ta?LaRZ4|lg+;e~Z!*%;FKk@J0;Xi#U zyLWBld)>?LdG*-j(MWl&aO6?^0bl&cr@x9U|Hl4TtbP7VS8i)v+tBuS@e}JVTk|}5 z{mFN|{=MuV@5~GK+Wr13E;@JJVQ(A|EHxiKzH|Q{@7wVwomE##jr(uBVyE*@S)p8T z%t;Tv{n`KY&~?Wi{M}Pl+`9bN=dQhI?<=<)e08t=R=x`C)6IwdF2FJbLnx9J#hMMH@tY{N1phZ@P+>mHZO;CD?YWyXp^@S0Hwh` z8}EQ0J!{jFldf7L{qalU#;cB!E@4Z%b|2#I-*MgsRj%4Ds}BCv-?v+R+$YfA-L>y) zkDPnnCjidd@Mg=a|MJC+-#%aZ^Y1QPd(vI6-}}=XE8VoBazXp2zue=TqCPxz3k-sR&>`r zaoSFobY8i}-078H?YHM8Pj>${+HloHj~@B%JIk*-@2v+m+}zgqRgkmQH)(*}Rr{DD z{ukx~O(XF{;)DNI06#k)Xy9X4+!Sm!=gWb-|7P1`mMp#LqyPBOtw#W)m zGP*d}@RfDWb^ETm`aYltyyMP){+*AZTYi7X!iFEl0EcWiX3K5#LtgpNt$+E?V{SV0 zkTU_!eE6Mycg-1x{qwe^-#-7{*4JM8=Jl`t<$JIGf!*zz=l9s@ZP7ZvvRC)0FW>+A zJ5S#8>JN-tj*mWj?V9?JuU*l5hCO@d`BA*F@3TL@{E; z%)O&cOMbfINaxUdE8b1V?sW0*PVNW)VSabTWj7ttx#bRko!{wiz@FJp+4!MbFTVcO z{>9k$gIKR#-g-8W>#`cv5Os=`oq;K7G&;Z~X0r z7dI{Gox>bAzUwq{>()8z#6w@a{J>|BCzrQQYZ`f(w zmCn64OV{5%I`go9e)q!H&wXaJY3(zuhd2FxwCus&@%`;AW>S97-%IPH3(h@nqq6&( z+pb=|{guFTxaP(CE;``B{eYd@>xFCgU%B?8w@*PwC%=5)re)^C@x2=$p>%ro$}athCNiThM zm3O#$+FoCNXQx}AINuHbCwp%l7UkCV4FiheV4xDBpx9Cd2udT0LBq^|Gzv%#Al;#| zZA1y_5Ez)DYmg8S0}Q$c5D@`slII-a6pSn(JEYj9;7= zDU2tZ+bFS#ggsgx9HYm3pGFfxDglZ(?)jl~=_xpgn#0uGj-Th~D{h6A&zxJBY}QYs zwodfd>t0sEH$ZdreQTTN{P6JOGha^P^RaHdp(ZP3sMiU(!}4zyPJkM7FQ)D{t@6?Off$E18+$f;Sth&q>=I>wl@2LeO9h5F0JBQ)9&Qs|6hr zB1AjQ^(PjVun9?1ZgyYf)h{k0v}C-7t9V@s3O?4t`E^E1#fL;=>69bIoE-N-WB7@A zNp)PqM(x;@APR+Qo_xpSmwx(LmI|DYVh{xW9lvuU7wYQ~k%zwXZ2H0R39~p5G0{-vaM0dAmABaZP-Tm2X32Gdca?=%c~Kv3O>U(*D-haGzajPA`le-1g7c{0lLIP8+vEMr1t zm=JXD`FC`i)Z@ralhsnomaMqV2c%iQi?jA@S0BrQR)r{MP93mcoSU>7BCF*=zx^^* zWtwV{e)VMLvA*xS)|VZD6J#kU{C#|oA ze$E73MELq!hG_|1`DVz6GeUrzu?@*LFqe@vvx%fpauspFtZ=m0t!(_*%OJjn-0SZ! zZH7-I+NV!PV{8-Z7g$;+UO{Q!3K&e-81so&6VDy;X9)X*oa+ql)f zL~Ts2ZMSP`5-kts@^D@!wRnES0<)*z6?0|ww&E8Nyz!OT&`?2>g0FQO_qnUY=)?9d zj*Dq<>5I%`_mxtJCv16sTz9uvFQ6!S2<}^Sf3xMxTXNv6@~{5HXezYweRCPMJ#y2v z(DRyOOcKOA2_2-b)$kRKS$J?Z*Y^7UTu|)FOinBK_}-7xqGWlgkdY16Y6X3EiDIN^ zBfU>U1KT8baRSDl^oA+E;K~^^>`e z6UsDDM6KCJ{{@xH*t7DAZO|k(VULm5S|VjMA>6qREsykUR9!vdwTHFdpe~8Hpzvt^KA~z zx{ROCL(2c2zJyO!uS94{-eY3fJwcoD(?vKjg-m)Bd+qZJJ zWp@Cd`84D#1MT`}49>J!aC{5LLdaU&5rIkEMw8zIlneZWN)mR){3=c?4IqbciwBUo zb%+KUPz^D1Kq+4tCDArFJ!(xB4o=avs}wq(!qUkc41Jn@-6*#KaX{sls;N@jMpwma zyoCFqRWo=81=?fjVVVoRERJdhKLB{P>w*nZm|D7@>Q~zqrMiDVKH}FIUvf@IoYpm3 z0s6rz(Lp{pK+v&OK0NQaA0?9Yf2KmVOx4P@jV*&7tc99uv2#in-v*q3F@UE$V=gM_ z%&1P0{evwz^!gl@2Q^>Lj}$Um_K>Ub+fy$+*((evN8otU*Dk^W@ z7wgpn=N5c6?!C+_O;kGeHKDW(Fq9!mCLfmgC|UHdA-&JmvtMbNH3-*8HU4GVm^6}F z>yO&F)N{8tjMxz_InVYyFN_J4)F|nhn(2O0Sk1`j@4`jhid})n2ix91-qVr4RpdJp z8*8A?Tu4&T1!$5bcp4IiFSA^52drKw=-*p(iM?*`2y)1Vw zBk441>!o-qE_~9ZrEe=53m|`Y(YEd#xyQ~l0ANTHEc@1 zgp=iKA^Bqqd?b@5k{UP;{5VS&%LIJc1GAW&z6?xU-K^)h@}OMnomvnOT|Jas%>eiI zQXdKIU413Sh@QbeC`C%+5@1NS7okuU5e(YA-e<>lE@|}xLprAwq1HFMb@MFUb_5=0 zZi*{hTSgQk@KfV^yt~#e1}!6~E_MahBh|$$WZ8%AkuL8aOP_=ba_i=IzEFfuY3f(` zNnc^ih~n>O|2nt&W;AsD0H-KkdT6+cX3?(4?1VL}rg7#gur}H2-?-K@T|OY~{Yd*D z2Hy3>N%@KGKKyJ35`{gE?mO37W3G7!N7>d@EUWM4qXUAC;7{3~T2RlzhXGFNVT%sN zhXXjq;M)OVx6dCy|NrREG=>;HM`^BU`r}1oGAm7tbf-%nr`Wf92W`D-*!Oltdo7uv zNKz>GR}aWud_6}=KUtlB{@cS7mH_^w zdzD1bUtFauZJ{f++^Trw{5h`sG_+Y?t+&t_kraV4vaMg$7o_O-I~`s&Nx ze76EFK0nV}IwzEaJzu_BbNO5bz0Je#Ikjf+kzDT35;Al~)Er#>d>Wq@=!O@tTspvn zhYj_*ngc#Y(Qfe(ke?oZu@UE!N~Z`G`fG?hDzDj)CTOSh0FYKEvt}^OpVt zokND;`U6Y{(EBNG`2X(v`MlUrfeNa>B?vKB{)QgRK>Q@Mbvyl1Osb=%AQTr?tEcM` z#D+3%qnQ22mOZ^y(}*^O>dyiZgAj`A?H8aOh{W}GdM)Q7>gkA5gelZvX^RjuDUIsd znvkM~lH&ZbfRt-f677$d4s;lKeS2dYZ+g*n)cGw!X^J`{v5A`VselDQ<#UM_*hwD? zNC|+4QqFX`*FScHraKK)rMZhh+EP9pFT4s3^)R4HnLySi4q1mRbUJr$ar+T_cPKUQ zOIEb!+y@s9`mJAVR5yY?Egc@s4Pe`wfk5U2rodV>x#j%ZGGT4;LJEjSg z7UAc&chJJDa|7f`(N4m=;n*HA$CUX+U_;G;yv;(?rfxbMtScS%9v;>UGe0RdT{35! zpsGsd^q8o11ffBJWOc}?H-1t}&Q5+1|C<*jBZ>1`)5&4I6d;U`?5mt?&$k;!jWN_8 zsLMCu6t%bU2v&3l)P|@Segg>HJXF<>|6s3mnRxU=vR3d#pKzn#i+T0sJxc@0=~Rh`=oQV}jGDrgRpgMd*J{%c?cR4yAt)8p{JMjW>a)Z0JEmk`bItAr0wCODukbQzVysFQr{akct`iy13Aa{>jSl&VbUzYo7oX84 zLwoPS$jWE)`Yq7BrSw_M269a!MdM0^(8rybziL+lMKoKCTmv9m-MzBcF6y3F^tmXp ztv}~x_j}F0s>lwFi+&tt7ELLqIz}-{ht2PD*xuvjA~FS+z;?_wsdntj1RU*AY1@BJjEuJUT6MeMoF zqsPq`PpOuiKU=7lAjk4UD`X+srI%d{$~m27O6!e1Z0(|e&*{>Wl_h82&P@#uaxll# zwKU+iD6y0-0O*^d8h0^`+`iXssEbbF&E0KI_(En!wPT9G(5k(ZnEMeo5-8B@-T>up zsn8nE63Nre-EhQB2!98A)?)TokK@mGY;Ay6w2wL{bp-V19F1}=^UZBw7H+66xOAd$ zNB}D&G&u?ce5TmQ%QvvW#hi4Y>r@C{f=1xOWLn{fElU}~Lz4k@V7yH-kACFfMFJVe z5mvqNsswYxg5s!yzMpWailDXMr9i=0lWilY(Asml3BR)YQ3y49x(Be7BOF-`*+jb^ zOE`K7`s(iqJl1osMs)Fk<66SejrP3{4ad(zZRhz}Fb)ZYR*q%XVaQ9`bvhdnc5@S9 zH#6%6#aHtjS2?P#BRBpszH2v$-i9#*|ckIg=Mq&qQ zd<&gMTlSOPb3wb64`i7lhLwk@$C~<0wXxf1bkaed&WN1WTT)`LY+6`9L*QYdG*BX_ z7qP=|9X=mZ6SL0wX!3E63coe6LyrS#ygzd&s|PH@iA&mOS2Y8 zrJ;tU|M=kpyZ{_1)Cx;g5(iO1yYd^h=ivAr|9rqunk!ct!W4xGclHuKnmI;}^^odW zIsD58tz7dSO7z4Tud^3l^Wl@_awen5tfa6YIvorRzcz)>aW`ShOJMA&ptufE1?XB5Y4`{NmCVdW&#BjB*L*dkSx?cJBuwM(;uho73EX zkUn{bP>G^D!%>AL#AES|#eWT;Q@I~T)^TCUo|p~ZP%)v4?|iV_xqmdQpj=6E)@a%g zV5IB#UlZ9pPe|s$VYd_j2UTimCSen)_m4*HnooHN5`m43Y{&VSHjnGKlmsR7#LVX1 zob23)8Gx*KX;bue{9wJ{i;O6``{WJ1)}o1YcCI%Zq|A@+5PGcLt$|(1tbC3klwY{U zys{Bp`WhUIV&k`oA{Um5tl1RexQ?CWzoA51!E(N5fVz((O6QM1N|)DT+RCzysbIF4 zxt+^}ebJ8h{{>gN7pj+BNsqZh5~(~9W^NLMJ^gr#y4QfY79qOC<3ugR?dMU;_LrH- z97O-nsyI0q%S=sE)5eiWVZjs{g$Cwts*^-$Q`s1@Q4jk|%_mI2_~Rk*yHY7}gnhX^ z1_k_kmX-!=NMtqAD8|!l@JjBt^%Xa&BFq5im9O{-aE%t=xE&_s;Dq@%7E1$0WP@H` z+MSV?gFfWY6A?9q@#N+RO#wKGUtN)3(zM^};tu@J@o22}TkaJeTE?D0C1kkR9P>YLe0&k=9fcpvu=5K&9)_)_^$Q8G*+_<;e z0ZDI#61lSLgRv>Yf-=`Vno#lq?$0lXa>nC*)hE6VZYx&^Ir&;iYH=cd383#M9?&IQ z$xF~@77@R;0zf(9IfUr42YO$AQj3+_G|2C)D>Ylb^X5zd0ABbe$2g8m1OOKJKUI>s z+6U^(o82jPeN`idgb&=w_S(V=EW5EnqC$kYB(na8u=ZEO;tzL1yZVvw$a{VHHaA!8 zTja1{@_QG>{TB%v$wVGU@{Q*yvw7}(R^EKYJG97>&1t%AlCZLt{Yxen+R`c3osz>Q zha%@MYJ2izBu$kuo_I^n?>8Z&lHK&$tjHj@`-K07Wg3mSz15awS}oU7GP(azsNwh} z2)Rq2g$}L>Dzo-O$ldc%XB`T;>rlvjeMs=aTFAYNLhjgifz#`kj;aL0@#f`#x{>iZ zNh^TIb@q*}=V!>-SfawsHpwFvm}DrR*uv>6auTA*4umUiBl&$pfmkK(UmCz3v!pes z`G!1;tl7t90ZN|AP{E`9x#dsxS(8H&fPZA&;N^wSEF-(Vn(Ym@8dO2s3E1&%kXm(Q z#0Xe2a8uuatRY{g{=(tEKFclkn5R~r=^To!gXuwmkX~VX?me2KEN%Jouc=^`iW{+#u3&!)~8y#D&ZPb3{>M&Fj12P5~thTFb zvpc(~Uqagol-1}~{hs-2GI3mtK z_dkAv%zkXOVf1H#E>ZJZ?*TY%(j$z}{jc_xE5|RN4?vgaCeJhXkLmm1XtQF^-$lyF zA-{Uopferz0m-8A8096xP+cobluYK;wf%5d*rqk)f`Db!ZXmDYJj^Q85 zCDH?%7EnSt$suGOXjtR;lsp%d@(RR8P4QQDPTvIJ*1Rc&ol(W?ICGR-6ZBAhBNn+J zg2{0(jF$9xruRwTCk1HGO#kp=CP23O(gED&TS)Scu5x?3{nA@X$fW3VbH+~>*3AHO ziHJ>Mk2(7@%hVf97E~ghR?vD+8#+qj&pE=S&}A@5W9MGG3|rtbw5s&(MwekP66S6@ z61snFT(P)M&Ap8KREPp!{Su!-Nf}{_iff;%vSY;Fa{DOB1 zpna%;bMn9+7$2#;z&T}|ceR}+v?`%SKWhq3O$(GS{gUc6@{MIhtZ*S3%L*Ka2b5ZK z%&^#mv+3V7-J=((J+d%HBr6zCnrvt4h8Oa3J|13euC?vR#=gf8eTzcPH~fyivJid$ z0ulV@QS@CDxp8ML`W{Eox2M(El3_uEOVfL(FWQR&6=*9b7H}QyETb!GSwObc62cRM zNi?khXj-Of=Q%e2XwM&KwKmZVbSVM+dZ|^WmkVF%0D*od8GI~Be zw`P5-=B%(k1Q@85O7j+WC2(HNd_iN))U_*8g(U;TtEr&3nQAe7qKS0L;c~tvVCL)Q zxoyV#4xoF1)c&Svq&nAk|LHp)RXj@g@FUW+`~Bmzfv_@RbHFRJpsa6Rl(s_uzUR$z zFCj6BH#I}(viE$fUwz)aUhrlq?Zyx~N2;sI5lpL5SY3in&J99HxAE8U(qat>_FL?~_Bhk$DHY$*k9{}lR6XVlHC;ET?dMiXn zdd~G{5~gyteD$VXr-MJ>YXH?cCkjzWd5X}3LMZZe8V`UbBXQtT&&MFUW%})YwJxvZ zF6m_?18+?nKElFUC+td=BW5%MWufSEl)jUBuN@C4u7&TFaJ||_ zA*5b^_rOZ5djI)9-jcI8Z@%3=)f;YI(A@w;w{Pt-00R_@^jA%fRq-9Te);jD4#zf; zK9Gjg<2uOJoyCszif8h>@&ee!Y10v$z9?aiT5GYFi>=C?Cj}UU< z4{z!HbU=KPMTs`|HAu&na2UUK0Pl|T)q~8Tl7eyX@@3NrIdaeDkrM%0ES1lo561dg z0)};3SKlX$pMW@5{JW-f{pbm1q~p}4fnamkQ2{ugj9Fgy#@O>4!^K@}WwzmOW1WW@ zu*$h$4=6B{SaF;`u^qSl zWU=wMW=EY##Apu@5>k7F#>F+?Okf~j?a!X|6`*A7w+WJQ`H{e`KV@l9y15`BN%fJ4 zuHFRHwMsL;?FSHv@zt@Kc+3URD-fkU2;@uHN3T zg>H*~zZNF(Oe$cLp1bU-uXVpXNl&c6T)rV1e_)AEJm9wC(J*nVhv0-400 zuO(w95R^??ay^Pzk2)e=TEZ3=kmkNTWnqCO+}+jGl&o<=BUK)ihE0%Ca|-0V`S_1- zy~xE2BZXS6RLi7o@)cb@?frbRz~GiW?wleTw+P)tJHM zuL+=d=w#0j`f=cT9A2UET?4{k2ix*SZ*)Y9Ii(4KxD059eL!M|@#`12e+=diZ@k8{ zivp-0a)kAziGjPxqV~nR8y+t~{(yW@BT_oZ-p+H!{#?_ktbqsfc#fqu)z&K}$Q+i$Ooet(TnrzSE*5BX$uiE@_`kA{~NB z)E1C#8UutLt{5utZo^g%Q^2krqMvYx)In*hb>I!s-#dWZRkskTM#om;=bD=W4{EJy z0pJUzz~QBUXlRd=XVG9M5Ekuyi1KMn*OwYD{y(zt!1a30UG!`ma0qqltN?qW;*TN( zU*6snY%vc9@5)^Npao=s!u||U`rmvw2fX9MmYE%N?68T$RP~hB?$!552yaEL}hb7gzLP!`#f8|0OOPw*$c#&LhPwY<=D(92{$bui6}4A*H=(N{7xJILkir! zxSqGGA1JK{+33?JGm{#0f5s3)`6WHmHlHgCnxa?~F#Tu*UnR*=KgIV^n|@8w5sxq~@;^ z4Qw%-aA1qqPPq6EIN_H9Dpk-CRzN2_pdexo&`p|Lon<1xpF5rDYm?ahiv30TIpDpw z$UPhX{cQoSnzZ-}uUffl{!-8+{Q9e*^hYxei~^qr9At9!$+zpH26AIlG_!AvNNLs5 zPmK0K8Q0E+2p|CIZ`77>ygq2hExls?MAqPok9Q+zko%9 zTheMiIv9Vb2&zP#Ml1ov%Y~K5IySj@9u#x17dL?ON_*ROO&mev^9Tbm|JaG6YtZp8 zCFmKyD2l8@RJp)Gi20vi+N!UAaX=+eiE|zprcM5`#$|FD(fQ0=gPW42qM9Am&NUBW4C9s#OhG7@BOu6yPfis4H~@m#%R@CF z9&AC}k7qGZkCtCceNf8^u{WLZCoWa15rGAgUIV1W6lhXLMuBHaL0~Sxf`X{bhFegH z?6D9(kb3VbaKFRAsXBVJ*CFY%+rrQC;ZT#POkYN}Fc}f>VLm57v_y1O3+N?HfOoX< zdScyC=#+cQznn&wAJ``TVP)fp-0iLjWAgWy|VAY*;y6K4VC}v&>O@9?lxq z4hWI=-kz?#vYw9R@=@;{&Vw@v&Kx5@;dCRag(t{59uiz@FCXmTs&{zBe~{%m?ySnReip@j z)|Sn_!9%aa(_~ zA3bqtI;}?(LJVNh3pdK?U7ipZna1e>fG%|n)~5X(s^s7}#+}xlU|D^Mp#+lRSoL-Z zL?|BE4*}(}!p_JGTq?BmS~!&%HT5-wN`4GEc(Nu_4D!kLgy> zv<&;XfQaGx_}9pzfK@Ops(1lZY64Pcm+8AaiTz78i$VsaG#a(?iq~E)EzTE~4BGh; zi=^YoC9hyFj0pOceNPOwv>FBFe2d)+H+7cDXSvWdiLt(|@5J+0TflXAjGt`-b^Y*) z^F1%h7wYqm9s5vcayR)vD<~kYw^b6y7l;LySPoe>rGzG5Omv*-x{DOJeM@}6r@Ixu zf3j~h>fEARELQ?g0;ls=ANKr90W!a6>14qoqP_mm*57%I0U?q#3iO<7FWJgKc2QC| zcpIHRIX#HYhov@7KtHgfhV?1t0ExsCD5Lq4A0R#+8}7gaVk#GlYuG8ni#{iVopcEa zi3XuzWv4MB+@Ir9_bw{Zp2j<>Ulo7H^nn19tZJus)zVSQp|h##*4pp##iCUfpSozXxzPm0UyBlNFw5)9nM`XcOf zS}q|f`KFJU7nWYo*S{erl34O0$f+GDr1o8nI5WARv;|lt+@zYOa7-WfkUBu7Y#D73 zvl%Dw=fvqhg6_w}X&*N(aV#o~&gaX|f)dcs=7ySN<>Oz<`v?iqr=C9ZAuKJOd^1c8 ze-K^Zj#$hP_t!+4=Vk6+gwuZZ^*5!4KZZhiQR}tPiIaVt8i9Rh8YReXYOz;@=sz%r z;4bqO&pxRa&b5YSz~}s}g8vh@;g}rF;d?Z#f9d@QmLVjH=ETMd<|5Ur$6AGb$Qy*c zmfW56=-s|0TP4`yO%ow)j4=6{7G-F>7%hUTSsnbPPM*G1MZtU#aR&aBh6NxUb)0`d zHTxL<G7|JD!U2<(A#2FaJogF@!E(w^2Ix-9xs*RPk56^c4^6o*XGUS#p7E3)EC*1~=Du z7jNnN&`0zCNh%x{_+8Ej~CyE@&)J)^8w0CWVNZ9U7<3XcUI_c%W8Q#mk#9Rseh?(1-=AaD#X-14`gqmc7f*79 zblE-?Z0<{sxZZvq*~8{5cw+?-`CTRYgHIC@XCVB&Oy?Qv*|x-TMmku@OKtK^@=(G! zXuUt;f66s9EN|H({E{HL*w_P!!wn97Dk$?tp8eFux-O~+m4MEwa&ZP|yQ?rzq@KN4 zOuex_N6{>6KIvGsb(R~h>peL43ha_!gpIV~6j_F0aDkrFJ)UPIa#ZsIZI)$woZ0zb zzD3AJ##aBCYb^msY=r_UGq6j`fk zg#!?Sp)WGsZbtyY&XvMk=q%Ydu)KVK`hn?We;&mht4?lk1mq@+BQGAggM5EBG^Obd z@}#@)htp;mEvf{a_N7jkT$@(Q`pI@idJ2eg3oIAi_g#&fmFQ}`h@=V6Gw zyi9L-2Z~a(^Qs8dWFWTnawSIRWnDZ2I^wAB8`?1VwiYF5!Hx59wMx}@sfVBITt|Gu zkh2%?ztg6wi)W9Qfb6rk*EB^S*oKX_MPVnVZdx}p!dqPamAWFYH24LKruAI!1< zHKSq_^m9seKaB*XdmX+(m74+X6Dmyq(2e0K=Jpr*%Q))u1imWd^x76yFDMhTJD_&u z?o-w_2@?^Lc9Pf9-(Lx@mI z0;jR%%vcxECY;Kmp>u7z!%1K6lJC~=Gu9)1X26pxMv03!iqmH0Sf4BQr-jJGF5MIO zyZ2%Tmsr>-Eu}RG2WCwwQwzp2)wHBNVF< zX#urS-kC4XZ*b=-Ek3}P;Au>dXLD*nnr~#^|ET=}id`gdGU1a(Tqm0}$S&dr%Tezz zFb`beRj!oyYJq%TW2VJ14X%3Or{HUno4?5jn7^BB+g13;^fYQn-f-f`bLf{^K(tDT z_L#aE1ZpaZG4f=0r02@^D4yx~E~81d*8tCGOIK)nS)IO*!t@(xv(-e4;g_u3G;*PM zYlVD$y?iH^{5s17;I z!!d&3Yd$irfael}yWi0iWRBrQ6K}4}$Eh?S)ve^V0&w0gs??+bI+i9ER;EFnI@N)w z;pQUfy+6-)s?fh<-sLu!nwJ7xO`1H6g}~VVRBY2FKMM;hdjQ3{d)a=|WM$umhFfXU z!iMi3wK#yuYiFCEV5l+qfiaBEdbLhO62@wn{Owo`==_ny;%{efR4Bt4niUy+v>OV0 z1|2vkk}60u(wvOxCfSY*5I?8zRn87v@KejO%RjH{&By@z8Iuk?UA*3mij& zOp`2{RsghiCF54c%!t_CP|I7<6gUq3kgUdeTY^+14@og~4Z$!!A_`J5Gtfc!2W!== zId&fY8cmSsx_9!p>s`8druO zMB6u3EDWzQ+>4+{)S?)DcoskXN6COj4Xr?>18`p*xo{hlvG9!D!tc-Iug9wRZWnVJ z;Sh_U(UcRF{0wu?TKUe|v9AVV7&rovWYOM4_Tugu#tw%q-7Z0XO z$4~ruEr?KQJ&U|GZAVnVy?mdq*sM*GUgwL~vd6S4Gblh-tf0gJQ?P`4e4MRs^1zHI zq2Wq7kqKI`fhcES*c9h5q&SXEgztU!)Wn_;Y4cA`wDHsK%azFWgzc^Vb49zOck5pz`re+Pi^5e70RX8e&ERfap1A}Jv_dI7wj zn(4*;yVDaeeK{7*RWNN}XlrBeQ;f;GGXz3wwuv&^$EUhPI-@23u-+nY6^BpuK!Hm^ z_5}L%C7|1#&Lb=qHkVfy0AMcxG{d8A#H$VeT4Fv9Ry7m8(Tp3 zb!XXr>=PeSe+Zm?j->d1?%!j<(5_wo`P2CK20sgjzJ13^xLgB&r4P|FlYibigG3H( z@bIJ;xKqghb6F{19@@j4ibdV79rQPp&UUS5yH!hZio5hgnDE9KhDg2Ragp6GO);%K zpwW2c++JTVU;xY!io$pwIYXd~g<5wA=$2eSjoKeCLlyE6pHo*&Digs7abJxi(gg5a z<5tN5!df&BAgVTq_Bt&}?=j-WaQI;YSRn*{U47i*01}_D<%@v*yjS+UwD~D*qO>kC_)A$n@ypG26<*u2--wV0h5i6~6MWK(^9Ezv#5qNP#d?SaAHtHX*BzX(lTUdGKF%T@vPDAh=H_gt|1YA2-Jy*&tI>-qKUL{ z4z|ZpvGbh>C&boHkDY~1mPO@9FO(O2HqHQ_=+InL1mZL07sW=wUXR`$QW^??iJK_*D~~F7>G*K z%tc{RUYlW3_;Nq-Ulmuq`ImP2=Gl)XQKMySe`Q+4IGA$=zImr+?M2dIri`iu1t>Dqf8g%gDqYT(RtssY7QJxs8zT?LmVx{{4 z)Us<#_@;fWi-R-WCW=RnJ0t<4LH-tR2OFvqcVEsY2MJv0E57AbG)&*d^qCG`!0&Z~ zc18i8Eo{~PBQ1F>fF}-ld4bSE? zEbl<*f@C0$phzf~m2ZH@1$C?S2;q6K^pb>!B(gqmHOjowM>Lk3(m=eB*Zo9FvZrJt z#*~L+7D?*~e3L__OHiL$0hE2O!`iipSr6wdU!BMkL>kbCBhfy~=;ry*_Q`-ab*mlV zD^tLG6}mJn#(FU#!z&Vhx)ERXiFq2F>xg^0urW~S?nSscro>x*ziAt0(7Rh~_dola zGKr~xJn=x`ozKesA^~;zdJ)Yo2~6>(h~f?(qYpttS)L7VUU7jQI0nK4@ZkCVk--vRPFjU`v zKgQc%&U=z~8vXFk{3h)WYg{qP!VcPt6q-+tM#moX2FEQF+e<)vJZ-daP9- z$j%H#Y9SFebOp=N73}_C@&o>SlNNsf(bvGCe}IzX;5-tiB9#$3fcV3MbqNo1A=z~= zenod&`nTG0_4bdzkd(?-BE}b1KU?|=5VpKmJkrpF;P3t@bejsWV^%ke|6N3W+0?NM ztiHl@4al|aQQ`$_6!aYx09YB0`W{C+Ko!|unN1!`uDO*NoDn0!wtC_I4Mt@3pZFX? z?;y1L*Z;fkphEM+W>pLDUl^Lz1^ho<&;PqMtbRSTb)WD;2k`&s@t;~JFc_M zw!R^x-Z8Ss%&n*z{aIX4-T(PBOylYnGpPz4FAx_G5$PPw6;B@xm8$BNh+ebQuPx!f z2R|PhBvwuoHe4$fSL=}91>Jx9({>b0ZwcQf{Vu-$`JcMbQw@{|@Bf`(df+k?GV2K& zuxs4$fBy!58+=!OT82h>M^GQF36B5y+88eQLqcMpZYCnR(7*8eE5C9F3#&Vu%l@xi z=hao-FSOy{7lIAAImvQ|0%PVE27KQSr6 z>be?k@cpB#{$G+I*DVnC$=2LB36;ga@Lm4=6|M+aT^XtJ>c4!kp?F>oCCtN^N&}vM z=O3MgD!>;Tp82n@jmC!o)Pt<&!e8V5oqzP7gM_x#e-6^h;rh=(T1ou>IY|G>NNWl8 zKN)G|Qb_+NBcU4L|39Uj&oR~+MC03Zm08iFDP=H7>*7!II_m+Gs)$S^Lql3-m;;d$ z#H*nN)4uAhOHWR^!|>TXqV`FTImMblVQsEu0+=WPys_89&P{9KR;sbu|^pcIo4908#rXl9W{G@TL*)8ITt2w%FcX# zBPBs+^d)Sci0xZ6su?KZo3XOK0+U0v$XeC=_~5I5;gjRzO5?8tSc2=r5!in1%^6w zQ_8a)+)(e2T|MWVc-i~2+b956t!Sn(C@qBWhr&-@yET3Lt?85X71!;%HGe;yaxFOh zmy(!Ckq(X2hYMfHTtxy<|FoinrQMdh+iA1D=Yd6fIR~c6)p^czZG_2jIiM%2vi)AM zonpczv5{KrQHX}+Tirt@*WeTSQBiMXJvu>TVZt~MgIvLNa5Hl7UJKG`du(`+skh1h zUCSTYI{&nK=Ay2j8tJf*eZYLP{)jZI`*fM{1#iAtCuMl*6dIs6@&ZWj3M&}7VCq(Q zSfmrkUoDtn*ggo?A{VyEjj-H=av5OR?~?Ne3^67=@g(y=q*Cbt>9fa%hp}iSH8-+x z|9mC8=@BJP$7>GM#i+r{M-2Xl7q_B$5NJZg$h~rlwEXuVCu4tXop-3O2xx2MA8>mG z8)yn7)h6Ugmsh*!jPxEZb#%hG-)rzdgM0ITM8Jd5YA5#aU37(ScW_Uoz&}FwR$3z; z)15!4xydm8_sj>g5_p^x+DPSYi%8*thWMd@wP?aOcSC@LnQp9`yC~ZSVNSVwkn21)Cg z-%A{fC@4p2v8qcJ;UacK?KX%`=y7z&X;qNhpD*9S{N>l=a`f^-`R>!E252<-D_HUf zJHFHcXp;LQ@(Ff#raxQS|F-b9>k0Ryd$6dK~4tdt-z1J)r${OtFqV^QNHUOw%4F08f5v>;5M{yUPnz;-XH8^!KR(&fTulmS=4Z)|#!Z>9@2nmL#+2 z+)kJPlnbhsj>&2GZkjOrzTHz8o`OhUI3ak3)azT~_h7MHYN@Li`{KeT^gy_d>h)Sw z=p++5{KWq0wxnHOr^=Pvb<7u!=1a33x{|i?1T%lNvXj9w$BVh1$uMD#3R$(c(7QG; z4{X}(?*WfzaD=DTN6*-Et3Fl)^`6+dIjcExfW(-?2kiNzaAaaqOZ@n=qu^Y zpL@}yP&amcMS;`kh>R2F!J)>i8ru<#Boupl+Zyy>Zq?)2>i z7N2=^5~e{Em?$e&{{n%pWlhYvB@1TZ&F)cEz3lP?Z-v;`$W%}N@LAjPaovKeqhDU_ z)O{9~%N>&t1EafC;fZpI$O+qNQsz%eQ{__C`yljc+Tnspl(@?+Ni4>mCol--1}COH zv#|K%RdyCGtiSRo=VJTiG+l7BX%4AYZ4E|cA{@XWtyFZ`BY z_()Y>9(;~ki2Q3`q)UTafamme!I@o-y$dr$-*qH^R3f)9w=j!iuU=84jQ|3?@S_HK zB;H(uOpY@*G{?{_jz=$_#+RvrE^ZNd0*yAubD!37eTEJrj~!entDN?5{$D)0+k)U(9P!IP+re&OBKX8Pd{+RrDD zWo=b|C|wJLApkG?kD0!Z)Amt(&Cxl{ET9&Y22!_nW+O68(1?U=*_5h{JY-`V=g`QE z^b0I4&8;oO_wuh#>C5s6LoDo64xH z&?^(%yTO)B!{ad|2YBvMO@xds3~aNHJ@sl|1MZrN8%K*;Hl@@ifE?d%fscQd+8gh$ z3-yfdw5!+PV$Ys=7c#fq@F)@z(oRpq2!xJFh^7ufn|D%5PfdF6J89sZERYnv zjZ7g*hs)T^<##cL8sogtM4GXUn?42cnqVmX65zDyEbds0_$84{zDzOx#L8yB#S-H( z=c#UTIX;QW6K%(2~El`IkJM`8*n0fv64t z!p6GC3J<0@+P>Y(9K>&98)fK@cBJWwIVnVh$?PC|2W4=dePQspOdiwCan`2PH^*JE zOHluE-viz>8U!Do5KCv>$h8(?{0H?r1RAwEW0<&`>~A7YdRy*i^`2*Fkeyi z*tZC~sw=0XWN?_mLqdATV4K*YZE^|AAgdUZeG7jYX{mH3`Ey}_d!dSfLA|OUrZb8A z#|xUUTQ_{%5}KLGJld2LkS2ZPEKl@S`+CYzul0{_M3ZyXcfzJR@-#M$ZkedJz?>yt z4^HO^9d)J8z^Q)F;FhPA>%4id;K)hwI1_wh)kF#!R(PK{7-03;)j2B;Bw7Z?B4SNSG_+^7toy{izgWJ z+!g|VQm`7sA*YdcqMSM=V@3YH#xlbmMbSvm z!`{jn=s+~VTHBthNBtk1y#-X3>GnRXub>htNUKOmH!316A|Tz3fOJVn8AvEfNhmF$ zARr-Kf}}_z0@5wgEdtWtzCAOeGjrzr{`1Xptx;!|zVGwgvG=vFc$mw8Z3p2VD&Fka z7G4Dp_UD4|>7scj*I@cmNT8}(@YOmM7V5F|Y*O==jXL}@=QLN^X_EFu1wKX^+`)5R zlyWEdM7$3=eM(N-pJo}^`eEIAYbc`OwOseXhtE{6T7gyhB}znfbcxB(&K|QO8v24a zNRQ8u>JY~=m5R8D&cG07*l=YE2y2tneE4;4#z$X&yu?7H74sPUP8R}Y_i)}@6 zqjP1(>e>e5sS8UxS(b39ipe~K5k&qQdqjZwORx0TUy4Rzy~URl0%jGW>s`31=4uI^ zDefem`*XpCIjUN?D%#78KS6FDT7e=c4H&Qb3f);N9*NY3R}wgu0YOH0=Aq_Ve`Nb) zMs{VD^6{&&b>g`t^w9g&voOY>MtRJn zGX09DZ_dA7gw;#{B`d+!E z9_|jdKp(f=6aI2lD-~Bo&s>Ai;xApv<(PMJX-AV2>F%G$j=!t+0YV)|0#ju(nKM$y zSUWNCtk@aQ?M#yo`O`48xZ7ts`wDHWKtN#6 zdFY_q+x#Q%WhL#?u15w6f5R^K8YG(n*%SX@ys7~+mngDTzXJkoFZm9cN1+(h6WG5< z%RfhH|H{(J@lom-c~W>hKIxCThfpD26Cl60ar;Y?yHqoGGLoD>IU&F(Ko8mc{9QM)7CBwV*C z1l|4)j=|3Vy<#8W!I|D}?}J3^^ZiA2I*+~ZJv(0$8!La5geTdHlr0d(gU6D{C52*u ztUw94qQNWew+yh3BTX9YW@KIlPCLO2I}hqsy|0HRdmbMMg-_{8-y&C4Rv9kfas!D< zw}+Jtq+akBd^;R`%i^S;4#*$$L^DAyll)vwnf+rH=v8+QeFw#`3sO0*VUt@ zp*OxuMV>3oVLX|1S$cmiIBfL>QVNKTN;}Gp*yq6GjKw-w{{-(ss`7KO#}*czRcG{* zF0K-h-^S}&1dg=qqD(;m9PuM*e*T^`+Cu4@QLhZrv*w2@hIcNMK`*|+=y+QAZgB<6 z7SMrxq3Y!9G3dsPf9@z1(mqQ zsNaW1uu<={Wqsq1g$E_c`lCtJoh(pYz4%C9!tkkJW5~T6*8@HlU={{Iv$Zoq{Jm%} zF;9MjeVRF185>2OMFm!?Hh~H`@SYpeR({{S*n@I}Uc3g)$nKcfsd`F-Bj_OZQI-k%{b|v$k=#}tfBQvS*)vJ;viddtm&DX6P^_8ArKSRvnLDs8i2&qy(jtzDiD0D>qQHWYh!&g9eVgT%FU*Mfo)B)BTZz`*|o+ zHj$m!G%}L|3qDH6G|$E9Z{U>)=Nh)%0~5>mk(XJFq7$+7LjMmWgO~S3rJ;4cq-rBM zk8E!sXGRTz4E zYjD{C92lZR=0ZrT;jy%vW#4&%2L;X-JaI@tY6%Y-(k z@Xq>;qIiH8q`!uXil`-baQk>l-Z?n*Dp4IUzq>AX9*4#x{LJJA66ub)cebFq(OFJjb56^05+K}!M8$D5j`%5fOkJ%`ryJ{ux0#V7GkrLUTLHq@YX?!Su}Z! z&uy^q3 z_ef2P9-1vjqA-+kIS|o6DNyRRRi8k!>OlTCR^NlX-BOzj&+nhQSBA#nX8I zN4F?Q%xB0r*UGhh@n(y@x%y3y(SOKQ&mQEF8DXbLC|2l-bJ+Li=A%t|u;(pi3nj2aKW2@=Nyu4%Sj*aelA zIT|m3e@RKft5p6cUX0}vYH-)~E6xFuV1#7zrH;M1CLA8*sKb~hm(g>FkMO=!x7A-v z6Zd^8K$v&B60Z24qqsF5442{4AITjRdplXrQqnLp|62Cb}Aq% zpNFE^>D?=q5kOJdVY1+xoI)@IlDUa$eOxBF7``_5mO`8UfxO!j%@iFuNzhglfMrGP z>=;}U9Fb{hI_0Db`+5Nc)MHXH>=wNBwRptBfIxnweG@5Eek8?!-3Z4L$()(0Wx!M1 zU<*M`IKaafZ#BgUA+*+Zcb^^8qE@CaMDYYL{)hVdI}_(`1Q$;Ntb2v=Hd*rpRP%Lk zUA@~q{GuqY;=#V&-jlVnp8KNeo)0;vEL|yecK6cujg70*d zH$QP&JNIpVZTW7dr5ALQ5QSg}RQ19Su>z%vKGA`Z9abgsqkf;T>S36$kma02(D+nA z*a8`skT5IPIM4MM!rpaO3qV#QD&{i)is7F4@KF$xKJ_X$a^jVf#WmbgX2qlpDyZjL z?tsd~840m2%Qw`gQ(ol|O|A?MBvMnUmotn#d84?>doo`#?RW}TpxBi(zSTz7tYRxC zG-4Q7Cw}>r1&$;eCTCo{O)*7n7dR-rhDfJUCKWD;Qcm{1*151Qn3@n<9f+h=B-5W% z)vmr^!zOe?5Z1*9$EkJlOdsFTXD)uZj;g7_tXfo78wu{_AR0;w>s7b&k!Mm=fG~ zsmw3a6RDl@({__<`JiUj*ezeL1YMcl`HS;v$Q23hb=>jSjpwfd_j#=CZ}0z43&Tgt z)5w|arDCL)QObOl(JR^{Lh2P)Mkw|0XKY+><(WMa5|19xF>reRppKRy#uH--J>Z-4 z6RH`SIj(LK7c3fS zaiQ7X*T1~agl*fA^MLJ$`{S)9mxzd*DC%>kZkf%}W>XtaSG$qUDG#s=QJdJ!k+vQCMCcsB#AirT#+ zh@)jQQ?JKXhrx9cyi=u+U6}`6=`bG%3Ki>%8E{aij~u-JOC$9A??tJPcu-~^+1tu%DWp$3 z?fmhm#C#u4@U6E_SoMMjSIY&|zA05og+;2`OH`fk&cqzh1$TERwF&@m=F=!im=u3V z*IbMfSZFo^?}C#K7m=eH08xqX<=M(R5(+Lq_SB2xKrDhWF5d? zzm!W3f{<)rT6y&|Q*Z){9?04qUK~@iSN2Yn;doO6VeHmOh*Is1$9T(~2|)a_P=kId z!sw(`u7b=aQcSIn^>u~Acw;8*Q!$lth83i6grM(%dn`2x=aU&kp`&QN(AC=qC|%`8 z=+yM2?1#(UE(LYqeM{G`D91a055@=|456#w7jU zyvUCIoY>(l2!03eKDES^VJS|U)Fl~n#CkcD&R?SXA`?N3)Jb9vmbjKeV1V>OP$IR2 z0rnGr`wFO)_PN9)V@&Mr?H48$krJ|1VJAbmWBYss#aYv0yVoECyB*C^lT^zGfJg1u zYW*ES$maTC8oV((nUzM_-p&D>&Uxp7pR)bm-}tZVfq(|{Xg=HD*Czk*Ze`?dMctZs zJ$_mI!Tmfza&$aPnO@I z1K=1s0Hj@nJz=-^sxc@dW5C=xfdtY)OxnQ98Tqt(E-mM~d!WW8LUuxqi`;oZ`1{q| zRaVazeB(cTjz|4OxfZZ=-#6V|a6A*U zdt>NrFJ+k~EWqdf_rRbE<$Ej?{21>8IIv-V-POD7_G&I*lmec=Pm*0vKo9+W)L=U9 z@YE|q%A8a>p0VWLjJj7d99>iX^FB9pY*$wYckZ#0jk+(&m~ zRE2v_ObkTg<5IxdXt*y@V05idw+lSJQL??d1J3IlkMZMI^P~b$K&J2 z3&f|9cPnUNT^cyPqwxzE$98{!1o7;5umA<#oLqwGQ~prdozgU$G_a z??VqOyieI(Q`R$QzEDW7_C-f18Zujlrm@1m{QUiYTb0x+NO>iAr$PFEGLjXrkM@tc z8s?A`Rc5Mmk%;6nNq!v0{=Pwemg7)*x|z^n50B9{x39_;GkzgVb?^j;4`b6 zHc{+(mz|mL6M4k7;Y}u8VUN1=pHuB${gJ`)7~FsjF(XzR2x=B9x(1(aMH8$;>Yh73 z`t4S4L!vKjXTMvt|LuhT{r67eoXS3sSslrFuCS%>)~BIUp*N2vIlE80|+=mpl zYFn;K^Zz`x`S3j13+by}Hf4i9{2OZ`YBL06os7qMR z{R^%ya)b&GrH~_T*0KbgcmMXAjksfGt@Yl1?BN!8D2ES&!5LuW8o~Yg+Ig|G!_AH35}m zYu+N~3Ok%@n@hCJXV3!w!1_KNCpbx}2K%=K9()nrrpX646SZF}j^Eeg@4LVRqhpf} ze^gDlc<)@)4GGw`E1I$Y`n`!J6Y-hWeWp~p1&4IW`P}EtP7!f`m=T%xGEe+tl{S)E35~f;l^3=%R6Lr%S!9<9XNy}?Fgq+Y5*q90 zB0f$ifWgPa!BM;t@HH#&U%t&sEj+jmYFF(yzgZwEl?@EVP}HkVvE2)BwwTS>N;!aa z_s1^fD|}zL@4jdWdP9+6|MCsJ)EWU=L!s;PbtIJ^Z+Kd_HrHze{F{|^#27=7QPEqI z5?E)l`<=Hg8?D#~GaY_eiXOf1zkKwf(O7VAky$~WsT&Myt`6;iX)DSVw}v88u7iAl zxF3V-|F~#*?S-3pMgL;XK^gR~-c7KjCyahke1{D*F}#pNYt@^ZG&|NN zNmT$-y1HR~@bI+;^c0wE5i{JyG`!gIz071MI^uhI1$YTHogSjo+!gO%zB17?tb5zb zk|_2EMZF>qB&(sfZ}xV9_ldGH=K!o(cVC1yJXbo5CCL(>BT&ebvhbaEEkh4hzxhd{ zV;&@ukSM_uRP>{w{1+F=12#LrknR9-tGAj1V-{rG3y;8hc>!pI!}Gw#;G(oo<#qTX zWd%)Ey^)=vH4a-2{jQ%;MPF760kfYP}DoMSx9a9%ME=5ukxG?DK-gPa*PiTv{HvQYDU5~l5 zHkaeRJw~;#2~0q3sQA5x1Yk~!!fytxym3i#p*Yn6a*x>QM|fvbDizkAR`m5)>cn0o zYe?hq{_&tg{^fRgz{UkR7RY~OU=UkLz#5}i}o`>fVx^gW@k8YTv1cDv-X=L z4bKTo2()|6W0bU_6WmOLzx6z#`LI>}!(*?<{dU;Csjmw8oeS`na~OU}gA*g{)`uWJ z@VoLW6-M*WlD8AlR@N}PTj)a$hhUn1v6kn|bo0%Sz!X(;**dj$0v`r+AuW>r%aiu- z)e(Rn*C6zw7YL67tNaNLK$5$(sMdoV!Fhqry?z@iVp+8Y=x@YM`1>bljA(3i>f2cR zvilBsbFDjH13{&k!vti{jroO0*!Wfol{NTz0PescUgY7kR^SAi|CG>A)Lx3C3 z0)Z~T!fbc^Lt*dkNDs3>*alfMt`QgoN7ePq!fB>h@|&-Lr#VzHr0fFk1^=OA^CTx! zEXaXBPY1XwHqbZustu#fp!jCyY9KV6(BoT?dD! zOIMz%YXn;hQE zuG)_5xed#Fx0R*KbNyK^C_u4ut6GZjABq}LYg{Hl$b14u^$lnWg0bv6khpFnb`7S>lS;nHvJ?i@KX+k4&X zclFJ}3v!SC@!>t20ikDGS>$H@rwXWDZUhB0!jS9J@E%MJGF+EGTbxjkR5*I#Ts`p= z(BqSk0nPHJ(s>^2hPx<=T^*RW&yAQxyAmajbw^~a&h>Vn@Nw7fc%aF_g!nqJiHmH@ zH)@fW&3Z|-5z3r0fia1k)oAh(-dm%^o@Z;x&|i;I#Soqi6ODQQMpRR|imNQV?)W36 zvm_Y*pIT-gW>`?%1%qs)|4_g!$%}T@5w|0rLq!L@On5Qwb>@Pnj0%0={A~k+mqN4F z(;8*6b^6Gc6(Rx5=_CUkC9fYW#35qPgmt_#48IvE1Yw<5k0zC$1o#o$Z*F#fX?fON zzWr4OvGTXHJ(^PBlb5!On`0t>im7>18Bi-O%e)GssP+ z_z{;uM<^qkB#;7+^pA)^Y7Y-sM$4!EvAutJRdjy_082WM^f<5st2!5at&+$~`0s5O zgFQ|)a?a`4>vU8dhe@X~42`lNgR~C(h@P6u@v_VCl7m%aH_?MTO- z6R`=9F}B?x24)zNtxSRYoC)5iy+9sZthR!gNFlh|S9^EgwE+0Zu^IU=(okE{Stn(}LUxA4J?=cqOeyjb}aEomB+5F82H+qV7YoLvtBq&y#2< zvB7=3FbkJNFZlc40K!~0j1S)|PWv=M);->ebQ@oX=|ff*BHw!3lqTd%wZP zKkWC)UR+c_f9uxRV12Vo{1u#4pCF6dOo!eYUm`v1?8-Gnn1=%XzVixjU%m%5H$PPDx6b^zEFq3^6#;()lUY2$*byFkT`RkXf zNEe0VQ)L5%Haf_gc3{t}InvN&!2Xdy+Sd@t(^t>?1ZHOd7@95$u45EvHn`{7tm;yG z#DX-^Qbo_sISV z^FNh?qr{4K)*oUnBGXAS+zzGSO`z(oxpsUE2?N$o4xB_$7#)~RBr9ry{BCf^5-G}B zVlJL-BYb*WZVYAet-(7eu>t|nh}Sj#KnDO~f7sT-cnEyRS*N}_RqUqG$Mgf3xD(cj zjw1LA9Iak>OB$5Oxm4w7t*zT9k5WV_Rnr9bJM=$xPV6iw;owmpYJ6m*S^F#E2;*e1 zEAXhH|NZOz{Gz}8>?$79VO}t!o`s3aTYuFn89+AXI5T0DCZB8<9{B7Ocz@zWrKZkA zF5XjP?0<7J1+HkWspl|u&POhdd(kYBsVq^O^Khli50&-%5i>uTx`y3(t`$NwN^wn2 zECQ+AzMHuxxf01Z*1*i%Si^CG~$=N`=@tuxQ0yeJSQd124u(dLy*cy+8qSWySD+!XAYuq0$ntk}K1C&OR+6{Vg4O{gD&xeP(3gri+1 ztJVTyrjZJTm3bgAQ3^OW_kjk;wqmF7&OF3dKB%i+dhTvb)ekqdn`Qh%!*dT0KdKCK zPD1AJV zsvU(nbY%ROFpXd-wZ)bbJhCgYm4rC z{b>H5W)Pk|9fu-#JfgCMHm4H1itUZocN9c+K4Fijz7J?LV!qL>rI-DYv`_J*C2nwA zg3fav5_?bXom7*8jEu0y3)tLue);s*RRJpsxFOht0-b(-sh>Z4OVCpRd;%DNf+4OI z)WW=!L|OpvBb}SxI{#4zz-q!_RU1F*a6^|Avj5imF}4D;_NQ+ZB<0hFLDAI@)8v7W zaG?6hIma|SWkhp}ot0N0MA=!d*eieyQfi;3mkGuF zQaAu(yR3H2P!4a4pKf*F{NVv@=jlWL^@GD#@C?Qx?%M=h#0D^)F67QzsH}*xqbv*ircA*TTP%tTWp%{{iR~+kVX~kPEtIgYdNhsTaYav&JbLL>VVdaGZN>Y);KpN zt?NAK%3Nf>KvZ~!R0!=F_#O7cJbUnznvFHI^1Ln!x>g^bd%`VRA9rulVjZO)4RD8- z7Xrl!c7&#%RR?!C#QGGXUdD>*_7u$>2y1?YAD*E5MKAkPc*#f)@w4N%o*GG9!Uidr zyLm=(r#Q~9i}pG)1;V%CmH8PA`NuB(v7p5W`5eCZz@uwbJK3=udg$n>Y}jKprK?nX z-yhiwmUOPo_fH0T&4D)~NJqQ%Zhl`fY=SCgZxb{?I&h*7cH{aoJF35RwTD~G@vX4h zw5+6bIp`J^wqS+jfmy01Fy+Lec)P_tDmnULIdJwj5ptbO4t^qv!#bK4klLrIm;S7M z{Ouo>jOezCLYt6bP&53WoQYmu5v`MB;Y+Rnh$0WBR#ixh4LrOeNYd^3Hr=r^II{<< z*tvV!wF%0!lI~BEP*5REZebQkb(%mj9N3Fs)B0R(d{vDMg(afmS}%Q!4Knslwl7Cm zXtA!lvM%|ReXceVut_PR?0A-fikIDwFtXMPpwkt?PCom~HcLQ8lEgPosQlBh(S8}> z9vp|0rLRK?TL6aYTH$Q&k7QJ}GJa3Z9i_VUg%B(<#S`cl6yk;F#SEzKE_s$_g7R>I zf7R)84GybrarUgFq#jEQX;0v3p&5)RB>p<9wLm7V1v1+X8gEaL#B^9k;|1=-@5Dlec?}mb*Qk&ocYm&l zKRm!DM_Cht4#KB^o~$2wms$K77iodtzkg33{m{!CP%?+%Zth4B#@mP01Oj4!!qs49 z_kkdd2)o{K2d3hmYdQ7H1xL9#FZ7I+tM{^yo!YA0#l>x>m7$IwUpZ7ud`e*WLr?|| z&&gk&Fo6#_l!%0RB(hk)uJNA-GeJGyezhaey2S`s<^o3)ZMZ{6Tu?Y{WK!zC8)KMGLi?pzHGlQi?C?qBv_KlY%TE$2&Dc>wx zoTe~G1c{&qcs!#s2{*4E$?&Y`)3j$j9qVt<^`~=_5S^RXPex+>>688}c!F~>AkEq>jq)esbX)-PBhp$b}DFSE?RX3s1xpF3p?66<-@!ZJ;e#D2GtQ zcM$1gfoMFn9MNqm#F}OhZ*3j(SY}z9L(1J#X70Gv*9wvDzJh5HYP#PF;~&di6j^ox zA;vW1*AM*jlX-}K#o#(ZxJjj+BXnf_7zatF?xJ6^`JsW z=Lz&4U)gBZRKJuR3tRxI}X_D?PJ>Wy%ejGrKw! zBv2{K4DJEk@%ZD!H*-+WCd7n_ojXCQS?T`>QuEl^hNzY=fq)mp4Ub z&+$aGC=KhEV~+>TFFbT6`n5-f&u9T7;P8XzZu~@Q{(QmEDvclu2=Gqs1+j!RkXCQ_ z@!!aWY!C>(@-|M1;SyZ~`+hB$rQ9D%G>8sN0n>`yJ3B~r50&c~tsL1)JUcB<=>4~3 z{AE2ic!#g$Mp%cp_%-9y)@N919&xwJ@F4LCQOlG4^{A*v37{0Itv&znEI`dcJ(egc}1VR9}1Xhvz%gx z!Bq6xc6D!-ERnMtA^Z(4;PB4I$g5l|zb@{Y3^*Mk2XB-9>4N+DxuUKZKrgk1;v`T- zkK%ODfCVVM$a{I0z7SFsBmz&NC4dpw|Tj+<6mH+Ec5}Wg>j)HGbmlpCa-8^cj(-A9XfCd#cgO>(6-?xYF0P6G_ zp5XGrvA0#-5sP92cAl$sXi`d7Xb zx(YD6Nqqz7`aT~*I%}wxeiW=q2@muD{ar(mXRx)OP%2W%BAOb=IE*&;O$7=pWCPUN zb8#|eY+ii&$gdaZ&!^{wJ4JT+(J`tU@V@-kON7%^I!=kSO-&7(FU=hB#Ud zkML-HU6ZDFbX=7OifC~}Bs9#={z!PxuZtf|*x1@#rr0J^j)e|^9{&@TKwt|tWqKPKsz`>O!>N=2}Y%sA&p8#^ow`?P0EP=2a2T zH@w~0b>-Qd?Y0EB*YI97YRXtyxbzRc`t=e74|F>Cww8q~t3;iT1fdIo;S>NO#m78= zkvn&6X%W zX1t8}7dzvuT+EG+Czvdss@$N&4XR%U;$Py8AHJUqK;vP(__ zFNJ53WmN?yCA(I|y`AT7v%6?>CvtQ;=8A$+W?;{KbD9z5v&=*7T?Ema7l)L>%RhkR zalCeIM~<%^(lWMtb&Z9X_Yu#}j?F!Gs3UYb7YArP%e>?dg z?oTbXry~qd!#`9~be4JPBhd8Y?#<{qaV=FfX6ufkvV*d z>P<6gkEdImob}j_XPf?dmem_W9m>=D(DLHuW6`iITgV)PF?(xRKo+3*?n$^|^lWCs z5UhX{SzGMY4{V^-?E?H#BTYElW}vtYlp#-Xu(f_B!T)+-jFKqU%Sg)2kX;5aZd&Ym zd2;vfV-8^M*Wr?J%n2WO3*o%;d9A`XBh*rr-;;7)JGEF|NfH32W#09lq(hkuVNz|s zr{OV&QhRYpSRylVPF+y-L`i!_K|&LO1>5kJ^s?EX^ns;N5s~}ubbNc;o_FcpVLtos z+0)T4%jIXaGmBGF!^|CQwQUtv-E4bKatIbS&CP8!{mun&PTIV7A8esuam%B@ z84S_L7gqr%8vOdD;c4Hrz0j|9#?PbX41p^+ZVYhRr%ms%Yv=p8cysRKy|?WOciz^3 z73bR}F9b@s55jJq13#W4mZgC4xKAaB@nKOz73ATn4{YrjUT=1RXy2s>on4;yW==XdpwELJWXoeIS-kz~vQUI;@#{(Wv$G&5@ko1= z+P4RNmu$t$TabIE*%~K=*vc-kKiK_H(!CcrsN8)GA_Lb@#z@)vu3D!h6z%GO!tGT; zN#i7`chCx|c_+^t)B}|X!bORgP`~lGucJ8b45dT~-y5BiUT004vmpqyc*e}rh)J^x zl)7ZsA-A`Mdmx^SMX=EDOSR^@zu%^P>V^O;x<}MxPz_&)D*+W#a8wZZ8-fEza zDArl6dLsSh5UWLegOry1VGKX!5*1%2gmSz2@Bv??+MA}>{_mJ%O}Ga}KkZysk*&TJ z9CawcZlS&b#fD*5VEO?K*{*1g3VkAG!tZMUa>a!wPv~X(Kr=J8BW5uI6XgY`io5&} z{I*v_B84Jc!Z;|mHH9giv|cIF?5%D#FC*rg{a7ue$+}IjJe~gJ6@VLroymDTEo8i8 zini47V^g>gOgL{9AM3kBcIxEy%k4>fnv370OWUbVl~!{2I34Z!Q_aPVY}1Ku6gD=_ zzDtBD?|Yp=7`o^&-@>lC%dTI3ci}SqPPl=z+~{*)yY=Z!Y}wR>E{v}B5PVd^-W*Yp zlVoOtLxsgSCucR|uXnPiEdBEt150ML8HJ{V)hIox*OJn zPH!~4K(MMhzQixAm&0EsWU%*z z@?LpHt8A|H^30IB3A4^s|D-cvq4~W}=6u;q8jjQN#xKshP3*;R-!%Pj@#cr9iz}s@ z-)ow82AbCInNHlwoOIFCa5ke$-&)$o>a6`(Rx_&C_2gm=P!g^te~WL9?JDfsKdO1J zDNgowL$kgW*?vNTUw+iz!yFGb**k6Ai_diN768r3JfBQkLbT~t=v@L^QGwhAn!)Z_Zcp69V~l^<9Rd_v@4Njh)2_Om{bOycL+d7b*Cr=+X{xk(U>N16;8^9tn$aXpA6(7_<09P>(gliY*kwV6+daK8oDE z05+em&k%;LJG?D2#Lk)*Vxm6Xh{Id8sjaVL$oiSmMXV(&^}JJcPWt>_-Y)$o%sH(; zy;t~vKHU3p>aXLUyH>gdUEAEtr}DVsI6STSp;@)17g|$jwnJc_6__WQ%4;Wd(PC(+|MnyJGEN5cJ*VBb?dj^Khqqb0Y|oSG1;9haFwn}X@qQRUYfip->6=?3CC5(=BXk;$Dy=vKA=)Sl6 zaM7D5#HX&_4`t__EEjg4u1AoO+L0w|=!22dW$oErw)m61^gmH%a7qw!$(QnT2pZPF6LYKPXVwjhf-NZJyW^`8+dV7a^e9*y| zO02nftsXtaH?r#vjMqMxkE&oT(Fh{@P~^h2z=u;`ZQGw&U}e3$WLRi5*cUlxlOdzA zmUpjfc(cy<#!L+$ZVuHsC+7~1{@jSa?@lRi4=m%WcDF}FtCzn)Ynh@skFY4MMk$FJ zx_LxHFB)+0e@xCzD<{TKJ6ve<%zwgIHbFoEvN(a=7y=%|3qGM+&4(V5%a?$60U!7A zsMqzkNn_$fTo(eo$#KoJ`Eoh|H=28VVTh~ocAQg}mUAtInI^z92j-^_gbW~A-ozlx zqq`a0cej}zzI*XVCFIFIY+T}OK)40u<6QmLnI%OG(54J8 z-nmN{m~(JfFGZfR`_RM0Rj5IowkGZCBRKV6s>m+-|7G|5=a-`4M3o{uaJx-zRW07v zzfUdQib5vI_{i|yRdnQ<$aJd#>S6=!qM@4rLM#UFuC#a>!UXL&la;R&zWXN_1;l1G zoV|Pgn9#RiR->!aE$HqP*msU}R_=lDJ@T)iHoKPB9;Tc~Zx36sDQDHX*ko$rDnC;R zGk7??7PPS~)e*gP&J9SkQlY54bm4J|@ORWBj7NAQp9xTzy_kqEX1C*0)O26kQ zb5Tj@vM!J-IeXprw)A!0x-Jvejj)vhj~VrwycP9RaGKpzipL{;Dcd##rO@PIyofYdeoo7_6JTCO65)$#1IY}49@|jdtT#!>=#o(ua?`kQaEsU)@HPjEaRRFi zZ->KGKIZckl_9JRHW{88WIe7pD+h;zLf%Ci*ZwO z$VGU6L^imYvZ|$p;#Jqg-JVJHuw4Ly-8@)s9lrH~m!i9Ic3CFwXEB|K*U#9Xmv(p0 z)V5${3@my*>~_bskyy4qth~1_&2e1u26AM(6`msQswsTI)+kyDz>^o~$fH%zl)%~^UP z89%=U+_AWbz?|mOSAhirjkbr!_kEM>;^Mi5SUr?0&|O{h)CQg&k}+f>@i~);=mc+# z1=PoHk&AJ`V7B3XRvOVRjtAEfrs}^`Ly!<+cqF6?7%LV4H`*T+n*i>_Vh1%YJ-h zVF|XI++SIH3BwXz+aW>J3hVBXCsZN(Yj3_Im#D4QcoIhg#O)@R>9j9Et;-#6&XY;M zeMk=P?}s1!j+8kDYZZXw4;!{zJT309qW9~QFOKC^2aSi7eA~Y8T@CIeqONXIHfp4- zSlM{MQ(G19MTJkty0^7hu_$i%z5LZVC}l*D68dpRgLkKW@x7F zjV8UWoCe;D3^%3M>*$h^M4xDba96d5KP%7MJK9&BKufqI4SZ8K53KrZ`($reEr8^Gw9O{0`NA zvg#COm1MqA5-%Qcv%_IrH41!RyyoGebx5KibT%{=T1nZQJfEeykCvxKmv4+foaXup zz7pANhDKK0mIz^N=t1t6Qax>;Khw$W&BeSDmUeFs68?M6PQZy6gH_svFchFRbq~{9X_fel=?0CPsQmU z$Dc9b{<|juXK*n%cUK)t<1-%3>=t{`z~{Txa4$LUzkQFcatR=yV;5Bd>80AwreOz9 zi^SL-rJ|_vjUyb8dQO|QeEMDyT&ZS+VKr2ygNGJ-)29RI-0<9vS`+dQxIupN6bv|vEKY3XYONcfo~AsYYuV+oaUfq zf~Z>wB~Rt~8%Wu;Llg2-+}jQ>*-1ayK^6T1dyO?8mG8AH`Hz-eI1fa*Y{N7+_BmG% zqFR%+`BmM8;iO?*%8{r#f`MCi#^Pl@F{YgG`|sE2DMD&Ik*E=&ljqEX@tA7N9(dq! zQ}m8C?4sVHgzbA=NG#=^G}vwhX%doP4zJN=x1Qyx(g1eFmzn!+{HkP?W^3@21on=p zVN{cOzWU~kKg)t0*V>tWnU}*}U5`~OC6nFFQ2fh>yX-v5B@Rz*9L8Dn3nMztC7+qHT@8lj!({8A6Xug4H>#}prAVg z|BI@M%Ivh(2d+j*+9zNA2YvAA50C}&bM{kI^ToKujYiV>5#{J)KlkTFgq60WYsnn$ z;dzp$Z`HI6pRMqi2MLEXjp@6#!wRc;xChmp&2=XTf2|oY2I!sFR&RBsat2%Br^s~4)nPm&k>i#z4 zD}QfF;de&dvFZsFJm`eU0;t7nw9(jM#eVeN@*xFqCCdX{L(o1Eo{_B``k|BGWD0L% zmIP5adXqV6Y@pbf-vN zA-mpnyweLO&(|gbzRf^)Ek7~nBEyW)+lMfmZQ@@`OlrOsF%kG=+k-{@Jx<+s&WLeo zhZEZ6e|>v3522dP86{sY8wsX85HSp8KLz6eE^n@r5`T!bP7fRvlZ~>;rl&5u!z;0U zPC-vDI;ohkDuLdB8IB zAz!W|bpG9NWl#}J(nuhH2-vof5R1&kXuL9q=KqLu3S8l_Yt@(PmtW+TRegh@zY{$Z zfZWrK*6l|LPka{I)CR=w_`Tl6>GNGmmaF3F#HiV+;%$M+Jh`5;ukf z=S0ng2X?bSp_S*x<|!r`kQ||T2$ig|orUyfECkZy^?U==!dX6;bO5@CiULr`X@b{e z43(etX24}?VV=0=Zr}NE3=wHz;DnmL`Grsb=vQ`5`0S zz7gs(?<-u`_RNG~IB!>dW)5j2##wj9xo*Xl6PTizL;*CClQE(#wtUkBAvAHD;Dk6< z`|gEg!+u-Yim4`n@QWY2I7_}Jh)h3vGgkR7b(&)Pt+jd84ws9&1n;KAnMuyG;Qg)8 z2UVDLD8V4iTDR`o%>mfp>|SU)ym0E_oZQCO@dIN#oZ_yGajpr^$h1E6=(G|vZ=9{z z*x(96Lpz>Wa;;%<)|eiA4r4F6G}5sFS})%ATTjkVU0_%FYZHt>CTdEorTrn4vCRwQ z!h!IoR-5d{TRW7Lxb^B7%>iMGIza*WOh-gcXf=49oj+veAp)kNh}}+e|Ld!R9$EhF zVQ~oT+b|Y<_s9tVyEhrT-}|AeIv5^?pYV`G@<_M)xenjDHQV9S4(j8rwuWl`F8Oz_ z_$RxHuw!zcIJFk`3EfGu=*+VzBnoQD``G)j{gc-53+25xoImHxI2%_w95-rf|Le&^ zZHmfYipKAYQ!wDPtLC7+xFgZUo~wc8O2{ivn(TOs6qYee5vu)swgX=S4%F)#Cy3ZZ ztf`TNmpz=Iqk{K2<&l8VnPSGhBz-*L8>-(0$v2BXcZIko&>)^_Z2xHS~M|{trgirJz z8tnobDt0%UO#Cl@c^I;c<~wa{mu&tExQEWs!x$J|7mdTSq}Rh{XjeWD|-4 zXsb%+=1%fj9}e*4G=VCY$Nl5!IuJteeheRx z$cr+ST(tHqPXnta=hwo$9CHAGZ1ya)>TBOybwSTRCV%m~wb|MJJ$H#*yT|P+B@WMz zIDY2V+QiYl5g{B6s+t(K_?Ok zk@Iu>-o}?|=Y2_BZ-!T*;4NFA6Lb|V8cO2R zzJhd^^PTPf`OpCB;nvZa;MCs;KfMxhuclX$wD6O($Yve&*#RxH*m0f!!|aq(46|%N znCL%{`)t(lORIeyCE1fpOK*K;lfE!0W%R%XoxyS)AYflRV=K>wORDw0-lfc;Bv)!wSsW9NnJ!;$OO!pYXaq8Ql_$xl*@;QgH zkgjjE^MmAwsz4`B-HjZbnk#=hEvfO)b>f{p=EQ_0PC>|~wE3i2CvMQ8i5&#jK8|7c zzin1ByTE`6Yg4z-I*OH&z?yH0$*}Si7cJi+6awomF;};7NS`kELFkMDcn?QgNovXR zn0q(gAhl>Ek5|S8)t-x7{GEl107>b*e1}4kR6ksH6N`~C=?e3p@A5iSFPsVHoa`$aI)7U+?6SYB~FXji~zkwAsXLE~)o|83BJ@pW* zxvmLiFS-RjXo#tE=Qh#_)9q_t5#biz?;+qkXLpai4@6_PZg7NP=$_6tOTFoP9RDFF zjA%H&qR<-0_l5P-l^DAWgH&aU>dBXGt_>5(HjTXgJ=)PqQU_6w*G9EN*uXuPFheD~HDY~t*?~5#lZX9_MD=SS zl6O#Xp>N54`Oo~DWs!1WqyEXhks{|kogT;e*7ZuK z_3SuC8rk`a+ziqUwuSD*bq~#%$G2wR#&xJd#3;DyVbn1+Hs*deYZ=$8x#XFF*k8~E zITTCOd-}?#(h*VO;T$ZqQHL=*^d53!Arb#Po0sE*r9NN|ew45Hl=aPSe}1ed+#IP& zcfJviD4#y9x{e|euOMQVX#OE0kNJwUmaK(wv8INTjrB2V-h0;0{{&{~NxBphm4 zGvGGz6;(ImR~IAwB7pi83D&0k$DOL^7=+I`H^BX~vbw1xUIAtGC;$P4KnGj-j=*13~K*gl`~s z2i(Q5UOlE}NjYJ<5b%mnp2VmP8Je?y+-z$PK~bQ#PghKDp8y@TL#*sp>eBsiS>PsE z8#a<2ayR;eD4)}F%s#)yH5nl{LKAQV+N{Z@{CAmy55}tyu)^^`EnIXO_sXGF8yva` ze?fKY0p17UlyNH1?(3_pDX?aDLWi~M3blh1j)@2+?{!4tSwm1Uov3+)E4~d>ISo0)7Xfxu+^`t!2|k~((6?65rR*lui_ePr2N(RSNIdohLp zNgT*NO>gq_t1&#V??ShqkR+L=rFPm9H=OmU0|$y_umQetNBDDMv;*3yg=~hH_7n>` z5|`nLq-gzUMDUXL0Bi)^1c-S04W&v0^Tx)xo&kbBKg1`LoCb1K(-d!!$!T# ze(o+&18LAAMAJ*`<0D`vJ>6ai!zjqp!>5&YVRD%%FGnNjLf?V9xcQYPGC9wIz8gTz zWfZk6VxN+6BZ_DRuo;(miB&+}PWQ={c*<;*nQrut3oeZ``5)qsdd-WcT&W<*;NL#- zF`!F3%Y$K*`!>1E@!kiA?J>nGsqv2zzm2>#7{l-Al=&kY3M?m6KM!e$A4NR^2VO%) z?DVjd1oPXGeF7Y@_QvPo7v}1g53$fv)>#z<~VRY!i~$ zu28QE-^*|3R-)7H-Hb>l>(6j*#;^2PGLXOxxh9EvXQf;=qyC-kBKb#FJiv3daAX#%-icu|Z>NXEj!2-}zJX;MF;G{p zR5t_!)T$Rr;F<8pSN~@^s4j@|Km3v3LmNxVo^)KuYy$hC-aU~70h8+2KRo@84sH%- z_I@&pyOL|YuI~;4I_!N`CU(4d>-Endy5Nl?KSaQGxde+NvKi5R4y*yoq$jOe$Ggey zWWZkwGdr?ss$@$}ob}y#lJr>i?e&ABy$6lyiy_vv{-(^|9=;{+cWExM?q>A6dV-LU zlSQ-eXNREG8uzOOf0)iQxuUYAf~xP8lwVtOjjO2ne&UT}^zbei7j_Vw>>3P4L6=BX z%{-!6k-gP^62nMlIc$Li)rE9|<|ejNU!3R|r?X3+zVO4E*>C3&CB+XF^N6g@Ybv?< zmoq8WX`9O|a6f>+@)TS&lmbRd*EH}Dqnz?he%+? z=0VU@Y!-viG^c%9SL(OT7WXwZ=bjDIIeaI~<)PG&3MxP0fPf@DiUu(3ZqY;*x^fqK zBOUD^YLy@bsF~ONam1mWvdL?-dEfd1NnocjQ6QqQ(Lc3Th1lUQMe#e2fL*nzkygk} z(2jZrNw%-Al6tFR346ZP;I6r9x|R0!p`;#o$=Y~-d75vMRA^3>Y9M&+U!d&IRNxlY zn&ng@%Q4~>+;SLo>J46{7x=@Xmk~E4&~>PqaL6(5v(lzDoV&+Qw@!N^?hO+&;R21b za0f(edK>OosRi0S$nn3nQpQr1O{uZ9oWby+#R!lo*x0*Y7r8bSlaONen(>9cAY~)I z96xGvj$6Zb{LrMn8^5E{Z|{6(Sm^VM9`h$PhwwA71)n9dX|cCIzL;k>eeUx0s;}CT zThHq6$4@7G8!zQJX>^-7A0hTm`s>vG+K#I?XZ#zaX9 zL@q5zo#erBpIRv-RO!?h-pCY2ngfu791%v800S~Z!gZOfR=})o1ag`=K@@m4I6|>h z4%A&{VW5x{Y@XAiu!%|(H3<`A$TJDK)qh@494?$2;27;1^a>ChrfDh_p0JI<@gBtf z0e^r?JN;9tJd^_0V?Nu&7xle9`=9lN%h`a32z_K6`#BsKp=;R}m)ES-Hf%(yny zDY<*3M(a=QlSVYM(ai`2jjsvm5rjQd@;}CU)&uL6UiUYE14tfd__s!oBYn-Yqdh$N9)L^k3vld3Lw4#mFUO8UhA_C&(`f&bRBXLE^po-dhemsgC`5PrwW%9oPw z;&!mn@MisNv!vEXP*>vYH#(m(%3F|DCnSd!I%}I|4{`o{wQ(v~7bxQp>fEJ1R)v5i zokl&y3<3q(ff~@z&z$_cW)f|82a7kZGaH&Ef?k+k^`D!yZb)W6j-Lx!%!=^8^)d3; zCq!I77`*@ZwbC>zE6(tfEWh2Sg(fv`c_#Z)lT;SR(j3evbaxidO5H-SH>YhozBivq zK$Bn8W4mPqW%-I17X}@G`yL;5g2gPF%1j5;-#3-1MhB23=O*-T#AeI!c^v{<#t5-?aA7JmEMc1i*Rb_)O`Ms?E$~>SpG~{T6MX!5&4_#{ zuUmiU8MTA$Gmmy3oue9P5%$N|T#;2@6NUk&+j83m&}k?G&ytt2b4&}_QG$2w2mWj{ z90SPcofnxtYTwWWqaB+xn|pwaGQRK&bWS{Y_q(*IH7u0B_zR*VP@onlsy+5E z;75BKMi6f|`PBY%)7r}VwPwN|*-z{A zq!Zv=L+=tJbF6MILDNK47)5b>+rrP3KGi~tG*#L)V-eF`UM7NikQsZz_|5RI z1UNF)mS52wi-CH@{wHN&TXq!eP5Gw$AS5^9dG4$S!b=KrBisAt3ZC5_5{7LCDY>-Q zL+(1ylr%2C=uKCRS*i`KaBeQ)y4P^*BLl87A;r&d+IcE)lc1AK5Am13?o&kR6{8-S z>m0Td)qVC+(X1qs3)#%0_e89em%?LYw>p<-Gar8hB&X=hg=+?Y0;TvgQ`)HTu_%3- zV{9ptUTFSa&h5kYn)L(*-2jFLPLQ7E9c5;`?jY>jA5WYFzl?-CEJ1|gLuX6L5`05M zTJ@rb3yeg!qv?d1f&?1@wzzzq5wG-uX#1iUU!cI76N&<@hO`56w5V$I2-R1h&m7C4Qd^PZ71@~cp=mE*nFMj!&%R8nN#C=(y& zrWR5fy)>SZu6v=?1o@W6Dh8V>dHf;hCuLn*$N3*-6Vov8H1qOxk=j*v9?QlfyXx{L z*?3cdLu7wPzdhl*h%JA5;AWR`>YPj&q z;*P6HZYcrY$5cMOW6GGh?J^Xa_5U5(cCglt$K4I+#Y9KKH|oHQQoNr!5&tue1Gd4xd#@huoRBWB|c+at1D=F;gU%G8X32?lTRJ8m1s zej?H3`(4OKBq-d*Mw__F0j_+Vs_1Nu0jE8t(TiJQku2As!!PI+#O*vYmWZbEn;qqj zo$An6! zRJiz}m#i{1U1bKyg^MoBZWP6*aa##RFIfb!butVA4JSn)+OwBZQvj3BsG*ME0LxW3 zIYNP4Ss(q)rcWl(2aG&1gH9KX*MHmiSog%Q_2XCIXw@roa+Pkep=V{Wd>L9Qqh%$c}LkqK-Hh6NnHugKOBp_c`S zjQHHLuhA@$4!qJJYpzeZ$v^s4@lwT|u*fl}FgchpY*;iKWQXtkFG~I=T)?t`)k)+J zocQXu$xSGcbDQaa@$k0KO;eD{W|LbZbJ%T|W&@97_$F21+sOn>2PR$4yV@R2hYVA3 zFHFJp?oAZ4l75^Y3XXu}p53O1WGAC$y~bXnTKt%c zW%kV21Lg@tu7joDG&~dWPQ9|pL-H{(PoEG+bZ4I?$}j($4H;udbRmEKP$}Vp=u?j2<9!-NHviMYV7T7m?0@DNUzYH)S;Qqi1yZ1 z2_T#ga}<)Euj?iG7@P*;1u610yQH^s(`o#-QMgAxI`BJ&>NY$(gIyQ99H2K-d@@Bv z(Eh~1lQ&fpmF|&Wjcd7dUw%98-DblyZZDm)%F%Tt^LjqC2Dq1!<~YiIe!ak64l+Uv zI$sz|ei}`NnN|xzMM-Y9Zz*2r^AXuR4(ikbttNPp&6hS<-Kd>9U(X9!s>_??-)=qy zj3r|No1|_Idb;F0bp@7YwdyDllr+p4C;KE`aUtvtL8l>~qWA)3H(9=yjVyk(ML#Wn z*GL5vgdI^tR?|a1&~pRSCLEJE2pf&}nk?Hg2`AK=XV%ODER%}HD7?v>a71>$4F%{D z>7`G0CM^_Z9B|T~*p^QkoNH*mk)*)6!C>^-@Wo}zlLjb}b~fh@%6V+JHNvB!nuYrT zsr;hy5553rrvI`W?ZLfUD5ZP&e zM8Wp*h;?iQjBoGT@#mOr(gLcm38I^QiFAZ>90k zD|=!u0M<&JVtULQCS^NKy*d(dqjhTR8oPd=#ys|{i_-DvXb0PkXFCfyWzbi%q0h$j z-Wqw+!C-wf)(FKzf$Re(H;vXnZ(|*9CO#__3YXpcWxv236nR8w0KbVRH>ncfNEsuM z0oW)SnVeP@PHN$EmEN4fEz=vVx)FJwI(qO_(>%Hhtxfb@oze_6p9c`F>m#GvNGJ;f zqK^@vc$sn{>})jgB&HrlW_pm!kaZT!S# zWy**I>PoXA>zK2z!jJWqL51FjNXSzz(OH^5vLw+{1>`yWyBL_Ufq5*IdSg5 zkf0N<)gD?Yo%4t%Q}U&@eNNqX&5BNN_a!6(rr1@pYFzREzM@tzeYr$y*h1Ggl9lY8ue|VkKVppWAE@|--8Ti$JzX>5VY*Dk|9Mzyxh}9GD zWHI|XGgZ7i{li2*<}T0rA8s%sg3}KSX-YhrQ2|6Q$1!N9`HeB?j4FeI&+hx~?yVDc z?i;mLUxqYX_gQtdKT80+p+fsv^dTGJ1YF$d*|ET>uZgxmbAj^gyrJc#Twf~_Wus+H z=ScO1;8(3h^vM=$hX{>`eyj;ey;TS;fjFS-iDO@ooqji7eK&>d7dr#WHu{Gveg=3d0`P;UC+)NGP>Vh zaC5zKHRQ(YFwkaT_PjJWcC-BCSLt>RCFO$GA8u@qCvKq&UiPdXxL5WM_1qqPO3j=$ z>nh_c@Jk27f*rU_6-SPDRzdl;BS;7W-$s92Pts6}Q}w(OqSq7_7s+o6^X4UI#(05J z0M#(v{8WpPEnz1Q=OoDTBz)jxVj4{}_l0{T`bs7RL|c<->uFQ44g=UfAyzkux5+|3 z1~iN7DtB`0>kxorWd&DqmE2YeoYl>bPBKLos zN0n~++;)$K9d1AY@(DhB2maq_?%$a-zdm<1Ve!y+DWw3T+Zf0~`UURDL_EdG8%a0M zl2P;K(4a(=tz|-tN~}Wpj1up!zYYtR$kgMCz_ojd|LWGU(5uUE8g7oZb5KVeDu37+ zW#DGm>q+_E=kK1@e!jqXPurl_{qra3zPWoa6#|&yeR($D)TMIvP8hTRo2{JBtv#rm z;8(Z~;fTvXl_LFxFjD4~>hr0mnqV?1nP?bvN}_7H@~~v)$;frR5Yv1HRufGQj8Sm0 zGp!VhW+4qReM+~DZL$Xqgdee-8#KcQ#liG+ak7ZxCS@u#&v?%7ZGuy0^|CeXWBIP2 z-iERxKRvotb_yk#E!a`U@TE<=^p$P)wpU5(7MM*?rKg=jPXM7FjR`HeQjC{j|H(!| z)-W*r9E(XFXazit0Go^Dc~tg$SkE&_vaC0@AV4gl(kdns*qH)E$q>jB%b=PhsS^W9 z>=O9rce;?}tut}DbtW0WJiPRmvcjgrTUqx;zW}3iTZK?*%X^|LzuGmqW4Pe>I~UQh zQRN4pTCJCyd{t}D-I=vi>FUllIL$lsT;&&Su~i7!mc$H_uWep8XF}8V@;4dLXb1b! zgg1@c9DBgzF^NDSF!K*C3iiK`E&^<%BJ`5T5#FaN_ zR+5!q??gnvo+A5*Wy6jUG0{L|70!5cGfdvg!k0Zab7JLOQ3{7KNa=0>)+-IPtZkTM z+IICUw3lGO!c5G((pDUCF@}r8i(BcsZVoFU)_ny=GTJ(BzaC9p5jD!of~Z`8oztyH zntYspXuL@bVn~K*72`P^#}k(w^F1|To9TJD2H#ckttgYkBJ#Pd27j8tM#w$|IZ-hDiVlzqrsfX2Ud}9l1h9) z<7P@7hPb|T=jIO72gZi9GG@9jG41cI#)V(L?wdv#JKz66LiU5*m@st4KUi;%NN;K9-Hq2j zBWR^k@Z!5i9r`!MNv4BUs;{8RH6dctT^(Jma)(M-w4>#@Flp0Xy}gErM4&%bbAWJ%mccCEGa8sNj-2O` z@Z39UUX7(PKjsJL7CCN1_N%tQ7g8glFAP|I6wc&oRc;ad8BEYV^sN1iagSZHfb8P6 z&4iNJ(&Iw%r#ED95uZ4BjUAPyek^=^i#f%3aEq~U#9mCqg~Q_)Z2o7&`{To?W(AJW$Y5=80#XRE3ysZN z-p4V8AXX+Lk7tZpu0|9sBfT#pB5;T#)5X3+^zuAQmYLz!FBPUvsKg&K(tTr{gT>km z7;rV`(?r_N$BRL|zldj>RGF(hr>Dj^k7d+E*9p544L`tbw4SUr-iAL3ahjW{3?pIyHg(6n@EHs^XSe{1Wp}7K)0wur7qXN@=`wT`}2s%yUitm3as?gjR zOzyhIt}rs5H&5@8B6iB9hY;V@v~D2cAduIBqx$?Z(4Gk%l(0;^>{M=7ssqBtJ8-+P zg$u@&bXTx;S!DZE6t0#GLqaIm+TxeNO4qly#&`RI;)n?@6)lUzBp0}Ony~r2XR46% zoKxzqPIna7dDi&-W?ILeXY2)5=@o?qn+jtXzM}NL*iwmInl|kjS!jGRQOStIi+WqE zvkczLC6I_GP+4&oIn*??k#T--e|KK+9qnj0SvqUNZRjZxojvaBO1uw=hB1h*P~)y3 zZlc4WrKP)xA2D@5r9l7G9SKMj%j%-hCgCm7{HADZ+j_jY&XM*rT<7o4iTGl}k^1BT z=5p0yiP+1Kjf;!i12t4Pm_*FRfQMNOF_X-Q=gP$AkgE~PcxD>Uzs{#Ql~@USp9m6L zfiOQy0_?<*&fYBuO)r<-8xOV~(5LV_m<>t!@4<^hd}>DHgheLw&Xj@2bCFPMM5;*K zV-M~@GpK(HA$io~6Rw~M)M8QCTmWJLN>)?-9)8^5R?g z5p5c7#7AzoV~9@z!fp2ENi>+XWH?yIRXU|A|M@dtp*8olJ!qMfT%zn4e`&uOZqob) zn-EyQfHSwwQ%H>9Tn=&xI%pga5ad3An|RHF*fD^(c)?ThO86gl^-QvYCt>GQsbve! z&-pbQeG*Tt*c4{qwk`uVu)M3`lK5|EjEdNdfXeIyZttGZM9;s9XliTUrZ$D)ErC~h zq%;QI2GOPNkMjN~X~dhhKngO(O2np%u9s}+u`S+q=akC5>di6eYTtkygMi@>p(Pwk zve+n1_Id&Atr|f$S02st3aWcxl*s79kCMW2gjVe559b-VAy5lInv>1>*pn?T5^LY6 zbH7Dh{a)nj!T&5;6)MSC=rKvFB4$W!(5_Q~Fwv)6wH+b4T4ws*NJm9?f_-6#W=%)G}nzmX*c zb<{cwi?tPADwj^?a;Z(cX%xR6dWeniI2&t-W|C>X@@>fn!q#Dg_gJcD;0`H4QY%2C z3t+QryQ>cIqIf~|8s8S(dl>?&yHlqDxcjjv?NHsI>#Y01UT_;4-H2YR7;)5ykw3h} z9g`!&oqeXeD{&nlqqO0mo{#THw{g+zdw}uX)pAB!?$$c(LjAFXg4M6Shp(Mv2h|-I zTMT$K)gfJXWE0b74cBxuH79?Xs|UPDBo)!M+gxCeI$`t~ES4BL#knzzR6Q?tK&Gaw z1UJuBo~L*5&=`SJ{OChgPL7@+;@4!qBj_I?;MXsWR0AlaW!AooOSsm^FlEaC70cjZ z0G41{{n;yxd(gu>G^r4o)8*_hupT_)Ufz7^xy{zaw;zry=pDC5r^9_q*RZrJ^Z|;g z95P7#i|5O79WPFnNcaQ7Nj-P7``3RcjRCykCm#xi5;fbfZZLDOrfL71vf&xen01j7!J)Ruj&8%WTWJXktUrN=pDR%bgF+M*ih;i~2GlUN zlfRcm9Tt&4r0|h43q|1jQb_%i1%|Ze#3||D{|4?p&a24ejO4kbU%GZQBT`GmRH#w}Mqp)k zDK4xkE0#v65B`aW|IY^&tUz-+U-WaX^Tp7a$Lq>B+1N0x>Go-hiFNQ38X@$o`rzd4 zbi-sow3b`#>A61sT6^U0oy!$(q%$?)-Fo1^w`qTF*j z+~SBEf@376u1*~*{Y>hAjRbz7p$c1+I}S_Kz;TvbOpHt9)h*4vqFT=K5Uq8Nh)q=K+!Q>aa#nY!N{|YCP>m!Iu5!@?U$*R!R{W)F@(0sjL zUC~Y}D0yszor$?2>4P=ozmIt|tg2Xg`qc&f|6ak)X)K;gHP_xMOS^xv=u9?n8g6># z`3Vgy%>$CT&2*%Y5VB6=Y)WT zPLmBEz|6o7oB%zIy1=>4So&yxBQfFbFM`Ip0-T#$BiMasv4Zf>9E53&eE41N*Z!Y1 z`$jRcGnyZE%W*YtQc;oT-IEgFg%`W0g#^6s*d58)x~kYKR?FpeFJrzm1~Nz6VXD(b zf34OZ7dk9T06&Jrd3|jX6kVUP2Bv&yBbYV!kGr{Zu%S-f8{si*$1?NFA!Vwd7k5Ok?C zX8P9&_`SZr_csYEl#L{#>H_R`6rIuhXuk^-3G=-hs?Yzk{#Iu~J!ss0Yr{BRf0z;% zC3xvY!=T^+`horu`106FugS)?=Ua(<}Y!}r_y z4e~jS9Pf~Se?Oo*SX5~g+Vy?2s=1k!Vz}SHus4n)?bnqZ7fk)^;%M@7exvQ>CtSyc zvL=t)7>wlNBs!X|d+7B^)6owaU+z)8%-|$eX#2h=Hs#Tc z;J(`qE}C>dpgvgSENm2dvt4lScf5@|Kwj9Pta>LMu<7H*sa@VuB&aA;l?Glf_6RPd zU;ZR7ZC~Fsw5XXS%Or^X7qbYCzG83rGABu{%5XbMKeJFH8y) z@B8mF8GdQXiK)!E^xP<4jXCzPqnTe23oFau=snk97W#L-8;-soWD!jsO?w(GHun2x9KA88LvMYz+!WQ*{Jnwx@buxBBZ3sT(ZkZ5YE0+(#`>Rek2QLI<4Ah-Nnr(3yrv1gH&?EcEzg=* zV3XW;Y5Cg=A@HV?ep6`DXuf;!cJ=b6IcoRd&cLM5hsLEt+50*!+5UbxMmb0`_-8n( zLrP#XPqwB7Rt%#cC&Q4>=Opiy9B6IQ)ApH@P|0IRJ)94?hk0gq63f^B%bxyZ)*FAb z&AseNnu7-ABd<5BQGVu|dlWyP_GsYQNUWx#PR+N z!(sGOzUt6QkLSIktbP2d#_7tFdi^?mN2f4Mvp(%A4|BgcTKlwje!KBamcTW@seaxA z>nd<9?u?Q4sbXCqlPtE2^}W5<*M210!oko(^z6%j3e_NDvz$Q9I;JCc67@L6`HftM z#Ex$xka^u4%h0Iu6fpc3X2aruC^jnU#O~weM!xEfoOK$^#kW7hb-$e=Mny^E{}Ey- zV2MO2+*opo9iL4b^lje0GJZ{Z-B8rw-kQT3)L%K>A1TC47DV#(Mz#Bv32+lETT{ev ze(uV(`OktjLLr^Z(B}CvQ*B4y*n7z|z5Vk!Wgeh(OE3^QY-dXX^+r|T03};RM<9S}i!%=)^ z#ENoJXE7M<;9!Vq=^IS?_cug-hXo&B#!|;nXel{_FZOy@{s^ylYuJd2r=C0RljQ$+ znASL072%MlManD&SR(g*wLlH=HDs6kpA_3aVaiUt!0(kGZ(q4V?_e$Z_I!+7Wk!YD zObLMjtJ(|wsDEGk5#|Wox%%;{t;RVPcI4SL-zKW|{6D5rk{qX+xD3sg9AGj9L%*P0 z-e$3^<3WMBkCtlLpO5h82X$lkyE(rOIZUsgW0C#2F2f(**Zn{1@&j+V)N}~q^C|j! zK2fo*ZOH`*#Fb4$Lu0C5A@~3NLL(Fw$l-Wyj6Aa=R~HQ||M^P$B0PSb-GBd6fr}#5 zUKBzCb|nj?n#OXGP-Rrct!1>dR0&P?=)d3U94!(cQVZWJ!iKq87ONq7kJ9ss!>@0r zj)OuRj}S9jd2o)c$cZ`A4SqMr2j7x1oLx%yE{rG=8wSo-gLn>?kCFTMB-mMy0 z3(}FQ5Ri7rKY7}Lx7bfjEpD=tl7Y4PY(f?&$r@+8C5+!OgHAk6{QI7d z2s$?N0%pjJBaXlz)K+8ALx5Z0Srq6#Qe^d3@)7r3HbmwLT&SCD^!G;^@&dpZ(d$(_ z|Bt=F;($j~@d!{prtw5EOs*-OzQP*H*uhd`d`a)~M*n&$7COXGfT*@WtX($H`R8`q zD}0Cbo6N(4jnQgt?)yC%1SsvG(X$1k&!7G(HYA90;^9|-zHI@(EeD$ZDqavW_YDd| zhV|QsLJKGm-HLf`KY41uACW~6kH2aj?r-!12AYk?VGZ}H6>S;Mq^BIdbt~};zqqG= zPu48BFw**gDS(M;`uS|Z=igBM@pmy|!B3d&J`WSysW(8<5*(?7C^hX@|^`tG}OHxdkgAEosSLi%@lywV*O&#W8DKBr09c$fQ+_x>v&u%yDpcZOS;y#bDQ6)0?iT)R7GRR6JwM3gP=oOdzm@GEB)eXpY}zhhfF8rcz3V(q$np+fGj zuk!nt1~Mo^^kpbdGd^cUF;d}q_xQ7mQo`IXjQ+e!BvH_ut3rBKVBNo>Y>9aI0A$9e zkPpJ#6|qKNuz)uJ%jGyM@?6BK{`U4t#*8l<{N}%39B8pX-^u|SMtaBKvfH0RP6)l2 z2aBrfLjsQ$3cLPYKSccE=l*@`v7qQU6t+qbr(82R5IuoHz~~Os^NUXrc|Q0cmRPAE z$Mb@Kn%C4T42L(_p$KZtco~rCpL~31H}+3CdQ|@-JSnSLRQ5r{^%56)iJ4G7nC6*B z87o$ir*Tf}{!T!Rp^|=4{ucaVEhS(++!oZuK6OrELMnYrq)G2{;dTfG- zGV+2}vj3!W3o&`VJWTAX1x(*m`kXQFEk(hF@_*KxbuGgeWGL?(ja6T2+_BCo&0jXF zmEawE_Pg=<_d;mS5s5a-2ZLY!eiTXrjwzNXg_Ddzdm-7X{Ofqt6#yN+g2M=Lof+)) zJ%C&bL9a({w*}1~#24127L*1r8~%p&z(c`6g0OLCZl-ZdX%UAAhBvGBp7(pscs?>s zWgp5>`TJx1@fl7Y?%y9onI#dg4%q(4ptQ%I>H+-#hrQM(sy_!aLsP>5894?phro@G zb$X2Xs(*jUY;n}6zjUehS`tc~)RwL)IYwkyaC6M>R$TpkvS5oqub~uaz}dk3hGyH| z)Oah6{B+klVD2-4fCCV}G&kq-91i1YA3xV;q&gmmATJQ?Ove#-fNzTf%!4l1IFL)O z1krQz^E@N{$Fap@bA}DRG*MFqUJG(<(ujeUDYV?ky}nL1PF@=>asv0;GNdB~avfXP zbTPNmPyDeaKX<=^FN(hH7*Ht!b{Pb@pNr9ST2W*Uh9d!-lSwpX$*z=nIfC)E0hZ>fE zS_7FYY%{$qmh|^Oq|IIYhvrb*{94%X<-TV%3CV?p9$|YIaQ|HWQB9Tv$#WU_=f#+EjrM6@fcmQ65rfKA@=>J)-(^y=i9Ny3s3avbK ze?j9z-rWipPQK@c$+-&;+kW4a3fc$=FqaYC%Hv9UEgsR?fE9ujvjq4?BbIpu;HM`J zp4zQuT4!vtmX~yJOSPmy3ah2`JO;x11$KoG$lWlW{aDlKBg{2hIRC(LAj^LY7$VD0 zWV{M=r<)Dxl<}YI7NuV*yx679qu&k^Bzw>}QyKo=9}(WDq!(ZT_d<5Pm6CU%yAd+1 z!-$O|Dv-f#Vuv+1Sy?*rP%1On& zI(Nk$Dj!62gn5}}k5g}~tnquSZ^swCKQ1GdaXe)THD1g#kvN<2E_+)5;kXZ$>Gz-` zRY_y+BW#b2?rJz(mfnbAFoG>KM%<@@l@Rd?k{8E~djjHa{R|H_n{X?y^_>{6u?}aH zaqo=je=rQq>g)48$z|`fW!`*A_q?BRq455tXNGS;W@GCWBR7V09=Bg#B-Kv*l>6oa zk{z)G;z7$mUT|;|w3G2xLx@!;ICaR*oNG8b^p*xikZCP~)m;Z;+PDsu)5w4_svl4G9AFzsyHTc#-@PGBG42E4HPT$Gz89pDw0Fb;vPY>gylFG7!T|o!VP+k>7f|Mw)8CK6;~)=Qr4cBV%JRQ%?lfXyzB*ywNW*`1 zFGl_&$$Xb}&C$Uy0h6RfC?pXHd)rrP4)zMQ8hi|3WMbj9Py$cr;2IP;8o_weI7BWO z`NaO|ul*OPXaSz>+H;%W9*&)-#oG-~v@+*6FOcvR0Ot)6I*&pOVHCmSw#r64p~3j? z%_~~;((+K@0~k&`9{CLE*u~0xizqa$6~}%FeW#I3|3k0mkig#=CKopa^23VlpeUBM z@9t&^==4XS$6*C;uJ!6w)3S{lNt|qfeR9l2C*A zSRf|4*#*z*+myU^xDQa z(l=U&wKz4wkj9)Xz2(*%g3n6Feh<;xHT|MJ{8~Xjl=%qFPwNnTEh;R*(x~)X%NM1^ z?hIY~(|9pdzbR;GVb? zB);xJ{#xT9^K2DVATX)!4i!cUSo~;MKqiw@50oI*#ce3lt^h#)!5i*U{7uFQT63yd z^5w2nthn}WHsNpWMgW!9gE8(F;yDRQPE!l6v&m4gR6)EN14BM5AVQN!6~b<~0y8o` zcmti!`A~f58)&oWh=5gMcTqH(*yaFH69dsq^_k{A@Ep>GoFO6XC#`iD76dNa>@rNv zDJK-Fdwsq3tGF~wrLzv@9rW8;om@o)=WC@|IkWLliKkybCVvHODURr|qy` zskk=372zh5?&2qdIFY=7=96m?LX%xW{k%_3BM=D0Ps;n;ODD3#u{@X#s*}nE3MfXS+$3GP4(;N1@ViLA;R7y{ zg1UQfFg!56(t5wTNiiAjbFYQ&Y&T3dcfH{z2u`IkX#Gr&HQ%V!eIPHp`!c)r3a_|n z>q?Hc)U8&QuW9w{9vqY|fDEN(Rc4Ec+UK73na>}b}eMBl)K>TSj(buJ7ewy*aV zPNJj&j*-Uw*jU;8yw#m5TzT5xZ~S8Y%dgKb^^nBdKUTmfYdjPgFK%)zG`3L#Qwy)g zqmMBkD*IxjcdtJ8{nq8_Qf6yVt4h2*KcHkH*qt27kDJb59E7A0b1bNdau(W|g+5UR zOb{Q(7*@tVFlE4&%pwbCO(*y+-9b!m^&GbBIM^V}rL(}nEup;Z<~GnrNcU`K0~gM2kcu$I_)>G>{vKWXPq7+-a<{ zBO&i_F|HKHR}hvM1H%wgqPTaohpZCZN4T|e%DK}JTeg(!EK<3hS9ja)(#yb(rY7ri zdAAQXUWggP2NUxC_`xW8iS)~-3P9dZY2boM+ikcF&a0oU(?Y||ySI=upM9V91$fN$ zf8GR*S*+Ev9&#HP=boeA;yt{snkbY&Dpy5ENK6S-rH3&1KUOb|MHuk_$NLX3Qhv^_ph^C1m=;iz90on<&DR%Sm%+$0}=n(cd)G{|4j-1;U85--j_oK?MuO5^a zWLcAyx*R^<@_NV^B#?FSp<7u6C(>W-K=Dwch4Am88E+7LSvZea89N zkMhw4M@m>Y%~sf3sEdDlb@D%x35oEW-Bmv^mwl#lsbw0@Ljk$-RN zOP;L8N6QS|)w4}J49+l%=;e8iSY$1Zv~Y*Tv{_Hi{jHd!`KUVn{I9X1P> z+duBApD`>p!*apvJe8dqF+q^YtSG;*_<@QNBNVgEt;oyQt$^l3crd$US-RYlKa*R) zg#^4oLf=rfns8(Nv!ROypFPxbrcRghXRk8;6(KKSku8wvb_DzH8)1E5rE2kS5B3rH zG0Q&o(&PC9iXgTD(uF=@I1yqPbPbXrmSA&xroh*ymT6r*7p(pH&5EJgt|Xay$DtiBV1`g=%{_j9;Ng z5&KwRsaoMR28r5~grn!0*RYEWOPaCkXQFb1_G2S9KZQ?e5M`DVl2mfyz3&m`xMVx}|~I8+KUs_)e-v0C`v;?*gIQd)>?JdQyUSXB_)t3k=F?cUdwsxpY# zip~Tf+P**5o@>Lz?WIEPQy0OIfqRZMHD&5j^Z-V-bWr#Kb(AbySwhtfypT0biqm(Q zlOCG-R6(NcdT6IZ8zw*0lQiEKK7gYrB}YhWbt2{wX{k7C@mV}ITd|?o9bD@d_|#kU zi+8r=Cb4%KrEr?48P@PAC!)+#2FMN<%55`dMYX<1ZJx-&ILgc$A|(Pem2T~8!uLBY zF3}qu8#gCm+!Y4%UL31Zw0{duJe3ofGFaQaXQX*fga)^lj19M0!j2n#sXJfRWku~! z+2nV<6gA|m)4AMd>tytAh7G`X_qv^!2%_#3xSSsz+UXhSi#!@XZQA?0= z?~Im*pjtyMR5@YpXYVC<@ctPf?u!|2F=7Rm2fk!_+`GhM{?S*1kJ5-D%f$F4a$UEQ zV_bh$ZMl(BTnDmn6T0U2e$T7lsM4yQym~>`?cMQb{2cLyxzh_=T~V9tVxkg~nbYc1 zVf{kSW@NLe>mz8co6$x+pjptIV>ha;Zc-s@C(gE;h;zeKZ5J8pxUEjUVpRN&FrJD8 zbK%ak$yA=mL|<7-*aNXCtrlkjS0!Mk6LyfaV6@(sCFD$)mA$^QPl6MZ&pbd@o_LO# zo4CDCJo|;kM|5I~ROkp%3+vgr;}Ut9dg6f(^maQ~aopMg@wIsfhQH1eYnk#Y^28&g zyPHvOoimHMGp(`hK7sQ)oycusJBAqETP0bNC;plt(WPNgQ3&1%mzSNrD2>o4z|Z-N zyuvcbYf6m&L^VKd*LbXFBMMswFN>^!e4i69iRZ`S01lM~L-PHA=+dOwj@X+@Y)Nal zmv<1`%5Mxig)Ga8pFT z+p$>tMUWrJoqr(|V!v}jxHTl=>><88a=~Q|(}^-L@x$abe=}pNieDw( z!WqxyPkCyWh_-kno$1Iq7RmP_KH(5j$LW2*6lMyWqzb&^EMJFv6Xhk`Ai6KNaaE4S zh?m7$ZYPj@!1B}+LswL>QnKdbW&T0w zosVr*eH)>=S&i?j)yn)@O=VKn&M7Cb3SJbWI$Dff)oD;WXcwgl>eQE(crv9Za;)D{ z5{t02uKUzx;8gOLQ;&Lu9OtDmFihBh`WRWPc|Qk9;P@^VmU3#QjD<(hjC&t-eDqT2 z@VNK+C@uS=K+j2-hWv@!T zEi^_HC{UvzahcUP(krGbDy23?gI}CD&L3ng())IQN2}hCS3B_aU7@pI__*pfxk|m% zu;DY{{e|j_K|#PqyxNqdfR#T=Bqqb3r?}GDl(BcXsLAJ0<^ms|a8AW>mB>iL24~g< z8Y&k5U3V>}ys`P&PjQ{PApvA$C`AiAJm&=>(-+YOV?NF^{5<}o9?PgiR`;Fk;Nv~g z-v+Y=#h4RPO=f~6>@f63+QQvldaqAEXu@STPTCu%VV<&|EeK|lkR$pQ81?lV#vRg7 z_hk_-$!PJBWxi00+v40k#utt~W-Q;aXfqOT=b-&ivokd>lv<7Od+%phYoR`e^Y@=% z*NMpxy$$t--Lu{IpSEFKMaaB&V%P?2vPld!7rz<>b zyEc8sbk|yWk?E!HI&CrY{j$}DA9QYU>8%>9%;tA3sp8gsnREzN_pupA+(VC9$0RI? zgsX0!#K{PDS3&s$17|6vasTmdgrH7fw4=gvJCIksVjU(btwpU3a693{9w8U8_x0 z$QGE*y+!bm=hpkCbZOJiI~h0wcG?l!9z5@szPR0O+=Cx_{z63i!-s}Z?7pLGM+5|R zUU%QI>N0eyE*HSDQSQ6g&m3T4+UZBL|mdtj;MGE75{d0NaN@us%4jU-b5ZB zS`OxyRrY6@nJcCAFA}y&lH4<#Dw)Epe^Ex;c1z2`MHYwByu5DfyktDNz{el2x=Wn% zSeY{qIP=;kusIm1e;)=GtRSvp=DlR+Wr4cmo8pwdZ5$lD(<3Qsk0WCg+l7#0fZP}+ z6jQnC+A-);+}7@q%mo3_|Hsx_hE=((-@}4*cb6cr=!QjiH%bapi}(wRhk7O`v`QlmSo?7cCaW zhsUa+sYt9tq*RIukh+LwH6zV9_ygY4zDQeJg;P^m9v8<(hsQu$E9i9~?++k?Z=_64 zGgWynuAbmZwss@~Lmc9cHwBNgPMqnj(;Vl)L(Uu{r~cy14w`Pd(=BF<*Qpk7ipK;m zSoAn)nstbqeI2Y9f}tZ68W32>I-|W5Q3?DP&cQ;4_wb$SAt52V`9LpfxbYeh_ko-y z-=8_2D|xZFvijwa7X=|X-mscfuc=g}8r2H!)JlUuG%TlGHyO`aF5YL3sd+=9kdWpi z280ePP%W~Im>FI?hrMcmRSr^^fAka)y%5)ZQV!2y`l=d=9z*KtjUu)-2)q9}$Tn^Y zzcUR@>tXoDS6=*|3*53|a=U+gxK;W;lY)1S~qqyVcFs3!FjE)-*sGq;8pR|xNBm_Is?CbIHe zNt}+=Ql4B6Z6FLX7{A680@077W)uPM<}3*Jy}CtB&gC9FT}2ZXu&<<4;yo76dRPsr zJG=uFDXlNl)Kh;xI13*xO;H=7mYzQ{M6Z2OpbNYf>j`P+7;Ih90Sm^_5~U4uCD%bT z!o<_P4(Do_Y115&3tN`as7>FH(Nk749OlLEw><8(-16?(7hzebli02@F*4dIKq|14 z)7F_^FR0Re)<9o%7l=4XC6SEk0JG9)U&dkPK&8e`0F$!MX`1T=gd*Wbvo)WG9<#Z) z)7a709rzNr8md|TzOQ0P(P#mzP=*yEMXiQqk~Ed*wjX6()|%g(;6?6nT+uKj8<_w3 z(Q`@vgnbaVNyYgrAWNL8y%bw55yODUh@*svH%PtBu_IDM8}*5};X&vteHascNVrYI zg}n$?ek=>&^@OF77R=D^^?q@tCje~DVbCN=@ZkTB-6L&LLEkGD9cViR%6n&T-y#o& z;Ki#W6^58U&hjRAaDN*%Q%JL*=?(~Hf>Pu;1h;uphDfhO9|1dyaug|oSf!y@s64=p zj5Lnsmoa_A4D7yXwKHS>>l#Pn>ePV7mQte=-g}UNF%UYX_1I;!IaTlu*`f>iVgMT! z*&0(aX-~a*yb_kTSGOb=KYS&G=_G&nvcodw``hF=Gm*h^`W&rH>k^yhd`s+)I=h39 zl=A48>u3|G~=iFcXPFu)s=!gOekF%J)V@?Eu@*DdeGEwC_Q$1x5Z*eXl z@WW(Cm}!wCo9(y7z5`F;!pt~~Ci@`6yzswr-EXCQ>w`~AfXZrN-u~SZTZl;;HdI4T z+&C}(OVz809%|n!K}ce@sk#&y2rlvibm!=F z($^L3VOEiGsbVXh-j*vi?P_ENpmh@uS>e6+wp9aS64Zu{gckj3U~{yk(>Q3&?V(!> zDc-xtUm$anhykNOGf6I!#6>1oLXQS8%*B9@W7i4C;|O)JCE?Vjr@{!>{Hxxj&hRtqFlngxAss~N3i zMxN1c+(bDb_iUqFel~niI0&Sjt0vW@66^XFH6ME;h(P{O6W$B{G?FSiUeAa!00QSX zJ^-llovZYVm@EfNJh|XKBX}CX7AB*=r#Ba>u@QX_T(NSaGH zJ<;-s!f^!j!w*H1p%u7?S0gzN(v9@l5c)qFH&i{Dd3^P0bJBmwAYLdR6R@gn|y7%cz;y` z#PATm+p+B1jKljF2H?i|c8jGnw!zWAzuJP^o-=1(o0`iIa8XDaTj%fk^@16(?+N!l zq};!Mo3ZOi05+*@+_ushweu4YH+=`aDCh&unr+b<)+XnM7uKv*%Z$^t}pMlZ3};9Ze>P>msCIgrY+R#bKZ6MbkUAb~H&0h52%F{1$0 zH$AlkZ0$=SG`0o&lCctH)6>&A!Kz9CH+Fvxe>2;3#&sAa-vrQoh4yFy zD@GYsKQRI8uY9<-k9E$x*qsg;w7-nfy@$!<#LV$BPhhH=n!H1Wi?zuYS&N%pVo} z&(8o^KF1KYpU;uHpgam&k&>iuRlVnD1{sY$EN3#8>D%x&jS$MG>+ZV)Ci3=eysqmV zRlmq`zlXhDi_N-Jns+ufuQ4>CxF*L*tg2n3$#|n`Y8|Br(8A)J09uxWgoGr^KwN1C zc2qZD1UWx7EcO-NA#umh; z3Rq?ZE1rY?b6+iIx4i6+$G{{m9q}NbG=A9RYiR@4VDpxA@Tm26i}R3l#Q;?(aPPi2 zI05oy#C>rv90VE#2+e16WM-BM?ETOYxP0woM+h@%V@!;F5!<~)k75Me?ahGNHp}KaFp=(TOM_~h_i1Bu*mYGND2w55Ix5dI@@|aGb5&?WJyzqtE)}OY%xf6T9^{= zctRcN>{Ris1j%i|5s?57KV&lN%b(l@bZ6}9PW#gwHOFl!u7eB=42&>8iA|Jli71^U zc3__j3rpk>E$V$Xm<&(m;O+o#`oVtVCszNCbGwh@^| zTa<BS>%Kq)F1d#7x zThwTo%GYkU_m@Ej6P(PiRx4|e2C-ceft*YGcg{6x$ISsnmx1-h#Ryp=89{X;w0+zK zxgcXJC>57L7`y;`m&k8ENqz16Lj$0=RVln2|LF7b{1|=I4>4v7uRvZwM z_XP6G-q(;~!06V+ssmR9A0OXm1C#%Iz^`b##U{XAU|-D=h-q(0n`DUkeclz<8pSDt z_D(3cbgozqEdVY%r-Wx3Nk)uk9+p#OQN(#OngrH>g29u#6v_OaIs10X?_sJGwP}f~ zST(F1Sa7+(&C%3?liamSx8AGo=O+$Bbo2vg9=mLBGLaO0PUkmVI*$CHc=-4X0cl51 zuOvIqwC3<(X1?Mi9)$Q~Aw@iE8Q!35Lc}0%zcgrcXsW`s$j=`Uu)vt_OX=WpDXq;g zgFqY(Mn6pN1b-?*NH*<`2O9iuOpI!f8k4h+JUY#m*qmIPcDK}mb)jY~e;&M~q`w4J zKGC)oymM24@*~HAA#M-O-C!>Xrg*He}=*OHv8#@aw5}#KYqvQgUuPe z=nZo7NsRru;QS+5U$kj1SQ4O}aq{gwls0El?bqNWRk+6o%`-Ce3=KtJ4xT?C_e8V4 zdCs4MkB7GmnBYf_se$7;;(B)xzEHQyS7lfVemDUXtCUYiPYIH$= z6tYJYA_+ug#E}T4Y|MaGB1L)RpOFr8#GA1pl1i?$@({rg zOB*(|z@eBHVr-VDbx#^I)Be(E!xKl>grlL#AETnL=K_s3ti=l6yLP)Dow`tQZQkxk z6+OirPsN`!h8w{_nr+oUy-#5}P6=(h+)bj_d8F^B?k%J61WdW=%HP@%J4$4QhuYJVaO4Wd} z|F)=2{aI3aI81;$l5wD%2HML0?xg;Lc&OmIL;@(zLBH#Nfn}n*=OkU&sm5CEmG&mbhWBWu zZf4qlelS=J3vOFPl8~ee;N5e`mY;V5>);*Ex79Bkf!xz2pAjc=3-Z02Te_Tkmmh>l z9<%LK9#nRttE;=Kz1ajNes6*pT0VzKPvX@60v;Dn#ZsL343crqk2jL-A1#5CjAQm% zON-Hs!cSZ_>--!F`1%l`z!1+FG<);MlJVzVice*?C0C;%$|ip;V8RK4ZQsiF6EUg+ zyvQ_Q#Sr3bmFz=`9FTh2U837xP_11<8N@d8Jt&SR43FoB05Sbt4~Qzi3eS0w8MkM? zh5$EYt?uSK$0R%?EiG-CM+q4CvVlX<+Ff=-MKgpU?vs9;Yk5e&-S>OC@!4ew>7k9!h z8RyS2b)muxegkx% zj>rl7!!SHVLFha3gJ5^8*c2q?&tDtd%7T^iSttYzEfVgx19{6=jww@Ux<%Rk8s(Gw zQo}<;e%%Mx0TW~at%;E~eL`tN@3=ss;>L!PkcG=rs_xSMWhEKOs zNn!zkF@Rp;A}MB!)MlXp|F=)-thS2_&*ujo^$gdpA1;-N`%)=&SLs-*bKLgBP$pTQR>BOp27K{0eKCC^2 zYs!JuGg%!2-~t0;+r-u^d<{??bP2RkWqjsLMY4Sst1RMf!k@HLHgKt0cq-DT@f1@Uj~oV-0dwck{<)Fgd*vD?l?aV$^O3GBP;TXAukC{ zck+z)1NRk>fK=Z^QFk1tHrNDqI0v~NE<`oV>(?FqAUrHoTuBq0dNas5eeC`$J!Xu{ zNZ18sgzZOg+En@4dqm2go9LwR2?_a+70LgA(QlECjk{AzcG=|H!@ww6L>XzaSAZQf z+FC!&?3S|(1OyAB6T8llOE*V=*EGDFokEa$tD%vH!G87mj!uwdMct@Xh#- zVU#!>j-bHd5fU;kc;)^R1gB{fz{1c?LV%Pr6?JMqW^L<7@P>m&iwSU#uPK~I`)9be zAFn6MeJ9u?RPG;v%2E45w`4-8Za{2pE7)a`rk|n z?_`S%a5^A37Baa%6MfhPe%_ovCEo zN1%3*{x(Q)2y9MS!$RVUBs1*12yVlV4u4y78 zWPL03P60(XYUqI6%r$F}zDi=*cc`)!q2?I=TK26p_o1Af-mfwNUFU3?09l6u*f5eH)j> ziojN;@}|5&)2z6D$x|-!f0F|u9ZEhoF3JrkCj;=VFV&JxX)Vt3M7g=SDTVtqs0`3R zJw2dU6V{9=fld>l!}UIqGm%zTV#q_Us;?6W!$oHfqN2N`ol07S6n{n9;OF=O3WDWC z0oQO5l=DRv{2phdZ8yov43ti`EQo)9PXu)K8PolD^hdV+KKwNVM!xsbN!|0ET)4{s9xQSZXExcD92B__t2Lsq(t%*Lwu#eP0F z3!KbHe^=@?%H;de3FFFEY+~f8`x^)Qc_dZ!_ly=1!NJQ73WS`jwzgur#9!!Ds4fp` zv9&b<>wZc}b$69MVI>kNwtQ5gY@TAeUbXPqyYVhtI`TT$a(1@&YTmoNYHo2!lIw?P zv{xd1##hJ2-c5=k2;0$q+=6(=wVa7civ%CXIXwoniYn+b=}Y_v(Cp%ciHzRv>RkSj z$-C2XJ5fGvBggV_m6>SvoXevvj8SC#q-`uaC+dmt>_sNm718sE6xb0{*l>B0$TA`& zl9SvC(E94qGwt%XnwX^-_44mrW)rziHs|>0vUG}CiSWWsjP=Udi7hzTLy zJs3RO%-y4K863TEIMVjB(#o~cD?|$u*A+^G8M(69#JH~iU8zwYlV!actz5gVXzH3K zY3sSXd?6G}xf+%lGea|nJ=6Fv>ah;z-A8?U7=MGCOqg#fYG9H&H`3;0i^n$~38cBC z_S8VnEFf1Wwle3p4M&kZwSxCCO&?_nE9uF7>V zkB!g6-(-3Y@9YbeICW7(4FjB!yFmbc$7z(6FcmDaxOi>FiUEYvCqjw&&9nhK7D!&2*6_?74Tb|H( zG(5Z$4fn1iV1Hmw9eIoBvKtpC@rPr==YOjYUEdyi%4@W8$#R zNNzzranZXeBN2yZ$%-jh^2SM>tN3wNgzN{`g$u2oSEF0Eol6g2^5=%L)#nR+d8_k% zFR#4HOY7|)7B3PVl zBo@k*)jSDK%wzIe8TC@R1eDMlHKjS**lZuuVY`nJl!N9b?eFi_(O6B@n!3Ym5#SxY zTP+L`ap#jI#3F}#V$8T0p1tJL3(FSq(fi@lbiYr!bRCKlt@vMDM_8+tjb?kL+scEN z3N<(ENcis#d*w~8E$AQU0ANHuKBIpcc@b)72yHXA3saHFNbKniX}J9btUpSU^S|L# z`LeYI?P$=1AztBlk_o^&dj;LGvb0q5pcWW*aH70hDX-3FbKk5_jWb~e+R`M=b3z$e zA72%9#D#%SMg)_eWMt$`sg$N7?>!Wfo%1^|7Q9na#>6-KCp3Z1o1QXKFm(vE)<62r zv=AnX6e^X+L~gJE>d9}!q95n%-WHU1E+OK4>X~OA!rnXqpQNB*+0g-DQd&PkPF6IG2(+H1g|++YWVv#m;( zEtUQGM#4-0)yBtftG6M}_|n*qldS&|m=3rG!6YD4B)e~VUq#Z>6-j@ZGiciDH2%i^oE^x0J}J3b|{ zlriM0zQV4b+FXV)qF26MLlXkkgtVy1SNprLEr+pj(LYC5O_+7-uuvl-*~=@`gmrFw zi78NAb+!MKi9+L^J#7{|(-|sQ@8F|U0R0^OKH}YD>;#!8)!a1>!E}9quN~`U5xG8j zajzBJxlcoBcT>?-5Q9N?X+D(o6;2ngdE`=H_({||zHs|%Qd#Anq$0bIXfDSnw#;rH^J*Z>RitE(_>I2o5ahzv4Ny() z60w65A|A*}C<9^<$!D+q74CfW^hqr|PI6rqn>->HBr$~xZ2IjtV0^9z^=14aYY z(m=y4rJ_^vNiq*^4W`bKhCp8eOkm5q6C!bI3mzskDXn1{j31 zho7kadh)8ucgQ^GQz=f-CLI+WK~{-nIZ>R7IXQXw;bB*Fk6eFvY*+OBH{*R93JlORb|Jwe7jY-cj&I;F%&zu}ip)D`p@&E}Wg{{{^3;%4kCi9W!mbU{gpuM!D39*RC#`NCHBGI zRKDqfp3&}W_ac=G0Y+)*5UcXhXy7J1$2q3QI;&Op|_0Qx)s>^*{spG98I_6YSN>oDT*3&}8O6Umn zg;_&l2gxyW0{&mWH;sh9ivH6v=2On4@(ON<;o3>SEdZNGe9M>=Z?qI}kpDNFnf!u-XzRLh=mk7AgTAPK^4Ka&^iCI_c@gcGj?^pN(@r%R{U6%vH0Zbw7Pd z%}NPtn%6H-`B<#${{6OdzF2Q_j@JA8%92Ul6nr^ z*2*8JznDtBG6GxyFHT3k!I7S~w=e&`6JkigVXdg{;((9As--(gM$T8E0Q%RxzqkvO zflWC!|DYveNN{wmWF%)HE8!<#@fuOqFG5(cMxB9bj5NWf*`|f)$xnc8IBS>HATyRi z`1U<=`?x+}?g0-doEr3wEJW{!n=fn1W0GDdh;}0d7~ZcEUhitRlzJ*!RQ{e;ET!wR z1i0A=U9fSs zMC{OS@XSISJ6`m8PL$#sQYB^OaA6-3j$&1s@1-b?!2I10C)&w*U%|-DfsXsUyc~rX z^m%bz$^YCRyQF7*uT|1{m6JX~?zd${+pn6he!Q`D9k(5VQ<0HDxE}6Ww#oj@LVt)R zc9B&O`1f01<4ngM0F)8$A_2Hoj0#m3_%{(nV~7^y)qj2IXnR;y;S0RS6UrwJ=AZ&D zRdI1~omrBDnEi!DzMSXkB|gRM8vrTqRFbZodLepMKePhO+pDday-oL61oo0sy?7yB zFaB^|EZPako+q{d$8SyQDuB>O?vOmD3`pR;=fsMzZU!S2UY zIyW1DXmIxm*bw@si;FIeO07K*_`OUCDnt=R zS5lby=*Zt=3GtXr5aTRK<7JTy6|XQw*$&rAe|p5=xc;<8)r!1QC_OKRxxfb=-cR3B zHX~8`Rpname@gZD4|aXYAY0#9r{bfReHiIFP3BBD368DY*8)Z&kX3)HTY)td29$_{ zi8FvXO5Iw!R2x8;+;&|6p3}>ZcZHCVI>BL1sy`onEnEy4@Xp-V6%ve<;o+3Lc`5Sg zrzw0Yk)cs6n%T_ffASqW1)vwOagbGqg9NSdrhXL=6x1w4PR874+kV|e=HTo5Xyi&W zhZF#VtS00-Bz%=qU0uE8B6`!Sx(aNLO?Qxx0l->!6dx#jWcR+Sp!MGF@ou`k$y~Ef zNrj$zW@>mAI_YqgQ{j{cv&dp2M+gg!X^_AAc!A#~zQ9FoY|GGjPtd}kn~&cEl3TX- z)r#u8nLd5$!yTzCRZ&+JP3pt-oM@*hUTo*jl0D3k5!1B{($cpd)KxK+F8GWZpxBez zzHzC-bL_OuxSx=P*=c{a;gg4bEV7*6RtRo%N7hFrfT=R?NZ=#4vCq^I{Wv6`%OjsD=T)Oe2tgdKX$f|iHNd|40|QIn>@)6tfLbRNuyRPHEY4W}7rMQsR*TZ31vGQ4 z(3tWz^fSvmtioW^rLNjAkD+h>&Vc+~RD^y2;3*M6SP6Do4=*ii6LPh-W(2J03lww! z&Ldm;Wy?_#7ObS4zY3(~@uK_$aNb-6wjx^E*~z?qop}40UIxj2y5H*F2!1e%kMw6I zQV4aqE+ohQmZG4j?z95?ol-RR`BYi1%cc^vKkYdn)NmME9kiiHZ?Am2MLm7sKY#$R zlj9>WuPo??M^=2|4By^FMtcGH`W+QNq|c(}QZ^{Bf#>fv(zbH?3Y(>l=Io)|N(>CGy9M&pFG<6S zMOZFsa)gI9hL{S}V?`O&}X5Mb_+1n}TMJy9D*7Z;5CQR~L`i<#hc zQ9*07uP_;t)-z<}<6#)9FAcHv`eJT;!?P&k0%KJaU$8&wO+u(X(C&c4)QqUQ|{o^8anJQOX9*$;Mm7Q!vXuXA{#kFMMX zQ{xg|*zO5trIRU7Z$2~Kem7Su8W5Z9_@&F%bIOgMtisK;-K^FR zM4dlkXhN-YkK@sc<1X^(=pGp*+0@Xzvy1os0{Z#gl=ls+$y-0<-mt~aZ#M>@tf`oO zG)x>^WiXT%Ms|=sr<8$U!uG_0s$yJ6k4zRoB)Mh5ZIPp@=pAjp$n z^dmyfw(>0(h0@U3Ra7a7e>auiG$xqWTNB8k77iQ?O*L4<7oG!cT zQ!+VfMq%9lJ)6I(se8coLKkTZ{_DQA^*cwP7%xAV4!9c1mK|&Iuw-Hk^g1!A+v-PV zCd+4!lECmylXd$xf}_U{4D$b)NFyQf-!xDCm~L$QP7ek{x@pJe+o9WUmb81>{=ny z!HxuS6^syjMq|?NF;=R7YPo+aVT9igYz1m*ZP$f(cV!CfmjpX(pbUb^wws@P&%eCc z!ms?8Sqw&6f4v^k1Ct}boRAF#=Ngz?pD_)7ebtdonAF-eMEmYku{N;zf8 zT|spF0?C1*l&a!h-bH#DwO<2FJFQcvWn>XQV313kK0frQDzx`UqkS=~K}qMc5z{cq z!(lsjJNRXc{cj}uJ3IlOk(~fJqsxkx?2gA*n4nRV@$Mc>(T#Z`snnLJJ|nu5_)kUf zUmrgpLP87B_6WH`P&N`ChwcooPDPSwix; zQcTREQ@o4ITSrA11ffr#TGx9QZDrcOhM9aHRLS{HP*i1s?Quel^XnIuwn0qEcU~z$ zvhbLwSBkJ9rW_pMYeyU$rLV~iLhq5K0mg+w4e{S^~lNkfaw>IR-NBnIi_# ztftnvdpg>LvzaQ~UP6`#!#1341jNYNHq7%0^c`HbBtkPY*6LGQ3Mg2lf~T~Q8bu27 z$GYK4)kZ994(*(&x7|r1#lk-JCq5T%vG~}UQnsZV$#<7(EXT})c4Wwz=N6^+1ITrV z+>oO*%1k<)=#!b97z^neJ+DjfWn*>KXFdl1`YtuDY#7mSpX8vb5@z8<(x1ZC;rR$V zs;3t}G7>PiHQ3p(YSKSAB)eE`6&?{mJhm|wy8JqY?ti2YqiCEG8J{RvGq=g| z^N9==2E{^gVtud;$qdL77XN((e_jyKN2cZgwmJkq1MKbXWp#ClRkHYlYF!W7A9t;* zm;6L+fTNM*m@bfiglED)RO*iFfUd#;yt$eNEFR(KPGI;}D2nj8)@L{3LrZ%^MkZrM zh5(N}t(W=@!5MX6NLM!v4+nNcWu?MP^9>W;j`mKI9i}L}NGhg87s*ccMBA`gLR~)x zIDJ;a43%OWD_%an{M7LW-`qH;v-6sv#3#Z@$#&q9 ze|?)&WhfO~tF$kNC~c&_EhLvB`a`YmleF3W{L+w2E^+sYD%K_w#@dnR2y0lEwv(|S z-h0OuC^l0I%HGDAobQvWoahY&Z`n@Qt)_5l){(j$goTBUyEawLi4L}SP-b~LNgnLW zgCDzU=D=nEqq_OpOqalUpUC9$po2T?`Pf%28@(Eos|6RrQ94yElUMaJvbT`LhkpTx ze?D@n5prTa+0gmpXUPSl^!EqeNJ8O=n!Udy@K8wqXONOG0^Sjft|(&Qpd4Q9_~gXO zP@~&gPy)SUNj>qFsmXG~kw~4^*ITt}6Pxahz=*-O6B89=!YF%{rr|A~_>TDa+rRpP zSlBQx17X3N{Q>k$iY%q~X8QBT{PYWTFk`(5;X+PuCzRg))gMWKZo$Y}2H`_O0yZUO zc`)VXdk0xkTEZ|WO%t5EFvm8xdF`C0hr$83Ol_rW@@J^P$ofgnh>c9~3|b>#9g}$r z9MB49*NsOOo`y0h z94xSBTM9*@T#>!i!%8g{P@4RbuleMY&c)cy8_dZC`dzEzpX+QxQ2UY_CJsP!1a;8f z;Jy?k5WiVhFAgf>2g23c0+VS}f_4r!7$uhrcEitNCerX9$_=}Bb*m~oPE7CyKZe{l z3H|KqQjqUEeycG0@qff7G>!npx&nwPv*t{2(Tl~opH?EU*g*4X;O(}GrYFPrKQf4f z5diM|KAgx^4wN^n2F=k+O~FKMZu;0OirCxWYk+KwNdH8?%~2j~f2A3imaCEL!$JKTedCdaAf zR>V|Xd4aVUUoyJ4dFcklP1hMIXcoo`83hFdhG%DIx40)~M*}Y>wWe`#miv4BeP+2g zxHtO;L(^gV)*?WdrMnHW!&o4zT6#j{YrKf7Ha_9Tp@rl==xRyCxUS6J5w17<6tDU0%=ctURalt`c zKJAqlP$dYSG3A|%&Cjb7pD%46D{5KL|7y4X1Lpm~Rez_fS`{GgJg^rGZ+L3r$7b>e z5iWTkHty{j`CS`>`Rw38*79<79`A~A=>)tqwb~oJ_^7Xry4PbdlmO_n`U^9}0+Lgf z3j?sYmWTUNiWc;WZA?5koGX$6H}So_K!Gvwgr?fB}3t(59x_{p{%1&oh&0y^wu!xqZsyFSj_aX+)X zayNRute_kc5m?zIRJX&OoQXbct0Z`aK2qZ_Ryndk!vLG#L8K@=`l-)6DB{S)t)t^g z?~SqbyP&OchMHmV;f{B*sCCt?QBxctrk*Q22YU$SP~C3~9#9R(X2etW@m%w^N5pqXIM{0#k zIX+n8zW@TGL|jX@mdN0yo&2Vh(f=A0u0ta0cHH2Vnc@)K@2HtWuFRHtxk`DAxhlZ> zBKA9)#{Y#Sfmqqa34ndWjbxc zezbsk7Vtb=#E;^{%na1?tNqIt=AYeN)U3Q(Ne64AjkK2GP`!#&Dc5ZffW)eZxhFM=;e!I6<+|5^njGy1Z%)$#^=SQKwu+Y^GcUMSY@d{Sl z$WBz5FKZK zaOd}>+V99yaIJaWx~+X?HT$G!cv>ZPWL3+V|1RxuMn@$K^vTdVjL z$;mHHkB!$|p+?`kgOr)HmIHv733Sj-FK{h7)SYq_`2KoixEW$QPY*ByTZ1ND9ex4w zXOVPZbmHc}A8kN{;xZM+C2}_%Ye+8XjikF=M0cdR5LEDe^8ct>ez#&3KtN5S1U631 zjEx12GHD{cdk;t$1tM;g6|i{ zg3`u{Y5ZonHE}+yB9r4yI(#ZA(^3SE!sg_pVjvxHu03S&H1$=nr!-GQgfZbrs)C|D z;2C;>(({2qKLHEY7im~C+6?63v)#Gl6c80uu0pR5C8?TA+S3svEXHM_!2Bpo0j<-o zsMjxjS;)WwVD|cTJ591MW7Sq~Pw=I+C20xr<0H%T^#Mxd@UkK5WMY|Brj|od5tVsh zAl$}IM#_{XkAxI^X84)&n{+*9Ev7G8OnS<6)i4$12B>#kF~>^Thb+>48tG(xSjb|M zBI5k6jIB^zMT6B3M`QBuAIx+I8w7Ngd~nqTm)btw@9A)@2}DK->(mX$r0N`5ldQB! z66`Nnbl!Y~=r?d6$Ar8a`3B{h7iP`LMMgF=ldE^fCfywD3`*zCbpTeUm_w*O=7}Ny zDLrVET4!b=77Tr0RnnD_d!*!e+YzN){}B(TBJa0R(2{v!456Q8(RUr5#uo>h#;u)1 za2OF6{y%a0_i;Lk0b$n{!^F*vkA##|-Dwl;t^18xlc8qFCCeM5H;n{xs@kxr>46&u zDw%=x1#s$!nAC^oR(L9zkuzy&a!PVy65dTt3mgJRYBn8(9p;i27WCF{-l&g_29mN8 z+Nl-1dJQ+U+Id{jWF{U^8>&y#3Brp{Tk?LzA3sn%Lk0WI(SZkZ1*_U2dW*Rnla)7J zndM+%!Ft8RW^dbn>_97z)54lD!^&#A_m@T#m#_f~p43O3)Ay*EU3F?{QhZ<7v(_lv z#7|y(2@cPe&Ue-g>nb%yr|s^o7{|z@qmKZcUZvi9BVL*j6ZP^F0#p+kYAizRT)<5r zw?Ft%bC(#xyQ_ScAC3RGqwg>oet4P zRhz@2$L1WaGF9e%QY1BT2l`JxW;VitK6Ykn528fWAbjev@ z<-5*u5h%i>G8(PU+3B^17Q~D}TbPz$jh{@Vn1k`-Hk=&xYt^_Z<1fXs{Lzjl$HI~M z0s=-rF0H92o-Cr1nw(;?s0=TnyU409MkEM(KH}(TEgv4CuIR0w!6-@Er%~)7Q zBpfSAQ3*Y<$k%?L?}8XO)_T;rRI;MlB2X(!m~`TblCIhocKmm4U6kt8eo)rgsM?ZHbUnPcANHhb_0Jjk}BvUwBnL}CXjXd=9VTz?Aj1h zSkTI2^v* z1M$l_DQR2p2g#*!dQ(}z%}uR$W+=Pngnqwb?5p^#ewM z%H<-8$Cb4$2g821ip=uxd!!7z!8YPKH0Yon+SKYsI74G#u&`H!%_+o2?;BiHRHWK# zo$!K!f}BQLrax6J5hH9faLfOaOW-5(S0bs|#(TjEg9YTu@qYVWFh-YiG@_HMg5f?tq>4#)&`*YskAU zGyJKH`F2mSy71Vh33R`umfP+MmwmHvem|ICH z)EW)%w&ZMX?IbxB+PE?t)%`rI`?=TA=-Nq6dY+6xO#Q;PBiN|8F{KkWt`n9^QH}0p zYv#w&jPLWzdkVE2D5Ui->0t5VL)=vmq?ELoSuwi9FifF@doD!zbE!^5d;7ulh42Io zQ9QiVdATs^7Z(-0+^wVIa6mcFY|cf^KoAwDtzse*#_>pjiyLGax!8J$={;UUbz}n2 zdIk-_p-n>E0|3bZ%udhyHm1NIGz40{OI4{{cJ1)ew`Ea#^?a|Zk5AET9+{2k3;H}+1>8({Zl)kWwrLX>mql5H=bK2eb0jU zvI03h(ZNP|60@%C3)TN>SOH$a4uCzm$S4IkXKZ*gKn!h9LU+urueI~n#DPSg@x_vnc?x-$k0vm z*Mejvc{vuluj?!ZU)xz8c18t^zxEGI!ICB_I(16@Zm(^|XF8ZAtz^qWO+$l7>xt?T zz4CU63vHE*mX;*+0mS>G3~Iaq;bb@={G#PfO|udasSzc}h*Gv~S!ZI>gz6U?bMZ(< zh^Xx?G!F#elVhQ%*wBa#hEHU>wvsL7gOVsDH@e_HTn(^HfX+Ln;o%$w=8xO#lY5+9 zSM$uGGYc_DRm3CaRa2V%kkjUm1K~9~Sf(}9-?XPa5*kw{B9R1QF9f31hw-A_`@Kql zYJ!x6RDEeWTybEaZhAB@Yao4P_FLzhZ(OvrO|kEcg*jlkyPV_A#2RhbGr=%t5o^3q`JIn5-C_ICKacy1P>m zr5g?{l82J+5(T6s4qYOhN=bkF;5g&F^S;0DpXc%#Wq6*oSKRAfYp=C_E}l!XmGC9) zStj6RjXIt&GNAUQL9+RtW9t))h#G=~M;EtEIDq&j#z(vRYMCKgB|F{X1h-_R+uPyM z(UjO9G)$uJvB#%>b^j1Zd(~a<^J;j>RL*EBQ=wQ!JKe>?0bj=w{4Q3;sm$*jj-=}PIvAV z1Z6VT#hAOYpUJpB2&O-RSL2w@GCciKJBql<_4AMniVIXqbbi1(OrDQyN`{Vy^6`hD zJ}ZTslbiA|xt2btd-YkOWK=%1WX&{0LN|dVewHgaC<}T|R&!A3U1k}fdWo(WMD-?| zknq`T!|g3aFGH)k$km0Og|_b*9pQPj)fOTSmIp?=bv9Gp)kG>eDAJ#(_@lVFlihBW z8YwdCdGk`Lt0cT}|4d<5!~AdraW}V-B9Mn{OXD31{*14PL$16E8V5mC;O_hAs-Lz) zt%~NO+o^G-Aw3vz?>dlth`IqiY2by(9R3enA28XIaHc)GGU7&JI9P6WKxi`TKFj|J$DvrtQY`p~!f@l~5x%8(0FCm*G44PM8028n^C( zfMm?Pq-K0Cf?Om#{p<_rn4Wr2u@qIHQQOrL%SaOM0fyIKN@M5=z|8YRuchnp%sQ`X z%S{jCI>?F_X5{a}dS9;9@yDvGWzLw0;rJEz$c^D(&-L}76B3~YyWM{Q{B6dM*N^jN zIAFs>_HWv5>3+Powl-{-;}*JIJN-^loSKJD@{tnlfB`d)T5ZU;!?7`q4<9~+*3@e} zxK^U7I;U*T0AKj>l-HfZ15xM?_C6y4ZDyUQvHEIHdvp{tQ#XGkRN86-@gOPlu_=n_nAe~*a!4HGZ0LvYQd(e7+^#Ztmli1i=5$z{ZY>`I24QNZ_Wx1P;4JWLbhnr%O)+}Z9 zbq_g3s2-{0GS0Wz@l)06u=1rUI89iYZEuJ>dkYn-Lf*8lifgOhB#)s(by6UEtX`qy zE-9NUnI@`^>?l_;%~d9lkd(N~L3ed;Ciu{;0mttae>kl7Rn}V#Xx6AwsDhDN!LcUG zRabUSh_uoD6}+*rsZd#7o4KhlvK5{3tHmtZb1>m)rh7Q5#id2K83L25LoJw8ZW7Rj zmkd|43#dyh7c6Ch)xUN*zbqK0JsCsfq;xW49vXP8+xM&q`iB)*)to4h(&f6Vx=yjS zY@r-%^MY&UMSQC%5#6^fKU0bjr`3pOsg6>g^xU>e5+Y0Y{z}l3%4s?lSY!0nDca`G zGkHi@10m%wQkQtb6N;(e^5S-Dkwj-4aF9f+%X)U)Mur(!IezxvN{@2fFdrt=d1XD1%`r zl=^MV4>@(~t_>aSzT)2z&OF@ypc}IOZn00TCv9Hb#ifJ@hQa4M^P(+?Wz6#tktgGK zrG#poq=5`7612$P@~fsdPaJ8{0W8pc*)P?Hk2D} zByWo-jG}$M6miBrJ9{(h!Ti|l7u$|g4JgWg_dud6fa|!r#%*D@@xy*Y$d_`mShsCF z>pmZq*NrV&*#`0Y`Z%V@qf>YBrc(~(aEi7}7$-YDy;R&N8E!xj$d6L$?NEt(d-GiR z2Doi0?JmwxC?YPsPL0>?8aD#=T!nmE5qeBc(|$Et#<)ohaq;x}TY*MSBnupA=uqYm zS%c+$IHOLZ3vQf}Ql5;0Bd9g5BVbq@;#Q>eaOz{Uc6r<0^Gs zAXU#Fbn)v{$lgxvs(C6WlfZ#pj`k=Wcj?s3+CLvqRtrG}LKXN&6!c1Sf`QK60`|*v zq=SQkuY#9u$mJDZotcdBn{9@LeqSY<`|&l`z{X1QtLL_Xy*T=oei?c-F|mQ3!CmEX z-@iHGC)6n*1RGp3OYmRJk|ekP^jJ|!`wAZ-bV+G?^xH(O)Xpoy2;w(p4R}iJzXk;T zUV;Osa2-hpqZI2j1{VpqJaaW?2$z)16r{)8a$cW?-NwS} zvLwtc8>goRY`V8s+|)*f=iX<_=9yVb6m>i==C<_fpu&7`A8=r8(sMuT=f>FYZ_Gx# z@IHA5sBLDj+)MQuOAyhO!;!(kfc6}^SWrCovS#52^F$YR(}U>Q@Lz==)CFK*M|3ce zTY{{{CL^!Mb^gSO#j&>G9y@ktDDbI*#=+{U?RC*Qp?Jpa>Erk@3{df$5YlJDp4jX` z2h>XgtW&i$c=+ChxaB4_k+4<&kJtH9S_EvhcM5WgY9ie+C#tfLrip?*2=8ur8R0k&naSd^k%bx}&t9Goj4IN-R_1&Q#D+qA6GcUQ&-XeeAvTJ+cFdq;uVMlwfq&CrFA(;R}R*j>GtynHxp^;(4?jH z4ms=j=f6~T#%QTzfkHVx~u%|QjLsk!%Asu3Jd1m4Yt ziZq(EVvXL5U9x`c>A-q}`1x131(ZT0Tp&lWgH-rL^CmG#_#FeAR}Y}hNXfNC5{(`2 zJQr)iA8!Tl?(Xwv6Hth;@*1gIavkl->3ZcLv6eH{(bp(pS$gT zktn~U_9v6-i%!=7rlKx|r}6n;cpRH=G}vG1r8>D~1)46$$MwKMXUv=eb%Uen?Z_Hi zDibLw8WCa2)z#G}ZzlU6U=c)yMPIo)jUq1UGNjq!*|S)nuH>*qzE)QLxy+1!ygR=Jw+pZ&AG6AwD~sZe!NA^*q>oY*zV2oq6|s zgEeuXdKbZd{j7nC&aKvTc`tygh?>?NzfGXq? zVd7J@`<^cQ8k)-D)Peihe29`m{(W&t#zV@XK%94iXI#p7j5n8AFTc~wwfE({mcsl`5& zUU@ZfVcO%8-f{YZqfl$=^}eNU224vL5UW1?{`|2()Ua?6 zri0lnQ))V)`6{{h{0({kbdEJ($7E;wG8TKj9i@ra8o|>iba#K%Rs;!Z0+_sw85QS; z-R?{zl6Om5slG4uwBJtLXm{%iz6m5+mRD6?(Izf929(dr(nuO`N7>=FCx(u-amRY8)qtVyKly_WM5MtpUc*#pl$*JD=d_oXugPf z3zy+{8-N7%pm+2jl1fX9+f)s?{$O=Xv`=a~wc?V(hkQD%GX0cRsz6i5Yc`xFU-z(5 zi&u9#@7rezhp|+Tiz`7shn~KR3UzWUmQ9S@Rh<`Mys=YLg|c53oPCs|l~t4r86&vR zZ-}D!6JcD7#4Vx^m>V0=QZ#vvf_9C1j?nDs^K+k#O}68Zq+#^lMBp zQKqa6mjHvb3cY+Z7&3&XXb$9JOnVDcTO;lCI;e)^S5`u50|UFdJ}GUcJhG_U;&-N_ zlgYsz7ggirLgi2~E-ZKq%a?Td+DYFr-xmF-4jvDKLvv(cSgEj0_Ik{2xf-ht4fX6Y z%BrdgioE!uOdV8h&YOv)YMfS{u^e^cyU}-?^t6IpHY(N?*^VqtJ2Bw3J0z9Y$rwD9 zq73mVRb^yD;^knOOlrldQ?U$QoOk_@GO<%YpCG%lH{WOpoxvBU;p4dh-+O)e7sVKL zkByeRVO@Rub~VjeC>R>8rM4?%cM3`qsV{%@ACFw(og|&FN$SD_&_t_LlK6jOV!*e2l%5FP@A0h!POQL7GX9GIntQ$EZ?T}frD^O#>9%pK~joQ zoP6SMh>7ns8;1yU`ZR1cZ1OM_%8Fg8z?{yt4ex#9&68awn`Z7-_Uf3yyFgfeEssbv z3MxAa!WNk>$Rl1(x{}sFs!`Ay$gc?vs@AH zR0bZ=S|pT-HU4aWl(@{`c}_)@MRePnZwu|_Ju9ER-&6F&0Nu^uIpi-wK`oY!wWhH3MyDV-5qfsH+D$tehSZ5FkuWE8TEA_=Z9L)T2ka_!Sc0C;O`RGpmfY8 zkBv+`WmTfA2Jep=!1G|E;SiGw2&Aj3S=@h;<7S0HkqQ5IZd09FNj%Hw^0xejm)|Cy zrss9#Jz9H`n%mN45!ifIr6w-E(yf0Sy_B8vJ?!P>_qAl;To>PG4={S(6gqVSX)(`G zFnBB$z734=Sd+B~eBOs$V@4P<@wtQ*KZ@zDz4{NMLfV*@M$7UQXtUd?Jux@8xwUTU z_j@!WO%ByQ-k z3ng1pM>?*BAN3fui4y>KbeHX&ia^o8n8+S}(dhAA5q;Z~IdS=l03-bo^+x+2p|}4f zBtcQ6kPa`Fec?U*iezVJ5J7_gep0shA#|GiM~lnasAcbP$zq?OK@AMB@$u9%ZbBW%d=!tfV`m%Q+md{3j-iF)&9t&XG>J8-1!Y$$X!=seFCM z8JWJSt7gmtHA*@1H`LnYwpInzK>iBHe!G$TEGm=BO%EphwT?ti3W=#t4!jS|=TDEm z^Ah)({j`tk(SG&t2m*4lEQ|%7%l~wR@o7fDLR|aINc|NLHhvLD)MP6)yPk%yp&HKZ zS4=>J{}fQmGKQD1s0-NT2gk!h^sSgd6w+B?n@sXIGMPjVf zfw%}3D*5-ck$gx9DmQo@8}&v>yUJ`BQKaU_Y>Z$=gGPh?W9N;oUWkWDj>S?RWO7-g zL_ww1azlgR;lOTsO0lS>T6~3ZNNh6G;&Od}kqKqFsVoCS^!S?Vhiju%@h$ccTW0|kSJcpGv!LSY&?jCJ;_=u}4<~r1O={5^Kt}{j_3G=`;M}{dn9L!Hw|YbG=w)daRUDP66>pxwElX!%bpip<6!g?hdD0t_YHNX##>Iev{D0Vq!uZ!=ipY z%gqTwm@Vj?gF{6-8X9Wx(OF;jsgQGsK^VyOUDc+#?vhiW-CLp4sTOD`hpz+ zE0P^8afRHUtRLMkA69ir5l~O!Rm8?AhewT9TSYI}`bIe}&{b}C#c+D0?7D4pJ$8)cN&eb{Z}$j1W?l(D2UWEg^S3cLu)D=no{O_B=KR zUnfA8W>-Tm!5OTHecXwXLCyOo&uT`xMZwY4kzZAPOoaE9I6a2=8?bY~D+ z+S&0W>a=BNC%Pk@U0qpXK{~A*<+$17eGU^`fUl{lA~}lNO0eFg8%Gq!_3Dt3F^MFn zlVh%Pn|g%`*IU5|=@f>+ZPNz%=ilxj-_q@ksBZ!A0=w@eOgb;Wlu_xmFrwr53Dv51 zV~O`fP%tT$mxO-ld!rbxPa%@MPyg)(lF@-1AR#1p0}86cbtYl_@yt;H&$IndEOD)C zYl~4dJ?cyp6En<}l+^sJe(cOsR=2BC@7BjhVp&n_~b8Flc`srd{eNp|L zx`kyzuSr6>Z)9|P#~NI-oJ)v9c~sXmRZ20g^%7@Y$MtVgqXO`X3z4jewBV+D1BFWq z{_I5LCr_!4yM}{?1xpYkYIaty7f_UI8@x8^Cu z;S`POe;)NMlP}!*Efc8`GOlbxZkS?rGGSTw#fUc@MtFO`~ZkKzuA=H@5 zKZ3ioS(`wHv1C!)R9v#oGriQVw~GBQtG%(Ji41r=Dx0R?3|E^kwCh$fiL$~mfrHXT zEn6{TjQlqJLev%wz0-pzdT6yGT(`DXDp#;UfLdli617i4ebQ^IgIXpX!(~0ihk=P{S%djfpo@_) zHaQ_T`q%@)pK8GY8Br^WCM5Fo#pb($>WY1XdcEAl$G)@*YFc3U9ZI2DtGvm;P%H|0 z@+AFaCy6LINvD;4*Q?&^(vwkrHVh2udRI#?>DS7Zmc%2&S*B@TgO)iR zqL*6Lpg1>#gjDXccQ_1@=R}I`VxBNFdIFB7p)&6yY0f66V@lyCwMupsXJ&D+oeP{D zSR6F-w-dPxoo>wlR1aZvIyiiF`z{R}q3Hyde8}t1U}f^n8*}cySWoV*BU{PItDgP&Ge20zt);Azoppb-DqO4x_D;jHpu)GgfN*@KQQ6=Pw5pbzvmN3L z+M!g9-bPzk5`P}f5)s<%d8+bE`0^zv?+r8_-)d#Y*Sz`CA9+sCuv7~su!CVN4812D zad$bwYuAFQEITbhjrgWESBvSeQLM$_PMg0n?P|I$|&@nuG z7>NRN6`TzHu7ict7B7f%C3Z*%g#1=s^okjGPjYS_F;kZP!tqp)dYTy;bYw(XDJnL3 z9Xk@D`Xnq2+tPMaJXhrnPqOesZQa42x_b-7pGG1O8^-01;*lf!(}gOqJT3lC^xlw; zFTTX9#!H-9^$oz4R_c%bAo7AD?|4~+*kR7^UPm~@?rCJ1@cEc! zZb!@SajV4@!^QGY+Mx6b|6Dyan3PYAL4hCsk)bb$Hj)1~Vf_@FTOH8W88m2wNO9@v zYEnWZHDjdvG1$l}_}C9cGdHLGB0_ZkI2$qb3~70KjE{20rD~OU)6$&f!dQG? z-@(IRa3d_4l_Bnw7r!6n&$mmFMY=fjPIB;i?C70+i=17Jjq=DBQ!jk;<_~9QXU4oD zh>LTj#d5#;NvdntBS#Zp|Hnl2j8VilpOEod{6G|8PnU}MkBl&mmA0+tcKjpoJu|xo zz;M>PG0M%`cVdi4Y=|}9a;w=fOEB1MCiMLmhvk2hTGXWuMbo8fBSOdoLM_1dNOOo@ zQSI5YjMK9-Ob7YCyzR1J?8T+U{H!LuIECCK61MnD&()tN!uohF6zT9_#kIAXQW2C8 zANSfaY;4u~XZ{o0jp}{qRHy4ul|W`*b$=M_&VDN<_5)V6((#GtpLy{w@mvoO4P;dH z+9(pIMM&vx_jc^Vsa`1A;nh@-p*}m;jv%OLi`6;OmV-$e#_a333z-w$tDA%vWZI-9A0 zz)p0Vks^dk-17P{h~syN-8kr)Z~JQ(IS4 zIFsm-?A@|<$^2r4HV%%Pd+%|+_xGvo&op{heHH&*FL&hpC2>#5M%n}&H-pylia!IL z+#uBDP|fXZ_?OgLFp)ZSSCqtnF)}-wfO@yp_C}7^RU`%oH9>qqmJY)2_C51>1PI{qYU9<)e&$VEwv>p!rPZQ|18q1s z);#m$6a>!urH_y)mGR{UzDey?!fnK)!7q*_0jc!K%BT6RBR$5BI`R9 zYHCVvrWyp}hDQqqS5=3;d>n*Bz+L`a+_-PooxyK9)0=Pn_;I4byS^(|PHBOAG;bQc z)6h_7QsY>L6SZu~1cpaw#IEpCX!KyOGzjFw!1xk$++<8u9n( z{`!+2DTtQ>x_(xZJgf6T#I-i5@vORVFz;r(=ZJFbTBQ42=8v^Vq~sP4H)l&&#>W|x zAO0c5)~IR?wB9_L%K_Sa@_hma{L9TjcDrA10Y-z}pmy92CZu*Op>M2Jd={KTjvp>R z#C7N_r}*o4|7{O`q)0!?B6{$g>Ve@jKZ|yioV2twW&H;Lj$F*WY@Y$kYh1#}&Yq~V zOz1K+1e;SshU25}ef%i>R&pPyJANpzQC5n-&+26o3M$88@dNPi7@Qo((aFFG$Lx?a z`!MeM1pnVJ&~gK~Nl7rNTd-ZO^({K`dmmxT%EraTye+d|P;K_A)sn|31Kjn%fY0G# zB`L_jC$f$HvX+*o;G~ykh(RRKQ}hsU^iOt*0aXfR^)z>SoqvO>YuA;)@uGLWTzT7D z(FX%|<1<7W7iaEiQ!Mi~)5+|cVPztUCZK~z5Zg@+2LU#y9L-WxakDw{9t&k5|CdP| z(?66n3RfpfE~q`LPb~j0I!Q%{{Lr2tO4l6z2S|_BtD~$}OyPNu$93;SS)&JDfR}riQ)Q(ora|y;Ei?nj0&s zBWC=ip??`Q$eDbQHUL3hURqlL2)#;*Qt9hUT&+5{QbHoa<39vyazP%bW4q;Y2Wgc) zf-+1@ao{p>^o|`QHwXR+y|ahi#p?fW2C2+93ZDTAtZ;73fhFkLFR$_&PdaxUsd_i5 zEv+ljzzA?*c&B`F#n;o_xLZ`dS3f*=#6m4=wO?ZO2Fi-S%py``D1j?)%``G%;X;g+ zqwmPOF|)`AzgltC*Yo_N8U;3M6!EFb;Q360VfLs(kpJKC#jWJhIw*cx2R)i>h4?6i zX9$Fu>))mUB0IMgv6zx&T07dRJjxpPgPn^(QW`CN)ytC?1a(L|s}j2G>TE4ZomF zg|QOwg(1yMgfebqWI|md?@I>tW<-ceTgs!sqh;C8pU<|sE!iHnP9xM{C@@NQ@v1$i zM(52qJpqcV;eYw5xkg|xQ}r(3vA$Z+sGD5?j&i?F&!k)CzrP?dyw>9Jl9-mFQRLZG~^P76aqf)Ve!>bI|-_yOA>8~trw0@zIc3i;_}QFdCZbO)^W2&Xn$WX?FG|(}S)0L3|%-@6*zm+W9-P$s(MRf0-BG z@}_r$&sX`rDb&BQ@ur;O#{ZOI)21v;6WUwff7Me z^-|BRU%zAL;bru`fsEed@J5!;gaw0%?jdpb=h|+0tjxQQ|9a8>xT!Z zCl5BuF4ok8C+Z-i0KC7r%_-<&z*JCBgrZrB70JyF9H;BFgkO)5y45xO4GlkLW+vJB z4m9W|Rce9FfKdd(;^O>_@nBb_b>%ZWT|m80mNm-p{foP&8G8@8|F2h-X@q5HsGIem zcm7$5`8@+cL0eYvLmAIUgBBGjdpDi}25kXmdb83fs83N=<+Q?l*(Teg7FbY(?wwgO zjcSzfmCeaGyF#?_hoF4>O%set%;*9v>ezU`H;okBr;prO&!;vehVE!)SIn>H5Rr2G zFSkKSheU)pAggIi6MMs3&Yg`F4l82pjgR}22mgo1_jhCy^$SHAul2>g-8ulG4q|)% zz9=Fr6u`iAD%M{zM!#Wq>5M#(P$9Sa;Qv-!KU1K%MmVzl9`|mC9pbzTG;SV^WMQt4 z0?hE?ZX3qm?rRHRWe|*!hrO3G({547I%KS7)}u=C_GcCSH%9{O+pQSbpbADOKYvyZ z-8c~9>_P;S!>$R7X2laMPE(H!88uZ1Lvw~GEy#~8&6V1K)38K50T@NVn~}^M)c7$HKo80rVS@;(k`I&^tk$IW8f+<1>j_j6ktVuvljk= zHhl#;S;b(#rrIl`K!RG9mhc5k5n*IxR8|u83pO-zcIqR4l)w^WXn584tZ$zJD>8MR zc<%g{06~Qc=}u^nC!UrzHtE$XLU~&|$2g5oy#2qh3e*E3K!9%usSEO++UTXp;8Cd= zn=aF%mVFR!!n$!w$KM8&J`2HOVwCYhO~8khV~+s(-~pqu{j-cBD_ihIkq}{}_ivD^C`#+82=jWsZf|mn~ zjH2MTPbBf2CMg*EEqYoAV(Nkt_3WYioMLPM#;%g2%_stVg4oW@EUVKx!N!4*-^@A# zm)IVnf|`l7lhb8{??JQ{6_pj~G6{WuWwpBMu|C1{zX92<&OVQtk>a&5`GFUX+&8yE z{t6{P{luQkEhgwASgNNCdsjL{&PyrX=KSw+3FHJI6*2+5avB=6x3|oCmbJNqN*!vF z6VI%b^#aBz(%C69W_s%ZLgDdO(;V<*}u_}*a&K(t%Yz&;N zyu3@qT2U#zw7fM@`Q39*X`IJqc($aj=YL~4%<}5hB%jA-%;I;SyL)b3vWmYfMwl8X z1ttlM;hvx0=uhO-WAzp>!Du~cf^qvEuk~Q`Zoj&rS3?IY^Phg_76`p1?(UE{2e6_~ z+ANPTCK|BQ6dD^Rb9}t92UwA~w^%5U9_$Qxv?_i*R=HKy$yO19nVq;~6;9s_ zY3c6ok-5ENr55GU7@W#g2Qi|N(EIqsAP9|LmkaI->Wt*)TX3LqIEGS8{zBs?Y(96v zowVc0Y*P3C9fj*X9XstG$CZvJZEk4~Q2h>JKpoB8Jm1jBs3=MxwGTBJ6}1fYZMG56 z@QhgyFBOQXIWK6;!mTH>z?Q$L)m5!3r+h*oH-RTe{CQCOECUIBv|W590?T&4tAZLa zURHMg_=^sc-stwwRV4mHMdc{b<^LPJT<5-weo9D(=p{$l z$w?==B!<(kN+8;j3*Z&d|5aNQIuR6PDifxqs+O}^Tgw<0Jox5g2w*&ZxG^vn{!+06 ze397Mw-H^oLv)Sy;~)Pwwi{0Xx5~{Rw?Od-Fn`fsYkhBwCmh+~{dR)sBxdI3pSQtE z?Z)%t^@&=?Ts%s_yo?NL+WYrcCM-)vbX}*jBO@bY=GsGVznz%Sl8}^ygMlm%_pid!EeS!!F+jG->z;;gU1vju?DGn?xd-duXSd*%`+`RK1=Xh#a z*wp(JZ1-3Lr!%7Hd#rMHe%M^ySG$kU-UoY5QXhu*^(mYk_4^_$OB!?JlX>z1nslk3 zzO$Pt5mIQWR;)9=Ft)I;0G31+#Kztd<_iV(8(u#tqLkD(bi}>JD3DZrq8o_dgS5~5(;W-$F&w# zhjQ05Ls-j}2q`GMyX>dIUiafoTVKmYmz9CLVRyJ?wi^%Ah$A`A!0cReP}4>1I(D;E zccyIH@p+^yj2A~u?tsg901K3Z!~_j$G@^|CF$e0be) z1?qd$t?$%^%d4^61SXPCG`N=|$MjNA4S}^rfkbFfx?9d*H%mZ(-9wDe39GP z0(-;-R|SdoJOSHNSVFdto9?59FSPeG;tb|DBXa%?AM9*ObqW_itdM)J+i4@62-1xK zZq@q z=+*^QN{b3Sbky~?wBB;sf4Kt=?%6}6V<(~Z{9zzbteu-Jo50A<{`ok9K+(z=uphnM zD$?GKjHwFTurhdon)K_}X?!~ET(L+?@pS%Af-VOQ#&F@eK}CJGH9*D&5K~w|d*Uxj z$p0<_65Dml_-$+mk(x&l-_nL>tHqT*3{3UT-TM{mfuR6yZpwW*6>$)eBXsmN=J7|UIeX}QIcZr1vZAGIdQ z;*P~w4&HUJ+SB9F=Bg$uGzFlz5sLgBR;fS6`+X1-GlN`2=$zWDF19$J+p0Z`tms*y zxozWqJTcFS6X*Pc@{c*@IgAt4P5VVe3hdg?TrfK2GORKtR?(m*huhTw)+RIa^Yb0m z*Ut7d>O@FIezfB6HEw%vzfcKXrilQJ--Z=N?F_P}dn{jD zU89iD)mxh~H*fB_G5{Nb2!6=*M`>|O zB31xi{8WL`d%Q;G-2d9eh zh{%TXu24C*srt2zA)>C%&H-dRVM}gFgJ~ZkghY89m*jxyt;hC<=RY*5de7xwxuqSI z)HGEqDYl^D)+jCU!iHgbW#?SmPuNgzQJ`Hdw}dW=LHIAVZ1Z%swlX6tu}vr zAX41pV=o`c9yf6SrFr@k&KrR9qAfV#flb?v35lA(<6uSi6i2}R%;r@vf4xet?&AC; z!nS&B2pt4bFWAGRqtr^Q9%qO+=dvq)q&HZ{tyN_;&QL$z=viHP5^ru&Aj|o3s~3a^ zZ*PZQ4_An@z;?rKA-2`D_94pn#fk4l|Ab6Mu1S@cklmbLB}Go@CMYqzZR!iz1*x@v zD}b-hfN*DGyap7+1mVfCpjC#`Kncvd*Tkp~6_I3xv@HIKT z*79?mK!?=6XVn&7`at>k^i0K{vby_I1yCe6ngb?-SBJDY-aivpkU* zlG|q?y0dNp5>k-#&(Zl76}k<-3LaMixasybtH`e5{ljw z9{Kb0b5&}xte}`lw|rpIK5RPwEQBqB=KXT->}KDeQqszLE4BFJhtat2kt}HZLtN-K zy#KF>QC|WY6czg&<7@9axJE_hbcl@Y-wJo_M@CEI;Y`8o=@KuZ#}fy2|HHx-%J{~3 zxp9@|M!qvphfPcUp@j$$pDvZ{+GR?no33=dswVYo@Pcst2_aF$@Nia3ON)w&C9olF zucW0_)G`VImzAUC^y>ExIl;;K*AYTfBi;d^J!!`0#JWhQwoJ;RTxhMy`$Pddveq%I z51M+}xP9w7kO`>pBas8$$pKIZoVXnpW zGGesWDfJMf!AjNBE|cH7UuyYnOwOKHQF`wwIlH(}roT;3PY-zhyy!ifZc$Yg;@B<& zq%t~h&x_fYk@?+oVDW|csAZt#LW|3m5)kDcjI|N2fW=tfJ%;Th9^ubS*VZ1pP4hzl z8NKY<%mj$uqj4ynzIj-fvTo{2W2o8KkYYEWaP%}ino4@o+%G#GFZl$wNF-m*`m*|J zCt#A~7T;~z(s3amx;^^Bs_YYu5$KJ-kxF)wXwyur^emyt(1;Hz)~F5aSQ|aold)Y_RYR2PB&+f z=u#gy|H8+`$4G$Shcx`Ez{P%_oKjE+o~i{M2d1n51RP6*34(*cUIW6^? zZZDfE1#)4pn*F4D#z>*lownoci*wt8ez0ugyPFw&mWbRCwd_+2eL-Gcr=c52D=G{> z2CGD?g3WXM{1YD58H_(|LHBQ40RF+)w7VbKH(g0h`w=@5my8Dxlg|WUQ*FqC^1l0~ zmbNyyeVQpGA<@;-hwukIwBN#PJ7Fmx?RwesItX7D0>K7rmHhjK=%rk$^fVgmI^`l> z|IIbIMO+qCMxKG9p1DSPfPqr5!}iyef27t|&k>T}&MLgmIDJb3T~cL{&e(+n(N?svX8JJc@0lk_X}e73m@_IrFQ;_pXy%~Pc= z$j|>gR%*l&P*cMPZaW=zemf+j%Mkn33($O_tFGssy?-o<(FwezX<4xj@;cS^m%tzD zp+OHiD9h2H%e3^C$6r5TU%xJBAhOu1k<~Qy92@Gb^d;pFzmuTt1tldSdgS-Pa-c_#9wE2^(9IV=SY2}BFS-F%rN{3Nf^+EE z4hB1&8>qM~Vj<2TZ-2 zWoeU3juBc5wMF~8X zFk92nI>|16T0qhrV|DccmvgVm5-r;09+>x5+q$9?e|DdO`K&O5kZxPG4aCf)3Jst9 zX=`8Vzxu&`vr*&$Y!TFetYr_71DdIq33;!rkE3!2-HW~Si=%YJX!A}W8@b4=*Ezu7 zY9&p_@cju8o{CFAprY5kh)F;FFriS^*f{NB{SfrL2%9iBpDwZ$dCq{g31t3%Uqqxi zrri{7t?Ru%!qLjWNk!DMHZw&`tzBUj#lgW*SS%|m%k6XOcF6oC*JG7I)Wqf6ZIJg> z#zbIYC$-GwwmG!VHJxk??e>e5w6{w#>6o>fw@)_Kg3hEq?mIW0@JoOQKLyCf!UPo9 z*|&}&BuhKBQ}H>__Oi#1Ke^e1oi-LHoN^=$p*GT+UJ|Zt6Xm!zEPOb>PoGr8B)<<9 za%ELoavN^zg_&Co?^N+D?(K};*Ap@QEtLJ1>ins>XCx1sRitHPl%1U`oi}L{bTR=# zW}>5$TwGlASj|q@1N_b>RRT_fw;(`klsH!+ZMAMSC%I5jzBLl$9G-Px^LtT-vb}vN zF^}hBoO+>*#_ZXaYtimiCQ)!-kf6W=A-s!u7|mKUhvvONHah@tLeUXG=5$uZ?Pl;o z*i(p$OBJ0$id(>2P}8iQ@hAXm&?E}Bk-4?Q!#BlX0!puw(cKq-A=W+QUN@f@%$6-; zG~_ht0lRL33hgF|6b0{=>za=yS#vg9MuWa6ww3SQY}MFpiJ+UB!?j4Mnab<326Gkk zPHNhsmVw?>(CqZFL&e`Jl2XQIVG)_)H2CFsl^tQqE1BjVz&N@<+jhem<0FxMsuS<6 zfn8J|~m2lp@orwReyK z;^_2fx3cwAuQ2GKPhfim@M4vEXML_sG%C{@PDSAUDl(Gt*v@!O?DinSZJUmAOnQ@? z2i>=@BO3v5N07kMZA?yj>bL5;tqZ*BP+vgMi8gGpib?Y{+E3 z9eHS*#;;x&*&ep;NTuhQd9)l3%l*gm!wku-NEu3 z3jecK=I>ANaPp4u$ws-_6RYLERCqyw%G0NjUltaMP~x%p0L``*%gd{+B7C+tq~=_t zTkoQ&O(iKVZnia5i>OLuQZKHkD%m?ctS-Jl(uvklVvy{CKaJ?GchqA6JsM7^ zWm7tje0Iq|i@fLHeR;qlw6?Z(99AA=#erIxbiw?B(Opr*GA4C%jfQqvIfUK4EIcu~ zlYwC{mO=T?K7TT@?6#onFtTjlQ!z#cdyFo*k;?TFS3rzxBYvEn#3`%1&C8(^Iw{b1 z@7=rg;Qz4jzg}*J5jb&BdRF;=?7d}Nl}Uod!?#f<`?%zYdy;x7GY3EM%46xF7BQu)_T8vvT?sZ zP%BAO>n;>p$r2iG%X*Rebto-@usJs^{bJU>9=#XtYygM1PKR?mav^}%-ejpUSqC?Ya| zYwL3AkQ0RiD_Mv(IcyxJu6A@PRDXbu((^;<^l+`r}CUZ~ti+ zA*3b^RC=*wGXnZf!jE~$79$r1e^lfv)Q`D0C+TH!oesSaK8v~wdUbj?_?0jt?2i)h z?|M(Sa&v6?-_wZU699{d*urROT4pyIUJawl zLDI`w{fS=mZ+2Ylm9rVEg0&_kVSx!!g4-J!^ORFfulll*?OQ=$h(Twbo#^c zSL6AQw}7JrY)t05<6ulQ*x6aJ3JwmvL&ccY)`+9U!uCR=!u|n{#19-2M<5tb`WW5T zmOy(sZLzR^Jdxp=$j|I&gIk|APGW|>xs|GkUg zG-MeSt#W|i1uS$6yB%EG-w{;mGz<$Bav;h)}EQL5h^$umI+~1*q{%Z2h=N^*~0qP+=fQU@9)~hl! zJ6j==QGRlgvI>w8XRZUo!YVvW{5phMDB=YEnRtZr$`25?z7!d42Pa$q;U}YL)r8FE zQeL50j_BL;p0xvCRJd*x?|E1*!kFnFw6}$?uiqgHNaT@C5a>q4rJ_j#0sOfA=$LJ3 zl0ED)-F96}Wv|mwC@JD-n?~mnMb=1RwMvOaSAQP7MAWY8{NKUm{`LI$rZFBb5J_Pz zEb#Vi&A6nz=h-@1Kj^jjC58qm)b;zx?|8VQ$SQlYK!6oBNqYGPb$Qz4^X94T!d9j)}J0 zfM~0ymN9U>WU6M3ahH#;V{JfJN7OucrFKK*gQC28@cgf~>92n3zZ|nuEXRY^)ymgE z*cV}1LLk$d^98Sj$QZTfe0FyozfWEyo+!FcG&z}YgSMckh>I|h9WR;(3aCYdYtxee za4HiZV~f8{c3Uwt2-1EG)0iTD9dDv#SJ2DD1Lbio7#2TrM=;)1ynI>1=*_Hz(AkR$ zWo5ls+X9qHWo4=+wW30Vd3THwpKOV37SYJwzT%%4)~ydJtqMdlQN1oS$>o|f=+zj~ zfwsd=9v#{ns3#MysgxYrpTdpxyAA1Ner3e{b$kACp@5M~9v#z2xARwhw9I^bhUZob zBVLl>D&2~cvaM7=*0XY!9Gu3qw1g{^*-Os{5rb09roRI-353AU?jgIpjvA zWu%Pluqk2dZ;X3OOLY^I3`a$UQU*@dAB_7@k*Or1J_@X(;GVhYH4B7`0u4;s{&F?=p8O%*VN(Ci{}mvL zVhdDu)zz&GD>ahM!H&h&dQQ8o2w9VKxRKG3T)=_EDu6-E(aX;oa2laBY{&CnZ#su4 zsSf5@_VM23i#`#bxwq#52vb%QZ=VnA>!KSKV*y?fl3juI;SJ0w#quM|a3I%3E#j(x z#}|Cn)=#$fY`@N9FvrK1pw{>BgOls_?7LKlpY3WtRg7@p#pN zug_ecE%Rh$IBThht8C0IL%5SahEWox$F{#%$ZFbnM%fbh)qxN0_4M4}@hDAnrR(fXBK?zb&7@t}IA{HUlHGm`EeSQ=zNX>GA1oCBf7QM0FF&!N0Lgph; zeGk{D6kWXS0y3hJ_D(c`q?J;SW&|DIBY620l$8ruEE(zeeQJ0e($T|lL=ExF0@Z{q zO4Ij74zCc}b*Oy|C`*`c9ZYhVz9Ez+pG>3S)97ZKtEy(!PmSo5hZvcay_@h*WW9ZR zbDGmzexs8=?(d*@k}67X}Z*xa+@BD z=CHx!^092Zy!@=xFP{HMw*K=e|FaGF} zzPq%wg;^eFKgweZ0o*z1=qM(Jd+I>l2ZM!eWG>?XPhxbZU{)pW1YX{{5486j7=SI` zJBdl6#&yPL%vcvf1MwV#n(N%gdA?Tq&}OAAE;4cvkIhKbqil?}7OuEp@WcL$`Jgej zn0K!-WRUl8WZe<0#Aywws* z5JltYYsFCmw>?R3#>u8>qn~UpAYk1V#a#7hTA?W(W&VFzcp4$chg1NN-+l9`-c4S9 z6i6Yc&4M@#YsoWGg~PQy*>~AJI^4NY;$A`tXqf=3YFa)rZ6Re&+Y21pRw=IYFTpIR z-hc4mIVot7DaODstgiNEkAk(o&O9Uul2e6pyD-%q(WQbcg9_VA0^JA@tQ_o12(hqa zK0m8}>z>p5<|r+K2+TV%m~XOAJY z@>meK4;va3q+|IhhHb3$uu91SV|QjN9K_BP@0ChsSH%&%h*vPyr+5zxLO_5jDR9cX z?CR{g=22V&Tg61}2|mrC2paRC@m!`sV<|nxPv)Tp3HewV>;lW~lQuQUy?VY{9@(~A z`_6|+XV`Unji((H6>M}8g%k?CuOUA(v-Th2b*FR1-!xn`?DsQn+`JiUfZAnde)aOD z`U|3hp8vy)fK+Ii5UXOn$ISIwL;d_JMNa6K@4E%e7*sdl05FajZ~bI)@;iiQtEG(fC%HE2Sh*;#F~w(~+vAYD=A;ms z{6H&{vAYYgwGVs}1(+Y}R{6Q+4N4<%Rcq}T3H)UbOj?A?Tnm-w=UuX5mHPJ{$fFYM zQ-mp#IA!mr1=N2_=Lin&kJT!K4JQeKv~^UYrqJJ_dH-TT8lD~Nt#qEVSRK#5YTyk$ z;$Vdsd(~K7xiY1s665sU&HAKGbo9FCj{b#-3iX~WKo7I&FJ*@C`iu(V_b%mK`wEQ$ zfLpGpO4(EZ(4euf0*-={Q^_{@RqOrnT9l$Pw2wk7m;ToM1VQzM{8wqrBe>q%K&64@ z1p<0`aj#;3uv17M*Cc-6Alq_RSKS4AW6|U0Z7i$oy@Z3&~7`q*~hW%4S=9Iz{B& zMUwJyROb7Ki?gVl?>5VK&*uCH68|z2|6))PAl|)0K~A}lx>|?6xU<|B^XvpgQ!~nG zUIU?$x}x)O&jatW8Y9N4_;$6vu+@*?gR;uNCK4jXI0p*si*-8zE6<2t(-@8bK@Q~h zr~AionToW3r~$wi+12ZJ$w%sqNTqNTnPH=OeTyCh0+AvlYGJC;Ypll3&)j@OAHwI* zc}XRbfj}ARlc+CvF7x?= zsqe24{O}?K3W7WWrAt%P{3X%`mhP2~j!sZOUN~iIYo(wRRZydmAi7H(8mzmYDd|&J zY7rK&I%G@(d1OK%;9cbxaB+|;@ImAEgXvZK)`^;(omf!mM4Zohbxe81)Nv|98zZhn zlTu~(s%P}q*u)DLRw;1f>QyKPtZWg`>paHA2m1_=v5sF_JA0tsdEl_^jwU^MXOjIs zmgsdn`@P0v{fw1c+#6d3`OITmYP6_Gr1;EG&HY2FK}&^3(htrn0I_?+dCkATmh}|D z2XY$}Q|$OI(?ia>>!|d$4xGyv`?`pB&ayiHL~0bhEI>eDo)8EnX14 z!+eW90HBc>Y^K7RqdI=Pjg@Y#&T`PzYRdGIK4PmOVv^}^Uv5&YPX;D{n1Fe5@)flR z%$PCBAvA#q83)5WtuLdnumsF>svG?_EEnT#*SjW%x-JuyiwzQ#mBE_WJmK+(U}6%8 z_QPLf&YZP2ReLQHdM)iWP>HY!{ba=Y%+k;F0rT-~!Qr&j)zODd7D3o=+wkeRr3phc zrh>y_{hq7VDr6^UOZ!K~GuLi}vOY9_XFTIYc79Q~%J0#P6HuwR^BxM%W4&Wu0Ia@w zow@kVhDZjniI|uQHfapAJdA7zxoP>W`RU^4N?g@;x`%S=a6#O)9D-8}64g{+4tzv@{;-feJ>ihjQ z95@Dsm{VM{9(eow>~RK7Z2xo6-q$(xGOu|>E5o|cvJXi_hH+zKN)(v#3D~D9#48j^ zLkSZ3Ia^76>D$`#x@a>1e*@h~`#<()(#wXSzBinth>1mK*XjqJBIq~wV+aqAz+*!L z8jOgk(Q#%Xjt_-BG#d#{QCy`BbZDq?s6J$!yO0>U($wh2iDg^vpP{~E_n*^ zjgzm(?8;G5?usJL--<{FaF(iwG8fQ=!+7lxLeDcl={V4c=AA5nlr;u!9pS6V=5o9C z506sgd+MJ5B6;o?Nw!Cq(f5X$`G=Z|lLZld42mTw+50hA%f7AHOvMC#+at?Fe&rDx zEfvR0{AdX?5(LrIJX+6@$jswdv;O#mpJm)R>7P?se2Ac zt}dKf^-OJ#Ws7(IA`0)44gIT##b0lC-$`)S2oW|*0gb%Ay60!NcAxGGh=E3IDHpxv zd;s*d)IL7`a$_i|yGm-z>R02eCnMS4zqBNygcPr`-`M%|+<#nHL<9=eMYpqRIhR%I z+R}zq1-C{L^L;qa zoiSnnPc>aoK%e6u+KhHVRY0_L7%%~6+Su47&8KTdUp+ciuhW2=4YEWO8+Q*o%}xn< z$}n?^<@8@o?P*+G+!{LdL8pc*HzMM&-DJEqIC0sw7n|d?*DMf;z&fLcZ|=X5q7hRV zE;m&4@IbU|&R12ZOYPVUXMR4Uvm>Z`G{^ljX}oexkklnVn#_>hx@oxk3Ts%Ex#zhG z9kDHE)`MjiLDw-eJD{)7dXf;DD{SH5;58{`O9PPeZxrC32T9TiK+_t{gS$a6CrY%s8WqhJv)pSIJ^rpJYP&qno4(YpEdQ1CLa_Hsiku3fu z>hc#0^=BhyGzv1F(&4FMt}3cFBiS@Ls*BnNAln|p0`LS{6Dk`gg zkad0m%D~6lI?{9NiD4=a&dkFF3&~=;D>jDIj7g41b{;bD@omLuF_&1fQr)=WjIA@s zSzN?bBGBJgeafX67$TJU@DemDufJHeq34>G7~2;sFd8XA(F#73*Rw>AqQvPuB!tB(m|WyuJyVU zim}4cGi>MNel9_@2HbZ_GXq_%9PhKFj|YoQhCz>7{9 zg#9}@j;TdUOW|S&*Yf@$CRL{r)4plEm(!Zn1LeW1g|jC0Pbj{+-HxstMH$6x7H^b3 zCA#=+LDcTnLz1luL)%1ct#_Er@MKS0+pgVQwAOT`2M(!bZfILP;a^=9MSh-TY!;H; zLNC%$a%Xm5sZeWPUS1^{lNl8yCyhBIHUkGFU(+07(0 z4K=E_HTJY#DomV3Ig!${THEze?g7F@_?E=#;{LQ)k>Li)#oFM5omfSdY?vs3QUtf! zRB~85mB?yQWiE4?&7D;>Tktwuw$kygC%Ba=ir7l%8_v#3POf^2V>#H&2t$=-z84aB zVm4i|mOkbFSG)b^-F_Ug#=QW3Wx7mOM#h8VAk*_(QQhJ5n~$|DatP|bcMywzmAv!# zOMr!k$8Bh}7;o!l-111TkY?djt1fI%zkX(4;b6i~?f(vr2Xu-M(L9Z>hEvhcovG_5CF zSNA;*&T+Txw*)J>r-6hcvt@bPf{@gstg)5(v6#27^HXn@)Iln5l<2TD- zhlS+T3&$&4&--wah`1oyMuu6QKq4X0Z1@>SM zON0yuriuJBvx_;ab-Lw+ddMur7(s~E722S|6BxsPQ(gO0F2RmX@)=uu>*@}=qy!QO zF72mYTj*f}{ru3KTGg>c0ma>2jToHhLTY=j6gw2U4)kXfo=y@*XJuRY0A*aoJk5-w!H(SBh&(n@l zpiK;2sho|fu?Xu8yQ$@2n@?8ovW3@iQt+%r(uw#oL5Z*pYRcS~vOzn=BZuDN{VkaGw0=$hzFzWD1~Gl#%}wixK%jrq*{R9J+Cda6bdpD;ySI0$xb!uYadBdNdouII z-qY30myd*K()>F-JTeDhIa2sC7Bd85eE=ta;R114Y3oQ|hH0Uer9mM^jMfaVh1Q(e zVriUpLPg~tTG;0UKfz&+umZ9keEQep$s#>l~}=tE}$q+Hmv_ru}vT9 z&2^wAm}kUv=P6UBBp1_D!8}R9yt>1dy`_D7?b-;BMq@;v)B=%z|LhK$^I8q1t{Ms2G0ex4})OAZ&#$AOJ?=9lGw0m$UfR5POZa0ZO!9LYLf-Zux z0iodXENOAH#=ubSRI^Ohz@P}OJ*h=RcxuBf=@Q%=76ZEWMn|R;ENwc^dg|sWz!Ur@ zlSDs{%V|w6+GV z#~8%6eu+r&(9qSwSuG|A=WEmUV$6)QvJ5B6`f_T8J^C}m&h~A!`zqns@aZuh!k9<< z8CSzIbcXuS(6+WJi!CeL+9Mx|?v&*k)li1VB73C8gg@iWojVT@z&4lSgJL&lYzuS#3Sr^~UTqmW` zfXfEX?0NxewId5bQy&k$OWhZ*R;7 zrm$Mq8$^vK*iCoa4v`!O?(UeZ!Z!_YzrJi{F7GNbS`vUX^3$H554YsDty0>tK&$b$ zzjAL(iL`suha%wT7p7Q}dQ)cj#soAcVN*0DXOg3I# zzAGXnDX)LZbT>~b9?A+_$|(+cc?`Hi^E3$`|+N$kUZnXQ%GmOQg7VZxg;6U55(nq`N6*YrOj8>r( zf4wXJ;yn7kybTuib@*dD%O0w`DswmxCN_>$mvLTF`*g7CDrKr--$B4NkVg#HiY0@s z)qeGha9xGnx6LQk)zLJ7WdotVyY}3A{xl?8Ly!6DYz?U~3}dh!#yH=PGJ4zxe| zJvzX(=e>jFK6N0l@Rht{L`jV7VEID$+$y%8mQ-Y7#3U{Aj{h>>BWT;JSL8s=G%X^c z)j1Tao!i+psSTTUL`Q9HNfW3YM7NEyn5p=4lSr49ck~TpXU>=dHky%xE%ow5q{m0=W0C?jXFe7!3;!JvCbw?1H1ybp4KjKdqajv1|K? z_L=ENZXD+;Sv^%tiuCo9LFQr_f49uc60mb%`LABRW?{J<-7>0|RD4tXbD!@i@!CU~ z1kz+VE!$mlK3lJ9DSaPzPAy9r?^^T0L2E^6e_GFxk)$1I5>&HE)#w`CXQ7|+d#r%@ zJ#$?heR^PMD7R5IY~g9$j@WW;0c^2)JgdNS6(MzRa&&aDd|@GC_N%e`MH-C->q6$m zp?e_88u$!ab4EsIB`w)l9Ly=0+HK`@6>#7+Mut%dF_bvnxXx@!0C|}#v!*bp8;uw5 zBN}_p75w>3Yc`E=roXq(yYg;XT<}O{sj|wj)nwO!`9q{3*YTS5V zMnRVfU>6AYnVzv}>(+Wxq*f~}y#OLSqZy@H3xFDrOr}Aann$;@kz3BX=CMXzSn{N! zD=SxIX9sEkzds>~X1QB2*(D-&9p?iWrIMv(cutj$e79ImRIDM) zSSyxzf3NiMp%*(7vjgh2wAO8Fz&h~stmc4fEowlcg?V^z@zGf;uZR)(2Kiq{D^+m! z0PSIV>Y)_Vz4IwRCTQn98Ri5W?kaE+qg|7b{Y@O4lkGkGt9Lai&$r(^Z$J_U920ME zZ>x)^ld>47VI{h0Y}YgeIaO1x^N_Q!Lv!<#Cfzq~LrQewI$6FqeHE>@lVcM!E5zlp zn8DIIkxJ%*mD#toD?Fn2rg>f23htRIReQ_A zP-wP`b#+SK7G9+p1_GHFcAd<0cuAC<@%^7e@hDvb+1AGM(x6L&f!91kEl9g<^9n2i z0STavkp2dG?Nv&9@0hGbPEEB-TQzVyRg=^P{7H1UJ+YKmDTE-O@V$M5IpcNWe0&0E zWR~<*kVL}ckqt>gUA#}zE>MwIZKyDFa?U_o(yJGQoMx&{;A;+vP5ao2WFCBCJk2IL zbGmhS1PAmkXF^FW<{v-Nvd~Q=xPF~@W(Jj$`A`fnP9$6l{G4V4-*Tf>7|}{G@w?_< zS!jLHZ}%*GSxB_tV7;Q?P|Ti3j&OWA7B-%6!~X^qg_TtVC%Ge~fZSEArMXt#i_A9z1$v22<4p;_^Cy`f6dCe1mJ;~R$WhF$)kVeB%Rm9?Ja z_MnbTme1q}l7Lte65D)Zc+qyt+ND@i^e%>^BL_F&p$S>+2`V&O#A{)okp|h#mO)d7 zb+EU%@;29*JdN$;zM4={c2fV%hJXtmfLi)^pfg_OD@WCpFUm>gHh+@D{7Ze|_rrD% zFe3TSn}Vb(hkjk&sg}@rT~&$vWZ;Y+eeY(qpYRTU77JB+W#=nt%2Lx28(r#@qu~PX zG;pRoJfRwznL;Jz$b#Y?c!G!st{0EQ0&lbqq&`R}nM9w~X=>*dDQ{RzMhc#>V3Um5 zd{5Rc;w(oZEW!t*RROT~wj^bS7K~uEnI#(k=oWW9l%C}D6by7?*+MqHGowsD@88da z979FQ6VJ?cK=ks8po}Gh&p|qj#f!526)C)_ZvYhqS7>Jm-_l~(7}|klf@ z=XYJHb7sb9L)kqgifq{}rvtEOe98`VKXxpK`B$7#ahN}}Sv)VmV75sfZCBKp%-EOj zJfo6kX_#@dge#GzM7gEfDq2%mRer=LuQXY8G4!*7En8(C!uo+uHGgJsXX_6Rv-=9>pHyW2eOTDc1U!ywf@qHZzP=0y$WK`VWCi{@qgr=7)*!-l$1W>LJb#nqs%AnWIsyO-oDs+>wBj-nxgaO6{;s2(rquns)1I^Oe2vc;e0^WS#p)e~FPVB$`vy({c|x zm6gMpZ+53dcO`{;c+x{;s@|5&6|U@HLv@=wLPy30MjK-H#ks#)2uRL|7gF5_I>hU@ zT*!b6+7uB#-qv8JRC?#CL@N9|#}iy!+u?9qn0t0cLm2HH-FnFT7ylD>?E z8_4Y8jM;6KKAu7qEyXoQ1iN;c(Jrxn42)^I^>Wtocs@QqpXI{o%?27*!RQwAs}#&2 zjaJ3%)#5qiCjReN;h#K=YdWAp&t(xvXu$Rm2GK=dbzS;c&=^<-Vw$@=+~jVX>V&o^ zc@i^iv(&j6*ljc_;>nQ@1C3~IUb}*sK}~K!uLdGE231(2cWBl@&cWhHnTYL%r#C)c z6Lqq+s(TQagq*<`_`rFrtTcsP3tm}#&@eDa0eT%tR`57+l!CZsTV)K`O7ml&v&%AJ8uWe29kOr=89Bf9bpUWo6rUQ zDw#tH>nUV@?9OL~X-ybQAx0ySl5^k`&>g|2ORG#52M3=gK$d?Nofi6!2g+?Eo=QO&dtb1Ij>hA|>adbJ#l!j(u zenI1jLCW`ynKp^1bsin<$%J@Sbz4ImVFqfw@ni|x@4h4;zA=jxRjTT)%tPemwVh@Z*x70M z%H5o&Lda>n>EZj`Dt*2iyTo}_%5M>iS$HR~rC@sidFDOH@nLxx=a+d$%zjYcqvgRx zOPTw=8X6jLSjY6#AnHGf0R4S&Uh*B_tWv#YHlm1R8+DxgEG@S6ePh^tGna#$JlCp= znsB97>pqDeoa!11b4l*Ob5VYrzH$h_#{;27He)o(^lgbR#3=NW+at`Yi6r0E0x19UAmTRBLRk*ZL^$7H!oSHJUuGu|hiHM~-ydX@DQ8aRe@ zRF-a?+h(is`ugkrgKaxYkajOb^?-SD@9_7HDsOK!YuH%|Qu(*fHir-IEQ`I)L~V;g z%Vtpp&KXv-wwk#{0q=GR6@*<4>L58#P{Dk+?J@>8C}6i9v|95cWMOA^7-wa3R`|Kh z`Aa~gup$4_H`JdQYv?XrNGUap70lNd}11y*Pxz>0q?*&l1uuBgkX zP-3}sgKE0c{{A?CUW&OWO|oi5^$(*uOL@(5vX}*!@kRIQ{%-eK8N8 zBi>p!`-EX28%>|1?K`pxkl58z#V2$;tB>Wo##6)+QX?}6L1!I|Wh8CQs`&Ku47Zut z=-H^de~I1yCcLL}0WqPBF&^Bk3Bx+cf=)6LUWe|>g6K7O5$Fa;nu820>p1<(=}%!0U|CVWz4G-zZZ{Hb_Oa_sf2ucv6w+iI%Q zb!YO^`A7Nb$99Z-i^5fug|#Qn>c|%I^cLy$-}8TGY+=7@9m zu*U9}+22>gm5J*kx98g_!V3ED%xjEW>8I2w9AX@IuST(wpJS#z*XB9(!YlBiwYx_Z zYVf{%Y%uidEx1*T%Xn*STSj=gJJipWO7G8<#um@O&Dw`z8u=?_AX~w8-)E_9j02 z-0{Jy6kx$6v%v-8Gb=)2Q0oy@xWZgj<=>LGuB{yHm7~J4+_q}9S7+fo(r%ZpGmru2 zX>9LWd%XIRnno}@pEYD2W%ohD{y+v~p`sKNrs4%u$NO@o#SjYa03I|v*;r-r;fC#S zg*qBm(BJ-w_^#kjqOaTT0uvEsVs0GW)uoaw>?9)#!r|>f!@-oGtGFuAc>om2>_L$X zq*zX-x+yaVwwuu67AWV67anvyd-o?>|&GACrGdEbV-{-&VV zOxbLGk9dH{$NSi=(Z^4p|1uNc_3G{RYJuqJM)0Ii0ZBjz_F{}`P|sS8nS{W(@3l=` z$t%3=ZBj|MM9#8{nolxWV-0i?MEi0So0^C@bt&V!xO)bz`FyxH zU7i9!ug24}fw+-bbuBvSG9g81V)a8Bf3tyNOt}bu5Qx zEvlC9q1>CdQw~eDAhfiW zD3;x`hnSP98xUsI>k_?C*f(-VSg)in8yP2U8)^41KyGpWV z?@nFTW^(sqm|g6;)Aw~#3zoPTWWtOy4l&DA;h677fzFgxBu}ZAOaaXV>I{VTx0x-D ze3UN+^08A7j9_hg=yl7jfC80@eegUB*&bWQ#y=15_qgs~eg=^QUhB0pJ*d~fbb;ER zMOSj)8jr>1dQXPO@;gF4fIH6a)gT-!)UwB+HdH&Bm; z9<#h0du;e%3sKS1;zUJaHN42qERUHdU$#!i9xC{y1fbVzEA+?pIhnmay{Vb)X3C+H zj^`;MPpVh*?e$+^BHF$5?sqHz6V&xk&)?CJqN_Ecyi$5Ro6((>bs7}iI(T@>L|GMs z0P(@Ti~0j6bI*78ji~VOG+y+cj3mE$H}_u1pP_?)H)Jkpu*zfaC3Rl2T{@RrjFgw~ znYk{uv)&;*f=4QZ$&P^vQHtkki018%_E*2Oo{Jd!g+KB3vxXOhHVf^NlE;Pe!_>mI z{Z0Pe#1V>xHCD3$=iOHpZS|#6zU#zDn>1e6g8l(UP;BN7rGe}fo3vMW!QnVu)yDP+ zVz4;`rClt=%F2?2WFZO(al4~^`ERbDKNbBzgyBmBWNMcf16x5fySX_x>Q5rml>)mqHpi0C!IBLuuL+;8_v6~jm*w3_mmplM zs*|IZ>y#AjBJ_rDGd2Bd#di~Qr>yN_tgNO0SJ%=CrO?+~n)yaj5%9EYDxIL*t_8&F z8vs4{=@+2mA7XS~oA75|SsoB+?Pi~CNO`X>OEdt*zQ@Z zk>;L7+|3+LOp>)^16pc~FIbs@W^2I$<7$r3XzqlBBn1?+5cnnh0N{sA%QJn#`?MjRat@HdR^ zqT&94l(|N6?o8H-9kP5dexQd4CLLIK=1gb6elpGc;{n&fka4?Q@AKFdqqhPgKDv2^ zFf%rgA)4JcQZv}EJaRy|wCX|`R3VX3DQQK7Z*5q{?6t>3NwW~HXf{5mnWbeyY;2Bu zUyil8ahf@(rhznD5(6`HTRiq(8pQm)tA2t20s#;r>So;P&f-*Cr0`)gmB-BP?AGTL zvExjyJ}a!X-Y%J-e2me(_QzRMg; zcFI>yt}{kb(tsoszvENyr9L4NhF?AKarf|?F1w^J8z?$9ra12Wo9zrSr~rKm7u!?4tJAr-1E0@fWE48S=#*^mDGW@5{s=p99p>lv}aztLVaZ*X=xw zh{)tuI(EwvVJ#aoJH1;IBdcts12_4d215=#mR+&7M|Cz6&+P>4lMiP%bYAy+haMto zdiEC#yYYp0Qd`L2cNi)SYYk>CJV(8khJ_F671un>6cf60KrY@aCx`Ve52PgTv$k;> zkQ#u#PF>ZcateLgBoJQhVs_dVVDgWL}H);nW@OAWtxF;qiChR%s*OeksScTStPJFx+ z9}&hP;m~g}7%AN#6~oTXUZn;{M&_s>5yQNMF`Qb*$RGh5HMbSLHa`{q=~Gjg<46)Kz9uDa0$ zlT+L7`8x3a)k0g5R(`wOPCwJ_S_pgR!SKxhCn?KQl)Bv)qVVL=NF-7vuCwkZw{S54 zo`rn*rW>6V5OBt#*gl?}_w*HLL%t{sNX`INJgc31iU}@DaWO8=k8M>#X@@Y;_+t=I5}+9W@5oq%7F zI{_*NL|m=TmwjK}`2-uU_S(gCC5zi@&jKlb%~(VX-|tQv^zydx1F z>Pa&J`pf#5hsT8n4vtVI-S`M@Oe414#HU`Ak8d61_?Eu3@Xdaf&i}f*iT#jRX1uKP zAwdY@o)J&%1eEV|{&AZB(^n0d05S(!lDsCRQ_Pda^Pwdci=h;(n;!@Abu9O@{z(t)?>wbH zes&(P@`K4vojlzP{WQ1sW!Ur6GXqg?ossTTEfZ;fzl&m-MgA?0j+s+a;WVmT*N~zx zD8t0zLA$uSMhO}PXx4DoLU;xOT*}7qcymh1P@AWDe^TrI_hY{E1|;@QQ#)4$H{_GM zdF;D@g*-?l^{f?!Xl54hS(DdobhVa7XIR=z7Y`b0tqatp!7aM2%q)>B+O;|tceH3X z+(a|*^ou`3-2($A0$~%|WIz%ry}dP|fyXq3*ls^$c(5;{@%nWu!)jO>z}~tImxj~C z5w>`EOjSC|gS>2%=U%A-3SGv_2c^==?_HSgD07>XVhIaTiu^f~M)ww+d4_L9k~^2L zJ@NJC_nz)b_Q*oYSMTrjV*sE7(7cmUB`^=>S7H(pr$O(GZ319o@3qcV!o~3N)qNE88jA)ZWTHfBa?K zDdp179jG`rkYZsRkF$SxPRY_2Xe$A7@4{Jd=M;J$?N@=U&7RK}0rC`qCtpv*`?uI2 zQ4zCq>h3#B>g%C2I@d_8J3!r}4>Z65zKg<4SM=aw*7{JCxaS=8PYwP($koI1r12ov zd7kwn4wnUb%N^K{fSDhe7{Ft=%f$9_2^3?PM6F|@lGt_+G(4+$pjkT$&|NF5C=Fe7 zf0Zx=!uhd0Q|7e4zYbJAjRC})Dh|c#>+7%o(TnTfUt-4|{jdCOX^Q;kuctK}xF$0|f9|gM4_6 z_LKTm@%;SUV|6AV$W5QxEjwMDNJWYLM|YF|@D{$Ofxc$Un^UUgmn(1tXD{9y=+dt) z%|R)6>gx2r4o@2gMQRm=2mx{p55rW)?>-dUn~znV6u#1cK%-I%F%ehtwW~Cp0ObyV z%{3s9CkQP!pP#CgNE-EmTRgG!L5nXvS0y2E)-(YQ*urJ$qic$n#w;reDFiOj+uf9(?87wZ3T=>9UOE5{rUKT^@LpE|R@ef->O z2hzW6q5rT*MBox4t4kh-0SlVF^s)CIFk5Ia zCB^N&aYrkY`z2hQ6(FjziaLC$J{Hy!2=*JkLR!b*m@MLf@gm!s`z#1`M#%kLjeCADkk=` zMjZIbr-4%z^Xcx1vH!zo-XGiD3KP}tpS32JB>%}t`033>=Wu-5SBCnW{>x(j(;Ug! zAD=59f{)(+htC`vyO$!{oBwEo`CpIn6}{tKpL)XiXXt~!ZTc%(;4}YQp8qY+|4z^U zPS5|0+yCw!a4*RH|8n(^|&MBGu7Ct>#-0RN~&rPSs>L_cE{^%p$Hl2yzAe@|lK0r!=zVZBF$WY3j|xiHOnRFqZpl%KRq0Krb~+_z z{MusD2t#ClApHIX+f3xh&rN&Y-rE;{lCoK>ZV>8Ir)gDr zjVSE$oydy1unFr}v0sHjUgr|%)ysr|%lWQaFL!Yh);__-;ViwJ=eq`xxYedU=Nw$PcrZ|}KMOH{f~;aWy* zZEkd^uDWd~(aG@>8B$RH&gE7jJa#{g$>&cUyPpklglDRYO+_;HhT`P$e_sUmIfWU^GND(o-bXN01goC%lyumg#*RKIvqz+wAfnnf<&`Nrtm<5v+>@fx^ zmF9FC`+evx%xeHeB4w1w){@TEe?j&LM`qtu$=O!x^$8Y!R?}^u+i(vSK z4&nGsq^7~`7^ZU3ECnP&FG+riAqt*pj-a`NYq7(tt-b$!EuPtFHr+~i%nb%hMO|{( zl)e|Y=$vsp*vR9-iajC!?Kio?PiGHrE#^Kq;lEa#D?UTI5CRAY7sc;mUT$i9(*DgM zHzEcPO(b|OclE~)##y+AsT5aebH$tSe}qA!!oJ}!hZo}Sj<>VCJsVpa&p8Aen7wKm z6fs_{+jc~`pYHnLPWcL=jpz5ld?bKO?;(`l-iu|R1pC=Lq!etd*O%^mVfX_b{{A6w zww12oiGFP5hnKG{hA@cupu&`+)Tac0dq28xLK#TYtzpaCr`zlp19OqwBA61Y=->X`N3k@>AReRW@+i8pVLPbWhH?`R_2q=5}nA-5|-?^P+^~*PVKf?$S-)Vofmo2;Iwfs_~!VJiiy` ziO;M!<$}L%PImA3ExZg2mwsn)J>ulLUTFA4Sa62B8M7Bx-CeACD~J~6XId=LhW}m0 z_|7jN?EK}Lx$tpkBqe=c?NM!R8dO-*D)lbT@Bj+rq75BWjJi|AhASLQzNfI=-~PVY zr@A;9c+pI%&wdqZH7|M}8b^4htGCKf^S7MidHlY$m|XlwchMyc1p zJP_@r*E9t-S-cv$D5&lK_< zD!cRhLJxqT{1JQm;g9c|rRiY6#yrp3)BYY1k|L^q%uEx>I2Tzc+?5J?vbG13HXv> z;F5zCk<#YkU>x{dTF{Tr3F!K>?QPzc<1aI?**x=GIQW?n65XW|mP1~%1=U~o!G@ouNvD(X_t z6=GjLJ@1wM;^5k4@cx@7H}~T}&ywhv7)BERI|@`Q!`sIVDvxFD1<6x)J1t6$-ulI1 z>}{za|Bt=*3~O>-+J*&Xp`c=+s7SF>MLq6pG^4L$T4 z6%~-)O9-GyZz3f^AbBS$Ywf+(yPxOVzrXj72Wq%;-B+18=bUq{x#8p#u;cWX74tjL z{F=2D4D62&NpSwkWkY6}tA$*2en;LBd@$*!8?V^LfYFfkrhh;B@#XbvD+NE|?hMX8 zs}_L!eWNj#cYNeIH>grlFmIoN`*~46t;`QOy!%4+K!HKs6)^*;9j60j`Cu)a-T34% zE;Mz6qy8ox<{q4=JwO@Y0;_STP^; zHaKe|3CFf|eD(tST_9fieydXa-BN2iLMK zb`jK8B76%E5w%(RU$!!e@&4$Uqihrhp4k`X zxXg3@1`D-;xs6Kpfnr@EmVB#%QKQc%Y>MbwVBXUhXUfs(ZFeYMJGV1~RJ&g@%Yy&ih=r0C_NbUwM2k<8K6d$BB5 ztMBz9VaKb0;W1z;3lr-P=SQX;JaYpM#LP%wr<2p;#+j9%&cem>2Kx{3!7IHjC^$NE zso$9I=c0X@3|z2%KfOdtSvRYHUAGVI1h1Ly_GtVx{~wzQPgkX<0L2A(++;1^1`ZKf zaQe6PR5qpH6*reDO4 zXF7E1oasev_O3v8GLOD_XDDh!cs!ysGl33Ts&J_-)OU+G&)>1^$0%w*H6&}ngUfKs z0SoqrVl{NDK;F0Y^an+2nEwn+`CR@lQ>~<|X*i24+t=ECw#9^nxH1%v-e4sO^c{du-(kHb( znM}8X`r6g2wmd)jTA>&7`vi{w!UYl$ORf}F>Zu`bF3gxb8aFYlBSGh|Jh!>xUUeig z3#t|1{bnYhLtX4>=_q@j^m=>nbfZ2Avt$F+gtNv&9GmSNQ<>>;x1r&7&G)dp$yyH5 zH^*qa^6;$4y}ZNb*tKYECTi_9s(lUW7b)+9v2ScqD2#<}kL<2r_iw)C*zf{vh@TXG zPKyj*beXt1XJ1k(ZD?X*4y{@TDjc&qoh9;U%?+lo)gQ5h>ILz6caTDRcvL@>jyG!#7sF;U zJRI5HV*7C3KHgq0V0(1+>Rk1wb=$S?a4CbM_<|#3V88_?Q$mcXIQRMTlE_$cLqmhY zYV*e&4CXsO78@yuSsH9{HU}lfr{?DF)j3=&;VkPCG!UGKnDbbKZc=$m6<4lZJF+TO z*WyZ$!e(YRxaRb&u0FCRTlK98tFz`UVy6yrnbB^~`u^T-c$U`*0*ta#%^V#;H?K1v zPY%@OBMi?>)^z1 z((4E}%(sXvS2)frL!(Rm1=m*hp##Q2dqet7f}kaZIJpH^oULmB!Ag7i*+>!d@PiuU zTA2+6e*GFrtKKICHA7|nt&H?6XB~3Mv-SzP2bD^-9+8TApX$;NIF5d<^@}YioN2CH zs6k>0?%0Wkd)+?!usA@cBniK74CHSNEu#jeV(yl#9(b!>Pf9N_{_>L82l4uIE@|(I z`FpbrToL$n%UqguAU=(&3m8GG(0kmU9Rzu#vjD}d2eFqZHT>6j*9L*0xmJ4 zg4(GQXLU|H)|LlrgQO^IBQkppoec3qdBztpp zv!JzdOL-&Hx$E((Q|8GXozAX3y{7DOvf%f zOt;^7EFz&NVI@KGYWB8pQs{UWUMoUxqccM3o#fJJmOO_&yx9ekk=2D^nOS=s)vlJn z?Cfm8>Kg*O6)6zE&b;%Xe{5y#m2Qn9;#!)eXQD;irTUwdO82mE(*N-|X!8oGx^RWB z%WPqL@}7_n_n*&Jm2k$o2R#CO*a2NgrjF_IR}r8~kzpGenSLYIPQJ=X!6`%3q~$0D zjU8Ezfz8d)c~!VcX)q+9_`$5T`N2hR#)SwKAix8 zuF@IaQwNT^Tl*Nw3H@0M9O4N`=73Gx6eUnTcX-D~-Yemdtwv^-i-}pSn)4AH3+oP4 zS8tk(*vO^2#In@lXA8`b&<*C*W_p$geLtreqIA)OVo zoxc@0o5eZ~XSBHXbrlsy`A5v-h2Pp2;R3vC<{DRFl1bl(q7YG-kd~Z7m+2WO&0y{0 z2CN49TSa}bOA^>o^&gle3kWn?#0|pUXKP<*T0e|WvJThA&YD!-GrGr%^NZ99Y0%+o zxh27zWp=kYt~O1!h(PDA=g!~1hbQZ{F;n5Jqfs-p)au3JHg$)>rD=10V$@QbKNGJZ z(_;2DZ$vz1BnU--JGd}i5?Wbi z9eOa~Z*CGcG`nIxQHl5}7!-Ap%d;5 z>y=odgvskwJwvANv&QN8OEFM7XJ0$e#J|yx$IoS(EL^u*5g}+DIdbHvKvs)Mo$1>v z?tw@jiL96hh}jwsd@{7>fX%d;$2v6bVrm8#P`Z!V(w?!#P}cW;s_f+-# zlUmz>HE+h9=-k9?-u^lD#Y346OQnjTH{ZGp#eKEd2`)7Cr#pU~OkGxFLgPCLr<@gd zrOK98=2c9q1hmSV$kT1@n>dObuDn;M zV=zJ!ZYCoW1<$^6WVJHZ($vGz7hY%J&eqBEP&)5!uCc!*S7vT0hImSdd86068%YhHOE*;5_Xo7d76HoE^LZ__Jg zJ#w9Gva9})?h2FWl=YTdmO|*TT|t5V0byG>-;9Fu2S%?iKpg0GRRCbEic|6s^|sY8 zW)4b>#XODK79v6~+ox{T9#%4IOT2lXJ_X7#qVQFHMW&sOwC0^v+6lGQhcT8o(K8o> z^0g!0?qS^%bEAc%hL5XDYb!Ev`QC6Qc8d6iX!PFBw0A|(+@frWh#Q4;`pKrEInNR5 zOT^6^s`cK-MRiRaD(%Mn556iOzbZKwgx_Wte+KNGM~O`UVtanHWP7vKeA(M0m5GMr zXNNaAat<~O2jPOc-zoRZ_F3>$O&W`R%>EKV^Kvly#rExnqvAmtc%Jn`bH>4e&2LP3 z=A=G)%ZaiDibR)m$)C3h*gMguA}$fn|4PJ$?v2(;^E-+5&Z`3i<|c=%m*sUva@_7Y z;1Mzp&bahtv#Ht=7@`_y$A0Xk@otB!?5E$cQr?W=H z^7|M2T<@z1>~TDcpIkAUh(M0LO&c%p?0aKd%pKcQCvR@Ws^ZzS>OS&@YQoX{bEa3= zltsK#i`JN!JGNl4ATwpqSWUTnfmJl83mEC4jvTGP7uv{-?x@(;t4nv84p~mK6MWMU zhgr2E&#vFeH!ZP{q!pzPs_@dry=L8DYhA>)uf1KUyZNTYo}PQ4*QF@Y+hBXVxumxt zMuV%WYHMronpG^@UY4V*Kc3$it~1%4wyx(#R2FO}Rl_-8svIw9WpvuS z*UJq-mlMyy%VPAgI1#kZi|l@rV}vD52hXNhxQ8DWtZ5rC#5Do{yR<5NVeMn$k@!Tci z#wUnR$*)Z;Hlw+E^F|MxbpKM_F*{oz7wC{R?KBlT%sw@cj0_&>o2>d%<9R?H7%lnT z!ar%k(^y$a>+}7~%%Zyc`K77B<3OX=no)HFjBEh@L4oNZT65+Dw!9wNOh>c24&n#N zZ%XSPO}&295IJp`Z>)yycZlqnO)Ef(H#{ogULS0Wq-oA}Yf)_u!tsP^6T#^$-Ali7 z)Pke^-t)KU|^Vm+BwUT3!`C zeA3(|uwRj^*(PXUaEG=qZ~Od#_-i(N>+j33t$pefUwsdHr0winsI(x}d`F$0?8*$~ zu4glMA@Htypao^`|XQVn1p%DgEaLRTWi*|*1SR7_}9EB*&93-guKIh zUdEz|`nQuc`K1g-y@H#DNY44uXD%>jpF#dEXYq=GJ37MEIvW}&(wlODkY}_i>c<*q z9YZJY-Nd+Scq&-7obS4Q>SD$hhLBAE$liGYH=@}y?erUL1cTy=m~;2!4PVUTD{-MW zrKd>xRIjzV>#BT8E&9LkkTbj^R&zX+c@)AvEGH-$;42&jc^RfeXp9(>R9R1>#?Fyz zlPJwLMIEQR$|?yme5%DK5W?3S4Qq$>%ei`v5`(oFOuN$5Ph6A@Z+2a#tyiCtO^kAZ zu-AX@tu>DNDdg->xuP|1hJC=^5bpOWZ*F8KIz2I4%Hj-{x1=LnD&_mM;C6em6<0IR zhSo_yopdL;VN0y=13Bn@nZ36Khe$VNHXSsdDI61Kb9Nv$U#iQ=4@a9m;K~>)mJiUo ze3ow0)$5}=wV|5;y5otw`nvsfs%mv5Au5bv>FZBN$5<*fm?~fu%0zYax~16aek_ja z;;!#0W@Ecxb9b<|b8)g_Nzi)8pBtSI_u*l39mHh@4YruypookAefFsJnUvi68K2ps$rvqzox@Z zHF6hxgdUhV*I%EVKZQa9xXQEmLAw$uKM`i($%k)^Cr$UE6Y$W)zAOfu6Qi^*n0xmXH zrOy9n#({==-}2+M4fdxjU(16rl{JZGRVoP4pS!E`@W-sAV4Y$Zp@;aE4jG93X&@H80+@Qi-8rJA_+O!m5 zbO=SDPq32c0yCq+e0gf8j-jePTk9TR<817aobH29PWn5w*Ue*BgQV9VXnHiTlD37h zx44FlCzbB+Dqq`f*p5iLADNYtmg~5ucwn&XFU#%cm>!uD#;=%oFWWOIF#q)azPh&VyWvZxU%1 z>fgT;1|CB>1P8s)1?IViO%JCbq>rP3+{3i`k3TI#$7|!N>3p;? znkO-HH_B6)p9gwhvO2H4)_>GLP-?xPr|I|rk4?LX`OMK}LKlm~P+=ToQ0oiFRwne5 zTH`BBmIvI@k8sj|9}>Og$)`*x>Ho3usoD~aqGk*nqp#gGACbc-YaF9TuOE6_khJ*6 zSH9nXjB_6lcwXl)KU?&9c^}w0Eq4%6FC_N3L2@?oyy?q8cBuj5);LREjqGz$cT^qo zv`%2RMe>{uyc zb^4fo*+bUGj)2I}owoY5g{EjRLaalN*Q? z`M1dqzC1fzaxN?(hshI{gcfcgUUj-(IRQPO!Zqm!r9IaBa&;?@`=$CD*0DLqh*%DE zu@w%WKGJ2R9pI$53v$RMmBhBk4b}EcZtHIr8@5pJ-EA8%!6F|Za=AZ>yphYG*BT_N z+RZA&bTmL?r_hz~XRx&D9F2xHd;_6G;%rqb9Zv7%n(}_%Vdwr056ESs^Rr)Yy=Sz} z-K4^Rsq8myir7!U9D=URnfJq$sqzZYVc|J53j2v@|5TJ6^xMl-~lYD1@r=nInm`fjvQo(A@HPKB6@)@NjiY$|z1L zMVLr?b&!&f_fM1E#}JhvA0BCbroEP(M&)eva)%`UAw=M1rT|80>=w~v?h~H5O&fX~ zTCRN`Gd-43p$?R0sE%f@88lrT#F!anw%tLW$k?VGvB9)s39U%!FPlrJR+Tut6L?u? zfy=b@7?I$CQZQ0}7tthn%`d-ph8eul~geHIK@& zF@#96C9dRZPS(B%^!rmpc0^?c^wBOKQ`-~bng)@)J+7^Gc=A@IlcmW~d=FRuHf_;~ zD|PGwvg7esb!v~e%O&G7nE_9HgwE!tce7$(4SjbW|G9?lw>|ix-xfT$IlmxG(%@B> zs27lB{y6NMNu6$oO|m2|>`_~j4{*LC_ecG^FO*|QmI|!dktA?o%@0fMR6&J-7P?&s zLbq!4t%XAC>=|Qtsa%>eB{UU=bHQ>68nmwui7Hc8Pi5t1*`R(+{t)($11B3VF=3=K zrIl>>2*Wlp$9@y*hROgnKR)RHnNXLN+d13t7*^TH_~QYo*;}kdVnZ&qb6SbpH+`aY z6f|=0xRyS?no6Tsf%4MN)02t@(igWd-JNv;@y=UgQIk_GI?@3hN5jNPABqAV$>PVi z&q2tEbUNF`kLmG`%mP`(oc?9~!u7Xx>w78lb5{E)LVIk$7?jhehEy)LP&vQBRNv*+ zNw2wwU9zuB9--jX3bz)NPn)9CM)D%Uu2m*oqQb!W8W3)k99<qS3!COC~Rdj|x$gK9W zbDX*q&;4$hcs3fF2Sav1rSp_#K2M-Fy!V}9TG)picUp}K6D49kfH7(ud}VspVS&*) z<9^P3vB>Q`AvCVm(aN5Dp@foq>l@Q~vLCB0c~IZKj$_Jg$Q5;R7|yJaR3zoRS=GF~ z!23JdR*#09Z?;{b@K4`qu`7j`z>VE^r6fq^_3FWed%@TPy+9j22w>*NTnpp*AnAxw zJ)_1{um0?6Sl)T{&uA-r#o@?55Nf;#^efBZ8oZBH)hDyeS-z*+wEH%!v71h;7ijIb^?30JNF7h>zBYw3|22;{Ek+nZQ4RqnJ0oSysIIT z+?~xxt5?t|=`&Xpyw3Q@80;aFR#T`Wv5vv$b1t8Y)rTY+__7Eo==Y|VN?8MoYp}(W zad4+_Y0fC6o&24Ajn6`xu8W;FWy(?JCl7Kqt{$B#`-0$HLY>fO>aK8Jh--4V6yDIY zk?x?%7qj2X0WJ3A)CJ}}FRgwqO{NA1z1lD1_`GV2u2~5H>+hv$ktSLYe~bp>k3Isr z*XiA^Gb!ie<>0@+{yJbPY1D@3X(E{6GV#vW*OyO)y3`II5$WEh9YQDpC+%HRx(7F* zId7@9K6-kBr6rZvTlCmaPUG11Vv48Zcqv!2r3HvV1>1W67Egpof!FIVG`{%@+Hi(U zQ%)C+%+*Eq)r{{EHFDXB*rz@EPwH5u+?H+l2hR&JajN0M9&N6ddsIOtsRuHnBZ8z- z#p2uz010?9zc%JQW7{(kQH#F2=#o_1zI%TCwsmY1B#EEP7yoG8v~sQlH@G$>pwBe^ zT+FIs>a<#;Odu?v=tMgluIS4PRC?K?8gJ01ooVx@iY-@o7N*Fdzt&P#6EZX^{K414 z`3{F7nKoC4Q79IdY}G_>Xn@_rpN?|(x=G{97~?MnrkQY3R@C;(B}hnx;Zz{W(`jWA z*~E%`E0`CXGUT_8-)C+yP}ES)bqKxR(6b2_PnN?&(oKb_^*k6`ruUSUrK#^Kxy>|v zzUzj%WyP03;Qyo0B4%6>Wy6n%FkYER^Cw0^Cqm3teDnXPOLFYk^^)e64`0}{!M(jf zitcu(_(+0&U+IwrVa2|mh!#<5g}>8xMnnwOjCch{ObW$38(C6VZ;s%qY)Pc{^k`QUW)(IIg{azliC$BH&t!fN5QYGtHVe7 zC2HyBLHoihq}Ke5QoN^#^G%vD=l)GYml9iKw zdT@hEh^;n4&|vmUfIyJzAehadSQKduK10kY9kL_Oa3|n&a~(W4TRBq5^@e+05ZnB*3CN2LDp=7RT_JrM2b)lkZ<9dXpkd9$2i`SC z-5b!-vFmB;TKDLF?iP+ooWL?`03q_Y1$F_mMudK$vIL2RYJy&qYZr^A14CM(z#t>yv4H80kEY)wLJ#}r;;8kP{^(}c6S3R0RS6}FaK_7i z+Xn@*`3ZB{h#5j2H%)^#03pz6c^ha~*7WcH?Qt0?HbK!Eh;qu_xk7((DFJ}pTfO68 z6S!2rcr>mTb>0Y2ANanYOSQ}ARQOrl=>fL~muP*L3puF`2ZFGHPY3p+5m&NpCt{rk zMuTPM^=@BLoQU|;rk_89{ED7VnNj&%nj9?cR;rS%S3Ph<#O$j)GsrATvn*0ZUMc;2 zH{SEN%k9Rl`0%pDzjGxep1Td26N}}^_80y)3v&G|nql{(jdm3Pc)RX;)+dZt6O!dC zcScO&JyvZI6KKsmcI~tM+YqX~4;&zfIAj7q(=>3BEh6_OO{g?^!=7+Ls_51jS0F&B z@=u1SjYU6ts;P^CdreJi7+-}pfSVa-zYXc##M2DqD`Ojo)Ei-^&gYhWp>rP#(;Ot8 zaLbt1p6SWaP2E#0(S0XXNa^{Z{h9Jw*hd}&_Q2eZaa6Dy?uMwW=))g2Gr)8pRVK)j z$-y5bC94IN6EyD$??HW#@8@+%TMaKjzhUY+`hh-V>Ib6#R>=|c$qR<{A(9jP^a6ZY zAt9wz%uV1=>~iugY^WQ+*Js1tNi}?I=ziOW4?At(BmOIpvRSA-XU#oi;(v}*)7Z1X zi=UVjej?3lI{B#1d}+Qpb^g@ZvJvWNh-8Q_=H;rsx&PWiYmx6N(;L)1XK~ipK=lX> z7d?Hxw$~gR2Ak_E^N%)$$t35mOE-VfE2F>Yl@bcQ;=3lMv>KGdg~y&|JBbVBfslpc z#D(zcfM}`TMTD|1pfpFrFg@-dMds*VBKwGfyO{@9UI3>8Nc#BObNtT4xzfsg?Px^S zpu%3n5gcT|DQMcMu38Q^*=2yIFL&%=k_LP zBpkgf!}6)l88lm>ulKb=<7T_W1a-ffd%4zVGpXwj%w#I07mr!ur*nN0ekzmrc$eQlFwwI(F zKVLc{)3e>)>h~fRu;d}Og*{?}`%JM@y26<|GQ2MUoLBCxWWO?%*j-H+ni;xIcZ!nr z5=VV|OFMrKwt&I#!=+}c-U^*Ix10-1f6U=Z^Rk#Tu$MF^Ek@pWopnj2)1#wtwM1SH zJTf+p@Z#GH{j`>4l*04Ch2a{4MisH%HH47k+3e4CZC4PIl2tEL>Ag{G)_vP8V0tsr zUgPd{g&Z+QOEW#h*tfz~Y5R#R8D2)u6`sOVtel;0bWCnJG606>-?_T&%$6BtEbELH zbCaD!9K02w!BoGY;3X+=huEgTP#&(19!#YTT(?i<9Ot^_smyc=b~&pl!$7vSaOHf( zOtx7!dR|h`V+G-?VtRJP#FIUHTEyDWoTOHvrFG$)*QIV&J3u^vVfrB!H_;&P2R0t{Ru}Ig)~Vvr$X}VZ-mn)?>Xovagh=$o9M=vO@$;JN?z`|O@G!UYLu&tK?hr-; z`5uqPhD2Xs&tlwE6&Fb&!<_wbAX3z%AXbe$bEhp$wIUK?jP^KG3p=<=uJ6=~?B~Ia zmt8;6UK{u9;F*dZ*LC_iEd?rXN`Q6l$$(RahaYP4^Ko`wiNB1D6+8=YE!cr-wQNM3vB_Rbol&I5eU&K)%)r_mX&!G>} zdkARF**B?#q%t}lA1sc4CKg}eYs8MvJr}kOv2S9WA!I5M0m=K=%AuPDzVg@1;xqjo zkP^`bbP29hX_JmC`_$%Gm@)!ZSZ3&SxouugukmVS(k9bcpFZNp@u-a6Dbri)qQYC@ z>eiLJTs>{^Qh8WXh5Mw~gEr36dPvRZXyoX;_`npdwhy7O;F!mhO45HT6^ms#e%;|Y zT0YG~v2<2_^5(*`$oqe)$ zQZ#7bkt!AD+&b^W)Nnt591cu*=UEVFbwR1++ig>@<(=#oM!k68B zR!}qX8p<~#Co@;gXWxp7D+1GDJMDEn+srZZkBrsjBP&1)uU(_!LJZvAd2NAP>RXrO zBrC~mduE%OgH6LyPl?04TST&--v@std!}UdT?$O+)QzqyFcm}0GEbd|C9P*=si*PW zLw|YQvNrQ$IbZ$Q4TN}SJe!-$v`%}iba83bET(ag=ycN;?aKWlRfc}qU7mI%F*?m?;%vUXyIj!<4XBthUJE5rn-ze%cv_ z;Y@dNj~i_hr#%E^^*`QXLg4+TA01yWyiQq(A?qEBk;hr7gcfS_y3^~PA0C}=aGYH~ z{)C#azL8AsnNSpvO>@tn2!U5t2Rq$y5Z7DaalVTS3=TJ2sx5V18z$;KBleP2hSMyK z^IAlR6L$)m$wa#c7ZLRv-E}*In5GGT&<6i5DfXe*n$K}EK@?jf%Xyay(ci95&AmgO z3FB$of0UYPSH|~Oy&dWdw|#dXKF}7fhIAA@$Z5fsJI|Qt&A=AuS(>73UBCNW{$;B8|~h)Z)dRQK-rx~ zYh&}C%OrJ?7v6_<)YHkwdK~wZ&D}NGYAZ03OqcSUEHFaTu)HvS^VFH8`8nfL4Cf@q zP~;m{IY|Yt$QMURH4mD^O`gdf_sV~mcEvbc{TUJwB(m(xWD@JBA(U0Hn|i0=6;ERC zj(oiki%t$>lmvhIVV5t$g_u)Kx!EQfB`$U|`Ha5-D@b~kV6;Y0!U8D)&d#s?o&)sg z4@aQBKuF+QlW=Ppv!@w8Dg3EXV|ZY>8Y1IX^z}XbEP2)XX~7ZOw9|b0rKxu^(oi96 zp7x$D<%&TGO=N6~l)u;TTs>UH*uA`Lcki9EEj$xX-jG?i_~N;{dNv!*#25L{v*Q{n(+ad>XRHo}3cBOueUIK&rb6xt^e@K2Ovu+;e9s8>20S(VITY^0)CODvU&jh?=b!KZ;AUNKr13*(bonUqv@atbXKkqf;CGcC(3fL zto^h~l;I|kPzoNcyjTC>qT)^NYrgC+_9Pj#y z2l2_Oa!%B|ACt=F&?dJEbQdn;R`Q@p9H<7%d$B*h&}XTo?-kxUHCxa6_l5pBktrv> z^&qXwNBYK_qepXV2t)3b(}vD?N6m|sJ1y9N)4zo|w&eq0j;Ie(hB9BdAWi63I#%GK zkQ2AkpR8SI>~*-{UqAPAR+Av{W2^GldOf)&YkB7n26l_kGdC&0Yl~0Ar&rvgJTGD$ zd$fB}ud`$!vNXIngkb{WsrUYLJHP($ilFux6ZY8)&9udV8aWp&Y8jQIRq(FF5@$>o zI3*k`Zy<(;yibOzSLEL>FW^iD$(PWl#*e=<760;BSn~gS3A@)fsQ92?7_>3mnz_HN z^#ARzvP$r}Mz3B6{;7)G`eoUB`*#|+e_@kw>hq-9Zt?!<{t}0&+qh!$*KCemw?wUn zs&>wl*^W}e_f?>%`g(GZIS<#qi+Zd(NQ_4q(9uiPQ3^nQPUI7f5gGDYFe3Bz2ex>f zMv8_mQL5*i!(AvP7|yXCu9*)x1N#b8g96Hatpz_%H02lnjmH1C*YWcUL@!77TH50(`WwSm+;jyMOZZiCVx zw=AM7L{T{aaKuGqV!)*R`exOAl=V!$;mIeQYq3>Lv+s%~_=O6)Y`?8}`g54#r}mX> z>j$)zZQLByQg$m@Nz{J4Npc9X5`|2>8hv1IM$s?BxYbUlk3R|hRfz?AgiZ$@XlzXR z<4!-%)|ZFm0y*n2rp54&tz&nM(}D^EqG=?gsACsFxoUN>X7X0%?Ni7~ryRD2-`=MA zMT7nSz2Us>!e*hFnX(N0@4f&EJ+&cJk6G;2)VEAl3j8#xTX0_ySqhREh_*}Y#y-VF zG2GZHOxd^dF^spVi5mVW!yvZ4ol_U=)YPW}_N~|YWxinQzP|F5kzEA=W`C^nkSUPq z1$$UUn#=I1Q+%-b4S8vMi=eX^O@@WVnT0X@m!w??mZjje0e(uivSh4J4PKf;zY z2MtO7MaSs~YJ(%deCD5tb2&bL5p?+_{K%4%Me)KWK_U;@?v@%k?5*`Bo zUV>_ZVnptp{%R)(sDFwO<_rGVbHottsVf+3e2s&Mbv|5tCcAJJiawsIqXWgRo7qbn z*6)kH=!mY=#1)x_ve~?$a_YKuS$k=``DZ>|@7&WxieVLyXo?W5{hF{kT_Gk31YEXx zZ>|O`oMh!9ZT*n@f|LYd(0&dWs3K@cje|Vx)F1(8E#n;j5SWqys7IKT91T3T1~#HU z&TX2TRm>`eLK2r)4_i@!lgf#jl^!Hsa>#kuWA$4tLuKdMbXMN%lY=*&x|;RJ)N$t0 zlx(>vAIcf|94is@&)YGm86mN@zA`gWk{!|oX_x!+iVUtpDClp-*&_3fnNv-5)|b^P zfBy-klU*IP?@Nat;UIfHDcP8LAd1?m*u2+?;n)i2O$NnkIZwVf(CK)K#mLz4a#zR{ z`!skyyJI<*MuCVd=><{f%?J83b67ITs(U66JA{AC^ELI`t?XME!>jH}47cH%6QYi)^^t6h9{t@g~f{uy{wPsFHz3P3}K@Rz(A1haP!EO0LX)ZbtQlyPH#K#zUZzVl( z=gLGIqQestVoK5zv>Zg}5bV)X?j>0#ZQs(cl=`}Gvm7nktFuxwzh`(G zbs`fa7}LxQhNND+Q^8j{i_v^Qt7qPaedfr79e@}!3QuK4%{E!t%Ad9xMtI; z?#O8rzINvNY2beXB|a(z9_ioCAbFRPaVLKN0AiWB7nj)!zK=Cl5^WdQb(gqGy(8*g zorz=mZD=`7z|M}%cG=zkwlYluJCy0jH_@e#c9aI@Mmc{%=KzYXA0@Z(I&7r_Xg zs2u3r7Fl|Xrd)mP`Y0SLCrhuS%YYwGP+@>F9e3S?<7qP|DzdD4v-_BO!EraPeQ8b? zkD%QaVFu<)>H+4?vOk)Bo6OEUoj9r@hJQsT(De* zGZ6RAK-i?E2yp9|ID7HQ-q%#>iOO?5EPPraXP$-+8&+?8Z+vm?^*m~2EMW3n^t=?Z z*lcW`12N{*o}~D~2=W9p{mbNnS#`xy&`QkP6!FuvZ=6sj36;Sw;y+K(bA1o4A&}s; z?o{4rexW&a;isIc$vV!J?YArR4+2+{B-|Ur{SU8lav#Wwr>J@b>y93@2PKGG-@%)b zpY_xfccCg{&(YN100mX20uQ3LZEe!)es-dtrrGt(RdMhaPTky}!ueUX)tL?~Z&Mzv zT52f-LvGLi=jKN(~BE$2_s0Q)+XQhy(q$VVA- z8Pt~9iFC#Qx}60wUt0L>Wjh|g{U(i0^N2vzH*ZjoanB!}YTQOi|L0}#yH`0yEQ*fc zIe5;e320sN!&j}`kXliXhJq3LChjtgQY&4;OV~mJ22HUNV#e;*5ZBZie*nrW^Wf93 zd047I7m6j@d)Cz3PNly7__Y$Cn(hY?>q{VT5D!-TqSAEr_g;{_4Up#L{rmp_(EI8g zsel=^G_E17&y=NSJ6(iW!7(o$ayYBtTol9iT!;U)tMb3+CYwnc_RNxv9UA#d`$pbA#(#ktKMI*}Ndp)V#-iJ)NR*EdS$cz? zXT|4_;-+QafipZ!Y5sa>yAt4)>!c)$ykuOM4m}4Ilp$VFoGcz+foVfonWwH;{)xV z^C1#!Du+4nd*gh~hMg1>t8-)bKTy`~{otq68|0YSz61g~5xi|Ahxnw9Z)ClhmWs3^w?Q7YCuXTEaz)DG(( z+YQklQ<USaTZc-|KsN>LU=SXuv73)oSDQKqU@=hm;RlS z={3XN?}9@V6%qLHmg-qxN#tM8U++9z$APM9j+2s@LO|eaX*p12+vq&iaq6}<|J0sK z#rZLi3=y#&lANEu%uu->U#Le>Rht4@Ol7kgVlR|FN>QX z^;p#0sf_q=zU9K`?r2e$mQP7rS^!HOdH?GI)mg{g51{Io;ut;YHB z$im+kV{1S_KRw(5gC#CthuK|5yvodf@P<$#x<{n7iFyp|r}2goRpnCZen2VN z_dobs#lyOm(9km*Di7&<&3d`yRvvm(f76 zm#OuIN2xGHQ-3xnpevUJ1|3u|+9t7MItSbkX2~~^a#@hN?Ag3>xplIF77xv6VmQ;j2|f{0eiczF+GsIbQ=TjKow*=zaEgU_XxM86B4`aa}U*)l-`jMeLEA zv*}=iMGb?x_+N*WYnHO8rGs_>6irlY(mN8}W*uwAnXb)vrPGl9u!5*zwow4R@> zE_7O%Mh?et^Er-q(GCD&r*Kwj0-Enx%>v6Gv>zwfJ^o|Q;P)ex^v`(S$Pi%r9GAr} zC8nLH2@6^VfIT%JL0o_R*P+C^jyrCRLI-@2f6qhvlE19b@1OQve#60ugFs^r#9o-k zdoOa0cQ_B)`mHPs4_Bw5$aB`H0KW8TBR$r5fX2kgWW>*&h7hd8~e199>M$Q>H-;}cJpz*oV z;S$KTd@%fuT9c)J&LJ~&w(8rvdJKfW#ha_R)=g9eKVNaKPQDBfeO3|xaP_}p4cNLs z396FA<+zZ37sfRg*1C5wS@A+pD`H#hcYeqBQ|KO00@ zX`krLZl$2ljw*1@xXN>_ zf>8MWp*U^>;z_)%$L31!JV`W6(C+J%nYP5o$g%eaZ#ocf)2oo%SPrWf6CiRg0tH-! zMj%CmfIRtkrBchHNawHy>})e#x>wV9Ttx>^eyo0t8#@bZ_254P(ML5A37OL6)5k z@u|!&D`-1CdI0E-&cAigPqPKtTSaft9gxEE1KcQ?BMUt)8LoDBHpf>KXJuDHO=s_Y z56ED@D0vBVgd-s>b8qZY`9vIRW?8BLZw5~uK`{W<$Ea< zP`N~D%;A5a^%Tx;pa((%PlrE3$rAOr#f8OtWN}hZ^^v@K3v$dS*I{>6OBmw8;ukG5Tp!x=U z-PPQSuhBgKiSzbzAm(B3X(UhySv~}vY+CpX+Aiz?*PS$?MjnqA`e3Q;s8S{5-ey5o z5KxJp7i2P9LWjB1|FNHwJ{ikXP;AlPp+3gn)5fCKHLo5o+%>OvLc^0UdMRSMs!(zZ zkfs439gNXzfeV|rfYtAxZZo=oNt*+w>R?XMxJ&I;!?8(yTi;k}wFDzO|5iWtqGL9^ zZSGu%4(UCso9YFZZ+9tzD@%wnKyfS1!q{0s34xI?)Q_uE>G1>i{Md{^C*NnO2C3Yt zK;XPP^&mUYt9K==ZdrD5)g-PJA4C`lHJ3`$zT#H<=wVt*A3`Cnf-Zb{8lm>0*>(39ox7~R zZKkRVMCnXJ<)ih#m;FDI^a&xmVkps1i^M`%at{ll>;9`PdTS?R3M`X%m&x#!CH@B& zy!CY{JGwsEeSQZm3bX`)@*B1o_8{=zo@i~@3dktbwvY9V3&;Py-hW&EeO#BQmnK?E zU!1sHaaRjCsci5?g28(HirpP{AUWvCxOJj;J@l_37Ey*6N45I*%*;QA>Z1eK^w4NP ziInqRT8@YL%~2waXpNi-ocP>edFM}oqs*f!;u=sZa}WyhcTF_E{hfG_wF1FnW1#C- zzQ2$5@7a!oZ8QVL<|Y6v>@M2?a6>|c_Z;A_62OrapA2tGt-SI8gFU|jpQ;Se&b*yU z_w8xF$d<|Yh61cmcHn>emTg{AjC~lRfMV0mk6=F{Y_6l#MZq9vX%~*O&%fy2T63?v zFzYm<^&0={1F3qGzJt{(5x{PAke1@fec;xOn0VClK`u8`oDW2D4v^DFxwlr2^E?bx zUYP0V&aI(uq1yjptAtQYWdDk>_5bjhzduIy0cGPD^IX`s_0|7zC;#;yoRu&-%uMsp z|Nh>8KGmxY)|kFo-G=kO8J!axGo#+<>VIICe{8?Mo|?FyQZ z-2V|P{KJ6$^;CJd#*gp3+FP%`!odIir+&%>*1FcK{|ue~dV|0J^h61u#)CBP?SCeF z{u;!8{0YMgqpKX6g$uy{<7fWGtmUFGg2S$z{#D6^i|Te<9ibcaVOrn(Y5ONR-|D|JQ@WRY6Tja02Dl_jLaW z3&=~BnD?HQn9fMH7^-sJJ63-p*g*#F?kTbysuH)!fLs9u(~Xzl&JO z_kpo@z-<5q%K-rFWi^cJ0}V$ugaPv?;>wH(Bu?w=AHBp+Ze>`J8xYgkFKKDjp-4*{ zS+`UDB{m?Z-4FlD>aTVfGJ}*zyk>2j6$iI)fjoZ*`jc4I9kqWhQ3I)cWS(C2phz|3 z^8s8&6k87u`R-w5_8*<#{B5@qMkpw3gbRku+Y-Ep1u|8W{Jj;9=4#)b|A~d*y57UR zRR5!ull7v5kQk3p`OXutGLOeaiCUUblElC$R~l48$ge`hj+nn4hDq>4pLd+<_+YsT zna^`H1Kvmb(Xy+MfB6~7?X3m??gZQ#t?LnP>i{}K?$FdCd5YK|tZhqdfP@%sU8BT8 zTXW?`Z=COt!FJlcMFzoAJ&0qSLVxD%WhsDX@89kGzr!jz^}8T9&?q!kao!C9n17KQ zU)y6kmx+G55SoX5?p5N{hVIG{HrxMAfUp7r1mn^%KL!pf2pH^S)VMH!q$8y`OSZ10 z^?@t4v=d`~U9t7=-}o=%sb};0twF%=(gl^-DqPac>wIG#Wg_p{G)vh(Ialasb{fz( zLh)EXz`8j~IKi}@R0sKhxp1VFtql7`hYUP$Z$4r1qg!mpZi+wWJRALYam`;KhVoOr z{$1Gr8o=(Aj%?`@P^t1IJE(-H4I|48Vc$IfJ#-&iL^ z4Ps3Wvo*?)78xk=fBrjVZEVr2KWVpuI`)|!3O$9>T!st)X=CXo4mc3}V&EaccWk2+ z&JAQdlnR?l;B#{z8(^xE_0Aa>N&A`Anch~z**z##0qiyFYIi~j{9dL{D=d-(K;r`^*Q5GU@qY%QWT?#-pt(5TgiABILAxYKA~YP`*$7*@08D z8OcEyiiGw}D2WWpy&|X_Lc(UW9Q_z5Xjz0}n_;!Cx(8A-pG}BBbBmMF_OVU_re|X) z%xuw};+I(J$dcq4*@;cy#&A&1MPd5vaMHj8;WzM5i00HLM?2OZFVhvKkI1)gmFlHv z1WE(p{sNGCREP?cjd(wqNF+STZFfm_oaqs@8Z5)>Y4A23Q}FHU%2ZRaG!nBM_?m0f z?9-yT5DQw5_k$_pQ$8$uHhHGizz_^jDke-IkICb{_<?W-+A|>269|MNWO<5k_w_uLy-w3WeVge);gsJ3IAV{aW9HdNy_<}BA}A{g3Ud}0;{U1a%;TY6 z+dnSlNh2*9DU#`Ql3iq|#X1;ccDEq#p5=DwqI>#XUHk!dG8CywB(Qu@)WiRI( zRF)P}Nj%qG^m<;upQrQt^|&=jdTM1 z8nz`R_wVdC&H9bYx-n^!^!FvXtPGi;b?y;^pDhs=clZ+QLW>quu9u=bnbohQMAZHB zY&}bAru+r-lmsvW5gKUrb&}W`GH2xTaArvR75q4zLcdZBhNIcfk55&v4;Stpy0Xm( zHMbJ(@52+wmHV({ilbrTeLU4{Z!tud@eN7x2fg7nulCG>K;8RTkZR6S@(Ep{8136# z?lnTKf$oOglX{|lbTNg#Pv^^11ynBQ$B6??oSxeR-9w`gPuvyg&YwiRRw2?=^#GbC z+>3H{w2nORLeg#JG)PmhJk?SzNE|zEFNfrF)Xtdf24Qf7VIz4x4?M+Ff`wQv_c7Ga zI&QBM5HM0)QO)q}sqhKGUQq@{VThP-NoGj@F{YCh1DX~@XzkezR-#Vsi}sC2(+0HN zrc&LEb80h-;?5$ntrI&r`E*y0nW>o2OSy`viCF}Dd!qFZuJkB#3=&51p zGwK%6RJ)T^HVKWcv$-*+4&r1P?RlqMMWeU2`t@NOvz_Do5u& zJ=AjQh9^7{Q4VqI8MA6gSjhLCKCH5~i38W(vDJdQvC1g=qt;nr6s^(mhSX)Z8i=(D z0%@`R&2a2`!1?2=1xU-uUyZ4wbyqHOr8Li>{%uSii7F%>w_6|kY`#qz^`UWr^so*P zHSMCMun=;DWQQ6=<1wUj%j+%YwC#R>S!b0W*5u4Q8H$bMROG97C^8IbIGa}5ej{qT ztdJ;y{9^yT3ak5K8Wfgd$#e>ppBym?l!*e%sNIyMTB2=T6kuL=+wuO{s-(87WG}s% z>=zkAMU+8BY|yA+zpLRoHhcb7Tayem;$4ZZH9rrz8r(3P+rpFu8&C+f1Q zDIU9hKqz-pXPLFR0;vqQO*1$=sV(#{K~7lvk#eu<+vMar^iIgBTOXFq2#WI1{LsZm3LxoLM?}YUb++n5H(0lp)C_GRPPuK0GG^#v3K?F7yib%Q37NzzrTpH5>9B@4 z6#5quh$&NX%t`PI1&#N1u@YS7?+nraNFWxWL$O=uC)zAtWc!;FI9y#INjW7-VX?3B zp8Uo>AnYzicR$zCX1ywcyL&Pq~1&E7P`@&_YJ+mSNZC*BxqY}4)&p}mi0KxCFvqpcMs+yXjd zEIVeie~Bh=OMZp-kBL~;$+Ak?KEXe+FRXKp(IQ!ZgwFY}#^)rMejU!(H(V{zLGDa6bf~>b_+w2OcOZdSrEf$T`CD%Ad z7$;^Thk0v*n1InX673>Ny|67`;F{L-lw*;Gf{!UFqd9SMu_7xcmUCJ(>z&25T9+u+ zW=rKi%GA;taBOe^jo*9Ysfeb7SP@9r2~#oeRA{k2I1RJ`Y$%cWf%ORef|2INVHn&Q ziA}rVz=|4~z8}DlDOi((5CNQRy@$wEu|@=w-aPs^UIwl!N~mgtHq3u=(@+rW1T(7s z+`FJaE_Puf)9?~2mnhzo{-o^mfY~nw6$2_w=N*mI#5eq(Z!J6-n?tV_!*O;{TL?5=+Z*Ql{SPOiv0wn3~A>dG3yXBT+$1eiT8qZm3@z23Lq>3@L}sm} zn^1>f)+dIMg`qlL+n~xGc7W=k%s#lwWxQ6^yLSVfNt=qnVcUdpDfE-MXrvl&nI^Ps zL+8gZVxsraCtF$l<(#mO<6~0EZYzbAINnu*)C)BUaABR<0gRSG9=@Peu>buZ!tKVt zQSkvxXrNU-99^AVY<*K);M02xQ!e8@*Ik9)1kK%{d>DhlCKpFN!0rwaOA^k%RF9hK z;IZzqvHuvE#T%s!iLV4L^2~oN`_M09nIySo9HrxoX25Thk-H#0>@}T=& zY*_A9I_?mNYv3gFldp!PRO@{;d_zI}CNjZLC$V#t+KY(fo-V+d`NZk|$>`f>p{##6 zJRJ4yfj8dp(Fz}k`gFY`PxsKl+-U<*q}K!NxCd^fyC}Zd4VzK$Y53OH#Ox7BOY^3~fyt?@F_2+T?l4?QFzvuyP;?@bF zvyc^CvCN@H+l)hJy8_7K`=X~{9;BF@QJacC_>ek)i#Znw-`Y!hQ+`%^_?NL^wi!@} z@yBXZ-CBMX*a0J|K+@?#cb@b&@<||BqT|{;zt5gr+5m`*r7s zG6DJFf*{61#q}QGOISXYR6A2w(^l?fdmP1`xach;+L?EZ7|EI3h}6@h*=%>mB!@6M z-y_Lg1#sAiC^$t0jdnh*u>iY%s(QeY3`09WFN52Qp`Et2>o%;PnA8d7;8ClO(`d2+ zoI8#88SeHtYm~%{hdQy`Z^I0eQD}7rk1));AQ^OmP#BWoRRfAn2U3Y#4()Rz1Q^9fIs3GB3& zw5X-upFV{|jYalcES1!`)EPM!Owu)~_MyV4&-Xq*jbVj543?56JQe2mUqYohvpAbu z1#r!(^uU&V3FlV=vEZaxl!L3oJ23 z@Y?0h4FVsh&u`Cgh2o@uPmi9HY!d?Y{WEL_nYXd^1DU&FvLdA-Ee+|4A^ShYgx`V2B&WQs9xNG`l)A!U z`dae=!FFImPoGQSz5I&Hxfh&VAuxMu!eZ!66euYTAT@#QN zrU3O+6l5Eu%Ti|~DS{pn%kuAD;kI`;UJvA>^5f60&G?+wDJOpQYgn#S3O__{*&JU8 zl&oOe8CYOnM^>oL!yWEz5`~ap_5#0yZIfjkPXo4q{n^aJgr}RLF58~%e#qvaj$j?C z04$5YsVb`Z*HceN#-`o-Z&&g4)(PV(8oYr-Nw`ks_GFwM7IS}C1prX;Jq_89 z$WD1T=`8aP*vl$Ivq}cI8^^qi{_2vj>nJ%`yGyVi;(nO&jd}850Oo40XMTR+y4YQ~ z@UzHYwwrF?cD{-iEnp<<&)nSydG5U}JjIPk@^4O?ftw-&rL&lL+-3j^UsdAOpbF=q z1BgFlqroVpcKa|y^B9Ner!Am>=yL<0iZ21@IXlr342ieLUY-^_lk93Z;zmU23}3(I zw@o|-|InGcyLrVm8%r3T(yM|W zH>C7=TnheuFcEv|34z1{e!O?&p^O;!tsiYpe+!5o%_g$jf8LKYZCmEAK$-#^NtaQb zesZdd=_K^+abDj74nYkz!aeKKZHoq!A)`gI1K#ZczRl?^}m z{_HHYrK8PYjU3aI<2NoIT^GJ!p8MYT`bakZ^iUv)dcS3ZDk zq!ateChB#VF%c@CzPZPs=%MG7pi1k@9E8dq82Fbm|L8Ax<;Vy~D0o&j4lTUPfB6g? z+THo8z0)fRD%WyQQjbpTXz5O39|jLw;6R1$Umz*6;9zV3tt+u3-0BB!Od{NY$DuP< z{nO>UaTf$BPa!+sNW|O0cJ+a9R0>@sE8tdfb=Gu&Embi{7R$%}ydL#MZ8 z;^ys&s8uvp2)yNm!i1efmrax?$zCGh%ii$?o( zs2%x-FZrL#Oh6CaUP35c@&EWgSvx@dlD=@WUSVFp`PrxXabPUrozWWHo;-Um2iML8 OfA;B_=rXkro&Glv$Gi0a diff --git a/planning/behavior_path_lane_change_module/images/lane_change-lane_expansion-with.png b/planning/behavior_path_lane_change_module/images/lane_change-lane_expansion-with.png new file mode 100644 index 0000000000000000000000000000000000000000..1793eb8f6e691e11446cc50ab2f91e78c027cd03 GIT binary patch literal 25187 zcmZ_0bzIa<-#@B?(w)-X-QA6pfaHRtba#VvBOu+<-Cfe{(ji?-ch~uHJ@<7#zu$SC z^AE8*?9R@7X69W(n6jcY5TNeWMw2izj^Zx1pJ%>`vLg+qyYaF`1aQEv$WWo zigALyH*ZMZ$V!N+x#=Bdyw^+^xf$qe(DW-JX_zn9{L1aZJzqZWH}4-h&*;)PXH&UM zNE04VR0JEI5ajpr!n?BF$k5d4C+D`~?pEP?_@FoXsPts}V z@_!!=>^h-1J>E9)Qi>Osm^%q%a7Os=3yO(IB#r(bzrjAfeYY>E5w0e(sM~d8>)Vw; zF)b0E&^4zaJNT7V{l8t2F?*LP2>K`wMLSiKq2J-vy*Ut5ZMmzc%i~KVBqVhEEI6Dy z5O_SnY%Bb2JiX{kIo@J}Wr$&4gt)XcOepMop_P|yYuTWGdmboqPMIA9p?m-9Q^;JU zp25`4*zLDDCgag$v^xY$zsyXc&%b2OboOGK5a8j(;tLdfE%}8@1xQHV=uKpj((vF~ zFEs?^Ct^8lk22-bi%N;(Vf|-RVx8d3C|g$UV2pm&vLhd^qD1sZEgY!UnW^C7;y${7 zXL3ONP0h{g&);F-#O|IRZVs21E+&L|9Bx@|R>xg1YreU~lU&Q>{clevDY8|ZBq0f1 z_eeU`X6s_pmHNcjoBg8t`ocAhNlc*MceUTnHu?~}9Xtcu_`$k**hX4B3y142HlfY=~NE$T-eytQ@g;RAlBL2 z9WUBr4P>Lq&b=53r4qGb4v(cG0h3lY znYE>*W#jSg!fkCIURYQ-FgUm$;bb6&Sc}1A=m%vD5xTY(5+YBpEKwCa79EM>&Zw|8 z_131efcH6c;Y50O;z-gND+ToT5X5yBTI&9R+%mm(JWGwrfS$mWB2c>*!*PQA|Iw|K z*KR=$<>wdYjb>6gS=iaXCne$Z$KVgpfWt1DtKlG78MqjPgy zeeSm0WDm7mUbe}o0=s*5 z9QkOmaTk?%TUTX#?%H~Z=Ua(wrw@&C_8ZSEL;T-UAK2YHguL$qlbH1#(xhVu{F|G3 z2?z+|I4!@_t1B0Qr+T3Bq@tnAKc(-i`QdR|T1+wMUqHa*br#?NNsTn@`uYwfCd~ho zItlc%&AV!JP+tU&^aPQhrVQ_=tno|+ItmXeh4j!3O1ZCn!-@8CYB2{a%ID94XPfr7 ze@KDRfDsQtnJXy?K_SYvPUAA0E&Eu&$74oliV4og(rcFa&zcv>C1v?*gWRUy*;f%Y z4rifSCZSPn*!T5IKD>6lO%#}mi-6DA7Cc?tQBz!;$1yG$WkGS#a!|CxIC$+p9DFq?Y|}A*QUB%;w)NjfyFY^LHw6U_`9T~<>6l*jO`Ij zb^4a*^rk?j_Wm64v=6wpQ~1HWHHHB_Y*vdt&@SXHdEy5jSlBrHjsk<4JbJKn<~~V( z@dojXY6n@jMsI@0mPu@r6_Fh|id5gXa`BSO??jrdjv=ph1R0#n@-{h65N?;cik_x9 z;t7H%h$2!N`h?TI<=8_x>NX#Te_(`J-w5Mmxa|L=4Gphep~r@Hq%$`lI7dyR-%f9n zxfJMN5?)k)aTdQ@q&b3~q*x}I@;S)g_qz$*n~RtDq7g$~1Q?f5@gux~M{PGZXeY;+ z-`yD(D)pbuu|Wy2s|_X~AK$V5r{wytP=9R>!xJI79^OxnaZ@xp6dRN3{DyX`$hd!6 z8JAoj^Y8z5)(Dy32zhHyn=fVs<>ppS>y@YpD^|&(D&YjZd$>ME zVs~^@94z#1O#e3C`{a33<$mx57k|K~&=n07wzo;!@ISyt#DT2Jd5%>%^tgQB%xrlQ zQ;z~Xle;Ms*wKmZ&J2ft{w`y_F+tx`Jg12ao0Uwb)e4=j-nuvUU@-;hFeO{Rpx#ktwvD!dkFo8g>cXbh0+$%Vg`%#y;I%&ivYvBDw}1# zYac>B2k5)=?T9N~EHIX(vBUR&0a!U~tjI?Tb_AaZMGMLn>}IQheWVAT!UzcsetG`D z+w>T+7F}YGDx8R69erP1EQ`=3oCZ5srFvx|tgwoMZ`|32cei0o=dsn?mU96zZ#8nH zG_a-N!TDDB3%RJED10?l%fjC_@a)IJUO(I2nf2TI>e&w#E)q#HE2xz+zy9%iJD5R@ zQlOaDpIIS`LDjXoN^Ch-84?#4_a$EBjtmV{Ek(usFO>Wf{$^V{W#(Wgv*K{!@-7qP z`4W_AW2(l+*i8>Zth?lo-Uol~nGor-aj9M|iL)Hv*F^Pmln|;^@nr<1P~zs%J&M=; zNh7Rc<$K}A!JO@Uodw4iu=suM|Ovpzfx70z46PUoK&q9EPBHx@4D%>EdnvY8B{(t{<#E+3FHx}T3O zlv#Y4%5)oHHVYYhE<#}9sGKe8b0Y-g69|+tt8#-b$Q=ucmZWGZ_0k25-dD!9Iam-< zZ`{FL)3o?#lH#7ZR@yCN9vD7 zC&9v%0ecyK*@NrW@HGKXRNVCik3o8aTedD$5@+kWhjYl6b;*+N4PM!d!VL<|G!aaT$hk%+p1SSF;R4M_tONGYZ9t)f zvO2OlKfY0{(VzxCiLC6!W&zWBV#>)13`wB@*X7B~2P3KLuZ|mpdI@7Hn_TYOO#c!N zv9%L2U`Qzk-VFKA`OXc9d(cDw!$ic^=FmbDAwQrhC7qsHim5r_{)2~ZTVZ?UoDvzd z(D7$02R0-lz8YCZTodx0RtuAol4{o3kv7;a1;ZB+h(0VqVQtB_V+LZ5&L*<1HlA(wvUDO>7(%V{w?y(qO1r)R0=kn`{A zBh8io5Hg?BHKmpHVYS5=UUEuG_s9ss=0Mc87c|3QR$)-nV4u_Sq*9dm@x$$a?> zszUn(klqxm_ro<(M@NTUyDzc6xcHr)<>JuFpFhe+%knlV_u%)D$o!I$pL(OsVK+Pi!X{P- zI{_gYE^cTlP#fMzQ{H%pChCOzH0SjC`;*ky8HWpvC8WxuCKSAF^vnN;N8@ z0oYunarBMy{~I)4U>niHYgFn*)t72?8;IFXSLg`|f#N;?T}ZJ0ouL3wz52_{PNm?| zC2wm>!0(gZE>_1e)zbsD*&l6Ui{aivGg?GL@k1tECC5(BD}2Leu|Qu1vU(|P{o{?Q z4|74o|BFD}X}UKR>Fvi$=1C2vOu?!i@#Tm-&l7845@S15{&#L(Nf;&wjgPX*ehOeJ zRd25LXTCo*+5ee)sm5o-I`_yB_QYn^YkL#)F=nSC>d$5^VKq+hdDjd3z#R5`d{848}DZdPGn*}eUhF(9Z9Nm zd+fz%bs_#86fw7UG0VKds}n}3qnJlfWcmfodWl1{IyWdgFP=yy4juODZAS>T%SE5i ze`}5;4)qU13wl_NVeo&4odo&^+gmh{tovoJ%l|eULPZ598VAcE{!5Yn|C*ipIwGvo zI>l|QuOqLz5?uuvGEZG&zt5SEQPX>2&HOFOGq}4kK!A$;TeJgZ`$4$_#_&Zjmd(WC z@@S5j_A!9G1I9P3>*d;8iS4(_|M6~tBDvHe(dBI(`mr0{GQBr9q-bF)Us;v^JJ_i2 zWD`XUdeq2Te(bM>E&mJL14SlDNpk7;A`>;~{<8^*z)~2z1Dc(#QP%C%&661|Vus#k z{`pB!aot1Sv1zHfQ6pRS9{?3d4gB%?0Ew(lEVZTFFC`3TxPD;fU#a?Efbs#%Js>NK znCy4_P_-=WXOi#H$io^%e#7b|*;WfRG8uf%39MevOawVYzglHI9Kz3DyX7w-B_g3g zh9CRORMF-s;g9TtFnD`&^Lqxr%i8VP=IOUr?n!{Zp@ z&7-A8fZ{L$YdR1hGC9V@pX0_NAom#Lq}Kl&(m#k^r_Od1J+W^%_W+zH{mO8d^x9wn zP~`;q^OjOBLBxZQ@RwX7oyr2Ch7oWUpkib9=N=5M_h@$75F*I)dwOzM&PJ9hn1M}x z2&&h`GP@H$t#%HSYOI`IUrU*p(U5WPM9@d}I_QUEGWcBpOHH@GIXjEflEeSyFr$eG zW5h0uP;AYXiX`{Imgq_Uk82RbY-V zI1V%NR5+G9!`0bx_BjzVDH;{d!S#S6rnMfd% zbavKks)5myNNohrB^KE09CsD3TVih_1f8M;Wv;f3_I- z-W(Hp-0TNc>UVUx&oV%E=n}JeLBqKtQ&Sk8E+_rfMgy^e(#Q!+pwzxF`|)%DD~Q)5 zj}Z%d|E9OKb#r&`o|#E}uL&q!;2IP8Yo9QP9Ci;w2I{+^0Kd=*W7bHxxv+Gtj?LNn zh-5w!csvfPK>*n3mIVFSqgF`vvz)8Q0s0RyG!F~MqTc{yttPKMbSB*fLyiUlT6-^x@SfP#CU22u~wHOvn6k-zL_MkE3BKDqs;2jSceSNudxOw?y8ns;2YUzaxHp0yp~lYHDlu&&MRo#A|w; zuD$(mc@SbTQSC>_rPa;js(0pO z4yF9c8rK>zP{CJAXw)Yk*t}l+#tt+tcrL|M&KfP;fu_u@j2`7W&_ z)xDweKAX$=vBVN0uJC)PukZc0iFDDBXhLv_vn3!!N+8_)7!>flW>|W<9KvYxc}fjp zhGV6}44|CQT>l+Z&lLl`)Li>brB#uz{3Hheh0*|BGO8dD*Sb2A8c z5wm7#cMSi!fJn$GR8SApqP;HORKe9a@{hvezbYppF=yMC_DKJ7e@sh2NJXxcDUi(J z?obyy(`dWOvb6BA)%8g1q{Ex_>zYXU7uHGdt$dHWjrRxvV`*H~sKe$~WmszHh9f^2 zL{sa`S=|Ovw+7>&?k;wBQSsquXLQ*m^S2m30&=9Mw-ul;0;*^EA!UyJ(Y|_Qb**?Q z@-n#28>Rg4kq`%KI1b(O=CHdaUtY^e)A^u3K)$((=j^PzrQT92*<>sgi_>z>R8%g9 z4}NO7#Xa6}hUR2!ejb-n?x%4u6&2NBGA%}@B7?f1N{)VKu4NL_e6y!(-7%OfP>EPL zKrEoccGbb><2ICsfcNlqEXsv*!(y6e4l7dZ~uv zcoNt4#qNaJTmxeWYU9a#PW?bQ(fnmLv5*xm0tYp9p;^H8wOPsv%fjSPFJ<&j-|Tf zuSe{yHME4&6IY$Dbf1t?rO|L;H7=JIPimtXTK?4KS{j=<`pH7Q`3Sa8QGfoUELif| z`~EUa&~Xcd4*+G)h&tM>;*{exKbBv8gK)KV&D)K-n-7=p2qnQt_%$IioCDFl$Z#n~ zOAR?%7ds55nDkF-NMtcaGIlJU1@EBVtsNXh0Q+?9O`L#XogbL2Ti) z$(_UBW=9y%{X({;>=AStm-By?MH2vtuy8CKlqlY!gOF9J&OhWt;c4LMcLDO86#__J@iWz+Ar3GU`Ms=F6>b;Q9Q)YJV!DL+2e3g%2|NN5U zd7DL!GEo%5Q9hSUQiIV2|*J=|VSh5t&9Hn#?P%pdu-f9cd7?J%z&5dXvPUbOqhlqs4I@T>(dTMNl z2BLOl97vfeG!V8S7%nb@P>`~joEs}<>Nj}tR+>gylcGuF9_);z;d1-5&E`g2!`IeV zuiF(YC$qLSi7tuZpZvICQr#KF74qUa-ySKPDX&vGIn=6EF0}XLu$hr9_1q!@Fy{{( z|2+(;-@8%V*yW3HYlIl!#5M8QIwWQ47TuHOo+^VL7UxBd>k_lpOZ`L{u}~&>tnoDV z5ZA0MF7K8vp4ybyU}wWQhn4T6{j)zCSCpABwabhx;2j+u8T6~k6yupmC2&5rxQyXh zEwp_!8i*3lXmPHu$p~C$`1UP%#ypy;oZr$pMwbFQP~;HKO0N--u;p4Rl>@F86y0(y z>D1>VupKQSCz1ha@jW4;{xzXr^(KELAYz3||MnPqjq>n@l(L3+ zh8zi;a^rMPOKj~%n<#)m_qy%-TMz>ZDSwGW25Kn2|DQjVMVb`&z%h-Of%uWtW!TE8 zZa<=(pWEQ>9d(<>UXaxS64Ac`KxZtRHhaizn5xk|6e z`HAg(hZ%MWjvZX8YLwo7g~%Iqv6gt__^AOuz%prq)DbB9k~!S#_-~}vEl#Wrm4ETo z!TIA2DXK@PYcE6|T1a;Hx1`W8@3T$#<>wWhHt0Hio_=2wuQXz;l9MU7cu9Ur?|5^k z5PtfQHpkSrZ*sAAaDm4g840%RveUfABQTE+#M$JU*s6Ge4TZ>Q=N>#R)Zz+ya3DXw zgo`YqlQU5QV_~f$nj@x70DyQVa_Spc|5fp>u`4F+S?)f?(R)_Dpx-=YfN!0 zW^21L(lo$%;^bDsc0~Cj>b+&=*Yk~@?Dt63qMO)9ae^Ue963gO%MX!L49Ta z#eclg5*%^UcK75GHKyE=`%!99$;e;&1mBpwcQnW{d$GfUIZ-l+YRQy8@_i5;;cmIa z=FZXS?Yj5zQs(BIN}HM%j}qbc*2W6MmGiMbGZW$Y7X8Vzc&Gf~J&kxVpr>tqE z)rj0G*#&WdiFp* zd!HM%iiH0$#x3$n}k~rl*^qP&ak&hRGv;E$zp!eS#;m?0c_9uD@ zu7)_YyJ8%;5EzNK>kEi44+q&l{=h%Sd9>e}SG@@_`&^3{QBjIB@pVgN1eag(cNB87 z#&umW2552qdj3f0i;WPfmcmnsB&%7k=5*0A>df#?7#O+meJL*@uc;<8!9piO;;2Qo zDF~tN`0IPYrwXdGxVd$LK)l#pA^F` z(e*yL5R2}`qRQC4E6KH-o2_RklW9`siIXe+fCVmTSN{cZ@ZB0-A*Ew(6A<~m)5{}( zBKU6>U|V`nBOA4I=k5}Xp(M!=?EG}j`>E<-EM=kfAGu#&9=p%SkR^Yw|dIuLR|nV%&iFuT=YV9I|q#EX%&hgST0a>qCb5;3I6rt|2Jh9JmQWwjea zrQxF!1nzI28#XN`;7ZOF#*h*;=yYE2lzge|xj9^If1d~AY6QNT-R0bsqy4eJ_cW0u zbY9X|_F=&&aSBUkDFHAWqn8)PW!bTF)E{2lSInwKDg^G(q^R8jp(Q;U21{pK3@ESt zt`3FMAAqj2j;~P|tNw!E@uEjDFyv|~dg_9&p`A=u0h_&k(S?*Xl!>ncvJ-{xb?V%D zeFSdQ7cNI`FCceFHy!QTwWUROlJ;NI}GvXDd{8SFR*uv367+|c@VoID+bhn4g4^+{$J%0XBccMkwE>^3^ zyD99f?)z#0ZD&w?^HNuM05G>lyTVNeD#gr5K(Dkk;SQo0SX?5Hw{bxvJ}H|K?A#=C z&OI1ET7oR(!5j`mN7=X4RZ|1oWyZQJ{;bOh_uY2=CZUDL{ zs~M9SC@YfsK+MKSp79jecWE6anPOiXK|j&kI0VDz*sML z*BW!EYe(T{MpAj#O5-$$h=>xadhH@Fp#6>9tDLz@(%kJHr&|s|o{)YEopm4=H9;sO zdO0^~lmC>sHdILG>6suIBVU!$Bc#YH`)|hNwM@2>gk`4W(lXFgK;XsHz z{rH<-`m}}5Pe~}{OlnOmS@gK7zJ_?7HBW!KziT!)(Rv``hJ|zH5Wu|b$dVUQx) z!p!4g#>{2A7)T`OnX7&<3wE%EKuPF@J6q13uMavA3UchN0%0Qmi8OAvr+dye*{{tl z8{o}>TTJwK8Id0ilF4CwPY1;lfyjiJb8SoJ8AVBn0n~;IWQjxoXreqb`l(cx$zpdbjXNDm>i5{o z6o%E~IH6_)Kt~J?Z_kQAtu7q=6`yrV1Mu3|gzg1>a~eXGrc(n}7Y%j@+-5 zHG!W;RY;ag&l_d>?vgS|55CQ7XB;?D#6ysbPQooece>gEt*w-g8 zFmMeJ9^5vLk>w;N5_s7=Z9Z3#L`FubWQ)9oKp?MrWkf|n@n^|B${Bf-8Ni6o4h)Bh z>O~D>;M+=pPRgoej>rSnNKF@cjxzwK&=Nh_c0-f!uxKPzmDm=;E3`!n+m z&h*sFa~6|Ws~v^YJF}|}V;2vFDR6KJ$u2h3q;l(1j=SSI`Y+D_D=x0C?ETS;&FZnW z)2}CpUQDrnd39C44`VOv06`7MWE@@}^Wqq%qGI7-Gh`*iu(e2ven|oJDo^5&7~F27 z{IU7i>_YLHm!}(jr(;2MlTW18g+=%)i=Wr@WX7@{Zgf8QVztut(fMGu4^ZMxStY*&K3B?X zFI|>0eY&`#OwUNyyp3+CHn7jrUTO0|;@8muG`ebyi5i_ov$@zcQmKcVqn`W-9NtlR zvLrp~W3@r3;?zISgk4D!Sy~LG*yzm(+|s#W&os>PO8Ue>pFSxAvQ`4E26DZ{%*IVo zhEAhR_jrHs#TiXf>6fELZ8#>2q#fLhndC7Nd>}R@%GIOW312<^4=E4D0F+_--&EYR zu(6Oy*|c|W-@fJXxTJBhS_)>+s>!yWDk#!x=i5~-_Gll3I(vM%InDKAJWmgNxq0(4 zrMB0tNc7Xo{i242biE)7Cg>0m8M(jR^TzJ-)F7SD86NQB4483dE*?Q{0pU#XhqUuO z;=UAWshqas8#2wY+3q`ga07c&_6Iu(fUE`wxEqH-WR>LZ-84880|OzpQ!_I`fOjXC zK-Z@ya_@U?X99?usSvUW!;Hmx`@QpRTuB^v!o8Sldve=_qcm<&dbK@H^c{+g!6mKi zucGO~uE_5dJ~a_@WYrN8p9}riwVxSI#I+K{Ox$nSeH5boM|TgT0C)iD9`*MItlWqe zvELErr7lPF-6)ouy3IVo;bJlih=_GQU#UzPFb&C1{s6k=ZD+TrsM&G>l6IY$zX0&@ z_uv>?AmT?)=aeB{=91gDa2Q`rZHN@y;>tM`>&Q+|*L%`mqym!Lw8F*6LVh9+%bN^^dP}v#pXBhs&+5JdXDqo=t<6 z+`Wr8(O2^OomOl(i1R{(_LeUpah%`taZLz9gK#cG6(Y7SO_+g5 zqf$T+j!FNXd{aP$Ygi!z9Tw?sSG=c6tCO<90U3o`@IJr7!E}(C@Gv*75M94=2vY z_}VVi-!GIY1sj-#-n6b{gZ3tX+gNUZlGI3EpOvY2m3!vm5`EzOg=PHCMc9o;1I51` zhc+IdI3yLkw$OfUQGSMQ>5Ji?WnF)omMYISGufY;>hhC>c}{qVy9!ccHY?Qzk~MYe zQwDUJXAYn!eN&t2lFZ{raP~Z4< zi3r@B8|Ijp83)n<#+pJJR~&z{rK4B$?~#05(K8py=w^m5uZk8A93TXwZ<2kXeB+-y z&d}z1LR6w&naME0@Q8;O9vd4w$c|w9x5F`{ozA~Ra)uZDfom?Vk)D;7t>ppJTgHso1qDylXe+r3lUtJ`m zqTOJ@@|3yw#J0rvJ}~aoeKSh3)a4OuGvJEcH>>IFD6y;?W6i%`@se1!#LXHaS=#^+ zG*hdidQtQBp~Npa&{$;5Jf!gn)A!*<%+zL@AP!XLosd`KQW2T&-9e3sAUK#Dexe-CrN!ue5uHuoo&B z0sA1$=Q^5TO`SZ=vmX{H;Z)3X9m_hXMA*T@JN2g<3#wlCw`iiGZ_TEvmuyFla<6T4 zTSM8l>BOkTr39RPVYB8cmD^pQdbjn~!W$0k&|oNvjFrt#yLnwsKr7}E$9j-O2}4UL!xdXT*^rV1ujl2_OJ z^obD&HsR~sWId77f86C&*n-(kmL0G5`8o;JQy2QyM&R5CB?CyKn#!NI7N|y~LTs%= z_>fZjJ&^m7`m;`hOU5s57t6d}@*Q6c8@>xZ^ZF>{LGBZep39i-nev3UAE$-E6%Ez^ z(fXO7n{)`5Y^>y8Z#jFq8X89qE_1&y3y2UJoe&UQ=kewnB$vu9Db1(!49RS2-2~9& z?ah{KEKOc+X(w&Q_2-WyuY0gXl;)@K^ZIr{x3k39xJ=Ls+SOxhyjr;-!(xwzM~b~<(Y!YFt1-L&oBA16o4 z&2TGi=l$!BH@7duf=wZSKxTIz3{#RgG`8NC2jgO};3eGv{__V{nptS=bi*r&QM28O z>F=_xN|B5`53?Tem=QYOJr-7k@n%owkP#OkRBnwX;*i6*1Wi58Bn#PNKCV7=w@HCU zwOZmNKPD_sRDSJN<=*@-1VZGbmDP5XDNunk2YwCuXY$>xb3{ytYSVJP2fe) z>-6vs@Zn?zn{PgE4#Rsj-%*)4WCbvuV$sKL(#?Gi!wdw)I%JC+c> zdt4P~E`6&=EZm!O{PT#xfFCToS$8tqAQTG7uX_gIHb#P-CbM+$>W>Ji`s1ntYpZz= zXM0AlazD$vyx_6v`WwIm=F@dZHmgm5emnk~$5kjYjSGi!pCb}`)?@pLApR)WPt$lj zcjRK+=bXV*Hpp!v-7q9+LeSvzFWkezQGsRa{y*0Cm+EXv zwIe_Cy1X|EzLHuF9&-~?25BMH7>y=q5jdzJO`#2>#9Oc3U9$Rq2ot`_Xd5q)To!n^ znSaZp&>#vkvZ4tQc+Zavk~sTpGUM}Q#+yie=}W!m#bQ2CFGOD6dgLK-tR6_X70&Sf zp-fT4vdwF@q_H~}@;v;!r0OMVxYkDBz3%c(DxP<)Eaw*%e*^ihr~9k#CXF`W(?30% zGo>2yowmeGptevL6rw7eNWGX_=0}+oc6IR8KS+E*Ctq8}Nd-5y7vl;1UFv_3xaMf$ ze{nb=dY}sz*Wne}x;o%4mj}&}b90ZTaw2^Au<&Qm0=DMk&Lq!!HOZuYe8Z-$*%lbY z8vNfj8=tV_IES~lnKzcDnZ=b>-&{(%9#i>U~J62~kI_sjAJ zGs&rgFKuEXQ`n657MH==`7q)m_XSOxXs5zT8YkCge{%&7sm3Jilu7s+i-LS+8z3vL zG&G2uE)x1pR*Nwkl*4O>#d)~1jTnGz``zn3ykx1qmQxhb->A-CyUkVxqK3k`C}P0< zhH!-k@^<?PuKlv(BcHGrC)T;kxLyruc;Ue}N16sB);=Ga4OTIWS!rcmE|2oq9RrW7%DqX#d@=3qzuOo$U>(lyD4vE-`;@|?_-6)gt|LT?JS3B$xVe$wO>!faAt+8 zPltd8eacMNkLD@&aa~8xku2(MuTQm~`xyq8T=(7!3lk&mgMYSfm+;13W)%2j67~)H z|9osFLI+SQDXJ z0i8iz03YW~Dg|h`*=i2dWI@!u<$;k5EN~;IhPxCX=7;N(TcV!>k7%G}4R-+5=PsBnZj8k90ew&lsxS^J*CDQwH1nAb1?pb#*{euuk1% z*(^~nwY#6Dbvok5d!^=WCmNv@z73TF*HQEfn_`_7dr9=}PN{W=e)rgnEN#9xnDi=m zAP>Z8nwA~L)lo6O;qkH3JB>XsLWOo%#j9|*A!utnVbD7_mBb#_K+B$VT6xd5O>Zxw zt^&EQ!77n(S2)Y8fxyEdZzN&q!J)@e*f1^oV$rt9SaDd)23IcCJ2QS^OzCl{)aJwg zrby6VAXrGY1gf6@xce-Kw_Trwlt9(m>5U*+dXHr=;|Z&a&0Bl(%V26&m+;D;=yKYZ z&S148M{K<;x!z51Np3}C9|KO7PIUlzb8c`+2E}ee97Pv>TunwdKDpq2FfD~U3yzAH zapOkDYAS|^ZdlCk-eWDRoX2k8#TaLoCwic-mf8&r9ah0kjZ%H1s$!u|)Ac)LC#C>B z9&*1x5I&~)XSd4ApW$%9^3N}jITp zxgNDch40h($N$(hGD?4zb>>8JQ~+6{%swTA{K1tKMRK9l5kqFM^THdS9-MD8s;1RX z(Gs3SH=w6Wm%u#RRfap^m`V;0Hu+pcLx;)Q6?s?s=a=Mz*=FTpG}lFB+uBx6ey;g= z>4QK?L;2xe?pdvcYE1inctgT&c|kK(t~>^*`%5LM-Eo&Ta(Pr5i@#)?MNT>ShpUr` zfYI?4p;=v-(Zj#hP~5gFy-jDEapVIN7x@YFfT+f2Wo`AE_n43Rh{2fi@-6rePPhNl z1FP$?E)WRH^^756-6`yIdI6NOs;|#pb+ve*9~71>4i73(LAH9G5>IrJ_6NnnT$Nhk zz#$*kLqiRmokJ^?c-t2SXZsm6Uq4IaK^C32*doa39$c*Zy$Zt!eyTCDy0-*hT7-D& zb;l(|<1fSrCSEFAX_iB`3H;5QnQ9Sl91JNqPXmHiPhhA~*Hpg&n~JtuzwiqJTcsy+9 z^?X2>OZ#Dosj#7p@W<#Y8EQ+RV^=O zTJ@>t!w10M>dvXX$qj6zO;~XqG{bK0P4Xd8R!qr_{dy>9MxkBb7@mG`Y;&`ahM`Jo zJ9{3)jz)m%cSqk~k-l4kQ{>Sy9hI`*&Kkyqe&`LebedoHF7aNTYm)Ap32;@T?c1js zQSe5-a=RjMv22x-?XYAqy1<<)+ml|v>yG!FOTkfZc~_<0+5{-8CR{T#G&tS!t(h`Q z|5?H^GGDb`9uYa_@PGV;7faamzem5Dm5mOMR0^!7W1)kDg0*#efO~9A^cv?uaK-RY_!2JT106jnj2tS%t6T4HS4g)s;d3!ZWRdikh1XJ5_VVA>1BvIUbc5ek~ zzA`$tR$26f1(YOb?17}0)9f0 zxb`Au5M+PR5mlyWx@0xE#|raHZV0TqcY@^H#9^i}H}2&d4Q%nny2>Ug{8p5s zk&!3C{WEB5q1o=9M=^^h@VjSYPt7g~;C7-ZIK6-G)fJGqMAoW6^a(yI4kt497W zd4^8TOA<(pAp}8k+j_+$pBv%heMBxB8@5^S&aA-=2=|D1gy#G~lOK>9ckNQdehGL# zzM;4^>*!T8L@x+GQ1jI-S|L_&GRI}#elS7@4eLl1VSv<7+^Zn9BD}UZ~-I zm>5~^0?}6js@%InP{qd=MZ?qujO2qR4+#0PHed$&FU=#6r}H}}5O0;}`>}2V z0xx)GwS*F}W_#@~sbr3^U0!;#(N+m6=!!wxuMLNqNjQA;NqbG;BmNi0Njax-EiN3L z*;W<|N%!5GpYg@CZ*^6{#@yQ~VDa$ZUmd?i?uM*%ts6CK?~A9LC$6)2^1cX%QB3{* zpxI)>?MV*o**$kl6XXhz#S&zvtIK+H&@{|OF>GAcjDWL3UY#4F@`k6C(}+d@oK;>cJ5#B$!{Jn{^8 ze#RUK%hRly3P9f$GnkwoXLojdE}x*U&yse|EzOoi3;f4qHH*~YF6%|$_P8dl*vq5g z1>wOBz4t|W`+xa=k|EK;4nc-GuhA4?mq_tQL61ujz+%m#JRO*h2}B2NS!)RlyeyB)~uLOd}noUnbZGKOHqbI6P<-0?ZmREA&1g@L`jMeii%!W4i zqtA6?Dv5&Z39*WB#}Qvnwsb#gJ4@>y({mk%m?v6*mFXljTAA9Fi_KgVp$mPp1Zra1 z-EU4-dY!rTf61nCEf!P^yG->I+id?PU?OK;;@2leJf1;DN~`P7M%(02lvHq8LOvR5 z*4|QaYIj8d>CE=8#LoeSE=@$h8(&}LXw|)QtZKtJc8I9w`mwySOwBiGgu|B`D(Z!) z`3zxaOyF~U2--DV3=r?0vOk8O=3w*#@&@NkKTfsT2Hx%}68Ck)bLWLJ3F{M2m+InT zd}ELpaRIrT5NsbJHm3cSy-yVYC8#OTZ_~ULED$R-ct9kIYRK>)0o`AAIx)z|{B82^ zm$cX!ZAsq#I&tStT_LdXmtjMG!}m}mgWIl*4?BS!nU2RPDBX{ z+c=V85}OGfPb6{odg~Q`jCl3D-}(F?yZdFAjo#_$iMlKFd!JCY30i5D=H7v+dg~r| zh7|6M-8VsDj5>2sHN5-4T_lc`BZiV1oJ0Yd13RBR zx+4+`5#V!Khwr?f!d4aoZlbM>xwuGOU^8m6l-Qi7CQIOiAzVy0--_}rn6svFx%NXd z=(9jckFSQvu5W+=;MzQy#2IuL4e|(u52~?XY@xCGH1xMo#%ke{M4Vwha7nQyq)ipb z6T!f}-4wWEv75(LR@C?;$y;c7)8L$Zz>|5=xX)?f&l;ccf{}1iU-NK&rwUx(!&V}0 zt)>q1(Tc&7f5*8$OD>!iBV3y%#@BQ2{2PpbLWYC#>7!AUw9QSG$;rp-SPrwl@UFI? zzN?X4clqx?VnJ$0Pl1R%F#hkJzvYZ4i^a4};PDZ@Lx;TdNQZ^{WB}ZNY@Vis$~(dB zb+8L2$9Rd3RIHz4rbWc=gg`92tDfdH!62{7<>@R%iy7xyLH!6%B~3w%-7IFAHd|U_ zclJzvNg-Yl{LOsid-puErO3^Yn^TM4bF5Os-l%%K!7RT`NFS!wl@gyieM}DVd`^2IC@}4w%RF@=Oz+G}L*sCo$zHr+q z_?BQzujbgYGnVY<-O9b$^WZvYlN_&#oZxsqEr{5q4h(&sB^Gf1}swkl7wQ ztdmTE_0Tt-47C1{LJIv%PLeAxq4D{VMR}5ao8hS}5|5t{AQhpGb3eXA!X0-pPNfzH ztfxunIV_jq6cN5qXH!mIRsw#|fyQJ)%a2zf8?X{Cp|LlCn@=*AuS)nmDLT{(=08t7 zPwU3JyxNQWuf5|R0C^BXy{#|BVb<*e!iZHKV|WSb3q0yN$#984&gAV_CMQCV8 z4{I3t3XFGvB>(sUuqu3@)QW-h>pwBZ)ew`piYg*L%=U-NFjW`~VCNMALV-Kul7O`V zZUD7Pv@2<(clBRT&6LBbmFCsrnDayTX*rx(DQ+J5wg^UjFn1UI)aqjCZkgNkDgLRh zadAHG$qmMfR*d9T>hDWT|C@9O3!Lu2KP`}?R8>t*OEda^s`~1vD8H~euJ2}nzc zph%}MbR*K;(lK;Mcc;?bt@IGmAuXwN3?)bmjoyQP>$~@|-o+oR;jHtXc%F0iv-h5> zNMffwZ}Eug7z!Sv{Zw`sz3*S@+R1V4Oy~Tp1fs3QX=vWQk zhQ|YjzLS7s^~>`v^5T;kdpcyKrg6&>;cBlP#TzqY;qJI4@M=Ms;!MPQFZMyo=*CP+ z@RJ@7at_{s3{U{^pih2~h!c?1mbyWi)z0T;`x%dp3c(4OqnX0qBqOOD(l6M@In^za z0CNCnRz7ff^8it1@EW}o4JhpE{5J=v;+_sQ*P{Y=lb=W%ULN8a5@}9KhUwU}Ih8fi z#c8mNxz!Gc4%GCeqfq%PQN;I`e0515%xH`KxS44sshRT}5K3HYqqC%Sl6E3-dAGbb zxI#OJG0K?M?x}-(=Tpvf^p3lOQnp&1*|@Oc7|7eGf$5UkgDG^2?d=aDrWjBtfB=!P zdAwGAZ!hr$-4D8e66eKYKL-EjA7+SIKzJ4P6WaS$7KBePO{d=qrKBswEL{fy{~>LH z^pk4fcVX1k6|hsfWq+nly3hjMRfF!mi)kgPdUbxPnbp3twH6!E805HrZN6;YHomIr z19?cic;!`or{c!};JZ@QHd<;@aX4-^zvl<{yC)WcALHhZ-^0Vy%oVSmy%v}XI?S@- z3Xl7lcU-D6^l;jO1I~4z-V>!e%MLHF4-7=Pq%rX#dqWlZYrU9T{?bVQ;bAN2U!IkO(5o=(Pjr+zwDra|Fcv2O#>TXk8kBM0EC(G(|PkL+z zHZJbQMl8VeLdJj48)%N@NNIVHT|^xe>W@kU2C3vZYVdLBMUf}jT_Twah=(s06j+qL zXHc*jfC|`4Ic0B-UrV<&a%3EZ6S2JM1`u$Gg9qdzX?cE#kc8-`n8jzhDrw{MF4{Y2 zhB>?wBk9CrQL{mAtR>+>$TIevZ&-S)}=^$w?Q6Yop%EV6L1uLF-%2dqSxTec&|mZ7|kdE zsL90ibX46ephVCz@R0!_j<}H+l8>+N@#V3pUb7=|4Xj$2k)iP&uQ0k;We?StPmw@kG3!N%~pROnWWc(u8q9;$nAyu{5@B&mV zsw53mRPcbJw3hGSnTfruUKUykpC4YD$fCd+@8s+QoV z&#}jWI!@h0zC>Es#eVd&R<8t1Hr&I7)HvMwoR=9Pkm<#(iS`<9oET$YLE3gD3hqT2J`CZue;5s{fIbJF)Wp- zwpwwsTY50Hn`~@Db92Qy8a>MDCuU~gb33ah0vB-yjpS2Q7z+(spyZIXnm%$82$5mIj7gSvojDmGv-Q|EzD`c`R)Ebzo~ zDKeziYFVS=Hw*RiYU_;h9W_e|&yk%{DuK?#et$IPtas!j=P?6Gu|egA4a~)(I-&ie z-`75t2wp?&L-QJwCW=kn8#ZLuOxi0kz8bVl+^X@05uK-1seHWXqkAoHDp_;H2Ymr< zrDiL~65gCc_MGDdx9B*>mZA@65<9~>N1Y?cSw370n~TR8D_=x2yC zV2KjgEg9MM?OXD9T4k~-ErtLsAQvPF+ZujHqV$a!o1i}6(IC+Mp{2V$M$*5tojk}x zwK8l!TgRj!emg07^rp#<0=u5NS=rkma5{}PX(wayv}+DFUpnxQuoW|XU2!qmVn67XS=pvltyjVV=cutwe6uY z&=L~vwLRj%qEo7w#u8a*0&i4gw~Z8qwNhPEf6+}1-$R-1(B7J&-1&di-tM?;+W@HmzW^9I?bO2HK6xg z;i)$G>gnl(jc;>joQOln4kkas&8oLnR54d2HhI3y5;v7yKk}(!Mt##r*XjVOf$9$J zy`B@4&DPJ#-b~ERNoRQ>;sxF9&jB^9HLyE?0S45K4^2%?lbN*%0Kd%039`)WB@A>h zluuQkZ|3bR7U8%ZE>l(Q8yg#6o*mPBkI4{qc%EV?=ZK((2n}TeQ8Gz55VvuTrQj?B zdX{GNwMr}WU6qR3%5sNq6tGEH>%KZAdkH0r{J>-8RH7r}*x;a(W%xwcUcjK;XY5b4 ztpN^CP}>*yC|mPQ@VlAn_52|3#=5!P`u%;Yi%IWIC%VZZWhAr+ z_go@ag`BsZI-DZn(F0k4kf&?X&Q^X8Z)bwyaT1$Pa@(uF2b#ZrP|Qm}JltK%Zhyic z_gI4s`9VNA2?6)FM-kPn|794j{;KoAUQi5k8c^T)wN-R#S!$<@5P8di?ODAosMux7 zJNF0eiZnRX&zu%q>c5}oL@E4kq*_d>DX6W;k1tWu6s^$sH|vc{(lxozmPp&kle{TH zTMUz%{*=kut>LV=p7g!`Q_Cc!Y08%`$42v`(BAP+Q;YiStnPTdja=<2`+n;X0`@ue zXwnnkuzn8$e~(rZL__?+bCSuFgHUw=B2APtW15=es3@GVZ2q7}RDvhV8VoRXmy*E^ z*Y!==OhNBd^f92|!>6SDnvKc|^`F!WqrBG29oqcAmd)`Gtgq?>!_Q zy;f^`TcIJ@evL@rvQ(-nH-2%o{h!<6k0E1Of~uQ11dgpAubs5~DBoP@!P6iL!{ndN$% zlDJcHAIuB;F!S-(wI4a@BX{VI$Rbt%v?nzyVZz>KtVF^{G9#b&rm2InKDsP^C*LQ3 zIY{dGd)UQKB;j0Hv_AD$4JBT2C#V_yl}eI?_c)kD`R?@o>WV3*m@8{k_4`=;ty>;e zqUQxS790zB+K6Aj_4yPk6#slC)(?qF4R5d;&W{pz@pD*lEIqc|vfQ}(w9h?C3xFCe zC=1T(Bhqn|CTC;H&PzPyr6oF`khqb7x*l<%>3ctlw1@=-^-lamxGOl4!<*%5*2Vlq z9;yoo3DvqGtRKVm)6SQ zZBD@wwh!FV`25b8pX;~w@*8PrXmE~Yk!Jg?iT->PMoRG(ol&78b>6FG$4~MyOh|uI zJKyDQn|_AfdLa#OeA0 zV!HVKVr2DK?fTwD9`nftiv>Mf?W4dX%_q`}vZgYp{=x07$F~c?MJhF|{15|G0NtS5 zE*EoYO04xA{(QW8K8@?sQFI^ZL>}*=qU+p-|oYX&Kw^{QKl(m0=4Of}-hL`FnZ{XkU{<-UpEZbZsc2 z0Lyy|at*t}$yb{^sH+DTk^~uA-056=(}jx5u{q2j?}m*knrq$fWmL+pE=u=@Smh0w z?xHAOm$*peIROogmmyP(^^n zpbxV_J{n+HMV}BW6jToSoFBropPS$%HL*Q6c#f_-UJ~bF6DG)8Q!gFS7+t$39K2HO zNEhO2uiw@?bmB_E9rP28X>3}Jsg-#y5=I%DB=rSIt)htKLaC29pWVpC15s4#tPz7%Lh1vxCMnb{32MI|-Oo_0Q>sCK zLf1t&78(W&Zhn=_OLWbioa)n8*9dXbjUdCDW z!kO{q%b`We2X=e6f6mDxrvL%v+>0ggPm(KqW3q)X?84-B2U(TGrMEz!1;N1xKn@Nn zkKIPR%eQFB?fS>Z&UdWdh1ofTxu!lq78b^6<9@0tl3W5Y7F?t&Fxx!|JY+(%k}L%n z5h%h7#_IdfWCn|60_Y=>OQ1y+h)2U^%)9N7I6~ zd)+X8WGEX{`M*?2ahhZN@XJS=6Y?=c$Q@r+Q18SEazacJ{$H;W>;PC_3_xp=>XPmM zQZD~C8Sw#J;~+wOCh7nC*?6D(yS|7ii*N*H0HC~!@p?an1j~CBpqNG`v*7*W;d`RK zr2$xtpaB(NULn67gm)PywoD+Usx`qMd2i_h>Xk~_d;uE+vB#?XpN*}ZnOW3|gY8qF zS^X%)rjAvF^AyXc#g5|@5f#ncoq9T;9)$@JaKa$$0sSvA4D1WwODjSF&g&C zN-UMFf}aFE78cYr(H9Z8+<&w=T0f+x-d;~;HHv*p`oEGZPS4858QWkTE9H)pF2A{udW@&swZI|A0K-_qXp^p zZ&zNUFo>aCBp?;-i*%c5_GI`&TI~T*69yCVX|}`-3<|6j5T;6EQg&-jQbF4vPGP$o zpEE3IZYE=rms7E<%N_B92U>A(a9mzqT7^3A&$7RI^{UJ0@{i=8j=ZjJMxqF~bKO&N z*6{H^2-rOqmylT7-7PDlXj_V{cY()eWyNe4KYb=I-y>h=)T}XGSSHMtfP@{7gw4k! zw(C3=&Mk!<5YK{<$?yBv;*<7}nuSI2qT0cb)7}@F#5a2C!9kd~>+5|{WW4s2FjoOa zk(ihmxlH?ISVRONlZlQN*_l^+q?l}uX@9h;uDiXx{UbWdPYboicV4hIrvg-`A&#UK zcQ?2E_5#$Oc6L_Q*5WQMT&!$ts&C&GIgdi>H~FuRH|ji&O<-gc6`q3X*{T{Ep`#X` zB7dK{A8co zW`Jd_MiofcIUE_Jz!A>kDEX!)cw}UybcV#l#C(Pt7z_1n!1qH(N9S9knTjLlQ-u%y zbp{4<6J|Fx4l9jgO14@}ht*Sz3ET<73)i=Y*RDR_CvvloeN77%m3$OxG)?0zuWoJ% zYHRTt8X9Eeellh&r=>-U>HYO#B zKdUsf_VyFJckqTsMiMd;^F6=Uv>Dxnc_fsu~az_Zd5pv%R(~y?EiayaQ z{U~_0cQq+#!iP@ZvxG%Iy`=2eIrw;|rF}j3)ldK`Gdp`<&Rli-{#?BKzWNxpyx}Jd zAav09p6yF-EXs{HG|9@!+Pz)*3<8ldS*SNpmsB2O{GQlAUei&J)R}1mgSXTp-|vig ze|ls&QcZMhDB+-BLQvwmN#)RB7qA!hc1oz~E7UZ6Yl!7nYdJ3Ln=(H=X(XQ}r0G2D z*72v~T1+h1PRgUX*lKR~O^MO6S--sMv5bPu`eWL^tDqSdjamN!nXZkD94+?tlx8fG zzkp5~IL+*Gm!&&&s7|FMCI&{kFOyFMhl#hEkRsknVFvszlpkBW_SJdJV{Tq%*AbAMmslNm>tkka zPTL}w_q*hz%TI_&Zcc2O^ZWgqiv0mS(xYXVP|OwGz1Dnnd;*fLrKRvW6}?~y3%U*;*QH#CPVa_$0pTEEV3#1V$mio2g4?uAR#?3SZ8D$`#(H)+)6_2mcJ( z3{6HVvXMDHUBe{=<6pFItP@9xgB{;BNH4bg*z+iv>oLv!-);Qm!$$ABAO=2`_Ee$r z)nhCx*}^{u6SS^dV`9T9ThJE?el!kIfBU)m8!V)y_r(WJ9|$I#%^?BP*S6cZ1_ z{}lH#Lki408mv+qe>u7M?1TWzY|r93`p{EuF=y>YJ=D*jdNMkPlqCSj z5U4~K-INBXXEY=fH^5bcECq~v!AXP5lsi2QsR5jdKmR!_o8QHvhPCIedmnJRyOL8e zfNQiO#~uTsvy2vTieXcnkYbD>2d#PV^(dCJO9}ea7S%Al)pm9`ch|_ zPdnm1X2|5eM@fEOjYqKabi%f?Sjj%;)jI-(r%63Sr*!mJOiD&JZagRtF$#-|>FSjs zm6#T9-Vkn9e2JQwDQ)v1XV+lsX!E1u=H{-|sls}M9Z(V`ePs36UnygBEj_!jk!MDU z;ock;7!rCY)P&`9iata}#=^!{HB=vN*4NWh&jHbRzQKj5L%{po4W&ITEv?wy4&>zJ z*($4d_EIPNo&8C9%I~ZP{wKD8t|AjmK*Xra-z4O92cnpnS*%}`GKa||`UG6|O%}{I zxpVwjS~~vU3=+1$*7-LceMc!icc1!;t(^2 zV$qvQ0*(Yu_CEWjf`cFYW|o!}c75O^#?jZmrlXjYx?L%8pH&!g1CWa3Q5iJIsn8&; zg@Yu^2|Z!7((E!X@46+UI5}RZ+D#(ZS!FvK-rf!7IPK5Ie{uHS#7{Y5{2o*9Th=hh zvjuNyi9ZE&x}_AyzJY;_$rp#UdR7yQ|Lyq>R6Yz`NhZso^ zVk!+tF>i9Qnp;~|Uj*R_*ts`iG7iXY?*F)YzXAE3c6l=LKDVJ=aZ4#Cczu2E0d*Gd z_E%5xI*xu?+dXK?$V^ht_WE96>VDNuJ+A(lJ%i&m<=_1phEx<~6YzKMg6->%h5^RK z29M?x|6lg~`+IjC1l;@6%l#AZ8YG#=XoEgze^cb&yra_EjB(%EzsCp<>qlz!YY!6Y ozh~Zm4HYDcrM2U9_zB#So(1*d80=dNB7q-SNhL_NxKZH$0h+JfdH?_b literal 0 HcmV?d00001 diff --git a/planning/behavior_path_lane_change_module/images/lane_change-lane_expansion-without.png b/planning/behavior_path_lane_change_module/images/lane_change-lane_expansion-without.png new file mode 100644 index 0000000000000000000000000000000000000000..6b440d862c7ac0da840adca71414b3667ce5f2d9 GIT binary patch literal 25525 zcmZs@by!s0`adisNF&`iG)Om+(%m5;QqtYs-Q7KefOMyHcX!8-(kcA5=bZ03&wE|( zKgz}I*|TP?d)@0(n=nOr2^2&E#5Zr=ph!uID!+LHtqc5|hwv8o_m3RnH{d@g2W5%R zZz{%#AaCA~y^#_XR(1V)q6@DRz4r7!H3jf?=0x$t@oDq9L&X*Uf%los#xd_g(q4y4qm80z z(uynXOXYo|kPsOeIywRZEG#rMl;1A}(C_Wr&qg1n)rL%;6`U!pasTfn-+x^xiRd@j zc=sD(!6@9)d;8z_{e3Yu86i-hGtlN0>phsBK^Vsi>EHMK_Z!i{GAB@e|M~e}_w0o7 z+m+HtwiJps_|-Vk*_9~EE}C5aYXCQG@SA?=KgI=#5*n7)ST`4%C$cor(IFz?cMl|9 zY20~kc5wak$kE{?V|&QbesDE1z@!XDAYeCrQ_HBUSglOCJDx>&|M)Jn{b^+2Ju%|{ zhV%OXMCRwH23ND+JA%tpWj8~0vRn=0cC{~NrmMRaQMOD+)(PXE#RnQp7?;7Z1U4VU*v#C^9U z#@kR~xW9|>pF3tEfF)Zx_A4TtjvK#qJwKSPxAB}16XpK+L7Q{h7lCVcHi{1m2e)-~ zphx=TbUe?{+uQqVaFAvW;b1t6kWxBXRD_&-c6vb~nrLIKu(ZzQd|iJ(5}(`to>@Ga zDB5rBCXT~GU9AOu;h!^vOCAe?xZ~u%Ev993B_WC=mxuv*+@9P&-q1fkKW{SIfjrOG z`vhN~6MTI=A1>i8E-sLdC;B~y&NLhir#m4bk_ru$OUkM%C1^EiC#5=th$kl}iUr^0 zvLooC_Kl`XvBR;Z{AzX44wD&6hflY){!tq*2C&K$x(7Dm-RtWZUXQmyeUo{zMUrdj zXZyi}gOcp#vj{(BWfePgc!H-E7H|*7vwHaT^a29|H)o0!1mSEfEk7nuIypJH35wR$ z)zvTcNg-7 z!F!GOWT`epfk(Ye9i=ZETckp#*_)?>RM1=0)Rd;ol2p*kpz$Cyj$En9cFSl01noLD z06&t#0MpDMq5UP#rqi2__Ul50u1KeV*XBMu7V!$_^PU6d|EGdYK*0JeyMWMl238E8 z#up%NNO-;?hGBWf_jDvHB=LaFxoSeA{VKX{9lT}LOv^|#`Xruz7#i+!o zj%m)Opa%iFynk#@A1-LRxC-ecI(?zn7g?~5j_#MCd~xuA*`<+csSf^#M!BR~uDf}P zpZ^^(wVeN5R{$QLE3>$^w#?DdOS=a%8;4k{^XcZvHfU*#MlyxMwNLDS#m|hOxiTjH zdxUGTx{F`eN;%9?ty~l1?afi1%E36EiN#2ThXQA$`!hy4HAp5I2quWjrVmL@&w-N6fm zd_OiyNdB*zBegPn^p?HDDZU>jetvkYuFUCpggxI+7TLqL;%h7kxvYD)gOI+|=i@Qa zT5YVi+oo}%RLm3?h(+KiTVtGwNzsHw{Hv+{-N&(bP>2_KqOhp zxObV>VYh^-yp2yJu(F*X%WvpjBq%vlgSR*IJ~s_-eAw>@ozh z=04HN(da5GzF+vio}Cl?Yo}Nk@B3+RgvME}tuVu))?FV>gthA*DrB+Y`tAhnR;7kf z7n_Cdy|0?h)@atci;-UICM?d|M97d0e0ggbJIK9O`G)2A5%F<_C}ILPoB^Qi)YY18r=;ZPdHp3=wO$Z2{b!L@%OH! zg=)bp0-pDwZEp5G4v%=6$jowYI%}ru^~<de$&94C zn>_Dlp&v}h#0L;7ftPz-&{N&Hfr`EJ^g%?jhyJa9legqcO7_W zvLD0MR&V_*qXNT7LSOAPpv2eKfe8-YV>AlI>A$HmEci4#cbRXY_sR2xD28AA`_6pU zK#AEb(p2SmQHdjlTX~61uxp)GTT2ei_IL6~LKVYm5mW^h2m4Js zPp}+O?mLf5Q6)<4o;A(_?w82*gc&>A)f^>X>xn8h+<$Rr@zfE`l_tuOPGb`jNAc8} z7~Y+&c`pAxZnOz?y^B63P(FfJb1<3e#{nNJxVQD`{HJKi$UoTLJo4jllKTG6RgrZq zAr|n)09GMiQTV5k6t3>VvLie6`KiQ@_hR>7L7XejBqF}&0xv!wrz0^!!_EaFcC(U+ z&Zo;gdiHRRe!o)(rA~PcDqSoDoB3*5pAPpP0oPIO82AO}6492Djm8gKH2Eq*sCM;_ zYb^GXT*!n*{SCx?_9QM$HVHmoYwWdMWor$#Q!}%g?e~1`R`O)Aj2#LuYK))0c2Vgj zGTOtT;X4Gt!XRd8!uH5u<+`{Yt(HiCo2Q0iXfBHY3{y+dn>@ozNaC-}~f;ZwA) zj-$a*1n$X{Wn&6{1xZ1#5*R zpHKSJ_rj)gqhwz`4WTUgEMi%1I1oi4TjV>9yggj0WoV_FiE>=)@FHw?zy8Ipq2c(b zM}z}a<$S88-ib=W8>n0;{i96-4x)_DY8UX|-b?X82-djnC;VsVXc>?$QnFP~>5T_Z zQG}!huEVF^Hh~mh$A|ShL+ps#ry;MnT) zdc*9@UvuV*8AEZAj*X@5zx>E(w&ZT3kt~1FloM0NTv+Oh7ta^1CqUi3a@81<@8Oe z@P}i6$R_rXC+iF*I6BnWPYAfHaL=>vV|~VlD;_G|JDl0+ythSk zWYVpnfvXSN~L+s-{uz;3(ojm5Fn_IbRd_@`<)T@-cx{n}QC) z#d;w0%tG!_hz5E5y#=HGQzwk0OvB;3n>m2=`e?2e>JP)>{aU3;Kq z_jg!1C>A-glxwyUCKNGr)jq-hR=7PGif2?#rs2*`tU}zA7GcoquEPi~#x0iB8>gmV z%F!9|yBGPWYx|lf$XjPNN{uB2_Y^lR2Bzov#AV5Yp!`77lq0XEJSouU%8>O51AqcA zZqrH2i5OV2J|~AtjM-Tn+MMjxvk3ii86bu1-Ukk_<-0i6&xq371pmb@U{t@57#JR7 z*sNQ6RYlAObuWFMx=$_*9C&tua@f zuRqmE9KJ8+emyOvrPI~x^xjkP$7S5;PYlDc%rH=)&`m_m_we!1xwsGu+YVw`u|oFO zYwJpVmu;KP9vN_wK(0HqBqe->Iv#Ov^xaewHXMu5HxEXRrK?CV<7(ziERKl7DMMqG z^8Zd_fP`!W`AUOj5~1G1RlZgXh>WWLm!fo{LM2J2(6};4E>y0#=Trap8$RnI0BxjH z^@sn>@x1<)KU@{DAc=0P(@u>b3k!=TvyVW7)mpgL<6{*bFIJ&UN^p8QL5<18%LvAw z%RMCcO?Y_ttJILTc70RR!JsnQC3E{If2coyo|)(S_dTkuadFu#XC-T*K;-R4CA~ra z#V60enk+&h|MW@Z-p_Kl2+hkNtpc%iDMAvi4TT@EL>MnH6sW`wWM zw?zFX0X2`DobyAX`r*~VgzM8S!(S*pppet_i^I5vNvFxSrqTQH`rU%3XO-s?>uQS= zQo+yi$wocFq|mK;i-pNb1=1!S6tRH@6ctuAPsabvoUf2ChGd*$Rww>D4-biJ$Vv)! z`Tf1CfF1YR7)o4Roat-{hE`f?u4l9TYF=d}(|FdW5RZ-ygm>?tFtT#Ys;jHXjAe9n zb=Tzp?4Dcr6QvZ+%*ZHEtKPi2^tJ#8lQ5!KA$xNcGSlPMB)Y2FT9K%9 z4mIVb620^UsWNpMWl{KXXZ~Dmts8qW!GNG9jsKPlwBKliP&oM5;%s=a%8qb@i zYaaVkGYgC264pN-)7M%Y0s4n#d$-=6b4sUn7ZMcY_rCIMy*>iw*6hW3XCVJuw#JVm zg;k3Gt?I9hFkg!4pmH8zV`on5<-gn)Xd?oN^K)V^&kr-1j#+{(s7gvorZWvzE#>H0 zw#di`LaL7JqobqW){D`?v1ws@*QIbh{y|gG5sc(vm8o=jWS}=XT2Xek1-7R!eNGnL z&<~h&`i{9i2ol#OP3hC;t015toA->?q0p(*M65PDKz*r!&iM+n(P89x73B4gePD$C z_kQ@jiu%F-J)eNy?>8FhOQxIVb`yB|&x;9QVIjlpGL*>ws1h0Umv=9K zwEkR7i z9Q*wi3FaU48<;6|*kSB(Dqv{3eER>?OVZ$>09Y}h^-ks=*AMn0AWSEP;WD+$75Ct{ zIT&><*g&kL`Uze~7HsbEa;h!g&;JLw3qAh*!jF~0MGd)u>gv0X)LR&lHX9uuXlM|C zy>EN5E%ukw9;XO`EtQi$4kmo!GM_IEYPmVu+VFW5yFFRLEZ?e~WV*i&k>ygck=Jkg z*SrmW`#XXz9E#dB6&*Hu`-A%!$9C^O1S{=rw%3PBfo)z9ZEjcjpZmgTl);kexRS5L zi%L+p12H69V;Nk7apdsB$qYyt)rLxi=4ubW{T=^AC!rhuYs`M5A%9oXW{fql57<^) zJt3NHwjUUEn%=;Oh&Ue4qa@L5h*zvO$1!L(ARD`wM?C;?!S>Ehnj`V$ZGTI>MVjXF z(n^7DtMjUrdjey-|I+(rPbn{CG^Cyg+%5!E)c#_H95RK`6fI`fVXrSW%utL53{i2G1`#ilJU&*lrWSg6=y!|-)9HOc@^fWN)axJ}&Z!`?>@d7!MI~LFkRmFs28PzZ_7pR4NB{eKn z@zfdhqG8}szaaUM9e$A-c}b+v?b-LZ^GQI zO}~EqB2&s#w;v%PAP5(Rf!{XNAzJ0<%T+2jZ|QfWjc4@n@i|#<#soT@aM$M`#h+Rn zRMcV-Si;$SZZDy0L{BgLUt!_NnVHc$Iyz*3E!SB^L=%6id8CwFAgvxXcn|F-2>o|4 zLXBlRrLdG4CU%tL?_`IL-?mWFP@bQOw>0Gk;Xmm=@%^}A-i`9m%xFpdZL_)e( zSNVqAD1zAI`aJH=^izZ2{_2ECgeIP2>8Xw{6>9NujDmuKB+EV(i$@XA=;c8>Iy$C$%9vr^S`#fFb*#s^2VC9pgR%5sVU36ou$SJSWdpT}CJ|fKi zn1QTME|X;%Opy%@^6#AUCO-+vGu&|s+3h(E84E5yXCXYKt_nWgQ;Q;t6 zeq}9LS>%CQ3^yVkYs6tyX~{Q**B50Kc_HbcGd0E|w)@v+j>qf7S-dX6fMN-9VTv1N zGa0X1Q^?`#8cAVFyMK>SAkL_%+&`Q|PrbwkvNV~<6vi|(9J-qfn#ksdp>+@~mr?dq zzu2B!Sddt8KD{RkP84_U^u7t7Q#}uW|8j9O*NV38H5F^$`XAa2riJ!*ETnDo@jf6G z$>|<5MwCvZfhwj|dEZOHpv5;h0fYyw)}#S(XVjI6Irpm#0y9 zgqiBJ+rwd=oJ{`E7OXp6){DPkJs({v8m zQ9w+bERn*b0`HcRbFD=kFYu^GZLf#pFoX}Ql`;prySoo&Fp<7ySE;J!3wS+;uD84E z1JYbrkwggk`ar+Gj=#-D+txj6IQ+H8W8&!txcK>CEJiI0kiqU*Ay2G@s&qkfTurlm zAELUFgm#Q@8o?NNm9FC7q}41OXuW2L=Q$e>+OLFFjl==#`}=sjmYVtR63p2x2hrJ? zS^b~Nzx;sSy**vQGqj3IDpR)`O-a1n>VbD;VKcs&K*wCs5Kydq;8UCVUw#Ey1QZ6cXem|@nKt%S~5wBidLuAWXxcJ9Am_q z-<_GIkh>D?e1n{oF8m#CmLs3b?MM0;aQ5D4Qp8#t_@nYF$sZr*!h|1s9p1)!wO`xa z!}cZ4zG-DJU0jeEvoJD7@3O12gpDTA>t)X|D6>24j}Dbm$5BgvGGK9}X(cXX2Xz_2 zY$-NNtJR%-he8>HR<_3ex8CK)E+Q0L!5(mXet3VQLMrQ&i9l~*QFlK1p$iP@6Ax%(-G68MjNHSyJPwmFZk!~F9GD&hvIc29KSZPJ4100ne{f45WX>^*H zi<+Ax?G?UbO*?rGC}#>dA>N{*mgG6+Cxi~p(yDN~dJjz(dZsJQiBp71E&z;bi`gvR zXj-hf8{k_tpJuGPVFgyn>Xo*2mCrAK{OAI7$U^C)ct?85qpZCxsGWJ;sTLJ9sk_j> zQmmgK5|oAnVVgI0BpiMFw3h+UcAnlFS;NGW>vp)D{Td!d9G@wwE(P5jcCvyX!YzYp z+$Oh{;{t+Xb85=+Ws#p-qE9u4c?K;9Vh&~r!=rQ}oUU&G${1QWl2UAbRR|9Oi7b?V zjT+0~)XxuqiOk?kGWvueg686ahu0{PG0so9M$Y*DFBXvaHnU85IPZb}@<8o1y+^^- z0f-Ql#ZBY^pjaYEi^l;fJa{6D3vI4cL*WJ)m@y1Lt-5be`Gy9Xkob5>cD7i?jaC=^ z^;WI}6+%8E$cF6^RTCgn4B%E>{Pm9I3YQ$RJCKYH4@piM)@xb%v zbG!QC$V6N^RFvqWREWwA`{CgNP?oTj?7V^jh*I&IOvM&kfpjoY``Bc#H!M12RA^mu z4bpXtpX%v>0gfs01?#o=a`#+5c;OasMQM{fSu8KCfY)Q_@*WZy;~9+o!B9k)ib&(|0TTVUUMJv1+ zzBG1pZMh0t|Hr%hLTwlNzyh^n7Rd!7P)8&sKa4Z=!PCEhqS|lMCD*THJ zC|213TvUh)$*;rSr33ds0R{AZua_U%uTFT=@7&7KvLZ&?8>8G2?vY=dzJN}%&K;hB zgRSf5vBqSlHofJF59*xxZ14cP$H`jrJDdW`sTL6ptdHOTVg40gd6@~_27IMBj4I+e zv_>19zMxNC&u%I6Z%e+cyy3i^N!^?}ScXG1+<%@^B++wA4hPdyu6%Eng>9x=+bK{o7DZxwBcOA`FtwpP!U}%8 z;Pak&lgq)|w>PE%avt(|o`t2B$-pU73;&w_6%O(qEMtxslJgEsod^ecwCGUp6=lPR z9tMZV^Mr(Sh;?Pcw?CM>UFhlb{p}=8e1bDRD4j=r`;V)GZhZ*5IlMvZCr>?kj zwfc2G1(OQU5d27zQ^KuepFqCvkqBR6P@^^p@d5_W&MC>fhT<4$8?pqv(c$Gcl3iw+ zk{M4jzq1OLe^JLA;XD!J@9BT$xzQ-g#7VYU4awwj$cr&!BkHh4>kIc0JQ2yE&-TUz z(+2-Hlbo%XuT7LmCW?3G1VO9tEX zr;~{w@dhge@GjK`Gv01oW5*i5LRm1Us-$Gt?;Azqokvp}!`EUl%inHKb`X~sPNGMp zr{_8}3Jg|0=!u~Vw|JkgKktakL_5Z@3ga*T?2i;)X|Q6OgY@Atef`!_Mo)eGoB$08 z8eJle{=Y1M$3=_>Y+oQOG$h)W6|!7yjDkrIV%(Jn&;Jm!ay(j=kZ&Ooyf$_U)l$qQ z4P7K^y+$u|9JxGy&JhR+EQsinhyC z*%Ukg>7!Q2ww3>ZxHrHHl546KENpiQ^CpOCnyP};RD5gRPlH$jUjcTO%U zUPN&Y>F#A~^LX&FmnCxR>AaO-_@j8g=R`+V28*?k9+j@m*Unu{+AoUyUN2i-A9J*3 zrx{C>Wm8HU0J<`B_GeMP7=kqUCq%T|Dj zM+9u1sc&n`oZo7;n~liVgF@{27H;Tqcm1xvQ{CjL)N!x!rI1_9TiT|v2V-WxS5hGn zwCM;e9KwQu;Evj>FL9;;GI0bnB!+Y;#Q4~yKy-+8vB8XTUp^;tX5mk@$$+?}W;24! z{HZAInmxj`PozN67|Wa&OL~SUQv$VQinO+jPI=_7jN%36r7qN-V6+3=Jo~HV29z^4 z6NB(tw&i+@6uLJ)jnmjbOo7RTE``l)7)!NGT`qoYH$KzUCdQKhPM?2BcbXpn&i3Hr zc>q96b_$+Q%gfrggBKINf+NgbmAjX{|2(nb7rp;X%OTvN{8~_ zfJfi9vY~1B={?X5?N%35pQbWd{j*C#bVaY&Hf-9)eYnhkny?EuQ&QelBF2k<z7BN9QegelkmCvDv^ul zel1AGV>W0@)Sli=-<8Cj>#FJ~RbnVLuiu|50a4@~+wp($5t?_mZ61)0N&Pnw) zfl5IWlao^=05FOEjyrz>!V|eoH1-nHK4D~S2&ntpGph5! zM+oL-W|S={B=hB8YTjI5y+(OURMdU^QkyRv@OF|>(RW~BYRa!D8Ryc%REXTio3Wpv z3`)|cFq6;DKSDi)K_mJYk%}V+JfCg(SFuR`_%#x$$5OFXzk7S5)1i}SqZ#>NB4;4* z9p-yAXfhpfZLRK&3A7RQ@>o7Wv8R~;M>se*{jN5*(D3Nss3;UV$#Q%*$hKHhYiq=E zM5hBxcr`5a520Vn`P3lt4gK3~l-xVNwL`yW`15U!PbyQ|{q1706_Kr+Y2B=+nReWs zwrHGItD!G2Z*zeFL70KnArvUd0AP1IL}?WTDO7(xF*2f7>a}+RTo*$Yc4Pq;jg-Ip zDHU&bJOeif340qp2CG!3*`D$!V`wf2i6{r0+2Y$z$$AfY#jY(Wp-~_IeM*RkMdKS^ zC~ene!eC{EMW>1G{qpixD3d-u>hA7_zCl5z=(C^VuKe1*jmHeKPIk5))T=UW`MI(5 z$D+#WSY0-g{heGoyOhzuT$u)o!J(o&vowX~+-<8Au6_%kD!aP7=bKDqA8vFC0$7WD z=%n4_?yvlHxa2-4T=Fo3FfqLS6(q}1YQ21JTBAv49U zm-j3*==?e91g~E!W$_QO7!U!s;BU;z&Hmu~bP|Vl18gnW8&bGjBuA*Kt~?ovj4_lC znhy17==ln5DeRCb+dQhgZ!gei5>p97Iw_3<^FqK7{u zZ^JODCmmu@N{<&(jEes?bLa?Q?7x}>c8!lzXCFr`wBGh2gG6tE=EXK1w=G$zdRa2f zWExh)N~87GNwdTAHWjYM?+D!c$Gr$52KzrrAC*4a6JgWp&MItm2jvx2Fyi0*{%uR; z19qPpX|r6a`74dUkdtFE(CHTDgFUqyEW3*2GA8THR3ZsD5Uan`{f2bXN;N<aL@wY90ZhEL~4QmP0AN&Ni$%8%0SPBRV(KzxBy9qk@=7u|5qSMP@kH!#m; zCH+)UO<&)Vo%O&|jSNRgGWLyOnB|j(j|^A-2&-{-FHtIZTe?u<*B?cAWx_rlMacCH z$kJT6VvWoJ3YJu0M1LW_cs&7D$<3^0~e5@9!_SR}!4~+zFB@Ys zU%|F}LkZLv5Rma-WlpEfkydINxcrYI377JS_18{R-aP3}aszpa=vnzSR%6?tj03?+dr{#A=R3G_{cN*8gs#IoKzDq$nix=9P<=4lzqkZYoa%9&nc8`P>_3FbwE; z3=bqNKmp-4TCW-GC8)B3&cT*9kQI%~9~x@c`eC61IZVsAoX@#<&A8YE%}M_L*<0hM8Rg$r+Z{62q=uzO6j0KmxiCNEmG`u` zyWcm8GtBI{(dZt*ux?8Mt4KU$V%T?iC zK0pr72{1T+A2Sl)~P7_a*Bn;Gu404HZEW6%ZKB|JebzTA6|dn-nU~*15S}1 z;1q2tdqk7vOrl`RN8 zgsTC_Pt;$ud8rmUXS*|jY3g4A3L$q8pa{9=Gxh(Spnv_!S7@_R*jH*Hg3IpR%iE9Y z_a3L@|GxO&xzWGbTyGR;(w*%%%5AIb#=+QBy_teTvHuyCe-ox;7|@jT5QJ&U+n|4# zZUCPZ2ZmlJu6fP$KOfRp=nbIj7!dw<0Dq&y_b7ndbVDeFBl1iD%Z^m`!Q%Y`ddUg$ z+|$$VEq(#7mr=3u*VJT6B>VlrE?NwlGQqukWy>7Fesa2xw=roIsiFV+-1`JzPaP|K zT@$plCV;#0^EQeaUQndE{OdPA2O%{92s|4eK7h4bhJiRC?nC|qaISPusGfXL$D!8i z@U*|gexXBTIbSaxVg~}cia)*Kh}Iksv4_=Uncv2(Ue-$kfh2v^%1fK{$V%zrEcXVn zjO5dAEZ>^w8Y$gQXYms*j&5W=X0=`xKRvGSN?K2VIdD4d(ZEI)(jF9r6Dmh~!v~%3 zk7o`P^qX$J@ipyJXTPJ}eC_1`>@ir^?fH!eUl1gpAk-T$qJZQkx7#-C0wx%F7hnuR z7u$Vt4l1>hWpL8y^bNbx>B-bA<6>|Bw6p6NY z&v|+yMhfnJ2mG7Zpl8CO59GSL^4IMixIiAYr$8cR66l+CRtu>Aa`trIIgG|>VZDFv z4;*JN=L<{_4OA-a+ml>_@gOAJ;N)Z+z(Sysit~7V;Xhk#4*277XD@uj>vZ((J``h; zUYk=+D&;aeox|ttU!+W-UCd6cd%%>{7s*q>z3D_T^z)}_1evZ+&rFVM^som7d0d5F zJ!tspS>r|~u-?2KvB?1fb-6#30fIcL?NBYC#SNY;)x1XMO*CrT57^oTLS6oY z8PqWpY$cZCt)U2>VKEY2{&19QBDj5heJooA)gy_t0R$Wt`9Kz;M7J2V%zoHTOYn#r zIJ`bJ*bD^U95^i(nYGkkJnDu+s-Qk86qsS96lkQ_RCZ@FTdx? zr+=FAt7c_B<}Y zoX4_C)p|urWi&F{Y+X(zF4`fIHf_wZWQ~Y?jBlrR+M1T@;K8PI+Z-AaL%QwoY{DIx z5$Q}te1CPLJ^$@txzP3MmID!YT3`0@hG6hY!%>R55q{mrHAcGrrpkUx>!Vh+@6+^X z<&cNuQr1so91O-ie%A3W-X;FrBQ4;zfsoqbt*}>2tXalT>mq(;&q#@{}! z0p}2Mbn#Ul@SCZKn3}-+$PJC98ya67FF2EyeGKQWw2n1v%IZc+o$Z7zku5zJ&Y+jjjXa6q278234eBchCU?{b$O>lxZ=tMr=WT4daE8Xl$9Q zcQq|yaxxcV+1V-#)ryyeh1-4`c(9{h=yg57HLJidf2!JqFqPc`rj-Q~$RSfTO=Lh- zI<+dcnZ84()oines>o{YIiu>nvO3hZ)ak%BcD!*_7)=+%Y-AGn#^umz{jXU^R9Zw!p1$G7tXltfzkjoc+{a)plhbnS@yAb-C>k?- z?R1L@rn=cY*?e1zs(Uf}`tA|sc#OhXapQyR=Qd}XzQeqE*}$;hs0}AE95S4jq`2W8 zhqFtVRZewX>3xKXKMagB1zg^fTYkKcNt>p0O8a%c-r3_3m@ToqB1gd42TKV5(s+`l z(l3(cNZI&(n5E*5bX~*(P(seHR4W`&Y6*J5?x6D&n$$Fx-q5ZB=BkOihv99aA%^B5 z3x3XuMMOC{hLhDDxR?hvyNBHyQ4iiiFYyUuRYwY+5Y-AzY=R?#A%QYl{utWRw8-Dh zWV-nJ*nueV=w#D3yw7kS-=gjRvWJ(D*p>QR*s{OVQ!xNY84k#*ULqpVH-K=3hyF`C zt+P{bK<44;VQXd}MsZ>C+nkh~Zq^XqpGmVWSn%-**WY;GxuN0IuftYQ?xKOA;X{!8 z*{{h-MJipTxVY!{8W7i;NY0fHdRw-kVi@EM3QnvTYc$p zMVYnVPYKL9$v^dI(7(EkT5LBHw0>ImFB?!*S6Z$=^G%kMV>Vx9_D;J!^e<|a(p!ku~Tn;s7s@|ip@B8Bwz;0UScgikSI zEHqKtgxilxpIk4F;6_J3ZTiKKR>E=AR7SW-@U`H_9*X7N`{$*Q0VD$sX@tdkX(+WC z0A?vb62#&fI*B9T`{VO=KCWg`%U+fHh5Kx!;UKAskJ@q4KsqJiZs*g~HiLG1>eG6I zbINl(Wf{(;jP`A7JG_hj+4j=mOo5>D$&JCbEF%F(7pDOJ_j8zzvUZgt<1Oj>NW=TB z4?$uwDiMO@l;z?9!)?y)Eyih%82Zl6wtEu+{yBO2Wsj>HSDR#xq~H3@O{(+z_O9{; zm9fI!(0&;@^*dR5)vr%P{a9x`mHc$ETn{H>whljD*i@VV(iL2WS=NG6)k5laJNH}T zZhHz`MZIgDu{+zwSO01jL&Wcfha3Gh$!Gnio{4IyBAg0!3k4Z1co0LFl+8Z#S<4;O zT(uJJ7{l<(srE@TksKk{!9*B(P;iL-3Ahw|EMY;l0>cUu57IT7sb_0csuKFpF*NLgBgA;#YvWNt2*xkO<@R)Z7BuU}_0j@XR9;%xnWFMd{FncVwD zq00LK=ivZMh8d?TVB-WGZ?M_`C7GvWt;_3dI2U)qTm5PYjoWgfr6#oyGcW5FLoL=4 ztcB8Ba13S7HlRQ_Gj=qk~3=K3jEH^ArQ1xacPu-K= z%ZB2ve0p8s%uUv8!YFV84l;~TMrIis2n3k6hIk!R&pw$h1sYlM2@4_$;~HShc8YyWr!gnUE9Scn*9B z$OY_OaAXf6H@57vAj&-b&ADq;Q^6TtX|__2U8Zn0!?(wxA=)AyLz=xwDGk=2hjzKo z?C4|M_ceji6tKZAb7f(fDp9WVgr2@3=QC!qeSITH^vNl3t`>mu2CoewL`>8xY@#hd z9qekU2tbuJg(!E^(*hS~&_>H8)sszQ<6{pYCYHy=%Xs+d%-2akXFpJrt#D#WkiR(a z35tY!l$f;!AFlmmI>+4;hs~B;sBSM#;DeOVL8Ji`xdW_zqKf!)sG}0;^_tUZ5!wLD z8BbLL_Jq~3Go^Br+M3A|+Ns>_7dgoP&pP+Zp-gs&z{@)PIlEP~1SoC5z-XFmvUnuX zJ1Z+IsXugIMN2jADs)*~UOW$vk7YW1dP6a|9geUnUM7OU{*OMh7_=sUlhkdo!ue6R zgXrdHE`hHINEtOb9COYytWiCXECpd^_U9ReDQk9oe>YCjF?ysk_EwF#>-+oGN}3{Z zp6?XEV_p*Ah*emu%Dls`;KgL&g2%11J&7jU2cp5ZV#?xvzv?aK{_Fu@!~`qA5z^~~ zHAg#)9(x>Na9&sc{v4wZm#S~u^YI$v>O151Q)s3l@~WmxD-hDA{gQN?954cg5a}>k zbTMU9D=)-r3GwDu=^yiE@_S0X*qLe~%wGN&8RF}!P*UWfRc=VITx3YmBkx>ocfFaF zLv<|X^zi#Mo+;Qj{Jt4c0<~H+hOzyjHbP^(;NVw9ykv^JKC$RP@8DYhHFS|H>kO*y z)K3RA9!NfS$L{T$W?>&(VB?nzYsFfmAmrwI#Hm)4Eif8RBnQZr%IAFYQ-Nn1TnJu` z*kuKaV1;{_ZiaSD&NKe9^QjRp&6nQ-J;PHpw)5njCBuJRMrk%NXBnpOfic z58y4y+2zhkj+L6J2JJAFsg|aHqc3ZjI9qQ`IH^sazACxI)#qIW1SMWy#$Z`uXwepA z!nrO$i<3{wU6lN()nU?_n{obCr+K%)4|8aU#_4TwK!HJS(EFlZa}kEYS4 z(Y&tqtPy*-ocHakeWKhTZ;h2l8`s_r0~Gq&))=k3m+!8)7~{hl%G6UItwL%++%s;R zIdtW@l^J9_r8UyR;pmj|g)>T`n>3Owu2b8d+i~(c92Og)FyoMj$KA9YJmXJ9YjPfd z*}Yp2b(P}2Jvoj^bXZo7N4NaBs}bu{;wnS7<(rSdDa!aV=RK(-rP>*K4Ex&X!P1x89 zm*4ao9bWm}=T6a1DF(7;yGX5hLyf&$0UU&PUPwq~ex_?}46o756#3E=zW(!JSY>5D zYW=08QwmR+Qyb2^;YqvKgIIp#bF=g6FSK{kmW9{q9@q&wPG79{)oM0>L&+&sk?+hc zAHl!4T2i+Bu-nNbb=pe-!`UUnpT+svVRo2Pbi+68* z>FBBX`u;BqU?HqYSYH}qhH8Dd+JSV&f8FQ1wJ+Q7PNXIxQ6zkgJl}0^nG&^bqgkKH z{G}|1CN}%_W!kOm{#Vb9_5!o5k)FE5@oeb`wWn8wp1vA`_N^t6k&V$L!YyY)ZrcPl z%yt4II7PZevXI@{q<5n7s~P|O>a|oN(T#*O?vjMnG8iKJTOsQc6t9~sbzIVGsFG8T zQs)r=U#LvygHhCj0?|dtEtiMU)3tuQ)pG#wx z*)B(>&sj(<$Ab~xe*ond=Vj+$*Ivxu4kmLDwp>FH{-itYLTG9FgF{a);Vd-!GB(+h zrMgZY*p}2}FXXYX>jY;|{rr7}p`emjWrouz4)r!H!d;KOEmD$CIk~`UG7jQ6yAU{brU;=k%LXQf3=T zobS;bxiDP^8|QN<1C;^)@5-oqi{Jh?m7^iKNG(CeGkvq&htxEY+9iApgby@mW0FC= z5V4jb`80pbftVfNMy}bpIm(}p6S0g^Frg8w4A9rmjTx3b7ZPdBarx?CTctYlbzT*@ zfJD{dPepj4IX|e#BIVeCCrhN+OvMH|3H){?7p`*2qN7R+D`T?xJ?txf&ej1zHj9Pw zu2Qu!+s#d3Q&Uq(R$br&nExc<{-Fg&Oyen%uzp#N8?8zO>wM8f`TXO3;V!K#YrtA} z|3&~He|N&0unaQ^2_ZuAH}A6BJ*Yj*nR!&EBOHI~HKNk1mjfy`?n%PvWM7s? zK}y=FbG@fI(OuH=ZES4J3GQCs=TY;OazLySoKPPOmEZswlDe$xKJtkoi5Sbm}Y|Fr@=5Hqaf)Z7P1u?_t2>$&Q<>ATP%} zE>Yyqq}LW6w7h(NA4NO&<G3M{Ab3($n!b@?@RyJL+X~a@l1p0+a$YT^Bf1I<2DI1)hqQlfJqAV3I~dA zOuR3{crVtV{Iy0C=yOl3erfgxdRfZLl(;^S(}0Sz`8F12YG%Lr@KM(!jjPDD6kcYh zSIaOWke$mES*Y2R5yk$@v%Yj75pqnq)t6~0#X@~DdD8#p)0={xR1F+Q*Sibg(oX)g zCnZd#VC*H#E6UC&cb}AB(XIY2f;<1wPP;@dhznnc^HL*?%xXGmBnKj(nx?~MsWQUP z65QYSR|j>#pt@Exevn4hr=tCu=}V=SV_DuqEzE5Tw zr|%q|w$l#U0;f8%N|jGYX=nRw#+;*G_WdZ^aCk~VHFqN6v=4s#G>E1^DZkr5$m5vr z5JZ*blN~{-nodI9D3jHk5n&w$95p|adZOv|si~}n9L(l? zqY0*CRqebp-OT`jOw@eGUOFKPP~qFLd1b1zTV{Pc8M%!9NOCllj<4?#xQI z4E05#%_mbt2@N6T2&4DJyxY;UHy>zpiU~30f?AM;4@6*oCptc>q_}H)5Hr>4ZRvCK zHHj)VR`PG~&edA~GU7)<6o=4Ft?hA=P)4L~zCDgWFi`y@H6N6;Bt&zIzaZtM+9^q- z##Y)j1ucD5l%O75X8}~sUW$HSMKvxThJfa6)5RWm`KahM9&?5KKVSGgpvlPY&bNET z;oz_sH9nfY^X1yRf4pP+sim_qUL-f$WQj?qUQRK$-Lbvxj{XP@#<7d{Mg^5hw}h`M zf7o5hM9DR}lWp>PMghtS!80vOkIxa&{Yv18?NZIYSJUJ_*UO$UJ5uUxxj0!vKU=c7 zYV*#?Z=I8>2}*(FgCfmUWw0a1UN;@aZQPbUCfLml;JyA8X1``pzLUbIY0Gpc8bN}N zOjp?Id^`w{Q)?S=7B*z`_kw)+pe zIjVprMJf`Dl!VkdB$-|VX3C~;McGD3rvl;eoQTa33sbh-Fm2p@u*-`?pev+JlX(;0`x7s$wPGH02+O1=%ZWZ&kXkvA&0nZbsRfNAbhO=(A{}eV zxxjti@x@Y3eZEALT0%}(7zh&8y_lHt9$CmS0O7RQy=WaD6JKvoMR%8se8Hnn-=7|> z{gCooyE`~>ALeIY-^G2A2@?7*c|E`pdo?VqtPFREncauKd>*2%A!lU`bYRr@>Ync- zOYyXweW1nZhP@*7!+9hC#O=3V z@6&i(I5W5`yNkR^ZMW|VG}8$ua#{d3k_JTQlNcVU`jSG*MC2C}nE-00{u@!qOpX3` z@WZuuouaq_r`=*WVPvV)(2n~>GaQ&SDViTY$30_o72Xdie$CYl_p>; znBV>M6>)=^1F1JKgs+q<47E9sxDz&rJtd^mYy^|Sq#fw{8rA?flqF0x1H)D9Y@Cwq zEupnU9LhykN)(`zmA?FkS8N&}6K07X@-m~f#^dE+%aiLSr?UWE7&2Cga^!ZkvfayH z7dM-8-$(TLUk}n819TwnWRah$Hi5S58NkL@GARiNli3v_Dx-s}A~l@C)I?3;FnuKJ*V6 z+NR{oVLfF}v9%QVSoekMxzy?8n$T^N#nv&Q5FF5l;cPMSxn`xs7_%aV8a3;C{Z!;j z8OvIyRc;x#dEesCC0|d@&sO(gY8g>6F4~0Zv^0xjsp3^4URSil;yFMogU@kXf}+tS z@|$<|Of{pHET?pBNRkv;7T@$q@(jw;m|%i@sI+(QyeW&{wvk6ViAw7qj>_Pz3ylKT zs+Nx}7FFRUD&&x=K7XdR*lN8_GR+p1PkqVYREH-yx>E))FghYE_FWPl0U5neuE-9} z;cNs*OEV+6)W=U%z*9dL{D$hZGaL|ELI3INM_mJs%_AKKy*9j^-#LJE45NXKaiWQ< zCmsCb=9#f>t1EIWiGZku79KEeeR{ma$M5$i3(UQ(N!NFA^gQsY!$<7;5WzTLxy>U8 zXi-d}Q;*PJ-X|c?6;qayf}@m63C_tOrqd`777alhkbyz3j(*1p5HeQwE>1xyDJdrW zH%AL_d^$SZimoE<8OW3?Qn+*pOk||SM3uK8YBk@WGT5yV0rEbPp|yU-i>nxDE`7Ii zOhphYNZ$KdI<->3i#S}83YNS6fkLm-C)!XW==8Lu^YP*=v2R_@o1b2GGl7u5Tev*m&)CxQXFJ0gzb$>Y3CpFVuKdCH#~!bo>|UK0>$ zQM-pl$9;YQc~5UW*Oyl!07k8;rjF%g3JDM;_{pF+LXlj#x@y3n(}Go^m~G?+qE=O9 zw-|j@$gtGpOT=Zn*!558${&lIjIYSWMY-A0RHG!ErR<4WQko|>`xxNI@e(U+moQT8 zKgWDF>}6mjgBB4H0VKTMc2X;HZ-)b767s!)Fo?OjcjxXnc;NtO>**RrE0By1v`uGC zsG~5F{$P-om#5Weg;eizcNWQ5rjUrJbd7pytU3GVyVu$Il-%KpD^0v-0#;qZ)pK?n z&-zau{ku5l{aOdGnCsEl=k~SfptIEs{e;3uUm2^pbfgl8_2CbPH_JgC?XX?TW-8F* z68m`BCTiXu7~1q|wP=ae#YY7BZjBv>^&iX8_pB!Bi5Ott?!?}Z%n#L>i1Q~{(MG4T z?-2xc2s{i4ku?&>6R5-|I5H>Pi=NpG77lgKq1cHn*LyLSNfyfCt8N{b6h=zt8bgMb%q{K{-k4}t5RLPblLrRqOW$ROJP}PVfyHP%@78EkGJFGZD0Ms zr}kow4@R|=yp1P4g>v!mf~Y8g$`zj6E~n7D6r~Ks^hGWd&~nH7g@{T>-ky08jCj*ktemzQCEIHOLeWo5H zdG#IS$h_Q?!LWyjj1=%q1BwSlN|D%1)c#~}<4s}Yx;@i_?#ERs?9G;N!G_ zo)=i-h-#J_5b&UB$_cz3A?~0c3AI-lD*3%%MORoMp^AyeKGByhhC3%{)qvY%{Hs_! zL0VJxTbxeZbu9x70(w@4q`H0A0em??b#4ABY}aU3&>qgNQ##g*`lH{bfm~3o1+gHq zda4*Hj6~6KwgwOS#Cg>LJYAF96~b?QUTSI(Z54U5=|Hx0c}C?}R>r%=O$g2hAZLe! zNBX@CH~T{KI~<%y_)FtH#f^&<9@I8+eUz8~V6r<(ff zR@s(4o?fLPAwvItY*^YfFBPW!vXGO^(3vD!y}?YL-EJ%pyPAxbw?Cae)uacT7zb8S zQIYWcdizbSb08ZP0}48w@b25O$4|ciQ8-M-%nXX% z)NT3hb7xW8buFnkurNkl;euMbb-_ys&a81*?|7jkjg?4U&+>ccu+y+a;+k>I6*7^7 z%pf01N6;=01kkkOU@lVJ*Dvo9xxZexLyx=6?O=GK9QIW6es4jpHLk%mW3-nFn(8=aqnH~Y$*s9AWegDw#|_q}oVlri0JqUPa24s^GS zR)7%O{FSL#v?HU-fTjckY!EdOIo-@^_H8#} zzPtAcC`xQnx4%Q@pNmz~=@;<09>%Zy)QsWl>-*BC6pBpp+X>kZ`%1Mi(x`=h`&ZZT zYd&FG7({G_sO6>mS}*D{$ucCGqps+M8D-&$SD`3`0e{-z&Wbh_ob7Y`!CW<>s$z-i zZyxGmyvZ1V(aSmwEO-H%V$A-jL_j4d#(@kHeyFN|U+4JbSgG5JrTk%x&`kAa%XN#YRMdkxAK*AqDlS#=;_e9N=gdl3i!Eo!jh5``*@+O6xZfd-;BK90s z1*}({o*Rg+^odV}_8g_p0>?3vLS!i7O$sD!{&ZJ^PjS1WSGY`HHrU}dWhazIPyrU4 zWqCda_-hWo zx}@VnmYRethr{ixhz8jn*52f2CK~NFtYwKdv1r)jx>+Zl-B%K)kvpY&SNaOZ%3r1H z#0!Bq&F_0pQ#|6j*2E$JlEwcJf-QaTo2#0a#FB=hGn#`VPa3E3!n|noNBH{jK(mfh z9&iJFx?Zj)Kli69(u0*(Jt6y3d78y<>7~=#<5g~M&x~V)3N~w;$r2Q}zgbVo9;?VB z?+qR{!9T!22Y1D9gs~V7HoXbsdcz7G5ETPpeSDvgU?0af=ayUDjWt->SNi0Xk&7&V z63FV}UBfBT>GzUY2fsH~SmcT1=1gjpO6Zcv1R|YgM6Pu-eST#G6IW9Ha3FB)bkm~X?Ek2lbipev5^bSpvinB#lQLh67r&fBKSFeSwEioR z1T@yt1Hi*{I{BgV`k1S9kS_N1?G5zcRww9>u2|RP7{2NlK6)gJ=orm=*%GYj`RqBO z;3W75x2=rJ{;eZqA(fui?ohK2#0(vO6BD3jXA2m%7ARH6MXJvTq|A3wn7 z{dD$g55p`4_P;N(cARo>S9o^#M+{qOg`p6Y{GqYzX`n)x!uFXsQ=qYOU%}7_LrGy9 z>^e^782^9z2uYcLVuQlbfklJs)9pTadw5Xx$DKm4jaV}{Fh`~wU`6gTB8&6YN{8W) zr#9*4-WsTy#;blHwMI@(?rbVme?8K;&%oBQn=!L0Rp;8Bsl>@KFt(9P&-2c7IO216 z60Pc_RAkd zyr3^iITQSFe~$t$I#+W(+_=(X!n#)68~7QMYE@A#rPPa%*O^9a#(&pz`3(%s=$AKm zE%&N+wTwP=qxdcJ^Yiw%qwm`~!MM7*y0r#tqQlXVV#31ypa+Vq0kg?-^5>sb9ho`K zt_}gQv8annODERhRWM(xt5LpeZIe+`!+C0IQj`>uQc=N*g*7=A${~>sy*!Okny%3z z^oU;A4*%flgP9s~W@c29!{z8)bn;qOM&ym3(G3eGpP;9K)OPmeq*Kbl;e$d_(y9@N z$Xerohz1oE)!oYr9Gdv6_2A&Zkez^ICO)vLs*3K?!^6XHdpI3FlM@+}T3%FI8h&wc zkv)6J3X=agjBjFYUQkwt9;vE&CaT6>ok74cW&Zx}_Sn_)&#UkvPr;*r?%s&zR{s<+ zJp2(mg_V_cGRbI%phN){fu~nOg4=%e)r)$S;rGz)p$S!(FQK8Z*jcuVO##XUl7=c4 zG;d*p2m%tEQ1DsB<(GK)_!eMzB6|Z}z%%PhR|iKwOnuTH+Y1U_+Z-KPfNdmcaB_ zCr&(@87T{kQna_ahQ@m9xnqCQQpm;5*y3VkF{RWS7{kr}c>9}EB`EotnT70y@v#6G z@bn^=^FV(_ut56#_44=3% zf59W7gl2Yt)8eNLh;SkakXs+(YALVy1q9HsunHxAQJCD_J$%PQ^9N2hZ({KB=9lm* zDeR9H>t3$_<^Pb+pWUCLxkx9nKgC4iG8+wT|FW>P5*=?_Su2Yh`&3@{_OH3lrHq18S>=2K3 zF@h?jHW6DfK7Kmi=7D-drJ6``vJzWg&-!R{wg1q8?9rJx=+-l?QPoqa-7xuer=8re za~e&%KwV8OI9gjf4Tm@ekaY&5c%Fmm<+b0P4a!}dooC&Kb!ck*3z)z&V-my$emu^N zAC9uOS1UOu1{h*;b%-zP4c63CwuA5J^tusiPoDM2Uq%5rg0xk?ZM5G^B0*!!7Kesd z5**P9cwnTzV?7fUf4gpkc^mZ-3Ua&1(F}Gy0qw)yE;R1Pn%CSe`$+@?1VX;vshO-# zr$LAy85tRAznyI2C42o~Cd=IbMM33m@W6r{Ig_AXJI~zG`vQk_zZHM{i30TJ@rotv zot3{)UpVNMSSl<94n83?DkA8ds9LDF*howxC1d+wU`#Wwf>ek^TU%SYtv&b8%yht# zkK$X9z@FiB9*`aWZ=p|fN3Tu-p)0lOpn1OdmJ2?QCKl9)rnX7Y+L;1FL+jBnNbFSz z#=HA6s0}DDy9HRI*I1(z!1vVCzQh9k>+AMUOdnMIEyd1>=TM7hpW}=}{4q+0qAM-6%K)}7jWL6g8;cN#HAd(tPA_c@``ja3a%}N6nh8=Qp-aEjT z+W5=L#--%MAYf8CHwTm3y{5=C9pV(G*Q^?ELmnN#q@Lsy9vk_!%_$taVYtCVD;yv~ z+cnBT)0)lYBLp>f%6oEZ2wA%Vl#N=k94?V-N))mqk|xz|@9r%3ADLr_RNv`!^4_@E zx>w0Wg}mI8GjrGIR6DxdTa1AEL9)a7W=tT|qmz)tdd&#FC>!}{e|yWBDQ^?OC?YxJ zaIr1_HSPa#*3+x2DHS618-f1BMXQ18a2u*g25H#)bHs5(KbOrLH8a5|1X_FQBY8Tnwf^3nry2JZ#J*F zjSZvg@oa#d!k3N)|K;!B#Z>iYrlt)46Xw>zoxQ5>3pl2X|K&h~-E}r$D0%2mG(`?p zH7zCo%c!^f@6Zjo5-99QeSJ6KujLC_s9wE#E%)*t0mpN%H8nNc@ZLrCiT8-o<8zG&XW#TTd=|Uj}g?ulNIw;tdNp0I7SMG9&lM@NjTrBNvdxSv-gFxOsS7 z%9z(mno8jxu8+j7<{I$+Y$no4L%x2^&C7$jy1Hs|*nkBzwnAj`@>uZRo?f2?#5Oh( z^d_{UW@l#~iN?Lj0W$eAkPwrKA3>4}^YaU1)ANY<^5FXw3pI6h?DC2Vhat0|%*=P8 z$nT1w(}JsZ3i8<%jR!eQoNbNGimg`0O@|EaiK=NUEuqc+u6mHJ|3qZaBh>2AGa1_X zrM+&aFA)G@ZVhg1-$dgDBwJeIaoJ{pPUGTB1PRNjJ4ViwwJb~+!w@u zV+a7!&$Rz#yq68tP71^nr2aMl9lszKAY=XWlfN&4k9mp!$PqWr1L1$)0HAHJ`AcGZ zxoIfG%fPN|-~u!2l>htv+^$@#T5X%tvx^^oPze)p8%C|qrojJjypoYn5U&c&d C Date: Mon, 1 Apr 2024 18:53:48 +0900 Subject: [PATCH 06/57] feat(perception_online_evaluator): unify debug markers instead of separating for each object (#6681) * feat(perception_online_evaluator): unify debug markers instead of separating for each object Signed-off-by: kosuke55 * fix for Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../utils/marker_utils.hpp | 6 +- .../src/perception_online_evaluator_node.cpp | 94 ++++++++++++------- .../src/utils/marker_utils.cpp | 11 ++- 3 files changed, 68 insertions(+), 43 deletions(-) diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp index 3ac4c1db9efbd..0831d580248d3 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp +++ b/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp @@ -63,8 +63,8 @@ MarkerArray createPoseMarkerArray( const float & b); MarkerArray createPosesMarkerArray( - const std::vector poses, std::string && ns, const float & r, const float & g, - const float & b, const float & x_scale = 0.5, const float & y_scale = 0.2, + const std::vector poses, std::string && ns, const int32_t & first_id, const float & r, + const float & g, const float & b, const float & x_scale = 0.5, const float & y_scale = 0.2, const float & z_scale = 0.2); std_msgs::msg::ColorRGBA createColorFromString(const std::string & str); @@ -75,7 +75,7 @@ MarkerArray createObjectPolygonMarkerArray( MarkerArray createDeviationLines( const std::vector poses1, const std::vector poses2, const std::string & ns, - const float r, const float g, const float b); + const int32_t & first_id, const float r, const float g, const float b); } // namespace marker_utils diff --git a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp index 8820ad16fd8d5..f3a08bf42797a 100644 --- a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp @@ -132,50 +132,74 @@ void PerceptionOnlineEvaluatorNode::publishDebugMarker() tier4_autoware_utils::appendMarkerArray(added, &marker); }; - const auto history_path_map = metrics_calculator_.getHistoryPathMap(); const auto & p = parameters_->debug_marker_parameters; - for (const auto & [uuid, history_path] : history_path_map) { - { - const auto c = createColorFromString(uuid + "_raw"); - if (p.show_history_path) { - add(createPointsMarkerArray(history_path.first, "history_path_" + uuid, 0, c.r, c.g, c.b)); + // visualize history path + { + const auto history_path_map = metrics_calculator_.getHistoryPathMap(); + int32_t history_path_first_id = 0; + int32_t smoothed_history_path_first_id = 0; + size_t i = 0; + for (const auto & [uuid, history_path] : history_path_map) { + { + const auto c = createColorFromString(uuid + "_raw"); + if (p.show_history_path) { + add(createPointsMarkerArray(history_path.first, "history_path", i, c.r, c.g, c.b)); + } + if (p.show_history_path_arrows) { + add(createPosesMarkerArray( + history_path.first, "history_path_arrows", history_path_first_id, c.r, c.g, c.b, 0.1, + 0.05, 0.05)); + history_path_first_id += history_path.first.size(); + } } - if (p.show_history_path_arrows) { - add(createPosesMarkerArray( - history_path.first, "history_path_arrows_" + uuid, c.r, c.g, c.b, 0.1, 0.05, 0.05)); + { + const auto c = createColorFromString(uuid); + if (p.show_smoothed_history_path) { + add(createPointsMarkerArray( + history_path.second, "smoothed_history_path", i, c.r, c.g, c.b)); + } + if (p.show_smoothed_history_path_arrows) { + add(createPosesMarkerArray( + history_path.second, "smoothed_history_path_arrows", smoothed_history_path_first_id, + c.r, c.g, c.b, 0.1, 0.05, 0.05)); + smoothed_history_path_first_id += history_path.second.size(); + } } + i++; } - { + } + + // visualize predicted path of past objects + { + int32_t predicted_path_first_id = 0; + int32_t history_path_first_id = 0; + int32_t deviation_lines_first_id = 0; + size_t i = 0; + const auto object_data_map = metrics_calculator_.getDebugObjectData(); + for (const auto & [uuid, object_data] : object_data_map) { const auto c = createColorFromString(uuid); - if (p.show_smoothed_history_path) { - add(createPointsMarkerArray( - history_path.second, "smoothed_history_path_" + uuid, 0, c.r, c.g, c.b)); + const auto predicted_path = object_data.getPredictedPath(); + const auto history_path = object_data.getHistoryPath(); + if (p.show_predicted_path) { + add(createPosesMarkerArray( + predicted_path, "predicted_path", predicted_path_first_id, 0, 0, 1)); + predicted_path_first_id += predicted_path.size(); } - if (p.show_smoothed_history_path_arrows) { + if (p.show_predicted_path_gt) { add(createPosesMarkerArray( - history_path.second, "smoothed_history_path_arrows_" + uuid, c.r, c.g, c.b, 0.1, 0.05, - 0.05)); + history_path, "predicted_path_gt", history_path_first_id, 1, 0, 0)); + history_path_first_id += history_path.size(); } - } - } - const auto object_data_map = metrics_calculator_.getDebugObjectData(); - for (const auto & [uuid, object_data] : object_data_map) { - const auto c = createColorFromString(uuid); - const auto predicted_path = object_data.getPredictedPath(); - const auto history_path = object_data.getHistoryPath(); - if (p.show_predicted_path) { - add(createPosesMarkerArray(predicted_path, "predicted_path_" + uuid, 0, 0, 1)); - } - if (p.show_predicted_path_gt) { - add(createPosesMarkerArray(history_path, "predicted_path_gt_" + uuid, 1, 0, 0)); - } - if (p.show_deviation_lines) { - add(createDeviationLines(predicted_path, history_path, "deviation_lines_" + uuid, 1, 1, 1)); - } - if (p.show_object_polygon) { - add(createObjectPolygonMarkerArray( - object_data.object, "object_polygon_" + uuid, 0, c.r, c.g, c.b)); + if (p.show_deviation_lines) { + add(createDeviationLines( + predicted_path, history_path, "deviation_lines", deviation_lines_first_id, 1, 1, 1)); + deviation_lines_first_id += predicted_path.size(); + } + if (p.show_object_polygon) { + add(createObjectPolygonMarkerArray(object_data.object, "object_polygon", i, c.r, c.g, c.b)); + } + i++; } } diff --git a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp b/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp index 75af92e83dcd8..a29e1a468e983 100644 --- a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp +++ b/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp @@ -111,14 +111,14 @@ MarkerArray createPointsMarkerArray( MarkerArray createDeviationLines( const std::vector poses1, const std::vector poses2, const std::string & ns, - const float r, const float g, const float b) + const int32_t & first_id, const float r, const float g, const float b) { MarkerArray msg; const size_t max_idx = std::min(poses1.size(), poses2.size()); for (size_t i = 0; i < max_idx; ++i) { auto marker = createDefaultMarker( - "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, i, Marker::LINE_STRIP, + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, first_id + i, Marker::LINE_STRIP, createMarkerScale(0.005, 0.0, 0.0), createMarkerColor(r, g, b, 0.5)); marker.points.push_back(poses1.at(i).position); marker.points.push_back(poses2.at(i).position); @@ -144,14 +144,15 @@ MarkerArray createPoseMarkerArray( } MarkerArray createPosesMarkerArray( - const std::vector poses, std::string && ns, const float & r, const float & g, - const float & b, const float & x_scale, const float & y_scale, const float & z_scale) + const std::vector poses, std::string && ns, const int32_t & first_id, const float & r, + const float & g, const float & b, const float & x_scale, const float & y_scale, + const float & z_scale) { MarkerArray msg; for (size_t i = 0; i < poses.size(); ++i) { Marker marker = createDefaultMarker( - "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, i, Marker::ARROW, + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, first_id + i, Marker::ARROW, createMarkerScale(x_scale, y_scale, z_scale), createMarkerColor(r, g, b, 0.5)); marker.pose = poses.at(i); msg.markers.push_back(marker); From f77f0f7bb7bd3257b3edae55eb42f3d04f96edb6 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 1 Apr 2024 18:54:27 +0900 Subject: [PATCH 07/57] feat(perception_online_evaluator): extract moving object for deviation check (#6682) fix test Signed-off-by: kosuke55 --- .../perception_online_evaluator.defaults.yaml | 2 +- .../src/metrics_calculator.cpp | 90 +++++++++++++++---- .../test_perception_online_evaluator_node.cpp | 65 +++++++++----- 3 files changed, 114 insertions(+), 43 deletions(-) diff --git a/evaluator/perception_online_evaluator/param/perception_online_evaluator.defaults.yaml b/evaluator/perception_online_evaluator/param/perception_online_evaluator.defaults.yaml index 976b10a2c73f9..46ea68c991090 100644 --- a/evaluator/perception_online_evaluator/param/perception_online_evaluator.defaults.yaml +++ b/evaluator/perception_online_evaluator/param/perception_online_evaluator.defaults.yaml @@ -11,7 +11,7 @@ prediction_time_horizons: [1.0, 2.0, 3.0, 5.0] - stopped_velocity_threshold: 0.3 + stopped_velocity_threshold: 1.0 target_object: car: diff --git a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp index 60e02c8f24c39..20d8c6d570489 100644 --- a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp +++ b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp @@ -37,20 +37,25 @@ std::optional MetricsCalculator::calculate(const Metric & metric) return {}; } const auto target_stamp_objects = getObjectsByStamp(target_stamp); - const auto class_objects_map = separateObjectsByClass(target_stamp_objects); - // filter stopped objects + // extract moving objects + const auto moving_objects = filterObjectsByVelocity( + target_stamp_objects, parameters_->stopped_velocity_threshold, + /*remove_above_threshold=*/false); + const auto class_moving_objects_map = separateObjectsByClass(moving_objects); + + // extract stopped objects const auto stopped_objects = filterObjectsByVelocity(target_stamp_objects, parameters_->stopped_velocity_threshold); const auto class_stopped_objects_map = separateObjectsByClass(stopped_objects); switch (metric) { case Metric::lateral_deviation: - return calcLateralDeviationMetrics(class_objects_map); + return calcLateralDeviationMetrics(class_moving_objects_map); case Metric::yaw_deviation: - return calcYawDeviationMetrics(class_objects_map); + return calcYawDeviationMetrics(class_moving_objects_map); case Metric::predicted_path_deviation: - return calcPredictedPathDeviationMetrics(class_objects_map); + return calcPredictedPathDeviationMetrics(class_moving_objects_map); case Metric::yaw_rate: return calcYawRateMetrics(class_stopped_objects_map); default: @@ -372,7 +377,7 @@ MetricStatMap MetricsCalculator::calcYawRateMetrics(const ClassObjectsMap & clas } const auto [previous_stamp, previous_object] = previous_object_with_stamp_opt.value(); - const auto time_diff = (stamp - previous_stamp).seconds(); + const double time_diff = (stamp - previous_stamp).seconds(); if (time_diff < 0.01) { continue; } @@ -443,7 +448,34 @@ void MetricsCalculator::updateHistoryPath() for (const auto & [uuid, stamp_and_objects] : object_map_) { std::vector history_path; - for (const auto & [stamp, object] : stamp_and_objects) { + for (auto it = stamp_and_objects.begin(); it != stamp_and_objects.end(); ++it) { + const auto & [stamp, object] = *it; + + // skip if the object is stopped + // calculate velocity from previous object + if (it != stamp_and_objects.begin()) { + const auto & [prev_stamp, prev_object] = *std::prev(it); + const double time_diff = (stamp - prev_stamp).seconds(); + if (time_diff < 0.01) { + continue; + } + const auto current_pose = object.kinematics.initial_pose_with_covariance.pose; + const auto prev_pose = prev_object.kinematics.initial_pose_with_covariance.pose; + const auto velocity = + tier4_autoware_utils::calcDistance2d(current_pose.position, prev_pose.position) / + time_diff; + if (velocity < parameters_->stopped_velocity_threshold) { + continue; + } + } + if ( + std::hypot( + object.kinematics.initial_twist_with_covariance.twist.linear.x, + object.kinematics.initial_twist_with_covariance.twist.linear.y) < + parameters_->stopped_velocity_threshold) { + continue; + } + history_path.push_back(object.kinematics.initial_pose_with_covariance.pose); } @@ -507,27 +539,49 @@ std::vector MetricsCalculator::averageFilterPath( average_pose.position = path.at(i).position; } + // skip if the points are too close + if ( + filtered_path.size() > 0 && + calcDistance2d(filtered_path.back().position, average_pose.position) < 0.5) { + continue; + } + + // skip if the difference between the current orientation and the azimuth angle is large + if (i > 0) { + const double azimuth = calcAzimuthAngle(path.at(i - 1).position, path.at(i).position); + const double yaw = tf2::getYaw(path.at(i).orientation); + if (tier4_autoware_utils::normalizeRadian(yaw - azimuth) > M_PI_2) { + continue; + } + } + // Placeholder for orientation to ensure structure integrity average_pose.orientation = path.at(i).orientation; filtered_path.push_back(average_pose); } - // Calculate yaw and convert to quaternion after averaging positions - for (size_t i = 0; i < filtered_path.size(); ++i) { - Pose & p = filtered_path[i]; - - // if the current pose is too close to the previous one, use the previous orientation - if (i > 0) { - const Pose & p_prev = filtered_path[i - 1]; - if (calcDistance2d(p_prev.position, p.position) < 0.1) { - p.orientation = p_prev.orientation; + // delete pose if the difference between the azimuth angle of the previous and next poses is large + if (filtered_path.size() > 2) { + auto it = filtered_path.begin() + 2; + while (it != filtered_path.end()) { + const double azimuth_to_prev = calcAzimuthAngle((it - 2)->position, (it - 1)->position); + const double azimuth_to_current = calcAzimuthAngle((it - 1)->position, it->position); + if ( + std::abs(tier4_autoware_utils::normalizeRadian(azimuth_to_prev - azimuth_to_current)) > + M_PI_2) { + it = filtered_path.erase(it); continue; } + ++it; } + } + // Calculate yaw and convert to quaternion after averaging positions + for (size_t i = 0; i < filtered_path.size(); ++i) { + Pose & p = filtered_path[i]; if (i < filtered_path.size() - 1) { - const double yaw = calcAzimuthAngle(p.position, filtered_path[i + 1].position); - filtered_path[i].orientation = createQuaternionFromYaw(yaw); + const double azimuth_to_next = calcAzimuthAngle(p.position, filtered_path[i + 1].position); + filtered_path[i].orientation = createQuaternionFromYaw(azimuth_to_next); } else if (filtered_path.size() > 1) { // For the last point, use the orientation of the second-to-last point p.orientation = filtered_path[i - 1].orientation; diff --git a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp index 2975a1b4d6df8..dabd17b9db46a 100644 --- a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp @@ -115,7 +115,7 @@ class EvalTest : public ::testing::Test PredictedObject makePredictedObject( const std::vector> & predicted_path, - const uint8_t label = ObjectClassification::CAR) + const uint8_t label = ObjectClassification::CAR, const double velocity = 2.0) { PredictedObject object; object.object_id = uuid_; @@ -133,6 +133,10 @@ class EvalTest : public ::testing::Test object.kinematics.initial_pose_with_covariance.pose.orientation.z = 0.0; object.kinematics.initial_pose_with_covariance.pose.orientation.w = 1.0; + object.kinematics.initial_twist_with_covariance.twist.linear.x = velocity; + object.kinematics.initial_twist_with_covariance.twist.linear.y = 0.0; + object.kinematics.initial_twist_with_covariance.twist.linear.z = 0.0; + autoware_auto_perception_msgs::msg::PredictedPath path; for (size_t i = 0; i < predicted_path.size(); ++i) { geometry_msgs::msg::Pose pose; @@ -155,34 +159,35 @@ class EvalTest : public ::testing::Test PredictedObjects makePredictedObjects( const std::vector> & predicted_path, - const uint8_t label = ObjectClassification::CAR) + const uint8_t label = ObjectClassification::CAR, const double velocity = 2.0) { PredictedObjects objects; - objects.objects.push_back(makePredictedObject(predicted_path, label)); + objects.objects.push_back(makePredictedObject(predicted_path, label, velocity)); objects.header.stamp = rclcpp::Time(0); return objects; } PredictedObjects makeStraightPredictedObjects( - const double time, const uint8_t label = ObjectClassification::CAR) + const double time, const uint8_t label = ObjectClassification::CAR, const double velocity = 2.0) { std::vector> predicted_path; for (size_t i = 0; i <= time_horizon_ / time_step_; i++) { - predicted_path.push_back({velocity_ * (time + i * time_step_), 0.0}); + predicted_path.push_back({velocity * (time + i * time_step_), 0.0}); } - auto objects = makePredictedObjects(predicted_path, label); + auto objects = makePredictedObjects(predicted_path, label, velocity); objects.header.stamp = rclcpp::Time(0) + rclcpp::Duration::from_seconds(time); return objects; } PredictedObjects makeDeviatedStraightPredictedObjects( - const double time, const double deviation, const uint8_t label = ObjectClassification::CAR) + const double time, const double deviation, const uint8_t label = ObjectClassification::CAR, + const double velocity = 2.0) { std::vector> predicted_path; for (size_t i = 0; i <= time_horizon_ / time_step_; i++) { - predicted_path.push_back({velocity_ * (time + i * time_step_), deviation}); + predicted_path.push_back({velocity * (time + i * time_step_), deviation}); } - auto objects = makePredictedObjects(predicted_path, label); + auto objects = makePredictedObjects(predicted_path, label, velocity); objects.header.stamp = rclcpp::Time(0) + rclcpp::Duration::from_seconds(time); return objects; } @@ -249,7 +254,6 @@ class EvalTest : public ::testing::Test double time_delay_ = 5.0; double time_step_ = 0.5; double time_horizon_ = 10.0; - double velocity_ = 2.0; unique_identifier_msgs::msg::UUID uuid_; }; @@ -589,11 +593,12 @@ TEST_F(EvalTest, testYawRate_0) setTargetMetric("yaw_rate_CAR"); for (double time = 0; time <= time_delay_; time += time_step_) { - const auto objects = makeStraightPredictedObjects(time); + const auto objects = makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0); publishObjects(objects); } - const auto last_objects = makeStraightPredictedObjects(time_delay_ + time_step_); + const auto last_objects = + makeStraightPredictedObjects(time_delay_ + time_step_, ObjectClassification::CAR, 0.0); EXPECT_NEAR(publishObjectsAndGetMetric(last_objects), 0.0, epsilon); } @@ -605,12 +610,14 @@ TEST_F(EvalTest, testYawRate_01) const double yaw_rate = 0.1; for (double time = 0; time <= time_delay_; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), yaw_rate * time); publishObjects(objects); } for (double time = time_delay_ + time_step_; time < time_delay_ * 2; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), yaw_rate * time); EXPECT_NEAR(publishObjectsAndGetMetric(objects), yaw_rate, epsilon); } } @@ -623,12 +630,14 @@ TEST_F(EvalTest, testYawRate_minus_01) const double yaw_rate = 0.1; for (double time = 0; time <= time_delay_; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), -yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), -yaw_rate * time); publishObjects(objects); } for (double time = time_delay_ + time_step_; time < time_delay_ * 2; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), -yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), -yaw_rate * time); EXPECT_NEAR(publishObjectsAndGetMetric(objects), yaw_rate, epsilon); } } @@ -641,12 +650,14 @@ TEST_F(EvalTest, testYawRate_1) const double yaw_rate = 1.0; for (double time = 0; time <= time_delay_; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), yaw_rate * time); publishObjects(objects); } for (double time = time_delay_ + time_step_; time < time_delay_ * 2; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), yaw_rate * time); EXPECT_NEAR(publishObjectsAndGetMetric(objects), yaw_rate, epsilon); } } @@ -659,12 +670,14 @@ TEST_F(EvalTest, testYawRate_minus_1) const double yaw_rate = 1.0; for (double time = 0; time <= time_delay_; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), -yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), -yaw_rate * time); publishObjects(objects); } for (double time = time_delay_ + time_step_; time < time_delay_ * 2; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), -yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), -yaw_rate * time); EXPECT_NEAR(publishObjectsAndGetMetric(objects), yaw_rate, epsilon); } } @@ -677,12 +690,14 @@ TEST_F(EvalTest, testYawRate_5) const double yaw_rate = 5.0; for (double time = 0; time <= time_delay_; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), yaw_rate * time); publishObjects(objects); } for (double time = time_delay_ + time_step_; time < time_delay_ * 2; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), yaw_rate * time); EXPECT_NEAR(publishObjectsAndGetMetric(objects), yaw_rate, epsilon); } } @@ -695,12 +710,14 @@ TEST_F(EvalTest, testYawRate_minus_5) const double yaw_rate = 5.0; for (double time = 0; time <= time_delay_; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), -yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), -yaw_rate * time); publishObjects(objects); } for (double time = time_delay_ + time_step_; time < time_delay_ * 2; time += time_step_) { - const auto objects = rotateObjects(makeStraightPredictedObjects(time), -yaw_rate * time); + const auto objects = rotateObjects( + makeStraightPredictedObjects(time, ObjectClassification::CAR, 0.0), -yaw_rate * time); EXPECT_NEAR(publishObjectsAndGetMetric(objects), yaw_rate, epsilon); } } From dadbb2cdad44145cd61c67bcdb11bbfd2feff4f0 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 1 Apr 2024 22:40:00 +0900 Subject: [PATCH 08/57] feat(start_planner): add validation check to prevent over cropped paths (#6721) * add validation check to prevent over cropped paths Signed-off-by: Daniel Sanchez * use constexpr for magic number Signed-off-by: Daniel Sanchez * make the threshold a param Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../config/start_planner.param.yaml | 1 + .../data_structs.hpp | 1 + .../src/manager.cpp | 4 ++++ .../src/shift_pull_out.cpp | 20 +++++++++++++++++++ 4 files changed, 26 insertions(+) diff --git a/planning/behavior_path_start_planner_module/config/start_planner.param.yaml b/planning/behavior_path_start_planner_module/config/start_planner.param.yaml index b17db7f907471..46469de68149e 100644 --- a/planning/behavior_path_start_planner_module/config/start_planner.param.yaml +++ b/planning/behavior_path_start_planner_module/config/start_planner.param.yaml @@ -27,6 +27,7 @@ shift_collision_check_distance_from_end: -10.0 minimum_shift_pull_out_distance: 0.0 deceleration_interval: 15.0 + maximum_longitudinal_deviation: 1.0 # Note, should be the same or less than planning validator's "longitudinal_distance_deviation" lateral_jerk: 0.5 lateral_acceleration_sampling_num: 3 minimum_lateral_acc: 0.15 diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp index 1e32237ffd870..0e85c1d0e76b3 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp @@ -84,6 +84,7 @@ struct StartPlannerParameters double minimum_lateral_acc{0.0}; double maximum_curvature{0.0}; // maximum curvature considered in the path generation double deceleration_interval{0.0}; + double maximum_longitudinal_deviation{0.0}; // geometric pull out bool enable_geometric_pull_out{false}; double geometric_collision_check_distance_from_end; diff --git a/planning/behavior_path_start_planner_module/src/manager.cpp b/planning/behavior_path_start_planner_module/src/manager.cpp index 050d591128a15..794577d7cc7aa 100644 --- a/planning/behavior_path_start_planner_module/src/manager.cpp +++ b/planning/behavior_path_start_planner_module/src/manager.cpp @@ -88,6 +88,8 @@ void StartPlannerModuleManager::init(rclcpp::Node * node) p.minimum_lateral_acc = node->declare_parameter(ns + "minimum_lateral_acc"); p.maximum_curvature = node->declare_parameter(ns + "maximum_curvature"); p.deceleration_interval = node->declare_parameter(ns + "deceleration_interval"); + p.maximum_longitudinal_deviation = + node->declare_parameter(ns + "maximum_longitudinal_deviation"); // geometric pull out p.enable_geometric_pull_out = node->declare_parameter(ns + "enable_geometric_pull_out"); p.geometric_collision_check_distance_from_end = @@ -424,6 +426,8 @@ void StartPlannerModuleManager::updateModuleParams( updateParam(parameters, ns + "minimum_lateral_acc", p->minimum_lateral_acc); updateParam(parameters, ns + "maximum_curvature", p->maximum_curvature); updateParam(parameters, ns + "deceleration_interval", p->deceleration_interval); + updateParam( + parameters, ns + "maximum_longitudinal_deviation", p->maximum_longitudinal_deviation); updateParam(parameters, ns + "enable_geometric_pull_out", p->enable_geometric_pull_out); updateParam(parameters, ns + "divide_pull_out_path", p->divide_pull_out_path); updateParam( diff --git a/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp index c6a56139e63d2..592f57ed97dcf 100644 --- a/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp +++ b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp @@ -111,6 +111,26 @@ std::optional ShiftPullOut::plan(const Pose & start_pose, const Pos const auto cropped_path = lane_departure_checker_->cropPointsOutsideOfLanes( lanelet_map_ptr, shift_path, start_segment_idx); if (cropped_path.points.empty()) continue; + + // check that the path is not cropped in excess and there is not excessive longitudinal + // deviation between the first 2 points + auto validate_cropped_path = [&](const auto & cropped_path) -> bool { + if (cropped_path.points.size() < 2) return false; + const double max_long_offset = parameters_.maximum_longitudinal_deviation; + const size_t start_segment_idx_after_crop = + motion_utils::findFirstNearestIndexWithSoftConstraints(cropped_path.points, start_pose); + + // if the start segment id after crop is not 0, then the cropping is not excessive + if (start_segment_idx_after_crop != 0) return true; + + const auto long_offset_to_closest_point = motion_utils::calcLongitudinalOffsetToSegment( + cropped_path.points, start_segment_idx_after_crop, start_pose.position); + const auto long_offset_to_next_point = motion_utils::calcLongitudinalOffsetToSegment( + cropped_path.points, start_segment_idx_after_crop + 1, start_pose.position); + return std::abs(long_offset_to_closest_point - long_offset_to_next_point) < max_long_offset; + }; + + if (!validate_cropped_path(cropped_path)) continue; shift_path.points = cropped_path.points; shift_path.header = planner_data_->route_handler->getRouteHeader(); From 2d105d5b073de25cd31ae2dbdeeed82aaa6c3624 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 1 Apr 2024 22:40:19 +0900 Subject: [PATCH 09/57] feat(obstacle_avoidance_planner): sanitize reference points (#6704) * feat(obstacle_avoidance_planner): sanitize reference points Signed-off-by: Daniel Sanchez * bugfix, first point was excluded Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../utils/trajectory_utils.hpp | 2 ++ .../src/mpt_optimizer.cpp | 4 ++++ .../src/utils/trajectory_utils.cpp | 18 ++++++++++++++++++ 3 files changed, 24 insertions(+) diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/utils/trajectory_utils.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/utils/trajectory_utils.hpp index fb49a7fa446be..d119acf09b6ea 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/utils/trajectory_utils.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/utils/trajectory_utils.hpp @@ -129,6 +129,8 @@ ReferencePoint convertToReferencePoint(const TrajectoryPoint & traj_point); std::vector convertToReferencePoints( const std::vector & traj_points); +std::vector sanitizePoints(const std::vector & points); + void compensateLastPose( const PathPoint & last_path_point, std::vector & traj_points, const double delta_dist_threshold, const double delta_yaw_threshold); diff --git a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp index 7057a2885fd52..94dc62b1335d4 100644 --- a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp +++ b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp @@ -567,6 +567,9 @@ std::vector MPTOptimizer::calcReferencePoints( ref_points = motion_utils::cropPoints( ref_points, p.ego_pose.position, ego_seg_idx, forward_traj_length + tmp_margin, backward_traj_length + tmp_margin); + + // remove repeated points + ref_points = trajectory_utils::sanitizePoints(ref_points); SplineInterpolationPoints2d ref_points_spline(ref_points); ego_seg_idx = trajectory_utils::findEgoSegmentIndex(ref_points, p.ego_pose, ego_nearest_param_); @@ -586,6 +589,7 @@ std::vector MPTOptimizer::calcReferencePoints( // NOTE: This must be after backward cropping. // New start point may be added and resampled. Spline calculation is required. updateFixedPoint(ref_points); + ref_points = trajectory_utils::sanitizePoints(ref_points); ref_points_spline = SplineInterpolationPoints2d(ref_points); // 6. update bounds diff --git a/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp b/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp index 453d55bd7f770..651b11b28e8bc 100644 --- a/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp +++ b/planning/obstacle_avoidance_planner/src/utils/trajectory_utils.cpp @@ -79,6 +79,24 @@ std::vector convertToReferencePoints( return ref_points; } +std::vector sanitizePoints(const std::vector & points) +{ + std::vector output; + for (size_t i = 0; i < points.size(); i++) { + if (i > 0) { + const auto & current_pos = points.at(i).pose.position; + const auto & prev_pos = points.at(i - 1).pose.position; + if ( + std::fabs(current_pos.x - prev_pos.x) < 1e-6 && + std::fabs(current_pos.y - prev_pos.y) < 1e-6) { + continue; + } + } + output.push_back(points.at(i)); + } + return output; +} + void compensateLastPose( const PathPoint & last_path_point, std::vector & traj_points, const double delta_dist_threshold, const double delta_yaw_threshold) From 8f67bc90a88e427de59715240ad933cd67fc2855 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 2 Apr 2024 09:54:15 +0900 Subject: [PATCH 10/57] fix(pose_initializer): added "user_defined_initial_pose" to dummy localization (#6723) Added "used_defined_initial_pose" to dummy localization Signed-off-by: Shintaro Sakoda --- launch/tier4_simulator_launch/launch/simulator.launch.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 4af7b3abaa2e6..76fb66e4ebfdf 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -127,6 +127,8 @@ + + From 6e6e6019b26da9fa68c021cc9bd21826c5691275 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 2 Apr 2024 15:15:31 +0900 Subject: [PATCH 11/57] feat(static_centerline_optimizer): static centerline optimizer with GUI (#6717) feat: add GUI for static centerline optimizer Signed-off-by: Takayuki Murooka --- .../static_centerline_optimizer_node.hpp | 18 ++ .../static_centerline_optimizer.launch.xml | 1 + .../scripts/centerline_updater_helper.py | 198 ++++++++++++++++++ .../scripts/tmp/run.sh | 2 +- .../src/static_centerline_optimizer_node.cpp | 67 ++++++ 5 files changed, 285 insertions(+), 1 deletion(-) create mode 100755 planning/static_centerline_optimizer/scripts/centerline_updater_helper.py diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp index fa7043de42f5c..f25a6771aa0cb 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp @@ -22,6 +22,9 @@ #include "static_centerline_optimizer/type_alias.hpp" #include "vehicle_info_util/vehicle_info_util.hpp" +#include "std_msgs/msg/bool.hpp" +#include "std_msgs/msg/int32.hpp" + #include #include #include @@ -67,13 +70,28 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node HADMapBin::ConstSharedPtr map_bin_ptr_{nullptr}; std::shared_ptr route_handler_ptr_{nullptr}; + int traj_start_index_{0}; + int traj_end_index_{0}; + struct MetaDataToSaveMap + { + std::vector optimized_traj_points{}; + std::vector route_lane_ids{}; + }; + std::optional meta_data_to_save_map_{std::nullopt}; + // publisher rclcpp::Publisher::SharedPtr pub_map_bin_{nullptr}; rclcpp::Publisher::SharedPtr pub_raw_path_with_lane_id_{nullptr}; rclcpp::Publisher::SharedPtr pub_raw_path_{nullptr}; rclcpp::Publisher::SharedPtr pub_debug_unsafe_footprints_{nullptr}; + rclcpp::Publisher::SharedPtr pub_whole_optimized_centerline_{nullptr}; rclcpp::Publisher::SharedPtr pub_optimized_centerline_{nullptr}; + // subscriber + rclcpp::Subscription::SharedPtr sub_traj_start_index_; + rclcpp::Subscription::SharedPtr sub_traj_end_index_; + rclcpp::Subscription::SharedPtr sub_save_map_; + // service rclcpp::Service::SharedPtr srv_load_map_; rclcpp::Service::SharedPtr srv_plan_route_; diff --git a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml index 37a9abc47bfeb..2e163e2eb93eb 100644 --- a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml +++ b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml @@ -56,6 +56,7 @@ + diff --git a/planning/static_centerline_optimizer/scripts/centerline_updater_helper.py b/planning/static_centerline_optimizer/scripts/centerline_updater_helper.py new file mode 100755 index 0000000000000..00a646406f14f --- /dev/null +++ b/planning/static_centerline_optimizer/scripts/centerline_updater_helper.py @@ -0,0 +1,198 @@ +#!/bin/env python3 + +# Copyright 2024 TIER IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + + +import sys +import time + +from PyQt5 import QtCore +from PyQt5.QtWidgets import QApplication +from PyQt5.QtWidgets import QGridLayout +from PyQt5.QtWidgets import QMainWindow +from PyQt5.QtWidgets import QPushButton +from PyQt5.QtWidgets import QSizePolicy +from PyQt5.QtWidgets import QSlider +from PyQt5.QtWidgets import QWidget +from autoware_auto_planning_msgs.msg import Trajectory +import rclpy +from rclpy.node import Node +from rclpy.qos import QoSDurabilityPolicy +from rclpy.qos import QoSProfile +from std_msgs.msg import Bool +from std_msgs.msg import Int32 + + +class CenterlineUpdaterWidget(QMainWindow): + def __init__(self): + super(self.__class__, self).__init__() + self.setupUI() + + def setupUI(self): + self.setObjectName("MainWindow") + self.resize(480, 120) + self.setWindowFlags(QtCore.Qt.WindowStaysOnTopHint) + + central_widget = QWidget(self) + central_widget.setObjectName("central_widget") + + self.grid_layout = QGridLayout(central_widget) + self.grid_layout.setContentsMargins(10, 10, 10, 10) + self.grid_layout.setObjectName("grid_layout") + + # button to update the trajectory's start and end index + self.update_button = QPushButton("update slider") + self.update_button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) + self.update_button.clicked.connect(self.onUpdateButton) + + # button to reset the trajectory's start and end index + self.reset_button = QPushButton("reset") + self.reset_button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) + self.reset_button.clicked.connect(self.onResetButton) + + # button to save map + self.save_map_button = QPushButton("save map") + self.save_map_button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) + + # slide of the trajectory's start and end index + self.traj_start_index_slider = QSlider(QtCore.Qt.Horizontal) + self.traj_end_index_slider = QSlider(QtCore.Qt.Horizontal) + self.min_traj_start_index = 0 + self.max_traj_end_index = None + + # set layout + self.grid_layout.addWidget(self.update_button, 1, 0, 1, -1) + self.grid_layout.addWidget(self.reset_button, 2, 0, 1, -1) + self.grid_layout.addWidget(self.save_map_button, 3, 0, 1, -1) + self.grid_layout.addWidget(self.traj_start_index_slider, 4, 0, 1, -1) + self.grid_layout.addWidget(self.traj_end_index_slider, 5, 0, 1, -1) + self.setCentralWidget(central_widget) + + def initWithEndIndex(self, max_traj_end_index): + self.max_traj_end_index = max_traj_end_index + + # initialize slider + self.displayed_min_traj_start_index = self.min_traj_start_index + self.displayed_max_traj_end_index = self.max_traj_end_index + self.initializeSlider() + + def initializeSlider(self, move_value_to_end=True): + self.traj_start_index_slider.setMinimum(0) + self.traj_end_index_slider.setMinimum(0) + self.traj_start_index_slider.setMaximum( + self.displayed_max_traj_end_index - self.displayed_min_traj_start_index + ) + self.traj_end_index_slider.setMaximum( + self.displayed_max_traj_end_index - self.displayed_min_traj_start_index + ) + + if move_value_to_end: + self.traj_start_index_slider.setValue(0) + self.traj_end_index_slider.setValue(self.traj_end_index_slider.maximum()) + + def onResetButton(self, event): + current_traj_start_index = self.displayed_min_traj_start_index + current_traj_end_index = self.displayed_max_traj_end_index + + self.displayed_min_traj_start_index = self.min_traj_start_index + self.displayed_max_traj_end_index = self.max_traj_end_index + + self.initializeSlider(False) + self.traj_start_index_slider.setValue(current_traj_start_index) + if ( + current_traj_start_index == self.min_traj_start_index + and current_traj_end_index == self.max_traj_end_index + ): + self.traj_end_index_slider.setValue(self.displayed_max_traj_end_index) + else: + self.traj_end_index_slider.setValue( + current_traj_start_index + self.traj_end_index_slider.value() + ) + + def onUpdateButton(self, event): + current_traj_start_index = self.getCurrentStartIndex() + current_traj_end_index = self.getCurrentEndIndex() + + self.displayed_min_traj_start_index = current_traj_start_index + self.displayed_max_traj_end_index = current_traj_end_index + + self.initializeSlider() + + def getCurrentStartIndex(self): + return self.displayed_min_traj_start_index + self.traj_start_index_slider.value() + + def getCurrentEndIndex(self): + return self.displayed_min_traj_start_index + self.traj_end_index_slider.value() + + +class CenterlineUpdaterHelper(Node): + def __init__(self): + super().__init__("centerline_updater_helper") + # Qt + self.widget = CenterlineUpdaterWidget() + self.widget.show() + self.widget.save_map_button.clicked.connect(self.onSaveMapButtonPushed) + self.widget.traj_start_index_slider.valueChanged.connect(self.onStartIndexChanged) + self.widget.traj_end_index_slider.valueChanged.connect(self.onEndIndexChanged) + + # ROS + self.pub_save_map = self.create_publisher(Bool, "~/save_map", 1) + self.pub_traj_start_index = self.create_publisher(Int32, "~/traj_start_index", 1) + self.pub_traj_end_index = self.create_publisher(Int32, "~/traj_end_index", 1) + + transient_local_qos = QoSProfile(depth=1, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL) + self.sub_whole_centerline = self.create_subscription( + Trajectory, + "/static_centerline_optimizer/output_whole_centerline", + self.onWholeCenterline, + transient_local_qos, + ) + + while self.widget.max_traj_end_index is None: + rclpy.spin_once(self, timeout_sec=0.01) + time.sleep(0.1) + + def onWholeCenterline(self, whole_centerline): + self.widget.initWithEndIndex(len(whole_centerline.points) - 1) + + def onSaveMapButtonPushed(self, event): + msg = Bool() + msg.data = True + self.pub_save_map.publish(msg) + + def onStartIndexChanged(self, event): + msg = Int32() + msg.data = self.widget.getCurrentStartIndex() + self.pub_traj_start_index.publish(msg) + + def onEndIndexChanged(self, event): + msg = Int32() + msg.data = self.widget.getCurrentEndIndex() + self.pub_traj_end_index.publish(msg) + + +def main(args=None): + app = QApplication(sys.argv) + + rclpy.init(args=args) + node = CenterlineUpdaterHelper() + + while True: + app.processEvents() + rclpy.spin_once(node, timeout_sec=0.01) + + +if __name__ == "__main__": + main() diff --git a/planning/static_centerline_optimizer/scripts/tmp/run.sh b/planning/static_centerline_optimizer/scripts/tmp/run.sh index 07857a9d923a1..9e475b9d8759b 100755 --- a/planning/static_centerline_optimizer/scripts/tmp/run.sh +++ b/planning/static_centerline_optimizer/scripts/tmp/run.sh @@ -1,3 +1,3 @@ #!/bin/bash -ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml run_background:=false lanelet2_input_file_path:="$HOME/AutonomousDrivingScenarios/map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus +ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index d98341ecb2e23..844352f577432 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -26,11 +26,14 @@ #include "static_centerline_optimizer/type_alias.hpp" #include "static_centerline_optimizer/utils.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" +#include "tier4_autoware_utils/ros/parameter.hpp" #include #include #include +#include "std_msgs/msg/bool.hpp" +#include "std_msgs/msg/int32.hpp" #include #include @@ -41,6 +44,7 @@ #include #include +#include #include #include #include @@ -202,6 +206,14 @@ std::vector check_lanelet_connection( return unconnected_lane_ids; } + +std_msgs::msg::Header createHeader(const rclcpp::Time & now) +{ + std_msgs::msg::Header header; + header.frame_id = "map"; + header.stamp = now; + return header; +} } // namespace StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( @@ -213,6 +225,8 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( pub_raw_path_with_lane_id_ = create_publisher("input_centerline", create_transient_local_qos()); pub_raw_path_ = create_publisher("debug/raw_centerline", create_transient_local_qos()); + pub_whole_optimized_centerline_ = + create_publisher("output_whole_centerline", create_transient_local_qos()); pub_optimized_centerline_ = create_publisher("output_centerline", create_transient_local_qos()); @@ -220,6 +234,53 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( pub_debug_unsafe_footprints_ = create_publisher("debug/unsafe_footprints", create_transient_local_qos()); + // subscribers + sub_traj_start_index_ = create_subscription( + "/centerline_updater_helper/traj_start_index", rclcpp::QoS{1}, + [this](const std_msgs::msg::Int32 & msg) { + if (!meta_data_to_save_map_ || traj_end_index_ + 1 < msg.data) { + return; + } + traj_start_index_ = msg.data; + + const auto & d = meta_data_to_save_map_; + const auto selected_optimized_traj_points = std::vector( + d->optimized_traj_points.begin() + traj_start_index_, + d->optimized_traj_points.begin() + traj_end_index_ + 1); + + pub_optimized_centerline_->publish(motion_utils::convertToTrajectory( + selected_optimized_traj_points, createHeader(this->now()))); + }); + sub_traj_end_index_ = create_subscription( + "/centerline_updater_helper/traj_end_index", rclcpp::QoS{1}, + [this](const std_msgs::msg::Int32 & msg) { + if (!meta_data_to_save_map_ || msg.data + 1 < traj_start_index_) { + return; + } + traj_end_index_ = msg.data; + + const auto & d = meta_data_to_save_map_; + const auto selected_optimized_traj_points = std::vector( + d->optimized_traj_points.begin() + traj_start_index_, + d->optimized_traj_points.begin() + traj_end_index_ + 1); + + pub_optimized_centerline_->publish(motion_utils::convertToTrajectory( + selected_optimized_traj_points, createHeader(this->now()))); + }); + sub_save_map_ = create_subscription( + "/centerline_updater_helper/save_map", rclcpp::QoS{1}, [this](const std_msgs::msg::Bool & msg) { + const auto lanelet2_output_file_path = + tier4_autoware_utils::getOrDeclareParameter( + *this, "lanelet2_output_file_path"); + if (!meta_data_to_save_map_ || msg.data) { + const auto & d = meta_data_to_save_map_; + const auto selected_optimized_traj_points = std::vector( + d->optimized_traj_points.begin() + traj_start_index_, + d->optimized_traj_points.begin() + traj_end_index_ + 1); + save_map(lanelet2_output_file_path, d->route_lane_ids, selected_optimized_traj_points); + } + }); + // services callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); srv_load_map_ = create_service( @@ -258,7 +319,11 @@ void StaticCenterlineOptimizerNode::run() load_map(lanelet2_input_file_path); const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); const auto optimized_traj_points = plan_path(route_lane_ids); + traj_start_index_ = 0; + traj_end_index_ = optimized_traj_points.size() - 1; save_map(lanelet2_output_file_path, route_lane_ids, optimized_traj_points); + + meta_data_to_save_map_ = MetaDataToSaveMap{optimized_traj_points, route_lane_ids}; } void StaticCenterlineOptimizerNode::load_map(const std::string & lanelet2_input_file_path) @@ -450,6 +515,8 @@ std::vector StaticCenterlineOptimizerNode::plan_path( // smooth trajectory and road collision avoidance const auto optimized_traj_points = optimize_trajectory(raw_path); + pub_whole_optimized_centerline_->publish( + motion_utils::convertToTrajectory(optimized_traj_points, raw_path.header)); pub_optimized_centerline_->publish( motion_utils::convertToTrajectory(optimized_traj_points, raw_path.header)); RCLCPP_INFO( From 8948859a107c7788765f3808d49d4600a3858df1 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 2 Apr 2024 16:57:41 +0900 Subject: [PATCH 12/57] feat(multi_object_tracker): debug timer to work with reduced replay rate recomputation (#6706) * fix: mot debug timer, full set of timings Signed-off-by: Taekjin LEE * fix: reduce timers, rename topics Signed-off-by: Taekjin LEE * fix: separate debugger Signed-off-by: Taekjin LEE * chore: fix comments Signed-off-by: Taekjin LEE * fix: fix stamp initialization, remove unused function Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../multi_object_tracker/CMakeLists.txt | 1 + .../include/multi_object_tracker/debugger.hpp | 68 +++++++++ .../multi_object_tracker_core.hpp | 42 +----- .../multi_object_tracker/src/debugger.cpp | 138 ++++++++++++++++++ .../src/multi_object_tracker_core.cpp | 111 +------------- 5 files changed, 210 insertions(+), 150 deletions(-) create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp create mode 100644 perception/multi_object_tracker/src/debugger.cpp diff --git a/perception/multi_object_tracker/CMakeLists.txt b/perception/multi_object_tracker/CMakeLists.txt index fe90be8c583c2..8d835fec20a9b 100644 --- a/perception/multi_object_tracker/CMakeLists.txt +++ b/perception/multi_object_tracker/CMakeLists.txt @@ -22,6 +22,7 @@ include_directories( # Generate exe file set(MULTI_OBJECT_TRACKER_SRC src/multi_object_tracker_core.cpp + src/debugger.cpp src/data_association/data_association.cpp src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp src/tracker/motion_model/motion_model_base.cpp diff --git a/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp b/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp new file mode 100644 index 0000000000000..ca1b20d26c25d --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp @@ -0,0 +1,68 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// + +#ifndef MULTI_OBJECT_TRACKER__DEBUGGER_HPP_ +#define MULTI_OBJECT_TRACKER__DEBUGGER_HPP_ + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +/** + * @brief Debugger class for multi object tracker + * @details This class is used to publish debug information of multi object tracker + */ +class TrackerDebugger +{ +public: + explicit TrackerDebugger(rclcpp::Node & node); + void publishTentativeObjects( + const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const; + void startMeasurementTime( + const rclcpp::Time & now, const rclcpp::Time & measurement_header_stamp); + void endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time); + void setupDiagnostics(); + void checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat); + struct DEBUG_SETTINGS + { + bool publish_processing_time; + bool publish_tentative_objects; + double diagnostics_warn_delay; + double diagnostics_error_delay; + } debug_settings_; + double pipeline_latency_ms_ = 0.0; + diagnostic_updater::Updater diagnostic_updater_; + +private: + void loadParameters(); + rclcpp::Node & node_; + rclcpp::Publisher::SharedPtr + debug_tentative_objects_pub_; + std::unique_ptr processing_time_publisher_; + rclcpp::Time last_input_stamp_; + rclcpp::Time stamp_process_start_; + rclcpp::Time stamp_publish_output_; +}; + +#endif // MULTI_OBJECT_TRACKER__DEBUGGER_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp index ca59f994a3b0e..94cc7185bd518 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp @@ -20,12 +20,10 @@ #define MULTI_OBJECT_TRACKER__MULTI_OBJECT_TRACKER_CORE_HPP_ #include "multi_object_tracker/data_association/data_association.hpp" +#include "multi_object_tracker/debugger.hpp" #include "multi_object_tracker/tracker/model/tracker_base.hpp" #include -#include -#include -#include #include #include @@ -41,9 +39,6 @@ #include #endif -#include -#include - #include #include @@ -53,41 +48,6 @@ #include #include -/** - * @brief Debugger class for multi object tracker - * @details This class is used to publish debug information of multi object tracker - */ -class TrackerDebugger -{ -public: - explicit TrackerDebugger(rclcpp::Node & node); - void publishProcessingTime(); - void publishTentativeObjects( - const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const; - void startStopWatch(); - void startMeasurementTime(const rclcpp::Time & measurement_header_stamp); - void setupDiagnostics(); - void checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat); - struct DEBUG_SETTINGS - { - bool publish_processing_time; - bool publish_tentative_objects; - double diagnostics_warn_delay; - double diagnostics_error_delay; - } debug_settings_; - double elapsed_time_from_sensor_input_ = 0.0; - diagnostic_updater::Updater diagnostic_updater_; - -private: - void loadParameters(); - rclcpp::Node & node_; - rclcpp::Publisher::SharedPtr - debug_tentative_objects_pub_; - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr processing_time_publisher_; - rclcpp::Time last_input_stamp_; -}; - class MultiObjectTracker : public rclcpp::Node { public: diff --git a/perception/multi_object_tracker/src/debugger.cpp b/perception/multi_object_tracker/src/debugger.cpp new file mode 100644 index 0000000000000..e3fc58dd5d692 --- /dev/null +++ b/perception/multi_object_tracker/src/debugger.cpp @@ -0,0 +1,138 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// + +#include "multi_object_tracker/debugger.hpp" + +#include + +TrackerDebugger::TrackerDebugger(rclcpp::Node & node) +: diagnostic_updater_(&node), + node_(node), + last_input_stamp_(node.now()), + stamp_process_start_(node.now()), + stamp_publish_output_(node.now()) +{ + // declare debug parameters to decide whether to publish debug topics + loadParameters(); + // initialize debug publishers + if (debug_settings_.publish_processing_time) { + processing_time_publisher_ = + std::make_unique(&node_, "multi_object_tracker"); + } + + if (debug_settings_.publish_tentative_objects) { + debug_tentative_objects_pub_ = + node_.create_publisher( + "debug/tentative_objects", rclcpp::QoS{1}); + } + + // initialize stop watch and diagnostics + setupDiagnostics(); +} + +void TrackerDebugger::setupDiagnostics() +{ + diagnostic_updater_.setHardwareID(node_.get_name()); + diagnostic_updater_.add( + "Perception delay check from original header stamp", this, &TrackerDebugger::checkDelay); + diagnostic_updater_.setPeriod(0.1); +} + +void TrackerDebugger::loadParameters() +{ + try { + debug_settings_.publish_processing_time = + node_.declare_parameter("publish_processing_time"); + debug_settings_.publish_tentative_objects = + node_.declare_parameter("publish_tentative_objects"); + debug_settings_.diagnostics_warn_delay = + node_.declare_parameter("diagnostics_warn_delay"); + debug_settings_.diagnostics_error_delay = + node_.declare_parameter("diagnostics_error_delay"); + } catch (const std::exception & e) { + RCLCPP_WARN(node_.get_logger(), "Failed to declare parameter: %s", e.what()); + debug_settings_.publish_processing_time = false; + debug_settings_.publish_tentative_objects = false; + debug_settings_.diagnostics_warn_delay = 0.5; + debug_settings_.diagnostics_error_delay = 1.0; + } +} + +void TrackerDebugger::checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat) +{ + const double delay = pipeline_latency_ms_; // [s] + + if (delay == 0.0) { + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is not calculated."); + } else if (delay < debug_settings_.diagnostics_warn_delay) { + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is acceptable"); + } else if (delay < debug_settings_.diagnostics_error_delay) { + stat.summary( + diagnostic_msgs::msg::DiagnosticStatus::WARN, "Detection delay is over warn threshold."); + } else { + stat.summary( + diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Detection delay is over error threshold."); + } + + stat.add("Detection delay", delay); +} + +void TrackerDebugger::publishTentativeObjects( + const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const +{ + if (debug_settings_.publish_tentative_objects) { + debug_tentative_objects_pub_->publish(tentative_objects); + } +} + +void TrackerDebugger::startMeasurementTime( + const rclcpp::Time & now, const rclcpp::Time & measurement_header_stamp) +{ + last_input_stamp_ = measurement_header_stamp; + stamp_process_start_ = now; + if (debug_settings_.publish_processing_time) { + double input_latency_ms = (now - last_input_stamp_).seconds() * 1e3; + processing_time_publisher_->publish( + "debug/input_latency_ms", input_latency_ms); + } +} + +void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time) +{ + const auto current_time = now; + // pipeline latency: time from sensor measurement to publish + pipeline_latency_ms_ = (current_time - last_input_stamp_).seconds() * 1e3; + if (debug_settings_.publish_processing_time) { + // processing time: time between input and publish + double processing_time_ms = (current_time - stamp_process_start_).seconds() * 1e3; + // cycle time: time between two consecutive publish + double cyclic_time_ms = (current_time - stamp_publish_output_).seconds() * 1e3; + // measurement to tracked-object time: time from the sensor measurement to the publishing object + // time If there is not latency compensation, this value is zero + double measurement_to_object_ms = (object_time - last_input_stamp_).seconds() * 1e3; + + // starting from the measurement time + processing_time_publisher_->publish( + "debug/pipeline_latency_ms", pipeline_latency_ms_); + processing_time_publisher_->publish( + "debug/cyclic_time_ms", cyclic_time_ms); + processing_time_publisher_->publish( + "debug/processing_time_ms", processing_time_ms); + processing_time_publisher_->publish( + "debug/meas_to_tracked_object_ms", measurement_to_object_ms); + } + stamp_publish_output_ = current_time; +} diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index fa609ed9ff9c7..b8e19d4ca2df4 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -66,113 +66,6 @@ boost::optional getTransformAnonymous( } // namespace -TrackerDebugger::TrackerDebugger(rclcpp::Node & node) -: diagnostic_updater_(&node), node_(node), last_input_stamp_(node.now()) -{ - // declare debug parameters to decide whether to publish debug topics - loadParameters(); - // initialize debug publishers - stop_watch_ptr_ = std::make_unique>(); - if (debug_settings_.publish_processing_time) { - processing_time_publisher_ = - std::make_unique(&node_, "multi_object_tracker"); - } - - if (debug_settings_.publish_tentative_objects) { - debug_tentative_objects_pub_ = - node_.create_publisher( - "debug/tentative_objects", rclcpp::QoS{1}); - } - - // initialize stop watch and diagnostics - startStopWatch(); - setupDiagnostics(); -} - -void TrackerDebugger::setupDiagnostics() -{ - diagnostic_updater_.setHardwareID(node_.get_name()); - diagnostic_updater_.add( - "Perception delay check from original header stamp", this, &TrackerDebugger::checkDelay); - diagnostic_updater_.setPeriod(0.1); -} - -void TrackerDebugger::loadParameters() -{ - try { - debug_settings_.publish_processing_time = - node_.declare_parameter("publish_processing_time"); - debug_settings_.publish_tentative_objects = - node_.declare_parameter("publish_tentative_objects"); - debug_settings_.diagnostics_warn_delay = - node_.declare_parameter("diagnostics_warn_delay"); - debug_settings_.diagnostics_error_delay = - node_.declare_parameter("diagnostics_error_delay"); - } catch (const std::exception & e) { - RCLCPP_WARN(node_.get_logger(), "Failed to declare parameter: %s", e.what()); - debug_settings_.publish_processing_time = false; - debug_settings_.publish_tentative_objects = false; - debug_settings_.diagnostics_warn_delay = 0.5; - debug_settings_.diagnostics_error_delay = 1.0; - } -} - -void TrackerDebugger::checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat) -{ - const double delay = elapsed_time_from_sensor_input_; // [s] - - if (delay == 0.0) { - stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is not calculated."); - } else if (delay < debug_settings_.diagnostics_warn_delay) { - stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is acceptable"); - } else if (delay < debug_settings_.diagnostics_error_delay) { - stat.summary( - diagnostic_msgs::msg::DiagnosticStatus::WARN, "Detection delay is over warn threshold."); - } else { - stat.summary( - diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Detection delay is over error threshold."); - } - - stat.add("Detection delay", delay); -} - -void TrackerDebugger::publishProcessingTime() -{ - const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); - const auto current_time = node_.now(); - elapsed_time_from_sensor_input_ = (current_time - last_input_stamp_).seconds(); - if (debug_settings_.publish_processing_time) { - processing_time_publisher_->publish( - "debug/cyclic_time_ms", cyclic_time_ms); - processing_time_publisher_->publish( - "debug/processing_time_ms", processing_time_ms); - processing_time_publisher_->publish( - "debug/pipeline_latency_ms", elapsed_time_from_sensor_input_ * 1e3); - } -} - -void TrackerDebugger::publishTentativeObjects( - const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const -{ - if (debug_settings_.publish_tentative_objects) { - debug_tentative_objects_pub_->publish(tentative_objects); - } -} - -void TrackerDebugger::startStopWatch() -{ - stop_watch_ptr_->tic("cyclic_time"); - stop_watch_ptr_->tic("processing_time"); -} - -void TrackerDebugger::startMeasurementTime(const rclcpp::Time & measurement_header_stamp) -{ - last_input_stamp_ = measurement_header_stamp; - // start measuring processing time - stop_watch_ptr_->toc("processing_time", true); -} - MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) : rclcpp::Node("multi_object_tracker", node_options), tf_buffer_(this->get_clock()), @@ -243,7 +136,7 @@ void MultiObjectTracker::onMeasurement( const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg) { /* keep the latest input stamp and check transform*/ - debugger_->startMeasurementTime(rclcpp::Time(input_objects_msg->header.stamp)); + debugger_->startMeasurementTime(this->now(), rclcpp::Time(input_objects_msg->header.stamp)); const auto self_transform = getTransformAnonymous( tf_buffer_, "base_link", world_frame_id_, input_objects_msg->header.stamp); if (!self_transform) { @@ -472,7 +365,7 @@ void MultiObjectTracker::publish(const rclcpp::Time & time) const published_time_publisher_->publish_if_subscribed(tracked_objects_pub_, output_msg.header.stamp); // Debugger Publish if enabled - debugger_->publishProcessingTime(); + debugger_->endPublishTime(this->now(), time); debugger_->publishTentativeObjects(tentative_objects_msg); } From 1aa5bb91240f52ffee9315680a19ea94e34f9dbf Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 2 Apr 2024 18:30:45 +0900 Subject: [PATCH 13/57] fix(object_recognition_utils): check polygon area on iou calculation (#6701) * feat(object_recognition_utils): check input polygon on IoU calculations Signed-off-by: Taekjin LEE * fix: MIN_AREA close to the epsilon of float 1e-6 Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../object_recognition_utils/matching.hpp | 20 ++++++++++++++----- 1 file changed, 15 insertions(+), 5 deletions(-) diff --git a/common/object_recognition_utils/include/object_recognition_utils/matching.hpp b/common/object_recognition_utils/include/object_recognition_utils/matching.hpp index 5e8b6a3d49890..e9b924023f62e 100644 --- a/common/object_recognition_utils/include/object_recognition_utils/matching.hpp +++ b/common/object_recognition_utils/include/object_recognition_utils/matching.hpp @@ -29,6 +29,8 @@ namespace object_recognition_utils { using tier4_autoware_utils::Polygon2d; +// minimum area to avoid division by zero +static const double MIN_AREA = 1e-6; inline double getConvexShapeArea(const Polygon2d & source_polygon, const Polygon2d & target_polygon) { @@ -66,10 +68,12 @@ template double get2dIoU(const T1 source_object, const T2 target_object, const double min_union_area = 0.01) { const auto source_polygon = tier4_autoware_utils::toPolygon2d(source_object); + if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0; const auto target_polygon = tier4_autoware_utils::toPolygon2d(target_object); + if (boost::geometry::area(target_polygon) < MIN_AREA) return 0.0; const double intersection_area = getIntersectionArea(source_polygon, target_polygon); - if (intersection_area == 0.0) return 0.0; + if (intersection_area < MIN_AREA) return 0.0; const double union_area = getUnionArea(source_polygon, target_polygon); const double iou = @@ -81,7 +85,9 @@ template double get2dGeneralizedIoU(const T1 & source_object, const T2 & target_object) { const auto source_polygon = tier4_autoware_utils::toPolygon2d(source_object); + if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0; const auto target_polygon = tier4_autoware_utils::toPolygon2d(target_object); + if (boost::geometry::area(target_polygon) < MIN_AREA) return 0.0; const double intersection_area = getIntersectionArea(source_polygon, target_polygon); const double union_area = getUnionArea(source_polygon, target_polygon); @@ -95,11 +101,13 @@ template double get2dPrecision(const T1 source_object, const T2 target_object) { const auto source_polygon = tier4_autoware_utils::toPolygon2d(source_object); + const double source_area = boost::geometry::area(source_polygon); + if (source_area < MIN_AREA) return 0.0; const auto target_polygon = tier4_autoware_utils::toPolygon2d(target_object); + if (boost::geometry::area(target_polygon) < MIN_AREA) return 0.0; const double intersection_area = getIntersectionArea(source_polygon, target_polygon); - if (intersection_area == 0.0) return 0.0; - const double source_area = boost::geometry::area(source_polygon); + if (intersection_area < MIN_AREA) return 0.0; return std::min(1.0, intersection_area / source_area); } @@ -108,11 +116,13 @@ template double get2dRecall(const T1 source_object, const T2 target_object) { const auto source_polygon = tier4_autoware_utils::toPolygon2d(source_object); + if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0; const auto target_polygon = tier4_autoware_utils::toPolygon2d(target_object); + const double target_area = boost::geometry::area(target_polygon); + if (target_area < MIN_AREA) return 0.0; const double intersection_area = getIntersectionArea(source_polygon, target_polygon); - if (intersection_area == 0.0) return 0.0; - const double target_area = boost::geometry::area(target_polygon); + if (intersection_area < MIN_AREA) return 0.0; return std::min(1.0, intersection_area / target_area); } From 5617f74ed9cbe86b2d06421a72915cd383630617 Mon Sep 17 00:00:00 2001 From: beyzanurkaya <32412808+beyzanurkaya@users.noreply.github.com> Date: Tue, 2 Apr 2024 15:27:51 +0300 Subject: [PATCH 14/57] fix(predicted_path_checker): check if trajectory size (#6730) check trajectory size Signed-off-by: beyza Co-authored-by: beyza --- .../predicted_path_checker_node.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp index 0cf2548d69746..bba069442bee7 100644 --- a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp +++ b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp @@ -537,6 +537,10 @@ void PredictedPathCheckerNode::filterObstacles( const Pose & ego_pose, const TrajectoryPoints & traj, const double dist_threshold, const bool use_prediction, PredictedObjects & filtered_objects) { + if (traj.size() < 2) { + RCLCPP_ERROR(rclcpp::get_logger("predicted_path_checker"), "Trajectory size is less than 2."); + return; + } filtered_objects.header.frame_id = object_ptr_.get()->header.frame_id; filtered_objects.header.stamp = this->now(); From f97cdc03ba8aa5d30fa3ebc9edd5f75f15adc4d7 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 3 Apr 2024 00:57:07 +0900 Subject: [PATCH 15/57] fix(static_centerline_optimizer): fix latlon values of generated LL2 map (#6727) * fix(static_centerline_optimizer): fix lat/lon value of generated LL2 map Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../static_centerline_optimizer_node.hpp | 3 +++ planning/static_centerline_optimizer/package.xml | 2 ++ .../src/static_centerline_optimizer_node.cpp | 11 ++++++++--- 3 files changed, 13 insertions(+), 3 deletions(-) diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp index f25a6771aa0cb..3e6aafd3a9954 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp @@ -22,6 +22,8 @@ #include "static_centerline_optimizer/type_alias.hpp" #include "vehicle_info_util/vehicle_info_util.hpp" +#include + #include "std_msgs/msg/bool.hpp" #include "std_msgs/msg/int32.hpp" @@ -69,6 +71,7 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node lanelet::LaneletMapPtr original_map_ptr_{nullptr}; HADMapBin::ConstSharedPtr map_bin_ptr_{nullptr}; std::shared_ptr route_handler_ptr_{nullptr}; + std::unique_ptr map_projector_{nullptr}; int traj_start_index_{0}; int traj_end_index_{0}; diff --git a/planning/static_centerline_optimizer/package.xml b/planning/static_centerline_optimizer/package.xml index 363c88bebf0ea..eef133581622f 100644 --- a/planning/static_centerline_optimizer/package.xml +++ b/planning/static_centerline_optimizer/package.xml @@ -19,11 +19,13 @@ autoware_auto_perception_msgs autoware_auto_planning_msgs behavior_path_planner_common + geography_utils geometry_msgs global_parameter_loader interpolation lanelet2_extension map_loader + map_projection_loader mission_planner motion_utils obstacle_avoidance_planner diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index 844352f577432..ea7e1c302fd68 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -18,6 +18,7 @@ #include "lanelet2_extension/utility/query.hpp" #include "lanelet2_extension/utility/utilities.hpp" #include "map_loader/lanelet2_map_loader_node.hpp" +#include "map_projection_loader/load_info_from_lanelet2_map.hpp" #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" #include "obstacle_avoidance_planner/node.hpp" @@ -28,6 +29,7 @@ #include "tier4_autoware_utils/geometry/geometry.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" +#include #include #include #include @@ -331,14 +333,17 @@ void StaticCenterlineOptimizerNode::load_map(const std::string & lanelet2_input_ // load map by the map_loader package map_bin_ptr_ = [&]() -> HADMapBin::ConstSharedPtr { // load map - tier4_map_msgs::msg::MapProjectorInfo map_projector_info; - map_projector_info.projector_type = tier4_map_msgs::msg::MapProjectorInfo::MGRS; + const auto map_projector_info = load_info_from_lanelet2_map(lanelet2_input_file_path); const auto map_ptr = Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, map_projector_info); if (!map_ptr) { return nullptr; } + // NOTE: generate map projector for lanelet::write(). + // Without this, lat/lon of the generated LL2 map will be wrong. + map_projector_ = geography_utils::get_lanelet2_projector(map_projector_info); + // NOTE: The original map is stored here since the various ids in the lanelet map will change // after lanelet::utils::overwriteLaneletCenterline, and saving map will fail. original_map_ptr_ = @@ -750,7 +755,7 @@ void StaticCenterlineOptimizerNode::save_map( RCLCPP_INFO(get_logger(), "Updated centerline in map."); // save map with modified center line - lanelet::write(lanelet2_output_file_path, *original_map_ptr_); + lanelet::write(lanelet2_output_file_path, *original_map_ptr_, *map_projector_); RCLCPP_INFO(get_logger(), "Saved map."); } } // namespace static_centerline_optimizer From 5ff3b170e2152cf064c220957052c63de22667c1 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 3 Apr 2024 11:46:54 +0900 Subject: [PATCH 16/57] fix(lane_change): check prepare phase in intersection (#6561) * fix(lane_change): check prepare phase in intersection Signed-off-by: Muhammad Zulfaqar Azmi * Add new parameter, also create function Signed-off-by: Muhammad Zulfaqar Azmi * Rename parameters Signed-off-by: Muhammad Zulfaqar Azmi * fix spell check * fix config file Signed-off-by: Zulfaqar Azmi * call the function check_prepare_phase only once Signed-off-by: Muhammad Zulfaqar Azmi * add parameter description in README Signed-off-by: Muhammad Zulfaqar Azmi * minor refactoring Signed-off-by: Muhammad Zulfaqar Azmi * Doxygen description Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Zulfaqar Azmi --- .../README.md | 15 ++++--- .../config/lane_change.param.yaml | 4 +- .../scene.hpp | 2 + .../utils/data_structs.hpp | 3 +- .../utils/utils.hpp | 39 ++++++++++++++++- .../src/manager.cpp | 6 ++- .../src/scene.cpp | 43 ++++++++++++++++--- .../src/utils/utils.cpp | 35 +++++++++++++-- 8 files changed, 127 insertions(+), 20 deletions(-) diff --git a/planning/behavior_path_lane_change_module/README.md b/planning/behavior_path_lane_change_module/README.md index 874d542b445d3..17cdc58f5ad47 100644 --- a/planning/behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_lane_change_module/README.md @@ -551,13 +551,14 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi #### Additional parameters -| Name | Unit | Type | Description | Default value | -| :----------------------------------------- | ----- | ------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | -| `enable_collision_check_at_prepare_phase` | [-] | boolean | Perform collision check starting from prepare phase. If `false`, collision check only evaluated for lane changing phase. | false | -| `prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | -| `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module check objects on current lanes when performing collision assessment. | false | -| `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. when performing collision assessment | false | -| `use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | +| Name | Unit | Type | Description | Default value | +| :------------------------------------------------------- | ----- | ------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | +| `enable_collision_check_for_prepare_phase.general_lanes` | [-] | boolean | Perform collision check starting from the prepare phase for situations not explicitly covered by other settings (e.g., intersections). If `false`, collision check only evaluated for lane changing phase. | false | +| `enable_collision_check_for_prepare_phase.intersection` | [-] | boolean | Perform collision check starting from prepare phase when ego is in intersection. If `false`, collision check only evaluated for lane changing phase. | false | +| `prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | +| `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module check objects on current lanes when performing collision assessment. | false | +| `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. when performing collision assessment | false | +| `use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | #### safety constraints during lane change path is computed diff --git a/planning/behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_lane_change_module/config/lane_change.param.yaml index 74c6ad0893b23..039e8a31ed10f 100644 --- a/planning/behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_lane_change_module/config/lane_change.param.yaml @@ -89,7 +89,9 @@ stop_time: 3.0 # [s] # collision check - enable_prepare_segment_collision_check: true + enable_collision_check_for_prepare_phase: + general_lanes: false + intersection: true prepare_segment_ignore_object_velocity_thresh: 0.1 # [m/s] check_objects_on_current_lanes: true check_objects_on_other_lanes: true diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp index 3b8d2ad6e9931..0eec0ce75f622 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp @@ -174,6 +174,8 @@ class NormalLaneChange : public LaneChangeBase bool isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const; + bool check_prepare_phase() const; + double calcMaximumLaneChangeLength( const lanelet::ConstLanelet & current_terminal_lanelet, const double max_acc) const; diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp index e48f687a89035..0d77135fda242 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp @@ -112,7 +112,8 @@ struct LaneChangeParameters double max_longitudinal_acc{1.0}; // collision check - bool enable_prepare_segment_collision_check{true}; + bool enable_collision_check_for_prepare_phase_in_general_lanes{false}; + bool enable_collision_check_for_prepare_phase_in_intersection{true}; double prepare_segment_ignore_object_velocity_thresh{0.1}; bool check_objects_on_current_lanes{true}; bool check_objects_on_other_lanes{true}; diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp index 35cc02e867557..ff5d7bc0773fa 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp @@ -23,6 +23,7 @@ #include "rclcpp/logger.hpp" #include +#include #include #include @@ -31,6 +32,7 @@ #include +#include #include #include @@ -185,7 +187,7 @@ std::optional createPolygon( ExtendedPredictedObject transform( const PredictedObject & object, const BehaviorPathPlannerParameters & common_parameters, - const LaneChangeParameters & lane_change_parameters); + const LaneChangeParameters & lane_change_parameters, const bool check_at_prepare_phase); bool isCollidedPolygonsInLanelet( const std::vector & collided_polygons, const lanelet::ConstLanelets & lanes); @@ -220,6 +222,41 @@ lanelet::ConstLanelets generateExpandedLanelets( * @return rclcpp::Logger The logger instance configured for the specified lane change type. */ rclcpp::Logger getLogger(const std::string & type); + +/** + * @brief Computes the current footprint of the ego vehicle based on its pose and size. + * + * This function calculates the 2D polygon representing the current footprint of the ego vehicle. + * The footprint is determined by the vehicle's pose and its dimensions, including the distance + * from the base to the front and rear ends of the vehicle, as well as its width. + * + * @param ego_pose The current pose of the ego vehicle. + * @param ego_info The structural information of the ego vehicle, such as its maximum longitudinal + * offset, rear overhang, and width. + * + * @return Polygon2d A polygon representing the current 2D footprint of the ego vehicle. + */ +Polygon2d getEgoCurrentFootprint( + const Pose & ego_pose, const vehicle_info_util::VehicleInfo & ego_info); + +/** + * @brief Checks if the given polygon is within an intersection area. + * + * This function evaluates whether a specified polygon is located within the bounds of an + * intersection. It identifies the intersection area by checking the attributes of the provided + * lanelet. If the lanelet has an attribute indicating it is part of an intersection, the function + * then checks if the polygon is fully contained within this area. + * + * @param route_handler a shared pointer to the route_handler + * @param lanelet A lanelet to check against the + * intersection area. + * @param polygon The polygon to check for containment within the intersection area. + * + * @return bool True if the polygon is within the intersection area, false otherwise. + */ +bool isWithinIntersection( + const std::shared_ptr & route_handler, const lanelet::ConstLanelet & lanelet, + const Polygon2d & polygon); } // namespace behavior_path_planner::utils::lane_change namespace behavior_path_planner::utils::lane_change::debug diff --git a/planning/behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_lane_change_module/src/manager.cpp index 9f1c3c13bfadc..7045544df50aa 100644 --- a/planning/behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_lane_change_module/src/manager.cpp @@ -68,8 +68,10 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node) p.max_longitudinal_acc = getOrDeclareParameter(*node, parameter("max_longitudinal_acc")); // collision check - p.enable_prepare_segment_collision_check = - getOrDeclareParameter(*node, parameter("enable_prepare_segment_collision_check")); + p.enable_collision_check_for_prepare_phase_in_general_lanes = getOrDeclareParameter( + *node, parameter("enable_collision_check_for_prepare_phase.general_lanes")); + p.enable_collision_check_for_prepare_phase_in_intersection = getOrDeclareParameter( + *node, parameter("enable_collision_check_for_prepare_phase.intersection")); p.prepare_segment_ignore_object_velocity_thresh = getOrDeclareParameter( *node, parameter("prepare_segment_ignore_object_velocity_thresh")); p.check_objects_on_current_lanes = diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index 08034d43feb43..a6d21aede64b6 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -889,23 +889,27 @@ LaneChangeTargetObjects NormalLaneChange::getTargetObjects( target_objects.other_lane.reserve(target_obj_index.other_lane.size()); // objects in current lane + const auto is_check_prepare_phase = check_prepare_phase(); for (const auto & obj_idx : target_obj_index.current_lane) { const auto extended_object = utils::lane_change::transform( - objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_); + objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_, + is_check_prepare_phase); target_objects.current_lane.push_back(extended_object); } // objects in target lane for (const auto & obj_idx : target_obj_index.target_lane) { const auto extended_object = utils::lane_change::transform( - objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_); + objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_, + is_check_prepare_phase); target_objects.target_lane.push_back(extended_object); } // objects in other lane for (const auto & obj_idx : target_obj_index.other_lane) { const auto extended_object = utils::lane_change::transform( - objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_); + objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_, + is_check_prepare_phase); target_objects.other_lane.push_back(extended_object); } @@ -969,8 +973,8 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject( const auto obj_velocity_norm = std::hypot( object.kinematics.initial_twist_with_covariance.twist.linear.x, object.kinematics.initial_twist_with_covariance.twist.linear.y); - const auto extended_object = - utils::lane_change::transform(object, common_parameters, *lane_change_parameters_); + const auto extended_object = utils::lane_change::transform( + object, common_parameters, *lane_change_parameters_, check_prepare_phase()); const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object); @@ -2113,4 +2117,33 @@ void NormalLaneChange::updateStopTime() stop_watch_.tic("stop_time"); } +bool NormalLaneChange::check_prepare_phase() const +{ + const auto & route_handler = getRouteHandler(); + const auto & vehicle_info = getCommonParam().vehicle_info; + + const auto check_in_general_lanes = + lane_change_parameters_->enable_collision_check_for_prepare_phase_in_general_lanes; + + lanelet::ConstLanelet current_lane; + if (!route_handler->getClosestLaneletWithinRoute(getEgoPose(), ¤t_lane)) { + RCLCPP_DEBUG( + logger_, "Unable to get current lane. Default to %s.", + (check_in_general_lanes ? "true" : "false")); + return check_in_general_lanes; + } + + const auto ego_footprint = utils::lane_change::getEgoCurrentFootprint(getEgoPose(), vehicle_info); + + const auto check_in_intersection = std::invoke([&]() { + if (!lane_change_parameters_->enable_collision_check_for_prepare_phase_in_intersection) { + return false; + } + + return utils::lane_change::isWithinIntersection(route_handler, current_lane, ego_footprint); + }); + + return check_in_intersection || check_in_general_lanes; +} + } // namespace behavior_path_planner diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index bae733610905b..f112ab103b167 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -31,7 +31,11 @@ #include #include #include +#include #include +#include + +#include #include #include @@ -1086,7 +1090,7 @@ std::optional createPolygon( ExtendedPredictedObject transform( const PredictedObject & object, [[maybe_unused]] const BehaviorPathPlannerParameters & common_parameters, - const LaneChangeParameters & lane_change_parameters) + const LaneChangeParameters & lane_change_parameters, const bool check_at_prepare_phase) { ExtendedPredictedObject extended_object; extended_object.uuid = object.object_id; @@ -1096,8 +1100,6 @@ ExtendedPredictedObject transform( extended_object.shape = object.shape; const auto & time_resolution = lane_change_parameters.prediction_time_resolution; - const auto & check_at_prepare_phase = - lane_change_parameters.enable_prepare_segment_collision_check; const auto & prepare_duration = lane_change_parameters.lane_change_prepare_duration; const auto & velocity_threshold = lane_change_parameters.prepare_segment_ignore_object_velocity_thresh; @@ -1155,6 +1157,32 @@ rclcpp::Logger getLogger(const std::string & type) { return rclcpp::get_logger("lane_change").get_child(type); } + +Polygon2d getEgoCurrentFootprint( + const Pose & ego_pose, const vehicle_info_util::VehicleInfo & ego_info) +{ + const auto base_to_front = ego_info.max_longitudinal_offset_m; + const auto base_to_rear = ego_info.rear_overhang_m; + const auto width = ego_info.vehicle_width_m; + + return tier4_autoware_utils::toFootprint(ego_pose, base_to_front, base_to_rear, width); +} + +bool isWithinIntersection( + const std::shared_ptr & route_handler, const lanelet::ConstLanelet & lanelet, + const Polygon2d & polygon) +{ + const std::string id = lanelet.attributeOr("intersection_area", "else"); + if (id == "else") { + return false; + } + + const auto lanelet_polygon = + route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(id.c_str())); + + return boost::geometry::within( + polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet_polygon.basicPolygon()))); +} } // namespace behavior_path_planner::utils::lane_change namespace behavior_path_planner::utils::lane_change::debug @@ -1194,4 +1222,5 @@ geometry_msgs::msg::Polygon createExecutionArea( return polygon; } + } // namespace behavior_path_planner::utils::lane_change::debug From 31b5a4ca4e9d4bfc0abf5a624f63bf0d92cf76ab Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 3 Apr 2024 12:33:41 +0900 Subject: [PATCH 17/57] fix(lane_change): fix terminal path not working in some case (#6722) Signed-off-by: Zulfaqar Azmi --- planning/behavior_path_lane_change_module/src/utils/utils.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index f112ab103b167..0b4893f94e071 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -439,7 +439,8 @@ PathWithLaneId getReferencePathFromTargetLane( .get_child("getReferencePathFromTargetLane"), "start: %f, end: %f", s_start, s_end); - if (s_end - s_start < lane_changing_length) { + constexpr double epsilon = 1e-4; + if (s_end - s_start + epsilon < lane_changing_length) { return PathWithLaneId(); } From 250f0818f8694bb94d4c5613602f9c52996b6848 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 3 Apr 2024 13:06:05 +0900 Subject: [PATCH 18/57] chore(goal_planner): delete unnecessary comments (#6729) chore(goal_planner): delete comments Signed-off-by: kosuke55 --- .../src/goal_planner_module.cpp | 28 ------------------- 1 file changed, 28 deletions(-) diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index 7310e93dda4bb..a890cfc21ed13 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -1640,34 +1640,6 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() ignore_signal_ = update_ignore_signal(closest_lanelet.id(), is_ignore); return new_signal; - // // calc TurnIndicatorsCommand - // { - // const double distance_to_end = - // calcSignedArcLength(full_path.points, current_pose.position, end_pose.position); - // const bool is_before_end_pose = distance_to_end >= 0.0; - // if (is_before_end_pose) { - // if (left_side_parking_) { - // turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT; - // } else { - // turn_signal.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT; - // } - // } else { - // turn_signal.turn_signal.command = TurnIndicatorsCommand::NO_COMMAND; - // } - // } - - // // calc desired/required start/end point - // { - // // ego decelerates so that current pose is the point `turn_light_on_threshold_time` seconds - // // before starting pull_over - // turn_signal.desired_start_point = - // last_approval_data_ && hasDecidedPath() ? last_approval_data_->pose : current_pose; - // turn_signal.desired_end_point = end_pose; - // turn_signal.required_start_point = start_pose; - // turn_signal.required_end_point = end_pose; - // } - - // return turn_signal; } bool GoalPlannerModule::checkOccupancyGridCollision(const PathWithLaneId & path) const From dfec62ac277f893fd6276e3c6ffd9c7d4f475225 Mon Sep 17 00:00:00 2001 From: cyn-liu <104069308+cyn-liu@users.noreply.github.com> Date: Wed, 3 Apr 2024 15:44:15 +0800 Subject: [PATCH 19/57] feat(global_parameter_loader): add gtest to global parameter loader (#5021) * add remote * feat(global_parameter_loader): add gtest of global-parameter-loader Signed-off-by: Cynthia Liu * style(pre-commit): autofix --------- Signed-off-by: Cynthia Liu Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- build_depends.repos | 5 +++ common/global_parameter_loader/CMakeLists.txt | 5 +++ common/global_parameter_loader/package.xml | 4 +- .../test/test_global_params_launch.cpp | 44 +++++++++++++++++++ 4 files changed, 57 insertions(+), 1 deletion(-) create mode 100644 common/global_parameter_loader/test/test_global_params_launch.cpp diff --git a/build_depends.repos b/build_depends.repos index f7b3f12484015..5a12a67dbd346 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -41,3 +41,8 @@ repositories: type: git url: https://github.com/MORAI-Autonomous/MORAI-ROS2_morai_msgs.git version: main + #vehicle + vehicle/sample_vehicle_launch: + type: git + url: https://github.com/autowarefoundation/sample_vehicle_launch.git + version: main diff --git a/common/global_parameter_loader/CMakeLists.txt b/common/global_parameter_loader/CMakeLists.txt index e67ae1a5c06fc..eaca44c515452 100644 --- a/common/global_parameter_loader/CMakeLists.txt +++ b/common/global_parameter_loader/CMakeLists.txt @@ -4,6 +4,11 @@ project(global_parameter_loader) find_package(autoware_cmake REQUIRED) autoware_package() +if(BUILD_TESTING) + file(GLOB_RECURSE test_files test/*.cpp) + ament_add_ros_isolated_gtest(test_global_params_launch ${test_files}) +endif() + ament_auto_package( INSTALL_TO_SHARE launch diff --git a/common/global_parameter_loader/package.xml b/common/global_parameter_loader/package.xml index 4c2568b9aec98..78d08e4038250 100644 --- a/common/global_parameter_loader/package.xml +++ b/common/global_parameter_loader/package.xml @@ -10,8 +10,10 @@ ament_cmake_auto autoware_cmake - vehicle_info_util + sample_vehicle_description + vehicle_info_util + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/global_parameter_loader/test/test_global_params_launch.cpp b/common/global_parameter_loader/test/test_global_params_launch.cpp new file mode 100644 index 0000000000000..2b33a695253ff --- /dev/null +++ b/common/global_parameter_loader/test/test_global_params_launch.cpp @@ -0,0 +1,44 @@ +// Copyright 2023 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include +#include + +TEST(TestLaunchFile, test_launch_file) +{ + // Define the path of Python launch file + std::string global_params_launch_path = "global_params.launch.py"; + + // Define the parameters you want to pass to the launch file + std::string use_sim_time_param = "false"; + std::string vehicle_model_param = "sample_vehicle"; + // Construct the command to run the Python launch script with parameters + std::string command = "ros2 launch global_parameter_loader " + global_params_launch_path + + " use_sim_time:=" + use_sim_time_param + + " vehicle_model:=" + vehicle_model_param; + + // Use the system() function to execute the command + int result = std::system(command.c_str()); + // Check the result of running the launch file + EXPECT_EQ(result, 0); +} + +int main(int argc, char * argv[]) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} From 1ae71985ffec3db97b83e1e9d5753c27d83d40b1 Mon Sep 17 00:00:00 2001 From: Berkay Karaman Date: Wed, 3 Apr 2024 13:38:14 +0300 Subject: [PATCH 20/57] feat(time_synchronizer_nodelet): set input_offsets zero if it was not defined (#6664) Signed-off-by: Berkay Karaman --- .../src/time_synchronizer/time_synchronizer_nodelet.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp b/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp index 7aae6c937f4a9..12b034043894e 100644 --- a/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp @@ -83,7 +83,12 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent( timeout_sec_ = static_cast(declare_parameter("timeout_sec", 0.1)); input_offset_ = declare_parameter("input_offset", std::vector{}); - if (!input_offset_.empty() && input_topics_.size() != input_offset_.size()) { + + // If input_offset_ is not defined, set all offsets to 0 + if (input_offset_.empty()) { + input_offset_.resize(input_topics_.size(), 0.0); + RCLCPP_INFO(get_logger(), "Input offset is not defined. Set all offsets to 0.0."); + } else if (input_topics_.size() != input_offset_.size()) { RCLCPP_ERROR(get_logger(), "The number of topics does not match the number of offsets."); return; } From d4ec8d3b3501c66902f9e93c7f92e83b9f80c61f Mon Sep 17 00:00:00 2001 From: oguzkaganozt Date: Wed, 3 Apr 2024 14:14:29 +0300 Subject: [PATCH 21/57] refactor(object_range_splitter): rework parameters (#6705) * rework parameters Signed-off-by: oguzkaganozt * . Signed-off-by: oguzkaganozt * . Signed-off-by: oguzkaganozt * style(pre-commit): autofix --------- Signed-off-by: oguzkaganozt Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- perception/object_range_splitter/README.md | 4 +-- .../schema/object_range_splitter.schema.json | 33 +++++++++++++++++++ 2 files changed, 34 insertions(+), 3 deletions(-) create mode 100644 perception/object_range_splitter/schema/object_range_splitter.schema.json diff --git a/perception/object_range_splitter/README.md b/perception/object_range_splitter/README.md index 89d266a666219..19c571962c0dc 100644 --- a/perception/object_range_splitter/README.md +++ b/perception/object_range_splitter/README.md @@ -43,9 +43,7 @@ Example: ## Parameters -| Name | Type | Description | -| ------------- | ----- | ---------------------------------------------------- | -| `split_range` | float | the distance boundary to divide detected objects [m] | +{{ json_to_markdown("perception/object_range_splitter/schema/object_range_splitter.schema.json") }} ## Assumptions / Known limits diff --git a/perception/object_range_splitter/schema/object_range_splitter.schema.json b/perception/object_range_splitter/schema/object_range_splitter.schema.json new file mode 100644 index 0000000000000..ed5ba3a96c18b --- /dev/null +++ b/perception/object_range_splitter/schema/object_range_splitter.schema.json @@ -0,0 +1,33 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for object_range_splitter", + "type": "object", + "definitions": { + "object_range_splitter": { + "type": "object", + "properties": { + "split_range": { + "type": "number", + "description": "object_range_splitter is a package to divide detected objects into two messages by the distance from the origin", + "default": "30.0" + } + }, + "required": ["split_range"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/object_range_splitter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} From c0fcd75fbfdc7dfc1b355d1325f8d12d74e7b554 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Wed, 3 Apr 2024 21:00:30 +0900 Subject: [PATCH 22/57] feat(tier4_autoware_utils, obstacle_cruise): change to read topic by polling (#6702) change to read topic by polling Signed-off-by: Yuki Takagi --- .../ros/polling_subscriber.hpp | 65 +++++++++++++++++++ .../include/obstacle_cruise_planner/node.hpp | 15 ++--- planning/obstacle_cruise_planner/src/node.cpp | 45 ++++++------- 3 files changed, 93 insertions(+), 32 deletions(-) create mode 100644 common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp new file mode 100644 index 0000000000000..f4d230e15dcf1 --- /dev/null +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp @@ -0,0 +1,65 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TIER4_AUTOWARE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_ +#define TIER4_AUTOWARE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_ + +#include + +#include + +namespace tier4_autoware_utils +{ + +template +class InterProcessPollingSubscriber +{ +private: + typename rclcpp::Subscription::SharedPtr subscriber_; + std::optional data_; + +public: + explicit InterProcessPollingSubscriber(rclcpp::Node * node, const std::string & topic_name) + { + auto noexec_callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false); + auto noexec_subscription_options = rclcpp::SubscriptionOptions(); + noexec_subscription_options.callback_group = noexec_callback_group; + + subscriber_ = node->create_subscription( + topic_name, rclcpp::QoS{1}, [node](const typename T::ConstSharedPtr msg) { assert(false); }, + noexec_subscription_options); + }; + bool updateLatestData() + { + rclcpp::MessageInfo message_info; + T tmp; + // The queue size (QoS) must be 1 to get the last message data. + if (subscriber_->take(tmp, message_info)) { + data_ = tmp; + } + return data_.has_value(); + }; + const T & getData() const + { + if (!data_.has_value()) { + throw std::runtime_error("Bad_optional_access in class InterProcessPollingSubscriber"); + } + return data_.value(); + }; +}; + +} // namespace tier4_autoware_utils + +#endif // TIER4_AUTOWARE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_ diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp index d1a9d0ff56b52..c368265ea0f66 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp @@ -21,6 +21,7 @@ #include "obstacle_cruise_planner/type_alias.hpp" #include "signal_processing/lowpass_filter_1d.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" +#include "tier4_autoware_utils/ros/polling_subscriber.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" #include @@ -138,14 +139,12 @@ class ObstacleCruisePlannerNode : public rclcpp::Node // subscriber rclcpp::Subscription::SharedPtr traj_sub_; - rclcpp::Subscription::SharedPtr objects_sub_; - rclcpp::Subscription::SharedPtr odom_sub_; - rclcpp::Subscription::SharedPtr acc_sub_; - - // data for callback functions - PredictedObjects::ConstSharedPtr objects_ptr_{nullptr}; - Odometry::ConstSharedPtr ego_odom_ptr_{nullptr}; - AccelWithCovarianceStamped::ConstSharedPtr ego_accel_ptr_{nullptr}; + tier4_autoware_utils::InterProcessPollingSubscriber ego_odom_sub_{ + this, "~/input/odometry"}; + tier4_autoware_utils::InterProcessPollingSubscriber objects_sub_{ + this, "~/input/objects"}; + tier4_autoware_utils::InterProcessPollingSubscriber acc_sub_{ + this, "~/input/acceleration"}; // Vehicle Parameters VehicleInfo vehicle_info_; diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index 2d1b70d1745f9..a069b4b6f9395 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -357,15 +357,6 @@ ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & traj_sub_ = create_subscription( "~/input/trajectory", rclcpp::QoS{1}, std::bind(&ObstacleCruisePlannerNode::onTrajectory, this, _1)); - objects_sub_ = create_subscription( - "~/input/objects", rclcpp::QoS{1}, - [this](const PredictedObjects::ConstSharedPtr msg) { objects_ptr_ = msg; }); - odom_sub_ = create_subscription( - "~/input/odometry", rclcpp::QoS{1}, - [this](const Odometry::ConstSharedPtr msg) { ego_odom_ptr_ = msg; }); - acc_sub_ = create_subscription( - "~/input/acceleration", rclcpp::QoS{1}, - [this](const AccelWithCovarianceStamped::ConstSharedPtr msg) { ego_accel_ptr_ = msg; }); // publisher trajectory_pub_ = create_publisher("~/output/trajectory", 1); @@ -493,10 +484,15 @@ rcl_interfaces::msg::SetParametersResult ObstacleCruisePlannerNode::onParam( void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr msg) { - const auto traj_points = motion_utils::convertToTrajectoryPointArray(*msg); + if ( + !ego_odom_sub_.updateLatestData() || !objects_sub_.updateLatestData() || + !acc_sub_.updateLatestData()) { + return; + } + const auto traj_points = motion_utils::convertToTrajectoryPointArray(*msg); // check if subscribed variables are ready - if (traj_points.empty() || !ego_odom_ptr_ || !ego_accel_ptr_ || !objects_ptr_) { + if (traj_points.empty()) { return; } @@ -609,11 +605,11 @@ std::vector ObstacleCruisePlannerNode::convertToObstacles( { stop_watch_.tic(__func__); - const auto obj_stamp = rclcpp::Time(objects_ptr_->header.stamp); + const auto obj_stamp = rclcpp::Time(objects_sub_.getData().header.stamp); const auto & p = behavior_determination_param_; std::vector target_obstacles; - for (const auto & predicted_object : objects_ptr_->objects) { + for (const auto & predicted_object : objects_sub_.getData().objects) { const auto & object_id = tier4_autoware_utils::toHexString(predicted_object.object_id).substr(0, 4); const auto & current_obstacle_pose = @@ -631,7 +627,8 @@ std::vector ObstacleCruisePlannerNode::convertToObstacles( } // 2. Check if the obstacle is in front of the ego. - const size_t ego_idx = ego_nearest_param_.findIndex(traj_points, ego_odom_ptr_->pose.pose); + const size_t ego_idx = + ego_nearest_param_.findIndex(traj_points, ego_odom_sub_.getData().pose.pose); const auto ego_to_obstacle_distance = calcDistanceToFrontVehicle(traj_points, ego_idx, current_obstacle_pose.pose.position); if (!ego_to_obstacle_distance) { @@ -727,7 +724,7 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles( // calculated decimated trajectory points and trajectory polygon const auto decimated_traj_points = decimateTrajectoryPoints(traj_points); const auto decimated_traj_polys = - createOneStepPolygons(decimated_traj_points, vehicle_info_, ego_odom_ptr_->pose.pose); + createOneStepPolygons(decimated_traj_points, vehicle_info_, ego_odom_sub_.getData().pose.pose); debug_data_ptr_->detection_polygons = decimated_traj_polys; // determine ego's behavior from stop, cruise and slow down @@ -785,7 +782,7 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles( slow_down_condition_counter_.removeCounterUnlessUpdated(); // Check target obstacles' consistency - checkConsistency(objects_ptr_->header.stamp, *objects_ptr_, stop_obstacles); + checkConsistency(objects_sub_.getData().header.stamp, objects_sub_.getData(), stop_obstacles); // update previous obstacles prev_stop_obstacles_ = stop_obstacles; @@ -807,7 +804,7 @@ std::vector ObstacleCruisePlannerNode::decimateTrajectoryPoints // trim trajectory const size_t ego_seg_idx = - ego_nearest_param_.findSegmentIndex(traj_points, ego_odom_ptr_->pose.pose); + ego_nearest_param_.findSegmentIndex(traj_points, ego_odom_sub_.getData().pose.pose); const size_t traj_start_point_idx = ego_seg_idx; const auto trimmed_traj_points = std::vector(traj_points.begin() + traj_start_point_idx, traj_points.end()); @@ -1191,7 +1188,7 @@ std::optional ObstacleCruisePlannerNode::createStopObstacle( // calculate collision points with trajectory with lateral stop margin const auto traj_polys_with_lat_margin = createOneStepPolygons( - traj_points, vehicle_info_, ego_odom_ptr_->pose.pose, p.max_lat_margin_for_stop); + traj_points, vehicle_info_, ego_odom_sub_.getData().pose.pose, p.max_lat_margin_for_stop); const auto collision_point = polygon_utils::getCollisionPoint( traj_points, traj_polys_with_lat_margin, obstacle, is_driving_forward_, vehicle_info_); @@ -1261,7 +1258,7 @@ std::optional ObstacleCruisePlannerNode::createSlowDownObstacl // calculate collision points with trajectory with lateral stop margin // NOTE: For additional margin, hysteresis is not divided by two. const auto traj_polys_with_lat_margin = createOneStepPolygons( - traj_points, vehicle_info_, ego_odom_ptr_->pose.pose, + traj_points, vehicle_info_, ego_odom_sub_.getData().pose.pose, p.max_lat_margin_for_slow_down + p.lat_hysteresis_margin_for_slow_down); std::vector front_collision_polygons; @@ -1424,8 +1421,8 @@ double ObstacleCruisePlannerNode::calcCollisionTimeMargin( const std::vector & collision_points, const std::vector & traj_points, const bool is_driving_forward) const { - const auto & ego_pose = ego_odom_ptr_->pose.pose; - const double ego_vel = ego_odom_ptr_->twist.twist.linear.x; + const auto & ego_pose = ego_odom_sub_.getData().pose.pose; + const double ego_vel = ego_odom_sub_.getData().twist.twist.linear.x; const double time_to_reach_collision_point = [&]() { const double abs_ego_offset = is_driving_forward @@ -1457,9 +1454,9 @@ PlannerData ObstacleCruisePlannerNode::createPlannerData( PlannerData planner_data; planner_data.current_time = now(); planner_data.traj_points = traj_points; - planner_data.ego_pose = ego_odom_ptr_->pose.pose; - planner_data.ego_vel = ego_odom_ptr_->twist.twist.linear.x; - planner_data.ego_acc = ego_accel_ptr_->accel.accel.linear.x; + planner_data.ego_pose = ego_odom_sub_.getData().pose.pose; + planner_data.ego_vel = ego_odom_sub_.getData().twist.twist.linear.x; + planner_data.ego_acc = acc_sub_.getData().accel.accel.linear.x; planner_data.is_driving_forward = is_driving_forward_; return planner_data; } From 9735dfa783a97e005565aff5432baac898792c7e Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 4 Apr 2024 11:36:28 +0900 Subject: [PATCH 23/57] docs(perception_online_evaluator): add description about yaw rate evaluation (#6737) Signed-off-by: kyoichi-sugahara --- evaluator/perception_online_evaluator/README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/evaluator/perception_online_evaluator/README.md b/evaluator/perception_online_evaluator/README.md index c0e2a516cf948..7c2179239221e 100644 --- a/evaluator/perception_online_evaluator/README.md +++ b/evaluator/perception_online_evaluator/README.md @@ -11,6 +11,7 @@ This module allows for the evaluation of how accurately perception results are g - Calculates lateral deviation between the predicted path and the actual traveled trajectory. - Calculates lateral deviation between the smoothed traveled trajectory and the perceived position to evaluate the stability of lateral position recognition. - Calculates yaw deviation between the smoothed traveled trajectory and the perceived position to evaluate the stability of yaw recognition. +- Calculates yaw rate based on the yaw of the object received in the previous cycle to evaluate the stability of the yaw rate recognition. ## Inputs / Outputs From 41aab5122d416fd9c83ea49885eb5bf07673daf2 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 4 Apr 2024 16:13:42 +0900 Subject: [PATCH 24/57] fix(hazard_status_converter): check current operation mode (#6733) * fix: hazard status converter Signed-off-by: Takagi, Isamu * fix: topic name and modes Signed-off-by: Takagi, Isamu * fix check target mode Signed-off-by: Takagi, Isamu * fix message type Signed-off-by: Takagi, Isamu * Revert "fix check target mode" This reverts commit 8b190b7b99490503a52b155cad9f593c1c97e553. --------- Signed-off-by: Takagi, Isamu --- system/hazard_status_converter/package.xml | 1 + .../hazard_status_converter/src/converter.cpp | 73 +++++++++++++++---- .../hazard_status_converter/src/converter.hpp | 11 +++ 3 files changed, 69 insertions(+), 16 deletions(-) diff --git a/system/hazard_status_converter/package.xml b/system/hazard_status_converter/package.xml index 9ae7a384927b9..082aa85cba97a 100644 --- a/system/hazard_status_converter/package.xml +++ b/system/hazard_status_converter/package.xml @@ -10,6 +10,7 @@ ament_cmake_auto autoware_cmake + autoware_adapi_v1_msgs autoware_auto_system_msgs diagnostic_msgs rclcpp diff --git a/system/hazard_status_converter/src/converter.cpp b/system/hazard_status_converter/src/converter.cpp index e1da4f463f06d..58282306491dd 100644 --- a/system/hazard_status_converter/src/converter.cpp +++ b/system/hazard_status_converter/src/converter.cpp @@ -32,10 +32,10 @@ enum class HazardLevel { NF, SF, LF, SPF }; struct TempNode { const DiagnosticNode & node; - bool is_auto_tree; + bool is_root_tree; }; -HazardLevel get_hazard_level(const TempNode & node, DiagnosticLevel auto_mode_level) +HazardLevel get_hazard_level(const TempNode & node, DiagnosticLevel root_mode_level) { // Convert the level according to the table below. // The Level other than auto mode is considered OK. @@ -49,7 +49,7 @@ HazardLevel get_hazard_level(const TempNode & node, DiagnosticLevel auto_mode_le // | STALE | SF | LF | SPF | SPF | // |-------|-------------------------------| - const auto root_level = node.is_auto_tree ? auto_mode_level : DiagnosticStatus::OK; + const auto root_level = node.is_root_tree ? root_mode_level : DiagnosticStatus::OK; const auto node_level = node.node.status.level; if (node_level == DiagnosticStatus::OK) { @@ -67,20 +67,21 @@ HazardLevel get_hazard_level(const TempNode & node, DiagnosticLevel auto_mode_le return HazardLevel::SPF; } -void set_auto_tree(std::vector & nodes, int index) +void set_root_tree(std::vector & nodes, int index) { TempNode & node = nodes[index]; - if (node.is_auto_tree) { + if (node.is_root_tree) { return; } - node.is_auto_tree = true; + node.is_root_tree = true; for (const auto & link : node.node.links) { - set_auto_tree(nodes, link.index); + set_root_tree(nodes, link.index); } } -HazardStatusStamped convert_hazard_diagnostics(const DiagnosticGraph & graph) +HazardStatusStamped convert_hazard_diagnostics( + const DiagnosticGraph & graph, const std::string & root, bool ignore) { // Create temporary tree for conversion. std::vector nodes; @@ -90,19 +91,21 @@ HazardStatusStamped convert_hazard_diagnostics(const DiagnosticGraph & graph) } // Mark nodes included in the auto mode tree. - DiagnosticLevel auto_mode_level = DiagnosticStatus::STALE; - for (size_t index = 0; index < nodes.size(); ++index) { - const auto & status = nodes[index].node.status; - if (status.name == "/autoware/modes/autonomous") { - set_auto_tree(nodes, index); - auto_mode_level = status.level; + DiagnosticLevel root_mode_level = DiagnosticStatus::STALE; + if (!root.empty() && !ignore) { + for (size_t index = 0; index < nodes.size(); ++index) { + const auto & status = nodes[index].node.status; + if (status.name == root) { + set_root_tree(nodes, index); + root_mode_level = status.level; + } } } // Calculate hazard level from node level and root level. HazardStatusStamped hazard; for (const auto & node : nodes) { - switch (get_hazard_level(node, auto_mode_level)) { + switch (get_hazard_level(node, root_mode_level)) { case HazardLevel::NF: hazard.status.diag_no_fault.push_back(node.node.status); break; @@ -131,6 +134,22 @@ Converter::Converter(const rclcpp::NodeOptions & options) : Node("converter", op sub_graph_ = create_subscription( "~/diagnostics_graph", rclcpp::QoS(3), std::bind(&Converter::on_graph, this, std::placeholders::_1)); + sub_state_ = create_subscription( + "/autoware/state", rclcpp::QoS(1), + std::bind(&Converter::on_state, this, std::placeholders::_1)); + sub_mode_ = create_subscription( + "/system/operation_mode/state", rclcpp::QoS(1).transient_local(), + std::bind(&Converter::on_mode, this, std::placeholders::_1)); +} + +void Converter::on_state(const AutowareState::ConstSharedPtr msg) +{ + state_ = msg; +} + +void Converter::on_mode(const OperationMode::ConstSharedPtr msg) +{ + mode_ = msg; } void Converter::on_graph(const DiagnosticGraph::ConstSharedPtr msg) @@ -148,7 +167,29 @@ void Converter::on_graph(const DiagnosticGraph::ConstSharedPtr msg) return HazardStatus::NO_FAULT; }; - HazardStatusStamped hazard = convert_hazard_diagnostics(*msg); + const auto is_ignore = [this]() { + if (mode_ && state_) { + if (mode_->mode == OperationMode::AUTONOMOUS || mode_->mode == OperationMode::STOP) { + if (state_->state == AutowareState::WAITING_FOR_ROUTE) return true; + if (state_->state == AutowareState::PLANNING) return true; + } + if (state_->state == AutowareState::INITIALIZING) return true; + if (state_->state == AutowareState::FINALIZING) return true; + } + return false; + }; + + const auto get_root = [this]() { + if (mode_) { + if (mode_->mode == OperationMode::STOP) return "/autoware/modes/stop"; + if (mode_->mode == OperationMode::AUTONOMOUS) return "/autoware/modes/autonomous"; + if (mode_->mode == OperationMode::LOCAL) return "/autoware/modes/local"; + if (mode_->mode == OperationMode::REMOTE) return "/autoware/modes/remote"; + } + return ""; + }; + + HazardStatusStamped hazard = convert_hazard_diagnostics(*msg, get_root(), is_ignore()); hazard.stamp = msg->stamp; hazard.status.level = get_system_level(hazard.status); hazard.status.emergency = hazard.status.level == HazardStatus::SINGLE_POINT_FAULT; diff --git a/system/hazard_status_converter/src/converter.hpp b/system/hazard_status_converter/src/converter.hpp index 90c6f6e42bf85..04e84cfb3c0c4 100644 --- a/system/hazard_status_converter/src/converter.hpp +++ b/system/hazard_status_converter/src/converter.hpp @@ -17,6 +17,8 @@ #include +#include +#include #include #include @@ -33,11 +35,20 @@ class Converter : public rclcpp::Node explicit Converter(const rclcpp::NodeOptions & options); private: + using AutowareState = autoware_auto_system_msgs::msg::AutowareState; + using OperationMode = autoware_adapi_v1_msgs::msg::OperationModeState; using DiagnosticGraph = tier4_system_msgs::msg::DiagnosticGraph; using HazardStatusStamped = autoware_auto_system_msgs::msg::HazardStatusStamped; + rclcpp::Subscription::SharedPtr sub_state_; + rclcpp::Subscription::SharedPtr sub_mode_; rclcpp::Subscription::SharedPtr sub_graph_; rclcpp::Publisher::SharedPtr pub_hazard_; + void on_state(const AutowareState::ConstSharedPtr msg); + void on_mode(const OperationMode::ConstSharedPtr msg); void on_graph(const DiagnosticGraph::ConstSharedPtr msg); + + AutowareState::ConstSharedPtr state_; + OperationMode::ConstSharedPtr mode_; }; } // namespace hazard_status_converter From f088fb45537fc74f0fbcbc31a76877266cd5041a Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 4 Apr 2024 22:52:42 +0900 Subject: [PATCH 25/57] fix(lane_change): limit prepare and lane changing length (#6734) Signed-off-by: Zulfaqar Azmi --- .../utils/utils.hpp | 17 +++++++++++++++++ .../src/scene.cpp | 11 +++++------ .../src/utils/utils.cpp | 10 ++++++++++ 3 files changed, 32 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp index ff5d7bc0773fa..7c8cfdb926a6b 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp @@ -257,6 +257,23 @@ Polygon2d getEgoCurrentFootprint( bool isWithinIntersection( const std::shared_ptr & route_handler, const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon); + +/** + * @brief Calculates the distance required during a lane change operation. + * + * Used for computing prepare or lane change length based on current and maximum velocity, + * acceleration, and duration, returning the lesser of accelerated distance or distance at max + * velocity. + * + * @param velocity The current velocity of the vehicle in meters per second (m/s). + * @param maximum_velocity The maximum velocity the vehicle can reach in meters per second (m/s). + * @param acceleration The acceleration of the vehicle in meters per second squared (m/s^2). + * @param duration The duration of the lane change in seconds (s). + * @return The calculated minimum distance in meters (m). + */ +double calcPhaseLength( + const double velocity, const double maximum_velocity, const double acceleration, + const double time); } // namespace behavior_path_planner::utils::lane_change namespace behavior_path_planner::utils::lane_change::debug diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index a6d21aede64b6..bc9a366e62b34 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -1293,9 +1293,8 @@ bool NormalLaneChange::getLaneChangePaths( (prepare_duration < 1e-3) ? 0.0 : ((prepare_velocity - current_velocity) / prepare_duration); - const double prepare_length = - current_velocity * prepare_duration + - 0.5 * longitudinal_acc_on_prepare * std::pow(prepare_duration, 2); + const auto prepare_length = utils::lane_change::calcPhaseLength( + current_velocity, getCommonParam().max_vel, longitudinal_acc_on_prepare, prepare_duration); auto prepare_segment = getPrepareSegment(current_lanes, backward_path_length, prepare_length); @@ -1347,9 +1346,9 @@ bool NormalLaneChange::getLaneChangePaths( utils::lane_change::calcLaneChangingAcceleration( initial_lane_changing_velocity, max_path_velocity, lane_changing_time, sampled_longitudinal_acc); - const auto lane_changing_length = - initial_lane_changing_velocity * lane_changing_time + - 0.5 * longitudinal_acc_on_lane_changing * lane_changing_time * lane_changing_time; + const auto lane_changing_length = utils::lane_change::calcPhaseLength( + initial_lane_changing_velocity, getCommonParam().max_vel, + longitudinal_acc_on_lane_changing, lane_changing_time); const auto terminal_lane_changing_velocity = std::min( initial_lane_changing_velocity + longitudinal_acc_on_lane_changing * lane_changing_time, getCommonParam().max_vel); diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index 0b4893f94e071..15db6b0055756 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -1184,6 +1184,16 @@ bool isWithinIntersection( return boost::geometry::within( polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet_polygon.basicPolygon()))); } + +double calcPhaseLength( + const double velocity, const double maximum_velocity, const double acceleration, + const double duration) +{ + const auto length_with_acceleration = + velocity * duration + 0.5 * acceleration * std::pow(duration, 2); + const auto length_with_max_velocity = maximum_velocity * duration; + return std::min(length_with_acceleration, length_with_max_velocity); +} } // namespace behavior_path_planner::utils::lane_change namespace behavior_path_planner::utils::lane_change::debug From 7d268799fefe6d326f906315293be1ea150af41f Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 4 Apr 2024 23:23:04 +0900 Subject: [PATCH 26/57] feat(perception_online_evaluator): ignore reversal of orientation from yaw_rate calculation (#6748) Signed-off-by: kosuke55 --- .../src/metrics_calculator.cpp | 13 +++++++++---- .../src/perception_online_evaluator_node.cpp | 1 + 2 files changed, 10 insertions(+), 4 deletions(-) diff --git a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp index 20d8c6d570489..4b882bb8b2e68 100644 --- a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp +++ b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp @@ -381,12 +381,17 @@ MetricStatMap MetricsCalculator::calcYawRateMetrics(const ClassObjectsMap & clas if (time_diff < 0.01) { continue; } - const auto current_yaw = + const double current_yaw = tf2::getYaw(object.kinematics.initial_pose_with_covariance.pose.orientation); - const auto previous_yaw = + const double previous_yaw = tf2::getYaw(previous_object.kinematics.initial_pose_with_covariance.pose.orientation); - const auto yaw_rate = - std::abs(tier4_autoware_utils::normalizeRadian(current_yaw - previous_yaw) / time_diff); + const double yaw_diff = + std::abs(tier4_autoware_utils::normalizeRadian(current_yaw - previous_yaw)); + // if yaw_diff is close to PI, reversal of orientation is likely occurring, so ignore it + if (std::abs(M_PI - yaw_diff) < 0.1) { + continue; + } + const auto yaw_rate = yaw_diff / time_diff; stat.add(yaw_rate); } metric_stat_map["yaw_rate_" + convertLabelToString(label)] = stat; diff --git a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp index f3a08bf42797a..ceb304894ad8c 100644 --- a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp @@ -214,6 +214,7 @@ rcl_interfaces::msg::SetParametersResult PerceptionOnlineEvaluatorNode::onParame auto & p = parameters_; updateParam(parameters, "smoothing_window_size", p->smoothing_window_size); + updateParam(parameters, "stopped_velocity_threshold", p->stopped_velocity_threshold); // update metrics { From 178841b9cc797bde39a5f47d8074729e0355bc43 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 5 Apr 2024 10:22:46 +0900 Subject: [PATCH 27/57] feat(obstacle_pointcloud_based_validator_node): skip validation when obstacle pointcloud is empty (#6684) * feat: skip validation when obstacle pointcloud is empty Signed-off-by: yoshiri * fix: remove mistakenly unremoved line Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- .../src/obstacle_pointcloud_based_validator.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp index e39de639a6121..db2e6ec3a7901 100644 --- a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp +++ b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp @@ -327,15 +327,19 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud( // objects_pub_->publish(*input_objects); return; } + bool validation_is_ready = true; if (!validator_->setKdtreeInputCloud(input_obstacle_pointcloud)) { - RCLCPP_WARN_THROTTLE(this->get_logger(), *this->get_clock(), 5, "cannot receive pointcloud"); - return; + RCLCPP_WARN_THROTTLE( + this->get_logger(), *this->get_clock(), 5, + "obstacle pointcloud is empty! Can not validate objects."); + validation_is_ready = false; } for (size_t i = 0; i < transformed_objects.objects.size(); ++i) { const auto & transformed_object = transformed_objects.objects.at(i); const auto & object = input_objects->objects.at(i); - const auto validated = validator_->validate_object(transformed_object); + const auto validated = + validation_is_ready ? validator_->validate_object(transformed_object) : false; if (debugger_) { debugger_->addNeighborPointcloud(validator_->getDebugNeighborPointCloud()); debugger_->addPointcloudWithinPolygon(validator_->getDebugPointCloudWithinObject()); From 804600599c546e5947d34666e842d6e29840909a Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 5 Apr 2024 10:49:31 +0900 Subject: [PATCH 28/57] feat(lane_change): check prepare phase in turn direction lanes (#6726) * feat(lane_change): check prepare phase in turn direction lanes Signed-off-by: Muhammad Zulfaqar Azmi * Doxygen comment Signed-off-by: Muhammad Zulfaqar Azmi * Add config Signed-off-by: Muhammad Zulfaqar Azmi * fix comments by the reviewer Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_lane_change_module/README.md | 3 ++- .../config/lane_change.param.yaml | 1 + .../utils/data_structs.hpp | 1 + .../utils/utils.hpp | 15 +++++++++++++++ .../src/manager.cpp | 2 ++ .../src/scene.cpp | 10 +++++++++- .../src/utils/utils.cpp | 13 +++++++++++++ 7 files changed, 43 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_lane_change_module/README.md b/planning/behavior_path_lane_change_module/README.md index 17cdc58f5ad47..62f35a053958a 100644 --- a/planning/behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_lane_change_module/README.md @@ -554,7 +554,8 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi | Name | Unit | Type | Description | Default value | | :------------------------------------------------------- | ----- | ------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | | `enable_collision_check_for_prepare_phase.general_lanes` | [-] | boolean | Perform collision check starting from the prepare phase for situations not explicitly covered by other settings (e.g., intersections). If `false`, collision check only evaluated for lane changing phase. | false | -| `enable_collision_check_for_prepare_phase.intersection` | [-] | boolean | Perform collision check starting from prepare phase when ego is in intersection. If `false`, collision check only evaluated for lane changing phase. | false | +| `enable_collision_check_for_prepare_phase.intersection` | [-] | boolean | Perform collision check starting from prepare phase when ego is in intersection. If `false`, collision check only evaluated for lane changing phase. | true | +| `enable_collision_check_for_prepare_phase.turns` | [-] | boolean | Perform collision check starting from prepare phase when ego is in lanelet with turn direction tags. If `false`, collision check only evaluated for lane changing phase. | true | | `prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | | `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module check objects on current lanes when performing collision assessment. | false | | `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. when performing collision assessment | false | diff --git a/planning/behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_lane_change_module/config/lane_change.param.yaml index 039e8a31ed10f..1ab33514c5f24 100644 --- a/planning/behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_lane_change_module/config/lane_change.param.yaml @@ -92,6 +92,7 @@ enable_collision_check_for_prepare_phase: general_lanes: false intersection: true + turns: true prepare_segment_ignore_object_velocity_thresh: 0.1 # [m/s] check_objects_on_current_lanes: true check_objects_on_other_lanes: true diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp index 0d77135fda242..fdaa15ff9bef9 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp @@ -114,6 +114,7 @@ struct LaneChangeParameters // collision check bool enable_collision_check_for_prepare_phase_in_general_lanes{false}; bool enable_collision_check_for_prepare_phase_in_intersection{true}; + bool enable_collision_check_for_prepare_phase_in_turns{true}; double prepare_segment_ignore_object_velocity_thresh{0.1}; bool check_objects_on_current_lanes{true}; bool check_objects_on_other_lanes{true}; diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp index 7c8cfdb926a6b..76331bd98eb9c 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp @@ -258,6 +258,21 @@ bool isWithinIntersection( const std::shared_ptr & route_handler, const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon); +/** + * @brief Determines if a polygon is within lanes designated for turning. + * + * Checks if a polygon overlaps with lanelets tagged for turning directions (excluding 'straight'). + * It evaluates the lanelet's 'turn_direction' attribute and determines overlap with the lanelet's + * area. + * + * @param lanelet Lanelet representing the road segment whose turn direction is to be evaluated. + * @param polygon The polygon to be checked for its presence within turn direction lanes. + * + * @return bool True if the polygon is within a lane designated for turning, false if it is within a + * straight lane or no turn direction is specified. + */ +bool isWithinTurnDirectionLanes(const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon); + /** * @brief Calculates the distance required during a lane change operation. * diff --git a/planning/behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_lane_change_module/src/manager.cpp index 7045544df50aa..81d4b86afa094 100644 --- a/planning/behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_lane_change_module/src/manager.cpp @@ -72,6 +72,8 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node) *node, parameter("enable_collision_check_for_prepare_phase.general_lanes")); p.enable_collision_check_for_prepare_phase_in_intersection = getOrDeclareParameter( *node, parameter("enable_collision_check_for_prepare_phase.intersection")); + p.enable_collision_check_for_prepare_phase_in_turns = + getOrDeclareParameter(*node, parameter("enable_collision_check_for_prepare_phase.turns")); p.prepare_segment_ignore_object_velocity_thresh = getOrDeclareParameter( *node, parameter("prepare_segment_ignore_object_velocity_thresh")); p.check_objects_on_current_lanes = diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index bc9a366e62b34..3a4a44ef33edb 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -2142,7 +2142,15 @@ bool NormalLaneChange::check_prepare_phase() const return utils::lane_change::isWithinIntersection(route_handler, current_lane, ego_footprint); }); - return check_in_intersection || check_in_general_lanes; + const auto check_in_turns = std::invoke([&]() { + if (!lane_change_parameters_->enable_collision_check_for_prepare_phase_in_turns) { + return false; + } + + return utils::lane_change::isWithinTurnDirectionLanes(current_lane, ego_footprint); + }); + + return check_in_intersection || check_in_turns || check_in_general_lanes; } } // namespace behavior_path_planner diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index 15db6b0055756..97fcc841a546e 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -37,6 +37,8 @@ #include +#include + #include #include #include @@ -1185,6 +1187,17 @@ bool isWithinIntersection( polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet_polygon.basicPolygon()))); } +bool isWithinTurnDirectionLanes(const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon) +{ + const std::string turn_direction = lanelet.attributeOr("turn_direction", "else"); + if (turn_direction == "else" || turn_direction == "straight") { + return false; + } + + return !boost::geometry::disjoint( + polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet.polygon2d().basicPolygon()))); +} + double calcPhaseLength( const double velocity, const double maximum_velocity, const double acceleration, const double duration) From 1eef4c0e102c53e96d30ee701420f388ba29f77d Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Fri, 5 Apr 2024 19:05:10 +0900 Subject: [PATCH 29/57] feat(run_out): maintain run out stop wall (#6732) * feat(run_out): maintain run_out stop walls for a given time Signed-off-by: Daniel Sanchez * remove printouts Signed-off-by: Daniel Sanchez * space Signed-off-by: Daniel Sanchez * add stop wall debug markers when maintaining stop points Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../config/run_out.param.yaml | 1 + .../src/manager.cpp | 1 + .../src/scene.cpp | 54 +++++++++++++++---- .../src/scene.hpp | 12 ++++- .../src/utils.hpp | 1 + 5 files changed, 57 insertions(+), 12 deletions(-) diff --git a/planning/behavior_velocity_run_out_module/config/run_out.param.yaml b/planning/behavior_velocity_run_out_module/config/run_out.param.yaml index 628b8725149a2..6d0d9571bf43b 100644 --- a/planning/behavior_velocity_run_out_module/config/run_out.param.yaml +++ b/planning/behavior_velocity_run_out_module/config/run_out.param.yaml @@ -17,6 +17,7 @@ ego_cut_line_length: 3.0 # The width of the ego's cut line ego_footprint_extra_margin: 0.5 # [m] expand the ego vehicles' footprint by this value on all sides when building the ego footprint path keep_obstacle_on_path_time_threshold: 1.0 # [s] How much time a previous run out target obstacle is kept in the run out candidate list if it enters the ego path. + keep_stop_point_time: 1.0 # [s] If a stop point is issued by this module, keep the stop point for this many seconds. Only works if approach is disabled # Parameter to create abstracted dynamic obstacles dynamic_obstacle: diff --git a/planning/behavior_velocity_run_out_module/src/manager.cpp b/planning/behavior_velocity_run_out_module/src/manager.cpp index e2ce3822bf86d..1c85a22f57bf6 100644 --- a/planning/behavior_velocity_run_out_module/src/manager.cpp +++ b/planning/behavior_velocity_run_out_module/src/manager.cpp @@ -77,6 +77,7 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".ego_footprint_extra_margin"); p.keep_obstacle_on_path_time_threshold = getOrDeclareParameter(node, ns + ".keep_obstacle_on_path_time_threshold"); + p.keep_stop_point_time = getOrDeclareParameter(node, ns + ".keep_stop_point_time"); } { diff --git a/planning/behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_run_out_module/src/scene.cpp index 48fbebb8b056d..da826e1cf0cf6 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_run_out_module/src/scene.cpp @@ -144,6 +144,16 @@ bool RunOutModule::modifyPathVelocity( debug_ptr_->setDebugValues( DebugValues::TYPE::CALCULATION_TIME_COLLISION_CHECK, elapsed_collision_check.count() / 1000.0); + // If no new obstacle is detected, we check if the stop point should be maintained for more time. + auto should_maintain_stop_point = [&](const bool is_stopping_point_inserted) -> bool { + if (!stop_point_generation_time_.has_value() || is_stopping_point_inserted) { + return false; + } + const auto now = clock_->now().seconds(); + const double elapsed_time_since_stop_wall_was_generated = + (now - stop_point_generation_time_.value()); + return elapsed_time_since_stop_wall_was_generated < planner_param_.run_out.keep_stop_point_time; + }; // insert stop point for the detected obstacle if (planner_param_.approaching.enable) { // after a certain amount of time has elapsed since the ego stopped, @@ -152,7 +162,23 @@ bool RunOutModule::modifyPathVelocity( dynamic_obstacle, *planner_data_, planner_param_, extended_smoothed_path, *path); } else { // just insert zero velocity for stopping - insertStoppingVelocity(dynamic_obstacle, current_pose, current_vel, current_acc, *path); + std::optional stop_point; + const bool is_stopping_point_inserted = insertStoppingVelocity( + dynamic_obstacle, current_pose, current_vel, current_acc, *path, stop_point); + + stop_point_generation_time_ = (is_stopping_point_inserted) + ? std::make_optional(clock_->now().seconds()) + : stop_point_generation_time_; + last_stop_point_ = (is_stopping_point_inserted) ? stop_point : last_stop_point_; + + const bool is_maintain_stop_point = should_maintain_stop_point(is_stopping_point_inserted); + if (is_maintain_stop_point) { + insertStopPoint(last_stop_point_, *path); + // debug + debug_ptr_->setAccelReason(RunOutDebug::AccelReason::STOP); + debug_ptr_->pushStopPose(tier4_autoware_utils::calcOffsetPose( + *last_stop_point_, planner_param_.vehicle_param.base_to_front, 0, 0)); + } } // apply max jerk limit if the ego can't stop with specified max jerk and acc @@ -230,10 +256,8 @@ std::optional RunOutModule::detectCollision( debug_ptr_->pushCollisionPoints(obstacle_selected->collision_points); debug_ptr_->pushNearestCollisionPoint(obstacle_selected->nearest_collision_point); - return obstacle_selected; } - // no collision detected first_detected_time_.reset(); return {}; @@ -717,14 +741,14 @@ std::optional RunOutModule::calcStopPoint( return stop_point; } -void RunOutModule::insertStopPoint( +bool RunOutModule::insertStopPoint( const std::optional stop_point, autoware_auto_planning_msgs::msg::PathWithLaneId & path) { // no stop point if (!stop_point) { RCLCPP_DEBUG_STREAM(logger_, "already has same point"); - return; + return false; } // find nearest point index behind the stop point @@ -736,15 +760,15 @@ void RunOutModule::insertStopPoint( if ( insert_idx == path.points.size() - 1 && planning_utils::isAheadOf(*stop_point, path.points.at(insert_idx).point.pose)) { - return; + return false; } // to PathPointWithLaneId autoware_auto_planning_msgs::msg::PathPointWithLaneId stop_point_with_lane_id; stop_point_with_lane_id = path.points.at(nearest_seg_idx); stop_point_with_lane_id.point.pose = *stop_point; - planning_utils::insertVelocity(path, stop_point_with_lane_id, 0.0, insert_idx); + return true; } void RunOutModule::insertVelocityForState( @@ -806,14 +830,24 @@ void RunOutModule::insertVelocityForState( } } -void RunOutModule::insertStoppingVelocity( +bool RunOutModule::insertStoppingVelocity( const std::optional & dynamic_obstacle, const geometry_msgs::msg::Pose & current_pose, const float current_vel, const float current_acc, PathWithLaneId & output_path) { - const auto stop_point = + std::optional stopping_point; + return insertStoppingVelocity( + dynamic_obstacle, current_pose, current_vel, current_acc, output_path, stopping_point); +} + +bool RunOutModule::insertStoppingVelocity( + const std::optional & dynamic_obstacle, + const geometry_msgs::msg::Pose & current_pose, const float current_vel, const float current_acc, + PathWithLaneId & output_path, std::optional & stopping_point) +{ + stopping_point = calcStopPoint(dynamic_obstacle, output_path, current_pose, current_vel, current_acc); - insertStopPoint(stop_point, output_path); + return insertStopPoint(stopping_point, output_path); } void RunOutModule::insertApproachingVelocity( diff --git a/planning/behavior_velocity_run_out_module/src/scene.hpp b/planning/behavior_velocity_run_out_module/src/scene.hpp index c7702ed15337d..3db6051ab36e7 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/behavior_velocity_run_out_module/src/scene.hpp @@ -66,6 +66,9 @@ class RunOutModule : public SceneModuleInterface std::shared_ptr debug_ptr_; std::unique_ptr state_machine_; std::shared_ptr first_detected_time_; + std::optional stop_point_generation_time_; + std::optional last_stop_point_; + std::optional last_stop_obstacle_uuid_; std::unordered_map obstacle_in_ego_path_times_; @@ -119,7 +122,7 @@ class RunOutModule : public SceneModuleInterface const geometry_msgs::msg::Pose & current_pose, const float current_vel, const float current_acc) const; - void insertStopPoint( + bool insertStopPoint( const std::optional stop_point, autoware_auto_planning_msgs::msg::PathWithLaneId & path); @@ -128,11 +131,16 @@ class RunOutModule : public SceneModuleInterface const PlannerParam & planner_param, const PathWithLaneId & smoothed_path, PathWithLaneId & output_path); - void insertStoppingVelocity( + bool insertStoppingVelocity( const std::optional & dynamic_obstacle, const geometry_msgs::msg::Pose & current_pose, const float current_vel, const float current_acc, PathWithLaneId & output_path); + bool insertStoppingVelocity( + const std::optional & dynamic_obstacle, + const geometry_msgs::msg::Pose & current_pose, const float current_vel, const float current_acc, + PathWithLaneId & output_path, std::optional & stopping_point); + void insertApproachingVelocity( const DynamicObstacle & dynamic_obstacle, const geometry_msgs::msg::Pose & current_pose, const float approaching_vel, const float approach_margin, PathWithLaneId & output_path); diff --git a/planning/behavior_velocity_run_out_module/src/utils.hpp b/planning/behavior_velocity_run_out_module/src/utils.hpp index 823dc81b2b72b..51b460482458f 100644 --- a/planning/behavior_velocity_run_out_module/src/utils.hpp +++ b/planning/behavior_velocity_run_out_module/src/utils.hpp @@ -68,6 +68,7 @@ struct RunOutParam double ego_cut_line_length; double ego_footprint_extra_margin; double keep_obstacle_on_path_time_threshold; + double keep_stop_point_time; float detection_distance; float detection_span; float min_vel_ego_kmph; From 35642a6df0a12750256f459b40546e90bcd5c09e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Sebastian=20Z=C4=99derowski?= Date: Sat, 6 Apr 2024 06:55:14 +0200 Subject: [PATCH 30/57] fix(route_handler): exception in route_handler caused by int overflow (#6755) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Remove cast to int which might cause overflow Signed-off-by: Sebastian Zęderowski Co-authored-by: Sebastian Zęderowski --- planning/route_handler/src/route_handler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 8cec5073efb6a..8d143fcf0b87d 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -1708,7 +1708,7 @@ PathWithLaneId RouteHandler::getCenterLinePath( // append a point only when having one point so that yaw calculation would work if (reference_path.points.size() == 1) { - const lanelet::Id lane_id = static_cast(reference_path.points.front().lane_ids.front()); + const lanelet::Id lane_id = reference_path.points.front().lane_ids.front(); const auto lanelet = lanelet_map_ptr_->laneletLayer.get(lane_id); const auto point = reference_path.points.front().point.pose.position; const auto lane_yaw = lanelet::utils::getLaneletAngle(lanelet, point); From ad79997a32f331c2ce41ee42e1ccd6ef068ea67e Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Mon, 8 Apr 2024 14:22:12 +0900 Subject: [PATCH 31/57] fix(multi_object_tracker): debugger timers checks if the timer is initialized (#6757) fix: debugger timers checks if the timer is initialized Signed-off-by: Taekjin LEE --- .../include/multi_object_tracker/debugger.hpp | 6 ++++ .../multi_object_tracker/src/debugger.cpp | 29 ++++++++++++++++--- .../src/multi_object_tracker_core.cpp | 5 ++++ 3 files changed, 36 insertions(+), 4 deletions(-) diff --git a/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp b/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp index ca1b20d26c25d..858d43dcfc5bd 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp @@ -41,7 +41,10 @@ class TrackerDebugger const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const; void startMeasurementTime( const rclcpp::Time & now, const rclcpp::Time & measurement_header_stamp); + void endMeasurementTime(const rclcpp::Time & now); + void startPublishTime(const rclcpp::Time & now); void endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time); + void setupDiagnostics(); void checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat); struct DEBUG_SETTINGS @@ -56,12 +59,15 @@ class TrackerDebugger private: void loadParameters(); + bool is_initialized_ = false; rclcpp::Node & node_; rclcpp::Publisher::SharedPtr debug_tentative_objects_pub_; std::unique_ptr processing_time_publisher_; rclcpp::Time last_input_stamp_; rclcpp::Time stamp_process_start_; + rclcpp::Time stamp_process_end_; + rclcpp::Time stamp_publish_start_; rclcpp::Time stamp_publish_output_; }; diff --git a/perception/multi_object_tracker/src/debugger.cpp b/perception/multi_object_tracker/src/debugger.cpp index e3fc58dd5d692..4304afbe2e055 100644 --- a/perception/multi_object_tracker/src/debugger.cpp +++ b/perception/multi_object_tracker/src/debugger.cpp @@ -108,16 +108,35 @@ void TrackerDebugger::startMeasurementTime( processing_time_publisher_->publish( "debug/input_latency_ms", input_latency_ms); } + // initialize debug time stamps + if (!is_initialized_) { + stamp_publish_output_ = now; + is_initialized_ = true; + } +} + +void TrackerDebugger::endMeasurementTime(const rclcpp::Time & now) +{ + stamp_process_end_ = now; +} + +void TrackerDebugger::startPublishTime(const rclcpp::Time & now) +{ + stamp_publish_start_ = now; } void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time) { const auto current_time = now; - // pipeline latency: time from sensor measurement to publish + // pipeline latency: time from sensor measurement to publish, used for 'checkDelay' pipeline_latency_ms_ = (current_time - last_input_stamp_).seconds() * 1e3; - if (debug_settings_.publish_processing_time) { - // processing time: time between input and publish - double processing_time_ms = (current_time - stamp_process_start_).seconds() * 1e3; + if (debug_settings_.publish_processing_time && is_initialized_) { + // processing latency: time between input and publish + double processing_latency_ms = ((current_time - stamp_process_start_).seconds()) * 1e3; + // processing time: only the time spent in the tracking processes + double processing_time_ms = ((current_time - stamp_publish_start_).seconds() + + (stamp_process_end_ - stamp_process_start_).seconds()) * + 1e3; // cycle time: time between two consecutive publish double cyclic_time_ms = (current_time - stamp_publish_output_).seconds() * 1e3; // measurement to tracked-object time: time from the sensor measurement to the publishing object @@ -131,6 +150,8 @@ void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Tim "debug/cyclic_time_ms", cyclic_time_ms); processing_time_publisher_->publish( "debug/processing_time_ms", processing_time_ms); + processing_time_publisher_->publish( + "debug/processing_latency_ms", processing_latency_ms); processing_time_publisher_->publish( "debug/meas_to_tracked_object_ms", measurement_to_object_ms); } diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index b8e19d4ca2df4..aacd37766e8b0 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -190,6 +190,10 @@ void MultiObjectTracker::onMeasurement( if (tracker) list_tracker_.push_back(tracker); } + // debugger time + debugger_->endMeasurementTime(this->now()); + + // Publish objects if the timer is not enabled if (publish_timer_ == nullptr) { publish(measurement_time); } @@ -337,6 +341,7 @@ inline bool MultiObjectTracker::shouldTrackerPublish( void MultiObjectTracker::publish(const rclcpp::Time & time) const { + debugger_->startPublishTime(this->now()); const auto subscriber_count = tracked_objects_pub_->get_subscription_count() + tracked_objects_pub_->get_intra_process_subscription_count(); if (subscriber_count < 1) { From 52bc600edf1b0bba58acf8f3ebc5b73fd992f892 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Mon, 8 Apr 2024 14:28:31 +0900 Subject: [PATCH 32/57] docs(mission_planner): update readme for route selector (#6576) Signed-off-by: Takagi, Isamu --- planning/mission_planner/README.md | 67 +- .../media/architecture.drawio.svg | 725 ++++++++++++++++++ .../media/rerouting_interface.svg | 435 ----------- 3 files changed, 759 insertions(+), 468 deletions(-) create mode 100644 planning/mission_planner/media/architecture.drawio.svg delete mode 100644 planning/mission_planner/media/rerouting_interface.svg diff --git a/planning/mission_planner/README.md b/planning/mission_planner/README.md index 3b649168884e6..a9eb488c71377 100644 --- a/planning/mission_planner/README.md +++ b/planning/mission_planner/README.md @@ -7,8 +7,13 @@ The route is made of a sequence of lanes on a static map. Dynamic objects (e.g. pedestrians and other vehicles) and dynamic map information (e.g. road construction which blocks some lanes) are not considered during route planning. Therefore, the output topic is only published when the goal pose or check points are given and will be latched until the new goal pose or check points are given. -The core implementation does not depend on a map format. -In current Autoware.universe, only Lanelet2 map format is supported. +The core implementation does not depend on a map format. Any planning algorithms can be added as plugin modules. +In current Autoware.universe, only the plugin for Lanelet2 map format is supported. + +This package also manages routes for MRM. The `route_selector` node duplicates the `mission_planner` interface and provides it for normal and MRM respectively. +It distributes route requests and planning results according to current MRM operation state. + +![architecture](./media/architecture.drawio.svg) ## Interfaces @@ -28,31 +33,37 @@ In current Autoware.universe, only Lanelet2 map format is supported. ### Services -| Name | Type | Description | -| ------------------------------------------------ | ----------------------------------------- | ------------------------------------------------------------------------------------------- | -| `/planning/mission_planning/clear_route` | autoware_adapi_v1_msgs/srv/ClearRoute | route clear request | -| `/planning/mission_planning/set_route_points` | autoware_adapi_v1_msgs/srv/SetRoutePoints | route request with pose waypoints. Assumed the vehicle is stopped. | -| `/planning/mission_planning/set_route` | autoware_adapi_v1_msgs/srv/SetRoute | route request with lanelet waypoints. Assumed the vehicle is stopped. | -| `/planning/mission_planning/change_route_points` | autoware_adapi_v1_msgs/srv/SetRoutePoints | route change request with pose waypoints. This can be called when the vehicle is moving. | -| `/planning/mission_planning/change_route` | autoware_adapi_v1_msgs/srv/SetRoute | route change request with lanelet waypoints. This can be called when the vehicle is moving. | -| `~/srv/set_mrm_route` | autoware_adapi_v1_msgs/srv/SetRoutePoints | set emergency route. This can be called when the vehicle is moving. | -| `~/srv/clear_mrm_route` | std_srvs/srv/Trigger | clear emergency route. | +| Name | Type | Description | +| ------------------------------------------------------------------- | ---------------------------------------- | ------------------------------------------ | +| `/planning/mission_planning/mission_planner/clear_route` | tier4_planning_msgs/srv/ClearRoute | route clear request | +| `/planning/mission_planning/mission_planner/set_waypoint_route` | tier4_planning_msgs/srv/SetWaypointRoute | route request with lanelet waypoints. | +| `/planning/mission_planning/mission_planner/set_lanelet_route` | tier4_planning_msgs/srv/SetLaneletRoute | route request with pose waypoints. | +| `/planning/mission_planning/route_selector/main/clear_route` | tier4_planning_msgs/srv/ClearRoute | main route clear request | +| `/planning/mission_planning/route_selector/main/set_waypoint_route` | tier4_planning_msgs/srv/SetWaypointRoute | main route request with lanelet waypoints. | +| `/planning/mission_planning/route_selector/main/set_lanelet_route` | tier4_planning_msgs/srv/SetLaneletRoute | main route request with pose waypoints. | +| `/planning/mission_planning/route_selector/mrm/clear_route` | tier4_planning_msgs/srv/ClearRoute | mrm route clear request | +| `/planning/mission_planning/route_selector/mrm/set_waypoint_route` | tier4_planning_msgs/srv/SetWaypointRoute | mrm route request with lanelet waypoints. | +| `/planning/mission_planning/route_selector/mrm/set_lanelet_route` | tier4_planning_msgs/srv/SetLaneletRoute | mrm route request with pose waypoints. | ### Subscriptions -| Name | Type | Description | -| --------------------- | ------------------------------------ | ---------------------- | -| `input/vector_map` | autoware_auto_mapping_msgs/HADMapBin | vector map of Lanelet2 | -| `input/modified_goal` | geometry_msgs/PoseWithUuidStamped | modified goal pose | +| Name | Type | Description | +| ----------------------- | ------------------------------------ | ---------------------- | +| `~/input/vector_map` | autoware_auto_mapping_msgs/HADMapBin | vector map of Lanelet2 | +| `~/input/modified_goal` | geometry_msgs/PoseWithUuidStamped | modified goal pose | ### Publications -| Name | Type | Description | -| ---------------------------------------- | ------------------------------------- | ------------------------ | -| `/planning/mission_planning/route_state` | autoware_adapi_v1_msgs/msg/RouteState | route state | -| `/planning/mission_planning/route` | autoware_planning_msgs/LaneletRoute | route | -| `debug/route_marker` | visualization_msgs/msg/MarkerArray | route marker for debug | -| `debug/goal_footprint` | visualization_msgs/msg/MarkerArray | goal footprint for debug | +| Name | Type | Description | +| ------------------------------------------------------ | ----------------------------------- | ------------------------ | +| `/planning/mission_planning/state` | tier4_planning_msgs/msg/RouteState | route state | +| `/planning/mission_planning/route` | autoware_planning_msgs/LaneletRoute | route | +| `/planning/mission_planning/route_selector/main/state` | tier4_planning_msgs/msg/RouteState | main route state | +| `/planning/mission_planning/route_selector/main/route` | autoware_planning_msgs/LaneletRoute | main route | +| `/planning/mission_planning/route_selector/mrm/state` | tier4_planning_msgs/msg/RouteState | mrm route state | +| `/planning/mission_planning/route_selector/mrm/route` | autoware_planning_msgs/LaneletRoute | mrm route | +| `~/debug/route_marker` | visualization_msgs/msg/MarkerArray | route marker for debug | +| `~/debug/goal_footprint` | visualization_msgs/msg/MarkerArray | goal footprint for debug | ## Route section @@ -168,26 +179,16 @@ And there are three use cases that require reroute. - Emergency route - Goal modification -![rerouting_interface](./media/rerouting_interface.svg) - #### Route change API -- `change_route_points` -- `change_route` - -This is route change that the application makes using the API. It is used when changing the destination while driving or when driving a divided loop route. When the vehicle is driving on a MRM route, normal rerouting by this interface is not allowed. +It is used when changing the destination while driving or when driving a divided loop route. When the vehicle is driving on a MRM route, normal rerouting by this interface is not allowed. #### Emergency route -- `set_mrm_route` -- `clear_mrm_route` - -This interface for the MRM that pulls over the road shoulder. It has to be stopped as soon as possible, so a reroute is required. The MRM route has priority over the normal route. And if MRM route is cleared, try to return to the normal route also with a rerouting safety check. +The interface for the MRM that pulls over the road shoulder. It has to be stopped as soon as possible, so a reroute is required. The MRM route has priority over the normal route. And if MRM route is cleared, try to return to the normal route also with a rerouting safety check. ##### Goal modification -- `modified_goal` - This is a goal change to pull over, avoid parked vehicles, and so on by a planning component. If the modified goal is outside the calculated route, a reroute is required. This goal modification is executed by checking the local environment and path safety as the vehicle actually approaches the destination. And this modification is allowed for both normal_route and mrm_route. The new route generated here is sent to the AD API so that it can also be referenced by the application. Note, however, that the specifications here are subject to change in the future. diff --git a/planning/mission_planner/media/architecture.drawio.svg b/planning/mission_planner/media/architecture.drawio.svg new file mode 100644 index 0000000000000..36be0d683bc06 --- /dev/null +++ b/planning/mission_planner/media/architecture.drawio.svg @@ -0,0 +1,725 @@ + + + + + + + + + + + + + + + +
+
+
+ mission planner +
+ main module +
+
+
+
+ mission planner... +
+
+ + + + +
+
+
+ state +
+
+
+
+ state +
+
+ + + + +
+
+
+ route +
+
+
+
+ route +
+
+ + + + +
+
+
+ set waypoint +
+
+
+
+ set waypoint +
+
+ + + + +
+
+
+ clear +
+
+
+
+ clear +
+
+ + + + +
+
+
+ set lanelet +
+
+
+
+ set lanelet +
+
+ + + + +
+
+
+ main route interface +
+
+
+
+ main route interface +
+
+ + + + + + + + + +
+
+
+ state +
+
+
+
+ state +
+
+ + + + +
+
+
+ route +
+
+
+
+ route +
+
+ + + + +
+
+
+ set waypoint +
+
+
+
+ set waypoint +
+
+ + + + +
+
+
+ clear +
+
+
+
+ clear +
+
+ + + + +
+
+
+ set lanelet +
+
+
+
+ set lanelet +
+
+ + + + +
+
+
+ MRM route interface +
+
+
+
+ MRM route interface +
+
+ + + + + + + +
+
+
+ API +
+
+
+
+ API +
+
+ + + + + + + +
+
+
+ fail safe +
+
+
+
+ fail safe +
+
+ + + + + + + + +
+
+
+ route id +
+
+
+
+ route id +
+
+ + + + + + +
+
+
+ route +
+
+
+
+ route +
+
+ + + + + + +
+
+
+ state +
+
+
+
+ state +
+
+ + + + +
+
+
+ request +
+
+
+
+ request +
+
+ + + + +
+
+
+ route id +
+
+
+
+ route id +
+
+ + + + + + +
+
+
+ route +
+
+
+
+ route +
+
+ + + + + + +
+
+
+ state +
+
+
+
+ state +
+
+ + + + + + +
+
+
+ in mrm +
+
+
+
+ in mrm +
+
+ + + + +
+
+
+ main route data +
+
+
+
+ main route data +
+
+ + + + +
+
+
+ MRM route data +
+
+
+
+ MRM route data +
+
+ + + + + + + + + + +
+
+
+ route +
+
+
+
+ route +
+
+ + + + + + +
+
+
+ state +
+
+
+
+ state +
+
+ + + + +
+
+
+ set waypoint +
+
+
+
+ set waypoint +
+
+ + + + +
+
+
+ clear +
+
+
+
+ clear +
+
+ + + + +
+
+
+ set lanelet +
+
+
+
+ set lanelet +
+
+ + + + +
+
+
+ route interface +
+
+
+
+ route interface +
+
+ + + + +
+
+
+ route selector +
+
+
+
+ route selector +
+
+ + + + + + +
+
+
+ behavior planner +
+
+
+
+ behavior planner +
+
+ + + + + + +
+
+
+ modify goal +
+
+
+
+ modify goal +
+
+ + + + + + + +
+
+
+ mission planner +
+ plugin module +
+
+
+
+ mission planner... +
+
+ + + + +
+
+
+ mission planner +
+
+
+
+ mission planner +
+
+ + + + + + + + + + + + + + + + + + + + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/mission_planner/media/rerouting_interface.svg b/planning/mission_planner/media/rerouting_interface.svg deleted file mode 100644 index e19c362611d30..0000000000000 --- a/planning/mission_planner/media/rerouting_interface.svg +++ /dev/null @@ -1,435 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-
- AD -
- API -
-
-
-
- AD... -
-
- - - - - - - - - - -
-
-
- Mission Planner -
-
-
-
- Mission Planner -
-
- - - - - - -
-
-
- set_route_points -
- (SetRoutePoints.srv) -
-
-
-
- set_route_points... -
-
- - - - - - -
-
-
- set_route -
- (SetRoute.srv) -
-
-
-
- set_route... -
-
- - - - - - -
-
-
- change_route_points -
- (SetRoutePoints.srv) -
-
-
-
- change_route_points... -
-
- - - - - - -
-
-
- change_route -
- (SetRoute.srv) -
-
-
-
- change_route... -
-
- - - - - - -
-
-
- route -
- (Route.msg) -
-
-
-
- route... -
-
- - - - - - -
-
-
- state -
- (RouteState.msg) -
-
-
-
- state... -
-
- - - - - - - - -
-
-
- behavior_path_planner -
-
-
-
- behavior_path_planner -
-
- - - - - - -
-
-
- modified_goal -
- (with uuid) -
-
-
-
- modified_goal... -
-
- - - - -
-
-
- route -
- (with uuid) -
-
-
-
- route... -
-
- - - - - - - - -
-
-
- MRM -
-
-
-
- MRM -
-
- - - - - - -
-
-
- T.B.D. -
- (Request MRM) -
-
-
-
- T.B.D.... -
-
- - - - - - -
-
-
- clear_route -
- (ClearRoute.srv) -
-
-
-
- clear_route... -
-
- - - - - - -
-
-
- clear_mrm_route -
-
-
-
- clear_mrm_route -
-
- - - - -
-
-
- ADAPI -
-
-
-
- ADAPI -
-
- - - - -
-
-
- planning -
-
-
-
- planning -
-
- - - - -
-
-
- system -
-
-
-
- system -
-
- - - - - - -
-
-
- set_mrm_route -
-
-
-
- set_mrm_route -
-
-
- - - - Text is not SVG - cannot display - - -
From 1524bdd813258e5d2b0e342821543da1cdc26092 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 8 Apr 2024 18:17:25 +0900 Subject: [PATCH 33/57] fix(behavior_path_planner): fix behavior_path_planner node to check occupancy_grid before running (#6752) Signed-off-by: Mamoru Sobue --- .../behavior_path_planner/src/behavior_path_planner_node.cpp | 4 ++++ 1 file changed, 4 insertions(+) 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 e41061a2ffbd2..1cea9e46cdb7b 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -312,6 +312,10 @@ bool BehaviorPathPlannerNode::isDataReady() return missing("operation_mode"); } + if (!planner_data_->occupancy_grid) { + return missing("occupancy_grid"); + } + return true; } From 86172857ecd6454d682ab38cba06a4230b94c5f5 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 8 Apr 2024 19:50:15 +0900 Subject: [PATCH 34/57] fix(avoidance): add update param to use rqt reconfigure (#6759) * fix(avoidance): add update param to use rqt reconfigure Signed-off-by: satoshi-ota * Update planning/behavior_path_avoidance_module/src/manager.cpp Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * Update planning/behavior_path_avoidance_module/src/manager.cpp Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> --------- Signed-off-by: satoshi-ota Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> --- .../parameter_helper.hpp | 4 + .../src/manager.cpp | 98 +++++++++++++++++++ 2 files changed, 102 insertions(+) diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp index abd0c017a6483..0a62eb5b33e8a 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp @@ -313,6 +313,10 @@ AvoidanceParameters getParameter(rclcpp::Node * node) p.use_shorten_margin_immediately = getOrDeclareParameter(*node, ns + "use_shorten_margin_immediately"); + if (p.policy_approval != "per_shift_line" && p.policy_approval != "per_avoidance_maneuver") { + throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); + } + if (p.policy_deceleration != "best_effort" && p.policy_deceleration != "reliable") { throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); } diff --git a/planning/behavior_path_avoidance_module/src/manager.cpp b/planning/behavior_path_avoidance_module/src/manager.cpp index 692e4260520f3..1f420baf4ae63 100644 --- a/planning/behavior_path_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_module/src/manager.cpp @@ -91,6 +91,76 @@ void AvoidanceModuleManager::updateModuleParams(const std::vectorupper_distance_for_polygon_expansion); } + { + const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) { + if (p->object_parameters.count(object_type) == 0) { + return; + } + updateParam(parameters, ns, p->object_parameters.at(object_type).is_avoidance_target); + }; + + const std::string ns = "avoidance.target_filtering."; + set_target_flag(ObjectClassification::CAR, ns + "target_type.car"); + set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck"); + set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer"); + set_target_flag(ObjectClassification::BUS, ns + "target_type.bus"); + set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian"); + set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle"); + set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle"); + set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown"); + + updateParam( + parameters, ns + "object_check_goal_distance", p->object_check_goal_distance); + updateParam( + parameters, ns + "object_check_return_pose_distance", p->object_check_return_pose_distance); + updateParam( + parameters, ns + "threshold_distance_object_is_on_center", + p->threshold_distance_object_is_on_center); + updateParam( + parameters, ns + "object_check_shiftable_ratio", p->object_check_shiftable_ratio); + updateParam( + parameters, ns + "object_check_min_road_shoulder_width", + p->object_check_min_road_shoulder_width); + updateParam( + parameters, ns + "object_last_seen_threshold", p->object_last_seen_threshold); + } + + { + const std::string ns = "avoidance.target_filtering.detection_area."; + updateParam(parameters, ns + "static", p->use_static_detection_area); + updateParam( + parameters, ns + "min_forward_distance", p->object_check_min_forward_distance); + updateParam( + parameters, ns + "max_forward_distance", p->object_check_max_forward_distance); + updateParam(parameters, ns + "backward_distance", p->object_check_backward_distance); + } + + { + const std::string ns = "avoidance.avoidance.lateral.avoidance_for_ambiguous_vehicle."; + updateParam(parameters, ns + "enable", p->enable_avoidance_for_ambiguous_vehicle); + updateParam( + parameters, ns + "closest_distance_to_wait_and_see", + p->closest_distance_to_wait_and_see_for_ambiguous_vehicle); + updateParam( + parameters, ns + "condition.time_threshold", p->time_threshold_for_ambiguous_vehicle); + updateParam( + parameters, ns + "condition.distance_threshold", p->distance_threshold_for_ambiguous_vehicle); + updateParam( + parameters, ns + "ignore_area.traffic_light.front_distance", + p->object_ignore_section_traffic_light_in_front_distance); + updateParam( + parameters, ns + "ignore_area.crosswalk.front_distance", + p->object_ignore_section_crosswalk_in_front_distance); + updateParam( + parameters, ns + "ignore_area.crosswalk.behind_distance", + p->object_ignore_section_crosswalk_behind_distance); + } + + { + const std::string ns = "avoidance.target_filtering.intersection."; + updateParam(parameters, ns + "yaw_deviation", p->object_check_yaw_deviation); + } + { const std::string ns = "avoidance.avoidance.lateral."; updateParam( @@ -107,6 +177,7 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "min_prepare_time", p->min_prepare_time); updateParam(parameters, ns + "max_prepare_time", p->max_prepare_time); + updateParam(parameters, ns + "min_prepare_distance", p->min_prepare_distance); updateParam(parameters, ns + "min_slow_down_speed", p->min_slow_down_speed); updateParam(parameters, ns + "buf_slow_down_speed", p->buf_slow_down_speed); } @@ -117,6 +188,33 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "stop_buffer", p->stop_buffer); } + { + const std::string ns = "avoidance.policy."; + updateParam(parameters, ns + "make_approval_request", p->policy_approval); + updateParam(parameters, ns + "deceleration", p->policy_deceleration); + updateParam(parameters, ns + "lateral_margin", p->policy_lateral_margin); + updateParam( + parameters, ns + "use_shorten_margin_immediately", p->use_shorten_margin_immediately); + + if (p->policy_approval != "per_shift_line" && p->policy_approval != "per_avoidance_maneuver") { + RCLCPP_ERROR( + rclcpp::get_logger(__func__), + "invalid policy. please select 'per_shift_line' or 'per_avoidance_maneuver'."); + } + + if (p->policy_deceleration != "best_effort" && p->policy_deceleration != "reliable") { + RCLCPP_ERROR( + rclcpp::get_logger(__func__), + "invalid deceleration policy. Please select 'best_effort' or 'reliable'."); + } + + if (p->policy_lateral_margin != "best_effort" && p->policy_lateral_margin != "reliable") { + RCLCPP_ERROR( + rclcpp::get_logger(__func__), + "invalid lateral margin policy. Please select 'best_effort' or 'reliable'."); + } + } + { const std::string ns = "avoidance.constrains.lateral."; From b98a21a5ffb71f7e33dc183cfc90c0196240cf7a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 9 Apr 2024 12:13:57 +0900 Subject: [PATCH 35/57] feat(avoidance): limit acceleration during avoidance maneuver (#6698) Signed-off-by: satoshi-ota --- .../config/avoidance.param.yaml | 3 +- .../data_structs.hpp | 3 + .../behavior_path_avoidance_module/helper.hpp | 75 +++++++++++++++++++ .../parameter_helper.hpp | 2 + .../behavior_path_avoidance_module/scene.hpp | 6 ++ .../src/manager.cpp | 13 ++++ .../src/scene.cpp | 47 ++++++++++++ 7 files changed, 148 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml index 3c3a086a3514d..b7b8d8434b9c4 100644 --- a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml +++ b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml @@ -287,7 +287,8 @@ nominal_jerk: 0.5 # [m/sss] max_deceleration: -1.5 # [m/ss] max_jerk: 1.0 # [m/sss] - max_acceleration: 1.0 # [m/ss] + max_acceleration: 0.5 # [m/ss] + min_velocity_to_limit_max_acceleration: 2.78 # [m/ss] shift_line_pipeline: trim: diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp index 686e4023bc7c2..fd841ede37e70 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp @@ -143,6 +143,9 @@ struct AvoidanceParameters // To prevent large acceleration while avoidance. double max_acceleration{0.0}; + // To prevent large acceleration while avoidance. + double min_velocity_to_limit_max_acceleration{0.0}; + // upper distance for envelope polygon expansion. double upper_distance_for_polygon_expansion{0.0}; diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp index 6d2eb81b328f4..4ff02df97bd89 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp @@ -24,6 +24,7 @@ #include #include #include +#include #include namespace behavior_path_planner::helper::avoidance @@ -32,7 +33,10 @@ namespace behavior_path_planner::helper::avoidance using behavior_path_planner::PathShifter; using behavior_path_planner::PlannerData; using motion_utils::calcDecelDistWithJerkAndAccConstraints; +using motion_utils::calcLongitudinalOffsetPose; +using motion_utils::calcSignedArcLength; using motion_utils::findNearestIndex; +using tier4_autoware_utils::getPose; class AvoidanceHelper { @@ -61,6 +65,11 @@ class AvoidanceHelper geometry_msgs::msg::Pose getEgoPose() const { return data_->self_odometry->pose.pose; } + geometry_msgs::msg::Point getEgoPosition() const + { + return data_->self_odometry->pose.pose.position; + } + static size_t getConstraintsMapIndex(const double velocity, const std::vector & values) { const auto itr = std::find_if( @@ -262,6 +271,20 @@ class AvoidanceHelper return *itr; } + std::pair getDistanceToAccelEndPoint(const PathWithLaneId & path) + { + updateAccelEndPoint(path); + + if (!max_v_point_.has_value()) { + return std::make_pair(0.0, std::numeric_limits::max()); + } + + const auto start_idx = data_->findEgoIndex(path.points); + const auto distance = + calcSignedArcLength(path.points, start_idx, max_v_point_.value().first.position); + return std::make_pair(distance, max_v_point_.value().second); + } + double getFeasibleDecelDistance( const double target_velocity, const bool use_hard_constraints = true) const { @@ -367,6 +390,56 @@ class AvoidanceHelper return true; } + void updateAccelEndPoint(const PathWithLaneId & path) + { + const auto & p = parameters_; + const auto & a_now = data_->self_acceleration->accel.accel.linear.x; + if (a_now < 0.0) { + max_v_point_ = std::nullopt; + return; + } + + if (getEgoSpeed() < p->min_velocity_to_limit_max_acceleration) { + max_v_point_ = std::nullopt; + return; + } + + if (max_v_point_.has_value()) { + return; + } + + const auto v0 = getEgoSpeed() + p->buf_slow_down_speed; + + const auto t_neg_jerk = std::max(0.0, a_now - p->max_acceleration) / p->max_jerk; + const auto v_neg_jerk = v0 + a_now * t_neg_jerk + std::pow(t_neg_jerk, 2.0) / 2.0; + const auto x_neg_jerk = v0 * t_neg_jerk + a_now * std::pow(t_neg_jerk, 2.0) / 2.0 + + p->max_jerk * std::pow(t_neg_jerk, 3.0) / 6.0; + + const auto & v_max = data_->parameters.max_vel; + if (v_max < v_neg_jerk) { + max_v_point_ = std::nullopt; + return; + } + + const auto t_max_accel = (v_max - v_neg_jerk) / p->max_acceleration; + const auto x_max_accel = + v_neg_jerk * t_max_accel + p->max_acceleration * std::pow(t_max_accel, 2.0) / 2.0; + + const auto point = + calcLongitudinalOffsetPose(path.points, getEgoPosition(), x_neg_jerk + x_max_accel); + if (point.has_value()) { + max_v_point_ = std::make_pair(point.value(), v_max); + return; + } + + const auto x_end = calcSignedArcLength(path.points, getEgoPosition(), path.points.size() - 1); + const auto t_end = + (std::sqrt(v0 * v0 + 2.0 * p->max_acceleration * x_end) - v0) / p->max_acceleration; + const auto v_end = v0 + p->max_acceleration * t_end; + + max_v_point_ = std::make_pair(getPose(path.points.back()), v_end); + } + void reset() { prev_reference_path_ = PathWithLaneId(); @@ -417,6 +490,8 @@ class AvoidanceHelper ShiftedPath prev_linear_shift_path_; lanelet::ConstLanelets prev_driving_lanes_; + + std::optional> max_v_point_; }; } // namespace behavior_path_planner::helper::avoidance diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp index 0a62eb5b33e8a..fbfec58abe4da 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp @@ -334,6 +334,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node) p.max_deceleration = getOrDeclareParameter(*node, ns + "max_deceleration"); p.max_jerk = getOrDeclareParameter(*node, ns + "max_jerk"); p.max_acceleration = getOrDeclareParameter(*node, ns + "max_acceleration"); + p.min_velocity_to_limit_max_acceleration = + getOrDeclareParameter(*node, ns + "min_velocity_to_limit_max_acceleration"); } // constraints (lateral) diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp index 5125191a6e544..899ec99cb0d3b 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp @@ -233,6 +233,12 @@ class AvoidanceModule : public SceneModuleInterface */ void insertPrepareVelocity(ShiftedPath & shifted_path) const; + /** + * @brief insert max velocity in output path to limit acceleration. + * @param target path. + */ + void insertAvoidanceVelocity(ShiftedPath & shifted_path) const; + /** * @brief calculate stop distance based on object's overhang. * @param stop distance. diff --git a/planning/behavior_path_avoidance_module/src/manager.cpp b/planning/behavior_path_avoidance_module/src/manager.cpp index 1f420baf4ae63..5ce63987621ed 100644 --- a/planning/behavior_path_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_module/src/manager.cpp @@ -244,6 +244,19 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "nominal_deceleration", p->nominal_deceleration); + updateParam(parameters, ns + "nominal_jerk", p->nominal_jerk); + updateParam(parameters, ns + "max_deceleration", p->max_deceleration); + updateParam(parameters, ns + "max_jerk", p->max_jerk); + updateParam(parameters, ns + "max_acceleration", p->max_acceleration); + updateParam( + parameters, ns + "min_velocity_to_limit_max_acceleration", + p->min_velocity_to_limit_max_acceleration); + } + { const std::string ns = "avoidance.shift_line_pipeline."; updateParam( diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index 12c59daef93ad..b22a4bf53eab0 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -686,6 +686,7 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif } insertPrepareVelocity(path); + insertAvoidanceVelocity(path); switch (data.state) { case AvoidanceState::NOT_AVOID: { @@ -1725,6 +1726,52 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const shifted_path.path.points, start_idx, distance_to_object); } +void AvoidanceModule::insertAvoidanceVelocity(ShiftedPath & shifted_path) const +{ + const auto & data = avoid_data_; + + // do nothing if no shift line is approved. + if (path_shifter_.getShiftLines().empty()) { + return; + } + + // do nothing if there is no avoidance target. + if (data.target_objects.empty()) { + return; + } + + const auto [distance_to_accel_end_point, v_max] = + helper_->getDistanceToAccelEndPoint(shifted_path.path); + if (distance_to_accel_end_point < 1e-3) { + return; + } + + const auto start_idx = planner_data_->findEgoIndex(shifted_path.path.points); + for (size_t i = start_idx; i < shifted_path.path.points.size(); ++i) { + const auto distance_from_ego = calcSignedArcLength(shifted_path.path.points, start_idx, i); + + // slow down speed is inserted only in front of the object. + const auto accel_distance = distance_to_accel_end_point - distance_from_ego; + if (accel_distance < 0.0) { + break; + } + + const double v_target_square = + v_max * v_max - 2.0 * parameters_->max_acceleration * accel_distance; + if (v_target_square < 1e-3) { + break; + } + + // target speed with nominal jerk limits. + const double v_target = std::max(getEgoSpeed(), std::sqrt(v_target_square)); + const double v_original = shifted_path.path.points.at(i).point.longitudinal_velocity_mps; + shifted_path.path.points.at(i).point.longitudinal_velocity_mps = std::min(v_original, v_target); + } + + slow_pose_ = motion_utils::calcLongitudinalOffsetPose( + shifted_path.path.points, start_idx, distance_to_accel_end_point); +} + std::shared_ptr AvoidanceModule::get_debug_msg_array() const { debug_data_.avoidance_debug_msg_array.header.stamp = clock_->now(); From d6824423c3f6cd75fd451fd6bdef7a53aea77719 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 9 Apr 2024 12:21:08 +0900 Subject: [PATCH 36/57] fix(tier4_autoware_utils): fix `-Werror=unused-parameter` (#6764) fix(tier4_autoware_utils): fix -Werror=unused-parameter Signed-off-by: satoshi-ota --- .../include/tier4_autoware_utils/ros/polling_subscriber.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp index f4d230e15dcf1..f8d5baaf02777 100644 --- a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp @@ -38,7 +38,8 @@ class InterProcessPollingSubscriber noexec_subscription_options.callback_group = noexec_callback_group; subscriber_ = node->create_subscription( - topic_name, rclcpp::QoS{1}, [node](const typename T::ConstSharedPtr msg) { assert(false); }, + topic_name, rclcpp::QoS{1}, + [node]([[maybe_unused]] const typename T::ConstSharedPtr msg) { assert(false); }, noexec_subscription_options); }; bool updateLatestData() From b09501e78e8cb09d7e91d264389114190255a39e Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 9 Apr 2024 13:01:35 +0900 Subject: [PATCH 37/57] feat(lane_change): use external velocity limit in safety check (#6760) * feat(lane_change): use external velocity limit in safety check Signed-off-by: Muhammad Zulfaqar * style(pre-commit): autofix * Minor refactoring Signed-off-by: Muhammad Zulfaqar * Fix spell check and remove headers Signed-off-by: Muhammad Zulfaqar Azmi * Add warning Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Signed-off-by: Muhammad Zulfaqar Azmi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../behavior_path_lane_change_module/scene.hpp | 2 ++ .../src/scene.cpp | 13 ++++++++++++- .../behavior_path_planner_node.hpp | 6 ++++++ .../src/behavior_path_planner_node.cpp | 18 ++++++++++++++++++ .../data_manager.hpp | 3 +++ .../utils/path_safety_checker/safety_check.hpp | 2 +- .../utils/path_safety_checker/safety_check.cpp | 10 ++++++---- 7 files changed, 48 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp index 0eec0ce75f622..7a76daff4bc55 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp @@ -172,6 +172,8 @@ class NormalLaneChange : public LaneChangeBase bool isVehicleStuck( const lanelet::ConstLanelets & current_lanes, const double obstacle_check_distance) const; + double get_max_velocity_for_safety_check() const; + bool isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const; bool check_prepare_phase() const; diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index 3a4a44ef33edb..db96f7c83d72a 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -1967,7 +1967,7 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( for (const auto & obj_path : obj_predicted_paths) { const auto collided_polygons = utils::path_safety_checker::getCollidedPolygons( path, ego_predicted_path, obj, obj_path, common_parameters, rss_params, 1.0, - current_debug_data.second); + get_max_velocity_for_safety_check(), current_debug_data.second); if (collided_polygons.empty()) { utils::path_safety_checker::updateCollisionCheckDebugMap( @@ -2062,6 +2062,17 @@ bool NormalLaneChange::isVehicleStuck( return false; } +double NormalLaneChange::get_max_velocity_for_safety_check() const +{ + const auto external_velocity_limit_ptr = planner_data_->external_limit_max_velocity; + if (external_velocity_limit_ptr) { + return std::min( + static_cast(external_velocity_limit_ptr->max_velocity), getCommonParam().max_vel); + } + + return getCommonParam().max_vel; +} + bool NormalLaneChange::isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const { if (current_lanes.empty()) { 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 99e312f98f100..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 @@ -40,6 +40,7 @@ #include #include #include +#include #include #include @@ -103,6 +104,8 @@ class BehaviorPathPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr modified_goal_publisher_; rclcpp::Publisher::SharedPtr stop_reason_publisher_; rclcpp::Publisher::SharedPtr reroute_availability_publisher_; + rclcpp::Subscription::SharedPtr + external_limit_max_velocity_subscriber_; rclcpp::TimerBase::SharedPtr timer_; std::map::SharedPtr> path_candidate_publishers_; @@ -142,6 +145,9 @@ class BehaviorPathPlannerNode : public rclcpp::Node void onRoute(const LaneletRoute::ConstSharedPtr route_msg); void onOperationMode(const OperationModeState::ConstSharedPtr msg); void onLateralOffset(const LateralOffset::ConstSharedPtr msg); + void on_external_velocity_limiter( + const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg); + SetParametersResult onSetParam(const std::vector & parameters); OnSetParametersCallbackHandle::SharedPtr m_set_param_res; 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 1cea9e46cdb7b..d250fd97c3aec 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -112,6 +112,11 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod current_scenario_ = std::make_shared(*msg); }, createSubscriptionOptions(this)); + external_limit_max_velocity_subscriber_ = + create_subscription( + "/planning/scenario_planning/max_velocity", 1, + std::bind(&BehaviorPathPlannerNode::on_external_velocity_limiter, this, _1), + createSubscriptionOptions(this)); // route_handler vector_map_subscriber_ = create_subscription( @@ -821,6 +826,19 @@ void BehaviorPathPlannerNode::onOperationMode(const OperationModeState::ConstSha const std::lock_guard lock(mutex_pd_); planner_data_->operation_mode = msg; } + +void BehaviorPathPlannerNode::on_external_velocity_limiter( + const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg) +{ + // Note: Using this parameter during path planning might cause unexpected deceleration or jerk. + // Therefore, do not use it for anything other than safety checks. + if (!msg) { + return; + } + + const std::lock_guard lock(mutex_pd_); + planner_data_->external_limit_max_velocity = msg; +} void BehaviorPathPlannerNode::onLateralOffset(const LateralOffset::ConstSharedPtr msg) { std::lock_guard lock(mutex_pd_); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp index d196f2bc551bb..09f3c2c66bcd4 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp @@ -38,6 +38,7 @@ #include #include #include +#include #include #include @@ -65,6 +66,7 @@ using route_handler::RouteHandler; using tier4_planning_msgs::msg::LateralOffset; using PlanResult = PathWithLaneId::SharedPtr; using lanelet::TrafficLight; +using tier4_planning_msgs::msg::VelocityLimit; using unique_identifier_msgs::msg::UUID; struct TrafficSignalStamped @@ -161,6 +163,7 @@ struct PlannerData std::map traffic_light_id_map; BehaviorPathPlannerParameters parameters{}; drivable_area_expansion::DrivableAreaExpansionParameters drivable_area_expansion_parameters{}; + VelocityLimit::ConstSharedPtr external_limit_max_velocity{}; mutable std::vector drivable_area_expansion_prev_path_poses{}; mutable std::vector drivable_area_expansion_prev_curvatures{}; diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp index 13009d5114439..53c4706e49c10 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp @@ -141,7 +141,7 @@ std::vector getCollidedPolygons( const ExtendedPredictedObject & target_object, const PredictedPathWithPolygon & target_object_path, const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters, - const double hysteresis_factor, CollisionCheckDebug & debug); + const double hysteresis_factor, const double max_velocity_limit, CollisionCheckDebug & debug); bool checkPolygonsIntersects( const std::vector & polys_1, const std::vector & polys_2); diff --git a/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp index e15a3c164bef1..6390c45376b37 100644 --- a/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp @@ -26,6 +26,8 @@ #include #include +#include + namespace behavior_path_planner::utils::path_safety_checker { @@ -560,7 +562,7 @@ bool checkCollision( { const auto collided_polygons = getCollidedPolygons( planned_path, predicted_ego_path, target_object, target_object_path, common_parameters, - rss_parameters, hysteresis_factor, debug); + rss_parameters, hysteresis_factor, std::numeric_limits::max(), debug); return collided_polygons.empty(); } @@ -570,7 +572,7 @@ std::vector getCollidedPolygons( const ExtendedPredictedObject & target_object, const PredictedPathWithPolygon & target_object_path, const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters, - double hysteresis_factor, CollisionCheckDebug & debug) + double hysteresis_factor, const double max_velocity_limit, CollisionCheckDebug & debug) { { debug.ego_predicted_path = predicted_ego_path; @@ -586,7 +588,7 @@ std::vector getCollidedPolygons( // get object information at current time const auto & obj_pose = obj_pose_with_poly.pose; const auto & obj_polygon = obj_pose_with_poly.poly; - const auto & object_velocity = obj_pose_with_poly.velocity; + const auto object_velocity = obj_pose_with_poly.velocity; // get ego information at current time // Note: we can create these polygons in advance. However, it can decrease the readability and @@ -599,7 +601,7 @@ std::vector getCollidedPolygons( } const auto & ego_pose = interpolated_data->pose; const auto & ego_polygon = interpolated_data->poly; - const auto & ego_velocity = interpolated_data->velocity; + const auto ego_velocity = std::min(interpolated_data->velocity, max_velocity_limit); // check overlap if (boost::geometry::overlaps(ego_polygon, obj_polygon)) { From d340d10fbbbb04eb1ba614bb05f3f4d3b110792c Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 9 Apr 2024 15:24:21 +0900 Subject: [PATCH 38/57] fix(multi_object_tracker): mot timer bug fix (#6775) * fix: set object timestamp type to follow node time fix: remove comment Signed-off-by: Taekjin LEE * fix: add initialization checkers Signed-off-by: Taekjin LEE * fix: timestamp initialization Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../multi_object_tracker/src/debugger.cpp | 40 ++++++++++++------- .../src/multi_object_tracker_core.cpp | 11 +++-- 2 files changed, 32 insertions(+), 19 deletions(-) diff --git a/perception/multi_object_tracker/src/debugger.cpp b/perception/multi_object_tracker/src/debugger.cpp index 4304afbe2e055..b5632a13e78fc 100644 --- a/perception/multi_object_tracker/src/debugger.cpp +++ b/perception/multi_object_tracker/src/debugger.cpp @@ -18,12 +18,7 @@ #include -TrackerDebugger::TrackerDebugger(rclcpp::Node & node) -: diagnostic_updater_(&node), - node_(node), - last_input_stamp_(node.now()), - stamp_process_start_(node.now()), - stamp_publish_output_(node.now()) +TrackerDebugger::TrackerDebugger(rclcpp::Node & node) : diagnostic_updater_(&node), node_(node) { // declare debug parameters to decide whether to publish debug topics loadParameters(); @@ -39,7 +34,15 @@ TrackerDebugger::TrackerDebugger(rclcpp::Node & node) "debug/tentative_objects", rclcpp::QoS{1}); } - // initialize stop watch and diagnostics + // initialize timestamps + const rclcpp::Time now = node_.now(); + last_input_stamp_ = now; + stamp_process_start_ = now; + stamp_process_end_ = now; + stamp_publish_start_ = now; + stamp_publish_output_ = now; + + // setup diagnostics setupDiagnostics(); } @@ -73,7 +76,11 @@ void TrackerDebugger::loadParameters() void TrackerDebugger::checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat) { - const double delay = pipeline_latency_ms_; // [s] + if (!is_initialized_) { + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Measurement time is not set."); + return; + } + const double & delay = pipeline_latency_ms_; // [s] if (delay == 0.0) { stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is not calculated."); @@ -127,18 +134,21 @@ void TrackerDebugger::startPublishTime(const rclcpp::Time & now) void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time) { - const auto current_time = now; + // if the measurement time is not set, do not publish debug information + if (!is_initialized_) return; + // pipeline latency: time from sensor measurement to publish, used for 'checkDelay' - pipeline_latency_ms_ = (current_time - last_input_stamp_).seconds() * 1e3; - if (debug_settings_.publish_processing_time && is_initialized_) { + pipeline_latency_ms_ = (now - last_input_stamp_).seconds() * 1e3; + + if (debug_settings_.publish_processing_time) { // processing latency: time between input and publish - double processing_latency_ms = ((current_time - stamp_process_start_).seconds()) * 1e3; + double processing_latency_ms = ((now - stamp_process_start_).seconds()) * 1e3; // processing time: only the time spent in the tracking processes - double processing_time_ms = ((current_time - stamp_publish_start_).seconds() + + double processing_time_ms = ((now - stamp_publish_start_).seconds() + (stamp_process_end_ - stamp_process_start_).seconds()) * 1e3; // cycle time: time between two consecutive publish - double cyclic_time_ms = (current_time - stamp_publish_output_).seconds() * 1e3; + double cyclic_time_ms = (now - stamp_publish_output_).seconds() * 1e3; // measurement to tracked-object time: time from the sensor measurement to the publishing object // time If there is not latency compensation, this value is zero double measurement_to_object_ms = (object_time - last_input_stamp_).seconds() * 1e3; @@ -155,5 +165,5 @@ void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Tim processing_time_publisher_->publish( "debug/meas_to_tracked_object_ms", measurement_to_object_ms); } - stamp_publish_output_ = current_time; + stamp_publish_output_ = now; } diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index aacd37766e8b0..8ff69ffaeaa9a 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -135,10 +135,14 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) void MultiObjectTracker::onMeasurement( const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg) { + // Get the time of the measurement + const rclcpp::Time measurement_time = + rclcpp::Time(input_objects_msg->header.stamp, this->now().get_clock_type()); + /* keep the latest input stamp and check transform*/ - debugger_->startMeasurementTime(this->now(), rclcpp::Time(input_objects_msg->header.stamp)); - const auto self_transform = getTransformAnonymous( - tf_buffer_, "base_link", world_frame_id_, input_objects_msg->header.stamp); + debugger_->startMeasurementTime(this->now(), measurement_time); + const auto self_transform = + getTransformAnonymous(tf_buffer_, "base_link", world_frame_id_, measurement_time); if (!self_transform) { return; } @@ -150,7 +154,6 @@ void MultiObjectTracker::onMeasurement( return; } /* tracker prediction */ - const rclcpp::Time measurement_time = input_objects_msg->header.stamp; for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) { (*itr)->predict(measurement_time); } From f5c30eb55e52d52412a71369cb44eaab775f8ea4 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 9 Apr 2024 16:15:15 +0900 Subject: [PATCH 39/57] feat(multi_object_tracker): reduce publish delay (#6710) * feat: implement a new publish timer Signed-off-by: Taekjin LEE * chore: add comments for new variables Signed-off-by: Taekjin LEE * fix: variable name was wrong Signed-off-by: Taekjin LEE fix: reduce lower limit of publish interval Signed-off-by: Taekjin LEE fix: enlarge publish range upper limit Signed-off-by: Taekjin LEE fix: set parameter tested and agreed Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../multi_object_tracker_core.hpp | 10 ++-- .../src/multi_object_tracker_core.cpp | 48 +++++++++++++------ 2 files changed, 41 insertions(+), 17 deletions(-) diff --git a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp index 94cc7185bd518..fe41f97cb5a77 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp @@ -58,7 +58,11 @@ class MultiObjectTracker : public rclcpp::Node tracked_objects_pub_; rclcpp::Subscription::SharedPtr detected_object_sub_; - rclcpp::TimerBase::SharedPtr publish_timer_; // publish timer + + // publish timer + rclcpp::TimerBase::SharedPtr publish_timer_; + rclcpp::Time last_published_time_; + double publisher_period_; // debugger class std::unique_ptr debugger_; @@ -79,14 +83,14 @@ class MultiObjectTracker : public rclcpp::Node std::unique_ptr data_association_; void checkTrackerLifeCycle( - std::list> & list_tracker, const rclcpp::Time & time, - const geometry_msgs::msg::Transform & self_transform); + std::list> & list_tracker, const rclcpp::Time & time); void sanitizeTracker( std::list> & list_tracker, const rclcpp::Time & time); std::shared_ptr createNewTracker( const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) const; + void checkAndPublish(const rclcpp::Time & time); void publish(const rclcpp::Time & time) const; inline bool shouldTrackerPublish(const std::shared_ptr tracker) const; }; diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index 8ff69ffaeaa9a..785038fb513c9 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -68,6 +68,7 @@ boost::optional getTransformAnonymous( MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) : rclcpp::Node("multi_object_tracker", node_options), + last_published_time_(this->now()), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { @@ -83,7 +84,7 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) create_publisher("output", rclcpp::QoS{1}); // Parameters - double publish_rate = declare_parameter("publish_rate"); + double publish_rate = declare_parameter("publish_rate"); // [hz] world_frame_id_ = declare_parameter("world_frame_id"); bool enable_delay_compensation{declare_parameter("enable_delay_compensation")}; @@ -94,11 +95,15 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) this->get_node_base_interface(), this->get_node_timers_interface()); tf_buffer_.setCreateTimerInterface(cti); - // Create ROS time based timer + // Create ROS time based timer. + // If the delay compensation is enabled, the timer is used to publish the output at the correct + // time. if (enable_delay_compensation) { - const auto period_ns = rclcpp::Rate(publish_rate).period(); + publisher_period_ = 1.0 / publish_rate; // [s] + constexpr double timer_multiplier = 20.0; // 20 times frequent for publish timing check + const auto timer_period = rclcpp::Rate(publish_rate * timer_multiplier).period(); publish_timer_ = rclcpp::create_timer( - this, get_clock(), period_ns, std::bind(&MultiObjectTracker::onTimer, this)); + this, get_clock(), timer_period, std::bind(&MultiObjectTracker::onTimer, this)); } const auto tmp = this->declare_parameter>("can_assign_matrix"); @@ -179,7 +184,7 @@ void MultiObjectTracker::onMeasurement( } /* life cycle check */ - checkTrackerLifeCycle(list_tracker_, measurement_time, *self_transform); + checkTrackerLifeCycle(list_tracker_, measurement_time); /* sanitize trackers */ sanitizeTracker(list_tracker_, measurement_time); @@ -198,7 +203,14 @@ void MultiObjectTracker::onMeasurement( // Publish objects if the timer is not enabled if (publish_timer_ == nullptr) { + // Publish if the delay compensation is disabled publish(measurement_time); + } else { + // Publish if the next publish time is close + const double minimum_publish_interval = publisher_period_ * 0.70; // 70% of the period + if ((this->now() - last_published_time_).seconds() > minimum_publish_interval) { + checkAndPublish(this->now()); + } } } @@ -232,24 +244,32 @@ std::shared_ptr MultiObjectTracker::createNewTracker( void MultiObjectTracker::onTimer() { const rclcpp::Time current_time = this->now(); - const auto self_transform = - getTransformAnonymous(tf_buffer_, world_frame_id_, "base_link", current_time); - if (!self_transform) { - return; + // check the publish period + const auto elapsed_time = (current_time - last_published_time_).seconds(); + // if the elapsed time is over the period, publish objects with prediction + constexpr double maximum_latency_ratio = 1.11; // 11% margin + const double maximum_publish_latency = publisher_period_ * maximum_latency_ratio; + if (elapsed_time > maximum_publish_latency) { + checkAndPublish(current_time); } +} +void MultiObjectTracker::checkAndPublish(const rclcpp::Time & time) +{ /* life cycle check */ - checkTrackerLifeCycle(list_tracker_, current_time, *self_transform); + checkTrackerLifeCycle(list_tracker_, time); /* sanitize trackers */ - sanitizeTracker(list_tracker_, current_time); + sanitizeTracker(list_tracker_, time); // Publish - publish(current_time); + publish(time); + + // Update last published time + last_published_time_ = this->now(); } void MultiObjectTracker::checkTrackerLifeCycle( - std::list> & list_tracker, const rclcpp::Time & time, - [[maybe_unused]] const geometry_msgs::msg::Transform & self_transform) + std::list> & list_tracker, const rclcpp::Time & time) { /* params */ constexpr float max_elapsed_time = 1.0; From 094f3e6710f06acec009d3ddad41aafefb000381 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Tue, 9 Apr 2024 20:36:43 +0900 Subject: [PATCH 40/57] chore(ground_segmentation): add tuning param (#6753) * chore(ground_segmentation): add tuning param Signed-off-by: badai-nguyen * fix: and param into yaml file Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * chore: refactor Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen --- .../config/ground_segmentation.param.yaml | 1 + .../config/scan_ground_filter.param.yaml | 1 + .../ground_segmentation/docs/scan-ground-filter.md | 1 + .../scan_ground_filter_nodelet.hpp | 4 +++- .../src/scan_ground_filter_nodelet.cpp | 11 +++++++---- .../test/test_scan_ground_filter.cpp | 3 +++ 6 files changed, 16 insertions(+), 5 deletions(-) diff --git a/perception/ground_segmentation/config/ground_segmentation.param.yaml b/perception/ground_segmentation/config/ground_segmentation.param.yaml index 756882391183e..594ef1fe974b2 100644 --- a/perception/ground_segmentation/config/ground_segmentation.param.yaml +++ b/perception/ground_segmentation/config/ground_segmentation.param.yaml @@ -33,3 +33,4 @@ center_pcl_shift: 0.0 radial_divider_angle_deg: 1.0 use_recheck_ground_cluster: true + use_lowest_point: true diff --git a/perception/ground_segmentation/config/scan_ground_filter.param.yaml b/perception/ground_segmentation/config/scan_ground_filter.param.yaml index bc02a1ab7e6e7..35d494a620b19 100644 --- a/perception/ground_segmentation/config/scan_ground_filter.param.yaml +++ b/perception/ground_segmentation/config/scan_ground_filter.param.yaml @@ -15,3 +15,4 @@ center_pcl_shift: 0.0 radial_divider_angle_deg: 1.0 use_recheck_ground_cluster: true + use_lowest_point: true diff --git a/perception/ground_segmentation/docs/scan-ground-filter.md b/perception/ground_segmentation/docs/scan-ground-filter.md index 21df6fa6ea1b9..d4eb9c6f3addf 100644 --- a/perception/ground_segmentation/docs/scan-ground-filter.md +++ b/perception/ground_segmentation/docs/scan-ground-filter.md @@ -50,6 +50,7 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref | `low_priority_region_x` | float | -20.0 | The non-zero x threshold in back side from which small objects detection is low priority [m] | | `elevation_grid_mode` | bool | true | Elevation grid scan mode option | | `use_recheck_ground_cluster` | bool | true | Enable recheck ground cluster | +| `use_lowest_point` | bool | true | to select lowest point for reference in recheck ground cluster, otherwise select middle point | ## Assumptions / Known limits diff --git a/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp b/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp index d017d06929702..d97bbaa2118e5 100644 --- a/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp +++ b/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp @@ -194,6 +194,8 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter split_height_distance_; // useful for close points bool use_virtual_ground_point_; bool use_recheck_ground_cluster_; // to enable recheck ground cluster + bool use_lowest_point_; // to select lowest point for reference in recheck ground cluster, + // otherwise select middle point size_t radial_dividers_num_; VehicleInfo vehicle_info_; @@ -258,7 +260,7 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter * @param non_ground_indices Output non-ground PointCloud indices */ void recheckGroundCluster( - PointsCentroid & gnd_cluster, const float non_ground_threshold, + PointsCentroid & gnd_cluster, const float non_ground_threshold, const bool use_lowest_point, pcl::PointIndices & non_ground_indices); /*! * Returns the resulting complementary PointCloud, one with the points kept diff --git a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp index 7a0333d95075b..34573b564fa36 100644 --- a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp @@ -57,6 +57,7 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & split_height_distance_ = declare_parameter("split_height_distance"); use_virtual_ground_point_ = declare_parameter("use_virtual_ground_point"); use_recheck_ground_cluster_ = declare_parameter("use_recheck_ground_cluster"); + use_lowest_point_ = declare_parameter("use_lowest_point"); radial_dividers_num_ = std::ceil(2.0 * M_PI / radial_divider_angle_rad_); vehicle_info_ = VehicleInfoUtil(*this).getVehicleInfo(); @@ -316,14 +317,15 @@ void ScanGroundFilterComponent::checkBreakGndGrid( } void ScanGroundFilterComponent::recheckGroundCluster( - PointsCentroid & gnd_cluster, const float non_ground_threshold, + PointsCentroid & gnd_cluster, const float non_ground_threshold, const bool use_lowest_point, pcl::PointIndices & non_ground_indices) { - const float min_gnd_height = gnd_cluster.getMinHeight(); + float reference_height = + use_lowest_point ? gnd_cluster.getMinHeight() : gnd_cluster.getAverageHeight(); const pcl::PointIndices & gnd_indices = gnd_cluster.getIndicesRef(); const std::vector & height_list = gnd_cluster.getHeightListRef(); for (size_t i = 0; i < height_list.size(); ++i) { - if (height_list.at(i) >= min_gnd_height + non_ground_threshold) { + if (height_list.at(i) >= reference_height + non_ground_threshold) { non_ground_indices.indices.push_back(gnd_indices.indices.at(i)); } } @@ -403,7 +405,8 @@ void ScanGroundFilterComponent::classifyPointCloudGridScan( if (p->grid_id > prev_p->grid_id && ground_cluster.getAverageRadius() > 0.0) { // check if the prev grid have ground point cloud if (use_recheck_ground_cluster_) { - recheckGroundCluster(ground_cluster, non_ground_height_threshold_, out_no_ground_indices); + recheckGroundCluster( + ground_cluster, non_ground_height_threshold_, use_lowest_point_, out_no_ground_indices); } curr_gnd_grid.radius = ground_cluster.getAverageRadius(); curr_gnd_grid.avg_height = ground_cluster.getAverageHeight(); diff --git a/perception/ground_segmentation/test/test_scan_ground_filter.cpp b/perception/ground_segmentation/test/test_scan_ground_filter.cpp index 444a38ea44754..e48bd36d8c54e 100644 --- a/perception/ground_segmentation/test/test_scan_ground_filter.cpp +++ b/perception/ground_segmentation/test/test_scan_ground_filter.cpp @@ -83,6 +83,7 @@ class ScanGroundFilterTest : public ::testing::Test rclcpp::Parameter("radial_divider_angle_deg", radial_divider_angle_deg_)); parameters.emplace_back( rclcpp::Parameter("use_recheck_ground_cluster", use_recheck_ground_cluster_)); + parameters.emplace_back(rclcpp::Parameter("use_lowest_point", use_lowest_point_)); options.parameter_overrides(parameters); @@ -157,6 +158,7 @@ class ScanGroundFilterTest : public ::testing::Test center_pcl_shift_ = params["center_pcl_shift"].as(); radial_divider_angle_deg_ = params["radial_divider_angle_deg"].as(); use_recheck_ground_cluster_ = params["use_recheck_ground_cluster"].as(); + use_lowest_point_ = params["use_lowest_point"].as(); } float global_slope_max_angle_deg_ = 0.0; @@ -174,6 +176,7 @@ class ScanGroundFilterTest : public ::testing::Test float center_pcl_shift_; float radial_divider_angle_deg_; bool use_recheck_ground_cluster_; + bool use_lowest_point_; }; TEST_F(ScanGroundFilterTest, TestCase1) From 9cbd02d7dd5c505ec604efca73d6eb61442ee2bd Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 9 Apr 2024 20:59:21 +0900 Subject: [PATCH 41/57] fix(avoidance): bug in the logic to judge whether it's a parked vehicle (#6768) fix(avoidance): adjacent lane check for ambiguous stopped vehicle Signed-off-by: satoshi-ota --- .../behavior_path_avoidance_module/utils.hpp | 4 -- .../src/scene.cpp | 1 - .../src/utils.cpp | 45 +++---------------- 3 files changed, 5 insertions(+), 45 deletions(-) diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp index 9dc23ea4ec80e..3f1d3495e51cb 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp @@ -85,10 +85,6 @@ lanelet::ConstLanelets getAdjacentLane( const std::shared_ptr & planner_data, const std::shared_ptr & parameters, const bool is_right_shift); -lanelet::ConstLanelets getTargetLanelets( - const std::shared_ptr & planner_data, lanelet::ConstLanelets & route_lanelets, - const double left_offset, const double right_offset); - lanelet::ConstLanelets getCurrentLanesFromPath( const PathWithLaneId & path, const std::shared_ptr & planner_data); diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index b22a4bf53eab0..a7430efd1c860 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -318,7 +318,6 @@ void AvoidanceModule::fillAvoidanceTargetObjects( using utils::avoidance::fillAvoidanceNecessity; using utils::avoidance::fillObjectStoppableJudge; using utils::avoidance::filterTargetObjects; - using utils::avoidance::getTargetLanelets; using utils::avoidance::separateObjectsByPath; using utils::avoidance::updateRoadShoulderDistance; using utils::traffic_light::calcDistanceToRedTrafficLight; diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index fdb2b9b71c782..6c2b72db0237d 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -575,9 +575,11 @@ bool isNeverAvoidanceTarget( } if (object.is_on_ego_lane) { - if ( - planner_data->route_handler->getRightLanelet(object.overhang_lanelet).has_value() && - planner_data->route_handler->getLeftLanelet(object.overhang_lanelet).has_value()) { + const auto right_lane = + planner_data->route_handler->getRightLanelet(object.overhang_lanelet, true, false); + const auto left_lane = + planner_data->route_handler->getLeftLanelet(object.overhang_lanelet, true, false); + if (right_lane.has_value() && left_lane.has_value()) { object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT; RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object isn't on the edge lane. never avoid it."); return true; @@ -1219,43 +1221,6 @@ std::vector generateObstaclePolygonsForDrivableArea( return obstacles_for_drivable_area; } -lanelet::ConstLanelets getTargetLanelets( - const std::shared_ptr & planner_data, lanelet::ConstLanelets & route_lanelets, - const double left_offset, const double right_offset) -{ - const auto & rh = planner_data->route_handler; - - lanelet::ConstLanelets target_lanelets{}; - for (const auto & lane : route_lanelets) { - auto l_offset = 0.0; - auto r_offset = 0.0; - - const auto opt_left_lane = rh->getLeftLanelet(lane); - if (opt_left_lane) { - target_lanelets.push_back(opt_left_lane.value()); - } else { - l_offset = left_offset; - } - - const auto opt_right_lane = rh->getRightLanelet(lane); - if (opt_right_lane) { - target_lanelets.push_back(opt_right_lane.value()); - } else { - r_offset = right_offset; - } - - const auto right_opposite_lanes = rh->getRightOppositeLanelets(lane); - if (!right_opposite_lanes.empty()) { - target_lanelets.push_back(right_opposite_lanes.front()); - } - - const auto expand_lane = lanelet::utils::getExpandedLanelet(lane, l_offset, r_offset); - target_lanelets.push_back(expand_lane); - } - - return target_lanelets; -} - lanelet::ConstLanelets getCurrentLanesFromPath( const PathWithLaneId & path, const std::shared_ptr & planner_data) { From c3b727f002e0400130e891909a868d3b75ee6d1e Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 9 Apr 2024 22:14:00 +0900 Subject: [PATCH 42/57] fix(avoidance): fix margin param inconsistency (#6765) Signed-off-by: satoshi-ota --- .../behavior_path_avoidance_module/src/scene.cpp | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index a7430efd1c860..33f58c6a08dfc 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -641,7 +641,10 @@ void AvoidanceModule::fillDebugData( const auto constant_distance = helper_->getFrontConstantDistance(o_front); const auto & vehicle_width = planner_data_->parameters.vehicle_width; - const auto max_avoid_margin = object_parameter.lateral_hard_margin * o_front.distance_factor + + const auto lateral_hard_margin = o_front.is_parked + ? object_parameter.lateral_hard_margin_for_parked_vehicle + : object_parameter.lateral_hard_margin; + const auto max_avoid_margin = lateral_hard_margin * o_front.distance_factor + object_parameter.lateral_soft_margin + 0.5 * vehicle_width; const auto avoidance_distance = helper_->getSharpAvoidanceDistance( @@ -1431,7 +1434,10 @@ double AvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const const auto object_type = utils::getHighestProbLabel(object.object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); - const auto avoid_margin = object_parameter.lateral_hard_margin * object.distance_factor + + const auto lateral_hard_margin = object.is_parked + ? object_parameter.lateral_hard_margin_for_parked_vehicle + : object_parameter.lateral_hard_margin; + const auto avoid_margin = lateral_hard_margin * object.distance_factor + object_parameter.lateral_soft_margin + 0.5 * vehicle_width; const auto avoidance_distance = helper_->getMinAvoidanceDistance( helper_->getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin)); @@ -1675,7 +1681,10 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const const auto & vehicle_width = planner_data_->parameters.vehicle_width; const auto object_type = utils::getHighestProbLabel(object.value().object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); - const auto avoid_margin = object_parameter.lateral_hard_margin * object.value().distance_factor + + const auto lateral_hard_margin = object.value().is_parked + ? object_parameter.lateral_hard_margin_for_parked_vehicle + : object_parameter.lateral_hard_margin; + const auto avoid_margin = lateral_hard_margin * object.value().distance_factor + object_parameter.lateral_soft_margin + 0.5 * vehicle_width; const auto shift_length = helper_->getShiftLength( object.value(), utils::avoidance::isOnRight(object.value()), avoid_margin); From fd1a27e053823fb6a3e38522b4c884deb5a9809d Mon Sep 17 00:00:00 2001 From: Aswin <130948783+4swinv@users.noreply.github.com> Date: Wed, 10 Apr 2024 11:35:35 +0900 Subject: [PATCH 43/57] fix(freespace_planning_algorithms): fix issue of astar search planner not reaching goal pose (#6562) fix(freespace_planning_algorithms): fix issue of freespace planner not reaching goal pose --- .../src/astar_search.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/planning/freespace_planning_algorithms/src/astar_search.cpp b/planning/freespace_planning_algorithms/src/astar_search.cpp index 1ab5e9d5df487..3cc3801575116 100644 --- a/planning/freespace_planning_algorithms/src/astar_search.cpp +++ b/planning/freespace_planning_algorithms/src/astar_search.cpp @@ -292,6 +292,17 @@ void AstarSearch::setPath(const AstarNode & goal_node) // From the goal node to the start node const AstarNode * node = &goal_node; + // push exact goal pose first + geometry_msgs::msg::PoseStamped pose; + pose.header = header; + pose.pose = local2global(costmap_, goal_pose_); + + PlannerWaypoint pw; + pw.pose = pose; + pw.is_back = node->is_back; + waypoints_.waypoints.push_back(pw); + + // push astar nodes poses while (node != nullptr) { geometry_msgs::msg::PoseStamped pose; pose.header = header; From 2b48d25ac6d32c7617be8d098b78c76df6101560 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Wed, 10 Apr 2024 11:53:01 +0900 Subject: [PATCH 44/57] docs(dynamic_avoidance): fix sentence (#6782) * fix confusing sentence Signed-off-by: Yuki Takagi --- .../README.md | 23 +++++++++---------- 1 file changed, 11 insertions(+), 12 deletions(-) diff --git a/planning/behavior_path_dynamic_avoidance_module/README.md b/planning/behavior_path_dynamic_avoidance_module/README.md index 10276db0efab2..89a661d66735e 100644 --- a/planning/behavior_path_dynamic_avoidance_module/README.md +++ b/planning/behavior_path_dynamic_avoidance_module/README.md @@ -4,15 +4,16 @@ This module is under development. ## Purpose / Role -This module provides avoidance functions for vehicles, pedestrians, and obstacles in the vicinity of the ego's path in combination with the obstacle_avoidance module. +This module provides avoidance functions for vehicles, pedestrians, and obstacles in the vicinity of the ego's path in combination with the [obstacle_avoidance_planner](https://autowarefoundation.github.io/autoware.universe/main/planning/obstacle_avoidance_planner/). Each module performs the following roles. -Dynamic Avoidance module: This module cuts off the drivable area according to the position and velocity of the target to be avoided. -Obstacle Avoidance module: This module modifies the path to be followed so that it fits within the drivable area received. +Dynamic Avoidance module cuts off the drivable area according to the position and velocity of the target to be avoided. +Obstacle Avoidance module modifies the path to be followed so that it fits within the received drivable area. -Avoidance functions are also provided by the Avoidance module, which allows avoidance through the outside of own lanes but not against moving objects. +Avoidance functions are also provided by the [Avoidance module](https://autowarefoundation.github.io/autoware.universe/main/planning/behavior_path_avoidance_module/), but these modules have different roles. +The Avoidance module performs avoidance through the outside of own lanes but cannot avoid the moving objects. On the other hand, this module can avoid moving objects. -For this reason, the word "dynamic" is used in its name. -The table below lists the avoidance modules that can be used for each situation. +For this reason, the word "dynamic" is used in the modules's name. +The table below lists the avoidance modules that can handle each situation. | | avoid within the own lane | avoid through the outside of own lanes | | :----------------------- | :------------------------------------------------------------------------: | :------------------------------------: | @@ -23,7 +24,6 @@ The table below lists the avoidance modules that can be used for each situation. Here, we describe the policy of inner algorithms. The inner algorithms can be separated into two parts: The first decide whether to avoid the obstacles and the second cuts off the drivable area against the corresponding obstacle. -If you are interested in more details, please see the code itself. ### Select obstacles to avoid @@ -31,11 +31,10 @@ To decide whether to avoid an object, both the predicted path and the state (pos The type of objects the user wants this module to avoid is also required. Using this information, the module decides to _avoid_ objects that _obstruct the ego's passage_ and _can be avoided_. -The definition of _obstruct own passage_ is implemented as the object that collides within seconds. -This process wastes computational cost by doing it for all objects; thus, filtering by the relative position and speed of the object with respect to the ego's path is also done as an auxiliary process. -The other, _can be avoided_ denotes whether it can be avoided without risk to passengers or other vehicles. -For this purpose, it is judged whether the obstacle can be avoided by satisfying the constraints of lateral acceleration and lateral jerk. -For example, the module decides not to avoid an object that is too close or fast in the lateral direction because it cannot be avoided. +The definition of _obstruct the ego's passage_ is implemented as the object that collides within seconds. +The other, _can be avoided_ denotes whether it can be avoided without risk to the passengers or the other vehicles. +For this purpose, the module judges whether the obstacle can be avoided with satisfying the constraints of lateral acceleration and lateral jerk. +For example, the module decides not to avoid an object that is too close or fast in the lateral direction. ### Cuts off the drivable area against the selected obstacles From 81c432e8110ca54acc5e6fc4a757eff87724c39b Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Wed, 10 Apr 2024 13:16:21 +0900 Subject: [PATCH 45/57] chore(multi_object_tracker): change node and glog implementation (#6780) * chore: change node and glog impl Signed-off-by: Taekjin LEE * style(pre-commit): autofix --------- Signed-off-by: Taekjin LEE Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> --- .../multi_object_tracker/CMakeLists.txt | 10 +++--- .../src/multi_object_tracker_core.cpp | 4 --- .../src/multi_object_tracker_node.cpp | 34 +++++++++++++++++++ 3 files changed, 40 insertions(+), 8 deletions(-) create mode 100644 perception/multi_object_tracker/src/multi_object_tracker_node.cpp diff --git a/perception/multi_object_tracker/CMakeLists.txt b/perception/multi_object_tracker/CMakeLists.txt index 8d835fec20a9b..185ca175df2b6 100644 --- a/perception/multi_object_tracker/CMakeLists.txt +++ b/perception/multi_object_tracker/CMakeLists.txt @@ -47,12 +47,14 @@ ament_auto_add_library(multi_object_tracker_node SHARED target_link_libraries(multi_object_tracker_node Eigen3::Eigen - glog::glog ) -rclcpp_components_register_node(multi_object_tracker_node - PLUGIN "MultiObjectTracker" - EXECUTABLE multi_object_tracker +ament_auto_add_executable(${PROJECT_NAME} + src/multi_object_tracker_node.cpp +) + +target_link_libraries(${PROJECT_NAME} + multi_object_tracker_node glog ) ament_auto_package(INSTALL_TO_SHARE diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index 785038fb513c9..220d1104b33ee 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -72,10 +72,6 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { - // glog for debug - google::InitGoogleLogging("multi_object_tracker"); - google::InstallFailureSignalHandler(); - // Create publishers and subscribers detected_object_sub_ = create_subscription( "input", rclcpp::QoS{1}, diff --git a/perception/multi_object_tracker/src/multi_object_tracker_node.cpp b/perception/multi_object_tracker/src/multi_object_tracker_node.cpp new file mode 100644 index 0000000000000..f20aedf16efef --- /dev/null +++ b/perception/multi_object_tracker/src/multi_object_tracker_node.cpp @@ -0,0 +1,34 @@ +// Copyright 2024 TIER IV, inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "multi_object_tracker/multi_object_tracker_core.hpp" + +#include + +#include + +int main(int argc, char ** argv) +{ + google::InitGoogleLogging(argv[0]); // NOLINT + google::InstallFailureSignalHandler(); + + rclcpp::init(argc, argv); + rclcpp::NodeOptions options; + auto multi_object_tracker = std::make_shared(options); + rclcpp::executors::SingleThreadedExecutor exec; + exec.add_node(multi_object_tracker); + exec.spin(); + rclcpp::shutdown(); + return 0; +} From 9f915019c9eaa4a1ecd0b20dc77c6c603ceac407 Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Thu, 11 Apr 2024 09:52:56 +0900 Subject: [PATCH 46/57] feat(fault injection): change for diagnostic graph aggregator (#6750) * feat: change to adapt diagnostic graph aggregator Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * Change the configuration to adapt to both system_error_monitor and diagnostic_graph_aggregator Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * style(pre-commit): autofix * pre-commit fix Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * style(pre-commit): autofix * spell check fix Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * clang-tidy fix Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * style(pre-commit): autofix * pre-commit fix Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * style(pre-commit): autofix * fix datatype Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * cleanup code Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> --------- Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Tomohito ANDO --- simulator/fault_injection/README.md | 4 +- .../config/fault_injection.param.yaml | 64 ++--- .../fault_injection_diag_updater.hpp | 244 ++++++++++++++++++ .../fault_injection/fault_injection_node.hpp | 18 +- .../fault_injection_node.cpp | 43 +-- .../test/config/test_event_diag.param.yaml | 6 +- .../test/test_fault_injection_node.test.py | 6 +- 7 files changed, 298 insertions(+), 87 deletions(-) create mode 100644 simulator/fault_injection/include/fault_injection/fault_injection_diag_updater.hpp diff --git a/simulator/fault_injection/README.md b/simulator/fault_injection/README.md index cbac41ebfb640..cb3d6fea96a7a 100644 --- a/simulator/fault_injection/README.md +++ b/simulator/fault_injection/README.md @@ -27,7 +27,9 @@ launch_test test/test_fault_injection_node.test.py ### Output -None. +| Name | Type | Description | +| -------------- | --------------------------------------- | ----------------- | +| `/diagnostics` | `diagnostic_msgs::msg::DiagnosticArray` | Dummy diagnostics | ## Parameters diff --git a/simulator/fault_injection/config/fault_injection.param.yaml b/simulator/fault_injection/config/fault_injection.param.yaml index ac02442d70b4d..e9e90a336348e 100644 --- a/simulator/fault_injection/config/fault_injection.param.yaml +++ b/simulator/fault_injection/config/fault_injection.param.yaml @@ -1,37 +1,37 @@ /**: ros__parameters: event_diag_list: - vehicle_is_out_of_lane: "lane_departure" - trajectory_deviation_is_high: "trajectory_deviation" - localization_matching_score_is_low: "ndt_scan_matcher" - localization_accuracy_is_low: "localization_error_ellipse" - map_version_is_different: "map_version" - trajectory_is_invalid: "trajectory_point_validation" - cpu_temperature_is_high: "CPU Temperature" - cpu_usage_is_high: "CPU Usage" - cpu_is_in_thermal_throttling: "CPU Thermal Throttling" - storage_temperature_is_high: "HDD Temperature" - storage_usage_is_high: "HDD Usage" - network_usage_is_high: "Network Usage" - clock_error_is_large: "NTP Offset" - gpu_temperature_is_high: "GPU Temperature" - gpu_usage_is_high: "GPU Usage" - gpu_memory_usage_is_high: "GPU Memory Usage" - gpu_is_in_thermal_throttling: "GPU Thermal Throttling" - driving_recorder_storage_error: "driving_recorder" - debug_data_logger_storage_error: "bagpacker" - emergency_stop_operation: "emergency_stop_operation" - vehicle_error_occurred: "vehicle_errors" - vehicle_ecu_connection_is_lost: "can_bus_connection" - obstacle_crash_sensor_is_activated: "obstacle_crash" + vehicle_is_out_of_lane: ": lane_departure" + trajectory_deviation_is_high: ": trajectory_deviation" + localization_matching_score_is_low: ": ndt_scan_matcher" + localization_accuracy_is_low: ": localization_error_ellipse" + map_version_is_different: ": map_version" + trajectory_is_invalid: ": trajectory_point_validation" + cpu_temperature_is_high: ": CPU Temperature" + cpu_usage_is_high: ": CPU Usage" + cpu_is_in_thermal_throttling: ": CPU Thermal Throttling" + storage_temperature_is_high: ": HDD Temperature" + storage_usage_is_high: ": HDD Usage" + network_usage_is_high: ": Network Usage" + clock_error_is_large: ": NTP Offset" + gpu_temperature_is_high: ": GPU Temperature" + gpu_usage_is_high: ": GPU Usage" + gpu_memory_usage_is_high: ": GPU Memory Usage" + gpu_is_in_thermal_throttling: ": GPU Thermal Throttling" + driving_recorder_storage_error: ": driving_recorder" + debug_data_logger_storage_error: ": bagpacker" + emergency_stop_operation: ": emergency_stop_operation" + vehicle_error_occurred: ": vehicle_errors" + vehicle_ecu_connection_is_lost: ": can_bus_connection" + obstacle_crash_sensor_is_activated: ": obstacle_crash" /control/command_gate/node_alive_monitoring: "vehicle_cmd_gate: heartbeat" - /control/autonomous_driving/node_alive_monitoring: "control_topic_status" + /control/autonomous_driving/node_alive_monitoring: ": control_topic_status" /control/external_command_selector/node_alive_monitoring: "external_cmd_selector: heartbeat" - /localization/node_alive_monitoring: "localization_topic_status" - /map/node_alive_monitoring: "map_topic_status" - /planning/node_alive_monitoring: "planning_topic_status" - /sensing/lidar/node_alive_monitoring: "lidar_topic_status" - /sensing/imu/node_alive_monitoring: "imu_connection" - /sensing/gnss/node_alive_monitoring: "gnss_connection" - /system/node_alive_monitoring: "system_topic_status" - /vehicle/node_alive_monitoring: "vehicle_topic_status" + /localization/node_alive_monitoring: ": localization_topic_status" + /map/node_alive_monitoring: ": map_topic_status" + /planning/node_alive_monitoring: ": planning_topic_status" + /sensing/lidar/node_alive_monitoring: ": lidar_topic_status" + /sensing/imu/node_alive_monitoring: ": imu_connection" + /sensing/gnss/node_alive_monitoring: ": gnss_connection" + /system/node_alive_monitoring: ": system_topic_status" + /vehicle/node_alive_monitoring: ": vehicle_topic_status" diff --git a/simulator/fault_injection/include/fault_injection/fault_injection_diag_updater.hpp b/simulator/fault_injection/include/fault_injection/fault_injection_diag_updater.hpp new file mode 100644 index 0000000000000..948c2b45f6615 --- /dev/null +++ b/simulator/fault_injection/include/fault_injection/fault_injection_diag_updater.hpp @@ -0,0 +1,244 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage 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 FAULT_INJECTION__FAULT_INJECTION_DIAG_UPDATER_HPP_ +#define FAULT_INJECTION__FAULT_INJECTION_DIAG_UPDATER_HPP_ + +#include + +#include +#include +#include +#include + +namespace fault_injection +{ +class FaultInjectionDiagUpdater : public diagnostic_updater::DiagnosticTaskVector +{ +public: + template + explicit FaultInjectionDiagUpdater(NodeT node, double period = 1.0) + : FaultInjectionDiagUpdater( + node->get_node_base_interface(), node->get_node_clock_interface(), + node->get_node_logging_interface(), node->get_node_timers_interface(), + node->get_node_topics_interface(), period) + { + } + + FaultInjectionDiagUpdater( + const std::shared_ptr & base_interface, + const std::shared_ptr & clock_interface, + const std::shared_ptr & logging_interface, + std::shared_ptr timers_interface, + std::shared_ptr topics_interface, + double period = 1.0) + : base_interface_(base_interface), + timers_interface_(std::move(timers_interface)), + clock_(clock_interface->get_clock()), + period_(rclcpp::Duration::from_nanoseconds(static_cast(period * 1e9))), + publisher_(rclcpp::create_publisher( + topics_interface, "/diagnostics", 1)), + logger_(logging_interface->get_logger()), + node_name_(base_interface->get_name()) + { + reset_timer(); + } + + /** + * \brief Returns the interval between updates. + */ + [[nodiscard]] auto get_period() const { return period_; } + + /** + * \brief Sets the period as a rclcpp::Duration + */ + void set_period(const rclcpp::Duration & period) + { + period_ = period; + reset_timer(); + } + + /** + * \brief Sets the period given a value in seconds + */ + void set_period(double period) + { + set_period(rclcpp::Duration::from_nanoseconds(static_cast(period * 1e9))); + } + + /** + * \brief Forces to send out an update for all known DiagnosticStatus. + */ + void force_update() { update(); } + + /** + * \brief Output a message on all the known DiagnosticStatus. + * + * Useful if something drastic is happening such as shutdown or a + * self-test. + * + * \param lvl Level of the diagnostic being output. + * + * \param msg Status message to output. + */ + void broadcast(int lvl, const std::string & msg) + { + std::vector status_vec; + + const std::vector & tasks = getTasks(); + for (const auto & task : tasks) { + diagnostic_updater::DiagnosticStatusWrapper status; + + status.name = task.getName(); + status.summary(lvl, msg); + + status_vec.push_back(status); + } + + publish(status_vec); + } + + void set_hardware_id_f(const char * format, ...) + { + va_list va; + const int k_buffer_size = 1000; + char buff[1000]; // @todo This could be done more elegantly. + va_start(va, format); + if (vsnprintf(buff, k_buffer_size, format, va) >= k_buffer_size) { + RCLCPP_DEBUG(logger_, "Really long string in diagnostic_updater::setHardwareIDf."); + } + hardware_id_ = std::string(buff); + va_end(va); + } + + void set_hardware_id(const std::string & hardware_id) { hardware_id_ = hardware_id; } + +private: + void reset_timer() + { + update_timer_ = rclcpp::create_timer( + base_interface_, timers_interface_, clock_, period_, + std::bind(&FaultInjectionDiagUpdater::update, this)); + } + + /** + * \brief Causes the diagnostics to update if the inter-update interval + * has been exceeded. + */ + void update() + { + if (rclcpp::ok()) { + std::vector status_vec; + + std::unique_lock lock( + lock_); // Make sure no adds happen while we are processing here. + const std::vector & tasks = getTasks(); + for (const auto & task : tasks) { + diagnostic_updater::DiagnosticStatusWrapper status; + + status.name = task.getName(); + status.level = 2; + status.message = "No message was set"; + status.hardware_id = hardware_id_; + + task.run(status); + + status_vec.push_back(status); + } + + publish(status_vec); + } + } + + /** + * Publishes a single diagnostic status. + */ + void publish(diagnostic_msgs::msg::DiagnosticStatus & stat) + { + std::vector status_vec; + status_vec.push_back(stat); + publish(status_vec); + } + + /** + * Publishes a vector of diagnostic statuses. + */ + void publish(std::vector & status_vec) + { + diagnostic_msgs::msg::DiagnosticArray msg; + msg.status = status_vec; + msg.header.stamp = clock_->now(); + publisher_->publish(msg); + } + + /** + * Causes a placeholder DiagnosticStatus to be published as soon as a + * diagnostic task is added to the Updater. + */ + void addedTaskCallback(DiagnosticTaskInternal & task) override + { + diagnostic_updater::DiagnosticStatusWrapper stat; + stat.name = task.getName(); + stat.summary(0, "Node starting up"); + publish(stat); + } + + rclcpp::node_interfaces::NodeBaseInterface::SharedPtr base_interface_; + rclcpp::node_interfaces::NodeTimersInterface::SharedPtr timers_interface_; + rclcpp::Clock::SharedPtr clock_; + rclcpp::Duration period_; + rclcpp::TimerBase::SharedPtr update_timer_; + rclcpp::Publisher::SharedPtr publisher_; + rclcpp::Logger logger_; + + std::string hardware_id_; + std::string node_name_; +}; +} // namespace fault_injection + +#endif // FAULT_INJECTION__FAULT_INJECTION_DIAG_UPDATER_HPP_ diff --git a/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp b/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp index 0f578ff343a17..999d18b38c7b0 100644 --- a/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp +++ b/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp @@ -16,8 +16,8 @@ #define FAULT_INJECTION__FAULT_INJECTION_NODE_HPP_ #include "fault_injection/diagnostic_storage.hpp" +#include "fault_injection/fault_injection_diag_updater.hpp" -#include #include #include @@ -36,23 +36,15 @@ class FaultInjectionNode : public rclcpp::Node private: // Subscribers - void onSimulationEvents(const SimulationEvents::ConstSharedPtr msg); + void on_simulation_events(const SimulationEvents::ConstSharedPtr msg); rclcpp::Subscription::SharedPtr sub_simulation_events_; - // Parameter Server - rcl_interfaces::msg::SetParametersResult onSetParam( - const std::vector & params); - OnSetParametersCallbackHandle::SharedPtr set_param_res_; - - void updateEventDiag( + void update_event_diag( diagnostic_updater::DiagnosticStatusWrapper & wrap, const std::string & event_name); - void addDiag( - const diagnostic_msgs::msg::DiagnosticStatus & status, diagnostic_updater::Updater & updater); - - std::vector readEventDiagList(); + std::vector read_event_diag_list(); - diagnostic_updater::Updater updater_; + FaultInjectionDiagUpdater updater_; DiagnosticStorage diagnostic_storage_; }; diff --git a/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp b/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp index 9b86fa2de4294..7b8f87400beab 100644 --- a/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp +++ b/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp @@ -43,30 +43,26 @@ using rosidl_generator_traits::to_yaml; FaultInjectionNode::FaultInjectionNode(rclcpp::NodeOptions node_options) : Node("fault_injection", node_options.automatically_declare_parameters_from_overrides(true)), - updater_(this) + updater_(this, 0.05) { - updater_.setHardwareID("fault_injection"); + updater_.set_hardware_id("fault_injection"); using std::placeholders::_1; - // Parameter Server - set_param_res_ = - this->add_on_set_parameters_callback(std::bind(&FaultInjectionNode::onSetParam, this, _1)); - // Subscriber sub_simulation_events_ = this->create_subscription( "~/input/simulation_events", rclcpp::QoS{rclcpp::KeepLast(10)}, - std::bind(&FaultInjectionNode::onSimulationEvents, this, _1)); + std::bind(&FaultInjectionNode::on_simulation_events, this, _1)); // Load all config - for (const auto & diag : readEventDiagList()) { + for (const auto & diag : read_event_diag_list()) { diagnostic_storage_.registerEvent(diag); updater_.add( - diag.diag_name, std::bind(&FaultInjectionNode::updateEventDiag, this, _1, diag.sim_name)); + diag.diag_name, std::bind(&FaultInjectionNode::update_event_diag, this, _1, diag.sim_name)); } } -void FaultInjectionNode::onSimulationEvents(const SimulationEvents::ConstSharedPtr msg) +void FaultInjectionNode::on_simulation_events(const SimulationEvents::ConstSharedPtr msg) { RCLCPP_DEBUG(this->get_logger(), "Received data: %s", to_yaml(*msg).c_str()); for (const auto & event : msg->fault_injection_events) { @@ -76,7 +72,7 @@ void FaultInjectionNode::onSimulationEvents(const SimulationEvents::ConstSharedP } } -void FaultInjectionNode::updateEventDiag( +void FaultInjectionNode::update_event_diag( diagnostic_updater::DiagnosticStatusWrapper & wrap, const std::string & event_name) { const auto diag = diagnostic_storage_.getDiag(event_name); @@ -86,30 +82,7 @@ void FaultInjectionNode::updateEventDiag( wrap.hardware_id = diag.hardware_id; } -rcl_interfaces::msg::SetParametersResult FaultInjectionNode::onSetParam( - const std::vector & params) -{ - rcl_interfaces::msg::SetParametersResult result; - - RCLCPP_DEBUG(this->get_logger(), "call onSetParam"); - - try { - double value; - if (tier4_autoware_utils::updateParam(params, "diagnostic_updater.period", value)) { - updater_.setPeriod(value); - } - } catch (const rclcpp::exceptions::InvalidParameterTypeException & e) { - result.successful = false; - result.reason = e.what(); - return result; - } - - result.successful = true; - result.reason = "success"; - return result; -} - -std::vector FaultInjectionNode::readEventDiagList() +std::vector FaultInjectionNode::read_event_diag_list() { // Expected parameter name is "event_diag_list.param_name". // In this case, depth is 2. diff --git a/simulator/fault_injection/test/config/test_event_diag.param.yaml b/simulator/fault_injection/test/config/test_event_diag.param.yaml index 83f58fcc455ee..d9006d239b924 100644 --- a/simulator/fault_injection/test/config/test_event_diag.param.yaml +++ b/simulator/fault_injection/test/config/test_event_diag.param.yaml @@ -1,6 +1,6 @@ /**: ros__parameters: event_diag_list: - cpu_temperature: "CPU Temperature" - cpu_usage: "CPU Usage" - cpu_load_average: "CPU Load Average" + cpu_temperature: ": CPU Temperature" + cpu_usage: ": CPU Usage" + cpu_load_average: ": CPU Load Average" diff --git a/simulator/fault_injection/test/test_fault_injection_node.test.py b/simulator/fault_injection/test/test_fault_injection_node.test.py index 4556aaaca8d80..1437d69b1c91b 100644 --- a/simulator/fault_injection/test/test_fault_injection_node.test.py +++ b/simulator/fault_injection/test/test_fault_injection_node.test.py @@ -167,11 +167,11 @@ def test_receive_multiple_message_simultaneously(self): # Verify the latest message for stat in msg_buffer[-1].status: - if stat.name == "fault_injection: CPU Load Average": + if stat.name == ": CPU Load Average": self.assertEqual(stat.level, DiagnosticStatus.OK) - elif stat.name == "fault_injection: CPU Temperature": + elif stat.name == ": CPU Temperature": self.assertEqual(stat.level, DiagnosticStatus.ERROR) - elif stat.name == "fault_injection: CPU Usage": + elif stat.name == ": CPU Usage": self.assertEqual(stat.level, DiagnosticStatus.ERROR) else: self.fail(f"Unexpected status name: {stat.name}") From c381661ba4a20b1054d28a95467835e95424b30a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 11 Apr 2024 11:56:09 +0900 Subject: [PATCH 47/57] refactor(static_centerline_optimizer): admit I/F for other sources of centerline (#6783) * refactor(static_centerline_optimizer): admit I/F for other sources of centerline Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../static_centerline_optimizer.param.yaml | 1 + .../static_centerline_optimizer_node.hpp | 21 +++-- .../src/static_centerline_optimizer_node.cpp | 84 ++++++++++++------- 3 files changed, 68 insertions(+), 38 deletions(-) diff --git a/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml b/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml index f62c34496e024..4fdee8a0ca6fc 100644 --- a/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml +++ b/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml @@ -1,4 +1,5 @@ /**: ros__parameters: + centerline_source: "optimization_trajectory_base" # select from "optimization_trajectory_base" and "bag_ego_trajectory_base" marker_color: ["FF0000", "00FF00", "0000FF"] marker_color_dist_thresh : [0.1, 0.2, 0.3] diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp index 3e6aafd3a9954..a920139a94472 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp @@ -44,6 +44,11 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node void run(); private: + struct CenterlineWithRoute + { + std::vector centerline{}; + std::vector route_lane_ids{}; + }; // load map void load_map(const std::string & lanelet2_input_file_path); void on_load_map( @@ -56,6 +61,7 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node const PlanRoute::Request::SharedPtr request, const PlanRoute::Response::SharedPtr response); // plan path + CenterlineWithRoute generate_centerline_with_route(); std::vector plan_path(const std::vector & route_lane_ids); std::vector optimize_trajectory(const Path & raw_path) const; void on_plan_path( @@ -65,8 +71,8 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node const std::vector & route_lane_ids, const std::vector & optimized_traj_points); void save_map( - const std::string & lanelet2_output_file_path, const std::vector & route_lane_ids, - const std::vector & optimized_traj_points); + const std::string & lanelet2_output_file_path, + const CenterlineWithRoute & centerline_with_route); lanelet::LaneletMapPtr original_map_ptr_{nullptr}; HADMapBin::ConstSharedPtr map_bin_ptr_{nullptr}; @@ -75,12 +81,13 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node int traj_start_index_{0}; int traj_end_index_{0}; - struct MetaDataToSaveMap - { - std::vector optimized_traj_points{}; - std::vector route_lane_ids{}; + std::optional centerline_with_route_{std::nullopt}; + + enum class CenterlineSource { + OptimizationTrajectoryBase = 0, + BagEgoTrajectoryBase, }; - std::optional meta_data_to_save_map_{std::nullopt}; + CenterlineSource centerline_source_; // publisher rclcpp::Publisher::SharedPtr pub_map_bin_{nullptr}; diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index ea7e1c302fd68..0feebe8cbceb6 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -240,46 +240,44 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( sub_traj_start_index_ = create_subscription( "/centerline_updater_helper/traj_start_index", rclcpp::QoS{1}, [this](const std_msgs::msg::Int32 & msg) { - if (!meta_data_to_save_map_ || traj_end_index_ + 1 < msg.data) { + if (!centerline_with_route_ || traj_end_index_ + 1 < msg.data) { return; } traj_start_index_ = msg.data; - const auto & d = meta_data_to_save_map_; - const auto selected_optimized_traj_points = std::vector( - d->optimized_traj_points.begin() + traj_start_index_, - d->optimized_traj_points.begin() + traj_end_index_ + 1); + const auto & c = *centerline_with_route_; + const auto selected_centerline = std::vector( + c.centerline.begin() + traj_start_index_, c.centerline.begin() + traj_end_index_ + 1); - pub_optimized_centerline_->publish(motion_utils::convertToTrajectory( - selected_optimized_traj_points, createHeader(this->now()))); + pub_optimized_centerline_->publish( + motion_utils::convertToTrajectory(selected_centerline, createHeader(this->now()))); }); sub_traj_end_index_ = create_subscription( "/centerline_updater_helper/traj_end_index", rclcpp::QoS{1}, [this](const std_msgs::msg::Int32 & msg) { - if (!meta_data_to_save_map_ || msg.data + 1 < traj_start_index_) { + if (!centerline_with_route_ || msg.data + 1 < traj_start_index_) { return; } traj_end_index_ = msg.data; - const auto & d = meta_data_to_save_map_; - const auto selected_optimized_traj_points = std::vector( - d->optimized_traj_points.begin() + traj_start_index_, - d->optimized_traj_points.begin() + traj_end_index_ + 1); + const auto & c = *centerline_with_route_; + const auto selected_centerline = std::vector( + c.centerline.begin() + traj_start_index_, c.centerline.begin() + traj_end_index_ + 1); - pub_optimized_centerline_->publish(motion_utils::convertToTrajectory( - selected_optimized_traj_points, createHeader(this->now()))); + pub_optimized_centerline_->publish( + motion_utils::convertToTrajectory(selected_centerline, createHeader(this->now()))); }); sub_save_map_ = create_subscription( "/centerline_updater_helper/save_map", rclcpp::QoS{1}, [this](const std_msgs::msg::Bool & msg) { const auto lanelet2_output_file_path = tier4_autoware_utils::getOrDeclareParameter( *this, "lanelet2_output_file_path"); - if (!meta_data_to_save_map_ || msg.data) { - const auto & d = meta_data_to_save_map_; - const auto selected_optimized_traj_points = std::vector( - d->optimized_traj_points.begin() + traj_start_index_, - d->optimized_traj_points.begin() + traj_end_index_ + 1); - save_map(lanelet2_output_file_path, d->route_lane_ids, selected_optimized_traj_points); + if (!centerline_with_route_ || msg.data) { + const auto & c = *centerline_with_route_; + const auto selected_centerline = std::vector( + c.centerline.begin() + traj_start_index_, c.centerline.begin() + traj_end_index_ + 1); + save_map( + lanelet2_output_file_path, CenterlineWithRoute{selected_centerline, c.route_lane_ids}); } }); @@ -306,6 +304,17 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( // vehicle info vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + + centerline_source_ = [&]() { + const auto centerline_source_param = declare_parameter("centerline_source"); + if (centerline_source_param == "optimization_trajectory_base") { + return CenterlineSource::OptimizationTrajectoryBase; + } else if (centerline_source_param == "bag_ego_trajectory_base") { + return CenterlineSource::BagEgoTrajectoryBase; + } + throw std::logic_error( + "The centerline source is not supported in static_centerline_optimizer."); + }(); } void StaticCenterlineOptimizerNode::run() @@ -314,18 +323,31 @@ void StaticCenterlineOptimizerNode::run() const auto lanelet2_input_file_path = declare_parameter("lanelet2_input_file_path"); const auto lanelet2_output_file_path = declare_parameter("lanelet2_output_file_path"); - const lanelet::Id start_lanelet_id = declare_parameter("start_lanelet_id"); - const lanelet::Id end_lanelet_id = declare_parameter("end_lanelet_id"); // process load_map(lanelet2_input_file_path); - const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); - const auto optimized_traj_points = plan_path(route_lane_ids); + const auto centerline_with_route = generate_centerline_with_route(); traj_start_index_ = 0; - traj_end_index_ = optimized_traj_points.size() - 1; - save_map(lanelet2_output_file_path, route_lane_ids, optimized_traj_points); + traj_end_index_ = centerline_with_route.centerline.size() - 1; + save_map(lanelet2_output_file_path, centerline_with_route); + + centerline_with_route_ = centerline_with_route; +} + +StaticCenterlineOptimizerNode::CenterlineWithRoute +StaticCenterlineOptimizerNode::generate_centerline_with_route() +{ + if (centerline_source_ == CenterlineSource::OptimizationTrajectoryBase) { + const lanelet::Id start_lanelet_id = declare_parameter("start_lanelet_id"); + const lanelet::Id end_lanelet_id = declare_parameter("end_lanelet_id"); + const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); + const auto optimized_traj_points = plan_path(route_lane_ids); + return CenterlineWithRoute{optimized_traj_points, route_lane_ids}; + } else if (centerline_source_ == CenterlineSource::BagEgoTrajectoryBase) { + return CenterlineWithRoute{}; + } - meta_data_to_save_map_ = MetaDataToSaveMap{optimized_traj_points, route_lane_ids}; + throw std::logic_error("The centerline source is not supported in static_centerline_optimizer."); } void StaticCenterlineOptimizerNode::load_map(const std::string & lanelet2_input_file_path) @@ -741,17 +763,17 @@ void StaticCenterlineOptimizerNode::evaluate( } void StaticCenterlineOptimizerNode::save_map( - const std::string & lanelet2_output_file_path, const std::vector & route_lane_ids, - const std::vector & optimized_traj_points) + const std::string & lanelet2_output_file_path, const CenterlineWithRoute & centerline_with_route) { if (!route_handler_ptr_) { return; } - const auto route_lanelets = get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); + const auto & c = centerline_with_route; + const auto route_lanelets = get_lanelets_from_ids(*route_handler_ptr_, c.route_lane_ids); // update centerline in map - utils::update_centerline(*route_handler_ptr_, route_lanelets, optimized_traj_points); + utils::update_centerline(*route_handler_ptr_, route_lanelets, c.centerline); RCLCPP_INFO(get_logger(), "Updated centerline in map."); // save map with modified center line From 5807f7a36835ee3258d524db9683d199a911be88 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Thu, 11 Apr 2024 13:21:27 +0900 Subject: [PATCH 48/57] feat(multi_object_tracker): process modulation (#6742) * fix: reduce lower limit of publish interval Signed-off-by: Taekjin LEE * fix: enlarge publish range upper limit Signed-off-by: Taekjin LEE * fix: set parameter tested and agreed Signed-off-by: Taekjin LEE * fix: define functions on each tracking steps Signed-off-by: Taekjin LEE * fix: remove time argument to avoid misuse Signed-off-by: Taekjin LEE * fix: refine function inputs and outputs Signed-off-by: Taekjin LEE * fix: create tracking process class Signed-off-by: Taekjin LEE * chore: clean up Signed-off-by: Taekjin LEE * fix: move processor to subfolder Signed-off-by: Taekjin LEE * fix: output filter is moved to the processor side Signed-off-by: Taekjin LEE * fix: rename tracker management process, process parameter Signed-off-by: Taekjin LEE * chore: revise comments Signed-off-by: Taekjin LEE * fix: remove not-related dependency Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../multi_object_tracker/CMakeLists.txt | 1 + .../include/multi_object_tracker/debugger.hpp | 1 + .../multi_object_tracker_core.hpp | 36 +-- .../processor/processor.hpp | 79 +++++ perception/multi_object_tracker/package.xml | 1 - .../src/multi_object_tracker_core.cpp | 292 +++++------------- .../src/processor/processor.cpp | 242 +++++++++++++++ 7 files changed, 414 insertions(+), 238 deletions(-) create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/processor/processor.hpp create mode 100644 perception/multi_object_tracker/src/processor/processor.cpp diff --git a/perception/multi_object_tracker/CMakeLists.txt b/perception/multi_object_tracker/CMakeLists.txt index 185ca175df2b6..41d150ef0ba1b 100644 --- a/perception/multi_object_tracker/CMakeLists.txt +++ b/perception/multi_object_tracker/CMakeLists.txt @@ -23,6 +23,7 @@ include_directories( set(MULTI_OBJECT_TRACKER_SRC src/multi_object_tracker_core.cpp src/debugger.cpp + src/processor/processor.cpp src/data_association/data_association.cpp src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp src/tracker/motion_model/motion_model_base.cpp diff --git a/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp b/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp index 858d43dcfc5bd..90291ae6fec18 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp @@ -56,6 +56,7 @@ class TrackerDebugger } debug_settings_; double pipeline_latency_ms_ = 0.0; diagnostic_updater::Updater diagnostic_updater_; + bool shouldPublishTentativeObjects() const { return debug_settings_.publish_tentative_objects; } private: void loadParameters(); diff --git a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp index fe41f97cb5a77..f788dd3895216 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp @@ -21,6 +21,7 @@ #include "multi_object_tracker/data_association/data_association.hpp" #include "multi_object_tracker/debugger.hpp" +#include "multi_object_tracker/processor/processor.hpp" #include "multi_object_tracker/tracker/model/tracker_base.hpp" #include @@ -46,6 +47,7 @@ #include #include #include +#include #include class MultiObjectTracker : public rclcpp::Node @@ -54,42 +56,34 @@ class MultiObjectTracker : public rclcpp::Node explicit MultiObjectTracker(const rclcpp::NodeOptions & node_options); private: + // ROS interface rclcpp::Publisher::SharedPtr tracked_objects_pub_; rclcpp::Subscription::SharedPtr detected_object_sub_; + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + + // debugger + std::unique_ptr debugger_; + std::unique_ptr published_time_publisher_; // publish timer rclcpp::TimerBase::SharedPtr publish_timer_; rclcpp::Time last_published_time_; double publisher_period_; - // debugger class - std::unique_ptr debugger_; - - tf2_ros::Buffer tf_buffer_; - tf2_ros::TransformListener tf_listener_; - - std::map tracker_map_; - - std::unique_ptr published_time_publisher_; + // internal states + std::string world_frame_id_; // tracking frame + std::unique_ptr data_association_; + std::unique_ptr processor_; + // callback functions void onMeasurement( const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg); void onTimer(); - std::string world_frame_id_; // tracking frame - std::list> list_tracker_; - std::unique_ptr data_association_; - - void checkTrackerLifeCycle( - std::list> & list_tracker, const rclcpp::Time & time); - void sanitizeTracker( - std::list> & list_tracker, const rclcpp::Time & time); - std::shared_ptr createNewTracker( - const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, - const geometry_msgs::msg::Transform & self_transform) const; - + // publish processes void checkAndPublish(const rclcpp::Time & time); void publish(const rclcpp::Time & time) const; inline bool shouldTrackerPublish(const std::shared_ptr tracker) const; diff --git a/perception/multi_object_tracker/include/multi_object_tracker/processor/processor.hpp b/perception/multi_object_tracker/include/multi_object_tracker/processor/processor.hpp new file mode 100644 index 0000000000000..6d6e364d83a41 --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/processor/processor.hpp @@ -0,0 +1,79 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// + +#ifndef MULTI_OBJECT_TRACKER__PROCESSOR__PROCESSOR_HPP_ +#define MULTI_OBJECT_TRACKER__PROCESSOR__PROCESSOR_HPP_ + +#include "multi_object_tracker/tracker/model/tracker_base.hpp" + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include + +class TrackerProcessor +{ +public: + explicit TrackerProcessor(const std::map & tracker_map); + + const std::list> & getListTracker() const { return list_tracker_; } + // tracker processes + void predict(const rclcpp::Time & time); + void update( + const autoware_auto_perception_msgs::msg::DetectedObjects & transformed_objects, + const geometry_msgs::msg::Transform & self_transform, + const std::unordered_map & direct_assignment); + void spawn( + const autoware_auto_perception_msgs::msg::DetectedObjects & detected_objects, + const geometry_msgs::msg::Transform & self_transform, + const std::unordered_map & reverse_assignment); + void prune(const rclcpp::Time & time); + + // output + bool isConfidentTracker(const std::shared_ptr & tracker) const; + void getTrackedObjects( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObjects & tracked_objects) const; + void getTentativeObjects( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const; + +private: + std::map tracker_map_; + std::list> list_tracker_; + + // parameters + float max_elapsed_time_; // [s] + float min_iou_; // [ratio] + float min_iou_for_unknown_object_; // [ratio] + double distance_threshold_; // [m] + int confident_count_threshold_; // [count] + + void removeOldTracker(const rclcpp::Time & time); + void removeOverlappedTracker(const rclcpp::Time & time); + std::shared_ptr createNewTracker( + const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const geometry_msgs::msg::Transform & self_transform) const; +}; + +#endif // MULTI_OBJECT_TRACKER__PROCESSOR__PROCESSOR_HPP_ diff --git a/perception/multi_object_tracker/package.xml b/perception/multi_object_tracker/package.xml index 699b28222f63f..4033f85eafb8a 100644 --- a/perception/multi_object_tracker/package.xml +++ b/perception/multi_object_tracker/package.xml @@ -25,7 +25,6 @@ tf2 tf2_ros tier4_autoware_utils - tier4_perception_msgs unique_identifier_msgs ament_lint_auto diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index 220d1104b33ee..d80a21813b28b 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -31,7 +31,6 @@ #define EIGEN_MPL2_ONLY #include "multi_object_tracker/multi_object_tracker_core.hpp" #include "multi_object_tracker/utils/utils.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -41,18 +40,20 @@ using Label = autoware_auto_perception_msgs::msg::ObjectClassification; namespace { +// Function to get the transform between two frames boost::optional getTransformAnonymous( const tf2_ros::Buffer & tf_buffer, const std::string & source_frame_id, const std::string & target_frame_id, const rclcpp::Time & time) { try { - // check if the frames are ready + // Check if the frames are ready std::string errstr; // This argument prevents error msg from being displayed in the terminal. if (!tf_buffer.canTransform( target_frame_id, source_frame_id, tf2::TimePointZero, tf2::Duration::zero(), &errstr)) { return boost::none; } + // Lookup the transform geometry_msgs::msg::TransformStamped self_transform_stamped; self_transform_stamped = tf_buffer.lookupTransform( /*target*/ target_frame_id, /*src*/ source_frame_id, time, @@ -68,9 +69,9 @@ boost::optional getTransformAnonymous( MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) : rclcpp::Node("multi_object_tracker", node_options), - last_published_time_(this->now()), tf_buffer_(this->get_clock()), - tf_listener_(tf_buffer_) + tf_listener_(tf_buffer_), + last_published_time_(this->now()) { // Create publishers and subscribers detected_object_sub_ = create_subscription( @@ -79,14 +80,12 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) tracked_objects_pub_ = create_publisher("output", rclcpp::QoS{1}); - // Parameters + // Get parameters double publish_rate = declare_parameter("publish_rate"); // [hz] world_frame_id_ = declare_parameter("world_frame_id"); bool enable_delay_compensation{declare_parameter("enable_delay_compensation")}; - // Debug publishers - debugger_ = std::make_unique(*this); - + // Create tf timer auto cti = std::make_shared( this->get_node_base_interface(), this->get_node_timers_interface()); tf_buffer_.setCreateTimerInterface(cti); @@ -102,34 +101,44 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) this, get_clock(), timer_period, std::bind(&MultiObjectTracker::onTimer, this)); } - const auto tmp = this->declare_parameter>("can_assign_matrix"); - const std::vector can_assign_matrix(tmp.begin(), tmp.end()); - - const auto max_dist_matrix = this->declare_parameter>("max_dist_matrix"); - const auto max_area_matrix = this->declare_parameter>("max_area_matrix"); - const auto min_area_matrix = this->declare_parameter>("min_area_matrix"); - const auto max_rad_matrix = this->declare_parameter>("max_rad_matrix"); - const auto min_iou_matrix = this->declare_parameter>("min_iou_matrix"); - - // tracker map - tracker_map_.insert( - std::make_pair(Label::CAR, this->declare_parameter("car_tracker"))); - tracker_map_.insert( - std::make_pair(Label::TRUCK, this->declare_parameter("truck_tracker"))); - tracker_map_.insert( - std::make_pair(Label::BUS, this->declare_parameter("bus_tracker"))); - tracker_map_.insert( - std::make_pair(Label::TRAILER, this->declare_parameter("trailer_tracker"))); - tracker_map_.insert( - std::make_pair(Label::PEDESTRIAN, this->declare_parameter("pedestrian_tracker"))); - tracker_map_.insert( - std::make_pair(Label::BICYCLE, this->declare_parameter("bicycle_tracker"))); - tracker_map_.insert( - std::make_pair(Label::MOTORCYCLE, this->declare_parameter("motorcycle_tracker"))); - - data_association_ = std::make_unique( - can_assign_matrix, max_dist_matrix, max_area_matrix, min_area_matrix, max_rad_matrix, - min_iou_matrix); + // Initialize processor + { + std::map tracker_map; + tracker_map.insert( + std::make_pair(Label::CAR, this->declare_parameter("car_tracker"))); + tracker_map.insert( + std::make_pair(Label::TRUCK, this->declare_parameter("truck_tracker"))); + tracker_map.insert( + std::make_pair(Label::BUS, this->declare_parameter("bus_tracker"))); + tracker_map.insert( + std::make_pair(Label::TRAILER, this->declare_parameter("trailer_tracker"))); + tracker_map.insert(std::make_pair( + Label::PEDESTRIAN, this->declare_parameter("pedestrian_tracker"))); + tracker_map.insert( + std::make_pair(Label::BICYCLE, this->declare_parameter("bicycle_tracker"))); + tracker_map.insert(std::make_pair( + Label::MOTORCYCLE, this->declare_parameter("motorcycle_tracker"))); + + processor_ = std::make_unique(tracker_map); + } + + // Data association initialization + { + const auto tmp = this->declare_parameter>("can_assign_matrix"); + const std::vector can_assign_matrix(tmp.begin(), tmp.end()); + const auto max_dist_matrix = this->declare_parameter>("max_dist_matrix"); + const auto max_area_matrix = this->declare_parameter>("max_area_matrix"); + const auto min_area_matrix = this->declare_parameter>("min_area_matrix"); + const auto max_rad_matrix = this->declare_parameter>("max_rad_matrix"); + const auto min_iou_matrix = this->declare_parameter>("min_iou_matrix"); + + data_association_ = std::make_unique( + can_assign_matrix, max_dist_matrix, max_area_matrix, min_area_matrix, max_rad_matrix, + min_iou_matrix); + } + + // Debugger + debugger_ = std::make_unique(*this); published_time_publisher_ = std::make_unique(this); } @@ -147,52 +156,33 @@ void MultiObjectTracker::onMeasurement( if (!self_transform) { return; } - /* transform to world coordinate */ autoware_auto_perception_msgs::msg::DetectedObjects transformed_objects; if (!object_recognition_utils::transformObjects( *input_objects_msg, world_frame_id_, tf_buffer_, transformed_objects)) { return; } - /* tracker prediction */ - for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) { - (*itr)->predict(measurement_time); - } - /* global nearest neighbor */ + ////// Tracker Process + //// Associate and update + /* prediction */ + processor_->predict(measurement_time); + /* object association */ std::unordered_map direct_assignment, reverse_assignment; - Eigen::MatrixXd score_matrix = data_association_->calcScoreMatrix( - transformed_objects, list_tracker_); // row : tracker, col : measurement - data_association_->assign(score_matrix, direct_assignment, reverse_assignment); - - /* tracker measurement update */ - int tracker_idx = 0; - for (auto tracker_itr = list_tracker_.begin(); tracker_itr != list_tracker_.end(); - ++tracker_itr, ++tracker_idx) { - if (direct_assignment.find(tracker_idx) != direct_assignment.end()) { // found - (*(tracker_itr)) - ->updateWithMeasurement( - transformed_objects.objects.at(direct_assignment.find(tracker_idx)->second), - measurement_time, *self_transform); - } else { // not found - (*(tracker_itr))->updateWithoutMeasurement(); - } - } - - /* life cycle check */ - checkTrackerLifeCycle(list_tracker_, measurement_time); - /* sanitize trackers */ - sanitizeTracker(list_tracker_, measurement_time); - - /* new tracker */ - for (size_t i = 0; i < transformed_objects.objects.size(); ++i) { - if (reverse_assignment.find(i) != reverse_assignment.end()) { // found - continue; - } - std::shared_ptr tracker = - createNewTracker(transformed_objects.objects.at(i), measurement_time, *self_transform); - if (tracker) list_tracker_.push_back(tracker); + { + const auto & list_tracker = processor_->getListTracker(); + const auto & detected_objects = transformed_objects; + // global nearest neighbor + Eigen::MatrixXd score_matrix = data_association_->calcScoreMatrix( + detected_objects, list_tracker); // row : tracker, col : measurement + data_association_->assign(score_matrix, direct_assignment, reverse_assignment); } + /* tracker update */ + processor_->update(transformed_objects, *self_transform, direct_assignment); + /* tracker pruning */ + processor_->prune(measurement_time); + /* spawn new tracker */ + processor_->spawn(transformed_objects, *self_transform, reverse_assignment); // debugger time debugger_->endMeasurementTime(this->now()); @@ -210,39 +200,12 @@ void MultiObjectTracker::onMeasurement( } } -std::shared_ptr MultiObjectTracker::createNewTracker( - const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, - const geometry_msgs::msg::Transform & self_transform) const -{ - const std::uint8_t label = object_recognition_utils::getHighestProbLabel(object.classification); - if (tracker_map_.count(label) != 0) { - const auto tracker = tracker_map_.at(label); - - if (tracker == "bicycle_tracker") { - return std::make_shared(time, object, self_transform); - } else if (tracker == "big_vehicle_tracker") { - return std::make_shared(time, object, self_transform); - } else if (tracker == "multi_vehicle_tracker") { - return std::make_shared(time, object, self_transform); - } else if (tracker == "normal_vehicle_tracker") { - return std::make_shared(time, object, self_transform); - } else if (tracker == "pass_through_tracker") { - return std::make_shared(time, object, self_transform); - } else if (tracker == "pedestrian_and_bicycle_tracker") { - return std::make_shared(time, object, self_transform); - } else if (tracker == "pedestrian_tracker") { - return std::make_shared(time, object, self_transform); - } - } - return std::make_shared(time, object, self_transform); -} - void MultiObjectTracker::onTimer() { const rclcpp::Time current_time = this->now(); - // check the publish period + // Check the publish period const auto elapsed_time = (current_time - last_published_time_).seconds(); - // if the elapsed time is over the period, publish objects with prediction + // If the elapsed time is over the period, publish objects with prediction constexpr double maximum_latency_ratio = 1.11; // 11% margin const double maximum_publish_latency = publisher_period_ * maximum_latency_ratio; if (elapsed_time > maximum_publish_latency) { @@ -252,10 +215,8 @@ void MultiObjectTracker::onTimer() void MultiObjectTracker::checkAndPublish(const rclcpp::Time & time) { - /* life cycle check */ - checkTrackerLifeCycle(list_tracker_, time); - /* sanitize trackers */ - sanitizeTracker(list_tracker_, time); + /* tracker pruning*/ + processor_->prune(time); // Publish publish(time); @@ -264,100 +225,6 @@ void MultiObjectTracker::checkAndPublish(const rclcpp::Time & time) last_published_time_ = this->now(); } -void MultiObjectTracker::checkTrackerLifeCycle( - std::list> & list_tracker, const rclcpp::Time & time) -{ - /* params */ - constexpr float max_elapsed_time = 1.0; - - /* delete tracker */ - for (auto itr = list_tracker.begin(); itr != list_tracker.end(); ++itr) { - const bool is_old = max_elapsed_time < (*itr)->getElapsedTimeFromLastUpdate(time); - if (is_old) { - auto erase_itr = itr; - --itr; - list_tracker.erase(erase_itr); - } - } -} - -void MultiObjectTracker::sanitizeTracker( - std::list> & list_tracker, const rclcpp::Time & time) -{ - constexpr float min_iou = 0.1; - constexpr float min_iou_for_unknown_object = 0.001; - constexpr double distance_threshold = 5.0; - /* delete collision tracker */ - for (auto itr1 = list_tracker.begin(); itr1 != list_tracker.end(); ++itr1) { - autoware_auto_perception_msgs::msg::TrackedObject object1; - if (!(*itr1)->getTrackedObject(time, object1)) continue; - for (auto itr2 = std::next(itr1); itr2 != list_tracker.end(); ++itr2) { - autoware_auto_perception_msgs::msg::TrackedObject object2; - if (!(*itr2)->getTrackedObject(time, object2)) continue; - const double distance = std::hypot( - object1.kinematics.pose_with_covariance.pose.position.x - - object2.kinematics.pose_with_covariance.pose.position.x, - object1.kinematics.pose_with_covariance.pose.position.y - - object2.kinematics.pose_with_covariance.pose.position.y); - if (distance_threshold < distance) { - continue; - } - - const double min_union_iou_area = 1e-2; - const auto iou = object_recognition_utils::get2dIoU(object1, object2, min_union_iou_area); - const auto & label1 = (*itr1)->getHighestProbLabel(); - const auto & label2 = (*itr2)->getHighestProbLabel(); - bool should_delete_tracker1 = false; - bool should_delete_tracker2 = false; - - // If at least one of them is UNKNOWN, delete the one with lower IOU. Because the UNKNOWN - // objects are not reliable. - if (label1 == Label::UNKNOWN || label2 == Label::UNKNOWN) { - if (min_iou_for_unknown_object < iou) { - if (label1 == Label::UNKNOWN && label2 == Label::UNKNOWN) { - if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) { - should_delete_tracker1 = true; - } else { - should_delete_tracker2 = true; - } - } else if (label1 == Label::UNKNOWN) { - should_delete_tracker1 = true; - } else if (label2 == Label::UNKNOWN) { - should_delete_tracker2 = true; - } - } - } else { // If neither is UNKNOWN, delete the one with lower IOU. - if (min_iou < iou) { - if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) { - should_delete_tracker1 = true; - } else { - should_delete_tracker2 = true; - } - } - } - - if (should_delete_tracker1) { - itr1 = list_tracker.erase(itr1); - --itr1; - break; - } else if (should_delete_tracker2) { - itr2 = list_tracker.erase(itr2); - --itr2; - } - } - } -} - -inline bool MultiObjectTracker::shouldTrackerPublish( - const std::shared_ptr tracker) const -{ - constexpr int measurement_count_threshold = 3; - if (tracker->getTotalMeasurementCount() < measurement_count_threshold) { - return false; - } - return true; -} - void MultiObjectTracker::publish(const rclcpp::Time & time) const { debugger_->startPublishTime(this->now()); @@ -369,28 +236,21 @@ void MultiObjectTracker::publish(const rclcpp::Time & time) const // Create output msg autoware_auto_perception_msgs::msg::TrackedObjects output_msg, tentative_objects_msg; output_msg.header.frame_id = world_frame_id_; - output_msg.header.stamp = time; - tentative_objects_msg.header = output_msg.header; - - for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) { - if (!shouldTrackerPublish(*itr)) { // for debug purpose - autoware_auto_perception_msgs::msg::TrackedObject object; - if (!(*itr)->getTrackedObject(time, object)) continue; - tentative_objects_msg.objects.push_back(object); - continue; - } - autoware_auto_perception_msgs::msg::TrackedObject object; - if (!(*itr)->getTrackedObject(time, object)) continue; - output_msg.objects.push_back(object); - } + processor_->getTrackedObjects(time, output_msg); // Publish tracked_objects_pub_->publish(output_msg); published_time_publisher_->publish_if_subscribed(tracked_objects_pub_, output_msg.header.stamp); - // Debugger Publish if enabled + // Publish debugger information if enabled debugger_->endPublishTime(this->now(), time); - debugger_->publishTentativeObjects(tentative_objects_msg); + + if (debugger_->shouldPublishTentativeObjects()) { + autoware_auto_perception_msgs::msg::TrackedObjects tentative_objects_msg; + tentative_objects_msg.header.frame_id = world_frame_id_; + processor_->getTentativeObjects(time, tentative_objects_msg); + debugger_->publishTentativeObjects(tentative_objects_msg); + } } RCLCPP_COMPONENTS_REGISTER_NODE(MultiObjectTracker) diff --git a/perception/multi_object_tracker/src/processor/processor.cpp b/perception/multi_object_tracker/src/processor/processor.cpp new file mode 100644 index 0000000000000..0d56e16b431e9 --- /dev/null +++ b/perception/multi_object_tracker/src/processor/processor.cpp @@ -0,0 +1,242 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// + +#include "multi_object_tracker/processor/processor.hpp" + +#include "multi_object_tracker/tracker/tracker.hpp" +#include "object_recognition_utils/object_recognition_utils.hpp" + +#include + +#include + +using Label = autoware_auto_perception_msgs::msg::ObjectClassification; + +TrackerProcessor::TrackerProcessor(const std::map & tracker_map) +: tracker_map_(tracker_map) +{ + // Set tracker lifetime parameters + max_elapsed_time_ = 1.0; // [s] + + // Set tracker overlap remover parameters + min_iou_ = 0.1; // [ratio] + min_iou_for_unknown_object_ = 0.001; // [ratio] + distance_threshold_ = 5.0; // [m] + + // Set tracker confidence threshold + confident_count_threshold_ = 3; // [count] +} + +void TrackerProcessor::predict(const rclcpp::Time & time) +{ + for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) { + (*itr)->predict(time); + } +} + +void TrackerProcessor::update( + const autoware_auto_perception_msgs::msg::DetectedObjects & detected_objects, + const geometry_msgs::msg::Transform & self_transform, + const std::unordered_map & direct_assignment) +{ + int tracker_idx = 0; + const auto & time = detected_objects.header.stamp; + for (auto tracker_itr = list_tracker_.begin(); tracker_itr != list_tracker_.end(); + ++tracker_itr, ++tracker_idx) { + if (direct_assignment.find(tracker_idx) != direct_assignment.end()) { // found + const auto & associated_object = + detected_objects.objects.at(direct_assignment.find(tracker_idx)->second); + (*(tracker_itr))->updateWithMeasurement(associated_object, time, self_transform); + } else { // not found + (*(tracker_itr))->updateWithoutMeasurement(); + } + } +} + +void TrackerProcessor::spawn( + const autoware_auto_perception_msgs::msg::DetectedObjects & detected_objects, + const geometry_msgs::msg::Transform & self_transform, + const std::unordered_map & reverse_assignment) +{ + const auto & time = detected_objects.header.stamp; + for (size_t i = 0; i < detected_objects.objects.size(); ++i) { + if (reverse_assignment.find(i) != reverse_assignment.end()) { // found + continue; + } + const auto & new_object = detected_objects.objects.at(i); + std::shared_ptr tracker = createNewTracker(new_object, time, self_transform); + if (tracker) list_tracker_.push_back(tracker); + } +} + +std::shared_ptr TrackerProcessor::createNewTracker( + const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const geometry_msgs::msg::Transform & self_transform) const +{ + const std::uint8_t label = object_recognition_utils::getHighestProbLabel(object.classification); + if (tracker_map_.count(label) != 0) { + const auto tracker = tracker_map_.at(label); + if (tracker == "bicycle_tracker") + return std::make_shared(time, object, self_transform); + if (tracker == "big_vehicle_tracker") + return std::make_shared(time, object, self_transform); + if (tracker == "multi_vehicle_tracker") + return std::make_shared(time, object, self_transform); + if (tracker == "normal_vehicle_tracker") + return std::make_shared(time, object, self_transform); + if (tracker == "pass_through_tracker") + return std::make_shared(time, object, self_transform); + if (tracker == "pedestrian_and_bicycle_tracker") + return std::make_shared(time, object, self_transform); + if (tracker == "pedestrian_tracker") + return std::make_shared(time, object, self_transform); + } + return std::make_shared(time, object, self_transform); +} + +void TrackerProcessor::prune(const rclcpp::Time & time) +{ + // Check tracker lifetime: if the tracker is old, delete it + removeOldTracker(time); + // Check tracker overlap: if the tracker is overlapped, delete the one with lower IOU + removeOverlappedTracker(time); +} + +void TrackerProcessor::removeOldTracker(const rclcpp::Time & time) +{ + // Check elapsed time from last update + for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) { + const bool is_old = max_elapsed_time_ < (*itr)->getElapsedTimeFromLastUpdate(time); + // If the tracker is old, delete it + if (is_old) { + auto erase_itr = itr; + --itr; + list_tracker_.erase(erase_itr); + } + } +} + +// This function removes overlapped trackers based on distance and IoU criteria +void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time) +{ + // Iterate through the list of trackers + for (auto itr1 = list_tracker_.begin(); itr1 != list_tracker_.end(); ++itr1) { + autoware_auto_perception_msgs::msg::TrackedObject object1; + if (!(*itr1)->getTrackedObject(time, object1)) continue; + + // Compare the current tracker with the remaining trackers + for (auto itr2 = std::next(itr1); itr2 != list_tracker_.end(); ++itr2) { + autoware_auto_perception_msgs::msg::TrackedObject object2; + if (!(*itr2)->getTrackedObject(time, object2)) continue; + + // Calculate the distance between the two objects + const double distance = std::hypot( + object1.kinematics.pose_with_covariance.pose.position.x - + object2.kinematics.pose_with_covariance.pose.position.x, + object1.kinematics.pose_with_covariance.pose.position.y - + object2.kinematics.pose_with_covariance.pose.position.y); + + // If the distance is too large, skip + if (distance > distance_threshold_) { + continue; + } + + // Check the Intersection over Union (IoU) between the two objects + const double min_union_iou_area = 1e-2; + const auto iou = object_recognition_utils::get2dIoU(object1, object2, min_union_iou_area); + const auto & label1 = (*itr1)->getHighestProbLabel(); + const auto & label2 = (*itr2)->getHighestProbLabel(); + bool should_delete_tracker1 = false; + bool should_delete_tracker2 = false; + + // If both trackers are UNKNOWN, delete the younger tracker + // If one side of the tracker is UNKNOWN, delete UNKNOWN objects + if (label1 == Label::UNKNOWN || label2 == Label::UNKNOWN) { + if (iou > min_iou_for_unknown_object_) { + if (label1 == Label::UNKNOWN && label2 == Label::UNKNOWN) { + if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) { + should_delete_tracker1 = true; + } else { + should_delete_tracker2 = true; + } + } else if (label1 == Label::UNKNOWN) { + should_delete_tracker1 = true; + } else if (label2 == Label::UNKNOWN) { + should_delete_tracker2 = true; + } + } + } else { // If neither object is UNKNOWN, delete the younger tracker + if (iou > min_iou_) { + if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) { + should_delete_tracker1 = true; + } else { + should_delete_tracker2 = true; + } + } + } + + // Delete the tracker + if (should_delete_tracker1) { + itr1 = list_tracker_.erase(itr1); + --itr1; + break; + } + if (should_delete_tracker2) { + itr2 = list_tracker_.erase(itr2); + --itr2; + } + } + } +} + +bool TrackerProcessor::isConfidentTracker(const std::shared_ptr & tracker) const +{ + // Confidence is determined by counting the number of measurements. + // If the number of measurements is equal to or greater than the threshold, the tracker is + // considered confident. + return tracker->getTotalMeasurementCount() >= confident_count_threshold_; +} + +void TrackerProcessor::getTrackedObjects( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObjects & tracked_objects) const +{ + tracked_objects.header.stamp = time; + for (const auto & tracker : list_tracker_) { + // Skip if the tracker is not confident + if (!isConfidentTracker(tracker)) continue; + // Get the tracked object, extrapolated to the given time + autoware_auto_perception_msgs::msg::TrackedObject tracked_object; + if (tracker->getTrackedObject(time, tracked_object)) { + tracked_objects.objects.push_back(tracked_object); + } + } +} + +void TrackerProcessor::getTentativeObjects( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const +{ + tentative_objects.header.stamp = time; + for (const auto & tracker : list_tracker_) { + if (!isConfidentTracker(tracker)) { + autoware_auto_perception_msgs::msg::TrackedObject tracked_object; + if (tracker->getTrackedObject(time, tracked_object)) { + tentative_objects.objects.push_back(tracked_object); + } + } + } +} From 06bb9bdab6398c717f5e5b234c0f35ad268e80c8 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 11 Apr 2024 15:38:54 +0900 Subject: [PATCH 49/57] fix(avoidance): fix invalid road bound distance calculation (#6781) fix(avoidance): fix invalid road shoulder distance calculation Signed-off-by: satoshi-ota --- planning/behavior_path_avoidance_module/src/utils.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index 6c2b72db0237d..f0d864f3fed38 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -874,8 +874,7 @@ double getRoadShoulderDistance( } { - const auto p2 = - calcOffsetPose(p_tmp, 0.0, (isOnRight(object) ? -100.0 : 100.0), 0.0).position; + const auto p2 = calcOffsetPose(p_tmp, 0.0, (isOnRight(object) ? -1.0 : 1.0), 0.0).position; const auto opt_intersect = tier4_autoware_utils::intersect(p1.second, p2, bound.at(i - 1), bound.at(i)); From a06122ce1bdbefae8c4b0bb0a7ce38c2f7edc407 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 11 Apr 2024 19:28:40 +0900 Subject: [PATCH 50/57] refactor(avoidance): rebuild parameter structure (#6786) * refactor(avoidance): unify similar param Signed-off-by: satoshi-ota * refactor(avoidance): rename misreading params Signed-off-by: satoshi-ota * refactor(avoidance): update parameter namespace Signed-off-by: satoshi-ota * refactor(avoidance): use prefix th instead of threshold Signed-off-by: satoshi-ota * refactor(avoidance): rename params Signed-off-by: satoshi-ota * refactor(AbLC): rename params Signed-off-by: satoshi-ota * refactor(avoidance): update yaml Signed-off-by: satoshi-ota * refactor(AbLC): update yaml Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../avoidance_by_lane_change.param.yaml | 52 ++-- .../src/manager.cpp | 24 +- .../config/avoidance.param.yaml | 292 +++++++++--------- .../data_structs.hpp | 20 +- .../behavior_path_avoidance_module/helper.hpp | 7 +- .../parameter_helper.hpp | 78 ++--- .../src/manager.cpp | 64 ++-- .../src/scene.cpp | 8 +- .../src/shift_line_generator.cpp | 8 +- .../src/utils.cpp | 4 +- 10 files changed, 268 insertions(+), 289 deletions(-) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lane_change.param.yaml b/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lane_change.param.yaml index ad5fe0b123f1d..384ef7bd285e9 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lane_change.param.yaml +++ b/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lane_change.param.yaml @@ -8,8 +8,8 @@ target_object: car: execute_num: 2 # [-] - moving_speed_threshold: 1.0 # [m/s] - moving_time_threshold: 1.0 # [s] + th_moving_speed: 1.0 # [m/s] + th_moving_time: 1.0 # [s] max_expand_ratio: 0.0 # [-] envelope_buffer_margin: 0.3 # [m] lateral_margin: @@ -18,8 +18,8 @@ hard_margin_for_parked_vehicle: 0.0 # [m] truck: execute_num: 2 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 1.0 + th_moving_speed: 1.0 # 3.6km/h + th_moving_time: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 lateral_margin: @@ -28,8 +28,8 @@ hard_margin_for_parked_vehicle: 0.0 # [m] bus: execute_num: 2 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 1.0 + th_moving_speed: 1.0 # 3.6km/h + th_moving_time: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 lateral_margin: @@ -38,8 +38,8 @@ hard_margin_for_parked_vehicle: 0.0 # [m] trailer: execute_num: 2 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 1.0 + th_moving_speed: 1.0 # 3.6km/h + th_moving_time: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 lateral_margin: @@ -48,8 +48,8 @@ hard_margin_for_parked_vehicle: 0.0 # [m] unknown: execute_num: 1 - moving_speed_threshold: 0.28 # 1.0km/h - moving_time_threshold: 1.0 + th_moving_speed: 0.28 # 1.0km/h + th_moving_time: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 lateral_margin: @@ -58,34 +58,34 @@ hard_margin_for_parked_vehicle: 0.0 # [m] bicycle: execute_num: 2 - moving_speed_threshold: 0.28 # 1.0km/h - moving_time_threshold: 1.0 + th_moving_speed: 0.28 # 1.0km/h + th_moving_time: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 lateral_margin: soft_margin: 0.0 # [m] - hard_margin: 0.0 # [m] - hard_margin_for_parked_vehicle: 0.0 # [m] + hard_margin: 1.0 # [m] + hard_margin_for_parked_vehicle: 1.0 # [m] motorcycle: execute_num: 2 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 1.0 + th_moving_speed: 1.0 # 3.6km/h + th_moving_time: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 lateral_margin: soft_margin: 0.0 # [m] - hard_margin: 0.0 # [m] - hard_margin_for_parked_vehicle: 0.0 # [m] + hard_margin: 1.0 # [m] + hard_margin_for_parked_vehicle: 1.0 # [m] pedestrian: execute_num: 2 - moving_speed_threshold: 0.28 # 1.0km/h - moving_time_threshold: 1.0 + th_moving_speed: 0.28 # 1.0km/h + th_moving_time: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 lateral_margin: soft_margin: 0.0 # [m] - hard_margin: 0.0 # [m] - hard_margin_for_parked_vehicle: 0.0 # [m] + hard_margin: 1.0 # [m] + hard_margin_for_parked_vehicle: 1.0 # [m] lower_distance_for_polygon_expansion: 0.0 # [m] upper_distance_for_polygon_expansion: 1.0 # [m] @@ -101,11 +101,3 @@ bicycle: false # [-] motorcycle: false # [-] pedestrian: false # [-] - - constraints: - # lateral constraints - lateral: - velocity: [1.0, 1.38, 11.1] # [m/s] - max_accel_values: [0.5, 0.5, 0.5] # [m/ss] - min_jerk_values: [0.2, 0.2, 0.2] # [m/sss] - max_jerk_values: [1.0, 1.0, 1.0] # [m/sss] diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp index 799364437955c..a3b28b4d63d06 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp @@ -65,10 +65,8 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) const auto get_object_param = [&](std::string && ns) { ObjectParameter param{}; param.execute_num = getOrDeclareParameter(*node, ns + "execute_num"); - param.moving_speed_threshold = - getOrDeclareParameter(*node, ns + "moving_speed_threshold"); - param.moving_time_threshold = - getOrDeclareParameter(*node, ns + "moving_time_threshold"); + param.moving_speed_threshold = getOrDeclareParameter(*node, ns + "th_moving_speed"); + param.moving_time_threshold = getOrDeclareParameter(*node, ns + "th_moving_time"); param.max_expand_ratio = getOrDeclareParameter(*node, ns + "max_expand_ratio"); param.envelope_buffer_margin = getOrDeclareParameter(*node, ns + "envelope_buffer_margin"); @@ -121,14 +119,18 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) p.object_check_goal_distance = getOrDeclareParameter(*node, ns + "object_check_goal_distance"); + p.object_last_seen_threshold = + getOrDeclareParameter(*node, ns + "max_compensation_time"); + } + + { + const std::string ns = "avoidance.target_filtering.parked_vehicle."; p.threshold_distance_object_is_on_center = - getOrDeclareParameter(*node, ns + "threshold_distance_object_is_on_center"); + getOrDeclareParameter(*node, ns + "th_offset_from_centerline"); p.object_check_shiftable_ratio = - getOrDeclareParameter(*node, ns + "object_check_shiftable_ratio"); + getOrDeclareParameter(*node, ns + "th_shiftable_ratio"); p.object_check_min_road_shoulder_width = - getOrDeclareParameter(*node, ns + "object_check_min_road_shoulder_width"); - p.object_last_seen_threshold = - getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); + getOrDeclareParameter(*node, ns + "min_road_shoulder_width"); } { @@ -137,9 +139,9 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) p.closest_distance_to_wait_and_see_for_ambiguous_vehicle = getOrDeclareParameter(*node, ns + "closest_distance_to_wait_and_see"); p.time_threshold_for_ambiguous_vehicle = - getOrDeclareParameter(*node, ns + "condition.time_threshold"); + getOrDeclareParameter(*node, ns + "condition.th_stopped_time"); p.distance_threshold_for_ambiguous_vehicle = - getOrDeclareParameter(*node, ns + "condition.distance_threshold"); + getOrDeclareParameter(*node, ns + "condition.th_moving_distance"); p.object_ignore_section_traffic_light_in_front_distance = getOrDeclareParameter(*node, ns + "ignore_area.traffic_light.front_distance"); p.object_ignore_section_crosswalk_in_front_distance = diff --git a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml index b7b8d8434b9c4..92f533bc63872 100644 --- a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml +++ b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml @@ -2,11 +2,11 @@ /**: ros__parameters: avoidance: - resample_interval_for_planning: 0.3 # [m] - resample_interval_for_output: 4.0 # [m] + resample_interval_for_planning: 0.3 # [m] FOR DEVELOPER + resample_interval_for_output: 4.0 # [m] FOR DEVELOPER + # avoidance module common setting enable_bound_clipping: false - enable_cancel_maneuver: true disable_path_update: false # drivable area setting @@ -16,215 +16,203 @@ use_hatched_road_markings: true use_freespace_areas: true - # for debug - publish_debug_marker: false - print_debug_info: false - # avoidance is performed for the object type with true target_object: car: - execute_num: 1 # [-] - moving_speed_threshold: 1.0 # [m/s] - moving_time_threshold: 2.0 # [s] + th_moving_speed: 1.0 # [m/s] + th_moving_time: 2.0 # [s] + longitudinal_margin: 0.0 # [m] lateral_margin: - soft_margin: 0.7 # [m] - hard_margin: 0.3 # [m] - hard_margin_for_parked_vehicle: 0.3 # [m] - max_expand_ratio: 0.0 # [-] - envelope_buffer_margin: 0.5 # [m] - safety_buffer_longitudinal: 0.0 # [m] - use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance. + soft_margin: 0.3 # [m] + hard_margin: 0.2 # [m] + hard_margin_for_parked_vehicle: 0.7 # [m] + max_expand_ratio: 0.0 # [-] FOR DEVELOPER + envelope_buffer_margin: 0.5 # [m] FOR DEVELOPER + use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance. truck: - execute_num: 1 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 2.0 + th_moving_speed: 1.0 + th_moving_time: 2.0 + longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.9 # [m] - hard_margin: 0.1 # [m] - hard_margin_for_parked_vehicle: 0.1 # [m] + soft_margin: 0.3 + hard_margin: 0.2 + hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true bus: - execute_num: 1 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 2.0 + th_moving_speed: 1.0 + th_moving_time: 2.0 + longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.9 # [m] - hard_margin: 0.1 # [m] - hard_margin_for_parked_vehicle: 0.1 # [m] + soft_margin: 0.3 + hard_margin: 0.2 + hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true trailer: - execute_num: 1 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 2.0 + th_moving_speed: 1.0 + th_moving_time: 2.0 + longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.9 # [m] - hard_margin: 0.1 # [m] - hard_margin_for_parked_vehicle: 0.1 # [m] + soft_margin: 0.3 + hard_margin: 0.2 + hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true unknown: - execute_num: 1 - moving_speed_threshold: 0.28 # 1.0km/h - moving_time_threshold: 1.0 + th_moving_speed: 0.28 + th_moving_time: 1.0 + longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.7 # [m] - hard_margin: -0.2 # [m] - hard_margin_for_parked_vehicle: -0.2 # [m] + soft_margin: 0.7 + hard_margin: -0.2 + hard_margin_for_parked_vehicle: -0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 - safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true bicycle: - execute_num: 1 - moving_speed_threshold: 0.28 # 1.0km/h - moving_time_threshold: 1.0 + th_moving_speed: 0.28 + th_moving_time: 1.0 + longitudinal_margin: 1.0 lateral_margin: - soft_margin: 0.7 # [m] - hard_margin: 0.5 # [m] - hard_margin_for_parked_vehicle: 0.5 # [m] + soft_margin: 0.7 + hard_margin: 0.5 + hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - safety_buffer_longitudinal: 1.0 use_conservative_buffer_longitudinal: true motorcycle: - execute_num: 1 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 1.0 + th_moving_speed: 1.0 + th_moving_time: 1.0 + longitudinal_margin: 1.0 lateral_margin: - soft_margin: 0.7 # [m] - hard_margin: 0.3 # [m] - hard_margin_for_parked_vehicle: 0.3 # [m] + soft_margin: 0.7 + hard_margin: 0.3 + hard_margin_for_parked_vehicle: 0.3 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - safety_buffer_longitudinal: 1.0 use_conservative_buffer_longitudinal: true pedestrian: - execute_num: 1 - moving_speed_threshold: 0.28 # 1.0km/h - moving_time_threshold: 1.0 + th_moving_speed: 0.28 + th_moving_time: 1.0 + longitudinal_margin: 1.0 lateral_margin: - soft_margin: 0.7 # [m] - hard_margin: 0.5 # [m] - hard_margin_for_parked_vehicle: 0.5 # [m] + soft_margin: 0.7 + hard_margin: 0.5 + hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - safety_buffer_longitudinal: 1.0 use_conservative_buffer_longitudinal: true - lower_distance_for_polygon_expansion: 30.0 # [m] - upper_distance_for_polygon_expansion: 100.0 # [m] + lower_distance_for_polygon_expansion: 30.0 # [m] FOR DEVELOPER + upper_distance_for_polygon_expansion: 100.0 # [m] FOR DEVELOPER # For target object filtering target_filtering: # avoidance target type target_type: - car: true # [-] - truck: true # [-] - bus: true # [-] - trailer: true # [-] - unknown: true # [-] - bicycle: true # [-] - motorcycle: true # [-] - pedestrian: true # [-] + car: true # [-] + truck: true # [-] + bus: true # [-] + trailer: true # [-] + unknown: true # [-] + bicycle: true # [-] + motorcycle: true # [-] + pedestrian: true # [-] # detection range - object_check_goal_distance: 20.0 # [m] - object_check_return_pose_distance: 20.0 # [m] - # filtering parking objects - threshold_distance_object_is_on_center: 1.0 # [m] - object_check_shiftable_ratio: 0.6 # [-] - object_check_min_road_shoulder_width: 0.5 # [m] + object_check_goal_distance: 20.0 # [m] + object_check_return_pose_distance: 20.0 # [m] # lost object compensation - object_last_seen_threshold: 2.0 + max_compensation_time: 2.0 # detection area generation parameters detection_area: - static: false # [-] - min_forward_distance: 50.0 # [m] - max_forward_distance: 150.0 # [m] - backward_distance: 10.0 # [m] + static: false # [-] + min_forward_distance: 50.0 # [m] + max_forward_distance: 150.0 # [m] + backward_distance: 10.0 # [m] + + # filtering parking objects + parked_vehicle: + th_offset_from_centerline: 1.0 # [m] + th_shiftable_ratio: 0.8 # [-] + min_road_shoulder_width: 0.5 # [m] FOR DEVELOPER # params for avoidance of vehicle type objects that are ambiguous as to whether they are parked. avoidance_for_ambiguous_vehicle: - enable: false # [-] - closest_distance_to_wait_and_see: 10.0 # [m] + enable: true # [-] + closest_distance_to_wait_and_see: 10.0 # [m] condition: - time_threshold: 1.0 # [s] - distance_threshold: 1.0 # [m] + th_stopped_time: 3.0 # [s] + th_moving_distance: 1.0 # [m] ignore_area: traffic_light: - front_distance: 100.0 # [m] + front_distance: 100.0 # [m] crosswalk: - front_distance: 30.0 # [m] - behind_distance: 30.0 # [m] + front_distance: 30.0 # [m] + behind_distance: 30.0 # [m] # params for filtering objects that are in intersection intersection: - yaw_deviation: 0.349 # [rad] (default 20.0deg) + yaw_deviation: 0.349 # [rad] (default 20.0deg) # For safety check safety_check: # safety check target type target_type: - car: true # [-] - truck: true # [-] - bus: true # [-] - trailer: true # [-] - unknown: false # [-] - bicycle: true # [-] - motorcycle: true # [-] - pedestrian: true # [-] + car: true # [-] + truck: true # [-] + bus: true # [-] + trailer: true # [-] + unknown: false # [-] + bicycle: true # [-] + motorcycle: true # [-] + pedestrian: true # [-] # safety check configuration - enable: true # [-] - check_current_lane: false # [-] - check_shift_side_lane: true # [-] - check_other_side_lane: false # [-] - check_unavoidable_object: false # [-] - check_other_object: true # [-] + enable: true # [-] + check_current_lane: false # [-] + check_shift_side_lane: true # [-] + check_other_side_lane: false # [-] + check_unavoidable_object: false # [-] + check_other_object: true # [-] # collision check parameters - check_all_predicted_path: false # [-] - safety_check_backward_distance: 100.0 # [m] - hysteresis_factor_expand_rate: 1.5 # [-] - hysteresis_factor_safe_count: 10 # [-] + check_all_predicted_path: false # [-] + safety_check_backward_distance: 100.0 # [m] + hysteresis_factor_expand_rate: 1.5 # [-] + hysteresis_factor_safe_count: 3 # [-] # predicted path parameters - min_velocity: 1.38 # [m/s] - max_velocity: 50.0 # [m/s] - time_resolution: 0.5 # [s] - time_horizon_for_front_object: 3.0 # [s] - time_horizon_for_rear_object: 10.0 # [s] - delay_until_departure: 0.0 # [s] + min_velocity: 1.38 # [m/s] + max_velocity: 50.0 # [m/s] + time_resolution: 0.5 # [s] + time_horizon_for_front_object: 3.0 # [s] + time_horizon_for_rear_object: 10.0 # [s] + delay_until_departure: 0.0 # [s] # rss parameters - extended_polygon_policy: "along_path" # [-] select "rectangle" or "along_path" - expected_front_deceleration: -1.0 # [m/ss] - expected_rear_deceleration: -1.0 # [m/ss] - rear_vehicle_reaction_time: 2.0 # [s] - rear_vehicle_safety_time_margin: 1.0 # [s] - lateral_distance_max_threshold: 0.75 # [m] - longitudinal_distance_min_threshold: 3.0 # [m] - longitudinal_velocity_delta_time: 0.8 # [s] + extended_polygon_policy: "along_path" # [-] select "rectangle" or "along_path" + expected_front_deceleration: -1.0 # [m/ss] + expected_rear_deceleration: -1.0 # [m/ss] + rear_vehicle_reaction_time: 2.0 # [s] + rear_vehicle_safety_time_margin: 1.0 # [s] + lateral_distance_max_threshold: 2.0 # [m] + longitudinal_distance_min_threshold: 3.0 # [m] + longitudinal_velocity_delta_time: 0.0 # [s] # For avoidance maneuver avoidance: # avoidance lateral parameters lateral: - lateral_execution_threshold: 0.09 # [m] - lateral_small_shift_threshold: 0.101 # [m] - lateral_avoid_check_threshold: 0.1 # [m] - soft_road_shoulder_margin: 0.3 # [m] - hard_road_shoulder_margin: 0.3 # [m] - max_right_shift_length: 5.0 - max_left_shift_length: 5.0 - max_deviation_from_lane: 0.5 # [m] + th_avoid_execution: 0.09 # [m] FOR DEVELOPER + th_small_shift_length: 0.101 # [m] FOR DEVELOPER + soft_drivable_bound_margin: 0.3 # [m] + hard_drivable_bound_margin: 0.3 # [m] + max_right_shift_length: 5.0 # [m] FOR DEVELOPER + max_left_shift_length: 5.0 # [m] FOR DEVELOPER + max_deviation_from_lane: 0.2 # [m] # approve the next shift line after reaching this percentage of the current shift line length. - # this parameter should be within range of 0.0 to 1.0. # this parameter is added to allow waiting for the return of shift approval until the occlusion behind the avoid target is clear. - # this feature can be disabled by setting this parameter to 1.0. (in that case, avoidance module creates return shift as soon as possible.) + # this feature can be disabled by setting this parameter to 0.0. ratio_for_return_shift_approval: 0.5 # [-] # avoidance distance parameters longitudinal: @@ -232,17 +220,21 @@ max_prepare_time: 2.0 # [s] min_prepare_distance: 1.0 # [m] min_slow_down_speed: 1.38 # [m/s] - buf_slow_down_speed: 0.56 # [m/s] - nominal_avoidance_speed: 8.33 # [m/s] + buf_slow_down_speed: 0.56 # [m/s] FOR DEVELOPER + nominal_avoidance_speed: 8.33 # [m/s] FOR DEVELOPER # return dead line return_dead_line: goal: enable: true # [-] - buffer: 30.0 # [m] + buffer: 3.0 # [m] traffic_light: enable: true # [-] buffer: 3.0 # [m] + # For cancel maneuver + cancel: + enable: true # [-] + # For yield maneuver yield: enable: true # [-] @@ -251,7 +243,7 @@ # For stop maneuver stop: max_distance: 20.0 # [m] - stop_buffer: 1.0 # [m] + stop_buffer: 1.0 # [m] FOR DEVELOPER policy: # policy for rtc request. select "per_shift_line" or "per_avoidance_maneuver". @@ -273,6 +265,10 @@ # if true, module doesn't wait deceleration and outputs avoidance path by best effort margin. use_shorten_margin_immediately: true # [-] + # -------------------------------------- + # FOLLOWING PARAMETERS ARE FOR DEVELOPER + # -------------------------------------- + constraints: # lateral constraints lateral: @@ -292,8 +288,12 @@ shift_line_pipeline: trim: - quantize_filter_threshold: 0.1 - same_grad_filter_1_threshold: 0.1 - same_grad_filter_2_threshold: 0.2 - same_grad_filter_3_threshold: 0.5 - sharp_shift_filter_threshold: 0.2 + quantize_size: 0.1 + th_similar_grad_1: 0.1 + th_similar_grad_2: 0.2 + th_similar_grad_3: 0.5 + + # for debug + debug: + marker: false + console: false diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp index fd841ede37e70..bc66598d3ee90 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp @@ -75,7 +75,7 @@ struct ObjectParameter double lateral_hard_margin_for_parked_vehicle{1.0}; - double safety_buffer_longitudinal{0.0}; + double longitudinal_margin{0.0}; bool use_conservative_buffer_longitudinal{true}; }; @@ -243,11 +243,11 @@ struct AvoidanceParameters // The margin is configured so that the generated avoidance trajectory does not come near to the // road shoulder. - double soft_road_shoulder_margin{1.0}; + double soft_drivable_bound_margin{1.0}; // The margin is configured so that the generated avoidance trajectory does not come near to the // road shoulder. - double hard_road_shoulder_margin{1.0}; + double hard_drivable_bound_margin{1.0}; // Even if the obstacle is very large, it will not avoid more than this length for right direction double max_right_shift_length{0.0}; @@ -276,26 +276,20 @@ struct AvoidanceParameters // line. double lateral_small_shift_threshold{0.0}; - // use for judge if the ego is shifting or not. - double lateral_avoid_check_threshold{0.0}; - // use for return shift approval. double ratio_for_return_shift_approval{0.0}; // For shift line generation process. The continuous shift length is quantized by this value. - double quantize_filter_threshold{0.0}; + double quantize_size{0.0}; // For shift line generation process. Merge small shift lines. (First step) - double same_grad_filter_1_threshold{0.0}; + double th_similar_grad_1{0.0}; // For shift line generation process. Merge small shift lines. (Second step) - double same_grad_filter_2_threshold{0.0}; + double th_similar_grad_2{0.0}; // For shift line generation process. Merge small shift lines. (Third step) - double same_grad_filter_3_threshold{0.0}; - - // For shift line generation process. Remove sharp(=jerky) shift line. - double sharp_shift_filter_threshold{0.0}; + double th_similar_grad_3{0.0}; // policy bool use_shorten_margin_immediately{false}; diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp index 4ff02df97bd89..2e481e7c98e44 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp @@ -151,15 +151,14 @@ class AvoidanceHelper const auto & additional_buffer_longitudinal = object_parameter.use_conservative_buffer_longitudinal ? data_->parameters.base_link2front : 0.0; - return object_parameter.safety_buffer_longitudinal + additional_buffer_longitudinal; + return object_parameter.longitudinal_margin + additional_buffer_longitudinal; } double getRearConstantDistance(const ObjectData & object) const { const auto object_type = utils::getHighestProbLabel(object.object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); - return object_parameter.safety_buffer_longitudinal + data_->parameters.base_link2rear + - object.length; + return object_parameter.longitudinal_margin + data_->parameters.base_link2rear + object.length; } double getEgoShift() const @@ -370,7 +369,7 @@ class AvoidanceHelper bool isShifted() const { - return std::abs(getEgoShift()) > parameters_->lateral_avoid_check_threshold; + return std::abs(getEgoShift()) > parameters_->lateral_execution_threshold; } bool isInitialized() const diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp index fbfec58abe4da..5b8963c7ca22d 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp @@ -40,10 +40,7 @@ AvoidanceParameters getParameter(rclcpp::Node * node) p.resample_interval_for_output = getOrDeclareParameter(*node, ns + "resample_interval_for_output"); p.enable_bound_clipping = getOrDeclareParameter(*node, ns + "enable_bound_clipping"); - p.enable_cancel_maneuver = getOrDeclareParameter(*node, ns + "enable_cancel_maneuver"); p.disable_path_update = getOrDeclareParameter(*node, ns + "disable_path_update"); - p.publish_debug_marker = getOrDeclareParameter(*node, ns + "publish_debug_marker"); - p.print_debug_info = getOrDeclareParameter(*node, ns + "print_debug_info"); } // drivable area @@ -61,11 +58,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node) { const auto get_object_param = [&](std::string && ns) { ObjectParameter param{}; - param.execute_num = getOrDeclareParameter(*node, ns + "execute_num"); - param.moving_speed_threshold = - getOrDeclareParameter(*node, ns + "moving_speed_threshold"); - param.moving_time_threshold = - getOrDeclareParameter(*node, ns + "moving_time_threshold"); + param.moving_speed_threshold = getOrDeclareParameter(*node, ns + "th_moving_speed"); + param.moving_time_threshold = getOrDeclareParameter(*node, ns + "th_moving_time"); param.max_expand_ratio = getOrDeclareParameter(*node, ns + "max_expand_ratio"); param.envelope_buffer_margin = getOrDeclareParameter(*node, ns + "envelope_buffer_margin"); @@ -75,8 +69,7 @@ AvoidanceParameters getParameter(rclcpp::Node * node) getOrDeclareParameter(*node, ns + "lateral_margin.hard_margin"); param.lateral_hard_margin_for_parked_vehicle = getOrDeclareParameter(*node, ns + "lateral_margin.hard_margin_for_parked_vehicle"); - param.safety_buffer_longitudinal = - getOrDeclareParameter(*node, ns + "safety_buffer_longitudinal"); + param.longitudinal_margin = getOrDeclareParameter(*node, ns + "longitudinal_margin"); param.use_conservative_buffer_longitudinal = getOrDeclareParameter(*node, ns + "use_conservative_buffer_longitudinal"); return param; @@ -124,16 +117,20 @@ AvoidanceParameters getParameter(rclcpp::Node * node) getOrDeclareParameter(*node, ns + "object_check_goal_distance"); p.object_check_return_pose_distance = getOrDeclareParameter(*node, ns + "object_check_return_pose_distance"); - p.threshold_distance_object_is_on_center = - getOrDeclareParameter(*node, ns + "threshold_distance_object_is_on_center"); - p.object_check_shiftable_ratio = - getOrDeclareParameter(*node, ns + "object_check_shiftable_ratio"); - p.object_check_min_road_shoulder_width = - getOrDeclareParameter(*node, ns + "object_check_min_road_shoulder_width"); p.object_check_yaw_deviation = getOrDeclareParameter(*node, ns + "intersection.yaw_deviation"); p.object_last_seen_threshold = - getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); + getOrDeclareParameter(*node, ns + "max_compensation_time"); + } + + { + const std::string ns = "avoidance.target_filtering.parked_vehicle."; + p.threshold_distance_object_is_on_center = + getOrDeclareParameter(*node, ns + "th_offset_from_centerline"); + p.object_check_shiftable_ratio = + getOrDeclareParameter(*node, ns + "th_shiftable_ratio"); + p.object_check_min_road_shoulder_width = + getOrDeclareParameter(*node, ns + "min_road_shoulder_width"); } { @@ -142,9 +139,9 @@ AvoidanceParameters getParameter(rclcpp::Node * node) p.closest_distance_to_wait_and_see_for_ambiguous_vehicle = getOrDeclareParameter(*node, ns + "closest_distance_to_wait_and_see"); p.time_threshold_for_ambiguous_vehicle = - getOrDeclareParameter(*node, ns + "condition.time_threshold"); + getOrDeclareParameter(*node, ns + "condition.th_stopped_time"); p.distance_threshold_for_ambiguous_vehicle = - getOrDeclareParameter(*node, ns + "condition.distance_threshold"); + getOrDeclareParameter(*node, ns + "condition.th_moving_distance"); p.object_ignore_section_traffic_light_in_front_distance = getOrDeclareParameter(*node, ns + "ignore_area.traffic_light.front_distance"); p.object_ignore_section_crosswalk_in_front_distance = @@ -244,16 +241,13 @@ AvoidanceParameters getParameter(rclcpp::Node * node) // avoidance maneuver (lateral) { const std::string ns = "avoidance.avoidance.lateral."; - p.soft_road_shoulder_margin = - getOrDeclareParameter(*node, ns + "soft_road_shoulder_margin"); - p.hard_road_shoulder_margin = - getOrDeclareParameter(*node, ns + "hard_road_shoulder_margin"); - p.lateral_execution_threshold = - getOrDeclareParameter(*node, ns + "lateral_execution_threshold"); + p.soft_drivable_bound_margin = + getOrDeclareParameter(*node, ns + "soft_drivable_bound_margin"); + p.hard_drivable_bound_margin = + getOrDeclareParameter(*node, ns + "hard_drivable_bound_margin"); + p.lateral_execution_threshold = getOrDeclareParameter(*node, ns + "th_avoid_execution"); p.lateral_small_shift_threshold = - getOrDeclareParameter(*node, ns + "lateral_small_shift_threshold"); - p.lateral_avoid_check_threshold = - getOrDeclareParameter(*node, ns + "lateral_avoid_check_threshold"); + getOrDeclareParameter(*node, ns + "th_small_shift_length"); p.max_right_shift_length = getOrDeclareParameter(*node, ns + "max_right_shift_length"); p.max_left_shift_length = getOrDeclareParameter(*node, ns + "max_left_shift_length"); p.max_deviation_from_lane = @@ -289,6 +283,12 @@ AvoidanceParameters getParameter(rclcpp::Node * node) getOrDeclareParameter(*node, ns + "traffic_light.buffer"); } + // cancel + { + const std::string ns = "avoidance.cancel."; + p.enable_cancel_maneuver = getOrDeclareParameter(*node, ns + "enable"); + } + // yield { const std::string ns = "avoidance.yield."; @@ -369,17 +369,19 @@ AvoidanceParameters getParameter(rclcpp::Node * node) // shift line pipeline { const std::string ns = "avoidance.shift_line_pipeline."; - p.quantize_filter_threshold = - getOrDeclareParameter(*node, ns + "trim.quantize_filter_threshold"); - p.same_grad_filter_1_threshold = - getOrDeclareParameter(*node, ns + "trim.same_grad_filter_1_threshold"); - p.same_grad_filter_2_threshold = - getOrDeclareParameter(*node, ns + "trim.same_grad_filter_2_threshold"); - p.same_grad_filter_3_threshold = - getOrDeclareParameter(*node, ns + "trim.same_grad_filter_3_threshold"); - p.sharp_shift_filter_threshold = - getOrDeclareParameter(*node, ns + "trim.sharp_shift_filter_threshold"); + p.quantize_size = getOrDeclareParameter(*node, ns + "trim.quantize_size"); + p.th_similar_grad_1 = getOrDeclareParameter(*node, ns + "trim.th_similar_grad_1"); + p.th_similar_grad_2 = getOrDeclareParameter(*node, ns + "trim.th_similar_grad_2"); + p.th_similar_grad_3 = getOrDeclareParameter(*node, ns + "trim.th_similar_grad_3"); } + + // debug + { + const std::string ns = "avoidance.debug."; + p.publish_debug_marker = getOrDeclareParameter(*node, ns + "marker"); + p.print_debug_info = getOrDeclareParameter(*node, ns + "console"); + } + return p; } } // namespace behavior_path_planner diff --git a/planning/behavior_path_avoidance_module/src/manager.cpp b/planning/behavior_path_avoidance_module/src/manager.cpp index 5ce63987621ed..3261214d1b9b6 100644 --- a/planning/behavior_path_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_module/src/manager.cpp @@ -46,18 +46,11 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "enable_safety_check", p->enable_safety_check); - updateParam(parameters, ns + "publish_debug_marker", p->publish_debug_marker); - updateParam(parameters, ns + "print_debug_info", p->print_debug_info); - } - const auto update_object_param = [&p, ¶meters]( const auto & semantic, const std::string & ns) { auto & config = p->object_parameters.at(semantic); - updateParam(parameters, ns + "moving_speed_threshold", config.moving_speed_threshold); - updateParam(parameters, ns + "moving_time_threshold", config.moving_time_threshold); + updateParam(parameters, ns + "th_moving_speed", config.moving_speed_threshold); + updateParam(parameters, ns + "th_moving_time", config.moving_time_threshold); updateParam(parameters, ns + "max_expand_ratio", config.max_expand_ratio); updateParam(parameters, ns + "envelope_buffer_margin", config.envelope_buffer_margin); updateParam(parameters, ns + "lateral_margin.soft_margin", config.lateral_soft_margin); @@ -65,8 +58,7 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector( parameters, ns + "lateral_margin.hard_margin_for_parked_vehicle", config.lateral_hard_margin_for_parked_vehicle); - updateParam( - parameters, ns + "safety_buffer_longitudinal", config.safety_buffer_longitudinal); + updateParam(parameters, ns + "longitudinal_margin", config.longitudinal_margin); updateParam( parameters, ns + "use_conservative_buffer_longitudinal", config.use_conservative_buffer_longitudinal); @@ -113,16 +105,16 @@ void AvoidanceModuleManager::updateModuleParams(const std::vectorobject_check_goal_distance); updateParam( parameters, ns + "object_check_return_pose_distance", p->object_check_return_pose_distance); + updateParam(parameters, ns + "max_compensation_time", p->object_last_seen_threshold); + } + + { + const std::string ns = "avoidance.target_filtering.parked_vehicle."; updateParam( - parameters, ns + "threshold_distance_object_is_on_center", - p->threshold_distance_object_is_on_center); - updateParam( - parameters, ns + "object_check_shiftable_ratio", p->object_check_shiftable_ratio); - updateParam( - parameters, ns + "object_check_min_road_shoulder_width", - p->object_check_min_road_shoulder_width); + parameters, ns + "th_offset_from_centerline", p->threshold_distance_object_is_on_center); + updateParam(parameters, ns + "th_shiftable_ratio", p->object_check_shiftable_ratio); updateParam( - parameters, ns + "object_last_seen_threshold", p->object_last_seen_threshold); + parameters, ns + "min_road_shoulder_width", p->object_check_min_road_shoulder_width); } { @@ -142,9 +134,9 @@ void AvoidanceModuleManager::updateModuleParams(const std::vectorclosest_distance_to_wait_and_see_for_ambiguous_vehicle); updateParam( - parameters, ns + "condition.time_threshold", p->time_threshold_for_ambiguous_vehicle); + parameters, ns + "condition.th_stopped_time", p->time_threshold_for_ambiguous_vehicle); updateParam( - parameters, ns + "condition.distance_threshold", p->distance_threshold_for_ambiguous_vehicle); + parameters, ns + "condition.th_moving_distance", p->distance_threshold_for_ambiguous_vehicle); updateParam( parameters, ns + "ignore_area.traffic_light.front_distance", p->object_ignore_section_traffic_light_in_front_distance); @@ -163,14 +155,12 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "th_avoid_execution", p->lateral_execution_threshold); + updateParam(parameters, ns + "th_small_shift_length", p->lateral_small_shift_threshold); updateParam( - parameters, ns + "lateral_execution_threshold", p->lateral_execution_threshold); + parameters, ns + "soft_drivable_bound_margin", p->soft_drivable_bound_margin); updateParam( - parameters, ns + "lateral_small_shift_threshold", p->lateral_small_shift_threshold); - updateParam( - parameters, ns + "lateral_avoid_check_threshold", p->lateral_avoid_check_threshold); - updateParam(parameters, ns + "soft_road_shoulder_margin", p->soft_road_shoulder_margin); - updateParam(parameters, ns + "hard_road_shoulder_margin", p->hard_road_shoulder_margin); + parameters, ns + "hard_drivable_bound_margin", p->hard_drivable_bound_margin); } { @@ -259,16 +249,16 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector( - parameters, ns + "trim.quantize_filter_threshold", p->quantize_filter_threshold); - updateParam( - parameters, ns + "trim.same_grad_filter_1_threshold", p->same_grad_filter_1_threshold); - updateParam( - parameters, ns + "trim.same_grad_filter_2_threshold", p->same_grad_filter_2_threshold); - updateParam( - parameters, ns + "trim.same_grad_filter_3_threshold", p->same_grad_filter_3_threshold); - updateParam( - parameters, ns + "trim.sharp_shift_filter_threshold", p->sharp_shift_filter_threshold); + updateParam(parameters, ns + "trim.quantize_size", p->quantize_size); + updateParam(parameters, ns + "trim.th_similar_grad_1", p->th_similar_grad_1); + updateParam(parameters, ns + "trim.th_similar_grad_2", p->th_similar_grad_2); + updateParam(parameters, ns + "trim.th_similar_grad_3", p->th_similar_grad_3); + } + + { + const std::string ns = "avoidance.debug."; + updateParam(parameters, ns + "marker", p->publish_debug_marker); + updateParam(parameters, ns + "console", p->print_debug_info); } std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) { diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index 33f58c6a08dfc..b16395f825385 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -162,7 +162,7 @@ bool AvoidanceModule::isSatisfiedSuccessCondition(const AvoidancePlanningData & const bool has_shift_point = !path_shifter_.getShiftLines().empty(); const bool has_base_offset = - std::abs(path_shifter_.getBaseOffset()) > parameters_->lateral_avoid_check_threshold; + std::abs(path_shifter_.getBaseOffset()) > parameters_->lateral_execution_threshold; // Nothing to do. -> EXIT. if (!has_shift_point && !has_base_offset) { @@ -734,7 +734,7 @@ bool AvoidanceModule::isSafePath( for (size_t i = ego_idx; i < shifted_path.shift_length.size(); i++) { const auto length = shifted_path.shift_length.at(i); - if (parameters_->lateral_avoid_check_threshold < length) { + if (parameters_->lateral_execution_threshold < length) { return true; } } @@ -746,7 +746,7 @@ bool AvoidanceModule::isSafePath( for (size_t i = ego_idx; i < shifted_path.shift_length.size(); i++) { const auto length = shifted_path.shift_length.at(i); - if (parameters_->lateral_avoid_check_threshold < -1.0 * length) { + if (parameters_->lateral_execution_threshold < -1.0 * length) { return true; } } @@ -1222,7 +1222,7 @@ bool AvoidanceModule::isValidShiftLine( // check if the vehicle is in road. (yaw angle is not considered) { const auto minimum_distance = 0.5 * planner_data_->parameters.vehicle_width + - parameters_->hard_road_shoulder_margin - + parameters_->hard_drivable_bound_margin - parameters_->max_deviation_from_lane; const size_t start_idx = shift_lines.front().start_idx; diff --git a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp index 5a8fd35f6d618..9137048945fa1 100644 --- a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp @@ -871,7 +871,7 @@ AvoidLineArray ShiftLineGenerator::applyTrimProcess( // - Combine avoid points that have almost same gradient. // this is to remove the noise. { - const auto THRESHOLD = parameters_->same_grad_filter_1_threshold; + const auto THRESHOLD = parameters_->th_similar_grad_1; applySimilarGradFilter(sl_array_trimmed, THRESHOLD); debug.step3_grad_filtered_1st = sl_array_trimmed; } @@ -879,7 +879,7 @@ AvoidLineArray ShiftLineGenerator::applyTrimProcess( // - Quantize the shift length to reduce the shift point noise // This is to remove the noise coming from detection accuracy, interpolation, resampling, etc. { - const auto THRESHOLD = parameters_->quantize_filter_threshold; + const auto THRESHOLD = parameters_->quantize_size; applyQuantizeProcess(sl_array_trimmed, THRESHOLD); debug.step3_quantize_filtered = sl_array_trimmed; } @@ -893,14 +893,14 @@ AvoidLineArray ShiftLineGenerator::applyTrimProcess( // - Combine avoid points that have almost same gradient (again) { - const auto THRESHOLD = parameters_->same_grad_filter_2_threshold; + const auto THRESHOLD = parameters_->th_similar_grad_2; applySimilarGradFilter(sl_array_trimmed, THRESHOLD); debug.step3_grad_filtered_2nd = sl_array_trimmed; } // - Combine avoid points that have almost same gradient (again) { - const auto THRESHOLD = parameters_->same_grad_filter_3_threshold; + const auto THRESHOLD = parameters_->th_similar_grad_3; applySimilarGradFilter(sl_array_trimmed, THRESHOLD); debug.step3_grad_filtered_3rd = sl_array_trimmed; } diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index f0d864f3fed38..bef3976be7e1e 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -814,9 +814,9 @@ std::optional getAvoidMargin( object_parameter.lateral_soft_margin + 0.5 * vehicle_width; const auto min_avoid_margin = lateral_hard_margin + 0.5 * vehicle_width; const auto soft_lateral_distance_limit = - object.to_road_shoulder_distance - parameters->soft_road_shoulder_margin - 0.5 * vehicle_width; + object.to_road_shoulder_distance - parameters->soft_drivable_bound_margin - 0.5 * vehicle_width; const auto hard_lateral_distance_limit = - object.to_road_shoulder_distance - parameters->hard_road_shoulder_margin - 0.5 * vehicle_width; + object.to_road_shoulder_distance - parameters->hard_drivable_bound_margin - 0.5 * vehicle_width; // Step1. check avoidable or not. if (hard_lateral_distance_limit < min_avoid_margin) { From e459f09dada0db9b57ac8108254a844d69e86569 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 12 Apr 2024 03:05:40 +0900 Subject: [PATCH 51/57] feat(static_centerline_optimizer): generate centerline from ego's trajectory in bag (#6788) * implement bag_ego_trajectory_based_centerline Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../include/route_handler/route_handler.hpp | 1 + planning/route_handler/src/route_handler.cpp | 7 + .../CMakeLists.txt | 2 + .../static_centerline_optimizer.param.yaml | 2 +- .../bag_ego_trajectory_based_centerline.hpp | 29 ++ ...timization_trajectory_based_centerline.hpp | 45 +++ .../static_centerline_optimizer_node.hpp | 26 +- .../static_centerline_optimizer/utils.hpp | 3 + .../static_centerline_optimizer.launch.xml | 5 + .../bag_ego_trajectory_based_centerline.sh | 3 + ...ptimization_trajectory_based_centerline.sh | 3 + .../scripts/tmp/run.sh | 3 - .../bag_ego_trajectory_based_centerline.cpp | 82 +++++ ...timization_trajectory_based_centerline.cpp | 192 +++++++++++ .../src/static_centerline_optimizer_node.cpp | 307 ++++++------------ .../static_centerline_optimizer/src/utils.cpp | 11 + .../test/data/bag_ego_trajectory.db3 | Bin 0 -> 2654208 bytes .../test_static_centerline_optimizer.test.py | 1 + 18 files changed, 491 insertions(+), 231 deletions(-) create mode 100644 planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp create mode 100644 planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp create mode 100755 planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh create mode 100755 planning/static_centerline_optimizer/scripts/tmp/optimization_trajectory_based_centerline.sh delete mode 100755 planning/static_centerline_optimizer/scripts/tmp/run.sh create mode 100644 planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp create mode 100644 planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp create mode 100644 planning/static_centerline_optimizer/test/data/bag_ego_trajectory.db3 diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index 83c814b70f0a5..ac8e472b2f943 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -354,6 +354,7 @@ class RouteHandler const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * right_lanelet) const; 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 diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 8d143fcf0b87d..76763821998bd 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -2286,4 +2286,11 @@ bool RouteHandler::findDrivableLanePath( return drivable_lane_path_found; } +lanelet::ConstLanelets RouteHandler::getClosestLanelets( + const geometry_msgs::msg::Pose & target_pose) const +{ + lanelet::ConstLanelets target_lanelets; + lanelet::utils::query::getCurrentLanelets(road_lanelets_, target_pose, &target_lanelets); + return target_lanelets; +} } // namespace route_handler diff --git a/planning/static_centerline_optimizer/CMakeLists.txt b/planning/static_centerline_optimizer/CMakeLists.txt index 829c06c1fba12..cc33f2234a50c 100644 --- a/planning/static_centerline_optimizer/CMakeLists.txt +++ b/planning/static_centerline_optimizer/CMakeLists.txt @@ -22,6 +22,8 @@ autoware_package() ament_auto_add_executable(main src/main.cpp src/static_centerline_optimizer_node.cpp + src/centerline_source/optimization_trajectory_based_centerline.cpp + src/centerline_source/bag_ego_trajectory_based_centerline.cpp src/utils.cpp ) diff --git a/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml b/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml index 4fdee8a0ca6fc..24a5536949479 100644 --- a/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml +++ b/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml @@ -1,5 +1,5 @@ /**: ros__parameters: - centerline_source: "optimization_trajectory_base" # select from "optimization_trajectory_base" and "bag_ego_trajectory_base" marker_color: ["FF0000", "00FF00", "0000FF"] marker_color_dist_thresh : [0.1, 0.2, 0.3] + output_trajectory_interval: 1.0 diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp new file mode 100644 index 0000000000000..db954b6ccbd47 --- /dev/null +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp @@ -0,0 +1,29 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ +#define STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ + +#include "rclcpp/rclcpp.hpp" +#include "static_centerline_optimizer/type_alias.hpp" + +#include +#include +#include + +namespace static_centerline_optimizer +{ +std::vector generate_centerline_with_bag(rclcpp::Node & node); +} // namespace static_centerline_optimizer +#endif // STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp new file mode 100644 index 0000000000000..6e52ff98d78da --- /dev/null +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp @@ -0,0 +1,45 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT +#define STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT + +#include "rclcpp/rclcpp.hpp" +#include "static_centerline_optimizer/type_alias.hpp" + +#include +#include +#include + +namespace static_centerline_optimizer +{ +class OptimizationTrajectoryBasedCenterline +{ +public: + OptimizationTrajectoryBasedCenterline() = default; + explicit OptimizationTrajectoryBasedCenterline(rclcpp::Node & node); + std::vector generate_centerline_with_optimization( + rclcpp::Node & node, const RouteHandler & route_handler, + const std::vector & route_lane_ids); + +private: + std::vector optimize_trajectory(const Path & raw_path) const; + + rclcpp::Publisher::SharedPtr pub_raw_path_with_lane_id_{nullptr}; + rclcpp::Publisher::SharedPtr pub_raw_path_{nullptr}; +}; +} // namespace static_centerline_optimizer +// clang-format off +#endif // STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT +// clang-format on diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp index a920139a94472..242a76ae0d94f 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp @@ -16,6 +16,7 @@ #define STATIC_CENTERLINE_OPTIMIZER__STATIC_CENTERLINE_OPTIMIZER_NODE_HPP_ #include "rclcpp/rclcpp.hpp" +#include "static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp" #include "static_centerline_optimizer/srv/load_map.hpp" #include "static_centerline_optimizer/srv/plan_path.hpp" #include "static_centerline_optimizer/srv/plan_route.hpp" @@ -25,6 +26,7 @@ #include #include "std_msgs/msg/bool.hpp" +#include "std_msgs/msg/float32.hpp" #include "std_msgs/msg/int32.hpp" #include @@ -37,6 +39,12 @@ using static_centerline_optimizer::srv::LoadMap; using static_centerline_optimizer::srv::PlanPath; using static_centerline_optimizer::srv::PlanRoute; +struct CenterlineWithRoute +{ + std::vector centerline{}; + std::vector route_lane_ids{}; +}; + class StaticCenterlineOptimizerNode : public rclcpp::Node { public: @@ -44,11 +52,6 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node void run(); private: - struct CenterlineWithRoute - { - std::vector centerline{}; - std::vector route_lane_ids{}; - }; // load map void load_map(const std::string & lanelet2_input_file_path); void on_load_map( @@ -60,13 +63,12 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node void on_plan_route( const PlanRoute::Request::SharedPtr request, const PlanRoute::Response::SharedPtr response); - // plan path + // plan centerline CenterlineWithRoute generate_centerline_with_route(); - std::vector plan_path(const std::vector & route_lane_ids); - std::vector optimize_trajectory(const Path & raw_path) const; void on_plan_path( const PlanPath::Request::SharedPtr request, const PlanPath::Response::SharedPtr response); + void update_centerline_range(const int traj_start_index, const int traj_end_index); void evaluate( const std::vector & route_lane_ids, const std::vector & optimized_traj_points); @@ -88,19 +90,19 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node BagEgoTrajectoryBase, }; CenterlineSource centerline_source_; + OptimizationTrajectoryBasedCenterline optimization_trajectory_based_centerline_; // publisher rclcpp::Publisher::SharedPtr pub_map_bin_{nullptr}; - rclcpp::Publisher::SharedPtr pub_raw_path_with_lane_id_{nullptr}; - rclcpp::Publisher::SharedPtr pub_raw_path_{nullptr}; rclcpp::Publisher::SharedPtr pub_debug_unsafe_footprints_{nullptr}; - rclcpp::Publisher::SharedPtr pub_whole_optimized_centerline_{nullptr}; - rclcpp::Publisher::SharedPtr pub_optimized_centerline_{nullptr}; + rclcpp::Publisher::SharedPtr pub_whole_centerline_{nullptr}; + rclcpp::Publisher::SharedPtr pub_centerline_{nullptr}; // subscriber rclcpp::Subscription::SharedPtr sub_traj_start_index_; rclcpp::Subscription::SharedPtr sub_traj_end_index_; rclcpp::Subscription::SharedPtr sub_save_map_; + rclcpp::Subscription::SharedPtr sub_traj_resample_interval_; // service rclcpp::Service::SharedPtr srv_load_map_; diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp index 8c8c346557fce..52dcd171e8658 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp @@ -28,6 +28,9 @@ namespace static_centerline_optimizer { namespace utils { +lanelet::ConstLanelets get_lanelets_from_ids( + const RouteHandler & route_handler, const std::vector & lane_ids); + geometry_msgs::msg::Pose get_center_pose( const RouteHandler & route_handler, const size_t lanelet_id); diff --git a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml index 2e163e2eb93eb..10718150d1751 100644 --- a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml +++ b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml @@ -5,6 +5,9 @@ + + + @@ -78,6 +81,8 @@ + +
diff --git a/planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh b/planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh new file mode 100755 index 0000000000000..8164b521553c8 --- /dev/null +++ b/planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml centerline_source:="bag_ego_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix static_centerline_optimizer --share)/test/data/bag_ego_trajectory.db3" vehicle_model:=lexus diff --git a/planning/static_centerline_optimizer/scripts/tmp/optimization_trajectory_based_centerline.sh b/planning/static_centerline_optimizer/scripts/tmp/optimization_trajectory_based_centerline.sh new file mode 100755 index 0000000000000..3967c7a4ca523 --- /dev/null +++ b/planning/static_centerline_optimizer/scripts/tmp/optimization_trajectory_based_centerline.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml centerline_source:="optimization_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus diff --git a/planning/static_centerline_optimizer/scripts/tmp/run.sh b/planning/static_centerline_optimizer/scripts/tmp/run.sh deleted file mode 100755 index 9e475b9d8759b..0000000000000 --- a/planning/static_centerline_optimizer/scripts/tmp/run.sh +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/bash - -ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus diff --git a/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp b/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp new file mode 100644 index 0000000000000..150218b498ae7 --- /dev/null +++ b/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp @@ -0,0 +1,82 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp" + +#include "rclcpp/serialization.hpp" +#include "rosbag2_cpp/reader.hpp" +#include "static_centerline_optimizer/static_centerline_optimizer_node.hpp" + +#include + +namespace static_centerline_optimizer +{ +std::vector generate_centerline_with_bag(rclcpp::Node & node) +{ + const auto bag_filename = node.declare_parameter("bag_filename"); + + rosbag2_cpp::Reader bag_reader; + bag_reader.open(bag_filename); + + rclcpp::Serialization bag_serialization; + std::vector centerline_traj_points; + while (bag_reader.has_next()) { + const rosbag2_storage::SerializedBagMessageSharedPtr msg = bag_reader.read_next(); + + if (msg->topic_name != "/localization/kinematic_state") { + continue; + } + + rclcpp::SerializedMessage serialized_msg(*msg->serialized_data); + const auto ros_msg = std::make_shared(); + + bag_serialization.deserialize_message(&serialized_msg, ros_msg.get()); + + if (!centerline_traj_points.empty()) { + constexpr double epsilon = 1e-1; + if ( + std::abs(centerline_traj_points.back().pose.position.x - ros_msg->pose.pose.position.x) < + epsilon && + std::abs(centerline_traj_points.back().pose.position.y - ros_msg->pose.pose.position.y) < + epsilon) { + continue; + } + } + TrajectoryPoint centerline_traj_point; + centerline_traj_point.pose.position = ros_msg->pose.pose.position; + // std::cerr << centerline_traj_point.pose.position.x << " " + // << centerline_traj_point.pose.position.y << std::endl; + centerline_traj_points.push_back(centerline_traj_point); + } + + RCLCPP_INFO(node.get_logger(), "Extracted centerline from the bag."); + + // calculate rough orientation of centerline trajectory points + for (size_t i = 0; i < centerline_traj_points.size(); ++i) { + if (i == centerline_traj_points.size() - 1) { + if (i != 0) { + centerline_traj_points.at(i).pose.orientation = + centerline_traj_points.at(i - 1).pose.orientation; + } + } else { + const double yaw_angle = tier4_autoware_utils::calcAzimuthAngle( + centerline_traj_points.at(i).pose.position, centerline_traj_points.at(i + 1).pose.position); + centerline_traj_points.at(i).pose.orientation = + tier4_autoware_utils::createQuaternionFromYaw(yaw_angle); + } + } + + return centerline_traj_points; +} +} // namespace static_centerline_optimizer diff --git a/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp b/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp new file mode 100644 index 0000000000000..5bce91be722ca --- /dev/null +++ b/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp @@ -0,0 +1,192 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp" + +#include "motion_utils/resample/resample.hpp" +#include "motion_utils/trajectory/conversion.hpp" +#include "obstacle_avoidance_planner/node.hpp" +#include "path_smoother/elastic_band_smoother.hpp" +#include "static_centerline_optimizer/static_centerline_optimizer_node.hpp" +#include "static_centerline_optimizer/utils.hpp" + +namespace static_centerline_optimizer +{ +namespace +{ +rclcpp::NodeOptions create_node_options() +{ + return rclcpp::NodeOptions{}; +} + +rclcpp::QoS create_transient_local_qos() +{ + return rclcpp::QoS{1}.transient_local(); +} +Path convert_to_path(const PathWithLaneId & path_with_lane_id) +{ + Path path; + path.header = path_with_lane_id.header; + path.left_bound = path_with_lane_id.left_bound; + path.right_bound = path_with_lane_id.right_bound; + for (const auto & point : path_with_lane_id.points) { + path.points.push_back(point.point); + } + + return path; +} + +Trajectory convert_to_trajectory(const Path & path) +{ + Trajectory traj; + for (const auto & point : path.points) { + TrajectoryPoint traj_point; + traj_point.pose = point.pose; + traj_point.longitudinal_velocity_mps = point.longitudinal_velocity_mps; + traj_point.lateral_velocity_mps = point.lateral_velocity_mps; + traj_point.heading_rate_rps = point.heading_rate_rps; + + traj.points.push_back(traj_point); + } + return traj; +} +} // namespace + +OptimizationTrajectoryBasedCenterline::OptimizationTrajectoryBasedCenterline(rclcpp::Node & node) +{ + pub_raw_path_with_lane_id_ = + node.create_publisher("input_centerline", create_transient_local_qos()); + pub_raw_path_ = node.create_publisher("debug/raw_centerline", create_transient_local_qos()); +} + +std::vector +OptimizationTrajectoryBasedCenterline::generate_centerline_with_optimization( + rclcpp::Node & node, const RouteHandler & route_handler, + const std::vector & route_lane_ids) +{ + const auto route_lanelets = utils::get_lanelets_from_ids(route_handler, route_lane_ids); + + // optimize centerline inside the lane + const auto start_center_pose = utils::get_center_pose(route_handler, route_lane_ids.front()); + + // get ego nearest search parameters and resample interval in behavior_path_planner + const double ego_nearest_dist_threshold = + node.has_parameter("ego_nearest_dist_threshold") + ? node.get_parameter("ego_nearest_dist_threshold").as_double() + : node.declare_parameter("ego_nearest_dist_threshold"); + const double ego_nearest_yaw_threshold = + node.has_parameter("ego_nearest_yaw_threshold") + ? node.get_parameter("ego_nearest_yaw_threshold").as_double() + : node.declare_parameter("ego_nearest_yaw_threshold"); + const double behavior_path_interval = node.has_parameter("output_path_interval") + ? node.get_parameter("output_path_interval").as_double() + : node.declare_parameter("output_path_interval"); + const double behavior_vel_interval = + node.has_parameter("behavior_output_path_interval") + ? node.get_parameter("behavior_output_path_interval").as_double() + : node.declare_parameter("behavior_output_path_interval"); + + // extract path with lane id from lanelets + const auto raw_path_with_lane_id = [&]() { + const auto non_resampled_path_with_lane_id = utils::get_path_with_lane_id( + route_handler, route_lanelets, start_center_pose, ego_nearest_dist_threshold, + ego_nearest_yaw_threshold); + return motion_utils::resamplePath(non_resampled_path_with_lane_id, behavior_path_interval); + }(); + pub_raw_path_with_lane_id_->publish(raw_path_with_lane_id); + RCLCPP_INFO(node.get_logger(), "Calculated raw path with lane id and published."); + + // convert path with lane id to path + const auto raw_path = [&]() { + const auto non_resampled_path = convert_to_path(raw_path_with_lane_id); + return motion_utils::resamplePath(non_resampled_path, behavior_vel_interval); + }(); + pub_raw_path_->publish(raw_path); + RCLCPP_INFO(node.get_logger(), "Converted to path and published."); + + // smooth trajectory and road collision avoidance + const auto optimized_traj_points = optimize_trajectory(raw_path); + RCLCPP_INFO( + node.get_logger(), + "Smoothed trajectory and made it collision free with the road and published."); + + return optimized_traj_points; +} + +std::vector OptimizationTrajectoryBasedCenterline::optimize_trajectory( + const Path & raw_path) const +{ + // convert to trajectory points + const auto raw_traj_points = [&]() { + const auto raw_traj = convert_to_trajectory(raw_path); + return motion_utils::convertToTrajectoryPointArray(raw_traj); + }(); + + // create an instance of elastic band and model predictive trajectory. + const auto eb_path_smoother_ptr = + path_smoother::ElasticBandSmoother(create_node_options()).getElasticBandSmoother(); + const auto mpt_optimizer_ptr = + obstacle_avoidance_planner::ObstacleAvoidancePlanner(create_node_options()).getMPTOptimizer(); + + // NOTE: The optimization is executed every valid_optimized_traj_points_num points. + constexpr int valid_optimized_traj_points_num = 10; + const int traj_segment_num = raw_traj_points.size() / valid_optimized_traj_points_num; + + // NOTE: num_initial_optimization exists to make the both optimizations stable since they may use + // warm start. + constexpr int num_initial_optimization = 2; + + std::vector whole_optimized_traj_points; + for (int virtual_ego_pose_idx = -num_initial_optimization; + virtual_ego_pose_idx < traj_segment_num; ++virtual_ego_pose_idx) { + // calculate virtual ego pose for the optimization + constexpr int virtual_ego_pose_offset_idx = 1; + const auto virtual_ego_pose = + raw_traj_points + .at( + valid_optimized_traj_points_num * std::max(virtual_ego_pose_idx, 0) + + virtual_ego_pose_offset_idx) + .pose; + + // smooth trajectory by elastic band in the path_smoother package + const auto smoothed_traj_points = + eb_path_smoother_ptr->smoothTrajectory(raw_traj_points, virtual_ego_pose); + + // road collision avoidance by model predictive trajectory in the obstacle_avoidance_planner + // package + const obstacle_avoidance_planner::PlannerData planner_data{ + raw_path.header, smoothed_traj_points, raw_path.left_bound, raw_path.right_bound, + virtual_ego_pose}; + const auto optimized_traj_points = mpt_optimizer_ptr->optimizeTrajectory(planner_data); + + // connect the previously and currently optimized trajectory points + for (size_t j = 0; j < whole_optimized_traj_points.size(); ++j) { + const double dist = tier4_autoware_utils::calcDistance2d( + whole_optimized_traj_points.at(j), optimized_traj_points.front()); + if (dist < 0.5) { + const std::vector extracted_whole_optimized_traj_points{ + whole_optimized_traj_points.begin(), + whole_optimized_traj_points.begin() + std::max(j, 1UL) - 1}; + whole_optimized_traj_points = extracted_whole_optimized_traj_points; + break; + } + } + for (size_t j = 0; j < optimized_traj_points.size(); ++j) { + whole_optimized_traj_points.push_back(optimized_traj_points.at(j)); + } + } + + return whole_optimized_traj_points; +} +} // namespace static_centerline_optimizer diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index 0feebe8cbceb6..4f729ab5c8c57 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -21,8 +21,7 @@ #include "map_projection_loader/load_info_from_lanelet2_map.hpp" #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" -#include "obstacle_avoidance_planner/node.hpp" -#include "path_smoother/elastic_band_smoother.hpp" +#include "static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp" #include "static_centerline_optimizer/msg/points_with_lane_id.hpp" #include "static_centerline_optimizer/type_alias.hpp" #include "static_centerline_optimizer/utils.hpp" @@ -35,6 +34,7 @@ #include #include "std_msgs/msg/bool.hpp" +#include "std_msgs/msg/float32.hpp" #include "std_msgs/msg/int32.hpp" #include @@ -57,34 +57,6 @@ namespace static_centerline_optimizer { namespace { -Path convert_to_path(const PathWithLaneId & path_with_lane_id) -{ - Path path; - path.header = path_with_lane_id.header; - path.left_bound = path_with_lane_id.left_bound; - path.right_bound = path_with_lane_id.right_bound; - for (const auto & point : path_with_lane_id.points) { - path.points.push_back(point.point); - } - - return path; -} - -Trajectory convert_to_trajectory(const Path & path) -{ - Trajectory traj; - for (const auto & point : path.points) { - TrajectoryPoint traj_point; - traj_point.pose = point.pose; - traj_point.longitudinal_velocity_mps = point.longitudinal_velocity_mps; - traj_point.lateral_velocity_mps = point.lateral_velocity_mps; - traj_point.heading_rate_rps = point.heading_rate_rps; - - traj.points.push_back(traj_point); - } - return traj; -} - [[maybe_unused]] lanelet::ConstLanelets get_lanelets_from_route( const RouteHandler & route_handler, const LaneletRoute & route) { @@ -109,22 +81,6 @@ std::vector get_lane_ids_from_route(const LaneletRoute & route) return lane_ids; } -lanelet::ConstLanelets get_lanelets_from_ids( - const RouteHandler & route_handler, const std::vector & lane_ids) -{ - lanelet::ConstLanelets lanelets; - for (const lanelet::Id lane_id : lane_ids) { - const auto lanelet = route_handler.getLaneletsFromId(lane_id); - lanelets.push_back(lanelet); - } - return lanelets; -} - -rclcpp::NodeOptions create_node_options() -{ - return rclcpp::NodeOptions{}; -} - rclcpp::QoS create_transient_local_qos() { return rclcpp::QoS{1}.transient_local(); @@ -216,6 +172,15 @@ std_msgs::msg::Header createHeader(const rclcpp::Time & now) header.stamp = now; return header; } + +std::vector resampleTrajectoryPoints( + const std::vector & input_traj_points, const double resample_interval) +{ + // resample and calculate trajectory points' orientation + const auto input_traj = motion_utils::convertToTrajectory(input_traj_points); + auto resampled_input_traj = motion_utils::resampleTrajectory(input_traj, resample_interval); + return motion_utils::convertToTrajectoryPointArray(resampled_input_traj); +} } // namespace StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( @@ -224,13 +189,9 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( { // publishers pub_map_bin_ = create_publisher("lanelet2_map_topic", create_transient_local_qos()); - pub_raw_path_with_lane_id_ = - create_publisher("input_centerline", create_transient_local_qos()); - pub_raw_path_ = create_publisher("debug/raw_centerline", create_transient_local_qos()); - pub_whole_optimized_centerline_ = + pub_whole_centerline_ = create_publisher("output_whole_centerline", create_transient_local_qos()); - pub_optimized_centerline_ = - create_publisher("output_centerline", create_transient_local_qos()); + pub_centerline_ = create_publisher("output_centerline", create_transient_local_qos()); // debug publishers pub_debug_unsafe_footprints_ = @@ -240,32 +201,16 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( sub_traj_start_index_ = create_subscription( "/centerline_updater_helper/traj_start_index", rclcpp::QoS{1}, [this](const std_msgs::msg::Int32 & msg) { - if (!centerline_with_route_ || traj_end_index_ + 1 < msg.data) { - return; + if (msg.data <= traj_end_index_ + 1) { + update_centerline_range(msg.data, traj_end_index_); } - traj_start_index_ = msg.data; - - const auto & c = *centerline_with_route_; - const auto selected_centerline = std::vector( - c.centerline.begin() + traj_start_index_, c.centerline.begin() + traj_end_index_ + 1); - - pub_optimized_centerline_->publish( - motion_utils::convertToTrajectory(selected_centerline, createHeader(this->now()))); }); sub_traj_end_index_ = create_subscription( "/centerline_updater_helper/traj_end_index", rclcpp::QoS{1}, [this](const std_msgs::msg::Int32 & msg) { - if (!centerline_with_route_ || msg.data + 1 < traj_start_index_) { - return; + if (traj_start_index_ <= msg.data + 1) { + update_centerline_range(traj_start_index_, msg.data); } - traj_end_index_ = msg.data; - - const auto & c = *centerline_with_route_; - const auto selected_centerline = std::vector( - c.centerline.begin() + traj_start_index_, c.centerline.begin() + traj_end_index_ + 1); - - pub_optimized_centerline_->publish( - motion_utils::convertToTrajectory(selected_centerline, createHeader(this->now()))); }); sub_save_map_ = create_subscription( "/centerline_updater_helper/save_map", rclcpp::QoS{1}, [this](const std_msgs::msg::Bool & msg) { @@ -280,6 +225,11 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( lanelet2_output_file_path, CenterlineWithRoute{selected_centerline, c.route_lane_ids}); } }); + sub_traj_resample_interval_ = create_subscription( + "/centerline_updater_helper/traj_resample_interval", rclcpp::QoS{1}, + [this]([[maybe_unused]] const std_msgs::msg::Float32 & msg) { + // TODO(murooka) + }); // services callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); @@ -308,6 +258,7 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( centerline_source_ = [&]() { const auto centerline_source_param = declare_parameter("centerline_source"); if (centerline_source_param == "optimization_trajectory_base") { + optimization_trajectory_based_centerline_ = OptimizationTrajectoryBasedCenterline(*this); return CenterlineSource::OptimizationTrajectoryBase; } else if (centerline_source_param == "bag_ego_trajectory_base") { return CenterlineSource::BagEgoTrajectoryBase; @@ -317,6 +268,24 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( }(); } +void StaticCenterlineOptimizerNode::update_centerline_range( + const int traj_start_index, const int traj_end_index) +{ + if (!centerline_with_route_) { + return; + } + + traj_start_index_ = traj_start_index; + traj_end_index_ = traj_end_index; + + const auto & centerline = centerline_with_route_->centerline; + const auto selected_centerline = std::vector( + centerline.begin() + traj_start_index_, centerline.begin() + traj_end_index_ + 1); + + pub_centerline_->publish( + motion_utils::convertToTrajectory(selected_centerline, createHeader(this->now()))); +} + void StaticCenterlineOptimizerNode::run() { // declare planning setting parameters @@ -334,20 +303,53 @@ void StaticCenterlineOptimizerNode::run() centerline_with_route_ = centerline_with_route; } -StaticCenterlineOptimizerNode::CenterlineWithRoute -StaticCenterlineOptimizerNode::generate_centerline_with_route() +CenterlineWithRoute StaticCenterlineOptimizerNode::generate_centerline_with_route() { - if (centerline_source_ == CenterlineSource::OptimizationTrajectoryBase) { - const lanelet::Id start_lanelet_id = declare_parameter("start_lanelet_id"); - const lanelet::Id end_lanelet_id = declare_parameter("end_lanelet_id"); - const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); - const auto optimized_traj_points = plan_path(route_lane_ids); - return CenterlineWithRoute{optimized_traj_points, route_lane_ids}; - } else if (centerline_source_ == CenterlineSource::BagEgoTrajectoryBase) { + if (!route_handler_ptr_) { + RCLCPP_ERROR(get_logger(), "Route handler is not ready. Return empty trajectory."); return CenterlineWithRoute{}; } - throw std::logic_error("The centerline source is not supported in static_centerline_optimizer."); + auto centerline_with_route = [&]() { + if (centerline_source_ == CenterlineSource::OptimizationTrajectoryBase) { + const lanelet::Id start_lanelet_id = declare_parameter("start_lanelet_id"); + const lanelet::Id end_lanelet_id = declare_parameter("end_lanelet_id"); + const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); + const auto optimized_centerline = + optimization_trajectory_based_centerline_.generate_centerline_with_optimization( + *this, *route_handler_ptr_, route_lane_ids); + return CenterlineWithRoute{optimized_centerline, route_lane_ids}; + } else if (centerline_source_ == CenterlineSource::BagEgoTrajectoryBase) { + const auto bag_centerline = generate_centerline_with_bag(*this); + const auto start_lanelets = + route_handler_ptr_->getClosestLanelets(bag_centerline.front().pose); + const auto end_lanelets = route_handler_ptr_->getClosestLanelets(bag_centerline.back().pose); + if (start_lanelets.empty() || end_lanelets.empty()) { + RCLCPP_ERROR(get_logger(), "Nearest lanelets to the bag's centerline are not found."); + return CenterlineWithRoute{}; + } + + const lanelet::Id start_lanelet_id = start_lanelets.front().id(); + const lanelet::Id end_lanelet_id = end_lanelets.front().id(); + const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); + + return CenterlineWithRoute{bag_centerline, route_lane_ids}; + } + throw std::logic_error( + "The centerline source is not supported in static_centerline_optimizer."); + }(); + + const double output_trajectory_interval = declare_parameter("output_trajectory_interval"); + centerline_with_route.centerline = + resampleTrajectoryPoints(centerline_with_route.centerline, output_trajectory_interval); + + pub_whole_centerline_->publish( + motion_utils::convertToTrajectory(centerline_with_route.centerline, createHeader(this->now()))); + + pub_centerline_->publish( + motion_utils::convertToTrajectory(centerline_with_route.centerline, createHeader(this->now()))); + + return centerline_with_route; } void StaticCenterlineOptimizerNode::load_map(const std::string & lanelet2_input_file_path) @@ -443,7 +445,7 @@ std::vector StaticCenterlineOptimizerNode::plan_route( plugin_loader.createSharedInstance("mission_planner::lanelet2::DefaultPlanner"); // initialize mission_planner - auto node = rclcpp::Node("po"); + auto node = rclcpp::Node("mission_planner"); mission_planner->initialize(&node, map_bin_ptr_); // plan route @@ -472,7 +474,7 @@ void StaticCenterlineOptimizerNode::on_plan_route( // plan route const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); - const auto route_lanelets = get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); + const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); // extract lane ids std::vector lane_ids; @@ -491,133 +493,6 @@ void StaticCenterlineOptimizerNode::on_plan_route( response->lane_ids = lane_ids; } -std::vector StaticCenterlineOptimizerNode::plan_path( - const std::vector & route_lane_ids) -{ - if (!route_handler_ptr_) { - RCLCPP_ERROR(get_logger(), "Route handler is not ready. Return empty trajectory."); - return std::vector{}; - } - - const auto route_lanelets = get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); - - // optimize centerline inside the lane - const auto start_center_pose = - utils::get_center_pose(*route_handler_ptr_, route_lane_ids.front()); - - // get ego nearest search parameters and resample interval in behavior_path_planner - const double ego_nearest_dist_threshold = - has_parameter("ego_nearest_dist_threshold") - ? get_parameter("ego_nearest_dist_threshold").as_double() - : declare_parameter("ego_nearest_dist_threshold"); - const double ego_nearest_yaw_threshold = - has_parameter("ego_nearest_yaw_threshold") - ? get_parameter("ego_nearest_yaw_threshold").as_double() - : declare_parameter("ego_nearest_yaw_threshold"); - const double behavior_path_interval = has_parameter("output_path_interval") - ? get_parameter("output_path_interval").as_double() - : declare_parameter("output_path_interval"); - const double behavior_vel_interval = - has_parameter("behavior_output_path_interval") - ? get_parameter("behavior_output_path_interval").as_double() - : declare_parameter("behavior_output_path_interval"); - - // extract path with lane id from lanelets - const auto raw_path_with_lane_id = [&]() { - const auto non_resampled_path_with_lane_id = utils::get_path_with_lane_id( - *route_handler_ptr_, route_lanelets, start_center_pose, ego_nearest_dist_threshold, - ego_nearest_yaw_threshold); - return motion_utils::resamplePath(non_resampled_path_with_lane_id, behavior_path_interval); - }(); - pub_raw_path_with_lane_id_->publish(raw_path_with_lane_id); - RCLCPP_INFO(get_logger(), "Calculated raw path with lane id and published."); - - // convert path with lane id to path - const auto raw_path = [&]() { - const auto non_resampled_path = convert_to_path(raw_path_with_lane_id); - return motion_utils::resamplePath(non_resampled_path, behavior_vel_interval); - }(); - pub_raw_path_->publish(raw_path); - RCLCPP_INFO(get_logger(), "Converted to path and published."); - - // smooth trajectory and road collision avoidance - const auto optimized_traj_points = optimize_trajectory(raw_path); - pub_whole_optimized_centerline_->publish( - motion_utils::convertToTrajectory(optimized_traj_points, raw_path.header)); - pub_optimized_centerline_->publish( - motion_utils::convertToTrajectory(optimized_traj_points, raw_path.header)); - RCLCPP_INFO( - get_logger(), "Smoothed trajectory and made it collision free with the road and published."); - - return optimized_traj_points; -} - -std::vector StaticCenterlineOptimizerNode::optimize_trajectory( - const Path & raw_path) const -{ - // convert to trajectory points - const auto raw_traj_points = [&]() { - const auto raw_traj = convert_to_trajectory(raw_path); - return motion_utils::convertToTrajectoryPointArray(raw_traj); - }(); - - // create an instance of elastic band and model predictive trajectory. - const auto eb_path_smoother_ptr = - path_smoother::ElasticBandSmoother(create_node_options()).getElasticBandSmoother(); - const auto mpt_optimizer_ptr = - obstacle_avoidance_planner::ObstacleAvoidancePlanner(create_node_options()).getMPTOptimizer(); - - // NOTE: The optimization is executed every valid_optimized_traj_points_num points. - constexpr int valid_optimized_traj_points_num = 10; - const int traj_segment_num = raw_traj_points.size() / valid_optimized_traj_points_num; - - // NOTE: num_initial_optimization exists to make the both optimizations stable since they may use - // warm start. - constexpr int num_initial_optimization = 2; - - std::vector whole_optimized_traj_points; - for (int virtual_ego_pose_idx = -num_initial_optimization; - virtual_ego_pose_idx < traj_segment_num; ++virtual_ego_pose_idx) { - // calculate virtual ego pose for the optimization - constexpr int virtual_ego_pose_offset_idx = 1; - const auto virtual_ego_pose = - raw_traj_points - .at( - valid_optimized_traj_points_num * std::max(virtual_ego_pose_idx, 0) + - virtual_ego_pose_offset_idx) - .pose; - - // smooth trajectory by elastic band in the path_smoother package - const auto smoothed_traj_points = - eb_path_smoother_ptr->smoothTrajectory(raw_traj_points, virtual_ego_pose); - - // road collision avoidance by model predictive trajectory in the obstacle_avoidance_planner - // package - const obstacle_avoidance_planner::PlannerData planner_data{ - raw_path.header, smoothed_traj_points, raw_path.left_bound, raw_path.right_bound, - virtual_ego_pose}; - const auto optimized_traj_points = mpt_optimizer_ptr->optimizeTrajectory(planner_data); - - // connect the previously and currently optimized trajectory points - for (size_t j = 0; j < whole_optimized_traj_points.size(); ++j) { - const double dist = tier4_autoware_utils::calcDistance2d( - whole_optimized_traj_points.at(j), optimized_traj_points.front()); - if (dist < 0.5) { - const std::vector extracted_whole_optimized_traj_points{ - whole_optimized_traj_points.begin(), - whole_optimized_traj_points.begin() + std::max(j, 1UL) - 1}; - whole_optimized_traj_points = extracted_whole_optimized_traj_points; - break; - } - } - for (size_t j = 0; j < optimized_traj_points.size(); ++j) { - whole_optimized_traj_points.push_back(optimized_traj_points.at(j)); - } - } - - return whole_optimized_traj_points; -} - void StaticCenterlineOptimizerNode::on_plan_path( const PlanPath::Request::SharedPtr request, const PlanPath::Response::SharedPtr response) { @@ -629,7 +504,7 @@ void StaticCenterlineOptimizerNode::on_plan_path( // get lanelets from route lane ids const auto route_lane_ids = request->route; - const auto route_lanelets = get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); + const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); // check if input route lanelets are connected to each other. const auto unconnected_lane_ids = check_lanelet_connection(*route_handler_ptr_, route_lanelets); @@ -641,7 +516,9 @@ void StaticCenterlineOptimizerNode::on_plan_path( } // plan path - const auto optimized_traj_points = plan_path(route_lane_ids); + const auto optimized_traj_points = + optimization_trajectory_based_centerline_.generate_centerline_with_optimization( + *this, *route_handler_ptr_, route_lane_ids); // check calculation result if (optimized_traj_points.empty()) { @@ -693,7 +570,7 @@ void StaticCenterlineOptimizerNode::evaluate( const std::vector & route_lane_ids, const std::vector & optimized_traj_points) { - const auto route_lanelets = get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); + const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); const auto dist_thresh_vec = has_parameter("marker_color_dist_thresh") ? get_parameter("marker_color_dist_thresh").as_double_array() @@ -770,7 +647,7 @@ void StaticCenterlineOptimizerNode::save_map( } const auto & c = centerline_with_route; - const auto route_lanelets = get_lanelets_from_ids(*route_handler_ptr_, c.route_lane_ids); + const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, c.route_lane_ids); // update centerline in map utils::update_centerline(*route_handler_ptr_, route_lanelets, c.centerline); diff --git a/planning/static_centerline_optimizer/src/utils.cpp b/planning/static_centerline_optimizer/src/utils.cpp index f8cc0953a6dbd..3cc7ed5ca1fda 100644 --- a/planning/static_centerline_optimizer/src/utils.cpp +++ b/planning/static_centerline_optimizer/src/utils.cpp @@ -45,6 +45,17 @@ lanelet::Point3d createPoint3d(const double x, const double y, const double z = namespace utils { +lanelet::ConstLanelets get_lanelets_from_ids( + const RouteHandler & route_handler, const std::vector & lane_ids) +{ + lanelet::ConstLanelets lanelets; + for (const lanelet::Id lane_id : lane_ids) { + const auto lanelet = route_handler.getLaneletsFromId(lane_id); + lanelets.push_back(lanelet); + } + return lanelets; +} + geometry_msgs::msg::Pose get_center_pose( const RouteHandler & route_handler, const size_t lanelet_id) { diff --git a/planning/static_centerline_optimizer/test/data/bag_ego_trajectory.db3 b/planning/static_centerline_optimizer/test/data/bag_ego_trajectory.db3 new file mode 100644 index 0000000000000000000000000000000000000000..0883307acbae0ff5e4a42efa165cba8ae262ae64 GIT binary patch literal 2654208 zcmeEP2YeINAHU9Y&{imWmc2Wx~3IVz62gYxmAhDJqERDX?yc-avr6TT& zhzOq^_AdO0FQfoc04abJKnfrQkOD{nqySO?De&K>KvqCtv#xD?iq$$5J=d(((k8P) zYmlo|bKysmB9Ar&CQlrZlsO_QW!&%)Q=%#ii5fpH$}udeTiIJtNg2uAt&#qcW^LN| zSc}by91ZOl=J+>&`_{~)VW}g^zNDL41%D@V#HbMyqtYj)q$N$98Z~yr)Lv%2L9K*` zDtmL>_{^wrlTuTAmH$!4=gQuSQYp-es9~w&hebK=b+<2q^wBdwCp(VOH3 zqdr%yp-mOPxVzQQ*G|Z(93jmLGBGV}|JSd=V>|BhJ-Fk2c_D2y!BbTxsAI$}Poef< z>1OTCK7>h`PiqzSt8aw|u;1%u|EJPlaptKJrmRw%%trk!e~Q@VJ`tBF_zz!50i*y@ z04abJKnfrQkOD{nqySO?DS#9}3jCKS5bWniwaB+l~MSKzQNyG;c z`y<|r*cq`SVtd4vh{q!yf-L^KBbGSV?O z*I`TnT$30jT!%7K;W~sF57)uWNVpDShQM_o(-*D-m_Bgr&vb-qKc)p-yD?4S+LZ~1 zYZoR2uALcQxOTD@!L_4R2iFePJh-;E&V*}}brM|LSySQK)|w30HrD=dZEcmpwUxCC zTw7Y(z_o=n60Xgy!EkM6g$vbmE?k=E;nJ9fOXM`TG)jj{!x3-^BVX2FFkC|8;1bdu zF2U{K64V4Pl2Bs*`$SxYtM4TCANUDhNCBh(QUED{6hI0f1&{(r0i*y@04abJKnnbK zDBzp9B7%4&8box1tM8JCvk^xk4n({bu{mO01QTJ1m>H28F@SyZzcXo^2~q$lfD}Lq zAO(;DNCBh(QUED{6hI0f1zb|VcXF6tpl`D$!m^+9xv)CK2o`e}?#{Fi0HYR+_#A*c^SC?dlyW258xviEfC&3*~-iHQmQq7&hsMx9HW3<{llpDBb#(Lsw&`-5rJ zj^E`PT4AE)DtIu`cG8_MRTS#gDmm%PNcvmCBPnUQQm-qdb>y4iFXbvUCYs3)kx*s}*@V zy~(Ur!vFjdBw3>{nbf&zS~a}<1Bh=SeCJ6(luW9U@JfS4ZXpebU6S2knMB4Qr3EN$ z^9z(vimD;5)N8d0ol0t=HMG)9tE7c=zFMhqN%+b3A<6cSf}GJBXcclnfD6pR00}i| zPStpaPSH8`JzEYvxIq(f3H=pIj<@Ntkcw10m5t`y`_R zj{DE`Jqb7Q8K2y$$;l<#?Q7gx@-+{`ZD92WAB#8KoTRBoD>WNm)8AYaIlbP0*Q#*-M zB#ADL#;BkNQP~J|mNG);D%2XeNs&uSwMH##`_K-W%i*XSaMTvYl#@EmsI4KD>x;%R zx1oee(>mbn@O-lx3#SE238Y;cnw+6eNNzE~743X6F7kpqB-DuPDoJlND=XOddO+FG-n+(uwh&U$~+&x9? zo~->(Euq2}G`J9YcSzfyEt2SfFChN!2RCoiYsvg}5~_DrJzzv=yCC#L7-yI4)u(WM!Sl4%K;blpLFAw?`B#v_NL(TKnp;Vz6t#o64!10X z@j+LFOf`9~f_QCR%MAO_k?crR5k;wp=9X2G9Xx|@?z1jW1lcpVp-6U;2Px7v(zTFK zvOEXc?FK%$%jH_Vie?>Jt|W>*fDgmdU^J_hqj(V#FY@LRN?MkLsMWKP2-fs*u{ox( z!;r#aB#AA!Sr9eV>f^w)vxzTNlhBWo#V??gINSRv6+Vi*5XB3ssf3zQX81e8q7Dt5 zz}{k#LRK`KTd!edPWd9JGQT3(K9tCtiL?RIi>fbh>WOV=kN@98^8Z_eJ{OW0^oC?u zz;6EmzMuKrbDPY6{4-7zV1{&;Pzln=B|W7%iae+aD4>mG1*q7Vw8^Y0k6#Sa>oxrN zj*f<1-en1e2hAb!RZ&s)Y76pr%PS;qf5k*@H&9vZ_GJ+%PjN^SQk`O#D0UZag`$)s zGL$psiR{MG6v5II8`TwrcR}Qmu~G#~Xvmky%~dPq8g*X2nT>op?wHhhP#;uo6IGQ% z0qHE{(;4hg0i#F|+VwtRKf-hiDqCJITpVJA)oh?**&sI=Xj%nT&Pw=)R`KQOX28%4GI9hr5Vusp zoW=Yo$bGSU!C08zLi_SOy2?s?l2djlYVm?vyxsn9M1?O8YY=*0NY|jJC7lD_@{jgi z>eI-{EUiaBGIQc2)L3?F<2+ANQ@%RaELYJ=wF<29JW#3SO0CKPN}l9|Q80{C=lEB= zkS6Cr8(lwg+itYmy2b`kMb>sipKuVpVz7Z2Fgg?K1d&4lEtDY}r7Akdk|zgM zn@i+$1SYB)OFBv71>WQ^u3y+ad7B*YX!6-)#C|MJ7dtI|0 zd{!2t5qepa-C*6f_C1pOV7U!6g6kmSsBmU$qxDAO#zlq*MT`{DuvdOt!6_g?e`B5DLB~EPnDUsAR_i|*r zI5t@awP{CXGm$j*?UV~}ly9e89HXoV8Z7>rHlQWvQh0JKiX( zDoP>|JJ3*d$@W+@N*J-2@4<(8$dj|M{ncDxKFKkLqj!xlUr+RTd;WhE6<*ZfWa#MN zXM(~5_5NS`CHOo?MG>Rl7CKl$Evg{+!4l(2)8)B(jYeMtrkDm)Nh7oXuz0R2c11z3exebP;Ii5CkK`- zqcnC1hHOP;{I%{6jOooruxhq)RCJ-5RSKlViXvEKdHf=-Z#)V%k%FyxKVVO1PqPPE zq6OjPSX(Ff&xL^*aIH#hqtc&DGU_2y`R&cdcrJr#O zsq9sEyiulvq1%P@9&zq;FOCt!{tuLdQQ_tWr$S4D{|Qo371NT+ecP2wzuQN2Yp zKs)`_CNPim1~>u1ZW&e51XG}MBKv;zqY3qe-1Cwo6wP){bWLvXUqffyITo-`U6LKf zO>_)H>I=kjnAt-mR7QowtxCcMz-~}jOfHC?&c2Pr79h4QL?)q%DoFOK>`jecm!~#c zRBCdZnMnh(UJj)dj?-B%d?s|dnmC)&7CZ!UNZn&bd05PqLkvTiV;{~X95$pkb z^(5b+y1np_JT7|)AbF5HCK?x)%fmd8JV+i#mlXFs^@tus52D9Q=Pcvm!o`J)3m4bF zamM?d>fDllv8mg?N+KlBt*Ip%buMi(D0BndsC+~8#JS2cMDiec`bCq@ z+_<;|kbttsMfxS82hlSi3f=MOjz@RAKu!P}73lM+_dXwz-f2X?PrdW|pi={#8nk=< z8??L7?yBd8MSVR~1yyBKmFvB#jB2v3HmS*Y6o>sN4wTI(o2xIINwL2#^*ZI-0xosy z#bl3=Q1(_*<<%i3xgsyG{MV{_s9~orF`c@uWeyLbpc9n!a+0*1o&xRZkhEe*ixL|p zcJ(DTq6g7~=)sUhZL-CLjxnm|ZbKvwdtN8*T)1=L&Q*JME-?4QiTxi+O`^hgh0Siz zHRRRcK9bJ@r}-c7%kX&wua+LXH#f9>zdS#W55gbb7_tJe7sye98*HhN`{k@3TTZw zU$5s{DplR*1bGrAuB8TJ9w(s`zA(ZT5qNOqBAw}qv_NhL}_ zvg_awNrgtv%Az8*IUf#ZFH{)S>=CS3hCV)ewpvjvO^ zq9#~LN$pao9k?Sv5D51^u}`eF-Bj^FFH_Fx2x(*+9(MX10+n5 z=IRyYePlsQ=b6l^a%yInjc^_mKS6~cSzo%BCXbX*ZOZ70RIGOY{}3Mw6+XAYU!gOD zzYQ86croC9f2r@6a1&qNp#U>|8l0w^M5L)fq15VC(j23rfSlD0XGqJ92D3cIem|~U zDx{J3CK}8!yn-PXB`qgur%aVlQns^h1@b}<=}KhHD2ATK+GMSYwKI5WOJpjR6q;xz zcZ!5chJ$p0lQbGTor!i!M)1-ZF+707@YF0jhRX>} zv{xb=Dv{StTaXQ|F^sfz(00n?TjT?4H;^9lJhVmmAkzC_lS~4Cv>$kVZgD?Y%xaBP zY1A9!Ir_QsT(t(gpS)+F@;id?D90$Vobb(*Q1jekgtAzv0sjzp5G^vnRlgo_p#WRc z3|I~g!6|*qa$vpB<|4JpEYG!=NDziw5;c4Nhh@i@~lIN{zI_2nVv5OmdapZm9F+~Q5P2b^5)R_IMG6jRN~OrI_g%!{jJB{+h4aky;>Zd=o{1;`uAOWs%{uMl~O z{U73!Muk5SHYW6Z$m-x&$rk}i|4`qT;3mG@qX3hm2du*R#brS|$BC{c0}Wo?s>JPN zI$y2S&>3U^?qy>3vdKEIYn`nxvqi|RMZ-%BVJB(rge`N%u!ODB597$1a79=_)wZ5k z2}`sZFlb{UmxnqGFSEWHW>*ZFU7Y^~>quSJkuuW@z|e>Er?Op$b*O^dw8{+#vqusW z>?d!Ci(D~NW&?Sheb!~mCO|r~I?McigpOp`u z0B7yVl&{XM+Q(8R8C>o17!`0t1t#a&DO;vK*(qD4P(b~O9Caj8;7-f62MNpfGZwPE zB7wY%@<1GMiTxk!b0-!4eAu|qKSO#1%?Nza|B~NOxP`CVM*&;kxsWKPVAJ&sv{6YL zNM*QGpEH|Qf^epl`aDu52)9%;)CaOZDK!?*JV-cPs?_V0Y*D8fazzwo1!QFFl=()z zPF;d&mR`-DvBeevY z>OIf9@_KCxIA}z$4S6My-entO4x*UgY756I)|pzX$fHR%F4-7K-gFL|FU_q&wsVaX z-c>?(JmT=cT=oG`{bOU}Tpo%jQfQ7e0W*DWH#2ef^Yre=OfiB3E7{3ESPV&*kYG$# z>0z0wD4GcGp?5`$cV*@r2{q6;=dviDhN?aO@Lv{rAA^6QeF5VPka0E8DdVb8U3E_D zWVOx}WD~FuhAo64_J0sHh6)=HVhDO&;u|o{Z>!H$xZ(E8*2@atWQ}o4Gb^)Z*9Ow!ZU$Pt|t4qCpD1WB-+d!ECYffN|A!y^3KR8lRrl zI!Z^C0MkZfL@t*|%Ux{Z10C2wqL5o}a&HSpOtW&CW>uP83`idAStO&t@wC7}6uU&R zJ^tT}3LoEKTc}U)M9DjW-Te)|JA9hC?Ev^MeZbb-8VsvD*e&bWpjYdlI~QC?OdcH< zY%gSY&X^Y&i0E$(0^a1g6^W?G8!@^cMv?S7FEB5`Dgoxnz05q^M?JldfqTYC}Z7{aJV7;YhI+TRzF}@vd7tl zTad@aTsx~Tu&S9`a<0kO+N3ZLl@8b?{2b z^+1jPQNJ`e{jX1DgWeWqjf6wC*n?NZdT)(-wJDBk^=q-HxijX;ni6lF}OUuvpmA8vpk}4d3bGkG^ozGd+3w)xU;6CH3ZnzuKMhf7Q)H#P|aLk2#s0bP_^LMQdkoI522E% zaASkxp&7yZf|>^A`k(O2@%aXBih0=@S=#`gTU7R+!XdcO*iLSu^R&>#)y~JNPXIz! zsi)a$lUQ3zr~<8Ul`QLFb1PpVlP%M5)GlKYtUwVgGvC?@&YFQU^Pn+|%VKkbkyfeg zy&bd)9c?M3jfHBH1*9N%taMp}?lgrF3T4nmCdx%dSzAh|sdI$sFFGoaZf8_k{XVV% zfi(cNVJ%>jNUOX_xae_fXH&3<%o1-(Z zap0}VDiwL*+**;3jT~2LmDKTBlR8hQ&;T20V|JYWGzS+BlQqqnFy^H5)T44Q{tG!HvkJCdbU$vmvg2Jx&y%h2PN zVGC;qU{lvhY|5$1HP0Ram}k^mbSiYQn7m$HZEIp}56o#-L+0SB@%XCgW{m>IRN?!o zYSmQUdE|PFSp$jzE~4A8h&ox@0k5D4|5iU`O?ZWC%HwOQskJTesl7NpRUIV8dR%X0 z$lC4yd@6hb)c=PE7fB8W_V8cp`?pX2f6})9*Cu6aV3kU!qJmolmBXN{>{D>O!}WUnm3U>`^Sr=wlhfGBc;gGTN6-TMY+3u{l{S3|YvEyv;i zEDz~}Hy|%xN(#mVU7e}wynORSy&9dJqMV(P)*eL2)r>jF7BEyidN52&YjgH9gj?Mq~8AgRK z3u_p9Ur4K<$0cn7Hu-n;eHm`zO9TZNowdJ&nlOn~vos2wjwI6?6y|(##o zoYbk1Vy~e=WrbnYCpl5-RkT7ydSJUFOf~9U+5};3_deq=9&Woa!4z2&CDe?HBvDEq4WZ%XB~rJg^+YfIm83uSXTH6dEglyFoo8536<>z50LU6qkNn&<@59k4ayzQ zx*?dk)>sK87r=a(n@$duQIK&;auIR6jgITf7D?+^zfeE714E3-8Y7`53DCaGwT)!= zkgzdZqa{?90NHau%~ru_ih48B-7|Ez+y6OK_{y+Gq4$S$4ticPIN*K%@xEXA z*OLKS#%LV^%{;1rdAYN_f-4Mh?g^aht%IvpVVtOrDvU>gUT7UuwF*;Ca#UfwkrB;U ztOKi7VXCG)sxbXMV~T0lRP$8xWNXU2SLxfsO(TsN%|UEHOFPl^ePj6{?M9 z=uRt#7Dt*I&>feFo$NM$>quyfX0JVP2(+rmUe*?!%e$*$40H;XrgPsh**;!xv}fH_ zKi9FI=x_l45n|wP?=YlgTQMX2YpjETYj=3nuHABHI=Xf}-I;;4|EalD`1l47g`5oT zB{2lN;CIe90d9HqW$SO91Uf;UcXR?Uh!r_-_5iVQP0|XesliG`1%Xo#Y<;bnz&yom zVP08W0XgRZt7)(`130I@9h@VJuR?|eGSCAI9Aupc4AkCk2BN3QGeHhpKkEeGAALLc zhb|}2re)g_tm(izVizD2L!zzYfNPVyv)t$$OCDMVo;D|Ky{&1$v+>^K85#s06peQKe+%jV_h`uJ z;8+P0@Tq@uUj?v^TA0_RX=@}OLR zM26|WwyZ2~s7z{|!D5Eo6=umhq_XD$AZ|$~tA3&;^gz=q zA;L|Q!`nSb?8v@pb26dXq^RoEAal3L&usocDVso zIj~QCd)bE$HqSWNi2X0|SxSY+H&__7B5-ejzh6B3im%&B0b38N4%QHHnt9VmBc~Fe zj#zUYG1aOKqL?r*+hFHAI&M<^*n4Qt+Gg&88& zJnp$Q-*ZP>^I^{o@baEpF`|pRu2*(ld;CA23QudWH00CZwvwpPbI(7vIt@9>dg9V>}4V>79K;WS*1m=;Vubq+9$hxI6$5~=oZ;l^L;MaY5=x*JJ%Ha zR0cUYsTswkcf_UCss}cDJJ+;~jkxk^yz+?sA4)w>g%5`O|93)q1uYF~8mRZ*gWpW{;iEFe|hMT7~f)fwDO7r7 zgNs*S@miZ$=K(CBlCvhTC}UftU~PpEjypaP+W>0`z=vdzd&lap@MNAc{?Sv)`E2@H zi-CK$DLml`;}JQ>aZYBP3!Jmuo^|KZ{7Gb?orT2y5Ar`nMJU4_3Oy7$Hh4o&c%TJt z;0q~$6hI36Hz;5WVL~L-0wMdN%n&uv8rJrgq8Gp$C4)_vV9*=d3B|@aM^c%gVAAUK z=6rI3DWn`LbkOI^tcNqO^ac{sapm_zZ=cAH1p!Qugfa;&6V~bCICU0Rh&NV9G$Vl( zGRiGZ@cLcL7LZ1*RYTKNlxp56BeMoGf#4p2*pztp2rtW=BOAalX9t9+sHaWF1OR~K zUJSmlmb4?NhM^b874~pHi{Xqvuu$zy7HafGa+SVFXODVd2+b>Up#|dyaskRqJuesR z9&eL_jqb|{V*mU5G@$(R{6l?L!VmTM#mr;EB~(_$*i_lxnX4edK$EmQOSUYupin6c zYI$Kyd0=5O*Q9VH`yn>sjNt`=@B%ZR34;SbE0W)2rfE`$DYuhf>Rj33g8muY$B_Ps zurG;I{--hx0;#DA*HWsQ+Wv+nOsIq^$d24rZuOYymcijCtT*T#dbW5p#!x zk_#}PVn-@m1D;(2B}|0yW?a@)3aRf=>VtvPqry3<)%CV{@PO@@Xf~I|?u;itYt&$x zfFfps!(7SVDgRxrfe;`qS6Pf+@{b@n5FPx73iF{OI-0=NWdr1TwqB4Tw|2-ziXcTC zhm)fmx%IeqqzF<(s7nQ61Tlgb@l>u7>Lc}09|8NnrveHom3ovVC`(Y5M91}Yaz455 zP)3~u-GtC|Oam{##Ms|DKNo?EhY33xsh8#vK@UVBCRm z2gV&3ci`HRiT2;qNl+j0bRPo5NPUd$VO&pK<0G_d(5|Vkb`9A7y*=Mt0rwl+Z!ovj zWWXI5cVJpMAPVzH5^H=?Eoy0~rPWt04K*|nq8>Vy8084c5tJhs#lk2SiDH5M--m5_ zi_-NrcMw1y3HnITM}j^QjCNwQ6K$K@-M+|jl_P_Ms>7a)@ zFz&#(1LF>iJ239R^?3)z-M4mh^hJFH^%2xZP#-~k1oe^nqmO|7AB~laQML4x0n|xQ zCqbPAbrRG`P$#KBItl6{sE?4Usk(3u6l!Rwp`nI`8d_b|(7^tW0a1(gFYY%QbuJAH zSvP=ffX^0%;0}xwsZhL*7`e5aA1Q(qiH(hmbJgGgF@hLDjF1zYopcMqf>T^IxN30K z;Ht?{Yt-gq`^oPrTA@OUc#tAs|Hncb0JQd^qHw>#{Ra0Nl&&6>t|(cf6WQ!;^ek3v z0*QMK?lrjA;9i4!O$7>AjEV}sqqT<=(Won80x9B2ih%tem(UNjG|<#5r4PEvsaxC47~2gco(%{Rl{SGd3f^%2xZP#-~kq{42DJ`&VNs;`fL{U0CK7k6NL z1_b7$VRlVLZzD=ql&;m6t|(a@84xI0QL>_Btw;fstSDJkw85NDS{+1_5?mvV6hVsM z36*$4B7++Pv(R@7TjZ$-To^;XoU zmd2r$<~=P9H8jkTSDVawJZlfn+QYN<>grj0weg%iu>UEnK#Iyo>1tN%btqj?x}tQg z+=>is8?I1SE4q{rxbVx39UEDbwCb2 ze~9fbKc-m_)vABwoxdkbAy%%pn2kyekkw2Za}`S3j^9*$o_JEm+=5y5ch6uphIChQ z9PvSZF303;$0%QN2|N|{e*&q+b;Lq)MA;XB-93-wKysL9lpQ)TaSB{4xL9zp6w|%|g)x1CC~HK9bBI=>Rw+mrT&Gl+X&wA8 zS1HU2xv5yE%s1+F>Jr*0Rna*X2&ES*HEN~Ytk%*HB{!>SW4xSwr#xmpQlnRx`^IOO z6)=Sp>oLPMdM z{kdE$j8hb*PtN3rERr@?p)t|SET)Hq8Y|-`t=yzA%X8IpZ$&N;I749`sh*287D%39 z%uII)l}7W>7-%bpj48bm8fxazdM#}>7MJ5Vvj}R{vef4MWPPE+s8;BdG;Vbw9g!BM zn}nL6tVDMMq=LzdfToa;=OAij%BRC9B>aG=ehKb&24S+8t`aI{RF#CUn$U=8k(kbA zx=5(Fv`VA}DMG8NRFH@1^%^9vNb;JP&Jv2|Pv`CHa04icFpqaYlwfkONV3yRCztkr zU$p-{X8#BI7^(1r(077cN>&H_<8Sai1~>5KB?>UJnZ6QgQi`*{w);Ocbgo%S6hBq5 zj+Pq~$^zPKD*L^xCSWo*B0~wfA74QLIn=R2HZf}%*1v)PTLUHm+)ZIsxSLpV8=*c! z4!P?Z@Famzqk-&o&eLQt>LH7r)Ni1-2|AZ}NU+<2n0VkvfcyMF&mXB^5O++gxJ?#Z zv2i@ESaxlw*rq5X-xkawBdJ${S|z(178i#%%A9S%Oe`=&!nZhFFa%eJr&mX5S0=_T zsg_I1Jhx68wbH0J$aC~_ao70w>UM8ca&E04t0(U8(hf|tgj$dh=?+p+Vt86&R5zo% zo}kp$kdcBwZC1tZCMNQWDu*{z4if(lqGnNH(?XsP?jTtc7~pU5lfVrRy-GVWLnPFq zDnye}otJNxR=ta&Y(m-OT%+y%z5%nD!BsnDj5K7XlsRG0DdUMuX>iI6f}Nl$rwmJO zbjpBYTi&6->*xok%s{)T~9Eq=b#l$x6VrCpejAgKMSF#OGW1CQB{avJ6IZEwd` z+MXF9q2{>-R20)Frf;i-&J-}iB~(@wNkeuwDmth`GmOs& z7hnj=YER2*TR4*h%xG9eAkQw1&__iQ5pJggH-s4q90{%tM{s?3dVQ33V`O$=RoO}9 zBIt?M4_ZIB-TEQ+f3Qz36>e_uQ|Q#-13@zaTl=r@{S$8C%VQLP7{Yk)17eym)v+dwdb{6(7wSr<5Px*_*g+eWa4a`;0z-y) zD!OV5V6r5XrCR*Jd=T1$EeRu-$*?jc)#3!^f_Nio5AvlZxt%Y?Z5@~f0``bU+eC&l znIv4}-uiILUMr;Y)k+PGTZhNCjxZ*}{k`0YBla{xWQfNY63$Gl(GnqNsi3;+*-d?d z`-CEwW4x{rGg=)PK zj$46Yyxsaq0uCm|!r@~^CI=EmZ>2fZMC9s?W>VdNRClK`LtGztCYMo2sAPLOmc2S9 z7m7*XoVQ$B3YfQ7sF1y}NMWSq3YEg3mKVl2RiPNQ1mHC&J*g*&-^^TQ796gpcakY( z@6HGC;%3ghM+ORWcwC+N_G8`zRQO^cE@B=P@(j zVBg{@>CJh`DwEvtM%i&gNpK925df}Bw%1o7`NfeRe3;X#>%&BknTO3B=y012O`hB{ zJvoOmI?Ft3a>BxxR^5exelia)4152-T~VG+SgC9MKh_+9hOp+2j#ra#2F3&6|N zK8b95oE(L-A~ot9BU`X7RVbCTMh?FfK+(OzAa}f1cD5Bcl^wKjm0U#^%JoVm83iYb zmn(ncl}ZbgyDN)F8P%xv38{UyCd_PLNK6eGqSRYRuLN3?D`!t@M#e^<=EyWSArz=xeaCJ+>AAv}hAHItt|#QVGl0pJP?7y3S5E+_xr?#r|5D!w65y)t zj>d;FB+!5;*VU+qAUlD;K~GC4dXkgR%;9@?^ye~I%6oOe&)}-h<5HXGxo~>4PN9*L z_(+-mEZJb0gnNV-2mKsIC80*-IniDZA%E6t1Cpy~HrPs+d*&;}p~gFglLYY^Mx^S= z&STI2pGt)r8ypMG2;LWz82D&_ub;-}2sO1vJ^*GBV*z!xnY0>qIGo3Bu$ZM51DN6v z@wMdT(Izvo$jcVhFuh(=eWk0OL>r;+iJ7o~?Z4!vE2JU|jEW-S1*yP-ks7_i92c8r zfsSiQMx&w_`5_R2v^8Q(z>gMepuKwhAPy_qXw)0!tX#BbaI#0Tm#+j zFh<}?B)jiak1KWt6e=_pkW*^f7!R()97|p$mXxm*WR6JYG-l=ibK2Bk$tW#GBWbf* zwsc%^2>BwCFA~N8d}&gB-yyfTquc49w$cho=6)Ys~yc|A+yOgXh^!Z@Yl65a}Ea?`E(v9d#N3od$&Y zT!?jQtDtdN0S3e{1td9FkwK!Jh;4D$wlGB!Dy=FVUZFHw?6GENfLGFBk{rYANQWzG zFCw%TTVtjWtp1uf^6egD@Vz) z0PoY8Bfe@S1xm960x6%sm7T^mdm?Q7(5We* zln+G(HY%m}T+R#hhi3-I7@XxmQ8@||9MrAW6~NEYi?vNY_+b0c8`>u{Q*K@uI(o~* z^qDWk4gLD^>V$;cblIBuzpTC6XQ?dz^4*i7Tb+B8nN@gthVLgb!*^>!S~Qy{Q>c@b z_iitc@sZ@$&dumg+x#<_=Eh}=?m7PXho|$7Z@7Qa`19t_J$&EyZ{5Gd&7+OL^My=L zyt(zyM!fUmd;Z0R_cV!mXut61@*gaG z<__+4b52;TLw6WAk8uLe_sIw6l*^1F zrK09>#$=jy-}6fV-F{B!9wG_a;6V2Y4du^=Zb_eS-Y4i@^GALGk=<#}Ox-bo$ZqZZ zLo%kP%X+<(zH}d;TXSKop%0)tZs_l;=L5PY?mp7!Y=zR1nvC4uLABkIVVU)>ccjM7_Bsk)m_H{z{p!Z(v?m%}!@Bv>wbT@9f=@EkN zye+$C6LcRLe64UWpu2F|h>J(3rOS$U_1cr-w^X*=$N%x(fbKox?|o=FpnFS;n3w*X zHeWWR?Xkv_uJEJ#P@j?c3upc_cqlh6R{Okc{RMt>@5o&9ch<|bPcu2r&10{?^UeC~ z%%G+n-ADJzU#`xZQ~0j%s(3B2!2HAabzd_{=_hI)v-+==rKJ+t?c;>*fgkxw9q85? zH~8?O`=PG%V+7sr9^T8MJL4h6s%Str^G8XWrL)pyUwzgj$_LPWOD*L*x6JKY9=3(6ZN6d1ROEy1(~xCx{%%e7R+t z;&j=h<-?o3dZkp>tJMN+49KBLtwUx`06CQ0Dy6}}x$|Ua?q7Fkc|-nP*6-e3tJZyf zbMRSiT;lw8$`gM4yKKt0H>@2ZBWj%-3ghOHA@F>=9e+TvXfLA^{ zU^oBt%^|uzv+BGYdS}xOQS<2T*KWlAr9_7ec0%{?ORpbup!=D{%|rRn{p!NclgTdI zZ9=M=pga8Qaf8`W^q zwO`#19Y87_u}spMa|>Xkv{`(ZX-HmkQ2I-_ZOXTpnFlt z$zVQof3RrIy9C`oQaP;spU{YTa3i35+XKNPn;6q&4@E9GdH#B-EZ1`OdxGw~S7wBc z0(5szdg(x6<~-RA|9cWEm@0HFzzkImLeRLoGd;jAFErroN?s}UAZ9d;$=h6Mm)mEbBal9dYYWm#- z-4Z8s4_m)%j04>_TJ8$sL-))d{+vW26TdFlrX{jlw)6eQxq$8`cU?Mur#4;I=wdg& z?bK3P)F+oCV*%YOf~a*#fbKU#Bm6pP=gGeK>bY)D2k>hq(S|O~9=v&Z@HgDJkq>?O z*%yEDqx-HM~q(L4oIc{rP9_9{Yp)=)QDfL#g?55s`@vPyU)WURC$) z|5eY5n@1aC$M!Rjy{2iqt{e*8f|Y9pNO0QWJlTcgUfveo2k^(le#7|o8jq4E1#oV*|G|CWW}&m22jDvMHI*xD21&o;mKL{{4jQ|F_bw9y_sSZ=Kg6U+N@o9yt$e{v+*8V*iIb zp?hqLcP2W}oieOXLq2pLy=0LQbQ{`+DhRp_Lx=aB0qFio+v>~Gl62YfRfQvFoG+DS zPJZk6UV!e0O#43B1nAy>G9xGP(9i}b){x!|$Mnh(D<34X#n()TS zY~Jzf^E9R&huhaWbWi8zalgRx9ahIIRIY2tJ3l@lxh`$d=dWISPw;b#KN)l-y6E#d zk8Wy@xOtqTT5m0kSq|t9b3%8@zPFk>(EY9YXapa+ca8qOn4r5$(`zicdtMrNGX>E7 z+8v{tY?zlW>tQH);5E^h!YY>$BI+c{aX8_Vy*KZSgz&=*pJ+2_N!4H}26UDdS&#o*&&i+r9nUM~B+fI&}Bs=CNDg`HHul$@t?t_t8D&%iI^w z{voVGJ{GE+_=xq^*s68v;62DMHM~S|Iy~P4&6_3^B61eeERTh zU$^hzzGiZH`|#64H;AzRXV2Mw_0hVIZi*2(k1d+O9&Bb}s1v$J%`x2Pkln3D-xrC44Dk* zUiZ~PZI>tK$&@!wc0T1IGx70+dmCN<(0@oCH}2Tc-J4QeWF|)JeD<4n$2G2X=-$lD zBU0e`-q;Xt7#Hn6y4Up$ZRmGeMErkKY4)0beysEMKh=JTsCl#~z_z z(eoJP=~CIjgkwWGfE;=t{nN~;exJzhPJd?d(Wxb}oS$E4^vJLLyX@u7A4I-!zVVP; zZrq)#dYs+%Z{)Zp@3B|^emndH_tAZ^ z$-0d`=S1j`@lEc&Tso%Cqnk=?AZ{M9LuX1^9kP)Vy2n4;_?iRVk01G@2_L#+wkr-0 z3+eNO5lVvY<25s_0y@tn*zG!BhTL1 zu0e_H*{AP(^YTOd=)QJ*MY}Besn+C?j>u(pl-De-Hv%|7I?ni zR}D)|I``3ie9nxAs}6Y z-!uIA#(d~*^vt=b1l?n16tUi|1$RI6zj=V}F}~Z6tk6KVkcHiNI z?leu@=MHoyjw_7hL-){T{g1u_=x$TcN`UKGZ==E1_uG(KBTa~xtp>L+}$K9?i-fmmgtl5w?+_-m}C2hKE zB!Ap(@q)zhy;jve&Ey|$9yWpJYn+z%>O%|MM|a~ZO&zT4y1>!p&o<(DMy$ z@O#GbI|SqSw+gAJ-`x6C!zIGrt;O;#zdY1CvCgA=akC#ziJ8Z^|NZ#EpSy^K)XWLp zlV1P4tp2~t#lx-m(7m(uwNFU?|H6+}vibi7K6ibT0qB12we8cUfOl)iuXp{H13Ki1 zz4PS+-KX_KXIlW>gXl|}dz~wmwP|fVoWGD?b}xFM%|}Z!Lx!~H#@*BZTjP;je%ZZp z#?UW&yxOAHp?f|zkJSRt_l@o4>6bdXFT1d|e1TG;;Y*Y=6FC0n1a^XOiiZWc9< z(6w>1eq2k?-P8%)nU))GIAr(GUpBPlL-&%yJ!cVgE17rM+O0RIzOp(G(EaMg=o3ch zZgKBD=lq9&ck7X!y`~d%@Af-1s0h$~^zKs`J%2Bjeev?I^33`C=zi~`t{b-{-7(~A zZrp3x1&aTv_|d)Kujm_vZ?>y-=zf=*$0C8}`$pYzW3k$Obbr4yC;!n8-WHbmz3*u| z@6#9RJi4hN%f!tiqD{wcto`4_3EdgV_m$;tL5QIRAG&8B4n9R96ZilAHCuPPuuJ%T z44}Jt&XC~`PEMDlof=?x?w3+o+nHfA2)bJgdAdb0p!=2n=JYq$mBP^;|GCoDk+1dYQ0vg`n8$g6=X*D1Q_O3<+(-AYDV>?? zSA{hbO7ni7)>#MZeEfg$)cvC7@ue!)xb;D_|8Lb~Ywz!+*=?QV(9AYI=N-H3?2w+F z_~g(eg*lE`NUtpD$y!KR_jT>bKpxV}mor|U)g@i_!i^De`A|bTu4TX8?LZDqU(_LJ zA;_WGig!i_{Zk?vl=bZoSJ&{%p(~euII!D%X7^BT+@^ZHx)<uhaWBw&i|)^(r=9P+gbN_+02Qe=8-yb%|D%X zlz{$Ahs%#)=zymR|68~D*Z{f!=qI~SkXoymz4t(Jy6jB;$-OT?4yh*Mo_7ek`~1>GPAsJSpiQr(eo-vjJNM^_|0wt^ zq=CjIy(jJcarb_1+_yRH_a02)w~$U28CyO*?9W;!yHmJ%91(cFWncA@b~)v~cdJ_; z^^6@q3)}z9r+-{n_4yNZUUqMP{0C9PER5euQW>EeGbqa(zj_&3$T#ll!HdTe5q8nPBOX`v5>;I{C$Y{ZpVxs z^XY_7ie)nbzf*rVogdxp9vF18`P-lFR&e9i_FQ^y<#2v<7d>|KhfmKOt##;Dar4L! zc)qu;6#P1_yZf5SwB2U^0-K2V|Gt*@wTyqH&ZC<$>|ZBp9*KU1y;=Ler4zcR4ogUK zpgU^#tag0pj*~AvMbMqyN@5`Bo?P_GFe%voXAiF18>>l|J^EYEqaC1j%kbrMa|ybo z_f!20fbOv)G!{?)VJns*4t-Kdd-Fz{es^mz z^T3KRosaO0zpU$stupsoo)ndfM9e;FCkk)9#)8A;_VBT3@sfIiyZ} z>9T%5M}Bc~64}+Tuj1xy zxY>`focVtml_Q8)q~#k2f?O;xV##=!@EL^LR+$`95wN{c>_A z_jlR6%bh;WI3cV<=8WDF{>Nffo!@1fuiP$b9``=FGcs)z(IGoHp*!d69akLa4jyu~ z8y~uF+-&sC0YLXt(|$1#bjKe*aNin0cThN;t%^>UozHvmu9pDa`_``igzU0(j~@mq z0NqQ@zHsBY3&pZuK4Fd~S^3eO7;$hpy^q>+h8y?E1Km#lrshZYp4Lw_RcGH(>(Jeg zo5yZ}=Zn1h=<$BD+(&nhw+wgXEE1tZ79M!|-8Z#$9^F*_x8mlp^slsjtPa`U3Ehf~ z*@+HxD~!9k@}Ya*xpS!m-OB@BoI}uk;n!W$mjSwe)?PcD-XmSsXZ-&rtp{|c&ep{c zbZ0Mob!7pddv2Qz`?437$Q~HF&zjkgUx#eayJ*^h-WPXoTcrQn*HPVeG38ITYnn1^HY6^EG#WhmFLTk?&+_`oY!_cwfhckoG!3)ljyVj z=zeBM@sBU9zg+9={~T@}PY66;|8b3ye?RIzy4A(Qb~o57jPB`EwmvXAbw-`{-M;Yg zGot44iY4bqcb16-;4b+oS-}Dul4N7MD6EiZZ80Ir*~$o zn_8yJ41cAJNdt8Ee|^=dwt()o`O+jSpu0iaXAQq=N@O4OO5a{^lV3CW<*m~1JI+15 z`y+1L&dIwcw)vGG-HpHL_+IBjf7d#6pXcTgF7SK>$F>;t-aMcAB-;NTG9Pcl*OX>=bCN^qOAB{8cG(1Zcr>3J^1W-; zTB1Y#z51w;=#cMx|I$6%Kn}f{KDX_Kap|(-LsJi|hd!i<2fo})Dx^Ptx#w5yKn^8u zD;V{_J5YzT_wbecY5cpax%)?B_grtd=PquXnr?M+=4k#1>66ph} zf#=&Y?@Ev?)cpwQy2saEUA0$4hcutFMWu^N>%JViN8CJAt3&ty@dVK!yE>sef7i6% z9OxdNdAJWBy5G(C^J{|ck)toN_J6~kXD4q3bho|sO#GQK>9Wl4c3w&XbU!e5updG9 z-OpTkxd)&-4^Zm4X#Fd9exQ}klg9kp1%@#)YP1X8k16G``^XSg`N!&cT^y-xV4x1s} z#R=Vci;{kKpgVQUQ@#1n?RR5Yd*Ztdf1(5HyDd4@(6$B8y=%^>4+f1)myPcG%-|oO zL;8&sk4@_c=>F!u2mVX|bYDJCpMA_!B0F__`o>V` zZqd5rx7mPhwe{C+q%%>B?~MDB0Noe*Bxd%WRw8?U#K>+_e&e^0_RlB?(LCR9&qv(2 znUTsSo4(;k_xUBUuUV68pJwt7HxHrbyF0pT!(p$uZy`N9WG&U{4<igM0QiYnrUB z^Y(u)**;P8Q2z1aM|&2M%EV4i=%y1wEe>>do|M*;58Vf{+I>XOt!(y95kdF2XC}W& zG812jS@2fR0qL^!tLA+B1K9tXyV_hOakn-v-2X@#pxgJ@n!n^n_v*W|Yzfb|u63HpI&L1T1fDNu#=!LLXWWnf-?8-c zGdn*Jmfee6EcgF-?Ug#8|4&)&5;c!)6Q*p@twa0&HW=<6`V*zuy`AKc{+E{(4mq@L zw_jgAIdpjC8ix2G4=h>D=8!&+XB_+_$f14XnmwD?2hRT+^W|O7f`!zpci#&{hkW(; zg9m$p9C{%p>&vU-=F1unQt7gP=Raj^VRoSH9X0G{@+cA&71)guof;oPJzjj}T>=O4dJ#&n({lB-t{ii>=x~$Hl zd+3&XM9t&52JN=J3|V%i**%@mtu0=)%Yp9V&Ku+S(Ea%7xf0^t`rWdX%^~fcHTB#x zfbL_Rii-vePnQK9)NlU~&>g(}-Gc<(;|??oZv*Jo?YKDMVE=it|M_%iZ2pWN-G>Vj zzB&AG*q)u-xbIfjGE?^PqkG|=ov$REu6;V>cicP{3q0TT+ zyQSm0IVoGduJh=o7?JZ>-99{;&2H)8gl^5Kvojs&PJBik%ZKhc7e{9hbhjP-1DoA) zx9ZUJ=K$UF_cs`5oR}^P&U>!t7@+&@D@#Un26TUt`SGkF) zx{v#E=-zMCZ@n-@*vtNB><3g=+qychLvE#?6g7{zKl*>xX(_S)W1P@!e&Vm69J}n& zBup zNI-YTVW}-b0_Mr~Xu72u9^%&_*PM=>mihFt-Fvxluf6}?q%$k{b;t?r)v+29e{$7pz{{Xpq;PyVk_W$BW+m;;t-(z(i-Bjo0qULe_`}Thvd5q|g z(N5?#E%;!T1KkJS-q@cH-G8k=bdsQZ!@O`dhxCQ5cOCj3(B19$xX8zQrprp-+W4$5 zSV%kajjs~>KjhOPD@pFw!@ZlY7t@k*0$}R=XN{B9U68(`-PSt z-LHHoiJ#Z!X01c_8g3r13q0Sv7Xo*T+vL7?tIy)aF%61^V@Q)%ZT=`@p`^}7NE-~) zikrtLe|;UnqFd^OZevFAn+|kecw5tt58ax8;%fxm?X&V&bbqo)*I+-Od+wS4U7b|EW*AQI9`S z_t8y_|LNvqV&-vtDni%tNt&?pDk+pZn&|mwmak+tZC&YkA{E zJAP{Z+K_fWd%ohv?J2$1^K|2xyyKr-oicOjtF^B((J_yw1fH))>^(bUs)6qK%y&)& zeszGCE@h_P#?+06zN!0tx2dS%qUK?|GU2U8>oNXc#{XLXLuq!RlN_4&!GNcT93uAr zkCEwtd~#_0xbHg=ITU@cAuERzoyM#=3v#H-vsx29C|&mR*c%&ugZ_WpmhFCm?U2?p z=>X{=eZAowhp$odWYa?LFGzFIA?<_g(5XH%e;n)>w@+m@KDv~DmwoWFFZbVh=8xUA zjof>=dE6)Pd|$MQ`(XVk_jlRcjPERJ9uEc|YJAR0 z?Ek(_=q`EWN47&cLHF+ubqe4^_pr``LJ7J}lb&XE$Q60Um45=d1LH1z{N2EG*_gtQ zf6u>BDtlcTKb>UReROoBYki~pYYvpiR=@qXEMLyAL#{hIH*?+>CkNlfjq{H` zy;7dWkM4iAeMHAkxK!)Vy^5R1Wr62={7CX^Pqua+-4o}}Ki}(nVGD^mtUNm_u}_^x zHhIgyw+ABjBTobmCdSq`i z9KGw_I*;zc)Xk#iu~h4ShyEer-HLZY_uN5e_d3x1@Yj2N`Ow|(uP+Z0bYE%t8tc1# z5YKzGv0;^BeNG4}Vk&DV6J z_|dI=eaEU-xBNKx95-&=Q}1p2DxM$R+hdQs`(x~%wN7?V=jQRW!1MKK)AjMMH@h#p z$6SwXx9m|75z_m|{P@nKHFX}{)DwNh&11u=3GG??Kh6o=MGf1`cA)!N+e#lkbX)1J z&l7atv$;2m?u*anEeiv54_L5ibW#6wS(feNn|g>$JkjCHlO*o8auu`j8l3;P`1wDJ z3l_|iS)>m=wYw>Q-t9|G{!-jH`T5`?ZrrMAH;bjg{CT%e$@UDGDK)FlSGMSNQw$2(WD58%qo$vG?^tDNU2N> zC{xMM^t$=YiBR`P>;UyM+ zw9_rr%XE8Y4tu% z6Q#Rdb_GO-Ax3_e=Dl9=OpbORBC_pkU8{)QA>|o3RF$r?Wq2Rb528*-y{_~#*GRaA zG@_t8D*5U$GTrwqCFY~i9df*=p7af=bPwq(yYqa*YTkhE{DYVD3|8VHUg7KM+v7dZ9X{XzFPmauq&s5Zq?l~dc;yW0gZd@vrI_$e}dZZfC zkb>@m-p5Jb|HHdm3G8EBXmtBEY+!=vj^w?$5B6^3sV^>;fbIYyZ|E-w4_(js(a=8~ z1BJyGyoC2|57^~hh9{&o)|wkE2jBm1x#$=u^)KK5?@%d@EZP00h8(wO^{c0!CeZJY znp{fXJzo0R1Z{=-Z~gN?M8_J8{FX=Wf1ef);oUXMO_R}_j|u8 zs&pu+O!h|S!QO2^L3iZxCvVB#9ry4yCmP)q>-H$Y_y5~gn3C@QUrt;(E(_=`?($oG z(i9J^^ZwMjcP<7x!elrBPe{X8n)M$BbT>uiX6_FrKpFF$RRX!tz5A8d72BDRE)#Ox zPkFt~Tc*(I-q(Nn&BoF9bk`v@Av%08@@r;h*XG_qyLa19f8ujaroy{J%A(@8{y*?_ z%lBK<>3DNPUWMe{`V@3W7$tR+=@z_qkOPhGvofK^@X3T7OAzVY?TWWl!Z6soHLp1# z)eX+w6ov3`Ipe$}K=+fe?Ja@EVbBG4vp|Dq=yacuAKBU;_SS?P z7b$)GIC~v>Wpbz`B>LXnQM#i$4AF4_BfsF^S7QqPgST5-YoNx}+ySeshw;3av4eO>;>VMyFz|-d#|Wknc$F>aIgpkBd?@yIx1RDo0%TL_ zp{~h+?n5a*Mcc*KNfS3Cak<_iE^J@WSJ{KN`If$qQ=_{M=?tPH8Y90aoA<^n9ix2? z36uEg`)^0FYsd|v!#~u0@C;u=p8ZIjj^iiIe^_|IHRK8kx?_*jqdNe zRy86t1=3*V~cd>BhBFsY7+M_9{{h2~p4;N2sU_z|9jDr&0(Y+qgA&ik9>&BR8M+a&5 z?n!C4#O^)V-fgVtEQ#CogyHFaa-KRJT3Xg7hYDctHl?8Zh<@Q$GTome3l^Z!EtVW* z0@EG(_;mzanap^9dzuC4#+Ql(2ZQ(jL{C-k*Zvv<8NQvdgij{+++te|zujUbkTrEy zAM9@7c|XWDqto5+JA3h#5D}t15+_#oh?h`?PIpHpH!*i?3Ek1%i0F8Vk>9%IRkq1X zY4869#h&z!Ha)<;A#L-bDxA>4@O0zCx~bFQvHgfD$-7M`=#HK~Wl5%c?sYg18r}B8 zd*xudiPgJFbbs2JGw%$bTjRJ9n?88E)r+M^&;Y#u*Op6kcWJ#rR&F1U@9-pvPo$0uSANpncWiM+|f} z>2f&iLsb!uB5Q#UHAE&k-(wGh&fR^o$vX|*hX&bB{j_``MI^^bA;! zY>=eC{=W~=(SVWPLYwyV<}0-O(0#=zZUr3n{eRr4%7#4`T^N6r{pCrOjtp+12+kd@ zAy-q-oseL1=x@5GI7HFtcDj8o3Z}cN{vGLd%lDVtubqYIHV%?6PQXKXIGOCb-(#Rb zelt8=L%N8q9CrkCr}g}DuzpQ|*aat#O$DOUJ#nWn%X+&EksMbv_;AW+2RhxKb{#D| zHmgo|HRL#=V-zDlbF)xQjw7_!kQ$AzGm3+->F)iN>!tGIIm6Sfba@3;I+$G>o`kTR z0d$*F&>bHbUqPl@>DUipG`dX-1s=n6$5_gT!`_|VS9T@?&>fq?qwqBz53M*WuvHGw zUDtGZ3EclHg}tls2Xt?bJCz*SN`N?vOkyi`pwm4<+)ebCmnD+pE`8wDyuS&Z?kL?V z6@zLGx}$p-(QybPKhDr!GX+?l;?TGJl5`b>chj%(X z!TG;U|bj_r-``XJNYSZLJT&-fjNu8KD-?-TvUFt5h5wQhw3# zdkoL-?Rln1`d5DVJEjkajZgPIY@clo|^&xdS z9s~=Bg59k@{r`Wbo2UIxjd5B};X}!nvg*h_R4k| zF99E7H<7x-auN?YHg`XH0PZ2Bd&pc>1U~drDfI1I@EuZq?WAvP4*|NQ%gnXpUpl0^ zn?{+ri2}q6NL)^>-^)YW(S7Ka&*Q%9QuOzR)ICH;8Ag65_rDT0iKKm%_1=^HPB{y^ zL&Djs?IfPJXZRWtx15(M9jfU+mz}u`_y3j@bf4b0Z!?*0#q=MNXmkhG9#DaANVl&d zkX}ej8tyW?0O&3=ChEALZ$;Lz+c&IAY}2)Vtv4X;a!)S-x!D zo=fi7Q+7H_cRl$g{EXr0{>W!Vm5z#=&$(Pl(=FFg(4Dl(R+db+UEMAQG`97SWhTNICXGwGn0owjz zMu$Tjo$ig}tkJD%VnkOYuE!{~brl;r-II>fPl*>5=#FknM8^b1etfRK=6Cwj?%j^( zn=PN-qN4v-J~?=EOAo`-jT4KdN=LS3-A1My*t;z#=sv~WX-cNs?C!aRXmsD0QqG3y zt`_tleY<6A#Pu=}&~0b1RP+O&TSIU-h9A)VD#mYsDG1W4`K zWX?iqx)Ql+Yn55 zn|)LW-2d;6Pd|1H(7iL?ci{k_o6YjaeIht_ixi5z49{*^wD8h@J#PM)z)Ql~tLh^XczqVl1LV2P41nT~@m} z=1jJL4k^6nwy71^W#2t)ptJp7cGD8L!i@?_{teXR`EdH0TTUZ`n2*CGp5OGMH+Vf96&HwU3 z`o${SnKCQ-qkFpTFCFJG@-y@ail{tGJKgVjxvvG8W3RHM=L6%9?9#gZKSkMp>)%s& z&z343x|%0tUz6tlSy9k^P6zjqO!v;`HL_@QFR1pDgXxw|w=0_YZYHUCry=>EQc+gRJeFo<2W@5<11^bW~cX0e_J(|jTe z5~pjVZc~?u-XT5U9u{ogwvg`Vwn22%V&u14HEgX)0_}8rx+=83XT{#T#eHwRezo!( z9o}o&I`9is>!6LXa*+4;e%A?RVWbbxa>mZFr_v(b_b?~`cVp2~K-2d|~G2^)m z=++Ht4(9{sZr`m3&W?fIt!Gc8T9p9Z!xc|2wF0{B<=!}}DTG05P8iKxAfnU#JduYf zXOx$?3W;NVefn-oF*@D9cE)z9sY=rw-7ScY?-=E8E?;I)q7=}tK9M3oM%8ryaEqEr5y|Npm2NSgoL7$;i_AG&-(Uy$rW$`!)OXg+j5 zI^F=DL*lnEk~D|p$$3L5c!qSgqh0UU^IIf6BcYuj!6-;+RUh*Dzl~q_>oy`JPS+{O)=hxPFNKG+};~=10W4j^~ zO!rRh`?g$Qm7Q_u3s2b=4y_e=Sa0$joo-h9^Zd`BP1l$saaleh`)eoB>5glfJ|}BN ze{V<)+x?~E2u6Oa(K%k1&1k2)ze}XP?)qcQ|5pU;uFE;_+mzwYkj$FyQKiG;r|eL| zvvffBW(vB~)`vKe=@!u`Qb42oXp#DQxQ2{b-A|g3mg-Do<_B~S5*4Cq9q>@a^}UPa z0p00aL&UWK-Hj&<62t)A(T9aS?Y|SC2Ghmthm+82NQVsRpDqVki4TxC!EW2nwo&Lc zqz>!au64{pbXP;JM|3R5$S+0pQ&}HGdkv}C<8Qb$0lPy|N&0!hM@^aG>HfWDhAJJ( zPxw5)9E0C(v7w;*;+KhLGTpq{kxS9&E^}Y|0j7Hjzl(G;@fGiz1UW!=d2%@Go9%dL z$jTX4IWHD^H1kDC3($R{revccpxaf#JI_do0I_(df82Hl{rms?)rKct?B^u@_WCRC zyz$p`u59%4f8P=Hmabm<+q=Dl=9m zlZB0)ROw(^pPaasbTiSKg6`Cg6lXHsvhOx8L8IGP`*;$(cdO|xMY`SMQCXO52z&R~ z##?86@Q}*-hZFjM?z@LpE?*Alj&;e%(g$>(RE;liHzGiWTz%rWN9c5iuslz+kmMxl zB5@Bm)Yqz3pwm6EIrgT*ar&d%7tt|_kzbScr+{C1w9_qg*R0&3jf&|OqXRYd8kP)y z?uI)(Nu7?k%2eq;_y7OdrqS`QW1Ji*eCTSt&)+kojCB@hp!pE<=H8QVhZOj{-5>6d z2F9|~Hv%8hKKIph4xIn*SibAWZE!*w*JHO;7x<9pf)5toK>uH(98BQ$4THFLLL-GN z=pE9R(6EmC;tNb!k+_a$MX_UF(Q8QQw0IUKk3~d!`$01i{?Z|jkzeWcUTfy7LYSS- zKlOFr*Lele*w`%Se0)0jAsIPP@z(KzGSHw|T^| zFsM9wFe^14o$eL;ik>RS^O#;o;*RJ_+}4Of@Bf`ySex~NCFzcCD@4Z*jQrl#jesF@ zw9{RF%xFp50xE8|?0pyHB9_ANbVvDk?4w49)BAG88~N}Vk^=?ZSBx!xk?HPqC|HI@ zccqC6H%#~ZleMJx|K4?;6c-0{yX_3j`~fDUF|WscndXXxTpvRhVY(xdwO@<@x>HwI zrK}qXgJPu22*O9v>CPXV&Gs7OGL1swPI3FaObbJ&yW;DypO3eQ(;eLvh>j|Z{Aw3! z7rG_WPPf)mwUzU!xZQ#q8~r>a@Pgs##t}b`QKKU$(IqM{6Qg`yTC8 zMWg$m-llu-3u#AY5=k$lXz8wV#7{YkFv&(`3f-eOA@e(qRkirM=POg9JnobM+< z_u_3jL#mwNP+z@KYk4+0-81nzKIh_COnZ>HC8~HOwp4VwOS@G*9uX0wJG$8t{?c(1 zBR@X>&-|b5Y2UkD<0a`HwSkJtL`F6AN{Kk*(=C%hoeo>BbLynZ#EydQjP`+SGTnSu z8&uHfURxPTqWej0NtbA0Sfm4-3!hiG(0y#fKt`@)=o#E z)4e6hRI=DKEcDkQg_kJ(A zf_?uV=l@J%&Dk3aPd9GgUFvigiJ#B%fp51sQ_!6!?ruP)J1HPj3yp52;Dm=T-K`%_ zkZQahKF{wd``UpZb+{;pFE=v=$_k|)%^_6ec^FRns_q-`aOc@ zxaERQ_W|LaMB)-Y(;rCOhmngut?SY0UVC}+n^T-L-O(L^=va@D-&0Ap>csz`hP2!w z6uo}{`wQu|{#FU=L(3Wd{Qqgv4XSiVU#LH2avDDW-$p@q?z=~Szulr1AFv#a?slUCbEWOC zSwWglCT?d+S#FD@!n-HeRnOf}V|co8eq2=P@D6+^&Uy*1Oq?j_&MEumOZM)2ng*I^ zbbE$qH^OvBoWD)FnJ6Kn_Spr{{UUNHZ&xTD>U=ZsEr2Z+dNc2e9=yB7{P>s6ETH>c z%c)Jd`jcAaRoy+c$fy zLSJQDg3Mh57pc(QDm#hjz{*cGPDLx;lJ*Yip+llg@E7bF^2H(M*I5mk4DUk@#S&EM z@Hv>FsdEsnA$L*GUAlg;0C|-)`qpZQM)&2VH9|1mS(;BtC!|>)s=lWKx=*|A&nZpD zL+`siIktic=`Le+b;f}1VEr5Q$$)NV9#ciFBm$%ox|~l-9-Zz_9hHUeYo$z=A#u|4 z^V(1GqSL+hNJ6GNhZ^0{J&Nd9gOOj!cY@ljbF{CrPkYT}%d@DcAv+_)A`6Tdo^ITp ze5!POz1NvnnFiO8J1OWckqi_g)9oFSVSq-rzq5ZF-2We~P4j_wx1b7$Jq6G$H!XLV z2xdq(ICL;=1~a5yT=b2F>Gn#LG(89Cew3dg%yWnUdHD&|-V{Wq+a~UvckXr>Q*R{h z!C5&%?i@+I-*l0z7U=6MAf;8RRJ=l zIaHLQWYB zPd9F>HFY{Jyh@ZOo&RsApu4crRfp`|=fsWl(C8i>=iUI*efjQDcbIPW6`|wsx!aLD zU%V~{;i1->RyN(gz{|vW-rtP?-JBfX&Zh&qEwr0zRMv$-g0{j&mA&Y69~-b3)c7oE zN{;i`$n~(f9lbJHeC73uhmb1W(R~8ZA&-&Y(%*fXbMelahFuXQ@K<&P zrMpOTNM5ENxp*4fvh!+BQMLtdNK5R}c_0M#A*%}~znTIcYG?{-^#VSWX&+f4VIKya z-f?9pYZTpwZvRq{zn#Qlnu5el)~vjp_y*mFzE0NE;3VnqmR%*H11mpe-OtIdm(yND z=5NWF;iYEEPGW$Tz{(KD_aVXos&oWogihQz2iK5Z6m*wsm&uUnJ}_UN4UO(SWkT^V z-O`8J0^wEm)<+lfyMXTSm?`_-y?AJHyPe59aEA0vOZym1x0H3z*1dr4aWx6E(BJbSvdEqwUZf+>clyRtrtDjk8bb8eZ5@a~o;1>LupZ;+;2!h5&1=Ho1A zbWe@B?t$+tK0nJOZ2{hX3NCJv+1&2QLZ{=-d%?rO*=L)Wgi31$;`xYnSp|#}>H=RKLU!bp@51&l1xL3p-26Qj) zI^M)HLx5^l2=DMdfljwPy%^Dfm0u8> zW1BK7H1%-%>-&)Del3JNnbCD-xaVPX;f)NnWPEd$%cw4y^o& zG6MBC2GH)^R{1g;@77_TyW!^AUU3VSG5-AjeIKdPA^&W(QGCUp{-0jE{r@ws7$<)U zAF6RMS0=Br&Hih-(R?VMt&KE?R4k{8)c;St+H@oGy4H$2OE|sL7UQ8~m*QWzfEiM+ z=WIJ6;6qdQT;=V651rQwvEy<8H>BsaT9^-^&mj@qKVh?KsKewE6370mJE-Uh`We#x z<|eT-A$@c=|BtK#D?e|8i~W6(wBNGBB};sap<>F8Uv|psS3S}UUqkAP%~7Qz@jdHR z-HUJyxtoISYKvSZGTkyq)aIknZDJ?g2(Pj~nCnS&XUMn7Uj=mEzR)X@qK1bOXBC2C zz?7Y6omG`E-H*?eopb|82c+boX9bofq+#EPdBbVmpUDW?R5&I zGbBF>x~rJIpONXFpFYBcM)$?Uwq}^_%e@^Wx&z&MzC8zY4=OH}vo*p)?W>O@9|Pb2 z3%|QSJKJ~y@qT!IF(g#a@w9~!z{q`YyE-KEDmW!JTh`(Zdy3-`7(qTCo9AiP6 zkmgH4cV%6>B$@8am)AMb=*Bmmc?8p)C-a6x_ZHbl%pzcSE2{ZPrK2St5{eb8a{;qk zJl2&&z;p|3Tk*gd(5-c9YtQ0a1SshCt+BFyc_DpR&N$1K>x)S+5_dfOU}AzcI^A1^ z_Px?O%S?Cu{|KT3E59JlngZr|w0B6+AJY4TS76`WGM$z${g!CP@cq9+;8Ln|H1F5q z{e2v+OnfNlzMajvm`wNKQ}G;VbUQ?3w8L~8>>nY~ZJ5bcxf{^^=E?h;R@?B9_{gq- zIWTuCVCal1Ot;+k%9QPZZsHntVqpUT>X=<6}np{nog)GqN zwlqECFz?Phx}%${V?9QGrO{?-!nbou(KLB{X@-&~+h$II5+ zYM?UtbN>H-cG~p$Phy;cD17LF>w~9cA9^irCV=KcW#+*t@Ep>G%ABM*r0J)u#yUX_ zx#e|TW4kUMI%ihRbP#+)8a6+u1D=rXJL+kdT_hz=o){GK<%FRS zy+gWcF#DWu8Fme+@pgJ)Y)1#f(=F)#jVc{t#|2ndr@(aYrJ(!n^nzkC-S}sHyl8Z< zlCjc(=`NUzCcXc6=CSmy0zfzGrfm|hl<|z4q!HQsQB zY)T|RU2eT^>t)gD{vPo)B+L0_%?l*Xbf>4b4>vm9>r{?DTv9hgcXUr9IxI2rdz~YF zFDHg}x(99?8cO;^#SLkJ=a<;RpE5k%xZ_W#)6qNNsz}=13ZS67_WrB8WV$O&N*18e zeRhS*Z@5D$w#*^T|6e9>+czH2tzmUU+!&lpjNu0C!6Vg>xzvNT@CoUuEnQ*JfbO@y zI-&9nVUS*=8&~ZBI^D%7hezJ#T&OWX;$&(c^9nvir#m&fLq*0bkM8J>Ms(z1B!*h3+XC`y?YM@-NX}%ACl=# z{JftBjqV@G_aDG?M|j>K_5U}WEVEo;x*f77MHb?r>cgou5@5QeWq-pY-2b0^XVkeF z(0zvM)D0WQFi5sZU-0$>I^A!#gs^SYt2J4S#69)$Hu3L6r+W?mOYN)fZ8bFiwEmZW z!vLaV6-It>6}J{_GNir#H}n&|e(yKzyk1DS3uS1wUBy0@*#(1%yq!;$+*cSu`n(=yKk zy01lFbc_LX*F;zMSb*>UMZ84HVY*BCML9MAx=&~mlD6(8KwD(Hh=MHWbPMW#JyLV! zON|{87rNEzc>gE#^Z%0`*P7YY>2G&S2+@&*k)IBC+|tbjw9|ch2iJ|+IqY5b4IhJ- z6VL5qc)Bm}?W9UaT8zBqk{q~(45pyFeq@6zneK}cFND$PW@r6U4Ab3o-H}v74qxB9 z3O++(4!xXe4(N_`#EHa!@BepM$ghXrklMrk;lN5jca(;_#I0=v2$u)>jDAMH-J*g| zbqWptQNx17;lr6W8h4@79pqD;9Pwm6-R<3~B0BbC!yaa*Qqljr z3FnV&ATT`LIK!zts&w=YK35_2|NANEu4~#zn%xS2-NN$ost_98@$M2D@a`6FtsiN3 zYt4QiXKg@tefqcc-@xq_N2T1@S#baVo}1<%Om~U;nh0G$_pCd2f%5z?D6GKlUP=bK zcV9iov1MO6j(8A>WAl()uW=H+GFhcQCa-41M|X6Sb(mx1$J_oe>}mt;bf2x-)}}E@ z#SQ7RE2<=Re`kEUUrJG>O;;|8oRVH=hM`+e#^CmV>$5Ja&Ci@avWZg>w8VfbPU&t?L`W{Qn!5a|7f4 zW&S^J=Y7yXi_#5QwC`^H%H5`! zWq`fAb;-F=km$RE;ptW}zE717u8PORR|$Xm|Np@T{eSsi72^~^;X{wt_2bDtv`9uv z3eAT&>o;n{HRKw14^oG8HEONWIk3taDjjZ~kikPvyTuKMr(&Q7OY#<|0UvT+)7G2- zd`PE%zV;HsFep;p<3Mve`YOw7Z2l|D;-?8Y?#|M?dC9ftJ~Y_zlyLkkH}QY@heh+h zegUGRA0xkhEn%PL$F%#9z=3dX&!zQsV>YQ_6t zx{v;l@Qeg>-zV(y`qdT&2@Qq+)bU22vfCy6ibpEwr-?8U7d)E~pYMb|Wj8KQSzxl3 z{^%y_IEsYsfGP zx?8{QH7CpH!9%0+l1AtWhcPxmTs17@iWta?wGbp zbwIa<>1fCvK)2l!vs#v>FleG(F^zv0I^D!sXj%KaS(8a5&VQiC-^CW4?!#v^yqGMw z=+3)q5gkz&`Sp!|#m~H|E z-7Og}n8|btFH2mAMz@t@pC?TB{T+))lZi`~EqCn%bjxT|st0@3O2Wa7&l7acb_jl?A%X4CoMhEBIXAB&EU z&u_XrA?-qR_+aFh>*83b^dC$n`oVj!RQ4YB-7VbG+uoO4_A-8D;#NSNj;-(Rq>$cj z38kRBIn$znOm_?4PH{B4M+e79bla!XMt4()RDRBD0yH(>JC7+4z3w(@k8*UdYBrfc z;vU#pyM?)+*WEm(CWZM~-E>E{9-`x$$-n29^=MboJ~`UGdq{X}hqNem|9{fH&EVHD z9K(C}GR^x`>F^u)vOH}+x&P0_@yN|H=Wu6@Wy+Q7IqfcV;%#qeO#t>Sr2J{#wOY~#8Qz7)RYj@Nk>qV=9t(CM0p3g$ zct2xP`TG;nl+R;wXn3y>RXzgaJ*s(wg!e^-EIhoq6|894(!q|0R+NrjW*Luxx~(_e zR04Q6jg+T!1H6ZZ+#XzQB0vhCEk50FM#uX=|Ax-*MPE!5k+`W%X{L4S(D6R=zAM^D zmxb;cq+mn`R(^h_nY$A|(|&}cqAz;wX$uucNImJbc2RK*k2fy+8dW+52W*00wZRS2 zAshwXPhNj_C%gA@vl>}6yi;CFoq+Mi$#s(O4n4l{YZAaaL;J{;OY`s$w`p0H@k9)? z_4S!lWq>zVu6z&kkNiSLa90+er)zw4JNI^LI>uZ@xJ7NiBx<_}MmqDX@Y}Na-Fx@QyKS^{KOj(b_0lL}O?cwC-#Y5%_a@&d~ zV<63pkYg%;vdM7^V;&8Qpws>O zgYir)W3tO#3?z#He|@rO9!p9tRu4(~ZmXrb@@&$PI@I zFTmyG;RMI`=yV@s z!JP;!roZq1^${Hr82L$Bdp<5XM!R<_pCKwP$;Q5!$es|-VLb4j;di$bd-qbMqxHIj zizb-e^4ItOS8+VD^UOGQu^wT%`oG`I{`nJV{0V^ik%Pj6UMW2+Bzw@N>w?N?9+c$C zo&xW%AJ^_D?XZ9Tt#nobcu*==;2Cq!9>xDI(fK_S11$+{b&>}jq&1axL4~CaQp;J? zZF4LX(s1m)`B(`3{;0#sdHcH-{W2lP6>W{a#6RnZ`fYsfw~GCXJbCDDg(d6A!N_lL zT=GjzA?+({mFVx%G6J>-S;n+@_QyLje0%gPsGBMszm`>WoQ)y1N9+`MzhtiY`|^LV z?WiIe-uX(?4`IA3Wb;VJqq@B(iZuY<8&+*L)@H*)2jZKL^nt_wBfHAgmjJvUl)~3Jj zN2_GtP(Z_5kw;(-#{2uCL!`Sch1taL^#E_5!`Av!VDHvnDbLXNYYZgrw}W>n!28Jj zk-Gu_@4+R|{fORB=)^CxfO&h+-FxQ@izcD`s|h(yq-#%!zb*Rh|M$L`()s%I*ZuE6 zbiBjJujTZ;>XiTBeza7_2aRAu?9+c7;lPHNxDm$3TcC|99XDEjb#Y!Jxi>2X-d%~% zW^!?|s5N3K8s5yY+esG_A9(qbE+(4rsg(Ewymd9djS!gekh6Go-Vw05)p6GS2aGoX zmwAj0;O%U^l|T1wD8$^R&>`=Sj<`hRA_mWgzLx1AMh!%Z9>x?CvV#|=*24xW5I zqX6)}ZL^?i8ub78l|#1|g%O~@@Sykqy^C$-1UM&6$Z@sNKGp}P(ed^S?ESnw zmHzN1>+rzHZ-jX1=j~D2i<7Al&Hv8u{Xg!yu-e9XF1m$;6Xb_J_qVVhC<^)p59mHp)aus&AV@`*~n%}j{6XE z;`+l;^ajb=a9@^Ms}S8Su_qB7SotY!ad-u>)9yjy1@(%nGO_O<;cS+?u3r29K!aqV zLY0oWlUAJ?q}$Pl=2PJP_IqIk8E;dKZZ$N#r^A0AgYmwwrjmsBt{~m3O99@&+ZyGq zz~z6hnpTb#0B=oAl~VZhziVo(MF+rpguC&^pm8Wx-A02N8t+xDcZuEzD1EK>fKjU3Y)unB;<9$p(fBk-+X4HKYvS$Xo@wHx8-Oun1 z(({r%ROvXsGUZ*>Nz&z(c@%iRA%f>Dm~c4w`)Hkc`ODDo{>Yzn2*x`~DV2oxxM!fW z9Kajr)tU5G7Hn_rdKRYw@ZNa%tqFX0>qsl}&LMy|M^1TA+m8_FK;Z7%JhA9_H(6Nd zSu3-e1|xCnja-8!J<#!9(PUN0UrK*3w>Bd>AdLKq9%U|Y{SVw*aSze_M>!RjTe4?< zr%aAAJl?oC>U5lSsIvb+nr(52ivsW0S6TkPApNv?zbYEuLcxSk81L;)Atbz?yneAm z65yTDy7QG6I3QJ({gfvN@a|3dTm$$2CtsEBWCs1eM9Ym+3wuJKG7py4ST}UM$IH%2 zWq)8cCC7P(d6}OzN5^~q^Ua(r`vvH(IGI3n%)`jf=A!gdr>C^L_hKDq<O|Zg4H*7z=fAlK`8u)p~Tn;R;{9F6o*8vY=cFQf98X!RT z>(*CDg`)34%C4=RJQT!cdKZb)lqNVTdZ6DyVrKuEk}yGk4H8)gR({*E=e6Z&(e6Qm zHB+134P!5{IJ3KDj*Cnfzk+POLzRxwJ85g0FOg1=_$csxH@k*F#@majQyUHMpn%7x z;U#voV1R^o$-E}rRRHh8)1%7>tHB4PY@N90@B`9EJA~o$e;-o~f&{=j#Z@xbw2A<+ zEgJROwFw>X8>Q=ayWL?kWkKTjUivz_8=>R<{O+nVwYtJ|x5VB=bYSJD_N~TNoSF6$ zq%VX=B)p>z{kW+Q@OGJ9zTv(h9=iU>Z=wWD|BE^gvBCZSrph;WMnM0+M?lDb z$$0{_>`W@Vj|w{8Iy-(`ymb*BSoyV=bO~)* zLA!e=l<&@yp2e;pal1Z@t-oHy@Oa}yK2oLQ+TBeSlBp#3UO<8OK=jhTcW*bo@?MUH z_rtAyq{E4U#k3tx>>asiXOl{RHjK&tPG5$O_h(bZ6%S?DP1hrF2l?L~Y!X9v?;UZn zyhW+>hxaI=11rB1BN<};iL~P_%FEHaKnWY~cBQdt$I)91e?a>6;uKXng1R(cFsG65 z=App5-)`ecvU~S88Ec~9edBIF3GYlL+VJi_Vx0N?dMK2%uJz?L2>t9$Bjep~i$`px zr;xZO2}L6OOVH2%<9S!yQeH=Ycxxg$u=4x7Dp~GX0_}Jg?Jh}{8K7eBR=avz?TcoH z#~W9sN1cvk99pvAa^j!+|8(8?|CJo*|3xS~=<||3(hX8BaDp^9u?vUhK_44_ordoq z>3YtP?jR|=I4d~^W{?h#ri?Oc7}-j9kERtgmc73A9C$ssY;Ht2aRr_7_Z z1V~ABmAQX6x(5}%5uZF)F=e8F#4R?tr`2>H-GjbgWWj``B|- zXm5}{i?iQos>WVoaSJ6q-=5OaX8)v-xxc|T6Rx%4l?21-f5JFgEp$`quj6?z6C++99{{a2J zUDXAtCoBZ$ckBH=Vlq13%{GQ{7m9wG{6ykretkIO9EOg!wubskgE{&e{zulKg^}M8 zn^Jrvrcy<$h13p(CH#hfa;B$-YBjw=&h_}d&E?^6Or_798s>CU~$I^hdwUZV?mbf<%BG*m@Ob0Y9#Ey@%A2s=q2L4w6eofdcn=*& zIYf4EzY#ZmG`xcz>D|sd=4K&g5mfCs#xX5Sv zyWVmS(IJhIA0M04wC*77co#<8l2Ln!eL-56_w}ss>Te9cy>)V6fGQpOe#d(ZCJ)1S z3sB(w@n~EU8E;w7m3nA+uVOJj1LHlja*VWlJKtUQs5QX5_43RHYdbvj!ExKz6)^u_ zYGGfZG{9Rg&iTTAfcHBu*{o)N0>l;De`X02`u0|gSFTi`Jew&e5|_NB@$H5Ybi9eF zcD~Np^mq0ai|D}0PmPU9Z9_2a#ffV8v9F7YsObOQ6jrztU1R+IUqqfd9gyE@zd!x| zKNoxY{59|(2?`JT!XC{5dl20J`%GA|qj`|kf!Uv={y!{>^un%_Ucb^T=>IJr>~d(< z#X|<7C9~93#J_QZL<=Txj>8Q_?%WdR?KSf?UjGQ||j( zk3J!!A*;ou*3{^T@qCiUlE@RmY!yvN9|^~=_$=hJD&TQ9UuqLON5Wg20`KuFD%Z()uU|UDf`<2=tG0tM-aB$kNqDdP zHY_~_@a9WR&c3%C59xlpusDRRHcqkMV-D)Tvg^u_A z0k^zMaTjVLkvM(LpVPjc=y+dxS{)&A=o;POJ%Z@y!^m$>`J#u5)$XKbboX^7y9{sPwa%!G|v#-4M?Ad=y-vVpZ`Za#phYHDW}sCw+i??%SQ+f<(_9cO(rnd*~C?k!4z_vp%lq<6RB+FNM+6cZZW%ZZZpFy2?V z8%b}s`WKsvj{>~ULdZuJGEEt zgDg7Uj~_D`8m5n!=pu0)Id_@(c+m0IFqrgUpPi#SydNPt)G_j7vJVnlJVHC(CcD&2 zTwJm77V_$_iQ!zv@OY2=UbI5gW_au*&-*Ii7$~jFT0<$Jpb~-u2gsdp)*3j^uPF%{J;Lu z#}OUU82OF%7__)+(0=~Ud~>{#nX?7+$U^sy^`09o}4sjx>z?jx>rZEB^=Q|2$oK>4yuk&;M}~ z@*QPAf*2p~-Aky_5j+!AcdwXKK}u2J{p~zHn~b;J?LjUyyq7c8_`rC(@;U}P{GM15 zSz+q-3*a3`sC>J^2@kpY@4SD6D;8qKujz-kx6F?(UK0rLCVq*@U!6^WE>1va^Yqc( zTmAdRP5P^+YtA5XcUk0xAIPKQeI@=tmf0jT5%?RAhk9iCw;zfH%H+;)*NdY z3(@g5_UM(>bDF5hK;rTr*?KKvN5{Lgq-LGZ7>@4nHbQh<$H;H8bFN2e2ki}#mrBor z_IfHlPMnoD62IKX@Oa~HEv8C`+@iej%yN=@OH$zd)zBuNjQ4tv6C7xGw>4OE!FY2z zwUM^B9xL@+fbZU>no5tl>Ej_t`|3${j#%imZ?F#!!274nW$QG6w`o0-=x?ySwRO41 zr5tH=yn9&V6kHldYBnQr+qHU~Sm&eTZCG7+VTr_dy4$^djp#7O$nWYACH4SS+TGj# z{sQHnQ`mU7$5fl&nRv?ZXKztIuTZ6f$%@PT*%9*le}Crx|6dzJdijT-|6fAkLBDy1 z#mFA?InqJ^&4apRZ&bDd59$~%3xk(f{(}d!I)Mk-n0%LoLh;Zp>q#YhP(dy}bZ`jv zAXNwTuG7GS{M}MKt2zmg{=$%=azAtr+H7~-q2QJ;)w1+<)M$Ci;Bq6 z-4aXIftBCht!E+Tm$WajoFl$h=T>7kNY(ekA0KlHVE83=w|WFsI*!Xa@x4AnsvzYl z@cvm7B1Fd9K$(Xh4R61nMsYCSyr(A!Fy5iVI~TtOcyHHGid#znSL}Lq&3XXduCpe~ z;RY#y^O|A=zw&7I^L-XcZ+w) z%g`O(WF1)fy*Tcm#Qz_R*y)yB_1&Eddy5_S%5_!GzyXHG8@FjYRXP;JT{^R_kSfT< z6nOuLuQeg#oz>aJi-tF!-)TD-Z>yh@B)qTsHcq|+c>A2{S$!Z3+}>g`kv#ymw-maI zV)+2x9Az(aJpkUJX`fogzyxVuo-ZyJc+uTkUtA@5N{EN(j>K8ZKhu9dhkpKVsO6A) zc&8-Y;jM@0z{;;9xMb#+1MTiTogpdYZi;<->uYv`-?NcDysTP?}t4TID0cal28yD35F9NWGUz1 zj)erX+_u2y|CXW)e(M6fJ0%)V##@F#EhoeD6bI1pUh-Ia8*dUj@gWj-MQj)nfT(IvqB+ z7IBrrKlA_SrN#f(JV5`i{Qr9po^@i=OR@(Qx9EtWd60@d3j{B*4%zofOKhHRgXL|o z#0E%a-Mj3EhwMM=J$VV1*t{JJE8s15VRoCQ!@z^qhi*BuIwA}Tx+5E#Eb52){~i0Z zotJ9Lg^9jM+!CR7?u%T`sPUhpA6PYLE}=UQBJ22sk)MN)S%e%f?R$`X8Y_b?LfHL3 z?&+fim5-wse~HD{QKdtss?y3EYT?H^T$K6{b#4w0=$XbDuyuL_foH{O#pbuaVw5YYz%|c-7|u@KcFwM zkdFLC*Dw*H0ur~abn5l1F7zd~pJ)Z`JEu}m6ChM@o$gg(SGBdvgwBzlsaB7}HGxqjY z)L!law*V%Ce_hEL;D3x-{yU!<9XDQe<+J`Z|4)GeZzjCm0W#jt=U)**!&|0Qs2p~0 z!wWe*@962qfOK#x`YG7G9S}~@hVkB{Vq=mH@ZQ##Ten{%4C?&2 z*g~Qh9dA*!K7;GFBE(iCPUEd0M_?K{-UZ&jt=_cKpL>&aVC83au-By5mUg_qo@i6^ z^2f&eBP(}d^llf1$9v6=;R0%OJY$y5dVi5roGhil8z-+|Nygi$d5<6(-t~9(yo2$^ z@q34pwzs~upKk|vZ(9%=W*35o7P)C84uI<|TX)YCa09%z+rsVt;@&x~*JTMJ@^t6knTQUo{6gD|K5Ayrj`!J6 z3nA7{?A==&E|r+{{v+e}|HV}5I2~P`3TAKpng7QCOEPGX)G0h@UVlg#*@HH3P?tjU zAh{dwg2|AEg+a68?VZj&=pJMsy2-V}jGs7(#O?R1bY1ueeTkhR_;1tiroRJHvW{7d{07}C zgZ5X_z6bfREp)waK6ZnI)Bnof zUnzuEfC_TAyNz|xzf_R&Dt#KKe(@7Mkhr~fAH6b5N5{KhZg~5?Q?hio#4bj36k_C; zz9aC!y2G?DvF5%dlhM1ex7Y=bo?ow;G|2FHXPi7qm5z%~q6`;x&xv!~( zjJIn?qXZh>%Z)#Z!FUS|FC*bSWSAFw1>ikcQu^wx8y<>gZZgRNc%S_7uxCEN``X61 zlp6qVQ$kI)%@_fiNq*zACKlbjLz~an$UYJvP9kx(>|>6d`_S>;Ab;#MuOt24-U>l< zVCDDnahvXV4ejn79<0?DbRYW$DK3MLNhWlR;qk`xQl}$hCEm&Luj?(U6nJxNn7Bp8 zo2UESLNvUczpF^Vc<=k9MZ)_`9{<;TfcKl}ex6uQJXAE_DDn`%yVehig!_M=P{p)! z0B?&8I3AZF0u(0n_LOWCI^N-|Ck@u!5hU(M;#H`{4=feQr zVQyy(`Nj#*8~q#YlmFu0PjxnXe!L?@>_Xzoo-eHm-j9y=*3UtF-;L<6|0nCf%J1`A z#n`D<+TDA>g=4aZuTs(fYuqN}i{cpGy`vUhr%H#c{^@duKkxrBK=Th$1Qnzw=RmrHFBfNMyOvj-kZkbL%b>4I43UQOz5 zxc`?RRO}iC9+c4+Egv}&4*C1_?l(-_je4HHd1LfQ==^y^A0+OPX?y$QI2Y7-NB1?E zL4M+Nx5Qc_I<{ftXK-e^WA-iWORU&y!kf1iEvP@2zag~WHhF8p_V(YuX4JpYdhvxC z9m4|byVw5J|7%g;&3ixDjg0sFLvwOyc;{3UeunW5E+#HC1_yACcz z+7}&f!8*3w6K)c8hj$aALl`5!S4lcU5v4-dnEnGxx7@D-O)8Htf1k~99==4bQijKS zO^tvEH9DTj6=YOIkt)dL6nHQ2(fPZAd@y!L77g#r2R~+DyoK3rlJGubHonms;N5@1 zK@i%7hft4FQPlV>ku6>82Pyjsn4F7q}{!=f1YAvIP^>9XjZ=uI^IKgH>;5; zUg8WAH{N7m6ylDKH~;2G?+z`OraQbpB02;y@>8_lPkiqsijC<%+?u=?zRhxk`|d>sb;Kfk_?4UD(F?f&wg0PocgNBJt^!yux+TXg19 z^t-oZBEBz#GWdwMk+}D32Qu`<(eK_`3HmH@H>AI_H?odR82QaeY%Uf#Lc4n>1s8t2 zNX6`}C4nCnj5^ygynDwRzobgXoW0NG{y*RU|HBOF^q0Vc3@AKEq*YFayu{u-C#a0( zLAtqWBk&AT6G0c!43ZV!gd4?x2Pp?%57@L83`l>)w%vv|7V4TFmW8+2)#edeF9HvG zx?{V3oMSk&dG(a};2gRKeRe!0T|G2jvk8eyg_e$fnMC)XDZYK#j)&=Q#Ljy}$1FyE zWjYVnHH6UaK{b2&Myy$>IR6ilTk2Ha$M6jjE?u{rJi|IwKpNn$&&@&5XHrD{HIYbBkUEY)e*@R(4gW5?e2uTDjh`hPtN zyoJ2Z{ypAeGi$j58s4&ZU)aNVuevBfn*Z0mgY_efcT_^a>DDcHXpQ!wT_a%kHnqj> z7ks@XGmWsf7U1pl{qvKP3&No}wpWfn3(@i3A*K~n^@*7{gT$3~eNvaWf{wR|_WF3Q zQ2LwR>Wt`sF!IaJi5|Ouh<5k3xs_jf&;t8{H0~XtX*zBj!{dz`3ZqI#$A<*RclSvB zzb*ydg6cYZ$i>N##Rr$7;k~cyDQSA^hg;&L>8*9LiB$^$-gd!7r<|Sfkj2g2LjNCo zXC6*fyEp!|4BNc7LWayF6q1z0UXq~<*%T?t5E6=zVN)SwiVUd`4N6HW(M+O2C7Dub zph8Gep+V`l)_(SVe*2v3UC-Y8{pW1&_4H4Dy6$s5_gA0uUHA7MOHsXT%mZHvpn98M zHFRu6^=>8az7r!DjXa5~i)uWDulKjx)7Q4&B-FIh+eLOi4!d87ueYN1(aj?IoOeL_ zD?JWnCjFDqiBt`L#J=7k1xV`F9Oet8Ty8PPb3av0dA$uc$Fda1Te+8lA9HDX>oe#* zeTmC`ptqc=<19SAO~>9m$Fg^D)jZntR(W0atC^_YK_RS!z3s4bB;S^gMvM!ySHxH2>+PXgdtO+dzh*JL-Qnf|qlt_7dW&y8ztR4v zB*zU-Hqhgk!K8mgrM;@Tvg{8|?q0gGHzJ9J>n-GqY~1ZzFS9%f;M9fzI<_pu@w!ub z&Oh(}aq7R~zxNBR|H%wFNKQKLUsvn~4hYS|%Rw>cUq@nZke(3UN_&GeDj@b6wn6&4 z=E=QlZ77IO&k@7TXbvhrvDOv4|Np7#j%sr>2VI!7dQyKZ8fi((xc1cye~SH{-G!yQ zX2IlUdb_ii(tkW7<4>`lK6uGn;f83M@{|uzd4GfIC5`pUGM;Xg9O#vm_hHE`x@4OPi)}pSK4@bkE+?f!1NwW z{S!z#Vi)&o*$!0i*Q?#%`>&uND~~Vgs6zEVFmjX|yFu#YZ`m#vRPVd1>N{d{qY=N0 zY2Q2y@b&i0&^P~h?5pu+db_I4YT@5?@%0vnv8}nP!Od}cZ>Gn=%cOrR2jlgKlI(wC zH#Dm5@>OJB|DXG^^y!hyBU4^)@wv-cibH3u<8JO$TK#XtptsD1H>yBy#emaVczS0i zD_dZ*w@%wGZ^QIIh%r?;xUDimNlNWbml{)pZG-~W~? z*E1&?v8!3HuDcLl@70~-l!G(7jaSm!MR+F^T+zYT`>RR&%DgR~IPL{0PkJ10ne?yr z+x5?(9_(jtckith@-LYeNHK!7btUTtr@Y=!@?)0bFni!xsD6T$y_YcPEv<0#U&mYY z^|#H%)4MmLvBJn;K)K<@cR=ffQic`Zn{u@s!uQ>DMEc;>c*;5~~qO)7y|iZz-ke z${>3uhp(K2r}rJ2jbWN#>b8kTezQB2hiJ9L%Fw3 zY{aks&khk@I|TM~-2MMb^f+pm^w0Lp!8^*=*w=g0>~h=G5*A)>-Sj$0(ad4W>kU18 z!CD-9Uwqd8r~d!%7oV*304L9pk$RZ+i8W==TWL@70igE`rPc*_dcSLM--?YObDSN5 zu>#3_{nDIssNNNOqBiBDTkL){TwVMYt^Yr^r?g;tC-HhmV|u??({qPFibiH@>T>0u z#n*e`%apC>`$Wm=^mZ>bXTHAmHw&al(5s;NyA(N2Zv%Q9WG4M*OPy`SV~Ukygr|AWp; z{o(!_z4NVW_qptuM&3qmCwgo}x8~pIExN0&pI26i6h&H^Mcd1ieZ%BR>OL3GHTILTI(z3S+gWd{?Ux+~Oj}t-j@$^2zqx84| z)jNd`J*9$X@A-*0M<1ek7k9@r&akH-hVS|K}%ZNc=`7yM;?8P)p>Z};LiD=A3DrbVk~quE=^#GnMb|37fRn>r8G8-7Tb zyB5vfcaHL3?f;wITj9K3VyCwAlR>+Y-n+eGf0MnT&`9$mU6LH9cN9I2$&kPA-%!@4 z`1)<^>s`L>rEu|n7V7_;B-@>m!&6>wXy0Mh;t9CU0nkAR&)8ko^c+k>=|`qKP1nu9Kd&6B^EfxbanTo_h}-XNX5 zQ~VWngVce|Kh9i4b5OL^^3xOVsfeVHWv0t6{3~{XNioKa0M-Y?#-JiE#So-%grbp%eQ<(904%~LnSg8LamS`5Z3r_tJq{V~= zD{)j_Tk9}CiDcUys^G2_WqwLbim9X)!WJWO;%np73s^)8KW5D>wVzO@0q>A zW5&JocJlefS!|C^j9 z2UcZFdA*^N1HV~`BmT5hv;g{o6goIDXV80=#PMOE_w&0x26%cuy)kZv>0Q2~gQj=+ z^{-l|QN5MNlujjuQxLm8jof)?fs~Q`%^TaCC@1SNV20|Agy;91Eu|t>+R+gyCir^m zw(fHc$^T=#g5GYq?ZTl;TKIYonfM%XcuwRvy^ZK`3^M5-SK&JEo>lDYtqQC6?q{L? z&sr849iub#cW;^0FJLJSjYnaHm;ZX4$c#a6l{X^#KyTs~y+wF>KYUw$7h8Kf_O*?6 zyyf;Se)A$Md)EdeulA)N4p;xY&P3PV)L)I%Vbfcshqazz(_3MQ+ekslQOKL|@fu%B2SmI(%YZ@2t$) zf{08O>i@*OM}mHZPyPBoKb^HWUhlcC_D}u)pQRdSGWvXtNT|H z@N&?E|Bn&u6Dw<#Nqd7NG?jP!7n+0O4c%`TqXkmnZpSPFTK~6(-g5XO^XX=n*u&}Z zyiLgOnoDslC#gvL-Yuh7jqpFQ_4lU7Mi+jr2JOOE+iAVf!2iS=#Yc`^oDY*Z?T37g z9)~fL{C=*FG$_FVb=ts zpV-A|MxWN9dN&idI<=t>q$d_%sVf%6*E>~(n5Q z|IeC1@3|{h3j)0lzWvUPr}y$C=bf0|QoPq_@Bcv?E?WUUe6}o#vyb6`~#Z zdQ1K6xIUcK!Et(v(&JEK(!Yi@bFZip_Oo}L{+e~YtgQcg7KJG<-ZS;Hcd`{rah%iK zLVW($`o9%}-g5*uWdgkye5vNb)BE@5K_g7>2g+w@^}m*R=E0Y!-V3>dEOum4kc4~d zD%w%Kvx4^!u?x~%w?F^Ljq1JU&di5voTy0FmO{RHf1~%xW8I;ZPwS0AJG0>3MMh8X z^$yw^67IgXjpJr-_tWF>V$wg$nR#J{N7&c<{0)OtmCwxA{|ltPnW_C6nDTmi7NxNi z$4B$@;Tc)9!O02+y)_0qZGhfsgd!ME?+ZS{V_5ya=0yT+?d`x>*(di=y%UXxye{si zAn}_Vo2pU0t=|zkXxCdL`@MOB*8k6o+q8adr6SAZr55{f;}1?AHXl6@xun$?w3DsY zTqyPlU+-R@jMhc>-*BAXBlI}BnDp_P+i?Ug$|Fesi*&h2pQ2*y{ zV=az^!}i+$)c>4TivG|2LF<19h8(ou@GDD@gAT-43FGCU_r>uaupIPpjR!3UB~FH` zudUEC>0aVzG8sidVj~PfwSFZahuy4oc+pQRsZ&Bj3;o0<{g@58-i|~@(r&E(uo`~^ znJ=01Qs1b*`ZK-VM4$mF)(Afbsp^W^JSzFdaU;kydK|Nu^sgydv8zam{ZDL7&GwP; z-^^E#VvaAn(2?&dM;pt7{JEwq+AT`|< z(MFKH{+;%AsNSL_%d@<8P>}DY9-Fl$6Oi}0KhAQadN*7DJZ6UK%~i1WsY-Grva?mq zc##yo-m?BebVSSWT|OEvRI=t}Tpw<6vGu%~|p?de3&936vML~}BUfoB95)t>atuwh$y-#Hy|LKbAtzghup5_*b z3z?cy8YT*bOebGPV5-;p7-a%1kl@K(*=G! zz26jk*pKPGc(W{R_V(M;qO*Fa-r9C)0w2-sEyS3%rrF$y$mdYqa0u0V>$?@kVW{4R zXXd4q8%HABVkGL?AK>d<{jp$cm(!2xV0t@e%b?|><@kCZ2+H^rdYzx+^sc1Gaga&> z_!o94UvOk!Z|F{agw7Y{^?zvGTg&>ssbBvqS5I5cN*wj(DYv#4(6aYR2EBFOD*kJF zYrph9K0LkU1dX0!dJD$SqpiKQyM5iLfa?8aL7}MbZVJ+Ut*>S!ArT?A5^E;WwKpR_ zYUDmt?+0bu&CCoVk*jq{kkvhWy-Q;obw3q-uLkX|+sAWTpTXDL{Xy8$F@Da|`zSpQ z4<`Nlky?}{SirvC!7KHKEm>LrPrLAW^TgY!pS?BDvKGg>hj&!}ssI1ydYjY!7X8Go zVaP#-3BTupPwbXKlj(Rl==!L_vPWnRx^(ly4(trlj6Dxd?m}}=QsrCUURMedIwBj=!V8yh{zg z{;$kDld|TCFvopjkJ00}#H4@qAuI2bH?p6D&U=MX(m%2=f^7YDpq%o4>hD21@|(3d z>K~cYN03eodM~Ejhy!{@nh8zA(_4yrTmaKscIzM7C)TCg+As>$J8S1EZcp?DsjwWM zbv>xw{1GYcSb@|$ZLca;AXR<%UiD%=6}hss+{*MWzTOm%km>oRW7VKtjGAP9)p>lq z6SD%uWomgiPVW`;IQB5ZFsy=;{`T9T9n&lQ3|9{|s^tEi3;vfp_ z6NxIJjUXKv^fu5c%>a7q@pO^!^oDm)A7UfOyOiIw0?FOTtadx9x0;5Yc?$Y^>qzp` z&@ZUoOEAnxK#(HA{Tcq5B6xb6y`E-_>202Ofwnl|qZ3`~jq06Z z+8UG-LP3NrLzm4!_12Ve55{(H4Nk@+Ek^a0=c%K7zY~ev)Eyz@IpOPl>x%xvkHOEY zYw7KFsi#~($oP5(AGsJ9^px}N|2sjCBZNu+Y$YEZJ^7k_y~`!8ddLP_|GzSA zfc8Mz*=_MnT4)X${>YQ9mQF#;R8*W~coUK9QQoCkfuvp3xR`?Gpxhs4{y4WqAvaRI z1Jt(RpFs-M4!!7?*;9R;-fsK13WWte_-ByTQ2o^d#6~&p6YE8f!<9+@`ZCU!)djPk zgA52N8)FTbk07CL!d2rpu2X&l390e36o*5F@CLuX3M3Z>y%EO-BcONV9xh2dy&vsG zu3>s}lTXo(*j17<#|=@v3wu63E{vxjyXI1ODCi2(GDoEVOz&M@b4wgiy*K<6d6<17 z3h~|kYNMekzTWcEXZdn@e^i5Z)vMpUl3j?eH??k7&6q#uO|j3Q$FYM+{|?>xWLK`w z{uaAYs+E7H`$MJ$lJbqb^4AGZr@Y=d9r-N9(Y#yRI1By6qS<>LgWhCCp@l&27lkbn zczV0pmFZ$5$Wm$sZ3KDoc}$r#s`rhGy*bH|6r}8(M4KU;h_uzd(#G@-J1t6fLG>0` zpjL988ijCCGnl75g*L&#JkhA->X&g7b^`0KbM<)G? zu8#3*_GLeN{}DJNHmb!!_RjasAAH(9<@JV6Ze}Tt!37eOqSLejX)S}^M%^y|TAb)5 z=8NO${epL4C8qb;rNy-AtYMzV=lsPmK?~o!G+{LlKkshZ8f(#BK~ah;y9Yf%G`` zG3noP%DWZj^VrYcHzPBT-M3<%z4JSyb_O1CnDPbE5T6W7aoiR%tQh($dpk4ez2s6w zH^|;n^HXp3vv-Yu>r=hC%r_@4sA_yIB-l3P*WLow zKVm5kH8Im)U3=pZ5w!B?^?TARViMX*Wp6MD?Gh?Lj&dezOvNgLKbkwSfY@L?rQ2n=Ez)Nxkty`#bau zl33#vJ<*3$BsF%PVwfj>4pOTZ4?pHOot!{#*Q(tg_m+a6gUnWGSn>99-VM^T>2WM$ z(m$_-b!V#+M41*k|EW(|ThSH;)c!68DoHddHyPjA;o;rY@s4PS40w>L;`>&%+} z{OA8~vlBfIIVSzflkE_(GGqS}s}PvJyy6*iy?@qB==z3?JXB%zi#ZuUqP}+yx(di%0q6ZxBIZ#YiUax z{t8k@?Q+x4Ibs~A_X>I(Pnh&?;JXt1A(;K_&1-r0PGrwLrddBm{gmbF)|@G?cZ~TB zmf{GYZmN?0>-Clm40@Zsy5I`*&JW9$!P9$#*e`obZ~KG&wC629ZK>5$LiOg?`c)>2 z9&hPVarRP1_3op1Ct`;aCG!Qt6i~fI{Cr7A45-LUgS-P98}aqlPUhadX3@Cub9y_O zmiZ|Pm+|#}?I@9PxSW^c^wy`x@rp_R&X(=Zi#pG~-hUdxLyqS%*BhGuG4b{Ki7Br) zG%#%sD{+W>9%=BnNt@nU&!G3xOCvcz@853z(s+9NA(e+Pz312wY0q0KJunhbM)fWz z3cPkTnS!*`9PA%N_y0Q&yfDVr|23EJH!VQ*b`3w_GonL9{J!s&h^WWcyCUZK`o49o z#=i7+H+!=W{Wy!Sx4KeY(5wN@JOAH8k3*hG|7xX&rmr1gU+>+{&Kk2x%=M1xtk9ZW z;5_B0x1g48mf{$Tl9HH}_fP%*-yWQ^^xsG8e;3hn<)HLl(LU^n z9cO4p05*ag_*}YLAI(AP^6xBQD*A%dbDJ(*^aknjstyuXAYJnhx8p){(82MzE3Y)8 zkYAqbn~vVbFOaHM{LZd@BTxQ8Z+9ekn^j;Heu1<^i=d*ds?Bkq*h};{7BlIe_>FqL z1!?T(ppBA879Z_qVT;{*4UrW!yi@-Zdu|R(ao9jlHC+zUKC#{mdRwp1ma7A+M)OVOFVH)#`Hd&_fCESt^X_R zpLcBJib5(#M_qqw;&&ra|(c85>Sn}<23clWBHa}CXe$U}Jy;soV_{yYz z<#`WevMB7=|CDyZf|4ZBwfT$LUR_ z$MKp;|0WWzo~zo;e)c{-T3KNFk@*TzOg--`gUfMKUhkMVL6+huinu>vewmiNH!|qG zyaS=V-ilpL-1#_J5l`qE3TA1{2By4ZrgS+hOU8%4bDi>m|cTV_|!;#SA4)BCl&`e97(S1LSgt-WbyZmU`~K}D2u420ij<7e-lBkwvq z6=slU(%Xd^rRgQ@#?RjAFXfM>9+<^(diT=f*vq7U4Vy-j9|*HQIEk<_c=oQAg|oM( zNKd2;w@>-?f9U*7*5bG!JN=*g|5>WO|ND*5`rn@+2RUrm5d=n%cUI2O#LGb@B|KW# z9Au)W3vG%$XSn3zQtT7EyQE?Ib_z1Q_-9@@`oxar$zeqrbKjQw3y zWMAB1R$4fI4iY`p8`St!j=Y!N?%d*|AA^1Hb5PFB7WE%Xv^XvY5$SPcG3lS~4vY8| z0qlQb&u+TEQ1Uqo_5Ze_hk9B62hRVe9%3nu+aHp;7Ua`Dv3?AC+iOnHp4i1kki(;I z)baF=jU0W2ePT~@OVAcb4Wf)RO;Ej8iX>k=j@JLAp5BDDsNO@}{o^)FMznMXAyC0`( zLH4elcWySG-rt_y*n{cKv+4q^K-##aa3LAhyY{@9;&zf=RrQKYKyJ^ zkIc#5DUa%X>gcxJl{r*o-svqv4>j@iZW0N9R`gYotV3_tH*&1vu_V6U1s>~uW~OqU z-XM;ACjC3Trqa?ihkd;T?%VOrV&VP2*BVyK(jGQXdA*l+G>yJ%u%}Sp?%K+6oy68{cH1u*}m(t@u#?iI6 z0<)9(*zTt1Iq4kfA?s zarAaSh!p|Wn)o^BWlBcA!B$0%8$qhm6`jFX!QO$R^n))}S;Rx0Zgyz*2yPVd+BI4qg;Z;8icaY&r~`u{|2hDC=8^ZH-# z^S2TI`%}OEH~5&wQXD^Gz6om|q}Bgh8T57>%^m@Ie?DEJg{OD4`8Rb;?`c;z(Qa=s z=hM`~UT@W0A-i?AKLycN@P5*ajv&8ez1@N7{Y@^aZ!4;IvlrrV5#9e^?qnQg`8WIj zTWzzn8dN07XXx#YUP6Y;{$~IGTN@^xP1}5|L@YZ?2PZ|;=~)C`$?GI#e+#H0jS=G%xs4e zeW{4^@Y*Xmzwz}xAzC|L)G(9mNN+dqj?l5_0ern9p6pRpmgl_9iO1=2gfZ!#ah3j~ zkgM$Ltr-^}^_`Xb|2>^wB%W9`^~c`7tXYf0H|**^_y4m}d~-k>wEo}Dkb^eZ70QAf zlzo(EAzlu8_rS~ryC8icd+Sat2Z^bRBs@Y#kU85{Y+Q-n|1YaJV7?t39Ckrkl4yr~q;3>)zEAYT;fMGIlHc|Dm&Wf78-sSnPKCxNZs6DdqnkhXbqP;a zbHGpZ-@34l9>)li{@r~LckAZ=;uAaTmC^XIYUU$I$kA!nx6R{IJ_p5Yq_PwTS?RM? zmscz{#U9F__j;@TV?gh(7e^Q1=^dgbHICgNRkNpwcK?6)=Yg z%&50T@BdS6wHUy*w_H(N6t)4?d)gP3^**zs5W=aj4$E8kdQ0?(U*1tQVa!8s7q>g7 zSfm19?`1#dA{T^(IIch<(&I2;(!ZR0O_GXL?0;gH?$QVn6k>kFE=9!R4BvCFDL;a| zAf3cg9G#Ed2dP3ynBE}_db|91)duvw{-Q_^Pw(APEjuy2yR84ZAYJ0-k=qTZ-UaGM z&&Rt{kd0c?s!yONNSDhQYGHc+7=Nefi|U>6_M3s;^eE)^e)-UpGx&N>b5HDeagm#R zi{7sE`kGyL^6~Zl?XYRh&Ly08{+~#XV}eQlEKPq}ssArdkV-G`Gk8D5!Vc2jH<}jj z2~%Egs4r(8OK~{WY&QJs{l8!az1N+~)dPBaKifPXPj719ehAY$bnh$L{hD_v>;= zU5eu)^U>QWJ)Un~brfIks@dAE9&&S^xjHI*?-l9YInV za*&sw$X@IdD}-*4CcScl@Ny8p+`{=-{U4j!NPGV;x+ro^4f=^ag^Y+=FQFjwrsaLh z|CxaFt=jejdtzsm+lL`j^b`ADUE*Z`DGJd`UD@1l3jY&3z0o7TX2odr0(!fYKaFOi z2k}3##>%rE9e&77=Cq%)EIkf{N&oaFZyJ2wzramf~>LXgG4Yl=g{@WYBvfv1tt$LC#rt+YnE0ipOLaruQ-HUfT4Q&&(T#>rlN- z^he5$FQXuQwqI6#NA>QxwfPICx2ySWp=GGv{Kh@wN54{$;XCI%ZPM`dPG2ovb2ss8 zHE1{K?bvlY3SaLcjmo9gBAlo90eT$AnDp;*!1=4L2iVu!Wp9(w+c(TdkeW{KmBp@G z8nCSshy4#m`cJSF2jNXhmre#v?+6CHJqFXa0=?fRWG=?jJKSEn4%2({m}Cq#d;4@E zIs~i#ZR&QCBWx+i6^U7L-st;(Pxu7~F};W73Uo2O?dI^_9r#E^8W!K*z9kV~Z@q%d z)Z;FnszJN;?Grk;w*QUZ@xjk~4oq^~>n-N=IF2*vpFs5ZR+(1z^>(lxGrG8gg%PC8 zu4Tz9b*8-Dkjz%r;-D1FpYvD!AI_k+dj%;E=&d8;V}Pf(>Df)gJnw>;pzQw!s9xYy;a}+*oEnh zoZX=E7}a}x3~4>Nj)JIj8;TRq=PfE9t1ZR!R=)OL(gxL=SEp*=Ssi+MYxQuLv!y_ zXL@@pWV&Rn<2=tPuQ$XS$66e`dO^k>693%)&tZeh|FJu0{lAML2l*MfJ775otN-Vd z90+(hNXwmMj_n|wb?>kD|AeI7nxZf2nHUPr^P3S%K~9^PsF)2TAdiZPL&9hd3fYld zdJVl|htK=?^sBogk>=4!o(*F7bCB=&lue!$jT^Vp+leTXs4+j*;r@RudA*6y${7TX zn}d8ok0X&u|6~#hjiYNxxbgju|90qKc4q09etN>Z{*O`b-ug~mbn1^F?H;ofN8+c& z-&2m#3Z$J3dT)ljo&mirF39uZ>D`mCaW|&7-NFId{(t0Wte`Eb_xvE2b;m;~Nbz3o z*xU~Z2){v^l@O};i5b7;+EKl4RvUh*TM>z56Yuu?db%0+pVM-BdF$=&e&hZ0c3)pr zMwH*c*V{v(#s8$$caHnS8qni#WzxT{9Icu#arQs46;kfU1z0#idL*dN$R>_D_4U5_ zkfk_&5?|f#+DFrS2ZP?5-kd!O^d`zoaO3H{{26o)(_7DOl6HFQ;sWuTLa5$#siR&Y z=;^Kb6VK`bh7%Aav&LNP^_Jluir&Mh-gA`3&xb2TA`5kkn<~rk^>!O5ds|ytYivMo zce2UQ(I*RE@5_Q-OP{W6<~Y6O>2Z`W>EE16>Xim7_Vqq;SWkXY77O+N#&yp+-tC_H zdMn$o7ROCe$o#+R|7ZrieU4_+7D%zd37k^Pg{Sw1L0(a8{a-FagZ8}TOs^!Fv*-rt z@4t;!$2d?B9hWfs@1GNp=hVy!=!;15oUqV~?@ zz4xwqFTGuNBqiNQ9e;y#V_jSG2dl3fSO1@<$I-&1f7ir9FNptUe{eE0oxlB7I}3*s z1)Ef|G>MDx202sa?}uNp6i1!d&PDxyU2hS^pttuyULlaZ&EM{W@$}Zc+n0msE&h8s z?RiW46BjluMD=ce;zFvkpdilG)+w3e2}qXa^I`0Ii-#kpD6>$#TcmZlq?b~WgAbO6Y8u!PMU*4N_eO`;msUJB*nxV1MSdK}Z3^e;O(xn<8+_Oo~1 zpbF9|%KUI*{oeYHqUm8%UT?P(Pg#oNlju8dC^qMx`hP0qtpt}i9)=tgq&d3}OM$PksgDgAk{PYIcUSL?(1bu)5-7Y?d~S)-0#W3&q2D2kXsjAlsT^c zccaHKk4gWkEe?cGgxSwQ6s7i?8#AkPwE(tqgw@C3j?f$P6;tUfzMPxAB1HJbzcrSpbcW8a@7EEuFQ6%jI>G8AN8%>B=UVhj<}>3zTWC*a;B|YCP@B4Z})oD?!{_0_ zDVcB^L*y}fyOE4vC6mAL^{#pO>XC9KiQ}@jAU%%jO#0XU!*!|qC-(IwAMrnFA%LAIP4DrSYKG@fy*Hd$n=x-51yPMZ8x@EaNIFu7Ziu0J+n(*! zutoL0yxk0rJxE2?6vU-8YU6)mRd&t_FxQtQyU^R|IK0b0ITL@29c1qtSd+wgSL~?L z<6zc5elj`yum$^i531iPRJ+am{6BQV;>0HDol}1Vxlj5eD{&YEm0j~cO{@R;81xRg zr4tFVcgyHg5}w{Yx4i5yy~U8%G`$tl+VUGvy-Q_J_9PoqkbSytehKLG)@l3JsOhNQ za#e0SJyE@nHFqclgi(>B-`6y}7sA&&rb#&Zg0Bp@nBLBEeD0r5-|(|{z6`uZM##7wxEj> z$yNNi(@?$h#;tQAP`&$7pFU{bL`81A>M^FS9O%yh`w-{7|CdOQV>Xli30}(_7Vl-h{;xZGzWx&n^?!=hqT_B{Kc@WH`-t!o zmg2a5>tzWNpMwaZ1#mxiGejCCy(e{&9+7HE7fB~che&CpU8G==H_4e~O(K(YNvb4C zk|6OnafJAe*g?Ecyg@uiJVxA4Od>`Rw-P;wtBICGL!uT@ktjwai2M*466q3Y6}cmF zMdXY~p-84kyhyl+pU8Rf0VzE{~7-S{u}(|{73k+_~ZG* z_W-_6S@hlgxiEmgj0k(LKqpf`Zbk#bR}8<3g0 zRyouK$n@0(SLijMrI$u>pjUuQqKkh+F99Kr4MxxlKx9Rsg-|CTqi&bE&~rdbE>(0x z&j1-F{GJOv1+F`p|7a$`x_uP(2`}J;?{4 zIzWm}9`kA4WOC(8rDG7fMhnjQH5>*l2*9+5V{UX zN@=<>bPdpqMrB3lDjq5SSTA%|DKdgC=1a0+4}xaCZOIQ7F1{-pq@*yr=Sc# z@8Z-hL+OCtI@zW}djY*Me7+A#1JpH9b{R?q^tuM!Ta*Im)d}u;sJGR4mX8%1A3whM?rCb+Ii>5La~5aUrl&J zF~Zyg7|q^xE!U*db^&M(3`*Du;PHyLlpO$?NS@Ns02)WPnMDD3c;p!u6~Kd|%kM=3 zxbNZ@8Udg|uG={rz}*ivN?`!*+_(L@9l-5f%}^+Sdbj$v5CC^ z25|KIarHF-jx@h3b^=he*Fek>K%xKT!>a)twvKRF1t9+7%+XFashPsmi z;NbRGMs@%W=tKQ00pto-C)onXc@$}310cKL*d1#CS)rk;tN>&#b5vRZV4rXYc{zae zmm|KG0QR10t+xP>mS!Al4j?r+^|Bd&6p2B?G5|@vOKeR6?5VmjuoOUIyhyVNfCLwh zB?y3cgR)UFfVgk_tc(G~-nP>;0uYmZB54VLU7M3X8UolkzqM;IfE`ORpBn&(x^H-5 z5ddo8y8{aWM1};Z=>v!`8m?UcAbgsfpB{kiz0aEF0|-6-tw$F?$d3E&^8f^|ioB@< zV4KvI+1daC`zt-P0BpVBS2GvDmdLbga{vTb4sXx|;ICP?Mgzd+v7J}d0r*~9H#8f- zrd>-vssZp>?FY>Q;H@vTT@`?rU_zh@0MCw#Ka>G@6u2x>0^q(~%2N@5+mgBo1ppi5 z;1PKM>xl#fIRGws84|Jp)}2d{p9x^Css2(K0M6ofe@g>!dZk@01;Fuo>j6mstG7?y zm;qqbvi&n8065H^KPV1>(mT^w41nDk@rmgGRvwm}I}LzsfL^O80GmZ07LWi~OW$!I z0$5RZYlaAb<%Mx?g#lP@3)(LPz(U1;QV@XI*!6A!0LyNNzvTyDnwwLGQI8c5ej zWu!vVK2jVhl;nd}|5hX;k~T?^G@Zml94Gb@JBf|N8sd4h_Rk?E5+jIyL|5WU0f_$# ze-D2Le*^zD{xbeT{(by${Gt3l{LcJV{6_rR{EGb3`FZ%p`TF@f`5O6Z_|Eek z2=h+zj_|(aZRfqqdxf`@w}3aDH-87Yo@YD{cy92N z^Bm#H;)&-88JSq>Rp35Cp#q z4hp^$Y!a*$tPm^~%oR)$qzVS0^A!|9Q^5s-YJyUNf&#w;h6TC>S_N(kTta6n@&wWZ zb_xUucnYi*un;g1&=imrAQDZ8^NFg&8AN`OpXkiXYmsJ=I+03|lOhL2QbeLfwu-om zIEa{`^DgQlG9tpllfomyZ-v{1?+RZLE)_076`=p3k4Ef8t`}~H!RW_c*g2*i2BRN) zp=IZ}VKDl!7x;CI2!qj&J^$n7`(ZHpvFE!w#~ucwAA5pJ*#Q`ge(ZToR8?Ux`myH` zRtkkps~^|GvH7_qp#a=d04X+3Ed^e;H zy8?RJow*5i0o2jB?-RTZ(34$a8{oBo+8x9m!Ono%7RklHYXG&3DcQnKfSPN#p1_WP z9;YuhhgSn?@{03-ce#9dQTLY>ecvk^i0ji5i`U$T9bjy5D0A3ELmVeVO*b-39i)SBU z3qaK;?rOs3fNq4nw1dq6U3cGS3NHh6O)py>HU)I0zxoEe6wu|W^g7rC(4{>QMKA)W zYSm{um<*^=HBk^Y22?TrBNa9Rbm88!W_Ssp^T}3DupyvxUQTP_#emA^lk;E$KxM!B zXTpmBow*kq3@-#!da^7D)(3PtVrM$M0MMzq7UHlTpb`Pf2s|IqNm-xIur8qD(#nhQ zJV3`o#Oh%kK*x;v4#L`ij!JsHfwce?y{nl6&jnO?F}oU`1L$z1-yT>KP=QTqI;;UG zUrE;lRtI!wbhQsW`(HHg;|^F2(1AT(a_}rbxo#R|uqvSaNvBA#3ZNWr;d`($psWVF zjj$4+%>DB1up*#+-t+ol1wa`~ofTnuK=`T!C?bJt z0W1V4+(FX;76gRtse=XRWWTmCt^#fV4?D?PL;s2aw~Eee>bl zfL6Ve*#XxBayU~A!F7P_drl6)w*XPR<~YE$fb66m$HF%O*}g4Fg=+xW)QN|~)qt#b z{)mTf0J3uS?}D!bTA|Z<3BCr%^8Gm@_$nZaU;g&+6+q@$NDO=#keOf4Z}<|RWg5;h za1|g^!NFL#5|GKKb`kg@ASCB}5?ld@?0xDRd;yTL?qyZ@JRl5y0lI17-JU6LA{2}p8! zr#`$7ki&?f;|=Bmgl!Ol34pNu6fiF!>|`^{0|+|^ z3UdR(&dtGGfUsjmFboJgl>tM5{IL7c{s5v~Cp8I(cKgn6K(xzBegUH0?Jxm|cFX!t zK(tG#e*mK0;rksB?aI?{fM_>Fjsv2-)iwr*_O#U~AlgenUjfk`PWb|e_Rhp-K(rU% zM*z_t$o>R~_MY%CAlmb*9|6%`s~iI4uwh3K^Z}5)=7cRYD1vIn3!i{Qlmt!rHuA)y zfBfecr~L%bJxJ&l0ho}gYK^V!Vj~`~2PxP~R|;~~n3UxvR2 z$+LIJUUH5KS(DzbaQtu+oQuB)N#@gwke;gf9Jl}9gB}O7{=Jt?d#Lh;{VjI7(H32? zn;+m_GzWBZf0xnrM=@f`Z?P+NWGxQ;r?a=JZO0x+j}u|g8yms{y_4_!nSrPG)@(Bi zOz)Fo2R37R-%Z(aS{&88L9&6oZZ-vh3pSlyfa+Z(!9PO+)jLbk#8VH|JEBSK(aQ&s zh@J6}&vzGmy(iTSUM-)YOs3G=5x>~Z4_tf^@ofVnr?X8el^eRkm_iL1QI;h?!9fTgX9EwCj z+$m3MHSqPeq>`qo4JwjByU(H1UlT;}^$vS*(fLx`JdV@bf*uF6{_&pBy`6oVeZ5JY z6xThI%=OkZQnT{dIXUI^E;O9QQXGF&0~S0#NXyaeEI{wpnFZo_dY1*k7cjlK zo2>mYy;FngUm>X8zxH2yWTi|&mfY!?*4CeZNE}tq!StR{Ho0srs`s)kN9bZeBoZqy zb~t?k|9VSG=r*q_R~5*h-MMt3Bh}sb*INod?7Mp5n>NSky^`k>@RYwGEoKgDaa^esp0>A)mc0cT^u}flf!+#vfns=iKbO1u z5z|{>g;@Zm_n+#_i*BgiGK!xXMHDDVYVA$w&*=3QWt6mMnBEfQ!?Eh9-n)#<*F<|p zA_*N5@d}^u^&YmHlnm_Ki^@^)@zT#xgV*W1%Fhov~E(k_AVyW{`4{|^*jocudlAc-;LAZ*

`qk&3%TwfI<;#bp; zcdPCD^ zAv0mD98{XZ!VNb_wj=%I5qs?X#^ykfgW}Gmzgm?^gdA8DE5%<$LksE@XW%zT&33n@ zi-S+>&U3pN^=AY_UZmV%Pc`fY>GT=5y=!*yn|ULC!jE6Rea(s8|1VhT=2&%`@n(?O zhz>(4@txO9c$z9ne}j}L9u~u4NJ9mgX_cRNc?0wJ|DkIOY0`0UXeILg-*O7P@9eGJ ziQ*k+EFpx2_k3SJJ{a#I&IvN!(*3GJ;Q;R^)%-%gQi#yr>MhNs0PjnBdHKo!?}Waz z8E$}g|J_91SKJ{GPATX#e-<|0VGAB5bsXb0V@3S7vGV0xgk$5qZmuY?=)E+<_5Trw z4o52SRcftOvCJ00Y#9G1AN}7y3D1u{cNtIpdQ03wt3mr6gUpY2$HFhP=qTI~VD+_% zTtP0Q!234TIECW9EBTE87T!Ik?m{r$GDe)_>1~+`TYWUZJHq901-`xI%%s!gG^ilc25#>5coPgAZ+r74$Qv7Pkqrj>LPWXEP9lB_?8+=-tg!K} z`(o7T5Wsj}Z;2y18mPo4@>2ZcEnfPwx1aBgjYfBo4Y>S45^V!AV1}SYDSIh{&d&W-yjS;kK-JysX6}gJSg%|8 zxF$Byha?Fx`yf=~dep6jT9q))1sBfoiIrHP~yYLe& zI_jV2P42r!#(N0`-ZwkHHlujQaqZ{B!do?WmlTZmW8?W`yydn;Mq~oKKQ4HB#yOG* zWw*VGa{*^>B^K~E!+5{m(Q2pG2(z)w)Ff{My92X%AY`k4dMt^*N!)m6C`02Nu ztu<4^#yfs=!-7OlVTLPC+z}m#RN_ls*KJZ4Pe0x^#X@JH^VAO~y7K;f|9(K8>HGhr z$;n63oNm#DRL0$Vo4a9gIc*3&cez;z7_W$!z1=RS2)O5 z?C4xAI}MN63zl+}XB;9zKJ|HJtzd}_Gfqf^`~L-TXJ^U44N`xJQDb`u#JyiNNMSGb z8Klp=t&x5!@n$@TU!ChvN!&*4Ge{oLru5^_87~KYMRa&liO)GyX-3J6{uyL(u+Eal zHq@8cr9VE;FBPw3`UWYqql+dT2j1wfxwf0U#IB;iyUg7@2*rEQnL`2#Z`r2q?J(ZZ z_h9n*|LD`3`r!uYO6!b@7N{V*M4w)=26(fr)V~7by|TvSi4?%QEF$>(>%tJo>(U;) zm^n7y5&J{l=8AEdc_V&B3hsBes$=6VTe)Xn#{O9hx5P#vI^?Oux8Gt>rb#gUc)z*3 z(&6E4>Psx{%mxLP_s^IfZ``;AZ929ou0Id1*a6vlB?aE4=A8dz@AAHvVpw<^Z3&o! zE67~o8uI@Cz*FK;VtgnFa_WzmdBMI={+4pj}VRQ)O zJs)?}Lkb&jH$?&69wB}+AH?s*E>iI2Y3vHJzj(=tj7^L;z4btJ3{r`2@s9_#M=sM} zL3)*cPam0~KHl1rSCzEyxh>N-NGIhBY0|M|vE=J5Ehz9V`8f)#-21SF!*?*=>b|XRqo;3ev|s~7K6-YDOs@pQyoSkUr%Wlg}XWI^2|9 z3zpdRTl!~jiz7m=Q|96I@1vo2KUc1UXOIt99MSIsGf0gT1xt_V5XjL=I5;TxPEZ{%okHiX^immY($49mH5&+>Wr5Cix;GWa7B1` z(ORk-t8&&-(2n-SOh1G4vXiDs$7TMMh;NQ3;0DQ>0`H1FovbL{Guv2ZW8rOaginQx z_xMFJ-p8GE-8aG&549Z#fhu;( zw|^1E#yhScVfXPP>;=9>i3CF|q4HB+?Cv7@14pu|I4@j?}!26Ms-6<4ro4_a1Sa{pI#ms~8 zJ}8|=#`{9qEKPTSw^u`j#>&G)D1D{+=G?c@kb|pGAAG#!ta_0aD`=3^|blv*`1&6z0c!zZ6Y6&U8qWzo;WONLCbhmk(Pvpm>MgJ0XRI_q!}# zMHp|9-WW38iGH`w?E`qbZ|LH?d5{SGWL;Zc&;ed=C2i7%@t!XgohShCt}sZ+JS!0j z1xLSXaV^5eyY3oq+N#1~(@?}uTlKW;;xuf$uNADk<}>z-;qZQe=qRQVpLg=5sI$-M z$NOHRsSw9C>UgK`_q8^SWn=o{L_c;XO*(1?mt9WTLmqEgQsDjIYj8J;_rjJPl2~~2 zR!+&ncn7ZtAmd$pVNFdOz}r5{d3JUL5fW1WHD(3&|D~Mu1K{zN=sa%c*#PfF>RmD- z;QRla=wj5EKiKFRxhDl5$0QJ;X;EBtT5mK|SD2Fl zUy!y=EP(I;G)Nq0mvMw!hC-eK!%+u%uyfEZQ}z6guajloh~H;(sfol!>>NZ=j_FKa z$zw)U?|<20C!*s%mH2$rqdNpx>CZt)m)=%2?4rKJ;_`~O&pfhX{tD9J3{5%+S;xP( zmXa$-I|{sOmOkZ2mssNUK1D3N`=1$}g7MZq;zP#!Zlg{!TtNnKJ1Z^%c<=ObJKz5? z8alarn?8)U+s(|mRRC}I6&LhY%Z5TW`rF#{?_lGdX*AMk6)|3Bi})`MI9d4crZvc4bP1Oz95<{Rnz86fFbYq_&^|a`(jwO; zQ;ofYR9>f!8+gUSaCj3C9c5JF3)ogMQPfHQ4pN%YsX&`v>f^0-FO_0aJ`?cF%I~ea$Q)e>X&xcq?Hv_!AcS(GT z0C>-_-Z(J72V8IQ-fb(4w`v%t*b9I+Yj;ZhIJn+&xNr9X=^<>qKaW)xztSBl`-=E! zEa+aT^9&nrc7kxttH>#ao8I;zI#{X1SIupb=<_eeTgP$BGN18L|3ErIFTP<7o9}$wmsz}hlTgH)ts6z-YVgbe~-6Z7o1%M@E$IB z8_o^zj;>9R6zGnIa&IY*!FzAdEH)3omlG8peX;c=ODI(NV8L7nvO_xF!w z)rcRMHQ#rN#4b*H=0dDzy~i02Z#hKAJ1X&s1j>Dh`bmHGRzH0!!#hbv&bANe=rXMhH2x<@n}##?FonI(k)?-Lc@ z8z108p{z(2`N1@7yoah=6;FL-BV{9gZ64gALJ`<_FLRQ*`M_I@;qV?nbS$9~-{o|% zz87}%8**;)jR~Jc$kQoADaw<50wYAU!PHdF0s~5r)HiJ)$FoN_;BB zN0~eRMfOg~YT*p|Oud4Pc)a1rGo>`<$9u|;CLNb=h>4xaC1-C33cTw(DjuMCyUh<% z!ovIPj7~k=Ahn&d@rLn^t*ummzuw9t@<-GHyz7YbzG(M>$BC^Hr{U?Xsza&tU4Xas z%^GO!^-!p;_>g(^8f?66JKC4HZ($`pMf~DEYfU&BW8=N&zQPCHVIhXY+Xm6Gi%NU~ zvQoF|*VCW9Zx4pOvk|3^w}tK5(fD&0n7%kU!F`e@9r|(UmUh8pyw_3SU00R*&-7L= zee*mlya(M>$#|a)rw{LDF#<`X7JQs2d~MBF7wqDMtLf2-@dH-x&{vPeE|XqtSg|(|b&hH|~ilZ93ME z;f?>^|M#!j@&Ee21p0p`iX7D1O5A`hv8k0J+E_VA*ZJmydbt0eIvfTsvD1^yKiI(= zq(-NXo#PAwUyuf`-u)dcv8ujB;zwf;zw-GH5gHf&mF zJ2p9+^bqm0s`=8MZibzMNNb&hlg;NdTn=(Tbd*tv@6FV$@YOo>=b-NF>n$q;srUc5 zI~jZVEjf+;>wNuh|Aqc{Xw%_!L>PG>eG3KNFBWzvqIjpPv}t1D{WH*W4vcqE6(I!1 z+dOCUt0_=H=FDV@L19FQ+wb;zJ%IO~hzCdD3bJ#y!+ZF6i`i}e@i}gx(Eg1T{6#a^ zc$;r;4<3IjK?+0so(RotGw8?0d-;9&*jO87hQoU~qGK7A_$o}=?hp0SKVpw9t^T-L zfcpMFZc^j)4~|sk$6H8`CLK!^LeqBMCs&Z0De!(it>%W}{Uhr9d@Q`vb1nwf0laNh zmj%LjA9}pv$7g`|lb{_d=YkugVnr9~+kpN*Wm&&G-2cCiJd<-9;GIw#oH4p86iRw; zsnhlW8}BPT`*PS`36W60+@_WaCl!vbiAb!Uv%*IJ&}3zXKyD5 zb^j89I;vl9an1hdXywLd{J)({|J#2aTk}_%blmo0^Dzn~A8*-2fp>Fj6#0R4_;F(C zu@DU`ypx7+mec~g+0+*9h4J1w$5P}iz}r`=;n_#sJ4a+jrEi>iapK++_-p;^Z%m)PeV-koNyprtF^x^XUvJ$=fp=47 z&NeiAD|%R|W8pp7w67GN-ge$n-VNhjyWj0^yKZ!Io$bK%!p zn@Vc9E(5$xN}t{MY7z?7m>e~VY{AA`{OR-E4aMA~I>hh6@{2A4W!TxfZ%tLTric{7 z;Vp{j_(&zb(_I0}j%=nsd-JlyeA3ONq5scNm|dFTW%%FDw*TvY-^L{}H0iK{)Ghw@ z|Nra1{{JU`An5&`EkTdUT}ldlaFF4T7S4fDu4Ibg$nbz zq)NoEt~o}0_8)GL;!(@kCR(q@a5)Io!Am7RhXkSSs95@!*r#P~XC(JiAF<;KuR5YFCYM}O3 zy6MPV(q_aDT2)Z4@Cv(vd=q^t;{>lh!{NOE(a}yNzUfnZPBInr<87W_cyly_dIkAp zjgh_vV!>Aj!hS4r;ww^HEU#;#O?;yvkjUJncJ=|z_^VZ5_nPKLtS z+b48G-#37_dG8D3_9!A0UOm@k+fX$0U`gZ9T!43}X6Z>)fOqWAO+oc*LZFGIDjp}h zu<>sCW~Keub1rEN@$+C+GE}I<#`{&;+Lgzkgj#+SV1jgI?{l@(; z-kUZ&-7y33CUHtVHV4z&-Ay8^uMS2-CoCRk!QcN&aUNX@KX0+=l*)*8UkIf7?nYMg z0qh2;=B~Kb&cHb&CB$z~jpd<%J9dLq6)m{#G7ID3jq0ElpRQf;y194h$9wt9WVKQr z8a|MA5wF-=@r3E|j&PH&q(w)vwX)&f^W^O9Oo8{ya~5hS-iBMvbg=LqyjDwW0C=mf zeG?Aj-E&q)MF8x*y$gAgC8s_zS`*F_^y7WH zeBQh*OR3l1PTeU{-sh*7zV`m8KS7g@G|j`V5r6Oh|9{f1|F8d{p#S%v$U*O&3gqA% zBn3w7YFD=4uyWAT(3)594w8dXXAqo&k{%>-JO@jxt!0{9RXP!J(>=nn?JIa#ce&g9=jlm%>uX?IDnE!}7C<6WA4`!&x_CQ-uOa4e=ZN;a*32gIz(U-U+|7 zalH=1<)C$l4r=k4d@j(;`bGZ?QmN*GC1>kKR80e#zMua|QS)tG7b%#I}8_J`vhhi_WCvWf`kDRAST8#MhhgcltbH!d_OV@mM zx_^i9@IHa)D5DbJ@J+|$>Ff04ZLHG}DSnH31sQSb+se__ZOmUmx{lGL!&-d4KuZz1 zf^?_A`|S^bpD5lZn$nE1@FsCMJcaT0{c)R&cj7y9aS^HIgBR+|0PlkLLO)g=Cqe=O`iAoX z-goUa_QH5;?EiT_2jJZ-5m@I8&i`k9&f+oHijB9auWh~Lc_X`Z)#$ll4z z#ui%GGv0U$)saFaz7Go|J{kOr{r|R$T#LM4Q-8fhm$Ov5{cAPT*WSt3jbv!i5q+p- z&z{}M5I4vN@9^a~ff0djfmVSh0wn?k0%ru01fm4?3b+fb7g#N@NI+9SUO-rYz(3C4 z$KS?Z&rjkn;?Lnv=0D6I#P7wwnctdUmwzt5I6o)fPrgrloqW&u9`P0PUE)jQi{lI9 z^W}5lv*laPXTYbzC&kChJI(ur_dRb5Zx!!d-aOt+-bC&j+!wf0xQ}p$aC>t*aTB?h za_e&|anIuB=9=Of=6c7~%vH&Co9hZ!23I^+IM;42S1x-lb1ow;H7*%0el8s62xm8E zE9Vo=63zn7Gn`4BQJi}@-8t8DuI60CsmUqNDa=XW80YBYXyd5oAaN9N6aLziPNhd2i(`%m^y?49h-*dMVMvtMFQV~=AGWA|luVYg*p&Thc2!Y;+m z%QnsSh3!3C3tJW2UA8>7OtwU}2sS^q?Q9NgE7?rgG}vU>1ld>#qlAxySA<$ZDd8F+ zn{a|~h!8;VAZ#R95zGkM1Vw@@i*`n z@G1Bs_z=7|-U&~{FU9NQmGHCh+^kcq!>sREn^`MaZ?j%u&0vjZ4QJiW>dI=*YR+oJ zs>UkA%Ktx$0?Up6`T6fpjQ<+7e7q zYZ<|KfMASTOYTVV6O2%6@rk7p1VhwAGxOITA0JRp4q#q^dqt?Rv3xf%I zsAZCr>`l-`En_F2xda{5GExM)w%Vv=h?k2aXrb1Eri!x!P1MpqW>!R)k6L=J2VWC3 zP)m2=+9w2c)Y6{JdO%P^Ev??=cL=JerFlv9D?tUd=KId`Cn%$qhV?TOf)Z+}&r{q> zn1@=bZMSa`=AxELp^hD44r(a}-H;|IqL$JcmkR_1)S5TX{T@LcwdQm+>k#BnOR-q^ zEAc9(=+oO*Ygi%Xmfnyp$2(^So z4hIkfQA@CGP?;crS^}4NQwjX2#qaYpjlhRme9QMq5_nOISDJebfd{p?ht|3ixKWEM zZ;2^^3$-|pZr?%RL@kcceZvF})M6Je+d*JQEy52qF9I8C;fwP|2n5t(jeJo=z@rw6 z)tm$B&CAO0I^4coBT;YUzwNa#c-{wrz?e#l*f|AJZr1v?Y*pHZv-Vdyk| z7`6IVzMa7jp;oVGzaIV*YV{0lUV$G(t?nDSGWY@1`fvod8sCpv@Vp)0hg$G>65oqj z@H7Yi5w+mv7vFd_9Y_3I)PleL z!*`+<{HYYa1GV5UOYrTe1s}x6zdjf407V-X!gkc!`)k;auno2RtDf-@Tv5v}$73a7 zD{AfWFxp0NL9N}U-@*vasI|+OyN=+5T0TvJ9fU2YbwOlG@G6}Y*<$S83g|HU2oU9+#5s0X@Me6<_m>)*4L@Yb_g=>5*YQYZz<7-e0em@oe1hwGjCh^t(Sm1R&d=+ZlJr$^n ze~emp_SWviSEAN!sBsEkfm*k;zNO+Hq1MgLug&;}sCDDcyY2XL)VdyXQX2mNwTjlN ze#DbdtB^m>3txs>SBKrW@TI6#P;iSAe;>8-1K!l(OHeD%yYv(O9%|(Z4&d>3QR{No z1tS{IXqf8cMS)`e~S&iG=~I&a)Lioc0k=cexk;%}f>!-w$&h-H7^@=;@gH~RmjlfI4N z^HD3!tz7}1hgzviJu30JsFlJs%!$8(TFE`!gZRs+buxG7UHm1~IuVlKi@%6k$IX`8 z<1e6AlDuFn{yb_W4jtgf=b%s)_#_mdi+V$3T-H@!=FH{kmS*e_~WP*99HxOpM+XL zi!ze%$51Pf|5!IZ5w-TUse9oQ{=Wam_&pvD?Em{v%pl>a2A)B}`~OR}*|THKAmv^N z#KA}G?v<92PmtbDU$ssT%pm3U9CcoX6QRKa=NoQ~fE%Q|)*hM#W{~H1JH~wjGf0h3 z5lK-CLZHUkO}NP?*!%x)KM_`($y6XcM*N~8N*~JPWAFbLlN#&@x{S9$+KK46K_$M4 zkOVXPkM!>#^{KU3T0f%U1gRbG^Jj_8Oh1Ff$$xLANymYv0(_lv^W zY*=`Ij6AR%#yjzZ0vYdT$|03j0B-|c!3oDhM2Kap_m6!5@7Q$_sgeNipHeJsT>$Ur zopZCkUkrib<7}$uF2WwMKd&W4?YC1PMInAtf*YLq6|i@ZO4ci0zc9dfN9>vr9rvij z*D0fSP$ivyyq!g4KYs6}VF&3ciA}xSnfZ5+6Hk9^RdZj%q6L z9U6SiG1g2!-fxQvFDG$P$J={x*1GzSkC-0s^%j9N=`decrWKJu#@mYmZ+MV`;=Qx~ z0V@{X#(56>Fy5omt3X@K|CYTT7l zfcN(hkDasPL!h?Ib3Vxm*m!^F*d|>qr9f&z{7$*}2{y1{a@+bQu2)*f7ao_gG~VM@_6_8dZ&rd#-Uz5Z-6&JG?W+K|9@7BQSCLM2A7p-hKL#`nAP~Z)3_Mv#2rb_W(;r)D?^*xMtaPtKD2C0iIw>;Yc-g6_D z2?-$VMRbe>1uOK=&sKiHLU$bB7H2rwbySA6rRxESrb zacY80|3Eq}Z$3>rGSZ}F_Z5({_bv*&;o}%6-VK|tabn^9lV|igjQ8hjmgEL0$|xXb z6yTk-%SvzGW+EiHWx>fIaC-}MJkA83-WF!Qs~Z4#&)n#AQq~TE@Y{pdr&VC%-3lde z%f!i(es25iCwDiDlz$O>bD}f;pzicM#_Ru49UWBS8|*!@tyhWu{=YWCtD!lfmTLBX z!EwCok>(+$$NRiZ98Egf#5SBT{QY{XF9qK4`63kWo$c`)Sa`pC-K`3bw`$@H$kW@O zCmnaPgZ}?eBYXd_ClMNw=luKt+`V=Gex(b%_jXM7*xv5|?;~yb!#$qC(7EgDx`HOK zixb?J@7GR+D3H<+zp|ts(kEVEXK#gz1{WR)GG70W>X4@rUv$l^!@IZApS`ch=B)na zPCa{js4SKd`mu@W@lF&|ph<^ckl6k6S%3Tge~ME^{sHv=ffP9iK4FRGAWIPwVXPdK z9pKyt-$8o+@C^A5(#$>~1747W9D;0oPDm4>Wv0QmOhNyDhckAiILJZC7X2A=1aSYK z%Bc~Z>>z0DRQN?%HS8R8A;ix6?l=qS6XI8M`uR#1R_q+Kt%PsP^{5cTRgk9<9b2iy z*YkRr__}}bf>g6(^VMAq)N>H;!>F&KHv^cyL3(nJHXZ68wSwA@kt@gm3cTSX!zkXG z?E*qrcyHt{V}<*F`D0#t;0EcM#O`}+0PnP`SCcQu6Cvob^OJP|@7+hOmq`G;?`L`~ z765o3*I(=2;1dLutV%Tq8u!4gd|DFrYz%nIMk+-7R!gth>esLV(|>s6Zr%FLjQ9Ru z9in59N_=M{uXp2Z>0e@vPJMs*#)RF zNAd1|^I8B4@0`Y;vM}D~%sc)MduJY2Q}_P=qcqSwkD5#KoaVDhDx!``2o)iX(m%P~$*4iYzYp%Y%@e?#idxKui?o%Q_54MiS?g4o3c7JIFSC9&Cy9mEP1!*WW@LHk^ z?A{i|E%Vrc?%w%5ZgDphII4aY{)wCS#50W(LU->wyME~&jHbUAq_YtnH!<=%v10SF z2i&ydEn*$9ym}+{4N_diww?xQK8CL#aq~Q=(h+Kr8mDuKku9G82KFz z)OF5jqaE)ur|Z`g*I?uQ>1RIk{AtGT|A##asL~NocC56RNcy}*5Cz`wEhRGEZ3ZD+ zXn05NwRVT`mTmn=!uw!aqSQx#_c0>pCoKa4bRmqdzZBptx;xbi-o5Q6wq$exyxFg8 zkr65hg|@lZI=h&o<2^|1V!ItHQ00uoT_}B4@>>WU@6*KXJ0`g0=??FHM8_$N{CrPF zD;x6Bj<-qW>i~x`?Ajam#<4ZsK8oSpJIc$6Djgi1o>n$T|Mvg%-1h&I8|eS{Q+N=3 zPm}CH6|6d8Cvu&D`<39t=o-WF<(! z9%ShE#SNYy6*ZL<2U>?gRhOBaPPC$XklxrLho_q3=4D8n&QG&g7b%Fo@^$;#Yhb=y;bEHF2hH?KEG2#Eokl)SU7|$D7mB z{ETYpU?rVU{ZAS~m;dPC!N`w;t$K%rFzrk1p~+KHtq}GB={&yL#G>{YhQ~YB_W@Np zOnaLaF9uuez`cnSc*8g8$#^$9zZ62lJM&5N5RA8}#0=>J=|@E`=)4DbXO*9d4`U-h z9^3GCOaSlw>Yjyg|9`&nDF-}3D(-VT;M5ul^2ck6Wvw@+}f)$Zn`- zYl4pVMSJ_$+RFpx|8PYoKYWn?qaz0+zbv!f6Qb*A$NN(bM^p$46&2*{$YSFI^BKN^ z#8nScr-Ru(8M(a`Mu9i{Gz1y%3YHu}RJ|zJxCnK z*@N*`|8aWj(#|h)!*lcKu0i_j_eVz_Mt=K!h`AL!wBsFFt+sNbG`4$>ncLi7c!|jH zcptlFL6wfEH5zmJf80Bi0&n=O6Efbpo*@Egc=w0PC&PG~RwwR;@%~LPp8Nsu&hD&! ze_4P4S$^B@_XYI-f+eovFy4({+S2&|-mUTcPfgE-Lg#fX@oFmQc$emj$d8Hqtjt8> zN?$SU_nU|A-eyt*n$6yvbcc5yqQe*?zbb;XL$D+5ct6_SFmSDfis8h?(L_1^eGHE` z?f{iK+S(7mZ*Tv-|4%1n%zvd3w<&SnzaHcSzxG7-poMyhQfMB8ue&nkL{JkC8v0Vst0F3re zIFrh9+56WE%>QrW)Q=mh)(J4Y2iX|RP^CjAU|`;*+HBAuCF1_YoAi7c8Sg_~R*TT^ zu2OJpg7J1NJVnC06Zfch7A&z(zdtI(0lc?Fy{=aUOYHcGF=bhR_W*Zvf)BtO`t)&K zhe{YUGtTnTz7&0l&7BHw$Vp(r|3KoB7cD-#C-i#ir0uOp3cTS5CdqielFbxH z!`tFxdp3;s{BO@lySEu@hD}BQ-Zt`%xVGQ+keBB29!t>w_j61+`LAo2j<&DmKm zVtF+bnqb>!R%D2d_r@(9_?=JY%)cUWcZ8?Uy6~doU1_aT5XjF-cX;nXbYSJDx=Fum zk2vkc$w)!_VD?KY-rlNzeU0r%D8suqZiq@9ZhN?t{`UW9EgOCP9yCa-|9X%U{AM)S zgS4Au70^6r`Q{yOYk>!e&fVPw??DJ5Z%9;}0A(oNcyS9 z6wTjbx(axZRcqOxXb(nFZPxF^XNBL{BtCZ@1CS_c5FJ}E^0SaCvNbtK`xQHOpXP6Eqf~fM^Yp}(PIiVLkm4rCsMFCBUoJ;FAf3oU zfj9gJIvH>1!=xM<-pa@NG~p%oCpQ!6c+2_(*Tp!nz2$EBeAozVvF{c7a>pOwZ6oT- z1miuGzCC6&z*}xMY=N(5I3ylvoz~3ci`us;*qDjeUT4NjAaOgbbZ@^MLC3q6{|4@m zp#a_Ct%K-zj*;K4n)&zko6?TAZ>iR{EJy6)Ex79ga|Vwx7#{Das<%|>$kZ5kT}V3K zk~p6NZ}?SzGTs{ad$MSFGkJ+8z<6)2@FrD|Ns3OlV7!aC`IpLa5TK*c1Z7Ep_oB=% zAK=~Fu>~^Sb^!0e*HRg$)`de4N^pkhW9aVv>G6IU^MZMJa$NAzJr>$s=y*STByt~d*D|*CtPh90 zwcj=jkE7#V*M+~}ZOVlALgF|t_GV_kM#no*h;w1vbNa)(3(;{HBfpv#fj=vaXvdp( zCg$|$!#dO=?_Yr2tnsU38Q#5dcJ5T^_{i;C=W^}u`Tu|a{pt88u*7muco6*MDY6G0 z{vxD`=0TCkr(V^73i1jed^_C#m%8m4;Qx-#{Fc5pVxl6;zNL zR#)=WF};McT!XWhRT7~q?iYRrJE40}g3J#U_W=R?RU~fF^N8JYCg>i-v3Z{lyT3f$ zHAsgM9b6dsb(VRy=KdcZNaO0eAM74PMT3-e@k7~i9me;d%mS)(9JnggdEykQf?P;} zH~c9zGTzyK6Uu0K|9V^e8OFQ+#UKgqjl@mHTmbKn_pHt~>45kDmakop+sf%Kw_?kzWK zW$6y@&xnr882M=iKQX@4O8XXjNryvY_($vp3Fom&=d#op#>d;oo+=&5dhXGx_egjz zpuijcHXs>q@1Mns(eQ3#SLB3uZ-eH!?||KVDNlLb0)Y1nlh|1cO#&npQgd<^;O&s# zx@s}NI|uLPzzX_*Cf(n{Extr3p+;0nk_jE}_aRTk*_?UtiAbE0^(UA1e)I>@l#W7m z0e#YRhj%}sLm4B#dcU1wPxxrBAVbOx9u)q@ZjkIYbuYVN&&==>B-MzwRO#Tb9xX`& zH%LKo!cKuV{IN?i-t97JN@#e;>910U@g6YzK*D==nb~Ui^_J~hLrX+d!TWz}C5NZL z;lu=wNLNLGx5V3f35o#kWzu2S!?qEj{eEiJu~X>p|B33~mXojH#2-N7n144ew2txQ@Yi2gn@qgxy=salI!zdz=4EWCjNwCkmD;<@^eE zZ>=`^EQN;?-+6A&w*h#+VoAQG&K(Y!>`E!xk&o`)(aV1%T;p1ZH$&p|A{Nx>q@vf} zc`MZpPWy?`9o{L3j(m*#cGybB7FyAc_qq>3FT`W9-8;7P(T(5telz^`R<>#>RXR+L z?HnG@`rH50ao7KEYG8@wrSKs5`_*I*3Xf9cOF!R=qSXF9)8)RR6$9`gGXxXpq zlb6*PzCqGlfICNxjty={l|5tO1Ja2+6nMiQWGCZY&i+Od4R2MiA_&IY@umDW7;l{U z&tnS#-pNBHP3N@<(AQ?GYHfhGdb4jkjQ5lqo^S==U0oD0Ph%4ivX@P(?)!pXL7w(i zi2pt$iYFj(F3kBYbIs@#q*d5Y;UGt4y2JY%qQeFwzghyv=2xt=<6Z9VmFs+oivItJ zMi~@p!0>oSMQc)}qjA-=&u`NA{}Q<=@aDP1d6JCxaqS`vG`x9^itT{$W+UDs;l1|R z3orQf)*qq^b<%YSQ0EJM`^^CFCe`?-Fy8BOJms$fye-PV@kXs6LR?2gRPJ`7<8Aj@ zDtcqC2%a40UVWX5P=StjA$Ld3A%VqohqnWw;|fN83n4?VcXqVnZ7j4d;cXsv1!=J} z=%>(b#^2r=+7wKcj`0INTppzF|0Qx!;LYvVkV(e-nn;*B8s2wI=N*CZmUi9h0lRli zRaGN5z#y>&g-aH9l>ZnA=J2gDZe%Y8J-Qm3t(Qy9C6zQU25ab5h{VWf>wy#@jn>r5YOEpK?!^!+0Bd36q8snVk2< z`2pU8(66H7h6G4g{&Pn?!26VAZa$3n@UPYZ81Lp+xTCj!5}~!emg$np$3g2km&@P-fNt)_^^Giz>@+ ziP-g+;rst6*~?VvNLy?${3G{o|Nn23O~*fh21$s*gG6y^hsYjeC(pVB&4W_ZehI)H zRHP9}>i?ssj^F(Z_8=3xzsO$hwTD_q9iK_|#z89vqZ{G*zsgR#l1AV`J35sEFSrmP zaoywRb^fD4>bQSR=Kf6y&HlOxZ5K^Z*59&g6Y{AHnMY727@g(h6 z?7HU_tS(c*A3^m5!;5`W2V|%>M-`@D_f2BY}+fhJ7#f(eSRQ zQRjj2e)rvzg!j9<*|p;UZzssDxq8MPV%epZl@IXV(7ez|4d7j&DSf>b;2pYtZu1^p zA~aO$7Rp(JUO`^oTfuYUr6m3n5+@RKSMXatdIjk`nWuD1n*Q*BlEAu($s z+LzefcOTkJe59g+9D1lw7$?K1+%1_bm z-YrXStmFQI-Tz-%uy;OJ_X&o_`^d#0s&sr^a>TglB5D55Pl31K_PC>DyrqnG>!RVk zD@$`ejCa_y0SWJF=vv7yfVWkE79=M z%14AoE95UWWMFoWU5-}nFMxbG*Y20Tcd!h;r# zEM5XHu@d}oJNOk{acCYSVsq&vyu@0j6_U2tpJ^p-@C8dO&e}BG^`bpAcfaE#9(-a~ zw?+Pe4)7pVk%{_sz=KBHHiXU?6QPiw6+(G0(3jX-3f;SBe8up4khrbStMN(2=u7Ol zF($R=&i5$=y=DgP7d|#7su-(aXz6-_y0&l z$6KTKyVauC^mn`^4$+~7k>6>yq&2T_v@fytkHzdVnyGl+;-hKX#sdKik2lWSh&ml6 z2Y2fIsUSru@Rmqqb0p&(r+?HK4ewti&$hsLD?YeQn*UqlSSzyt-Xrq72gdH$LreNz z&Ut_X(y}%8Wi1Kq6_u`$UW-#6b?^Q{7A28Ods{nX&?u1+w9@#@v z8oi$gU_h$7+XjLgB&cMn@(#dzpY4Y)Sx1P_&xy4QJQUFJZr>76P1qobpF!e8%v56{ z*wOLktFzWyd4>M^{|-cl07iaid)n4ro~9jdQ`Z267An5p@|`bGpmSy&!(VTC-a?&@ z)SKlY@`)t8g(>hBGYpy`;~k!%ZHR`q;9*};81JJm(@Fh*{w9|_!vJqWu1?#D2774J z)*ZTeAL1aHyGID{>}|<-uy-fGo6j!%*@d%2Xd658=XyPKyoUq&D$UPG;p1U+7d-5~=;XR7z_=S<*J=unv8D_K>C)ur@ZkM^RYj50%Z5w%HPcnZ0PuN18 zj)ea6@b#9z{XeS?)>y_;aAF&(1 zK9KJM_8@)tFSt|D4c;L2Y*vH&|C!(N8NR@S!sSH1ER`cdMbg>VG;X6e zNavh+QbwmF@t2UeUGp+OEI)zXAYI7Yr|oD%e*@Aph>nXG`F-lIQ}o+Iy9XIvRI2g5 zOGO2FrOz9mafIP3NLml4CDQa zIl&#qdr$T$B{A5&>!M;~yX~Qn#HGi0K?OOFHBM3&;9d0VPWT3Zw|v`f!o=+`NMKIw zteq7)-Y<7n>ySH_Sj(&{%_IRE<|GSrVymyG_ z&JWJUKD~w8pEcqe{r|xQX@4qp)R{|Xd6NdDk`#E$*xq&~zQ@vFR9$_mRyfhStEv$YNx@OEccLx1|be0#+hulxo-}M%6LVGl^}9CPp9>KMcD{lC^;>U6Ad$!#!7B3(|Dpuk&Nw~(8Rw`^wGJT$zYwhOq! zcyE<^PTJmTS@8PGHGsEhu2lbauzOpwjo0cTxc~2~rn*oM;9b~#a>fGS?e1yO>KqmZ zU6?ZFwq-}hn@>Ae%lV@S{wxwVdn+N{r5_z{PuFJ#&^r3Vn+MV1g^^#R+q0{CtZCog z(t4QP6GP3{TaJ!Y1eruJJl;`jsMEpWaAG{9>_Os2 zD>>0Ts6s551NI<+Ng`>9W#hC;XD$H~B(|iv`QV7%t7_Mp)n!VQp z57G?OxSM~D2$kQAd>dncz6WVxvgGFHG%5UDByN)fZrf2Y^gT$ibf@e0+coI!3=&y~ zBu0Mbkp7N{WZIY5a~pdVI;nXeO)g>A=w?aA@Bh0GQl+CM%ITflpY#9n6nHBa>yQSd z@b=cTUNH_dym#To`rrm>PN|#JAT6A;+&%~zq&7X4G*LkUG~s1yy}L0Eiu%=*16PnS zqNRSD0p59w9`QSc5TTOw$9`)qM8{j>m5dNeq%{5p64%~panX1by+O)xsWUOXuSs`! zt0Ow{F!GZ~XX?E7gm%0~r}eHHabY(|!9^c5^smG*Jl>sZJyhvfFK3&r44&8l?kz`w z_u|l-5@h!ds2W^=hPP<{uW}ggbM_h}yq7Ip_u&b^Tix00ngRGgx?_`i(1}-Z(CUYV znlRpHYYelu0=ymi{c;1h5Ft%7#j6j#qF0dq8=tp1aLVA-khtq7R-~D>pyT~pJYch~ zvliXq?T6@KmiX`dKICN{beu=~3sRbqL3QEfR2+~t`83(pn9T5a<3>JHrz1_0UFXm7 z7Fi0smDafDk?~epU(Sw(x96B@3XHc_^6o#ox35p1%LI65O%zv%vk;(@>ry9Ix5q)F zR>?Qv-P_6m*55k;-aLMXFU}(nq1O5MJ4}7(c>f5R-K@tWgKtLSBo3B3>C~X(y>s73 z`}$4vhxd0xhc`xkVqc=qd)}qpy}uru+AeS&dqBE<;S2VR<+F^Bw|)y%I&|9QC@iI8IRLWjpc(DCNAVjf$h zC5@Lu;y%UJdW8SS^OhHTs*lJA(qD1HiRdW6$j{*uPio8$+VSQ!uzq?=lnVFOHy93Y z{l@t7e-%7+I;5Pn;Oi}a=l}n<*>w98s327+JVNMkf&O30|HAqiWdandSdcaHBo6vn$JSsBme{l{F?A#JUP6Q!qY%q@B4m5^ z;$063^ad%neDN8LBni9?5;rz-_}hhF=u51KilpiKKKdJw<{>)7F!H;$P%%!^hjtHY zi4gm>HHQih3epf1KdZp_OYE#FbvjOa&X)eEAeAZb*1V+hm5g`2-9kPzyzvfG9WdUn z1&c{|Yp5THh5+76{l<@RFD5`6>T*?QYT_UQah|;qz`Ln*`{;a7K_>I|Ci>0~hob8Z ztg_Fb&{W7V}l8yd#H$1K`y4iTf<*5h>Z6NyVpEuc*oront<`% zUoA%3z3s|-Y`FyB?doRQ)TRL5|BtV@t@ktz8uH9e)_Mx}0v+$=t1q51ye@&?kHoQ?@7tU1fsVJgM7nVZJN=y?CF}6R$S>EP^IPV6+VO7J z-r^d56B}=wqFkoe3Ngl?AjwKlr6Ymp{au{&f%HTr3cS_r8coP}C!H(hM#J0HD2McV zOQZV{65i+7jTKb^-r{?mSRgq9w93eED(_hwl>A{<#sJ_Q$-Ur-A;5dc0NT_4ng}rk zCzommqvOpv>ou|)FNyyh^d}DLP?ox}5gqT3EuOE}WY8bpT!@Y#jQonF-u)=cq#bWp zEx%#&UMlczdGs^HaxcTG3(T z2b~u+7De+QEvbr`YT!Yv3skniCrE8>S6(*(9<(~Q`r_#)_E2!*?xbnZ|9`hs%rF5S zq{Fo|_dV$US2#X&PqidM^Fx?^jQXONB%)ki9Wu?M8M6+MScGM+L19;CrXs&se_tb`i>od4IL zz*|2RPx^v1Jpa$Gz=@#Yef7~2S-3%}tEeX7T{IAK%pBl7*xrBBtH&PNx51(88Nj<^ z2}dQ2_ucfwuWta}-;|3y^Q6H1pXYm|{0(%xQ?K7RTvslMzlp@H-?n=+|0p`%9OWNR zjBwH)-bWD~oEZ6;A8q#aAEX^`*F|Pf{yOXl(zdm%RYKZ&48O!)(O5v0j-oro+L?bQ zNa_@L>urnaB)j)|&1NAqyj991Y+=0p{QXH2Br&BDXc@rU1Lc@4)a)DvFcI+O68B%NZW;s5R8-7zujc&IS%hgW6k_ z0&nfvv-in(k1zKTK*M{U)m#ybci#F565fa3eYmt5;NASj^g{voyru1uL{}z&_xS@V z%V4~dYg_iV0=zp#e~hgz0oz+kUJMdfqT}8E<-*#jLlSr#61Tug_<6ksI^J$!{!N;_ z^f#R7Ky@5FG?wY@J9Eb4bw|s^-lBS^^iD& zs}Yy;?a@8x-nf#(yLdUeJ3+b`(NTes-<2)N#sN{Zd(iF8n!zGd*cYUu_T;DG6nYuH z|BsrYPRBE;bA8AET#(kKz}qD4m@gUcoo|0iqT#KQ@LmwcJGj1<^aW|x3CVhHfVXl0 z$JUeM_7Gm6MlKcL9nH0=3C27524T+}SYl=7_C`I)Cqf3(@%R1B(edV%ZCia{P6Tg= z#Dy&2{w^PLG2AKu>jAy+SfhWGhz#XI2%(s}7$qzRJjx8#0N zfOlRhTaM#9d*}i;ORfsQ+ka=YBYb+RM5D$18^AkuRjbqcBqD@w&8+Q}LC3q*tUgr0 zUJ?%>aW(Vv9)4v;$D6mn$)GKl{`&t8L1ckJ`|;`-QiG&Tfwz%dt{&OFdA6pDqv3tG+oAw&kT!q*N@|eqSlX&6 z0lfDI${slT)E@dGeS+sEIKB0w?rb-V_q$gbzlH(c@w@8P4#W~6{@K;)o5j%a7R+O> z6&aMmljAAT5IEc#o0a_^c}5LWuSO>BS7KxxAB9^#4yg zx-=YaGQN8^w^OIX!{u1!pXV*KDDXC9mOf0zn{UWZ3=QvlYpvSh*_&I*sm*Zh?LVJ? zlM%o>&HQQQ9`HEv(o5pv@&NCjJGXknySGVKpIGz)y!FBkzxFspgo3wT<@1z6$NOZL zroNeu6rLRC9{PSdY#zFMm#AI;bec$icW<*09k(#@TU4^qqdAOr_kQ+aKCfjP_VJc$ zxqFozwC^)~?QIl6q)JE0?dj@)0lOx)Gum`cMGQJZ5uGn$vusm>Xw}%FwMHK!9N9?p7j77pHNJR=R*vf+bKYGiB zqCHoLP$%a}_eB=y9%No{eC*fy=E`m)ZuA{LPmLnF2U*WO6OWqcF{hM94?oZ5|IuNB zk)M7Te%aL_+C6AF(@ae+6ZRRT`FX9>ECK&I# z#}bqz0p4deXhvzJeDq2v8!v|Ni!kkYM|KVd-h4|%1?ld0TlIn^!{d!x=tY%|#DUDT6RYFk z3DOb@ydgV@Ph`C92g+s9@LqX??<|bBaV{qbZ`VE0?yCUr%ymNVi@(@I-LmDWc!2ks z_a=)C0p3-tFWQ6w-b#bV7QfyAK5toc+COOoeg3cTK4+(f&7}DV5*On0&Qtp(I^O=f znUd_D%%{8ETYW@F07ic0J!g1S2(;rJbzCEXzXE%L)Z*1?pfpm*@OU5Ve?^s!x`9vO zZ84<&-+%&dyxi6yGTu$4M`h6PPBhaDhVc%Q+35qjw_upT-bR4;`|F=vM1R{uK7LF# z)!=%|qPJ#IFy5&zhg|po-bU}u0u$B|Aq%^dD@vcx@tzjVZ#0o(!doJ7k9e5NDxag{ zZJU#cJ6FO-cX-be`=etuMt((3A*TcX504YwD5%ssyON5_iJStXwsn^n9&cPaKXp2O zoaulcNC)n%Pl31D_^Bi^-uy`$q|xvm8IiPs@y*!_Q0|3Lws(7g=b|Kl2{ z(-EL<$*hw1_x(T0LYZ!V1|DQi;X&5<^BTw=q?RwJisnHPA{)c&fCurh)$W5mXr9z1 z*?6$TmQT)`k>wyj2iWF4HwG2tuhytd@D;m&bKPP3z=QO*k6d_T84ih#HWAg|qI-~_ z=&|WBBfcsLB<}ig<4>_q&^<`Xi>c^llMJ5T{+{^|9a#A#EIZ5Tx8(zqaV>y%sY7Y|N$qfG1B-mP z&ogwq9fOWK#uFA)Z9?LF{qr@6V6ZTK56GEsq`T6$78QNdLM)tOww2iT}_K<1J{o(?|{A9Xwllu%bO2I=WUd z^Hi`e>dnX2mY@|UPT{JKA#q{@Rbr>zwxGtVyPG%PTf$3sc)vt+sAA+NA*xZ<8cI9f zX1m)>FFwJZ|3{6y85OK3Wq7=!A|6qtW3!Fc;k{2u?rlPWw@Oa~vs!^w-_fgGRaJ=R3 z`+xM-jsA~(K>u$+;X!M1e)f@?bX{kegaL2|soe$Ir4N=^_65vGt-unSnVHwa3Mxp;N?w=tAoL|RDd^Uw-JGkf$!)EwP6Y9R!U0M!)Y8%Xln+S|R_Be>u{xe6MaRjC@9g z2NfKtah(cg_zDvDHkmpdEKK`P|2bl}i~{e~k$UxHytm*!YNFvi5i8aYylwG^BFT6wg%xX{;msb%-v#4sw#tKq zw@UY`x*GuRF#>n_V^IPmB5lih9-RNze6DdD#(Vo*zwJ_hw@Fsu=dEYMp-ry&yBmzq z@qX=8T{B=HUFC+v#l$2zt(HT_J8U4M+JdM_cX*R^gk$7K4ELXKQKKDib%9}*p)qXt zj&f7%sq~*@c)W4d3RLNkbavD^{+QGtK@@ne;@19W_crB2m^vEXT)dxOz;aWIk)X#TdW+gh_ z?CE(854y#xOp!Q$xfdmUdgyrTomCOoW}-@Wc(Wop3^4NJTzG4P(QexDX4XviOy|VL zJN{<>#<=H&4BsF<-SVC)9sWHEwZGCyc;hMXwi(#}jqKj35mstwcz@S8q6XvbF?W&( z*WRCE^KnT4Z{Izx10CRb3yzVbswseXPqTtJynDNAuhJ_cfOk}-56A1h;gDO6{--T` z=y;cI+g&lLC|u=%#2pr#aQZxr-v5_Nju=npDAFC?w-FupF!H;Xrr#ZVop!wA_GZpV zR8TRTc#z~h(Dna8|9>}%IvqjTC0c*q|3_=t=_Ajjj?m1GavrOdPh&4V~U zoS%R_=yH4$X^G9f!|ta5&L9b15N{p?{r@mWC_eO29CWU=wNndt(8a)a*~fqfJ@{SQ zxH&Z(%6s)#bgwG92d&5p>RRzYv5Fk`Fl{eevH56 zpQPP`c0G{Y8F&GEiH%x(y)I#r@!uf9<+9aNqeIDP__=E;X^FL>z}sP4*(x&L%v&4u z(eVDJe{>4Q``&>b65bjqTKeJuZ~ajdUM7II{H*{N{>O39p))x~@E4@Mifq^y0r2L- z^ZrZ=4~JUBtYEFr0p9*^zvRN-|NA`d@4Exw zy{b0=Xi@H1>S`D@~&jOWoH6( z(eQ4$-HCev@K!fti-a4beNvsvW$GdOQ@!nPFybRy3P;~)`E1!s%Q>{nG+x}ro^IlK-!+R&9gMg7= zmrVb+O{;0g`>^->i7QkbZ^0#2NW66T$?*L@F5(_lI-2-XMZ*h7?!BA>Z@ahG*8GEa zDWrpjx8|JN57@o!@x3JXR`O~c8U=XQha^p~g8sijIT~*aW^d!q=2^gaKTJ|dSqbpo z7J7|Mnt4BT!nytI?;LczRaTy^lwwk-I)%gq_1%n`N=CDYK z7c9I1D##UcANME%56an^A+?nGCA74#^!?fsL}-jBi5R1Xeg^5DtEscmoLm(-u7j8N z$N_Hj1}WfBQu6yl^f&)6M|5E2XD21JLUNe){$E|`4sQ2HDk{kLV`g01IEMEi++_}P zs&xEzJFNDng0!W;dxNvae)1B_yZNyR8s1Y5#v5R~J9cdfhbu^yt&f*T0lXt;C&h-8 z2++AG(JV`VH?Lon&0>JJ@vn+WS%CMzcm4NEJ&DlgLnS%Zv*DZ^$fZf})s|`9T0PoFo@$D3HMj%qUE7u~%_T^kjR3>2%#ahXG` zPYkQk-Fw9o^@x49=@0J_M8|TB{I0Khz%o%lJKn2A1_#~ju-$uk=tG|LJ&b?6CDebK zDjiZOxVH@j-cD^(|7>rS8!a(J!#l`$lyvs?Q^X@u|G#jAD?}aOjn7lcxGV&U zlj3y~6A$Ac>m~dNngH*sIgVe70N%dqHEeuj!lB#CmgaWeMX$ZR9&lF*S14AI<0{TH zx9FThuf5sR&!}q|)8BA{tb+|BKj*yg z3RLO1zM@F_@BIINw%c^~OVIzXrSKrP<5yb9{lBgI239l=S~&Yf9lrlRnR{w4TtRl< z^jfX~23zbNYfCim$3gpU`mn+cQs7fjKNV0xc16VYv}`3pk`ETuj!dF2 zvBJZflcLhZt3;8wP;I@y%69Z6mfPP)uXRj??)D)05goi3`3-+Lr)YbK_9eD_;Y{g< z1}Z!#OGry%7vsPGk6WNlosQ3Qv$;rzn434(9)T)>V+qgE&ZLuLz_B@P=5HWElXw^q2%PR48)v>Sbi zy`jU@y4_+?l_nCGeI=@-Qj%|(Qz6hKaKX6Rf)E=<8A%;K{PK5 z_7;0o9oI7V>Oh8XkfK&gQKh4O)@i!%&+!&}3cR<7oi8TiJ-TCr84d56v8QP;-YjRd zLt*ze8oCuR4^)t6HrX~D1P7#j(o?jJK?Ql{?K*#W_txTMtEC0N+iRz|>gq>Ch|^l4 zplAa+-U)8a7Vjsds}>@0>gQhhwV0vfUHoC+(-V4Hbcc5gqT>cee)XfLBTJ6cj`xo< zCw06a?9*Fmdwli{?doKByeoc0P^IHr#L4`rNYa4RjsovZ15=J$-Dy_a^p zc@D-JZ{Wr5|8Z@Da_b8_7#?q2<~!PpZ97#A8l>^-x=Oo@2~gTLo1>dSgT$Is z?JZVyY8d+{~z9EU2$E_TeT30gJieIapj=*|F&rt z2sy3Nbmu{D5FK_H`Efo7JTWpwy9aGbwrx$c!ETV)O9q#jct8G1Wc;EK65H1CHXHM%k_~;U#9Oe90 zet`G4O)?WQ0PkDp_8FxBytBD3H9q_r2JP5pSYsQ5j<>l=#^>){d{yp9TvYz|dqLaK z@h+|J`Zc{R5nJ zM!q2BM1i-5i1jjZ1-Z7lcL5sSg|)o>Fy1qF!bo`69PD*@0PuF$G+eX=oZeDzX=SYf zySKt~FH+xV*(?;{ZaPKrF&?1Z?C0wlL>FJUyzoHDu{XQ&sFxn7H~%T-3f>~ z9l9)u@2|v?p0{wMz3ikt-}!k~WbjH{m%(ed_f6l^QW5vqEJ#Kph( z7<8Wr9q;tBES~SA=jQmdY9Q@jMnf3?L55K#iTojG%-cjWeO=p_;7#?q2 zBy~DEW7w__XOoH(2MWC1AOAi>#@qFH92*+mLVZ==VZ7TTt4Me|sk^3i1H74}l~@PB z{NKsBe)~XG97H^MXcFGNEqSA4ZVK?e&U$L)e1Lc9`)EJo|G-=5vuz|-r%2UJBu;rc z^~C)Dz`I|+ul(7{#dPQ1e29(#jQn1WzHP@((vJ76$7;?y0odDH$?b#t4`uo?Jl+Qf zsM8_wt}n^u{NMhcAy#J4|8Ju3AfGo{%gG+}*~*+B&4X~wkM-aucE6;?`@{YJ{bzkw zmV!OVkIto68n+N2-wj>bXYa;AUr!Gf!xiMo@AvnF01wLb{^hTdNrVJM2Of`WpzlHQ zjE`xLXnd>WM&fp^{rb*}4}A~v=%`(F-d$$8^Pst}e{>wj$nRISG~~2__6pLXaRttG zC3gQGmEW`5T1A`j8>G@+s&pLVFe3Elkd{~%3cS7T_r#L%z9%fshlcmP#PK6A-r4NG zcEflNzB<1VK0zv_cwXzVGXc^Txc*YIJPx|o!!{}l@IF*Mw=f#uJ^a37STukLv5Vf{ z{(e3>-mVqqVy}MSs+f>CZ?2N$wFBrCWJt}W*cD{(@w+<T-*W(Uc53x2=CjfQum_D@&1 zLCREh4uaiVXLx&8A83#^hdXkQSQ4OC&5ucgm2r^!Qms|+?(Mb4;EYoMZ_Y`}8_%~8 zA-)7RABn-|muxXm1_b zcW>nv6!iy;Vt&Xdspx~gC*9`>?}vd^DqcXeYrJi6Z#VS^+kiZ=6rU%ITCj&=&j+n zG5QiaE4d;@CP1W$-u}*K5FOJP`IYEzD0e$f`yOPPB%9x>J=hf_PBC9eD&-5qpFzUS zUZ+Zjnij#4XAU_L>*{}0dqn=f;Upy92X8Gawe`_$0UT`=BV)+)cO0p3;z zmVGJ)c&`zE&dYH-4l2BKZ4Zq1$=`$RE^vc%$YoFGfdPO_lTp!Nd7i**9dP_>d*Xq>u z48O$U(ymdZV_a>0{Hlv2yj>~q-fg__pX)8`!mUDRc%KO<5r)4Yo$K@63YL|xq~ zxc|RUcjF=Vv^PjAdk#vU41I+C)tA8# zwYZIU7$5KCz0~Pw`!5mQ-jQm1a(gNIG)7~IyCobD_`UXIt*vXkVZ2=fuUL2kyj%Kg+fm2tk$68JvlcqRdRHQ?!N!m{``*))}Q~KpXTbFar=d6$J_Vd zVDzV0%d$$i$r9-`&Q~TxL`9Hn6{r}Df%>Q>#c+kGgiGL1ATO3!B zLi3=SjNbL|1gYbqC}}`icn4<#4@mb5Wb?9ZCqQ4bp1Mzg{(t6TeFr@Mw^(y$D?I-% zNcni8|3(;;SbRFk$pXEC^zhy!yXWKrd^{58<|lO9SO&dw)_cLDKE$|Y{w##|M z7vR0h!Pzo0HVk@pjVJnr06N~HlM`-k2Hf}>B(8e&i{6nj7t}_e&wu2+%>G4mhqpAM z11rD%CtKc*%+ii`!TB{(qZhF8R!rSmpLo`T;Txpp^&V8|NH>XWI}%5#AU!DX4*vQ1 zp9|7bMNcKr@V=UAvmVA<*6X)7+#so3OIV->@c#9n@pu=&`_lWnx6%RLT-Xm|^LU-Sgty*+!nkhFWd-!w_r1mJBH()sxwz&l&ZZ`J|eeV`_CAH2O) zXq7Yv@7_A%?Yp`?!XTx%NW*pG=y)3(nH*GZ;l;}%aYLRC>!6qDcsu{p+5g>_{_r+N zbYSJz%$hl(lteq;=Wdi_Y#YO#|2sS!D~-X|FuZ#&NS>rhhp>4Gui+um?(J3zyaO-n zvLWL=k+Me&4R6n;76lmZuajasVfPMT{*1E(cxM)?J0Ayl<2qxzSOMNy+Z(yy^Z%8X z%=WDXc;C8CyfJn#3^Fq|&Qat?FHRoh%?L{7bKy;pxGQ~=;?1AY@$Nr!z2noEB;C39 zGek!pMt&{rUCw%MX~#SDS>>&B5>yN)^e1gt9=S1o?fvK%bvi!Jj=*1U`TPF=|8BYI z>bIc(_oncmi1nS)WDnZTEw6y)L1~pM&eZ@9y0~-F1NNXNjWJigf+Kc;E5rGhgD*(G zCTtXY1tv(Vw@pUD@BeA2Cu%4I50ZQ7np)`>25}$E*p@YizQn5VrrXxJ^5Hp^zf`$piOuhLQ7dXRW|&jhzxq(|1!>$o)6h#s4h+A< zM!j84m5%9n!)<0aNK3321>XCUrNYQ~yI=b*hlcmWcf38k#D3WIgtWw-%!)3X26#V` zS;}z(yN-_c(A}Y#2Z3UAx5SPkIz}+^6W%;ONj62BUgFvu@R;Fa4`biCi0vFau| zGUL6GxHOkG&h@$IcqeDM1vI?or#rm+5gjQQ`LTavv01x=cDzmWC1q}Z!ETUnk`6zI zH6JrP-Z+&&>U4a&(CG8$fV3wC-eKk6_LA|Q6h9(^hWAp|m>wAK&|`X}-P_6TcDxNo%q44IV;@d@Zm{4! z>jhngpZ{mB)T2sAk;T};>|-SN-bsOXX#Q_mGTy9@+@#U)b~=0EDLi{CPV5hWYwz!i z7d9vYynnTPG!+4}H~I7ztjT0PhXI{Z?q%he7r4KPZ^LLC2fF z>R`@=r1|*gNSuwkjoS6Q=y-QlR2{YC5~Mr4#StA{82KGqz_cgHn|8cIA9_7@3Z}xn z6MeRszFE)s{ePf8bvjgCWZ`db{q6tJx;8rcJ?Q^;Q+QAe#H&U2AgNk@RWuLU_3`mK zxc_fUuiXZF&_2h3mX*MRSa($%GUXyb;h~uaKNZJ8L1}jC@D;mXMZ6O5`+uu+T6)B6 z!4W&fyl#(o=zEYh4#LZeCuHzmNStrCjhx~`^!fkOrU|1{$=Y=1K`Rj*wHW!$9nKRA zzD0ZgKb(*6&WXfskaT;b4z;=|GkgVk$xx0e9hm~`FEmb&mRNrZybtm|j3?u5?KY^4 zhId=_CJPvE{m@Vn-a4FW`tStFf6#FO4&aT)H?9@F5eI$DmeqroSo@giOEECs1!tHY zxrtDL7t;f&^XPcr|5EO{XM+qrABmIF{{Gk{8XfQ612^ZmhqUMp?+1tuto)eUmX#%Z zp&jqd?{TjsJh3ZCTnOP9lczqzbL?H;N8wUxJ0CGV-WL0*(m@cqzbp9;$-R9k@IH{AWK71}?@5Fb8s6;s zi9#^mAvq7X!o|s+>Lpzj2v59ksWk*J>n^PH*{8;2jxNHbureq+qQg z8s6OT0Y9Gryw^Lrk?>yEC}S}Uh7-X}+MnKX5TJe5tG14T{$E)t`ie5Zd$WCLoglz_ z{Ao&;S6&#j&bU16j6QmC(&WplsWmKwcS7RAq86zy;YTk{Qq7ZBp4_2GcX+oVI*wxG z_rUjKz=s^#-P>D|D=0pUiu3|K9(nqb?sk70~|& zQ+UuJ6Qu)W4`SC`sEy`9MlpMX-~s7Q?RBL4|NRx!LTkYi+n1%wF$58yX6cucD!_x5 zPje3n0}o2^;XhR(_u={k4K#(2n;(PtS+YYbuV|=}n8Ca$n5wc;f^Isna1S zovHU{KpIGacYJf58QHzL+zK_&@Fw0enuZ%Bx6|8pzztHw>~Asn2I=bhGYg-9_y6bH zP1PiT{$Dq5`7UvQH)|Imof+U==q9aq{0s`YLa1r?;AZrtN7)3jl{J|zTEz-61_nx@YpdO*QG{xODtJO5k`L5Zw|0}?WKK*y%cy~wCy9d z2kAa_URQi=1H)I4&&%wn(vg=G@%G`!;nza_wU2X8w< zT4H;jxkzmVc+ZTOMi#3Opp7EOl_Eg}sZbEU8Sej$y8>sF0Nz{5e$;!*5Fw(8>WPUG zbi6Z;`WXwjNZ|J)arc;#1G|r*qy1OZ)Ul0{E=eX@%|NT5iN9( ziX(PETMwL%-OliMK3g5x%t>4A9F39FY*n*N)D}eVsDE0pD6BJlsWpmK^1^9R` z`nYkONuVrA360xzH%j4!0zTf3c>(Wh+E@>7%!f0b{O**tk{z{}Z;+zOZ+!B3O&{+M zR)YcuKX|fz|G#JHJBEA+v{+aUCQ|qRLuv5dpKBd}Rc}Ypg@$-|XRfY2h2UMb*@*hQ z#qcKcb!236vSLSqpEVgi+B`dTK6u_TTuySKB*6Qvi`R5#fVb)S5lx8_3Vf83_W1hW z9B=XP?#-C+k|X7#aR$#L6Z`+>c*`2ob7^}ovfkVq^Rbpre*1IERJ+zNU%j75`%MJx zp})LE@LYRujovx7@Bd@wu4KrEF3GR?&A;#eu}q8qw~2uMKZ>RX9r8Z87O6oq!3L@B zId=kH4J!Ro(2mR?=iNF@ok3dd*Z(XBYLH2G^F*Q*8NMG@HGCd?|Ib`(pENSWif$iV zzXa5vqaDe=7RgdzUj<&-muK)BBHnqe_7&>`yj>2xKg3%S4s$j9K2>Xsk9YEu_B{XXGf7xn)}phvRTB7k z2QQYArCir#x#g`C)WNCCf(GyO60g4wCvIKlZGwk){KHNM1n>QwmDJ4%Z=(@mbAWe@Ra;`c0qFmo zV}qB2{(r&lupnghwj-zbqzb@WVw%Jbl@#Q0;>#pcd3?N`ZYeF7?wCnRMB}uZD*DrZ z;9rndxm&LLS(fzvwGzr5w#KZDGO zkM}PQ1@eLe(qQgQp}{*XcwPiny|;=O&%?u8s%}^b!CQ9bAocwJpx)6!RlW+KVzjDlyQ8~kU)f@BCODDfq?I&gC?qMG9gpf7fg|8XdoLDdLBSrEN+v80T zbzsa#x!iiKfA|0YZl1?FKZ{?J$VF3wj+#&|VEun!jSDwk4cf=?Kpt6xEUucOo*-T6 zfBR}TxPx>z=hpBJ8!~Lir{5|EKC!El8z(IeY7pU&%8qzYgKQQ#>(q^d8D#$B=W+4) zHHd5>5b!Kaiu610Ph333SLuKc{tU9}nB~G zeY&}lig(xX$_E1gZ^6f#k6Z>z>|PvO)-SA$hX>wS@=XJH&q?|j9R~1r-|y_ldoLUw zOW!E>&f{zD!_v6L*et;o-fi&*3{V zgAAJbbN=7u>&3%g0N#sVyVO2i3ikgcO4AnA#KSUP2e~8w-bs>5kT1adTCZU;*_Hy^ zNjx3U`kU8Vu9Q3K>Xb>7tkJmnQR|gm{^s?Ta&7M0z7m=&hj%UN;|!hremSm7ZJWb9 z-f1h6Lq9yB-yjjrs`z=ed}V*UZ5Z=W>Yrb=C5KwQ2{d>g-hJaFhByDFI!-*i)oum# zA$XUQ1*p~g%J*?gZqOi2EO&FcyMzquWw;4VzZwtAQ^>r?2B~_H+7z-uYTY`^t=EzQ zyYT7fBtFBh-j7FWl%ZA`k`o#?*0s81?^XQjyo|NqQW#%Qez`|rKAFJsI{?&L$2 zfBXM`Rzv>Ve+o26yfiiFxTxW2tOm95*a+g)paZev1ubBR%?R=dL9W={QdrBw35Hlm zXjuG|u;Y`u2^3_%&#FC`@Wo8S8yP`VQ)2kWPMzQr{=zHi*#O==`5}_?7U8d9^Zd zgETU@?AxL?_OC&vD^D}xBjNVtQbFqZ|3n@dyz@I#gE73=?pMeYyB8O( z*oxq7`>+f80UD$aRbKawgZuyYIf9$a0N!i+T8{|=ytjwAk8}gPRU*7?MHW-wjj{D3 z-~VO?xemO8{Y8t1Pt*s}SLf_e90zz;5HFTUfdkTO;bhep_2B*g_$^Yx0B^}h^-Z?`-lyWWeqC=s zfmd|A&1-7JpFxI2t$n6^R+O|1jZ1$Kcxr12KHl?`OJ7a5WxcPrgrh!;>Ex$RIOcSz zl=&It3l8|W+#mxpNar`(hVJZVd%OwHh8gn_d0ASYdc7r)NQ3vWkWL;9?=jMOUOc=L zoCLIy_y09KmQp`&Y2Kzm=?8fG)&2k9xGv!1J(R`eotZ2_QbFVHykF91eh43LDL;?XZ$wmCu6mE6J|yYnxAxAC zvB7_EK>9+HLe;A=`u%@xM5o<&H2W`aNlkmtkdJOY&GtU(;lxCU2Jc+gK@x`dv*~+y z@bKna^Gy%goS6CDf_lAW!E~MjPXONB58k@T*^*)L&7oI1!QR`PW4Q)m0PiEyyv8yC z-u+s|yoH9~apD@{$oD3Eyw8T^JXej7Bo(1?Sxy{sd8PPxmxU}#Yo261yem;3^z!pO zK&+dQ!+iBFb}`!VF@u5XZPdTLMr@S*=idBp8T0YI{ifc({r~@L)mT%5{$Gfu29SAznTQ@mS24f=g4ZU@pJDO8P0><2Zd;B4N$TXtmlZujV^fVOy8ZPENi z$O}?DJlu=N!5bvq6P!|6SHT8pAS|)g4!;K3l&n_aBJtN_aqsinI+p0**C3^!J4BzO zG9*^}C0n9CROsY)HQ{Z>tzXR7pxA;kmwjg$*g=w;8+s%7e?k9Geip)z53Q%-xdD>M z{=Xm%-o+0dQNJLCTyNoM6%xb4d&fyfPXzCN$_^^tDel`7vH{+DPv6;Efc^hkg1+32 z)_C~S5m*yBAnhHRsipyj*w#Ev?b5(-*yb&#f66cXPwdQ5ox>r$oLIjMjf0Op{gT#+ zf5c8q^}?sj+Y&5?w?67)8lC)3?tjhsNR@fK7vHd{PyI~)ddu&G%T1T|tz!EI$@hIA zLp~A?-tLdyg`EFS6rjQTM0MACta|GjJr}{l`=I2#bqLxkCpR4*v zSd!tNI?cu=cjDnL{)P$UcuQpNp~iIp@A!RUCE;_z;S(2|o{lu&;~i(EU&?_*2(CoI>o zJ>CS-YkZ9O;0cYo8JA04-r}dhyQqAK`hj$$dK+#m5yr!N&-`&$1n&f$HB`KRl&w{~ z0q|Bmc=(yDIT>!>`78D4E%16vnDrS^fVb3Xf8#8G_gvX%u4LJ8_{@5PM(30GcsD)g z6I#9CV_i8KSA0--a&{a(-nMi1)h%ixupHi3P#??b>^Q*UcLd4yfrS$v% zls!txd6yd49`DQk=aLxl0Xxi4GsvUj%}0ZGq5XL;ta=*@?i0epd$H&lCj{@3Vp}TS z^A6{}N6y|lCdtIk1e+5pQdb)%+>D1C%nvOS0(ig8-j?10@NS&om}Vgr4s*V~d8n@l zA8!ZS0u_NL+2$N*T!xi&ZC(^U-k#grf|E9!s$;de_nGB?eDrMl`}|6)a$7C;Fpqb) zoZ|gpB?kI`multk2iMsiZ-SKuV?K`CJU|X7{`>wPtNlOX|B?@wL5kDVpfg-MoBpan zqsG#BHK;A)%%Z!X2Awq#jX?VUl$kppDS;X^*5fcBI)@BT8+rfkVn;k&((!UGazWbW z{^!}VK@E!L+Zy^dI~>j$=CMS?J zx}rYl<>&UTW9s%M<{Kn?@521OCm5JPhBg+N5WCrb4YJ9RAs^YL6E5pYsY9$74c@2Q z-u$)yuRBPXj)!-wz1K_x?;o{0CgRyRdl}J!5?CeY<3z}HBe(Y zymz5K=;i0>BJ%lWKJ$3HUi~3uT}XchxpSdnT*j0&+YhmU36-&o_{gNp`2Oe!6>m`* zyvxcAPGQwMDXd2l5AP1SkGf7AarT-nVT zu|kFA@ODOh+@zD=6_{V=@nh!kp3M_QDwbtn2HE`~m(PIxm$wM1dl>TpmO6C*?Ej0< z;C;%S(t+Xq;d!nE9^Q*HeeWQ6Z?{#X;;px~GjavM+dfKNDaL{f@0WZ&EDZ2IuIHbO z-2c!2eJeo-;B7V%u(hE+91gnL{JofrKRMad`Y|lsS*$)7jayc}Yh9T>{^TUaQRqs+ zpd!oR?Th-@O((y;c^W#ViOl02ei^(1T1)@*7NJ=3mAYUz+gESGWvd=Wd<=isr+2!V zTD^s7@IGlouE6jX;MhD35AT3ZyBq{>jkq;Ck?MV{j>Fgw;GH4sswxAnw=9ZWwrxc_ z*qk`Yy8*fXzbRiri2(2p@qhQ~-nno%Z+^yRw?+7PQ~WFH?Iwik^U*l>vE)xgC49UM z6Fj=4%xAJ3-rG?hv+3mb!PeM+w1IiN1N#;{__~}v-UlCCDQJ!~W&7(btDjWmGvY(~ z8;CBN5`$E!h(!F+N^4Z79r9fs5(!?oj2 zw}BcIre7z-IURh1WVcV%M=-=XF0|`HKCvT|zq76h?EjC=N!ur7LxFEiy&`Vt#;-w7 zHqCC^a8IJX8I22ZO_=fUI(`k>*(#H8bcHI*)u8*Rj~#UKD;A$-eexgd|8MB^6FPXU zh3?K%Mcrcki4P8JKg8;*EMdsUSZm$QMCvDY6QyYIKHn?)3d8%=Jeiqzc#rXgEl2R? zAJ(NVv8zOy@AC(EUq~Ep)|x?v8>L^X3xodO?y_{=41jmRHZ8Lk0Phv;!!5Dj!(nn} z^1i+U_;?T8l+M?Vm8xHf#u?-H)mt#x^)1r?+xiV!THI-nkKdA(hSH z@FgpoUr$}}@qR^lwNaHvy8bd6xB8d7hWLDZyu0_-kCbfJV7cnuiTa?IpU56hZ@uTt z<8555s~~ZaKHeAFzB*c*ea`lH9~>QL$j6d&t;Fy9sK;9*Xz)Jk9QOgk`+7>IEFRu( zKCZ4q@NOy^r{aB(^NkzQ|7-86Rz08wUT@9Z{lXF89lGft2ht#I<8XqBph2q5X-m^N z5)Qw)Ud%g32OsaWi`)(BzohH2IP&52XgfZ9yz{pSpT6v^$#Qrnp+4y4w_A6eNXl>K zH%LXknPuI$K)*pE99k$qh<(NOc*pEDW5~ygO#Jr_tbDF;|%n!yAtEl)=Nh z&iMNjg7=bNpQ+1RC+;_>BCEG$vmDQ8=#t@Ca^eSeBbyT|e;r3wZ*8ospUePw?^JB& z?L80<`^U^&eDrUgw>;@8+n_EWQ;)^9We4{8OyO@%kT!n$;kuRe@GeAs(916~Q6}Q) zKX|=mUW4766l(_Xu23iXkD0N3|4%rl!jO-O$dp?_;PsY&_y1Y1-Tyx_0{y=nO%1v{ z+MV)O4Z5PFidTa!OlVC-J0QIR^>K+#e!7bb^a8gtKZCrVxBk+b)eJn4_NsZSQ;r(j53z(h#~Jf6`Ao-h zJ@x$m3>v&IU2OepgEarfureOrL7VQbK=7XGQrV8+EtPZDObFn8b+%iwC%8dcuU@}- z3LLTXH+k?}5#U|_HsVbZz4| zNJm1CEpcd$htmo|jwk@USE-0B$^&?tTAnU`l1PD#tvZjKRm8{pRf1RJ-sY$Tcu!?swcyxDf!|xsn)>+ze{%BNYpzM| zb+P&ZG*11hm8N13e)T@Q{r1!4o3w%yr0|^pzghe-Dhs^t?{FwZppj| zxMn|;-tYjwdXEwwJnXZYR*%IQb*ZF)hS6A$l>pA}0Gyc0|YsCdueZ@K#d;4Ny>aG)cI48LiO9P$D0 z|8I8U&PMPax(n^u0Px;K@;K0J76Ip-b=}(Y6n}^nCJ1(~6?j;ekH)p8Jq*&hj*s`C z7v(@~;%jqOs~;`D1*krH>Ex$d)XLvHi+Q}u91QhONVejZ3GDZAd#73L&bt$AKZBGt zWXwlrlW63Y2I>Z>0uA1^kyqof>fL^*LIV%)M&prC1n+^iQ$a}ej&i&x`WfIYzC`R{ zrXLxW4|^*}1TRR1?j8$6@D_UnTloOI9aJ|jtmch?>quMdty z$YCK5aQ^?6-tOxFZ&*v*5y88?(N5eK;QixQ%jn6U6j(D!5#>=G zfo#9L)hx@HkF{2dl=d8?R_~cKcwe3NpdG`T{C>F_9^Pb=oYx56#zMZ-$BEUKHB>DE zcwbl^vgD-`88&HlK3o8vw=5M=(ns(vH);6b2k=&?uimiPngUxI-+xp15`TFMo+j4i zC%{pU#X;vhmyKP+U*0Oc=so%TxG2lvZH)RTrjuWL-H-hB3z)Co7e-V<%H`=_PTV(I zdNk2@8rxUzI)?;?eB|&G&WVA`iU0Qh*z}Zz{}=TC>NGW|vFA-OR)d@tiW}h7pwsi> z?V3Oh@>V+LjtsF*ZxtIBf*GW}y|8a)BpLp6IK0^f?Ek|HF7+Ta=+G#?-WpJYK4{)} zr8j36tg1aPU_<8?+@WEs>(0i9&lE|TXj~Pnl*ilQjvMb@{qV+%Z3gwM_M6^@`dCjV zzl}Gy*QtFJ$MuKjYiNezC)npM{Xf@U+&g>L7~9t%f;MA5M%H|K+Z|1vL8{Tzz?eesHa=YN1+NP^JZsOxzykg^}E0vO@Tr_Th*3YA*XVaHW%<+vXm1?p0FsG5sH$JC@g;-=cGm?w>2H+U>KsFOKbJkYhh$81nIbWO%%> zEf3isRi(kZA#%xIc)#R7I|~o*67ATp2;L8uZ=-%7t@d(n)MkLU^|zvJG6>#r=j}Ve z46^*_k|zk>e!;J@*8#jkrqs{>xD)|*MQ*B|a>8G|eH!)q%A+z~QV$yEAHPq;bm2PO z|BQkqFC}(MNwZw_?m>Ns(8(`vQbTy36Z6&krZva><2>{mq?cYR-;M`{vOV5sa>xw% zXz=PVz7|hykW^^!zTwedgjMg@rQy1Gcn^CezDFKNH||*Jk4#P;Gzs@40lZBz6tnI| zkYRzfqdL~0{~w(b^9aHF-es;%cYwF!y>K_hq6j#my>E4~1wP(SdhEf09 zuT(bb;NzX?s4Nhw%FA+i_n|(r=;ZgoAkC^ip85X2e?`)CYaRN>TL^9kqn5qf#`bu} zm}N5LBTV0XzHUBsa-vLw_jPgO1`Kb#wM%sH@PthBWi1Sd#2510t6gBrA~U#8Ru)S&vWvRB%c?}7*9 zm*gdV!EcaO3O<>!tIUuzg2u&Fd?~8>fZrf}IkO_#4PMA{L#zYpgI<1jewFlEOHRX` zA>+ZrOZf5Rp*{oq{~TvbH}C9Y`x+GU>@-6@j&016*`!7tVzp`TzEe>A8^gP|_Sqaf zybtJbiZ=qh`*X5f5xjMh)=3!xycZ2Vx#*Nah9^l`hP6%cu%P`FS2cjQxrF8#7~uW> zo#)~n(k{4>Z`PnyKR(`-!`GC%|JS0y`?jy%U*G@R z_aJvR9^MK{O)C(*S5;)VA$Tv_yXgXgxAP>tbJbolEFtaaY0wxCd&(a^t_twhZdw~| z2k@Q~o7P!vvI{QDxOe|Y4?fg=f15?BK;yO%6vxgy!pA#S)s@q7u{q1(jrrI^ zCqJhjO3sCe%;Wt&)M?(~ZS;4L2-ZJ4Up=s4d%Ot)zZml&m@cmN=YX^(4c^Vht7c-= z`);nU5gy(gW`{EoypLs-u0imYReO+Z1n?IAAXVH5mbWyUzHe}8h==>``Sv3XlBVGX zq8q^5r*BO}mE|s2dBgB7%Rzj+XKs?5x&M_mNezvwh^CBKzQV_QTw0g2*xZ!m@Wy<6 zqLbeS7qQGD3+D0GeBCiJ^_YJ3zIZ$I$FBoR*?w{&D9M-)gZkqtt7EB?6Ac=?Z;1*N zVt7x?v@yiPyZ6>fD&CZC=I}n36jzbt6bXNb9&>T{ir@d2_A0;+_NkLb&^TB{d#g`B ze*b^H{I-n4@3}08H|FC8o&1j5n*A0eF^@O@nOeVhpBSj#{FJxyGyWHRy+t>iF&}3> ziYS2U{qO!iUf0G#e;>>s4QOgmNAD2zfi!vWiJj+H+z5CzD0cDCDP)L!ZpFVA8Df2& ze)UlYL+pjzifhq3$na3dK$$c6f|QlMwvR3tVkJ*C%iZQ|hpVOs{}>yMfHMWodGn^? z*Pvc_iXd2RL^^`T?bA}7Z54rEgDip*DXEr=Sgr=WMtv-#lOI?0E3aAw=68@hB%aOb zJVn3%kEwmQvb2W%@Bhav8DPjqh^u%YxsW=<>eJwT@1V*iY=|A)e%lle@1viLd=b2V zt(c@XNJ=N)j%Wb9lM|oKa*8IyQnG7rEC+apRxLKs0eFk{iKKM`yqEN4)WtrEfGZuv zW4>;~$NTxJIo~hLm`%Ej#_?3FF->#F$Gfb?aZhV0>*3vr`Z!G|zekR_60_Wy$9u;G zqu7Ne4B#!3wIw$)o$Y6k7ITXj@^Lgcbu6cXinksO-tBA7Ex_=WX-=Duhqq~kr#ynU zp;sGqdFyKCM6VXW`+J?k{?G(6yy=9lt0lm@OhTTZ4e;LiNV#?t;C=L()Ha(Z5pYKT zyPA#=e7wukzOQy%F`JZ)#*Gfn`W)qfk2lAC2c_9BSP${CbaGACgvMeg=6h zG;qU~JO(aEr^xEQeA>_UcoWj)81r%WvoHGo|1283+cbksFudVU-X?f>?>bS~j%-f2 zi0-9sPV60g7px2LmLKt2F+Y?AGT%fja$U0w)TY|KHeiIY-Dy;u^!$(P#^U2+te>|)8;kv)%)OD zx1yX7`VG>R6ZdX&&TwY?<*n0O9x&uXsJl4g5V#->=H9wAc;DsmI)mXIl5RQ=5AT~r zDJ2Nrb<1A4Aan2a@t;V@-kY^m&_#};WO!cGmIbqJ$HTWLYwMA{H$w6vS9O5*i{y{t zEjJ?JAkyh+avSlNw=UZ>u8O>7L<&XY4$RdPyzYX(yw#bn^ssq3>*0L`^+7K`XTFRR zdp(%1-hpe5%IiF3;O(uQyE?x(yRd)tj*Dc>hv6Nk=U)Hz|18wyO63=(_Y-WZ0Qg>EK-O4HCcP z!Z%3&f3o!iXC0V9N_^HmE1OP%our|-7!CX@cCtN>#~dbRk=)R@M;EjUZ}H<_vD4SN zChTp&dOJv%k2!Sm8_(GKy>%1wXOR56c5GS_&%g|l=hr*q0#EjTgJiD!C__GY16HC> z?98FT`*D0gBZl`+UR5F<-d!qR79x1x7}`$7n;cp8egNQoWPgXYDfs^1jMJ;gac%MN zYr`VKEP%JRi(^U+!28{`h`|ws2>3~jZTS5w_;_oF<}99q^+}y*oWJvjt>p#yc)!#z zp0PNV#B$49n2%mM`IXE%uvt=%dAtqFW;Y~WrGLaOrtVzcYr+?{$2&&I>;xk|7AHI0 z=qRAhAZOFy{b=RNa18IU@Q+-0cqei==plIT8djy^{iW74XB^;d663(P8a!`V=ajE< z@oqePIKLCY0qLg=<(B#QcyCx_^IF!?fE0tq&3vMHa8Eow z-h;=QzW(TiSq^V+)W-;&{OpO^Wo0{<$9s!rgn#x22Jo&LcwAQD#r88ui_PN<`S@PD zjl=L16>lRNydTO*|5d&BRMc?d;VtUWEsfya71h2DX^@)zLi>LKye&2@c3!dqOirXv zhc$!u|90H0g%P}ezR}!!8Q^`5tlfAIyfKuB4|iTN8{#?2rWC9 zgpc>m^Q4%FV%9soRfGDV(8=#e*52@V7v>wJvmUnovXb;yZwdS(N3x&>w#S>0Ju8(V zAL;FdNB=xdWJrVe{crnAuBB1~0O%54~aVNvQ zw}sp)TH@iLWiDO_-hm$%f4YcFPKtjoFA|A>XXjK{E;xmccM~7SdfBIjBvUl*=KS`s z`>FVNKd>8r@FIZq&feZaeLSR-pHGadzCsT3%Uf#BKQ}BoMgR2{1J^c(UCQQczr5xB zOnU(%K9aM4ChppG@ZbG^{H~jIeggV`Q<@soRXKbXt3hTO%LMUiP_eYPEpo-qPUQMV zWQa{T|I_R|s6mSp8{{fTWcb}@%VsaI#Qr!V+*J$IpsR%h@gJZDeVCs+O}mW(H&hds z4tV3&Ac}wE4iY$n)QrY$70OnOx52MLM;86gU;2yn&LBmiJ__jM$20U}8h0!6Z;&Xa zS8ojqr+>tbptR#)=EUkttOMRZ%;ffo8b*9r+-`9mJx85E&Zoh<7o;o7IjI+4eS1VgNoNU$NYLHcIlrobV9 z_wZ)_1Bz7?_}SG1k&A5c@s64}PmasgB)vrAWO%mLF4V)v+dMC9-59qC%QZ+bs1Hjz z`NePD@~z+>yddS!K3J-@j{XkPae0pYQqb@SZZ0*@)nsDk`@Dsov>x3|9C6ye$;>m?nYcEuF7>^nF2t)RVGV6gl2f z-l?$QCBVD;ZtI0@=O{2V23zf4ijQ|+{~)LKL2VK*8khGh&||j_KHixo?WfO<&u2Nj z`%xb`bn+{{K9*|j%6$KSyzPBe+(iaaU~_Vc`Wc+a)&eSXPoGagdF-g6C6wyzLEFOqXm} zz;bwFJ{;-f7u1#>KB2%o-rZ%pe{|iWKRJmB*4}cwMUn0M|ClM$Z}|-PsCDhVWb@~6 zqA?BLPrFwNV|X9!r10S3y(Yhzy7#sulDWON#7JZHhdU$S4L8k89!cOIZ<#)yf9hz^ zERr7@x9n4f!SkQ^c&nzCO?K9ru^ir*4{bX6=@&K5@eX7j?_F_sG+X-VPfo}dAC~dG zwPX9u2|wFx7e;)DmG3TrQ~tgG{|`Hy|Lz|H{Xa}ogI?!LhG8|xUJDk-t3eN^UD}Pz zAor#1q0S(+rhadW0&kE$+0tk4>`R7;l)&3WaQ}b#Qte6P43elj$9olU21#s<>^#00 z3jD+Rj^SfT{2?}E`?=JMElQ-{Xx#O&7)PH;{5MEHy$g9A=5EMxH7FGIF-a#s?y0); zc5mj_ATLZvx^Pv|UxOTwyL3(KkkjS=E?ocb|7{bqM;P)^y_C|wGm83x6p04!UcW5r zCw7tk-|Hry7#`kNJ)Tz~cyB%L;Egm$!Am}U^9OkEPf1c6@Fc_G>5o2<0N&*C#zh(c z?_H}GOvnSg6RRI>w=$=|lfJ_rLhj=~v0JTY{ODb~66qHjH+-t*okt};-n$Q*-a6pL zdU#_#_R`6(XzBTx#)p_6Vl7%Ye@?4pU z`;}#TDOSCe*1r+K!`sng%?AYU>Gej`@he~SUYJJ?A$YrP{G?lOAj)&}q%x9{yi z@V;62ElL95y}e-m+n?MN__cn{%ibJ(yrcU~g_UZRNdsuy%s!%QbT~fVZ@0*cYuFmG z+~j08>f=3~{5Ge2akZ9UesVJQX5v+E4*mY0(Bl8}^{E!N$D5$Kk1-!Yvwd>@?Ef#I z!TaUN5iJbw*qR6-JiIl^K5j(tc0Xa{i%d>RE&a5)0p7QRuP54WzG>!D`T`vVk;S4H}j?un}2euWlNmo*?a9 z^8`KyYLFx0@(|}?GAyWKKJVncc=)|n0~c}z$@8J@cjSnj??=^yjm8u>x>2BNO$&Yv zdPm6Sd;d+9v>S~};HxVCS%zPO1TV~+xs5W1;-uDYx(<_wuHmE zRZ2F8*WlwFp{Zrp=%zx-L*s0)ToA!ce3yPm9KSK5AW-!k92zZeb_yrJ-|HP zv+BHp@-8!QIgwnT{QkfUw#S=Lki(b{6Db{?KgU}vXz+eBSR{wxz0n|i8Xn%m5_%*A zZ|B<0UP$#G;%wcP0Px-$KAtr{gbb(lEaqGX&fa!pMw=o1|MaKc(}h6)-ymS##}!C{ z^GrW`x^v<0y=`Bgw=wmD5~%=<^RMrDzoQQy?@5(M92vVg|Z4nkSa{hM)8D5-si_;cdke=MK{w;F< z|LH2N##%7M#%z%@Ge1v(moo5}VK(u27+4EbnE;8dvj^Tdud z4c^0RwEnt5dgsBU93I|x)PiCVyn`EqsK;BP4(t=-0C-2Pc#wY!ydV{;<7;^h;4N7o zGE9BmGDY_#a{u2ZL~ec20Se4({eE7l3O?RGYbpcYg5@oKG;T=ouH!mx{3CXAH6+5L zSa5j@^I=LSKj+Wer1ChJzd<^=%sKzJJOeXGH_a_cTl3f+Z-SI6V?ItdTcOWeETzGF zNPqrGta>+B-JF4k_d>myItboxb;PMN$R~u^w+6rrGPp9}`I&>DK?;g4Sqhf7w1-{4 zAb95}<%}Tr|F=dz-qWrU0k69CLoK`xAMe*Yg*anm)JaZgoT`lF^wA=Gyian^3AV{( zz1v%uk2Cc0ljOTFag+J#t$87O`n5*-`~L(1`=@I(wAgU3BZ5AR6<|2AZKYoTcdb$Kh(@?QUKfOpE4(64pi<3t;y)2s#n-mYE5 zp9tQ1PwXeJ0K78~Iq1EWkAQP?8gGPL#>d;gINNnusX8eijoX))75pF%AMar~ZdH|C>a%;UX2%Ey^-hyLm2X3U58FO6JqyoDchvah(V6GX;E-ikaCxh-;4q+BFVBuyk%Bt&GR$Z8Q=5i=1z z5k(Pk5lDDKctH4t@Ll10;d8=;!Uu)-3hxvS5MC>6FKi^NDl8?;EA(AxNT^$=L#RRM zf>4Q2w$Of|NTEO>4kX}qz#A-o%TSM%EPn(^xKD)Nf+LOc^Z13WKy?()?0 zoZ~6vImok@XD3ep&srXP9t$2L9#tMG9$xP6+(X>m+#TEv+!we@xU;$Ub4PLqa(i$) za4+UI=GNqvUA1jNlX$@PJ&i>saMx?qgpHbHMeXF+R0Q$bxp zc|lP@PJzz?{Q}PfS_EnZDg+7yG6ePrgbDZwxCz(^kOT|_lm#RNxcMjfKk#?)xAR{Y zw&1GdI>D92mB2;e+RWw7Mdn(>HHS-`OPY(HbBc3>^A+a<&PL9QoF_Sta3*s`aRzgG zaXNA?;WXjY=9J?U{?Bp-N9BM1`rp4|{ojBP7dPkhA|a;@@e7X;bui^+*m0bwjVX_b z@{L3-Os#)#Y(G&GQ|@IP=|l}ot=kwlL{!Jr+J)yRL^VvU5$5zJs$$BuJM%D61yid_ zvm1!Ym~z>vai6G!Dd%-(&WfvFXmAq$DJm|Ff_wTdW%DZ8tmBZ$(NS{66HoCsFd|NNG09e3;|N@2=IU!tBU zi79J+hpR*hOf9+lWDRi|rmPO9ni9n^wRi)+8Bq*Vma{DCiK3WVB%>fs6v325+tz%d zFs9&wm)D3wm?Gt_TuT(hl)3S~RYU9{ zru6!=0-@iSnpKlO2>rs8?*6i^&`(V1tQjnTrZA=bSg{8Bfho<=s}0b1OldSFr$XN_ zrJhPS0!?B{&BM|S`id!4y9jA$0#nLAbTXhXm{NKieir(SDaE{!nb0RpDTKz#L*tl| zH@B;SK4NO7aM%iH3{x|nt%9LZOv&c;ia{fok_q})2MuFN+VZX@G=!c^DGz^;W*AEtyGCP>g*ObMM{ zAOO9=lwd;281x!b0=gHbLA{vb=lPTgy}}f4^Kd29gDIX94P{U_rnq;y4?!<6MV#X| z1$AKxB06k?Ix)rB8FCSN@t2aZxeh(Y6k#W~5A+OGj=vXG`an-H^-C`C0rUh@Q_s#c zLXR=^qdI62^axYmx9xoiJ;c;EE15aa158bNmrFtSF*Wh_F(1@{sV~>GmO%F~^?84w zA=HkkPfqK*p*Bp7YyF6V?qcer!1IStE2c(o4{AUym_pXup*xsDmM5Xxm_k-_pk_=V z%`bEdQ%J7>HDL-lwFfm~3OVEi-NY1fCIo806taa5-M|#G;|N{H6ms_ux`rv_suWa@ zDdc7eREH_#AU;%!DdgNTRD&tx1tI7vrjQ3$pevX{-lu>rV+y&>4_(3(a{C#&h$-Y9 zVyGHZ$g{1`1xz8YTtZctLLLQ#Dlvt;p$47D6!JAA=p3eykH0`?F@=091FFCj@@WC+ z45pBm*r9S%IqknJ{G4cqsl<$!tHfoPN>~xyu6>$-!cAXsAKwOBaNN>qS zL<>wsIIiF)!kD6Pe(5KYFtxMi<{hFrrgogQTuU^=RM_qo5^({hLTxjOh^Ckd;om$# zoR6t(U*k21CYaj#XmkT{9;SkKjO!DPF%{(gNt!qpQ-KmkRETphwT0hrDRDNYHeJbF zPBg+)K)TmHq9LaIH;0W74KU@W=$S**$CR(&&M=}LrhNK4b%?Vt<$X9|B~ceuj>s3T zq0^W`J_rnzVG8+vDs&1{$mb@ZlbAxj&IgrZsC?8Wb)?e+RJWO4k_Mja)hN;V= z-6>EmrY>D!f%EnaXm#5j#VN9Lx6@3L|Vd~tm zL{I1trp`LYeSi*Ps$#A(AC!ryGh92HpbSi%ZhI39rDLkB%-|H1hN)BTlny8rQzwnc z6;KMMN;!RhLI+Uglr-?gi?|&7S@DBMVNf!rPE>cThmtT=R6b-4?Z;H1{dq4a5mU!S z4NpS}n9A==4Tkn%Dz8M$7TSxcVfN z0-|6lRfkXxg=6Z#uLYsdPD~}YiOE4bFqM?`H5LlP)c#!S04NkwiKgn&Pza_HWIElU z?U>s8pw$f8hN<|%2R+bMOznw3oe2eFDh?Lahk`H_D|%xu6!`D=|5(4rBY^#Xdzv*! zWLAT%L8^w#RK;6^G*~-L61jtag4r`#9>ul}>&~W{6}THeh}SY4D2$spLKV{eQyV38LMVH1=PEtej%VM*!b( z?RCegOYF;O@J6QT7~W;8zbfP5Eh~12iuY{j0Tu7?anYZbkqy#&*Dmb@*ISYb`vWoo z-fMP$ia?Iol|OcWi+n-K|J|9zH?1jff>d0Tz)O6*E%t=+oJ^QWN=D;2_K%DY)#2kU zdYrFf_G4X^!`l+|Ax$U0^d_eg-U;UM4!V^ok`>qj(<`J8$@0A&*5YixgVdz0!jKO) z1@A>O_fem>u%p2n={qsJ6Q0~q!o$0H`&TO7KkhxG;_VtVpxgrR7S`;PkIDiMq{m24 zzyNP~pTlv;0cq_=vLc_s2I=&%1D@|h!TtXON(oPj@bTWdKxfC8n*wP!8pr4Ku5Wc5 zKHf2hPoCeBtH*M9hoC+Z>E!p~9^d(CI?Us(YUD5N-c0`nDM4c1m8-rp*&c6#8Dlo}b8{y?-JcCfDuS`78k+?^`Rw;(oO%l2)N{6$%F2 zmwoZ^COyk|IqqY?a(FkRJ}l|vr}1UMjGoWT<9#Viw2<7 z;>`f><#UoNk;{o68;|eo0C>+6PuR6?ARM0GW|-|v!N>a?_!70bq%vs%8s|Pqx!AiJ zA8#K^g;DQP);s@y9`zAGC%=f2yWd^)na4YJSU+~~H2wYmm}-h->UbvG<4p);%*XTb z)CrsVf6xEZo3ygT&q4pcilzo3dm~s4YIr$K8?Od!T&Ny~46!~+Yp8FKL1I4^>mekA^#AAH6%kdD2I;NfA*teUI3z#kt>0Yy8pQcBK_U5y z6lo_K=Wry^*+3k>24!(*C5Gy&v)m9%M135gli%nE<8*5w=4(*+ro$aIjtm@-PBRMg z=D*JVFGzP8Fy@1QWv=$0D|QYvcq5yA7~XLBTTMK?yU$H{Ab6V(KvcX(-|zI@3GkLy z_CJyh@NO?My`9<=4;M&R7$bQ5$tmno1b9E+UQXN+6%HTU{Paz`5I){-&B>zQ-c2VR zN8=VeELvOm-VL|UU83^r=>=yEmczRr^`G$~EoGU$Nt_uBn@xq>uNbsf;yW zN01k!qJ>l)5WJVhym%xB@Q$^p*{iT49KN;w!pl|M_;{Cmp%ltV z$&l`%aZh{oxPJ8FRb}A)|GLK+ zW}FMz9&f@*27MH)+phAbdXs7JMvh}(cpEK_R>#BJ_vJMM1n(JpEvR@qLt^6x0p7}r z0k7_Z&52QUgYdcF{{NetjR6SWvAbUiAkSOYb?bd!@--a(6c|9sO2o(8*4szzzP&7I z5{)zX*ytYUhd(*FKRL(ubA=Ym;cbWdctR(?BRS_RQ(rS*z0Y4ZTbHw!fz64@*GFGG zZ(x7C^BMC|W`Ffmej0UoYXuG7$oV1+?-N&+tKs2IY2l)--n#5$Ztv}s@B7DfQWQ9L zm2_XnDSW&G`8hua+07s&pm77?&wRHh;^XbDHkgxKqRn!62cteV(aA5tN%+@}+00jO z_swEyfj=3j-a0Q2cll0df4uMYG33KlPTdR!tGEB||FcAg|My9N{(tp0&$Pjy~ z&*JBFFvPn4w!Zl$CLBKWlk(J66u$;7i!3xWIz63q1dR)*R$e-12!93{bM}@hWd`dt zNXtm2h#Z2Yf>l}h{RH%Np5PNk|)IrgtXzeE`Gq4us>`p*o~2yV#E%-yMLze4mj$AdC z8)73-AC7eLn}T~CvbQmh_jH%tt&{iZ?;sI)BWJAAJk9=id&e;3qjCOL$xq;k9Z`*i`uz@^PZ< z)dt^@j}v8Yo9TsooalFPrbTp9I9$=rm6q#_kN3^qb-MSGBuJHL+`|ip-1O(*<9$QI zgl|%q_3&;&eKgU@FCcoL)-!_n>Ro*dzPGxL{st-Gu5Z{8HAS|^oA8w}ANI$JWHbLf zPUJ{~H*!k}!@Ko{y$&AU>d?tV1n;u&GV11pUBR`-8v)+k8P9dJj*#J+bW2a48}V@5 zsbAj^ygPIgf;0f$NlVyUo|L;-x#k3-MHE!d?-za z7a`3=A$W&+ zOh1M^kUqZbamVc4WcY;ejn8YEX@-~psTA_tg~Mry)gzn{|H zkL>XA-mSrJxlu)yv>A;%zPyp7qK#j@Z`h_Q)bC-v{r^3vkDGMzt607N(9}QJocO)q zeDH;2@)-2N=jf#WXLG`p7H{y@35Iv{4GTj&yx$AeK0%(h{GES= z`n=`+OGiCAz~;p3fl;p;;Oi~^u_giPPvYU#Uq(%k)myiak|5;smKpoQ4llbL4$Je| zte3UH$Ggi#hJ!LJO;SPQQj7x*u2RRx+jyU^mZ~%Bo!;t3eaxeiU+4MLtA721>b))? zp`~|_e*eFL+^&$2BFgsFo15~KAs=F0RddcA`nUgQkq-aw(*XUy7flU9UVB1nkOKHX z`f49H0$vR=OpBl(4btkoL~4WdV|a$4=TAR^)Szb- zU5|J{4e~85wEs3mfo~t_TVHz!{|!>f)x4)9W?wgNLgR9#WpMID;J-myo>zMIPU*e6 zzc>5e|LGCb$LjpQ&+lICMuR|C=68_NZZ4k~SwsJcUBVIlz-`e%Y+r*2d&C*?@vHH9 zXM72D2I)zIH}ZTLHpC9xZ8pWj`;4f|H3V6hhQB@C_K`MoFo=49AxAlB)sJ=ykTcmUw)!p&&J`ixYA?I+d`E4{VX}L&%%p!ce zrQ>HQ{2Xm%IlK>ULVeK5Z`JpAQG$n<$NQAm`lA!I^c$q?!%rjblU}er-X+tT81f-1 zylF}0pA)1WG6`@m|5D1M zs#9I@aFFHaYNY>PcV=<}(*Ga5mO0FEoC4ck^tiis9zNa$7Fi9^mmitipm95nr$0%Q z#mD;$K_^br>@CaT{TlVrNhiOF)|=Bc9x{)2N5vXXv)lA%kOaLT#kBA@Y>zi#PatDH zPIKJiHG!*{?bJa$A;W1L z*LySp-jq&0LuB=~oHR1&0PyxmUE^C97Xgd7q<39c*o=D{>$Aaw+bwb*&9S&o7DKN# z@~*>;*BRdzY+g-Zxz$_9@Q;sqbn<)V4DD=5V;=9yTSMztjkemP+k z6KEVUT%v4;I6mG-#HV?@4VGXzykDa}3h3mQI$@`K_p2m*O#kBb&tG^eZZDR1Xs7$< z7S4z9%=am@L=DuSsl$$?$P&Bb z{Y{%!zN5fze^2W=5RE^B97(eHvRL@0ITp7{%zwJ2H~tJVwQ=IufxHJSH-mIf{^O&Q zPJZ4ET~AAtm>*(=^XmFMY8f~n?Y{0^)^snnuR#RqO$_;1#6Rtj2RMTS@ZLy+H}VKN zhIdw`A`uVolBRn_2;MQtbEtT~JN=_u5Dc--3OCEI1(V^Pq}7XK0N#s;VL?d$f1r8Q zYgvGI`y&Z$v7C+$2{H+U2k5*e4vlFVE4ecyYsr)9`B3SzA@y(_T}EIKJnB8(mphJBd_{n zc!vlKbK&8gXfPIs;9Zw}p1OKFxFFI`7vL@aczC>I2N`y7)!-!pyjy2WSRkvnYp(`@ zSFzjSXL_@HUM5lCohmgky-N6auh=Vj_1CN}^Brj1$K9FLju1ZHc}h3te%mw1a@G3) z>Z6HHey^%SpFRBt_y3pQ^{>pxq`$mHAiJ1VsP?fv-Z8hF81k{R>R78>F|~So)8LJK zrUJuztwIea9^RMYG(8c#H`Xds@qW-9-0B4IzMFCRYZEw}xXFI&yY1ca@Mz9MY2@|R zIiEgG{00xCxh$7+Nr|Jt>RXmXxXa+_5nq7dUAby+0Mh>xMovbj0K6^aWM1t^B*Q#~TH&|A=7iZ= z+wTb8dxL*Aegt^SS`4_a%Amj>{Rd7(YvSWQ$z$U;%j~}S2pU%uI!9Sa0Kaw86@%W2Q?~*+gT%2+{YLDkaCnny6g!A#Cazfm_ZhV zp1+(o#QrsC+JhoSeB7z}rc?fBiG33d-pHraFuZfiB?R#BZqiYcM^2Dx-1+mo#lo3- zd#?e!DcxI+ow6sxgKq{GIsv@pMvM0$cvn@$h9docgX9Grt=e#SVzg35b2&cVyWAE} z=)UG7eMRH0iEN|z{>=$euJUD@eXV3z4(~mv4?a5ine(aUXE!sCcMJDP4*_NRc$c{t z*0kpMuziEH#4_RnBR*zW7Bu8@F~1Lw9dJKOr}g5+B3ieHYOohLNAV=f#)Y|HbRA_}4d*N8ZtJKzh7>xN|6u>G8&W zc6myZj!3pZi$C-K5GuUkk6lvmJ~eZe6AkaLcrG9KdQ0i_EcyQb`k=yfJpgacCP-tc z8v$y%w!vf(*xnlHQ*MKY6VLbBTu=gdrz8YK4adYnzg5lI@SNy)m*4P?J#9Z~PKnFr zd9m^S2>RnhJR=Wvyl;MGxCW^O(IJhI-`h-%^V@srcki$Ufxb8z4oHV)CT@5{{LS=u zSB?GhqD99~qA8)hnC#xcRCvQ*Z>8YvzdC~h4R2%r#lmp^Usd=v1g^cmXc-CK2YAQN z*#GwMAwa~oocAYSyjwM0V7%L;ISn)c-U=rPJX*w9h}6?ul+A^X_du8}YgYS-mR2P0 zl>WjkI-}@#O9_g#mr6F8|KE+p|Nc)p8~^B-n*ZznbDfVxf3JG!N3uEG+8) z9@JfM-WB$s8In`=4DcYF@OrmHCkfE!VyhNDa6$UMDf=l+;6d)Bs+lUV2l;IHyx*hE zL})|E3x8WK^gYOgIZHm46fD9AAaM#S+wO3@N3S5u-x?lm6{tUZ5|r`wa$H)%q*oiAY?IUXuEBJ38Ld1@7u_8yB{zOmEt+(cz15vJaf^)iCMvuo z2Am-Z-VgML=Aq#|u|Yf;#+wW0bSm#sZD8T#oVd?5}aQ>g`puUGJI6*3E+7b$X zAgwMx`^6K0_j$cy4~Zp2XeVhI7uOARyrb}oAK@3u;ggWKdp)ypR@LZubARhhKX!)k zK9IH<(ZP$6U$CEhE{TQy3R08(Hb?tG8Y)OO>E5MpRx>@`xbs@H>EN)|=lj$DM^ND{ zUi?CUg7;g~U#k1>5Z3-TS5p>jPIa*Bsl;7h;^hM z9*{nsGU=QGcwcc)&C?hnLTfjN%9?IRFHWpf(6+i4@jM>S8uHo zX1uSrE=P2@V&r#Wp`pU)HTvDVLClHk;|uK5Te!qrKM(mE%#U}`ZJKoOhxJO|__KQ( zPKEcvO1UKEKFFep5wKt#v8#UJNzBcJi`rs%-R@1?-mu)0h1 zTlpC*#KZ(RuRk8Nlsh~GVw?o~2;D?PEt~jCSz{-z5Qu|Xrk$$|5 zZs!Sy^wZG)f2!yYkr`%wyh$f$(y^lCeJcM+vU^8U;VrXumox?M&);K((C~InHGp8e zOO8seh28s>(np)Q0B`-ebCtX;1c+bOaGw!)z199_n4vbn`?9pj>wN(4u5arC4>l1Y z-!;LPE;yp&?YHw${_hfHygw3$&nHyqEJ4Rxw>T>7^?XBy!<(W*4<8Mrc(ib`~Uy#)}E&SKIs4Bs60rmU-qB* zKdx0%8qI@hia&6|9%LzL>H>R^YKBJ}>_Mr8R(+&11ZWNSyj^{uLGpTU2*GENye4XY zYlHq@-_KMbONj_sPqDrhY(lRf_Xj*Z=iRM}w?X3WHl=cR=A&1TdnEbgG_@G7f;@oe z$i&Fcnzxu3GCLphEs_8HJ57vpm3JDz?*DOj9{Ifeevj!r2nX$4Pm2zxZ>6pA$H+@8 zkqU2>Pfb@SOKe=ilq4G7Q%kzNV7w16IzV1xEepoR*#X{KS@+L(UL-)u3pKuofbFe2 zZX!W2-ko_~YVZ*|){5U55cvL|{D_X<#eL{_Yk!)rY^14*S3=?>`j0xV4MWF!)d5r7 zm0ZTFAaxKO4jB2J`7zm`X- zl#F*Q72e97d-qfD_K&_UfrfWdonRx3_rV-?a{uqu&HoW@kd#ta$`&^hpxb46+#vvO zJ%jW6VZ0lSv>-KrcWlx5BR_{@q15{7uaCE&<1MKg+p-V_}_G4kUX+_$LNjDEZg#%2dfpU}|%A8Oy>v+4@-p1iZ9kPkgy%>pOK1%3#hsN-^)vQ#-KS1IfVjD&;aH9AB<+(OR zJI^v6-V_~W82P1I2pX7i(%=7AOt9rw$zb>YAHF^Kn!oo6)7Rcbaa!MK(a~YCD8VcD zZ~y5J{eP}JUS=impvT&2 z0&8;#5T|0O#GU>W=<>ITGq4A3=6L%WZjeqL2%Q}R{eQ{DZ-?UlrT@>o`8JWGUmahD z#D%#_WoQx z49OrpNu7+RO~;3RW8FU$Lpx`~i@<|>I?{dhg1IC-(a3LA*L9JF33xIdv ztt%Hb!TJ9O0Ubs%;0sbWR1*%sc$=2_vccP18JxFypOq0IxkG%oaAWi(*18I}xUxeX zuYkl&hR5hHmPB7-Ma!R6ZkAv?yq6(5u<~nqwT$offAK)t{hw`V+MP6f-a_K(-qzyu zMtVqM$XLhgH0fCV*3v%t47vYLpu$`8a>;uN-fA}Oa%gzV3rx1bcqdl~knx_Ub~iu| z;9b;yv+q_h_<~f7)8le5L2?=?4Ttf*YTm1@1Mucab5dWIM1;2Gs3uB^qT_wEUnMJe zk2*dEi96$04)Om$ckh$ujwxonG+{XRE$RF-CM|we)mpt(R-rrjg9xJFTDpg z#D8XbyxUmXY0|+{Ab0m^1{v=iRCsG-)hK6l3kSEij8wCi!FX%>+K1@^yg62E7MI%sPH*|HOV9k5%ZdClR|@py z)bScf+{EkQ!z%xBIWei)w(@yAf=^mtnjWzsx$rwf6`MA&>*$ zop3L$ z)$qAU+$uJ48H?BG?p-wC9!I>(c(b>Sh>k*x{Em&kC{Mpl|Mr&bsW*0GlGy#fN^k=U zJNtE}@Bbfkd$7@>!?or3_QABj{Xat%nE#m+=>OTNJjh@k%Lj@F^?VRiL-Qcn-ycfh z3DQ_?3HgYf_Z%LRZNP)3bId(6&l8|QZ&lKGZwe$G809AqJV;q7Tq_iK(7T;Ui%olp zkYQLw&@+E@4>H}$yZS|=3f>rrTe3|=>#Qw$gY;%W)KLiq#@mCmLUdr|$HV)ud9s84 zC3gK&kNHwj-I(VFl=fGRw13>l^cCdoi%KtP(Q!N3?CI2A_<{6HHY&XJpQ(0H@YX6B zRYAl1cEYwO7;l~QLGt{+Okc1e65!1;Px#$#u*626NMyITl>+@X9{Ar zduCC=(jR+?kOIfCaV`aPyzlv0X87Gv#V$ZA_0h?o}yGI_kX~q(6~AZ<)zTh4;c}yh&zMf8;OuQ=fS{Q96H{2uCw)9-%`VCA#oc&x^d1MMz0_TuZleG*I>K`=>ehx zD?g4+7h|8Equ;$#)>IBVe#OSy>HJ|K(N^YfkfNl^Y0`16hC{$%7umg8sPNW{8w;S| zy(1%02@P)xkw|tJ@7ISE$cGavq9Rh(1H6s;lSS(a2@v7(>B_x#Q=p1u_YW}Mou^;2 znFGArOe{`7&P3>I%z-m6U!xyyQDi@vA-PK(KZV2zd}Z~lyN-_cO66qJ%}*E)Z&gGG zR(_Agg%&-3MZbHSx!X5Qm1Fn+iP71vM&jd4@7{@(2WZlfqWFA({f~Rkp~72t#bh4^ zZ-s}e7NOx?eeie}-2b1trbOP}O4X3~;0*94oZH1OmrZ~q+vauG-3PC?NEh6K`~NJ3 zrU4CrH~zjTx9vJ2G^>)sV(=9m?}<=V{tJ!jcox+^acVIgNA3I3@qQ?>!tKg@#v4vd zB02^z@-y+gF7K~GzkAp3_J3nphJ85k$gbB(kE}j1{p^i*?GQ~mt{qm5)ZUZ)_x}HX z_S%g2GiZ>wsXWNcY#bhZ~2#!um^4H^LK>zAe+ynJ52!(suyXv%>@of zukycdW^z3R>Ra=0C;WnR@SJ`n_ynol9fK?KT14pEhPhck+R;7e;+MO7J111}-;p>! z)@2+|kD+_eMxMLb32PazL25yCgkj{z$F}XjnjZR>*ovR!+r}lZD@fwY=NBLHL>n<8 zg7oCX^?8gY9SxN72YO4TAL|&pFBIGg@(7^=-WUT??H}3PB7kSE6skt z0eC;nJ6&7{@IIPb>o@}NUhHm}4==Iz*2NVV0lbr%wCt?AW1(be@4dC2=y-qgf3nW& znF>A~iF0e?`9QC@BbP{`s#VLjD z9^4ee^myacf@srGmd3Lz0G=Raa#G=KTz_wzf_Is8wI&+gW!`Tt!gxnC4w5HG*P~Wj zJ_LA|c}5+IXdpl`oP(p4H&UR0^Ssq?gQOZZSYQM2e*SSD*SZx%s9vnI=EXB~ygl7K zq%Jlq8j$F!p3ZE~~OX+(qZZji1=bYSHd=5q91e+B*S9mi@T`;ny^bN3e4 zK6Nr631>`?Q!-@i>?4|VByUYm+f@Y5|1&wL@HW~q@eke^K|~ESyi>M9JaGRXX=p_5 z{|V~uO>F>g{u0Y%LL&jVzk74%C2&b_ z_F&?@VWQmWhjKL2o_{z$u6QK7jb2LI1)E9Pgm4B6&>#aw+s*8EXKn-6VZW{-|)GupKQ+2@7`h-X>V3n zVbA|@B9YlEJp7p+Z(L5}ep+-C6qHYA9{$_^Gvo^VpGkowb{>@nSuK! z51OvKwL9K04ssTF8Pk0SeS&mzozWETu_@^001p;%@Q;iJuB@i{7Xb z3f@)R_w~{6j#|w{e*fQI%AI_Jw7%eO>u!MewuIJUGZL8pZ+O4;_{|ikyj)2WUSc=0 zx9^Jpco$w(w>dp84$9l~dJ{`EI^NcX`~%tP>i9w=ZgP3`P(l_u-gP6*GxaYRZ-TS} z(SeoU0Xbp8%Ov`j*gTm~d%YLf{eR+N#nOp1N2c%p6FcN-($SI5a*jm4L7K@&g*Q|> z*h;~B$h&ee8s3k?$|c|m@|9%_xj|Yher5N0fcF3|AAfQa0ZMJm)h-7O(z2oG6>$GA zB>LzVJpWI*vu!>%PaJe6*@X>XfsVJ z)KUerCCAb6jy&^g&G{pYhj%riBMKwGPa8Lx>)O#@oV+vNEBGdZh7Y8d-3>J0-N5t* zq;YjawCPy9L4EFe^6o7U72f6sY0eb9w@e!9qTwBS^ecJx_EUg9yzlB?@r-W-+gnjJ zNp-8y@vaR2pdQYvj$ez!1s%GtHD@t8-p8`saEZZ;SDc(gbd+J_7msUN%JE-(-tvz3 zJo{q`*vDIN(Q;}7T2suA_YystbP#(?GSv>m{GI>*XRpnOKZ7M!n974}wVj$^50Vv3 z33wP3f8mhr?{~x|{VYw2hAPX+;k4di}Kxd=f)5;&DKnH)lbC(1a zWOTp|$?Kqklyca@t0Wi)$t=0BxwaPFgFKs#t#l1ofR{kxLg%n7vp<0DLB_r>ql}&{ zVz@2#AVh~LMt*rl_*GWv^e?e>(b}G`G-%j^B#7^^(M@Ff1_>v#kR~0;bu6!oE6Eci zAu7C=-+bUnSz@Q(UN=F*`(XCtAQ*2`oKO&q_YK`)S!ICtE}gFegF(>5$?3lWseeVdGu&ZDH74o9|4I_X$lgnsnr+ zl_VcZCU0*EQsKQUZ@&oz@45GKjnVKvv*oE2jQ9TDkpLL)$hA3bFy4vI$L`dh1-rNV z%H-C76QsBD8=PUh-zUuz>;`!2DyU5@XeL5>3K5Di&ggij$+`u#YRlnuk+=-62bJ#) z(D7D0nDMr)i}Akymxbt9gpr@N;f4pqRQlcfv+>RJgc9ug|G11Jl0Up>m>zH3*+Vqx z@Ro@aPi!Q+w*VF1OZ~XbD0s_t2OFW`J*x8K<~4wKzsC`O7;n|KIXNl-Z=Hyz_l{pC zKx1#E>j%O4e{tJ3Cm8SRuLGrf0N%IesyupfjtGT`^E$JxM8{i;SA}qOog$tRCw2iE zFxNuI`>b$?mha2O4CmhZhz_j$1dkkCf9WRuc(Y}T568=3YGlkw*NZx9_=`DqK@+Be^Y{^EpNnK;tpK|}vPAbBBz=l=(9 zZ+A=3rh})&F&8{|CrxP!5gH)Zztc10}t}6 znV0q$c+lt-bCE|ch*0pBqKef-^d;6)wAm-QbE3r$iR)T&-v71_x(B`a_`oTX*?W z<%bqV!@CmEp@ETKk4r&zKM(zQ>%6=5(r6KO|G%EADu3s>ai+)nwSFZ{Iwo&VS-sC7 z_y3|)c(2?&?m)r&gZ&sQ8s2yE)U{!}XR5s-V7$vVYt7~Yyp0|Up6fkAfUb|}>1+qz z|GOx*?+A?dbc2`i9f0>dIipFlUEl_(FD~C%3?1)QUH;kj*;(^nNSxgMv7wM@^b@29 zEJIFbTh3#+2I(!LBM&3LkNuvui!JGIkUDdkIHE?d-8&JN;Anh-`M0+c+v8}`F;@3s zy-5YRL0UkC_lh;!lPGxC9cyDj!#hWD;^1|F_tc5!8)3XjPG-yQ0=#X1RXoZ9_y1X3 z64L9z_y0_qM8Cs$t9S^mx(V?1^7$a3lR$)QXU%Msh0*aYYMpN`%*KOXhQ!Go){2*z zM8`Y+PHv70IOj{G54^p#Ou|673*ddVai}ZoAQ9r#Nd59c6&>%K^XY;=%?0pWNZc~@ z&vxFt=*0>57I8O&2eJ%@cQK-a7bCyq7wf%;dg*uXRk<(Ni!NfH-oj-K+#SyS#QgLB z2Sc>!@E*#8-`@V)|1(;-{y*dc`hRIE4{{zePNpoesv8}6(LAVL%jY<}#CquKhru4y zEf%gxIJ4Ly;;v5G>j~o4Nc1JP)_zLUe!B?6_5aO?juRO9DMN$`C4KrEq_nhK z_qMgr;6XP%zPR8;nZ7~7WgenU$02=TJ@WhinNn1EJJo9IQ1HI^WC0Hv-e-Ex&cb-# zbUPYOUSeC4cLxK!FFF#=&ejm1mpXMz96zQ&CyIBu!&~fOOVy7b0(eVA)?Te|iG@}u z-LaHkjgGffMAF;JA}-Q0ByOsWEi_029q*~7Wf={>#TX86Lqx|{jQq}}U7ywcLjMxG zVtcH#UM2SV|0`m_J(h7fOpmvk5_h@egjqZrI^Lf|k6-#}EWvPiA3=0{z{oG&W?cA! zA^q+xIU-P>n7V_uyEcwejYe%D({fS$bnt|9a$1$wAxln6ISu1!N<8v)*1PqXZ7 zS0zGMU-k^&Y(dA{+GB1;K`9TZ4T<~pWcjYPqv&{d6v@fjPKq-e-ir|(tr+?F$n>tl z|DxZ$jqXaMr(eaM|Kn8Jiu2N?n123`D{CvEMTf(ruG_so+gsvPc&}F3VoAaKOvHW; zG`u@KW{lz4o5Phd^6c$nW{3C?!24rJy`xV70eYjKG)LxT3iNW}<9+b29qh38jozdoM7bi`hhN9GU#vb(18+2&IU z}UJrkBu2-O@D}#;sfO{suttG=dn;{Z)%Qq% zHyfMc>!}g~w0dQ*@fg6HASG@j2k?&UT|MIu@V?G-P3z}tB6MVVZ|;RebiC`*f(922 zeQY^^#7Q_t`-KLeibF80DXth>mKE{CbXle0BUZ{qEg82WMBQf_=Ot zx6-6E-BXn5E6Ac#YiQE(N>d|;kWO}QSt`8OdY|4+!Mp6`DSkA(UwKB!!@IY!JA^`E z_co2$uiyvpHVXQl`vh!nDda2|bpgYPfs!{C@Z&`HZ1XF&0KBvFYRBy#5+T#wC+{EK zgpPNXox9-3%9$1eB<^rs;Pp4o=y8>oc-@%TVF%!u3Lmg7>fVNIo>Y>wc^v z&))bZ7t=L+i@xWy$QHPF7T+`B>7D3!&nq>(>@LAV%0%KcMa~?r@khrye)i%$iCO`M z!Tb~^gT$zy@E?p4|wscNZb~g zo_gzM^gT%bW8;+@RU{d%|6haX2*Sv3VCb7sXD$6pY=hN3g;hN?Jh9Ukw5y2|$MhbA z)2C5K$Z;O^KNBQnD!hGa<{Y5ltt2lXiiUTXQ^+P5Z;Jq9^8J6FMDsuefcKTR4w5Tk z2++3A6?1w=QXqA~?{0Aa-i3)voE?}Z?WU_abK1^%wm4L z8-IPKMaQKDcUph^PJtgtQ=-D#J1~O$^;Y-RE?|q041C0EtUx^quchZk{$>HP9x?0#3WTwQ) zjAI>NnI7-<^lF-PGz(N1oy{XRNQHGPjRA1g|{a^i$4YL-o7v)G`zQ74&4speJj!258mG5 zxbkpECcqot9wgiazW?Xwy(E(z?A}(_q`!pm{?NNK+8E&djO2`4M~s7(vn|0_FF?Ql zzbCSYbb2lu-U5lURa3H^`HhZuP}b<4XIVlFhj$L5BNQXQ%xfbt`~HjJL}K?Yj|=Cq zcW-fDBbT=YNHRa(SBNy}a8m8j+*bX!|Nqy%n^FEHs30||JSgDR6LpFQ{f<$WM)RQY zCwEuDN9_DQekR`_P5YG6)CxQ(T6n$Mg8kqVJI(i#_J9gUKELWKB?Tx6%*(U;g+*YWCt(f8(TNSvBw--F}k=pMAo&?L~w@+ZR$NV(nq=*Yy# zZ*O7YN$z#@FR?y9gB^~UV>d`QUv2stdwVm}d(hR~NSbsUO7trWv?EuL8dP}u=cPMR z@GctuDT#)6iH;g8jJI=pBl-NlsF9oH0Kj``_lehs(g{%VQi%)PqbX3$A;I0-7_Qe2VNFsF6o~^QUE;`;bQG-b*PO;+akhs;YAD`R2LEpXY{In6j&XDmc zNL=(E9bFjt3BN4O6MaN~|KE8yj(6!Z?Bgx(!Zi9C#>BET^LgEypWZI%1qT{XT zH0^h*N0i~*+Y`~Dgppr_J@2%LDE)X#-46@(+eL$W&)>r$#m)Smw@h4=Nt2Gjims14 zE|QBARVuvKPo4~<;9Ylr{X#UnU2z8|;N4q^2zT=R|9i>jg53b#yUv&v*oK4cEy>ph zJHgvq&hwr+!Lv8LHI@dE0B@6nFSkl=BSQPTrj-SF(cQbYGxer+4>vvoiE~Ox9(+26 zjyK`z{MENr8SiplXOtHIU-JO{zaEtbZM<~wpBJRYm&qxjc~E{tV*-2!Nh$W$W_S-0fA@fr zC-9)uua`8TP6FhQk5CmJ0&kG!-wPB49<+Fp*d_$}f3^?)8S^uV(Dh-l6~|@KJ?NX- zn|(98L0aFnR(e64DE?oy{xAGXiVh!){7P9_KP3L7--C{sa)v8# zVlT0MZi*9}j*(2?|6f?EK$DK)--B|wyU9zeE*0LP2R5Wpme|tRX?ZlfMU@V&gz-Kl z`I~&ju9L-TE(GviQ~W)55WFC*y~9)H+Vd1>p3;4J7;njwWjIlQw_z(sXt*B{s<5v~ z=KFzOK~76g$Sv$u$4Fkm2zDj_44^$Zt@IL)XiS{{COr z)Pcw5G7S@?&*jF4C5TLqH!krQZ91lLKbHKNAn8!y9TK+fBL(kDg%&w9yr1Sp3d490 z1WA(dzO(h^atVO9kHs9jiFyL`-i1@KbvOljUm*Q>0l>S<&BsR^;BD&}{l%3n4!YIz z+3ML*bocfxIsDDAWvZnMiE9xJI%%~V-MuTfxN(oDaxfg;K8TJ|jQr*nwcsN;=*L^H z<>1ROBN`@1Jl#6MciEY~|Ho~(Nt2FMQS>JpL-bXAmWzq0nEfoI{ z-n}(>EFT3ICq@<8&L6<`R-IF?l_>Z)(XX2tCW2u1)?xXhJuu!UJ6j%00lec?&arR( z33hKEZqsYYMaO&b9sUoAks~bxBref)mgi+GI^Ic!L1txN#~JQ=iyERM1|z?mQ;w}R zkLbtS;KYT9@_KB%x4n-EBxP=4dc42?jH5{hk5}dP>#5}JEiEd%gLq@MQSeUr;wFQJ z_XerNTo~{6BlF46TX@?1cwYa-Uj8Bb!K2qH&<(?91~A?SaHZSi0NxS< zTp?*QL`X+}B%uE=I^IJ8oPOPR8_iXaII*c=JGOXqyf@U@pBf0d&Tz9gjle%T$}#f8 z%P-1WDM>%xnxAX#tg6GFz2W>ed4zqN%k;%bqEr-3IzC+~h%l@A+yDPBw43z*Cqe&j zNaaCM_doejJV^Dah#Hy)C5&%8+Y3A>sdXX|UScyk;@k~E1(}_Zm*&Od2<5Q3jC=(R z5|?-v4t_x@`{IeI^I#8h{nq5shl+8KM95}2`&M)hdg}bD)oGDDNeqd*lyO`gDNVMsAAD+Fo z`p@_O45;vq+&->N!JFVcqJoAu%lpS%Fy2-LPy&p%M#Rrf_*fS8ivO;}&$h zPp6w)FLl&lIJ`F@I%+ZUi;6nIx`|B~^O=hO^si(gtD0mQp4f4dN#79={E_MLmcN`v zla9W-nNqLtyqY`td&XDrBg>6MOd-w>K~FTHrUP z#~YVQqmI$rdU=12x9C&h9U)wxK*4)eL!uHI-laA@89e~+VouQ*81KpKsbDXFckaG- zdh*Y}>n)FbZq$GQX{DL~-$H=*RQR&^?*MPYHj6ps?L3FNYIJN7jt8D9bV&-fD=BW{mto5-*88jiae zB-8i*Cu?cbktHu4p|ykD|1YM(JDfY%hJv?4r_&-dyxpzto`QF8C9Jczzf2T{AN2n>H00Dh!P(pMOCn>}dZ4?vYr4pb zgi&77DJ0G;W%&ykJi2?&_wCP?*Oz2CyeT^PG4i`pv;J;g1O2nN9~q4@@h@p`@AW$U zD}J#szkBc2rb&n0rf|W5qQCwBe-^V0`7`MM&8R$R`)O-0iU)~{i0GhsQ0Ckt&*2Kv zQzm~0>_G=7l~mG!2Ynr#=Og@@0NuTR`O_ir1*!8JcMIzP50WCNbi}jtL9sp(8s49Y zP}joQ{fQaq9wf+h?}rJyD(MOmms2{c7Z8E&L0t-0e$my8Y`-mEKI7qCis;D3$d4%B zy={F6{qB8TKCWG^hK36A3ICZo*56EzH}2&;nsi*_iPX9M=YX^^72aF8!zL+sXBuqR zK*Rfi;ha$z@3swBli=cH#mP4s1c0~JgSpGwX2J6oInUiH!1mVe{_=*L@E+A&jthOf6o8?(fjT6!>j|34kdN|O%J_`|M2f4<&gM1^S%axFetO{19*!Hhwp~*E{}@3tPSu!*_M3Tp2ra~h$6D5fa@)zW?RkS>n&ri z6{ku7-bT|(Ug>AS;Y8nqclB4GtC4u{6B6!jXL^Psi=a(iGRQU$B-TW z|D6=*|1GIJXvc|<|IGgbK5`kLc~JP+L;$?RewOdp34734FW>8mz=PO+ur7Igod6XN z7N6(`-ylgEo|=OD|G7GydxJoOlr*sXXKHdRv}2Q>*KuL=1Jbpv#G{;xlu490ji9SX zmwxs@9U#hm>(!of#DL*Es0Ps?jgjB6v>!bA_vqh)tn`c8_+sn|>YvL$f7yqjSC^yagphjbXfB2XK+`e*NG?z5&2{ z@7=+Gyrymzo({VX>W3-PWWS{EOMj(2zI`-c&N z$|Pz%)@xUrmmyhrW_TROU6U$MiTaNVPB zRLT5!8wt>)Lp$^$_xi3R7;lIQ@3=LqxhZ&$rZp@^!#mv7lpDs|JjAufKyR9y0NzqE3$!90#X{#-cQ32kh>myDxh++j zd6h|Lkhq^-hHG}%q2paM##!)HT7TG#GC@72ZUaZ?7nLr-y~`bqapT5r z%-Vb6#p8rpqbQ~?PDB!E)A9L+&cirxyyb8I|4;YDxW52P>~bm(+MUN)4||XtctQF% z>joT}2X&3luZ1hfp$9|c36j&hH&W)ngFXb@T0PW8fI?*wTjanCQdzOPm9>EfacT!o zqyi7R3bCj2tYd6XUc?Hq12N~@sQ{hs;{CkjQ!nElKjIEISb3u9;72dntwm+jR zvBnFpnxNtRLDZ%k#@laR8yRmQpV>2u0p6)08`n;@6QG6o-6jjb_SOZcY8Q;Rc)p%% zBEZ{XL-4*Wi9{&<(|)CW3(%L?my^aEA9g5{C~;fokOVEhqvKsol<9x{k@4^zL3C7M zHOc_*^S_>)HSZum`;O%p7=R1XyaRWKV7wud znV49BH~!;Q=eyg9(2tv*ZmoRic;6=|#U~t4CQ;&=ZnDeRenQ9ll%tf*&pC`&LEb}j z)L`UCT3GGwtxbP}q<>w?VS%!Fh6I{)G>FHQN^p^nw^&o*z4QBu zf3~-L4|*A);a&ei{Q!)2l)^SL-hSQ${{;YV@Qm5kj;jP{P+(0&7I>U^>%&?+Je-g* z2ylr8c(1S>E%wL>5Z>gh2hsc0miCz3|czer=3h#ue zNoPuN(sA9=5Do9F6>?;}=Y8Kw7v85$_nh>ujD<9VZCor2&};7<+H%e*%E}~4+?~%$ z7M2O3en(Fn$_!1SAMfjpyWj7Z!QS555&r!4u(A9<-9mgEDdwn<)MN{xZT`G!Kd%U(ZKA|DSC}g!dp< z3Ei8(fhE@Cgo3u?H3IZ*olD*<=>PkbS#(vw5-YZAq3T<(#LC$Xc&d%YLfelKjGeZl zdyvAVkvg?9dD1o{F0Q<9(fc*%9uyX{U`ex%9>dN5@ATDMH&F1t+ab-4hPScp^-vh^ z;ib*w3(~$WudeX|yf=96E&2i~$oDFPXVU@R4JIoh)BxUG&6?lt1H6wIUo~&3h=tk= zWi z`Ty~yKfiK_U~hgoNkauGF~ueE*p}(>#_@1+)1u>aTJyz_8gl<{M}>EqzTX`R-nBk6 ztY~=akb-Z+c%P~9CJ#u}dKcV;-~X#xoXFz>`v2#w!ePI`@fO$RS&i`ZmR6SZ@2voD z`SV4c(z|1!E5daaUj)(d{^=0dIhC@AM2Wl5;3uH|5&iU5`KNMS94q6UAe}~Zlw#z! z&95-r`UCxVZ4E`I(w7hbST)pRo67h^8|R??CqMb3Glu%@K&h? z;QhhI`-083ScnaOtMCpxI^J2KF5BW0l}PMJ+?V<_i5<_;@s7dQmgGz^9^U&99osPS zldA8U`fNmhapIriti1j{4a13VX;V^FrA&`E?qDu$I-K$fB>oI1Y^d-~nYV%bc?)>< zW>cI$2MuqRqpQhpZ}Irgko$kr8$;`?LVwhhKdl z>;riF;6#ntRESXfFFu#Im(lTVn{!igKtq{y1&O=&vcht0A$oE0)c2-YZwce||E-9Q zM;Q4fF1%sBeKq}fzwszL;5&@n|KDHt?#`R;eN4Z-W&ipFO**1X)_L{b{CofZKZ{w0 z{2BEB1S${OUmSCI0>F}AmOlbL>r zwb0v6la4IMzDDm{a)Y#*3hylYUJnZ1jd)oeG`xrWsy4xRhn1Wr<2@5&b+!`V-A9V^ zmgpluYG+P-F8lyakP41Sz@OOFB-Na>0eBxZ8DG)g8Vi-YuTJB4M92G#zx*R9*M+1a zBu>nt@>R7aI^Mb5B>i*EDh!ABX+%dBMt+M|21R~(MnB$?1}0h@A84o`=O=hb>0~iI z-nbYdZ94Yal&buxAXic0y-(ooJ__E;9u0G$;eFCxF9pV1<0cpRfi$nIh}=s6Z$k4@ zLED=IsD4c9g(LVtx@mc5wIaa#oz%I*+5qn|QN_3)E=1_%RQ&1wcj$O8oLr|`Ge?p% zjKq!UmEP9qLB~7!&b7x}uIdbj_X0#m0!Ds&7W8*d6w;5km3rIY^>f&}x46e_TV8Gu zW&Q)wleFnrpg1=WcZlrX4peyWdGqa`-P?B~mpIYz7X7~9D2#W|;cznESHH~E+=Gjg z_O)Y@-2^CeYtfk!@Id;hV)qqF0B^zL7I_N*-tt9G>{rc*5MJ^DKl>eYyw#5S9Qrvc zO)^K~&bS(-x7MTMT{X%1P|aG4;qX>Qbd+M`H`aY#VEupbfi!{7pgc_L#@zJ{(spe5 zQnZ`t@%GT7O~*3ckBcVK$ioSHD!elr`5#f-`@^+V4m7+EO4>HSc=z-?CgUBrcqkD5 zdaLk_-VZyw!10z_{ci)o;Y8)hC$sSDE%DxaN`8Un(15i&Zz|*@B70Y zPkyq=ktlJ?di56`DMH74yr8ng?WhjJ;e8L$@d+b8qu&i7R{urq-L`A1gUw6q(_1+G zRNU?z*Ob@y74)s z^jDAxUkfX{WwG}laS@Bs`K7a&zd>50NShAbFj37v4bmDaymObkbx`nL@_vB;8s7Xm z3VP%dq|Zjl7o@G0bZV>yc;7dRu0IKu*qw`t^!ld2^OgeHk7NPfFSfbQ2>^J1BzykdQ>EXI_>)o$Ok|=R`sTbb+$NSxd?nsg+tcRTT>n%p2cQ{jD(?T0)C?@zAx z=Aq$zPeQQ^p8s0~Ymw*w@3bDIy8*nDrAa}tHwaLJ&IdM+$rPy3VL=^?w>w|?vtWSt zu{+ii_qGtBPE>dwc$$+$ z!J9YvBtIJ7KNs?mKX0)+&w+e;tA6I^Mt^{J(}QNdoE`#n_52aXDR)_}}z81F}$ z7Y&60yrp7x7OMosLZ(aCZG|R7Q2$zXZfdg`7+@*T@=qtE~Ij18v`rZC>; zEp{L}vN7`Gt}yE2a;4wB4Q}zCjk3iaPH;AVF0s(v$Mks5_Z_22hw^BBX-qxYy&b9W z&ORgGL&4kd%T7Ktyx(Pp-h=yp&)Q|N@a!#hw-x&qfcLW~iI3c1IB|;bVPWk!7)~s; zafk8#u_uu&3gG?VJh3|3B^FxQGSVXU5*_ay?7gZgq9UXfNSserstq>@9q;h0$_o{T z6&cRG;}9J|82OD492^KaN~U+W*~;$7yJfk>OtRKum=SkOZ;I0Jjm=(8eShf zkTw%J+kD_2@lN9z4zLDzzi|$qYX}CU zVjVlf^QKcEqGHfE{6PBeF*9`wfH%*apFPd<;vk20!8JP7=y=DCy%b5ls7SI$;xu=^ zkXFh<$NR$f8J7YheTJ(bV-X$o82RnJQh#yrBKrIPA)mDZeao=t{|{DeKHE2$%=CCC z*wUtBiS<0Yia#GnccsER@4<*K1@EcIQeiZ_?{?&0fbq7kWF_P6>*1ui4B%Z;aBg-j zc%1mjfoBg!!Ei$BYUwOIoY-IJxsd?y=8`JU?*w0OJ%8wX;h`*ayuVz_vtD*cfpiv$ z8*I}E8jVKBn|EBFeX%s--QN0)=-|M}FKxfxA$u?S-CJk1^|A9p*dItwY_RyLAI|)E z<0@#=p}y^RRO&IZd#|O!`|!~_=P7ve9|#sg!~5JdzFZjZ@3Jv;&ECv1pADUyB|_g7 zf>$;iLC4$q<1zQy0D00R5*O?yCA@40I^OxAQFh{!jQ8zrCqzdsMt-eYxpIa7#pT3x zqD_;rtFgDYf=h~ZZZ0P>eeFFrt%xQa3#>M-6hHX){6FJ0`~O2mpg~$kfdZUCMjeQw`Lo*)r5qcp|9603FV6cqK60Ld>}lyAk73N^M6d*BPw zyQj=G8o?PP)s8Ui{tA79baIPUJzF;8 zRghkYj!KODq^-Rgaw6zoVhMJEnX3-b(Epz>+4^dXmFYbQCuK^TjO`_b{dB&kHqn@CS{!3jK0L?c}Edf zHZflRAC2fZfRUfJl;OCaGW~d8<^Q}{c#wu8b{BTF9l4sz{CFqrrb)+B(tI(K266@I zO@(&}+shmZ-h2mcNTA`}888qI4cfF2yZ;aK6O%ZQ&(HMze?i_tnsn5RG>~k! zljr|lRCph~`J|PCx4CYSI2zv4`!{sJcxNwJO78zFlvFqC0=%D_&mQ;gCqQ|)`f~!m zQy@*-=}Gwf|BZ+IqtgIyjs?)1<-J7cnsvt#*#LCBUv3=RXI7_7qQp5Bo9czwqT}r? zP;z{OG~>PhH-hMJ!^m&9p_IOvJpFi|T6!R*X9&ANO6+?!FK5ntrpFtnI7E|9(&1#O9gJ*BJuUE;lH}Q>^CE?lIo1Jm(p*LUMF8)Z0Ob}zu)Xym@WZpy!$e47r`rwwICQ+Dr^Ov_*(sAKak1N0e0<@9 zj`x6BmZVcN20 ze!7A(H||IlqS-fw~a-=E5ZjvpXKP?lJk4ogKe4~o{f{i+*yklT@@t?>MRyEtg`j#3n9uxJJ??f)Avvjce&dKmUL0 z^PZuZtqVyUNSyDhwqv+T^#0$)Y&z@bW5&B6-Hqt5#>j78)%%vmR`h$2nCH?B4|8bf z|6?8t53Cqv{yRtyr)kq+>=KWh|M#Q9yGq6A76os-&u4iwyuB(Fm%>Nv+J#ui_x~He zFWk2Y;Qb)Y@%{nui5=Ao^Z0IpCH82WYbuO)@j?YBk{*@2FA^cahtajo4(Lnl z5B=on6IY~2^N={(*CksBI_OI*aTlj_8J{M@4M@KsI)X9so9itzetdd9>WNx3Uwjo~ zGQ#qdhW>xQ(Za}r?abf*FQQGy++%B^e_S9}kQ=D*uK3m@N5T8awq`jryidJ3Rs-Wb zC31p%gS1uk8jCx?d%4w|%C$)Oc)*S(0D_QW#x=_dus~O;fs+U^y1l*+!p%XyHF-Z zMq3QK|5rUH9W9$Q&h&T}ZJ?Y}0V2jhKytcRxz;C=WI$EM$Vh)@{M zPE#X!bi6$iT%JeXmM4WGac7eBYnvO`MI9@vRCyB{q8*< zzrgX%eeC`p*JiikQ`}dk$2+l)HXZJ|?e%^YWcOZAg?Cws>p!oz?Ah-sgNFBw3fy5B z@0#LB^7sGhdG&q^0=!K`INdeg5TMrJ>kcbeQz4$bwpsY~R=op1L&^c(ME3Uw-yS1E zW~m&+(?;lc%NvBRI{j6FWQxSy`;_c{UmP88-_&nCo8lPnc#ABe!yO~P!r14cX^ZK1 z?-P9!=}WP-H3wu@pgdDMMm^7 z9^UPU4ik+0cCD5Dpm&&l_x4FUwBoclcK=`eljjYe`zxl$+fPoECLO+c7wlwr`GqQmbB0}~-@WUT9adKLWB31wRg=Qo++H$0-nhJPH0k(ys>w1Y zkL=z7RCu4rGRdU4w;8X~A~d{j@mOcWc#jNAZh_tVvw+%({Q&RW=697v&j^rIl`m-+ zTyOc^wx$QhTT%Ar;-dg>TbD-fkgV{aPom`~L#D+_Ue>`&dV#JNk{e$ z`n(rp|1(sl|34=K`u_+j4?4H3;-5E2c5w0Qpm~rPpZj-s57J!q4f*{4Jt(PU z5_r(HqEAs?-w9CkLlb`eu@orZBA6S#V)tuTky;2igVfTp{pYfUySELhY%gb82JgkeZ_&}r~d}2o8_3~FCXkH zc8?^V<|(~q{xe7)?H|&l<6LIG?KrrD1n>^0!uu?j>pusi@23uEq2ayq>5pa@Z>^z8 z@)mnwxU$VBfcIB(JMNjE1n980XEPDtO?u_Z2jBl+<9hWV{Qm#6(Ne#b2qF}^SoDq@ z8#> zv#x7h>$=y4`fbZT*HZo(e~JAXs&>MC4)cxJ`JMeo#~_XP0(Qo(BCcf|Z$FjVq5MkP zJ4nJ=!uhnvtpAA}p_q+69g9*|C-0|>w>U_JcYc?^BWwq`V(jW-JiMd&E&UL@!+6Ii z1Jb-S#J{`&cwfJpD6@oM25)~eL2L$i54D_>L2i)prz&^I0le$CFS$3v&?>xKPosXHe_UDITZoT$Yrgb)g$>MCAPt~8%4o#5>Aw5nau3FLkmv7x zPq-{byZ#UOw0_rF=o`xyNG;|Y>C$n3!=V{Af9n4ORCwn-I4F(by>g|83Lf5RMz#`mVONJ_5j7&vVYjVP$Z7 z+cU_KUxAOe!?79p=Z?)R7f1a#4XkXkQ}OXWuwiIoVwMck)&F*=4l5e*9nrabHixz6TkDa{`D4uk}F+0E{>NT_xjWS-%o{iZmex4hIcq=gEAi8?K8H# zMNV(!LlY?T|K_AfeyRg_KT1)G9OE&A6$oGX(*fRHR$&3i$BC<&US~W9^?%ir!|%xD zKJZoJ+5Oqg_;?riPi4Inm|32Q`rYv<5c+ZbAMh?*+59An`A%>1Q5}{v;!Dxa)HpcE zINqd(zIQU|=>Iq0I8bb#{+Q+Ke;spIx^$=&{km^-@^AhBp9^j#`za`p+^KTVUF%gF zu^e>o^K5Or92EZh=`iw%oi(YF@`>Gw`ZLnMKn}A15Tkqh85zDAv1-Xt@IYFgfa|9@ zAO}6{@5$){ODtiViLFE!xIwBKvtC~czd%YXFWCz7N|hf#{j6@^=}9Eu*Z;MIrLOK9 zneU06XjDfrjri)n80l>AWxPPD4{*Kb^MiJSbkr~;kxMp=<#&*KB_rw5@pJ4LxgwU* zL2{$QyO{HrJcf5*^kYptyi=nq?jv|Vs+>c?yY$Ft-%o%y$L|km+~D(;wCQ_^F#vC; zqhiW)0p1EiOI9=jyyF!@u9=wn!0Qd>?E2V`zr+qMZEIAun^(RD^|MmtJWy7Nzr@bh z-G4Xa2J_AT??ZLWq!C}=aFIbpCgTN?<(B*Fk7UwO|GPpw*>~bt9`68{hb|pY?~cEk zf0c5)b(jk8!pC3#HUFRV1O#t!_dS#eQX_orrxCm-3nCm>fD6*gtd2o9 z0N#R2<{gp*cn9uEpIZpp?7CeyF)%K!m-akB$cHu@@dauCf7naAHK-8d5 zhxNVcMSm_Q9-_kgj#K^#kC&GXBZer4wX$ zN51UsNq~1O*OZtPzYekOO&kkr% z`u_&chs&El4!Zo=P+aFR8TJt?3f}lJ7#`G5Jt+=ykfcqO)da{v=X2(KQCjH>e?O|~ z*7X!W2fc{PUGV+dyz*t`QPwCR3TNyp-_J~p-c~RkA&Z!ZJEwNDsZMt}P$Jx4w zB1^27=Vr}1XRc}tjX2l;csA04}B#CP*4dt!bn z<2y*pb;9JgJdHH*UbW5X_rkaAEI&a?w&5UMI;OVUgvCWtj<-Ci@GdR){?`Z6uB6!I zczF9CZ`_68tq~kaDUe)026XlUyob4s&+U6chV@TQHH!kgpYCRI69&Brxiczi4Keg7|j>LAjHk7IGI ztZpOY*}G+#3ukX8?fyUE^{lSJULKamo1iX2mkyrm=Y{0{G)O(D@Vn*Zpqw^5Fy~}=o`U3Ed z_PpsO4Ceoh?=mU-vm%GUl!j-@D9_cIfURX zJgy=%T<-&KOYJJUx(gp~*X`A(%eP6FZ$|y9xX*maFv8E?{Rdl%?!0Bb&B;MjM>~!9 z^esm`3@aGV-q9R;I`eC3_udF&r`D_u=4buAw`4S3Iy}qkbH0J>{rCR=e=fP1>ZhRo zKSq^i@&{)c(x>zrQ(T=`9WYE@4ICh#@lEt5UGy z{`+89=Z2 z@HHyxm6nH1r%J{&?9F~VJEx^aSTz%t`v6k88Zm3_` zoQOolcznDGO`9rQjO3ZF{=bRp_}ci-@qKGeK3LktINn`hswIb8AJDA-33Yrj_F+ye zk2hf<4}Ch^Hc2b}=^*)1;ayc4JPRBLAd8?VPgR~yiAxI-W13|b}G?{U{a}zTbO!LsuL6V#r?2ega zeY`h+qf5u9n)Fw*{*1Tqp~CxqxW*WU_llwlHaxuR%@ooQymzL0Qt-ZcT5kOZP#|gd zTl1uKk>QX-8$E)+@m7msnkRBO(WNUle-sE|4-b!Ux)PGGN!f%wq5suWx6AmaT(#`ZF|XH z=&aS;axv6zrolb&{qp#DZ+K{-xBE8p-QF@obr{f!?@H2ae^thhw|1I7_>{;;d+$vU zc=RA6f0E_z{}XOJp-)Fu!Zj7JIr&@vGgYPkpMweB9>GSHgBn$>rm-AUW@5vKmxK5X zp?Am(l8o(pDI<1H`P7G}fE^?`S+jOy8W|RjTbH`HFBrD?)fgiUa*)-J9&SI7gWmEV z$XFoZ11}fdD@(}5FOWuhHSaVDe=A#p`Yq#%lIV@ZFOWPw$mwkL<6^o3sT|d@l}3DD z*S)>iBf$6)t8-x@UVjel9VB7IDEIR#=i>hi0So=qb2VK$&PS{6;F=u_me`0HRCw3F z==h4^ZN5gB7Z2~gxP+C+Cw4;FWt0JFkF#W+!~neYS1sH27=O4Y!|ky_n;Sk9RuP*wPP19OaFupF&#=@1zMn-lKc!l$JIK zGacUHsE%G5@$Cy^=l*5NINod?JJu8^(cVGs)4Eb9d*cbq<85|^J{_7~+(IdV$PO}s zK!tbRohf|`Z>3Xjx$*E8UcWL4!Q1?o8fALxN}0Z>lK}6g1f5>RVluq3ZM{s-KrnpM zMaCGxJJg8VEehbheQe#G&|BUx^l_tQmmxmhbuS15k=?xI)1!al=+hd8^ z&0Mv)Oow+as>6Xse6Mzkj66EcINrVUa=vAMq~n6LE2I@}+0OEK6TIlu(Rr3%{m=2% zaVoqYdVej&@Lq5+p9>G~OC;5A2;TR#t0^By2a-z*+yLGK8;&m8TT6zG1J>V{e-jLk zJ-U=IAK>lcuwDBs!25TgQ+t=C51d?h;-&g1KHl3B`m7BkXO%~zeq$CtBvV`P@%|XQ z=i$y==KKEN1l2J_BR-QFziPMtB74g|_jqhnLdW%%l@<@hSFOIwLfer49BMCpI{X&( zE$sdC{+~Y;-nC|XFJgELn+0*=;msbcmEp>2B=XL53 zGK2JnYgZ_;gVg8i+M<<5hHtD+lim+@kp1G^aY+3y-WKZP4RX-4Z?i4gVtruwFKf3q zEW$s7eubdlvoebaG0*}?d42HGmJdQ^2*7V?%@Bw)5H@4lo z)X4`vrMjr>*Dw4fc4=m-#jg9m^iH6Dw%(Bn?S1%5ta8AIlJk%N)8V}X)nP&-K68#^ zN>iH{$2-X-hEMe??IZS7$5}!JZ+%%FZw}c3L3(tUfB81-{0DD{3h$O4hdK;ziR}Y| zczCmY;*&*AZ%JWVZV28z)t)Ai0PpdN`w@F`$neo(`8Yvh-kqa! zCB3$Q>^(8%RrL-Z@5ZY!`>#A1)0>a_8NXQgO1J?ZZ?Ph&i4zA2Oo#V3REHLg_zHCd zOMb;Lj`!`MJ5QIT&{6+e*!iCh4Pbe^3Hs~l(@|oau12ZG>;^%?Udd-c8Hj&cX0b z;dbT6!`tQC=eG#nB|?n#-s(HnpRyJ7g^jDHi>2v#>pKLMaL# z@BYA3`}U7a=rJ4KY^aWlG~#Qw46=}z&v^Y`(VWW{qDA|7t6_6y)6NA}ERT23L;7?$ z4fgsKhy1PoneG3F{}>Ob|M{qLP^X~Q7c2*H)vpl8%Rwee8SW234mw|%YyF z-v*Z0r8RXTw((@xt1cv15u8Di$wEpBU8;9iJIFj##~B*&3GTjfDeW-hIVc-;IB7`F zh#f15m14r&ET4l22Sn)8u`#Ad{?87QmkRHWNB8bwct<%C#qjVxVx-!R;5`y`-x0z4 z%FJ_hwg}!IIiG$zM~3-cXZcwT2EzspH*Dkq-Y-@KRL%xF$e9rtT$+VhNVcze|H zh`QR*#`~z>(6*640?Ri@7dgiks!~FdVbxmFe!y?87ak2pK6+VY1EdbvAx36BXYxjY3 zzCVA|au6SHW3_sN6<#w*X{g^^p}=<=$oP0`d0I#f^2snA-sY%|l{Dh}6nTCAP!8jG z8{fFpId-3p=7eYU+)GKUk2m2mojR%-)|{oh-V(t@h4*8f{C*5?#ghkw@$i0TeoGB$ zPDEH+yC8UXmh$Wm0C?|TZ?-w&CK)yh$uyY&y|)VA841YgtwdFF?@@sF%8Y8Kj81TR zYj08_=ZcTFqj}uMSvUDeQm7w0Z)?Kc&G>ltUnw=)z$VFbcppb~e54Vdd-w0-v;T|P zTh^zmcbuC;yZ%qM%OziLrg!TZ#+TSuxMik*3++2doh_gEV)liwd=9c5tfEWDiQX5X8NtYi zod_W+yq{M;Jc8lfK4U@>5AVF*$8!<9FIxO?MwZxx))LM=$Pyc9am)nN|DQK_-0FD| z3`ZW_n}s~FJIS^3+8u!RRo)M8^f|zIi`0!eVM+LS4;o}WHxipqGC=))Jn>tS?}3lE z?7+u^&UTBL4(|`B4rLngP5p$IXI3)aAm!Q6zQenUjtVf-h%1~qY>YF3!rd)#6?dy}6p-tCl4yZ#TT$PPAKKZoVjUD zWY}ayAM_kY-cmpjYhELs$-ac6FW{UJgo1^Wa1Zq}_vAlme+f zYp`MxzGU*r&d;N5fAn|7ST z&q2;_9&#RQm`U1>`e~^1+duNc&p~TtiZ$o&V7?=EcT@+NMtpZH$(@cljOQTp+2h5p z=@_vSpm<|zPwZ}%FOXzyztE*auD48hbr5BV6{W)aWmS?5hWAE+PqKJ;pD`7dMDVse z|DA&OW*w+;0^mKMu|4$WJ~Hh0&A{MFXE5C8duF``zdZ#Nz7wz5`lxT7Iq z?S)jB2;+yhwvT3@OI-bk-@`T@<^CEg17p> zHcAJnuj5V1IKcbrzL&uXhskh8&VAp|F7Sc$mByE90Pmx-8l~(3-eNsZ{e@k8;E&su zU2SE@?;yGD^^3kGEle6h{T|KmTkQH8AMblGM~3!wS*EN1kD@xNX~cJiY-bS5AToS zKTQz4V>Xpi@Gda_BJl+&kPO)CC61Bd>v4yTBA*4rYEo+*mjb+J9nLND26+F>oRq1)Di~-Z|8YRl-}FE3;i;m0N#Ny-yi3Pli}~9eA_F!gW)sg$uCp^-We6yW^n-T zCW~~P6p{~YHoBj<>Iwel#9dAFxcrCNBoowcmEq6j^|$cx?%C%^xV}rC>G1YJb-bYw zU&FlK2-|YTv$vO8?snHK+Wmh*;*w?8Zy#rQya`+0)1@Os)=_FRxSaTR{@;JBxS8vR zp#Gmrm4n{CJEw)^pnUx~N_aWQqcQ6!l7se-dQoyvV3Xt4ZjghfFNYO-x{=`y^V0@K zV2O=u9_CaBIq3fNrII^A4tjQ2S9gyEcp$CA?qSd;{2k<>U9l_O?DJ8 z@$Vp6kF6Te&11ehNPeh}{WRix>&Cq|E0^&cl;*V6(X5n?9Hbq6XJhRDg86@unRMyU zzmev|nMc_{N>JfFbk(yA!@GB?M*$D-%N^4@5xl2DXHoE;Fwhz71$ZwtEpoi)0wzei zcNMgN0x9H>XeNSpWUcl3tpM+d3zsze<$dAuJnMvkN_@PhD$c#Hs}>{`pni7O*GF__ z;^QrEs{KfwU5e?JSYqWL9ojVF+onNy;p)!#4zk}H+7J~^yFfbiVovtw$8T7^{x4Qv zOqY(H0mU^}PEfA5%%Q@2@c6C87~U`K@)qIYy}rVc<8sI$w^%x_^Tf&p-lF0Fv&C?k+L?a*g=!xd#NnQ9m$dB7j9Ddg#L^_1} z-I5=2{a%E>gLE$RF+Sla&2)HAqB=Zi#3y)Y_mY$>#Omhg9=0<9Ju?ec&~(jgHq_6pgov7CmBl zya}ds>M(ogf}Y-rQQ`esx;PlaTSVV@As*ghwtsqWCT|$)y^YLVSgQ5e2aa@1$QF#i z-<(uMKOV^Gm`Msk{e%t6&3at$Hz#ZbYj1HnF(2Obs19Bl@qO%)KfC5S<9MH)mH*~9 z7wxaN2ud+3A8f~pn5*#nFQVyhpi77Q%+Xq>OMmPC|Kd0N|NTD#>VIjf95niA^fQ)& zKE&}X#mhnO%`JB#caTPNU+hILNT2S1qv->d*jn{|kycwW?CH7P(&0%kO!PfczZ@*F z>n8X|24=Ltdgim;>WqEh9hWONYQMnWL4MHe9oh6=oMemol`lJda(5~I66+$|_}X}j z0@Ljv$59;~G~x?Ycwg9hL5Sv2`TqoDDqx$Zs~a6TXi#s4OydRCUt*h9(xt;rrl_#K z?HF?ZUy2Iv56>-4Fua9{d`s}~=KH`_fZ!c7w32eg?vqpX6Xc2=-~BI~I=jfQ>!K~N zX?rlNmHggR2jIPU)uPwa0Po_V4^@h4KJaVV2S@m8@bOk~*)HU8Sd{b<^-Jrhipa~r z$D0tz*J1RL`8r5TP#v5!;uAfP+QR;falF%qM!%LUqT_h$Xz9_>wAn0w#2%1!k1icA zo-cWv`a2xKdp;H3BmN`e7~ZdRa~I>`z46@K1;_>I(^>?|1?k^ozrV!-ycOcd^yEQ- zw4muZheby)e9=WAOB>*QYYV|&6ck8Jes5MU81aUm1b8m;t#1k`QbB3k5E64 z#LXXfZpX*FqeIVwD9wC3NPbjD4~_WTgGie~<}<#7WZPS|r9_C1>|M>dPH{Ou%i~Q@ zpijqmN#R(*M@s!aj|%Vi22vsz-g`@qsNmu4W>*x8;5~Gq<^Zxe`P#*sn-1`{vDF+d zcOt`AhR-gF0GAV23E%jETuz*pXJ zVV1{xB)N$$9UV}mr5v~*4YIc+72d;A5kVNd|DV+w6WSmLEu_jp<8RvBu^a^DacJY^ATP_| z&$S>2*}af)K$h5NN|O^vfwU&KHt~)Z8FuH8*|n=J7~W}p(iH|dDA7&UDFhTqv;55z zpSAhGmy^@^_B!F8L8eYd*c(pEkT5@&o1GW$t;auu?CX=O$~vvabU7#u)iFRLzLct| z$&ZqZH%NzfZH_*WLVJlN5a+!!6H#FO`oB_=J{^KLXPo~tVn>b&?=M%gT`{~r54LOK z;qB3!!GqNQ7bXHJcyk7=S%Exnu{1|+=sLLGA{Q2}TLbWxIbS0|0(h@7`LO9cz*~Es zpS(hf4}7?oNA-{zKHfuVz8A)nWJs>4-yzY$An#fDc(e5t3#&X}zEA9iQ5_JC_;ycv zb7_zn-$8Pe+qipn(*8iY{H>mAUfXq+$J;-aJ{=<5+mfGzQTqQ2sPO)L+^qw{d&$Fe z4LrP+9vqiL@P5%WLcx36@>$#`0N$1nLETRelHpS-JzJMQ4u%(OTUopk;2kd1Ot=m3 z{w{cY2Eoe*cKFGy=Exn*0WNqbPg4de9^S4Qx6ka`lIeO|v_!gSd?9M!R! zMtqyrbDPx$F@C%i-)iT)$AgaSJ=kz|D|CzH@eatOPe)t7$T@E;h zGyuHEGnH&kdHTS!9h^?H{{!B0)?B+PT05U4iu%=YRnIi|2fP`nOj&Z#6FMbxU-%k7MtrndGrIZH(EMFi==f=~e<6KpX_`+BU-ZE5pkFiC` zV|Y*GFH^(AJF%dP(tCSV+Q(4uEvJ9g@b_pRc;lhCk@@oY**ii%Q2A($BxwWcx3Hk5 zikB0Ab0S{&@`90=3e#opI8=uejrh37JUSZ%8Q+{7OR);nDWv0i%Xm`acV|wP&)x)4 zI(6{fz7@IiZ~f1N)&Bn*5~%-`sB+Nv9ZxBDkQRXV{~Xu7BjDvAar>>ekosRvY5pFh z{tvq~sdxq~v4Njc<(ebN@O}?l-ehpZe)#7)1*AawnNfHr2`sU5*76#i{0ip(6}%TO z`-cJPXD&$h-90Qvl0*HD9#`8{jOQ@bfmyT218P%)YVv!?uMJl|%C9#=eOKgHpoh}~U8V&nO z5xhNDtfAn&w=Y@(X^={rTNT!vBExS8%~wM}gVgA^Sq*}B_aVVi({}X06I=0RaVST(U8tBr|WY2X)&DjmXTY(DisTX_FFucEaaNy!yF+Na@ z;N4iakAk3i3J>n*Dm%3C3)w=z{Q9P$OodDE{ynVn^YfR+=+d#`_Lc8jBF-atFQUTx zt1^ENhPSB9E*-q={qQ?)8-llz<5>#cPo}*DA^_gK-6DarPJrRW1`yl~>i>DS=0W-h z-czF2d;#7YhIctyPy4{O-(=bA;_$QguZn`KR>=h<%&%_ok@SQaaB*dUPD=86EnWPO1Op zsqmiUPs+sb9-6Jb3=i+As#z}(ysdrfD0okJ$8Qe-c=JHzR z1i@P)!^+?=zYx2q7JFT5yF>gk8e_;@R)*ARl!Wl5MHXZ>Kp4qzl#43e-{5){&0Rjeiwc_esg{! zerz*Kq4_D{)J53vd&-K6Ab1ddgMDRl;?h zE0rsTE0F65*Iq75E)%YmT&i5sT(h`1I43#Za&~hzah7xDbEb2~bB1sp<=oF{!?}@D zpHrPvj&n9A7jc?6LhL0zB32Ra5VMG9iQz;)q6^WEXihXDY7-TR5=1`e7c>S9K8YYtNm z630>wSq>2nBKs8kFnbSs3wtGB0G}J*9zF{`V?JFz6~6g=LVRqz++gx7aVUC$gVn_hCQCzJs02 zZosa|F3&E`&cpVDZIrE_?J-+5TOnIETQXZDn?IW?n?2hWwl!=zY)WjBYy$t@o6NZN z??3oCvsrcp0BE^M0U*D-SI`8$c9<=KH}rV z8JM+e{S9y#8nf)=2ZNyBn6=}BychHfvusQ3^`M`aWfSzC7y5x&+bvbgpzoMvEtOIN zO=Fhj`%Tu+H_X~rwKg7_!Yqrk6K9~Wn6=eqOa+?6tSzuy12lnI=94uqpmEGHtBP`h zzF-#lx|RU+8M8LoR^5d@Vb(^Hb}=-DSsMiUxS)@iwZ84!31}3vOs>^!gg#)_x`@>} z&R*7?8 zfZkvhJTjsRy~ZrkFIj8o6=vy09aDq`Fl(hcA|OCob2ZcFam7PIC;L)K6YX3e=5cL%D*Eb$UcQRo3?i8=4G zhpI4Zwq}qDbRV-sek@OdDltpAtL!pVfmySzH2Fd0m^IV!&RnPrvxKzH=R&2JCCKx* z47!I|0&_2DLnWBSmo88P-Nh{45bY_b7_)eccJG9WFpFFHasyO|S)2o11yBKI5sM|b zpgWiao$4e&w=s*u#{Ld;3$xhm$llOR%$o6iXD^hGS%gB{XHXt$ZT%f?y%NgBtY5AJ zW6%xE`l&RB6S|IB-@h&+K-d0df%A6gDrOOPGaxDg|A{Eab})C>67ii}=t5 z%tG!hL+3FInIHtEU=}iP1xm&&WIhFS4zrNY`JuCzg?#-CC1DmahZsu4EM#melz>^t zluIZcvyh>H&>74^W~f1Nn1#G%1jS+&^7soBgIUO18BjE4Ax{fHQJ95HVuwznmPL}t z_8Y{-n3YiB>_}9>toX>p7er;uI%A>ul&FMRaZAeciHevNJ45{wQ311}9}>!li!duH zLh2(?9=3stgyCmSE4Ltow|G=jVOazp&{H3L}|n<#`??rLmZL_y4QJCW5x6u>Ok_GCRGKWc47Ubu!LF$;MR7>d9w z%xdXzsDpwrtJ!0W??uQTvuX^LnxSKu^?%gig z3VC2w$wrtlO(E zH$pC`WpQ??X*p39`+K*zx5Yuun3dlp@CZ7HS$Pi*N<#-QD>v3Q6WWhiH!OEbKu(x- zU0l>3a>T5w6GlPMKFrD~PozFS=0NRdO zDL3ttAZyG@HuUd?tT5}G_;dhdiCIZcU+sdnVOHXWwmXmoW+iwiH$Yo4D}IgT1856o zo#FT<3vI@%*q*o(kU3_>+>~vE%rGnZvh;F@j9F2p&DPMSzxV%{zs4hgBlac#K7+JC zb~VTuB+~!qtJ+A!JA<@*VA+FQu`70aMfpHF{G`s5)NKv@#3hib02r}5%POJv$fIDm z%Oq|0YH$W=?>xs!4xB;Oh%e%btMY+KfxCxxTH&8T<_IX6Xo@Z%tw8KAZDO*&v1{uiXZv6&^;OPKEq z(g&!Hx3uEhEB!+@n(-X;ZN&ae)DZ0@_L1H}n;XipEMFj9+;oU89W4qe2fv3?c90rW zcq7d|4DU6&=kns=ZKSy66oU8K8DW(A|BUzfBoTo3`0h{NVDJTLCHJ090|0NCCB)>l z0B`ZgY!!BZcVt1w+wEt)VTs*t(Y1^4@%||5aXes-G)WBglkNWEnK=U=?@qOB*YmE- zhxY`kV}M3{Vw=1qHr;3Zie1m(%Olm1w2!w4c5+h6+~-&x?|^;Ebm{1Bt)EqKm9m3W zr@|ZQUSoJS_zrU8;hprx;0c1ab5tqi^meRr+3W=X@2OkvJXK&o8uyCgxoet&;rmJx zdyN6!qpP~(CI~HXgoq4>Xs9>b^=XhGI~yPGApKSPyOgC#?WkYrSp&a}kJh+#Zc1l^ zYQP!h!#f<+kx3&yzO5StUa~Qsy(gXg=REbJeY|!4=lLzQZNFF^Z}F#@bm_Pezu`++ zI0bJtD!h^F7#QAensr=wc$fHTFGS}5<@NAU##=&F+vjQnya~IOpA!HB(qvSQ=H3H% zzq^p6yAI%8AgSRy1n>?KJpFc4v^VT9aIyXTe0;pa+Sjqyrb&}_p?-EBUzpfW;o}_; zCiKBZkNKvzM58)_X~Y*@=;v#+mT|mmHUt|gy`$p;>2CKZ5xZ%Y$D3e(ggzZMydmm; zUT*}`sUdiqt%50d|FG!4qzmwN$=G)L<54m!-Ep6@swEgs zpY8Av*_`+}lc#?Iyj^VhCwSiYz{(QZy_fv(>;E+AA*U)Lxc`s(m8PiAAKHOm{|}#& zmYY7ue6zQ%pgKO%h|l1?)#mb0f@pZ5KKf?HkWY#|ZW$2);O9Y0bNYbA63 z&i`lTvj1PPf%<!^qfPWKoagcbRnp~8$MJ2C2jv|{3Z5H%*wfI&1FcD zs9&ca=f1mA_ytk`iLI{d9rG=*?@=AWG~!c;dVg-~L&giF65n}gC6g{AR~57 z$}H;TlE`rRnx-5MfcK2Mlk<@Ne^>LkvJJpnS~bRW`6+L>^LzxKkQhGRawmB<39ptR zwV{67Hb^aA}7`5+~zJ?BHn)d9gt{M(kb+7CnD7 zg5~ihIEK=vLv~ZM+MgZdGAg{0JMb9ZNrhd4cz8#M`hP(1&i=^rXL_s3pl$=eyVAGL zWf|!I6S?1o!Og+2j+odkLx8tLTkPms29weG_H* z4iaHm3|%?`S6vdCPNQURZ7RHxk2)~CAKbeufQL87E6XVa@7;HFD0u71G!6Cxyls|Q zsvJH-h8rG#aoPsze}68|TSfqH(Yrfds{_2N8|o{U^ZUR~ht@QZFXH1JtT&Q!y%mhN zME#bO9F~3Ki;wpWjdSY__cI^fk*JPaG~&yA;;5z_!+7@oGIGCNWlsa{u^+YxO@uQ% z^eaxXJl^8%S#;@`b+oKY%%9Sn(4xW{`AP}HyWGr!9}jQ4H)}bN)7$H>_fzohRG6Ij z4e&NfQQrLnyuEeWq>a}AG$*eAIwg$s-kzJA{gMQD+mysMZ6Nx<()Hy5tIy)&t+?(| zr(T#eNdom7bMIVMdITSDJ(s3+o(q`|@1>{?LmKgkXof6|Z(=-qUp-N<$*Guj?~U*+ zRiotU|AP8IDvd53N6*Bby>jty{g0(Lrv59a|4CFi2>DJE%RwjPG{o_8kmPc%ht(hl z9UWh8gItgv;J1iEI!L44Rh7R$fm9G5B%cSCSk+tdkB|vc>7|FQPJ$dXa{H5$v%e24 zA^XvXUl{)kQr2HOS994yk_hS-^YLTHqR;p_DEZlDUEd<+yMv^F>bOKBzCNDNXUhJJ z=b)@-vGQB#xnie&^Rsvq>-YZ&CiLmB8(AYcqmZ(L)T6>1`S2LS`$j&y7#`lc{EjWJ z0eBN^1$H2KKb9Br765q5ht0WIbDj*Z-N)~u3JN5vPw~wN-u9#H^ANmKb60tIf)}Lu zu6Sz|cH%Fw+Gn==S%)tm5mCR*E|xR*7vSSvbt&`dRT1X9|GyH|QAZ=bqY~-EmsT^r zgPeW&c<_)O?E>kbYwk&b64t*UZE%b}9W$T36{!iL>>yWC;f;JrkKuhZvRM=l?~jUO z1qj|bH+k(4yp10>=6?Y@$o>>nqb=#+^Omn}fmHzSo%JL22;Ld7RWAbp-h{HM-CqQK z-~sQc*6}oayuBRfdPpkEl6p|TI%Vgdd;Ib7Ze093_Hr5Xb&!ssI@)N&M=p_L&*<|?hd&y6(;Plp9<5@L=cW3&IYy@wC=hltyzk9<@ zna6*6p2o-fWud~EN+TJPJ?iJeZnn?W2_Ns+7eTkKGU4g%5UL}IMtsSKH*G)hUmS1E zb9ek54byH;+~O#+K4)~0o#k=2eWECv6J092ky$4g-UY4)h4Jtn%ADFNHmqT^jq!C|2!O>J%A;vc+ zv4eAEI(TT`-XcVj?PhXAtlyj>i>6ep#C?c%0bAqCoBiq++8>y zF9*GI-L~=p$U$tU2eu+htmKB_$eo}-5(p<9xB@6NIAZ_WEnyv9=1=D>& zYJ%#pq7mP)hnjgOk?|b#JkLedabqLRBX;TDXc3O*f-Jwp&MiGnmkznIG>)5p9!N8w z!W$W1hT)y)!Z8mIZ~x)~X9VwLwOk7XZno0hqFc)$C+BOSqe<>t_B2;O>PCys9cc>gf_6>#Pp8P3jaoA(po zeRQC@Z8^YOu%yf79oRvx_@rg9YMVDKa$h#D>a`PY*6Avmecq;0ktBfnIoB;L3@gRQ zd$mN*4!4ENnGWw>REG(T`0iA+f&uW1<2}#0r-$t$9oJg~+!x>e!TR+-!PS*M9db7p zpcka|sqjVyOk#Kk?@W}y!`n*e+;ht2MA6+6!Tarp+dS zF}T?7N8`bfhMtp_lhvT-WGmiIZ8%J{IFWLo?Y|Tj8>|Lz?dW-3n(&@I(4j4+p7RB zC;pxP_wO>BY5xRvkj7Lw2$>m;<)9=7c{#isbm4uXGm?Xj&3$N%Oe~TOtM0?|_0)aZn&>gg!U#arJ@2?{+TMg7EAASMcl=Zqa--*e3wd##T%o`bA^i1!vhq2m)fm4O4d zT>lr`L5k?7PY3jMp7Ngy(rc;kMuwnccvo_a%i`gkbbpyLg7=BMLdp`G-ks)n8sJ?L zp93Gm(#y3TYZ_{47Wftb@f|KSt6;$y|Ff~~5g z^{AiswL@y(Z1In`#ENaA3Pnjwhj%HeV?K@e8sX$RR~^RjE;w+Ob8;3P4N{-*pR-Le zSpSH9^(ne^Ea!0VUz|nhAg!Uo8=2~l;e9WwOa>3{lTRNEAO%vP^=V3hl-7R`4g`1y zy}tRq84O74kWKI0`T$ICc|WfKIlZ-$KlM@y;C;$%v(WuoAK1=qru0Hv{OoEb)bFgnz|5a|_;@$%tITz-V?MkuqdK0@h>x_QtvTo@<9LTWu6?FrO8a#>0E_;u~iWyn{Q9DaTv4<_smf z1HAXE{(Sp1o(w;G{i%*r6ATl(pZXwp|GMW8zX0H^o)((1w$uk+wdBE-edhRhmkZUZ zEl2&{4{);mP{+r6pkzhu%dgCbcNMDREsgkMIWAalzQ;J;^6~`!Eputt|Af9e znI z-WN9D9V(I5!5?qAQsB8)UcM?x7xnvf(qeS^eEjj2)^=|Qyi?4#_tr;s*wKiuGj5gN z4L`>5z8lv&c1*Pa_Z0kJH6KZ#+&C$W^*1M>@^tA?=o^$+18#5qt^fZ;0Q3F<;8u8UHH%|#Y&v*`k!qQ8vWN2TI4s<9|Iv1C~@;PWY@*G_{goezf z??h29NSjjOjXb4>;e9*dg90Aj5uxJQ2;NfcsgxaLm;CNsVgT>*()Q&i!SU9^YZe8w zii6?stz)&i0PoVx9pB#oyi>wz1H!*}!+nQmt{Dl!$9tB;?ro3etB{_eetGbzb@6ui zc&py^PPp#De0YnZIy7m-_dUbx!Q6Tw+DqmCNR*Y+$}75_(=Lz*`EREsdDB@Q?|?nc zbmy`Bnh31i1F+l%hi3CbCPy}q;%hDP0$rymM@U9 zk7?7T<3O7cTlAmlEhbcWBadBTc!!z#%j4mFr9pN+a(b)u;soXN_D#^@j$u&$|8h&} zZ8}MYgS*|OIqreaTcQgMk?SqSUoVXR0C-2Pv|qfU&>Nm_^VWX;8hpG3_BVgL-L6a$ zMg3NKxW6!v#>ZRXwcUW}V&=npCaPmGjrin(x_34hGLCmqQSWwzi*z(d4OWbI1kPf4 zya`Hzbn5Upp!ui%Uq^*E@_H+V_l#p(7UJQ(#&6>;1n+r^6DYkmF(M?@0PwcS(Mv1| zB*UMc3~hW_8Vp~~d+V+P@c!XHCd>_vw-&?^-FUBg!=7?d<(&N1ucLz7y9G^SA#0AA4EmG{FwioGJ$)?^k0vXplp2DP9h0y6jwlro%_mKn_ZkzH#i#1XyCf25b=v z#m_;9H%z!sPAZVZQ9n14xWW#5{2X+(GTiiqoetAANROgA@@T}D*|Bn;{Vv9r*s)lb zlIgj$>wlR!zl9Sg?ODD+GWlg7LXQr%O|q_+|J?sKqrw|`kR8L@C-u219^O92rNJ)BxTqFYrzH0lYI_YpLzK=?&lM zs*=!Og^%~K0{u#=AZzp}*8d&q<3@g|slrc1|89kXRo*_8U9Oog`szd{R!_X35i#dvrxY;jqQ z;QjNwG-U^=HSL%e3-ET_0;zs-Cc}2hV$oILdW-mvh&T;^w<(Wtjs?JbKUWId&j@e$ z@*WArVF`S^kJ>n>a@#1AE}(wW9Y4mQar_&k!~A#J{EL|H^Oj?%j*m3rTcfF)<=4tM z-cvSWb02-Ay@MPa-BUh1GRX3H>n4QKrDNJix_fgR1@BE%c*_r)I%0TxRUTKt!~5a# zVF>U+?tK!aR0ih%!AHV8OUl7`%Y~ZaNdKQa^Zb-5z*}`Z?wN?M zH<<2X_%4APA8(nNAtWg?6%q;cd#>RmzIp&3Z?EOWD;{MrUx6f#>hPlx-~QTRp>iR{ zHz)mrO&<=#(oz3c#>8BnH^K6F6E>fwPexhjC;t;xWHB}n~$?)m2y2;kky{kCsJ z-Uo)xi)@Lyi;uT=u+@UTUKP@hls|qw)*^1+iTIlnx&5!!>#D6}y1lnQszZ@Rd|zeC zAEZBGJbQoaG*x}wMaTTVih_Vk`&hsJC#2k_OGgNSD?1_nZ~f1l1^@qu3e^AGsB+L! zXB~bl2OW$4sfCw=Y_8SiAxkXpwTF}f$zq55LuACRs!5qs`yMhpdYk*_doV#NqI}cE zB_IcRxST#14RX+;m*WS*)6(sNM3W4 zm;JMYw4lO!iD_LFhW82CmzsEZ|M0$%kKld%LNf*LiMy*5KLWgU8dRO50N!3pf1l_B z<1OE`<#-@?r+U8|hy!@@$_t*{?B@+fY}s1Q$&0_lM$Ug6})@lHC-+`<>DQ&qRRtmPGZJF=Al;|G?zVUpe@Aw{awmJj`B5szCkDl-NpUh2ZZX zi%X70r^++m7o<;79c47)+ghBo!y%P%yrumwzYo7b`}CF|bRg`U-w&3@o1kw&myWA- z#ivY8QSjbEg}2HRmunc_^_|Y@czBCE8@h$yy~6A{1#cs%>@#8j?sAF=t_^IUdF#t2S8kI@x z`n|3DJ*(UtA8)TqY3GL|m~XtrZB&OJjrg?3lM?EZ7|-4T>zZ9Ib<$D)Pe>RG+FPy2f*A8RI!f z=yh;{02l27>Cu>raGAaU%kLnK68-4X@iNxC%Vj@h2f3XJZ>?q9E3qZEPpw545AS6? ziq8?e&ChsH@E$AJom&9#t`@Ey={`V)<7dQqJ^|w`A+w=i1n;A>Y@jTF_YvWO`T$TM zy?f1FEqE0l?@Kx>EDyNKlHQO z<9HizpCu+%)6qeSUo4$z^S|JDYd(oS9T7bbjQ@0ytf}zU`1SNAhPURq*yVV5H=LYk zM)1B^p-;h^aEbHv34r%TSH9vwCo=4wc{U>i3`jG4wC5Fqx3Ic#MJmAChS@oxRDcu5|--tqzUdpfc+{NPUf&B^R_A&0A&@b#9*s16Al@kJh}TC>uL zalF&d4|)m7(2>2XCfe9sBUv7Ag83AEI#NV7DE-OamQ;AF#WwuwapIzAg+dVXXH?K7C@-igfV)-=dHgf;#x)E$Wg_wMh!ekt9&RZ2immOT_WVTSSxhN5>^G zU+=96)p3SKe9qU5cG@js9B&7$V>>Q1)9$?mOh&k`cg|SGq!l3jVa>{0Y7gY{gX;-9))&E>MmPEW9w958PKJo_1r0wKxkA z3E8QHM1xYP45eY01`R@zgpd?XNRkE`Wr#`&NtB3+QlUX<@>|dL?DN{MdwDtn@YW6M`#|PhJsY$Djko`T-0$%Ff6F&~BEA17 z*pdAq3GgOVwKXt+7o>OhIITVfR&R~;$~lw(?}LXd@;(6GCCZ!1WQ&N8CAJp*h~4kT{$$`e)E!u~wC3{=7Y$qwBr5 zP_h5d@IupASdad9kXFB>Dvs&Y=}Su(65;H?J~_G{<{dZO zMS8vUgze|p8o>ME-mx>9?gYqQ@W7=$aR1-QX#HKvfcKb(LS_Tto$3=<_x=D8D%7_s zZ&--V`>25_*X{S>cyc?=?RA#l`q3vRWm1-3wh(FWfwbdD92FS-V>l50JJw|WygTl< z4rFLxZ%*V~Uvxk^jEnAh$2f6N702rj&tIQCL7JR6QSjC}9h^$$o#JzX0gd-UhtLst zd28(C3)1pdpZr3%-*EO`>%4c`j{y0sOAHVMyxmjJK3f5Jvu~(-a~trUV2cc>i6%nZ z1(RDR1<`pA-H~GGb(X+8A?@N-@wfI&qVrx?Aj%RmNqfA%A#vDX^zU||ice!17o{$sU9gMSZ(SPzOEWb7(PB6<_uXTVgGS%gdcyU8f|Z<`7|1~*XJ*VhL4nj>`z%=sd?1|@s8=Haa**Fs z|LQPM|1a5AcBl4CDCEMh+i+MN{SML?+e!`ni3NCPq+Q?8l~#Wt^gBoecCyxLk6RNGijbLCdB5SgPOA+9rN?2Vg{Katm}R(kp2rKaS^KG2(I3lv*QYBh;^sn zZ6wHkk<7bGNnjBg@BAOH(qP^Xx0UaLdGD4mXORWG1%z!RV{HkLwu-?*eK5qbMzfuf z0=#qWOhTOi?=NxJGTnkhA-AQ!wVv>!^EU9V3fi5v5KnGrd_1-1&@c1?$^F-OiT<1r z&G9xy;y8fOKOxq_>BDvN=iQkWx}kqb1Lm^W!6d1SI}SZ`&wE@%nyNUazK?~;*`0z5 zq@5JJp}|2FGVk@tpV`rPXWmfX1oK`bbKV2yy}fH`r3&D^(XlA+#0CPSY<4~%4%GiW z#@eAWfcK&HeX<6CwyVPYBOP-9O z^L}P-{p8h<1kLegSoSB5*BJdX;|>t^dOd&MrL5jT(x-tRn(b7@ z0r3OC*s?5;MGYHmb`H_5)>$pre| z8}0;trP%kD)a_XxeJj4bNi=BUf52Sx?`LX!+J_00XZa(@8%pmte3|Y&;5ZlWW zG;sqAv9f8e9%XL}g??O9)3`Q)K7%}1D(aHFyrXIaX=k<1-e{r|eTe1JyXna9GGOqZ z1N`6pC%#A=r*;3ne^ItO!-c_YQ%WLx4`-THCZwD zZh`v$TvJ>G%sV|Gb;B*ddnhC6tA%kWB!X9ny3mQvdp|>~-`Iji19H1uRaUcAwdlMX zhHULeliybT?_&PXzj_K1$D`rD?;p#X+zHwB^XEOOxN5``!X9EDMc+$s^Ngf>-fsT2 zRK+3jGk_?2p2XXWg16bY&0#Wc&vRqkXuK;}M{Ydt}X_=PqbOD$kYpk!dg5Fs$QY3F%l%mBppCg6%-bXPg6SQ=dyUKbm3_Qn(B@blZuwj2^}p(rt+ANRxBd`aKImmA^ugg+jr_j9;jR5nw#fIl z!F!~gR#@Jc?iO_3&t90G*jmCxd%Tf2zG3vwp=RO0p`Y{Tz5A%=)%qUn&55i#YZZ0C z^T+>r`b1y2>N2BcMRm9o>S+| zjbDU7K6~#GC*9E3AcNe3OP34_R+HN?mhdkugwWR@pMU$NWoa*ur?ubmKqQU^jQ)jq z#C-Hontu+mk$f=nW{`?ANIOSpdHpcb5k9 zQZ(N0Jl?-)1iT-5h=#ztdn>~?tOUFRFRXA8x=DbhcVFhp2fVWy*iB&G-nDb7Nr3k& zrfa_zZ6-oY$IE_C4WjebUpH=pH{h=(w^QL6bZ2;q&inY;p9ynyk~GJg97h~R|DGM) z7}Rxp{!8o&--ep$ms2r=4Au{97Y5pW`il6uj3y{}n~%?a9!x z7>&1v7tzg}fcJXo=mRkCRYX=9Zos?kT>rdCEGDeNRg>FE`s}_xdky{e)>y{OP@xQNn&Zum#Nmz6 zzn%K)%nT09KYK^YnU|^iVlQv$ho@fmO+7^Syd|`$i-Wy)N0bz}APvmDeJFUZIcBC! z<~`&Q#*fB(j_12R%zNy6*nXJz*P~6541jm*x-HHOF$AbSV0N<_INowetyl);9b$eZ zE(`G9Q+B2HNOuUNx%fezuRnVBZXC!6+j8oAl?Ku-V3qnMrw!=YyQ^&AWV1Yu=6F9r z;;6;w-`7r$hl8^7&)zq)hF899e1MuJ{;EY5OdiVSiJ*JlxXV<=p}qgjvVYG1|Mj1r zrvC!upaT>+$PSWjAm^aWMAhYJIjC|?%o=!uly%uv(*D0jc-fwCut6I9mME-plmJCV zFIC}bjfKuO1lq#i|4VuIUtt0{=)k#w-;JO^I;d84sb>g12lZ}TFg_b6R2_k|V=LW$ zZ&4F^4iXC*y?$qa_UiwSNF2f#{d+rX9ishTxFFpNRUET745~xA-G| ztZEDT25ELO;Y;}iWttme$B{TLVf63xqZez>a?O8;Re$NC_Gyrc1JV<2Kbm{~4}AZx z<3&{*Rx^8fh{dECq(233oBN4gWZs(+9*Cgv_W5!p1D-)zNlOI4yrn)q7OMfgm+u<% zVM`-G0j49;-OaI3AN!^RX}~*NTyBLK;C&{xf5Y8-MCdN=Vx;wEbl#U8nwxrA#H-2e z4qt7kVAe(FeI!EtO7ohPG{-v=iQ^DP|MF%M69en#&l@)#9xtbfy}V_`d@|+rUO~E_ zL2~t;rz#Gm=AeSqC{q2upMp0be-#&*_YJQr!f3n;#p8Fv%Uf2hhNR`K@zzIE-vMvI zMbfw*xdcemS?{zEc${e9qT?A!zxqvQauUpOn4#QSjd2bpI}ycgd8K5E^f`*6pOdHyNpddF{RNd^m9QZUqrq zxn#6l)E1rhxks7tVP2xu71I!ED8>}22Rkj@~rFx&_yf+1FU(s{RKC;>8X8+$6#77KAcsGEc9|MZQ= z=ThHkAY{MR6TfG+E_}+4q?(2Wc(#d>k;wb1ivAX8Z`+p%6 zyf=T{@Yffl+Ij<$XuL0&TZzI)?D|wbl6b#dJDC;)c*obKT0R3$?AGaWFXRTiMNK_T z;rsv29$Q#60(f^Ci*wrEB|@*wnYtSZ=)4OE$+i2mSgOhG-WJIxZBa+(O;DUYE>^IZ z=6Gi#aadyXPq@>m@LJmZdCNamKi*%3J;dTvXPt}2PSZVa+|&SdacnjjP4Fh&{})Wb z+u^=N3ORdoey))~<6XGP%L?Z0eEA&dfV5hV$dEta{Zu;Rd}=rW8v7}3F!m}In!LFy z0p=ZKoUwEm@E#S9yf&RggeKnk#0ATt^X{AsvX;x>tR}ac4(Y+Ou%YwDFXr9%vVR%P z@oq)pSdGy?*SVp`3U%|JL1swoRT<;QuK$lMcRVwOUrP4{Qn8>3RdF;3F*R-XCe{Bz z6udX3j-Mj)?jB1KN8`=ISQ!fQc39`S8(!YxW6D~%2k=(xOmwY?1h2O)b<=7EytkBo zA>H0ua;0EXKj6(iE+nlKPK4f?dB>>! zBxsIzCK5+7M*j}4E9W`$dH(f(MnvS-r*E*ccck+3#5SwNbk94o_BK^Qn!B-58_hpw3($`x|8FG=aaVDvlqehdRo@H%NeYI0f(RL$X0+-U5dG@@TweLc$YZ-tQ{%Ni#^o+mp5V zfcN$uF9D$w1nA?J&#Vq_V`~L?icsrH58jyJ(^eB@<<9)I(XCus8th9zy|982R zif01er9ruZ_#@y8Qi7hJ#+z8^*3G7Fxc*Q5$}Z9ecyD*rKlEiqD73(UZ>P=^^z2^M}Jw#9V!(H9XI{mbhHYc zx2BDI|ChZVs}hiQ8{bBY-OWVj9r<8E$eW2DG?%^kkT~2i`nS4ny4Z3dANE1#|1i@{ z#I=7ntitA<(B1PsWAj0}=PfJQM^zm0IWgryF{H^!C!7-gp&z88qITJ`^^= zdv87;(@A%4Z(6s!ISlZAs(=5|WC#J8d6ck22W(DQ3%XUndv64m>X2!`+rzNJpaSp~ z@a9Wz{2ShW*9+uKH;z`3+daASu4LwKc=JAy`K;N_NOSeS6A}j#M*q5Y;F>kH=AXS| zY@Ssvx{tm0hO>WkMCrnEx}TijT#KoSBjo6L?<3j&)c^k>8`9?A#yTb}pvXZU+_HbY zAaz`jQxz=-S+0C}0v=-ROR7l)lDmO~RvXAco3;wdYl1b%vm4i6T=gy%l2A7rgmcil z@K)(jkb`<$4wbiT358yKF@CH(jy}Zx-gs*#>#jQ!2 z8)AEqI0zX1lU{bKLfU)&IjBx{yX-+`>@P@hi#K!c%!sG|9AxiIRUBFAnuZ@P!!yVP zCJNp=Csh8rAboB9M-?>Qr<M6P|X=1yb{$L8h1O+8WK?h&l5-^uzaxPZAT|&mgat`BN3g*`R>b zyK(RgGJ%nTx7({xb@B{SuOW8@8t=|mFDqf*y*~p;yoF?BMVkO`@l~D#fdm31U$;x( zQD-cqFlx3EUf$|+y%pF6cr)|_oY!Uug-qA^NbEh2&U^B6c49^RP?ZtV&fnXNvG^c5 zZ!7=I@Ra5mn&aJp#G#7Ozfk|qix1Y#KYO2Ery3iahg~4yikA7U31p{x-nfG0RK z=)C3uW{`k40|jqaqTm>r_fnT&Wi;Nm?gqEPyx&Z8l6V)Md*oXOc!yt;$}2fZfTA6_ zk`Dsjv5$n_z`P4~OkI2lcuVU%2o0SeLLm%R^+8GKyuB*+)fy&$tqMfiSyTn6MERrh zHqJHnO6-}UIo?)C910lyyKmz!QO!R8?5&x+@l>Hsp_?Dvk(^ z_UHFW^?w46g15`s8_UVOjXErp(0D5_r;Wh8O;k6KE+@`+lQyjaycM^|JNc&)p!Fh- z9ddxTI&XhG{CewYt1n(p0B;eOPZ`F5_mFF|KJ+)d&-ztr$=&Fw8bI2))LoKX`!~D= zZ}L{(mLH=z-UpC4ei!_G|Mn{@=Ju|hfA*GN{IV&m7JKgv7rN_Pm-7PppL_3grYepl z+1sLjUHqs1r_F-@KlBO=vFsE%$cO#+Ul*i{STL_f%RvEe)=0sh*o|zq2!xN=`KOE} zRf8PVwrJ%Gg#ZF{Q|WVc+k5cDj@Eb${DPE%%Bm?D@QK|@m5`-!TZvHh4w-(tZ|L9u zZxS`BJY~&ReFtgB>dGOo>lyk6>FcfBQYPg~X>JXYfW*;)(Laq(sayTk=bwWXM8>sx z`%!Vlj_C&VB@VuHpM#Pi0#$Le%e`E1;WTLm$wtB3yI*QAd58^n`KXD;o3}#j1pI-t z(}#Y4nD4 zX1Ws^(RqJ7{oXg|7p{60(r(4xoOiWX(Ro8zjt`HX{pAYahR2#Y#Sw)0q zR^Sf_*rOLn<-%uTV~R(rCXjZ`EHY0ntwt}9?vDD43>wnj4$=)Ij(m*%Eo&}a@OI_= zc~6rdu=IdZQ$8t+HS z9R@IO-qnXmmlLVW{!D2GyxX@_KuqB4t#@V>pA-OZZ%M~1@cVxqGMdj>0dIzfPj_A^ zBSOUeO)K~|pz}WOuF8kE{8)7WY3C^2kQ<_k&RhS>s=O<$w735sfy5z&(LYvsdy$<1 z^XKgu8izMA!aluqJe6;8t%)<;^A_!+E)E0kzKK_VCMV1kymuKsE+zBcl#EwH;~f&u z9R}C`0*!v8y*HuWQU5o9_tAj3%~=rysH{4z&=qV>7?s6tg!kSY^P(7LLH!@6qxAe{ zJrS~grn4>41)X>Jo-@_P$9t>RAno2d9o^?`g3h}p*()iGd7S3ze>WtKY>fVi6ngCH zub4k?J^YX0f`!;~Z=A_fv4agi>Hm2Pqh{*j;Ai?G`_KJ<|Dn*P(Z2=tKNm#~+8>qE z3Fjag@ctiu?^YaI4oYlM{Q%ehJVG|43(_C1W0Bi~q#yL74Aa?^vt)en(&9bNGshQ!f% z4?DK?ZRk{>Io`!c90M5rJD+gQo~S$jA$He$mi>oUVDskbcF^xI@1=X*c1Ng-V?>jC z$m}GkK;od_y(cqxoIHcvUVL5$jkjZ~>l2ta)5pPJczJ98OMzG4zzp&ZacF%6xc`sm z?OCTgU$Z$-&)fh4V+8=?l$U4O&TZclCQHS>3>PP2oyEaFu{Fp#>Fw!oEsmt@# zGxY53vuXF;axQ6_<4r)~@WSYy_!gqeSMB-p7WgrHJb{|mTP}Nvh^*a5_w_$6iMluz z_|1M?{O5SfLJHo#>Wu5jysLMv&_d%Kdc7nc=3UnmOyYe;(}ceQ@SfWs!=k&N03D1e z!5Myth3egel;FKLE@{(ED*9gL`Wz2%|Z=67;Q0d$|e8>F^S z6^EXXM9(pBIFS>Syvz*QI8KR$#;k4&V!&Vi^9QZ{4uJZfpCShZ4R0Z>LBjR_k%e|F zXgR3r8Q}|@gYGtZk_se6|Ck^rP#_5(NSDKd2h!9D`uW}96Fbgz6(!3+4oZAnr&tSe zQ2vL|aGkyoU?Y5ERxtVoX@YCi#Mni#YBr>umd5#Ijdti8r0SJU;zC_2G?#;pB5|l- z^snoS{n*0f`Pcu}yZ!jiQgOu&?sN(Fw&wzLpMxT!3#f{t!_@us)*MoS#7Dt9u;QF7 zd3np-QIZ*rw`*56iFdVw4~h4eVvck6fOk)-FaNzF0<>I}C3eo9mQT^x49E_w2I>p-Sgfz9ZFRkFV=quJxaPkDuI`R_kk44 zBr@*{KgOBRc<=UN?1!^=0^?p1Z|;Jqw`&3KB~F2hYQgKRs}qjb^a9?KdMj+DK=!t? zFT1`G@SbML9BVxq0$K1K+=3H9=dG_#Y_wApt2Rd3t#~Bx>fIRn18G@XWZKkyX^*!S z5=RC`|H3YZ^$W1gzd&;CI}jyE&Fd|DMXR=19H)EUxWpyY#lge;di9_BpNE2XfPG*d znRnyk3Pv>Ew!};lZ^idN9v|JZ}s5#;*6$hj(lpI{A>Hm2P+(&7u;_#FujEEGGCMVn!y#3V} z+sVB7B~LJ*@g8gw8Gy65*{5I_5Jl&iov_`agH_{G&KylZH1a#haM;DfEI7@r? z|5qY$lwkBP-Oqj3*~9bC-W-0ceM%bGUvKRlWEMVlFrMz0x03G93Q-fsmiA>4$0Gl! z|7oq%|Nr&})c=AMIVgN77^aZ@|E#US9B4UcEM^JEGmwKe*oq&5caR=LJ-ZwQ)*ubf zg=d@GB|ww$kr8+LzztFwn$3$r4mx@${HFYZXVA`mKA-Q8L!hVimlizPf}VrI7LLjr zUze?}L)vizIG8c|H=X9uc&TXqysgbz(#7(y z4@l!eWhGrA66wD{icF^}4%<;C-X-qQFz+Q4yhD>ZNyl5@)!Xlzzq6z9c0Yc4Jk*DO;G=vhs!xje2j(k7ezY@0^ZKOsbLI&w~>n7FL5w~T=Dqz z#i0Up-s009O|vf~s}+!T9wB=fLjGn3`CLCgyUxOP^m zq;_`*bTdif`7wWV-tUzglLV8+s;?pKY*w)(r*1&!ZU55{ANPXxR&U91*kJVUThdn( zf2a9pZ_{OFN7jg9*Z;|@e@CeM9-w>Pi5IdXsflCTME*wKBmdO@|KEC>*8U+FVnr!( zP;~D=4><=V1ex=p_6H5aI0BTcdhGUiZ!GjY zqss#xV)=_MiVlMuWN4AS@Wq2rDC&1-fQqXR>cw7B{JLwlw<=VJBJC1*C1ej-Iia@S z_40z6wU!Re4Y83(9G)2cv(G-4miKo4L+nFS+wWq#8&H2=$lNaUT+a6VLjPxw?kdJm z702H0+_<@T(gkVDD0m-wmP0y03eO-vTvO*oDqJ;2pnD<_RNb_{STlVVO zt%2Zq3y4RRTNx~GX&D(C!Ud9T-^H&uP#^{F#>ID@4~5#Qinpt3qw_uyd)uk`m}2#F zq@7M5_gJ79I`7qGD-vA>Xpc8J4y^tSU#k=-`!C!eWtn+Cq==d;c6@e))>ix<_`IbU zqAHHbz{$ReO41IJ2nFw`kP_1KmZbV$sht~*cjo0TZ158xd-$;t&UZ>0=)`U(Kv;F{+^kCUO0)Jfh22UO5`H)pSGl_*lI7Dd{{ zuibYja4|Y>?^it*joi94m%YhxcwzMK%7C&;(bM^7Z`+>uSM3AX8>AeWpEEl0`su#@ zmrO6FDvn%(H@sV-NZDJMf_Ef7r;t23`S3c63yt@Mh>fJp37It#^V*z{F6LElJRJ%h zGd~{Dua3?;RCV9aM?Vy*V~}?5US&+p2%+U60eZ5w-5#I2=U^-zP;U9>CcJAyWUfm z#M`THetU0)=Qzc2H;52}8ARA)ihlloxb#?zMv#2jZ%=U@K^`W|J7OT<2$nBvL*NWJ3=-Sg&%@S-Y?BF|RE!SH|X z|0CC4H2r5#|4UNjpd-)6{#s(+Dy1ffmV=Dg9v*`0|J9?-q%}xYQ?6K3FoP6KNtokx zCP0anKfD75W1(+Rr9PZs28nliv8E8rAm8(zmEIH<3h@L@E?X{yKEyUY@|YUJ$yBo; z?ab4czN!C>o`Xs!Z!b29qP-2$dL)iJ82w9PyZi7v*Zhar?uucTU~TLnHqB{??lQ&g zcWBxo6`gxn5JXiRHJVXBPrHzYSP2T=@maew$umd;i-k+kcw7CLafNw%Cafj#&T>;} z*a3K(<~vV%?Ib|jyiM{61F_Kk{@_twz&mpB!&DEz+l#?Y<-)E|s7ut&=q7)`rUgytyt7-_ z)lS>UR_7t@ggz}+V7!A~AU*iWF8{fH70t~cvyeC*V)W0l;W3BKvibAgrpb`|n-P2U z7H2Bj%wW_*|GWc}sfwe;dN%jSp9|8&D0s&ihLEnefS0$zTdoM8@wPtNC$Drtc^|9aHM^Ua_6j5cB#s1({sr5#<9>XbKkvQI-PJV~ zHDYc~1RL*GzN9rw_XSeRB?GGBxGkV%I(Uqhti>3b=WHNPe%((7Yn*HaB9a#$A ziO0mgk%!oY0Y8?Z@s3&-yA9^uS7%K+Anjih?{O0Fe%M!>UaPkOn%#G~J`eB?VhFQf z0K5Y~K&ruj_gt=WcM*JfYoYDT1;Wunpkr#a}n6CJ0{ocf_b zb3<%55=Syd|EAK{?ESJ~{zI(USB4w2N3jc}^wUGzf;{Hvp7(VQ>f$i>U*PKS=lwq! z3f{+eA8I7?W(#~Gg2vnF_cA4zchGPQ>3EB;gZ`1*fOi&C{a%@@4N&Rn72XbjcVyx9 z{fvOO$o<3VI{|OE-KRpVOo`A}!7l+<-=Lo$ZGE1q-6JMl{RwFocfkBw=^gYFq|kBA z=!9(A2G-Fzj^)L z{V?tEE<)nCiP68;H9Lhl9?qY4dr98#+GkX}-Xbd>XxsIP?s?2*Qmoc)1Kp?09$m{CR)dQMeOg#r}E=S5mw=nr*!7f4|uKZ}xz@pQ<EKA{}6kKovJuI@O{%C{=6WiM8P{H;mkWS?{_vsl4!gW?ME-byjQKz zCk?TUvRh8J0N#0R5^j96R?wy>8*Y5{NIkhEgAk3{JE^%u2E z!_av@-}J~+S5CTm0BNT=^3(d*4s_n#-#MmF<Q~mrged z;-lh<9Vxe&c84=ecmHQ{=D+V(sY}JZp(c)7N@jg;LrFVGiWIz0ZBl3>^IjBuR|1W< zOJmM=nD-#_8B&21^hERODBx|l&V1Bqb}h8*)_Nxuz}r2z;x5d4fs^3Z62SXcdWY2l z@cy46OYrSGfAjv|8zu)W(bY25dPqCh&y%Ba+UUHyR1}3Li)n8L*@ndN38R0fM5DSN zo6kRcZ!R=HyzMvk>8;2lMGwJEY;?~X_fmnXINGmnt?5l8o!(NQ;GMj(`mgii@j*Tg!Eo)?q8PL>)rZ-F0=PTiQ=N%y?tCmvE2N6S!l`>sFd|K%xopJY(~LC)TZ z3tYv}cLCD90M5r zlZrEwk7}KN_HO9T`nZsq*IO=gn;gsgKT!W$3Q!k^|MDnhu)Oup{r~^IiQ>QPCxiN5 zjUoqKDDnU64$`;RmMWsyE=d;|0yD@DgFT}A7a2qEn=P|> zMq?q-p)&<+U=8w_N!(!;kb~}g63Jj$L4=rj+XU|1N8dr(d(KQwQ~`%)K-$@aw%ld9 zjJ|^;w=|U@B8t2EU-tX*FZw|T$Z=rwZ-@Gh#6Z{i7f4T(JNIvTfIYQh);?*+0(eVRp5a~rc)Rj1wQ1}PfwB_TF&BoQ^Oj<|S&%#Oy($A~ zcU$-KE*S@O-tS|6Z@-&@qq+TmQ6vtQ*uU@J%fRks+R5`DVjntPb-A$&`-q)%xM6wfA-FP_4RYmIQH?D zFZ^LLBR8Yzo_A7I2vu>Y=BN}_og(pGLBad1fa47^Z}t}+GHASg-dN{10N#D9)&VeY z&&gM!cL47@yfH8NcUnM1e|fdrp#FciSnDjjyjAMeE^!_3KH0V8IT7$a{mX*I{BL+4 z+u#w56OyP-M%r!TJlJ~fZ+IU$DG7<(qP^=ak0Nm-V)So)iX^_tV*b2?YE*wjoTK9I zZGV-0r5TZQ&l@*KWgKc#8Y=(P|No*2^56VpK>fd(A_ryW5=d{5!sq`}ZnCSQ3-afmgB}JrIc>UvUH?axu&Np|nbLjzAIZc?RUCUN8nv#ckcQY*6udJ63&Y4m zY?{a$6*S&?XO^hJ%Ui6811>P{tqDIDj|1M3OeO7|KDv-wfq)FhbS%_Rb)yxo|ECto z_DX;uR{caIugd3%ZzFYWJ;!tX)aovUm0?2tj{?NDu|w$@pL=6HJ{ zacsospN{(jZsyPP=bbf?fA?H2_6)L1wTlODTS)i3htoe&701@6GdG2^NW3*Ecwbt} z_t*V@ToyN0pz-c}yHOkF{Y;aMw0awSEw%~X|Nri2w9$R7K6K@3*4M~i;Cc(8JS$ef z`+@rLabdvw!IzDPH=YcEaAQ-01Sxdhg70o7E=rfc&yN0S7j&TR>eD&&_y0tn$Gy!| zRiioH0+SOB z3f}4bI=tlUogNmTjK(|3jTwS@59LUac)t$uRUQGnwc}o<<)G&AuJ`322c^Xy*MJKoqYd)IJHQ#F zFLNh*k7%hwMOg}8xaVRawU%4k>_85x3Fq+=!99cG4F#|3n1({n7o^_2^#T11Qcjc6 z`Xd9;_!gv{{qE1K@9NOcAl>A5R3`2}MRPeQ4~YY-fBs5uuSqrYK`EtO*YS>)r;krTrcIuyQKZzRWr78d@24K_WnO^orI))MGf8a#vRqA zDvp5V#+QEGB-Q^q6uh&IN6pE+qXV)u(0E%KRaV~vyx+8*TT9}dplqW9cn7~*k!<%% z6Vf`S$FdFZ#&@%yS_OE&-gQG+7`!08cP{>>>mU*84%<`wIS!q-{;NA)`m?+6T}Zn{ zp-!|0#NJMj-%wR}*h49gtvuR=`T*Hb<>%5k{WRCbM+ zTlh3!wtw{H)*--PRP6+?Nk7~@uxF9;Rn)%I=er{wGpAH z$38qK_M-D%mLIE=F=&GiN7@~5*(Ypdht4~7wnm0M!iDB|ljAsx(LaTaUnG`}^FnhK zTi2u<%*Euo@Y8;o48WUV%Eb#$&Fd|$Rlcu^)aaf!?#mad;Gr z;T4(pTRuHCG~S_VdjsLUH^RB0?J#fh-rMBiY_*P8+7Qn75Vs59J$QTAV>#fx^YNLz z=fVAdg_Tu1R`n90j0IbsT#P{H9UHwQDEG4=J{@V7p417xYDDL4BB*t|F@ivIykn3! zj4}H6S>*fPUln}N6S?qb3tf+6@^-(`a9McNt!B-pCcDf@>~C*>Z@;~;qFa^jCnrbR z%czRO|4g&yj@WO)Q0tzHUiX3#KtS3zR> zA;Y1oy$3%xW9Fc+k3UTa${sa&`xtKQZ=vFfoqGFdw!QpxpM!7%o2ZN9YJ9K!pB*HK zf_J_f50N~?E_(P_7mYV0xqQP7!252^>@>{#=#ar#PB4Sqo9j0!%A^EwCA?3`To4Co zhFrR{51v61p9!eWH9>9_TGF@&M5v@_we=-O^dZ(Q3p%3t>N36@YtFYeyeTa1m z2+%QiFQPf#u1Fl)F!~qW(m&!`#S7gEKETlN^(iKAqQ0E`uicI{m4oS$+&tJz?2!?# zB}%tkp?}_zZ>fsIhT}+|*lp4b5>LVVy3W~AGVk$Mr*zPGhd*gQT?lwDY4K!-XOQxF zS0|+b?++cVdX-Eopte=gZ$B``L2qjuOuPZ_NrM!|8-RDbL(OgHt3>E(tKz8?BXr&w zR^VZ7V zsg1_F^FjX8+kkgfU-A-|H^Vcw923CXd0alCcjrn-p22;r85ak6UM=tR1iW1$+R`5Z z-iK@kW{tCnP+I8RjuQsxycs?Qa(vi(8h-(4Ct1?>I8Y3oH=q0PyOQr&G{>792Uh>2 zYQBAVvxX1y(CYiZXNJ8RyZO>%&m32L&CQAS35P}4r?+rv7mD^((?4$t(wmnT{fOmVsq%6$)P=C;MU%;EE-+Lx(nHuy7r)Rbq z?7cb4ZfkV`yq%738q)jS1kH9i8!m_ng=~96i7m^~@Bh>C5sJU>ort$V+HEFw@NQ;7 zzyI$_wE%}&@kN^Bt&PNi)xXF$W^RgIsRdHDx9aJy_ws!)#F;L=+!MxD9ep`JVEh zeZN5cFPb*3TuX#Zrvm*JZ$=+tt#|_anctP+Es%E01}tJ$>7Wm>p0kBGBb&!GmxId4zW9MNYlIoIzeUDqtR!^Qhq({kdnkGWHD8DbCL35caBQ6_$29Momc-J1n?uYAy1|8}Yg;!^C~xHOdrnNP|~JF1}bzQz^kYOGm; zw?x`Gc7=yu=R)V*A1d!!Q}&SNcwa~2!0O-rzI9S#v%HYAfK}*dEH>}$bH}bNm++{O zV3o))_=-Iw$By6jUQ*D76C2)LXODw|j6=lF1KvE9_eB$@o1k1C?t$Be zq0qqkE5QaG=)6~1`d#b1SA_qHv>WLX-`G@x&fBqQC@OU0eVXG1 z-gyKTi;d4Qv$rFYpw)4`jWu!|<#)BqunQ_2cYbrh9{Rr^4Og8+RUF%w&y?LfOj_PD zrr>>Z=<_l%@2|Oc7}0otcRj&>1@P9ATk-^Xq-LXk>i>U5b^h=F8KC~RqR2sa58fg@ zu>%)K!*9$v&~nhyn%hlLAP3#!?pp)rpi7&Qq->Mj4 zPy=$%K2t|78BqUQKQh{ICXNURXNs^X3Zv(s&&@K?Z8`VxVn{pXCH=FEztD5gq`zn8 zd)*f_mxIW0Okniy`J01Hwf?-2*A6AGExc`*L+mNyQ1PBzQ>gRM;k5iQ>>PCO*W{3u z;&bhPKd682uTWt!N>vFl7-sCt0G5WWlF@8 z{|b}$LF*TJbtg=rqWCnQ59g_<|9MW=HlBM=_q=g_S=7bB!SPA;PyKI6!MjXYV}#5* zWlt|V8t*K}%8{dh_jwJQJuvT|Mf!{G0^T3kOva)emO$CNO|p*y-fj-Vt`7n4gNqv+ zngQ>}#XBM-XNb@%N%Kt2Q|Q^d$?ZKu-2EDS2hxu7o3Fvr1Ly_P<6#$u5%y-9<4umE z4x@iBD_5P>2;_zCtu4=}&2Giy{q*BU@r|!7Ys@Pj?|n$k>n+haVNwF#I{)6>`akf~ zhqI`PL%vO;-8z?)y)7tsm-I<_lX(la6|$l6{`{yc>;&Lly0Rw<=KWf`dtU^cz3=y` zzw8i#BD-&nmjK>lA*)qj-VW}9sV@NUN|p}ibK^v4dK)utECHQ&^6U1^!opQ}oYS9n zr3W%Meepx*-4!^_czo|un&VB5;~hr-MouQGw;J<75*$y9D;4 z?})VPviEgdYlvPTZFF~w)Tnzyb2%smiDLss|6IeLW@SKpP;cG0(J70!m_zKk{$2ad zuo7wl)Q^a^Y{D*(B01Uk`L_$x{SrHFCo5HPjK;sb1yzt{kk%Bus}0Ra@BhKeTN7@J zc+q$>LbI#<0PjJeJHKGw+fF%uxDNB?`SH;3MIZj_Sp(^4z`Jv&Oll6`ZLfMVy9V%n zt9{wOwsG#D7i_0F-bP3qkr@3G z6A(Wv5y1zEy1TE~nfL~icirX#TMjeYLQbNYZ)eo+W48b4{rvbhk8rx@J;UBYRUCqh zH+x3^JdnPgf_Ifblma<>E5CZpjmA6EV!e((;60_G&jrsQ8^&U1o&esFQ#IqZ0h4&| zQx#sn0PkO%i&ho@-lbivYmESJ0t?UfP0B>5e}TMhVI?|mK{>lETBCLNA*9_c-qKLB zbLhOY+B{^c{n}`b_fjN|OpN}8&CRs&g75!#bDo)yZEMHmT9m?Tocwzu#F1mTFw+p5 zH?Amj1s~7h(r)`*xs>Zl==J~Mj%~T3Q>`?|8;`^hgVDbX*T!=HU%XJsxn;bU zlwM=<&bn?VXu@U&C9oW8eJp}q|7R^W%^lAlru*z2XQEG49LD|Mi?zT9(qQhrmV$Tr za$ct24&scHvaZ#}ORZTr*)o%aP>ZHcA)5Ahd~cDoh#zj?2Q&fAQ&u$t@A zOPb?Nj>80_e+lsp8%#BMp=;-N$l*(|_udGjdUv{5&7iQtY4e9~vFm?atMCR-hwb#g zIdOl^nwmJu!=Fpu`KSK>?^fpjGyguwL3R{5=n*kyoScK++|Uz5%|VZc8rFjx^Z?v< z4i`vu7wc88zy;FSZC`t{r8P%R$JgB%j)iQm2NB=`sg~8d={1-^PHiUO)?EvMgtOa9 zEmon=AaCxwu-3QkIbIxTr&BM;9LIw`gN)M(Xl&fkO>;S@5Q!reqkqOCVxnfOd{7jx z6GzUC_n1Sh-Dbu56+gDuB=y!B7hI+y2l=hLV|UAt?uXb&d26cT*i@9JSCUSu|7|IF zKh*F4>wxs;cGjh6yf1V|?Xv~Em&nQ_z`RE*O21x&XOKS@-`!)(U!!b0<8&W9Z~2w2 zTlx~DI7vvQLe1{}Wh#!hjNKg5 zx6h$_-dZt5RK;P-cF{Qg&jV>2DR@5+;))_?Z|Ajd7o+jka9samGvNL1d){T3cbbN; z?pZi{$BNxv$jw>9u={p?I=KIze_Q^7%YgT9b56abfcK}7GW_)Z5QxoHd)2mCFVz2x zOwZTbk7_2K9agPnq9ss{yE-aL&3ZDRZ0?> zH*QV302=R$zAN8s2fTy)+R9G~SQft8{k)-hxtHEiiBC?Yz4W!P$GC zPkWlt$Lgx`@CA>+=PexyyB_BQ-eUEF(OUrT0fA|^w>(71fidt=(j|1>gJQBK3W87Z z+mLoM<>iB4L(zFFnv1C|4eX#f-sCuBG5Tk8+JWf`7eC}#=_~s2DfZr*AM|2wR*6u< z^-|5+$r77)Z~h7c*CYINpS|NYP#1@xy#C4C(f{24M;B=f)c;#3a!})0g-LP_`YN$% zIa&^KU!p&|0^}euzt$0Zkb}lgvGA+`If%!^?$Oyz$~7HEUe)GJv5;}NiXJ?~awR_u zWdJkC9JQ`%EEyrtmp=aO6Y}Ue=*0D2hla0h_+g|Sp(EyrFe`cv61!~hV*9Q>n#)1t zII#Nn+|N#}WgQ<>em~EI?c+zxA@<^M(=I+4of>7%D^K3{Q89xYJg0qc2BP~Mgv&^! zE)J*UqwpJ~fcIt!-VM46#$?_LCYeOhc)wpCzIYYjy(O-T8y;fqRo?1v2E6ZeSveE; zE7W{9oEz+Y5euze^Qi~s{mrO6VFV1ZUCAefx5yKroh+a4))%Amo?3?I*!%hw-WzH6 zKAvgR;WRq$@+bM9O}F&Y9B*Q6!49^FduU3S+BYbYt=+ET}aUTWL~b(5mjI zmxsNBgqxZ1*Vy@#{&~+)7e|h7WA4;7(hSmpf_FXpmcMRqiS2$Ug2vn92LCBNzC@R*BqmwY7aLtC)g22RyE?Nm z7w}H`e)xV1;GHoW2>E;ofo3^2Ul$EP=l!Ibuh`(xOFT2@pLQ*_+hpF@p!0U{wGtPw z{X}!T>ybD%Vf4>}W4fhhAs_TAI_1V(!v{>RsrlmUe(o!3{FfN+WvRiwARSj36!bnt zm+pB}8%Of9WsETwNZH$-f_L2ocGCU-@ZrS7Fb^R#-uUVoSxdnC;dH+f%zJBM#{OKu z8z=A0CwWh}W(~e()8>I#$S!8X@f(158izuoE8tzx^{{`z_Yi1o+o1xJFm&G6{~vpA z8c5|9{{3&$ZJuRlphQxXnGAcGlOz&Rrie)9MpH5+DWQZSNi;|$QBqryRO}{cl4Puq zGSB_jcJ}@J_KW8}_kLbIdq4m4%K3J#7uUBwuC=bU*1gsVZ^yc)Z-|rBxTV%oi!VE2 z8&BS3_JHz2!O!c9Oli%6IuY!H=ML^H|DzRK8e7sFn8>%uy-AL9^`WJPF@$qg6 zRd}FmqQ&%+6QvPFx_mU$-HsQ7)%(Bm|4gs~02?G%ni}-l$-Mv_VsGfm$YIqW&h?7- zd0`FuJf7}N>HmG>Qk}G54RYTlxq4BkCg~y8_%pfY|4ob=j#4cZe1L*|y*1vjaF`ViZ&`^a3}Yz%^VUwbz5`YY?Gnh&~^nqHmyV zZiscE!TXhb*J2cJ6PA8iEWE*XZ#hwjcdBw<90l*N1OrcPi1*3RO@B9H{yo=jl3&$YJ8Z-$eK?Il2=USDB)!wet_CfWTC*VGTPnZv0M# zVdnz*E~dx(a?221KD6Ar7kWR*r7Ukb)8I{>Wz|RVjw*Y&1QT!PTYID+-bx)$aw&Kx zth!XD1M${bFnD2kuNukZFXzUhqIlq3_A~Yz#QWJ>vuDK+@A_K7m$EYlf$2VnF3uy^ zGsxs?}J`p!i<4kK_OsxNx4N}tHh|eEtelQ%~$EZH=@(WdXy<^2u5g=%OZ}`C> z`tct4{bX^iI{xyO^}dF_^q_Z4kGF^%eLnJvjJKI3%=Q1l}$7z^*W zIV!%3A>JzL;64TKc@?gKx)5)bP=2}FcB&-RiBb2|@^}y*J%39c#QRZI%tH@|cj+1) zwSdnDfsu7j>d+2syk&KOyQR)Yq6IZ>`OV0bt>)Mb(!&wy?4yO>84m9yR3CWxak7LK zE7b~v+(TV10qppAH+NTrv2IWSUyh}{+=?UQv?!B*>9&ZAd2wgsAO8*#?|MPmw zRvNq;a@%lXlZ|`p(8ucOG)l*&)9G_N^e(d>TyrVuI zY^5fSW%O9)`mk^?{e)yltX4PY8$rv#O2!MH@PBCmRiF;e~S2Ye+HbgL+nS9`UxT!+rqbo(VotuK z9;`tSZx0&0n`JhSqIk26b}h%kJA~syZXd+^@=mTE3f?Z7QZeMgkndl3`0JT{BgRtW!~@1` zHdkZgeakcTXII;AhQqs=>Z24VKRsZV!onvC@=X?%u)g??i??xy5c%~Id*CiPHP$jn z$Mcqf^9MC5wlF>3gsY3`^I^l8LOme8od)lwp-cTJ-d9s^Dq!LLwltw}7~=h`>I@fU z205$qjDraAzO4SYF)B%$ba8M0jG1RVSa9s8HsyIsi_-=duE7V=$Wq3gXJ3W^6ZzUM zJ7?_b&6@m;7F*;mtzzftTN@UB9%~J`(}F_5H;* zk9%6lUQcDpzfqY0~b zbdU76!hKq#=W-|WFDAg_Ez5joV<~zUXJaM{Cei zH7*sb8k8LWJEH;)u^jTp`6&&OnO#xpCRl?Cp2)5^!l6&9%)LFk>T?`W;C{7Kj?y6M zY0hx5lfl}&ug&Yd!$7jT4cGO4>;~!0^MlT7a=VBpsc}12UK%|76T3m0oca86h0F-U z)u2~Y9}_tFiSL$-=-(m&KCYKg_;alnw+5N%BpzB)Y74?xZNJ2S!asvVIMCuL{K}K* zXOM*ZAL;UO(tEH#?4S4lcGBS8vf$or6z{N+wpCbogBY%l)e!IRda>#hy!*xp<2DfQ z1Fp_*l#l9>q8>-c=KqKTZCgxBS3tZ!c1CSZVm0;stBb%PY z|GJatLygNl^ZQ&%AvWIqCWLnr4#NzGcQw@qUVaVSLMKj3iUKLKZ@2vB;p3exv%m6Q zwj1y>S>W?=DgFkjnvT?`{5@??q?A1{MKAY3f}FXd#9}--mkcg^c2T+NxN1zE1OQnfn7ph^0Xn|w*7uyH(ANR zhU6jK(0dSk+m-NFAs8F)vGW>ab)HUQ7d5V9OvyUM3mb3$!Bdx-T z7=LE2LGq%(`{TVeUs1e2UOA|Qh4-?_w-aw5-nCbnA}M$;R31KH1@X?@Q1V9EMwfI! ztw|_{KOUS_NlY|_c$dg>j5e^4!7Wwcq&=?=g5p~-!e{NV@xGxXlrd)7LA*(g)A#=+ z+V(FSq{9_<<33G;42O3y)dyaFxn~}%Z-mENPRDOk)YQSpJNCBr3|H^a!$yf9?r=7I zyz9jde!fJuX8QiW@XTJid@Q)~Wgh3HIlOn!;Qb+~=Pio&@UwL*vG88EYtN6*5bu)F zz4;Wp4~8R3ly7f;f49*LJF$jj)>s*g0B{90DX9L#MH0Xx{< z+aG(4zxNh>p!B(@^q+@9u5RHXm+AQSwn52=!@!E^@g^uK)90h+Ld~-O`hO;9{$Yx+ z|M#bpLF?H*qv-#et2$(-A#jc`#e7~ig#W9M-42zC&S2#PeHuj z<>#rJ0RZgCAUWTaFIdr_9zyEk}$A) zr}bl9O>DfI0}_ZH+&_rH)VNkz^++uvY`hm7&ffQC&p5;3{g&!uK2CnWL|g9I&5D3F zH*4F+y^Y+u_qhLTSsQCC?|L;eG zciY4PFBEUJ%jeax@V*tlgDVH(J?a>nN5PxJ^aDE|oIz@A4$0lNok-d`pgS-FZ}8n; z;B{^U;=R36X74IaGN?LzIx_NT7*PM3Hq9-Bjd!Z7wnfOg@5D9KIDuoxtMd}rc(eNQ za@@N&#&CG2P<^oA3USoQ^gKG8Y@*yr;p4Ipd-o7+=x1RZugyPNnVT~#l z-VG}rq?JItZ#QIrr{In5z3mz5;sIRxBzCD@G0NVX+V2{hg%IzxAII+|!M(Sd+Z7G- z^20#fp^~plR$y0e1#!E+)VgkBA~i1I%Y;nFzdUc@c8vTiz>x9qmZ$n~#mO&qe$A@U zRuN#cbJfwmr}6O)o9Yy}qp=;B&F;T+@Dv^W|6t<7!;#OKf9`D&PoIzOpQo4q*Z(t3 z{~tnAgMO&xK}8@az&l9P#hnOPHR!<^Rm2I_plj@35;wsbbmMm>zY82x5i4w!}~DR2VQ=Ti<+dyvqS)k z=1qyvu>oAXg$cub)|ih4)KRZ>T@S`@+VK77E^PM#O_xQu_aar}>AIj7UD|!Ez!S z;=qW)tMVfdZ;?o$t%(9;V5_6T@?&EdXiet3_U>OkZ!vX|_xL2)N9>@+?T$<@=Iq1X zLHg7lY&{S-#c(S+7_mShl??UJB4xquiGkHNH ziubxJdfHfcE15V(ABK2~`q-?d;9XY~Iqx0ZoM_j2aCeKRAxS~iy4`DE9O&(5xmW@5 zUgYkz*^ZYCWEcAw5Iw^{+IW6)Ko2(F4Q&Q*Q`3JE&rsuXgep8b#s^-86FHBmUl70_lcd4REnW?B7p zTUdh(bc*J#*jc{wZQg@C6Oy#3hOMJ)9I$Da+M6#mK(fn?z7@KN4E9Y5rEr9XfsKiO z{nia**P#B>=4X|j{3dRq#x;l@>sI@hH%PC({_P{~LLf2B-zzndKB^DA{B&AvcrQi> zgWuoUZ-lS^gWDht_)GC74IKoJ9!fVTPTyN1XeYQ3XaBNaLs$Y+dx7Z0ei$=HKL~d#vubfng*DUrB zo8xnKD0Jj6!_6Q?sXp-XQ~J0*mz^XG{9*^Jnq~3vPRW12?7Qwku=Ko1T!0Eb-dnd8 ziND>vhw1UI*mIdKA4jj>t9@EHhxc9@y!+lc?nLqCyTQVag}0mvtI!&V_pY{e9F+cF z5gB#a0P#*drWf0*Z$e7{%0K=B;{AP5z4S1|d&&3mFUpc+z^2`*AFdn*Bn09fpT3Tb z_o64dw(EWm5EoG6%q6%oa=u{W&68p7yIhI!@LoXmftO!ksFjI6y9l_OY`gS2J3ih? zwY_||wBRc^g10IPf6_67R5!HqMGi7O-h@tL`h1MlmQcPRg_Dy#G8$h4;so{XC`+?_t-&Y81R%W7yrcLA*!Xn?$7uCZxgs%_Nbfap2U}o%)inL1M4@ zo%~@Q87TR-tMa#pfzyvA>Qr}PZ%)WtonH1(d4QNjjdL%O>FUbB-kjLyPVihEILmO= zdnwfiUVe$|7Po(WDhyWCC4e2*@i!-~98f+qxHK5>ZdqbWxP`xZOIT3DyVhWW`SJFu zqsxbP4r#@@{JH8KN`v>$aEY^M^-dN#&Vq&anLfKa))4ROw|BWx@a{vT%K{+Y-M{W2 z0{4tb1@YTUydd7z^A@eufq2gxIucYTN(QUHylT(s3j=I%Ek7(nu<_0wIsJjd?-!Ai z8uwv&)g$8^Y`mqnDMSq3nqfG+GpRoC@@qLTIj)o`0{#jJOR)yv<84!4aA4K0AaJ1J z-G}hV=eToq$Dj5;-mUFr`n|WP`P=C7!D$>y{s3=p{jdLLv~Ki&lMftXBWP;Sh*8zt z8zht=Hl)sh532@sG^yg?G!b{KcaX@50)3 ze<*lw@NAJxf_NJm{_^G8xR%tkao^1cdU0SUNBGzhh&Q>sp8cvk8O$Qzj(LcMgE!*$ z*|f8;hgcq?4x+K!AhC%W=SS*#o;-w&cUr5agExG+n$iBPxT!u;aPqrsdCc*#h6uR* zc<2;2KR(_iV*Qh+l6=9qR+G*q2RdeuK1L~(e@-$z-UN3*myfE&NbZJ=5K4m-MvJ%B zB_kAXlTIfdEWE?khY1nj4DyQO+WC~_t=-|4R)Y}l&0!m+Pi;0QCC?+~XJ|mYJ-QOq zAl@f;vS{bZk%8wkp|8Fs;oyt3N@nsiY`k;HT)Vfg7$knB#;w%!@C;nyf?3r>pEbHU zS1=ylIaD9QIQiLg#I7}6Bnk>M_WwB3fZzY;%UQ`e?h6H}T~_x4NchiN%saOCRaJ(x z9;5yG|DWcwt2LM|ACAJkRzXweD0m;F!TZmV^))Eof{Nu_Sa{Eb#2E5Jyn7pN*--G_ zR`=K^3~rE`vPRzxT46?7^{Zh@MJWypE9=#7gLv;h;BkCv3A~(m#d+lX--BSXyT?Q; z5_@^;MoezJ%JDzM8ERbhk~6Cx*I+Mi6&|hO8I@){yi2G)3UKn{iPqj;e?S=AQ5?+g zX~f4no{INr<4wOlc;WB=zZx=6xVdkP>HB};X%o79{HXn0UYb1D{~w^i`?sg+-2MNQ zxpzi%JSP_3o43f_mV|h#Xn#LM!Tb9?lLzXs{};OOig(8|6Ovo@TXjXadfTG$@j@iT zn{eioe3J|ryxC$RJs|=&Cn7A~o1|jnEpRJPmT$!$A{RBT#^~5V;%jWYlX`Ur;LF<# zH#y;_`Z$V{pT>%voUPTuz(^^7vZw$b@4|x@oF5zv1tJkPMOW(RxSW`EyF}`Z2&V7< z37vHMC@(OV{BQsN|8#KtzY`z7?Klff4VscUIQKvrr3MwGn2TW5ph0Va)7N2xw3xl= z$wpX%9tv;`kCwnEcII!1>Xo%7Meu}VzS|fFID-n$J(e6G4a=U8xwaCX|4;A!CY=)j zCa>g|?O)-KIU~F)S1j6NHbR`B#?nC<@-orQ?N1i>*i@hOScq z@PPEGo&Hv2i1)(GBfT>#$UwRIb!%5l1X!mLFZ^5(8}Hq1XOjn-hKUx`I71|e_f{4* z-UZ2q8|17Q5AOh~j|({Y0ow-k0ufQrvMKUN?_zwsmn3nYRxREFj@gK`#K^zE{dKT7 zaNeeN13%OE|7pItboo$VF?+G{;N1EDLo|4g-~J+v;@yaR62!vW=h2mQPa)n*SZ7yL zmbYY09(IgCye$Sy){6{Vl8*8q%I7TOKv$Lj%C8Xb=chE5_9~LWOSaal#=9dxApbS9 zTjRSi|5?t-T-ep>GfWJi#<9-3&u1BijrWr+e-f{DurXZq&Y}9K!O5?O;M-kmDFWvA z-rVuvCmqXM-fVHlZf*g(=XpaHzM*4zYf-0TTR1n<<4t(nPL~h;%TGQBh0ireQ8aju zg;vF)c(dHUAb^E;Opm^L6T~~`^9C;p-uDfHgeZ7h-qTAl?6x3T4s6_~w>A!>3>8ZZ zK)iSPen0$uIT<`~wb*kkA_Be7qBFCM%wEx`SnTpZ-MD;!jRwCtk4VC;evn z$%*U9=XCj~ZZrB3l`~hpBWds+T_>N3;$6mdfFBF*P0G!Utq||Ow+N}Uc;{{s(>mX2 zL3+Slw$A|K9jUVS`8dQo1-TV%0rCFcejw{vMHpC_I>PC`27C3^BCS?HQ+J4n#&s_~ zXk(F!y*Z)&u_?^*A>-}6p*~b_@|&$ccVK?rv`0dVV@jAYf!g{nj}^Y605nhdnc?x9iyi&TEihWWM$o6Ww^xd z_NkpG)Yz8fn)tK*3S5Ic(0%0WdRT+T%km4N)XCti{D$`TDdFJ3s-lC&V%RgtbonU( z*%f2Nd(=4DbM>2Y>acf^O3h54yCx$HH-kJw^-+S8-!82K?Mruyf^tIltC6q6m@{jX zrO%DJ9xVNPfJJh7qhB-r0cnC-kBvfYKGP4e1Q9xYTu*wPy^FH{f1Klg@OJpyQu4o+ z*w-6zNMPY@8bHq63-MmNSihBmch4`8%qh4*+IMQ<)5`+3q-!%;?JMC9Qq6Scz9342 zG~FC4rAh|B)nfhMI);PWR|VA7TCj&$>x}O#z9pl?o76am4Zpi(;;`}dR{s##DaLqs zZ=(9}#L3SyT`MFp2R^audSZiL06yNqPu6Pgf3Xb==pWrYYlz<xOLj|r7$R8RMZX3@$v2~6yj`q zvJJ%45i`qqp5j(}LVnFrE%B91k2gVsJ|Dg_7iw-6Q2PJlY&3Y!oct||;>{6xRSXO7 zMOS4vr9!;9yZdb@c;D};F!6%GqnOR@2m9Qk|aN#h8Sml{`3G!~v*i;Xu&s{Ht{9^>J?fa-%4C%?ce z?PtyiiGaeMIval;e7qm`7Tf*sbpWQa=RV0B;!jQr7Z;FnN)nhJ?@w75>GI+JF?VlH z^c>!-Gke8ti_VV#4_S zKVfOx`dvy~%s==3{*^u-SC_2(@BV+ZQ)BR-aERsopBl6UnNZh8YtW{&WztwR=mpnC zQ8`$HTs3zmZ-6z(Jp_r?gJ+Or&o9a`J!wN?lW3CI{x%kzdbsy+p2Pqtton}B9U>Xn zoe@vU8HxaZlGNOTqOq6Qebfst&A&83?4!ojjQYJ=AK->LQxbdW>8bjgi{WOF{!||# zIQdQItseffL=@bM6jmyEK7#2JrAa4A$>nUdH~7sTkX0Imzr;?c%zBz5FTwOfETN1( zA7rr~QtOV)4Y52lcym0vl!4-Hb#ihc7T$mOiMFZ`@50V)k12TH5!F5}4)N|3A!!&_ z*^tW4RvIn%77M-_+-e|4#=C0QdXc-KjEDCUs*ig(`3bTFUg-WI3Yy-h%FAEH$Gg-ru~J!oKbYSW zddBnH3*29a1_kT&{?(~Wk9XTr`h2KX-@4olKe2<=o0|r2_R|s$DBhAiPZnU|y?Ief zD-q(|D0^~>f;SuQu?szL^|p-P#^YVT4TiyNwmx6av zNXR35hK>Wtm!yh(c z_y1FC%$(Eij1h&YaYy$4ezlYzyZ>holqa!@G9KQ4sXhoe`7Mci^Rre}6bybl*S$#& zAMdwRyfb>c`DFs|S8ua*&TAi9$oyw-C(Y>dao)6JVMb;g;DOCb8(TF&a8R&QuvxHP zuu`yCFjw%TV2t1%L2p4vK}$h>!Bv8b1w{ne1x5wF3w#o25O^qXQy^d9lt6;O0fAit z&H~l~Y65Zs;sRX!ll*=Bt^BX}Yxv9f3;8qollUX}1NhzfH}RYDYw<7VpU=<7H_P{% zubr=nua567-&MYId?$EHc?x(kcoKQScy{x+^4Rbg^JwraRkDCBntdIm-E+^Al$S=R?k$ocWxmI1@MzaPH!C=CtNCon^x);88RthKD=te07{S(90#Sc6zSSU0npv+A&}U|q;6fOf0|0!!)t{P%zV#rS^% z{A>uT#6|us;Y~pjNI$B=?ra-E`cQT7Ora{$i>d>v6D`P3RPE>SQ$T*8YHw%jeB?W- z_FRmqLV8dYdN{uy=|)wEW1$h!g{t6rIo?Pos)AI%FF`s`6;L{mhqR;0Kg!z$`G%_9 z0b9Q!ZK(27eU*oNMV0U1CvBt^RX%r9yOA%b+L`7uinO50+mpQz`HU*BrTvSLPpI-7 z<=cRKM3u)Qohal3s4phu+J22pLuOuWyEA1aVVo}y}lot`FAhbk*2qdUkGR9W^$ zr6aYdTKCE`7XCb>($8;iK<=VSZ|{gHQh_R6n+gM@ z993(U-=BxvL6vq-ydhGCDy`?QCy?8y(hR$K4k<;IhUxq5$SqW<^N(FeZlX%HPcsp@ zfhv_dq+p~3RjcC@?;zJvwW{%B7E+8VWq*W(Ttk%-=esfFDymjIl(>mpL6u@oh8c1h zRm*otZAOYvr69jc11Ut+viXvB$R$+Cy&oVV1*lqD&?t{wM3t;x?p-7wRZBEf?2!wo zS}f+g6UjrBbcd}ZavoKS?ww6Ta#6K#@9kzJ2UQDnq7smEsG2{on~a=AmE=dM)krp~ zByR88ie#ZmJZknml8LH$>*I;Y8B~cWb3Z~dP$epT>k4ujRl;Sd5y&Z230=+NM$%Cw z=pSf+q@hYcMg13&iYmU}{u#(gRPjFUe2S!?is!_*7;*wt+|D0Ik>jZ1QfIk?B%_M5 z-i{nY6=iu6NkSE6H3vD0DoXQrI=4Jwgp&(Z*J>_IW)u}f3)ts!TN-ql==43%tT9|MSCjnKdn-{)E{-WxnEJ+%f zMb(LKxv9tus*V?tb&zRPB}WgpB2%b3X0zorGKs1r@v7y>1ga9JHs&Mas59ql)q%FtQs}l=o8+KU7hkn?!b@it;)i;)|*;`q}Rh zA5^t0xOW@biKixDC{D>#2nq@YRA|9w}8oJbv zY)94GvMhhZ9aV466>%eOsCw<>UVylw>Xm%gV#Ebi5+ zqUyyN#c{+5RnK)5jS)vwJ>z!TiflpE)929#5C>G%o#lRq*rV!6SlkG*8CA9VKMo>x zsCq0Va2VNysz>imokVO=RegQ0A7XfKw3te-91Kz9819dLVXK z5!ryM`@I*$5i3+xKK*KrtVh+o$Xgc?OH|#pwJS!}p{ioO`XFL~syp3FcOh$0RrYvT z1u;j}?ZlL=h#9I%UHV-RQ&inrmVFR0LDh}^o`r}ps!AHIrVt}kU9afQLkv+>>?st6 z090LDb7lx3qUy@*1!u$nRhR3;6A^t>6`gaiK=e>m7-Bkx=%VV9@sK&P22};Z{3{S0 zR9)mveurqI>Ozst21E;0dHZfgAeyK;zg}c3qJgSh(KW(|I;zeMPK6+9s5*Nm^aG-b zs_f*MB1GlC`~Mif$0NWUBq5qLNXo1RU4zuPw@40a4f6M+tY=^At{Zwj;|;cgYmhgm z{5P4xHOTcR%YSsT+mLQ~jU@Z~#Dcryha!UD4w9vK&st$)GDw$r_GZ>80xWHRq0syV zdkwPFKjwy>{4{Y9H7;gv*Aw$;>@~aG9 z$Ci!ZE}8%NR`OeCegH|FuQtzmIUQ$^rYx@$8!j;a8KiMKeJFLCs?OaYeO!4&O{o5m)$>{3LWuJkTwSgIHf*X!1NoW z-hTA?Fcw~0WIOk~<#7QTyeWMriZ|OS(h@AZty@;fOhLT2utl{~@Lqc;Yxfn1_v;&8 ztDIKbkesu+<5!)G1(Bb2lOiDARw=xd$`J4Lx6f=R7DoUdn-!e>1=x726~OC}7EBR6 zsBx}$yA&m_VdHHy?{rfC7RJL{i|WG=C%t%*_@>9v?7u*d79tt%bJTWsF#mR2lae!SPy=Yy;zw_IcHdCTK`G+zS=Q4QcnW@ix||4RYVj zcz7S6`Y^=FZ*RzR+2&qRaCh_af$y#O`~NEj-q)=u^9B+o5$krG#y^}WbRlSq{8e72 z$NQ!meLj|WWIW_M@ZbIaOwj!kDEt1nJoZQx=U_;McjWRteUi2+QkMN# zd9iDdUbRh_+wNJSFEws+;84g(Z|oXWaPp$lsU!RhH^ibo@^JDKY29d98XyWBwPQ9o z8jj;ONF0hrH90OjKti{7;>}e2Ay(=5uU!txl1yKN2()Q9O-&UW?-VxDiWw=! z!}}A}M>0-+>%9`L@Rx`H>7KFdm2CKUU;V?^U+lO86iV+HiyyDY{dFL$<~jPr_5Xne zX$^foY;zb>0QAT3IRH)Z!4#aqFoLIDf!@e4hTWt8gOd-ov)?=sDH_jri6gyJ88 z`EE8Os|SZxo14UfC%U(0oFLwz30lJ0CS+jn?8*jP=LoQf!!_wFAXz3)(cxZvdHnv_|2I7SpWc-|V^Qh>jDo8y}_&%M?j zSbfjz88^qj-XihSE0YH=&M^oc4uyAHS99bsTO^qzXzO z4t9$G0&&>kq1k55}m;2)4CynJE5`1&cP$2JK#h~)RQA2G1{-f3 zts_WaE933G4N`q*;pC?m$Rpwkm$wRTeYj*`gO7I~zrZ^&r2x`C-mfd>+u?6cXq8TN zrg5ES`n|W968d}uiDZwGhuCa2?cwlGr50J(buFfp5hF9!_EZR9;8Ud=0 z7KBGBVb>tO3qB@^hY6sH8uvZ-%(orSuxn82>RsngvIsHU43d}X11~=zPwS1938KKJ zPN4D8i3!|>=Zv*x$D2Vr&>7i3B;bxegCv}Ava8Z-WcnIJuaEA}$D5*Z=Ncp_8oVh- zhEcq)?rU9zg?F2@D&JO!_m6@~GYZ}g`kCyjAl_TI8wGHMZXzwoe7d-5Q!J>I2KhA* z@8z4f-8R}l1|QuG*ln{TK&Nei*4qR#mBoEk3;}D-@k*rY}j~*$cUAF8vaX^ zrp6^a^g)iqV&fgLHuIMhf${K0eH_5aPxju&{?%!s!1wHwfUYb)-Y@;utU_*hgH74{ z*UU=LvAop~9dVF-1JmP8Xr#}F{^wxUpYR50xH%y~gE!@)4ixWoei2Goct3i>v+)4L z`|JACk12SU$nRah0OG9}F}|WB)RvTYh$q%jKNgI1c;}5mydBJ~^QPC4!G6md6@^(5 zpdlvc)_^!R-Z#q#eon!EiFMStAosxvo@3Z}&)Scqv&9H7T=hnMOycBc5O6tp;;Sey zs+w^cYR6x_-5K(0hUL#L@YFmYuc8~j|JU!kW@n>vmFe-G?5EGi3B6bm?te~iiPPXs z`AP}J+xnU1N-VsGzp-pP0`WGTSjtLS-cp?h9`HfD!(HZ0+Pt(OJ$T4@_lt5YaG&>5 zL=5)-g~8*QOD)J?6MNk^<0lcIFs$T>y%{#%lHQLuZ|k2Wo~OnYuecqdQ-Y26?;{!! zyVw{HZ`4O0PJYHGH?#4mih(QV=WR78#K$`_V&0pIU%Nntj$;#&j*mA%{LF&rrD@DR z_m-s72amla(88)gYfi;p9D8!zaNV8_#TKvz z^*UZ&auMD^T09Zm946pEVmITB{QW)_aGG13O@>3PS>FAdjy7aqq5bsw%9jyfuhH2% ztOnRMs6cz5L|Tp&gi_-cc$n&^i@9U=#qy^O%M#Ot8E%Npr}|imli$_dZa2UG5CIqT zN1i!;o5b{q67{o~XF=CkFzFocwQII5_%$ec$l!ZX$xi04K@Mhg`Pjj2YtsJD2B|a+ z-jolIQM^sm+cdE7-sFF~hYJp|zod1CDR^JYPPzXS;yr6p=%{aOPttnLBD}pK7O?CU z=}&-o=Ol9OZiIMqW)Jvou8ROGKX5LZ@Nq2%;BS5+R8Wk2>Y`pDm`4YME zSU@Q?PT?|7LAf9{-hH>qG(_ex9^RX%K6-KTD?6HV=sb%U@VuwgU=e|jci-z5!Jk|= zlIm`MCU_C(IR78SYV(?t`9E(V1kmZDVOgruKj;4!(%?OHx-t zyf1oZ#ZmB%w1_^o1~y2!cB?CYud*XKh2Ps@=ot&n#CN;rLA*J;HmB~~NCvgJXZsh< zMgSJU;AL5%*m!H)E{)#f$^vEt{)rPhQ8x(YW8)ntIF+@&nejF!P#<{tt>*faY*jA` zq~;sleW{F(H=oR+=Nze4;7!lb-yl zZ^~UKDBcRB!BT%GXAk^9V)9@FDZ$fnar(zEp| zVDs{OM7iyWQiGO@#Cr|qI1#XFkibuS(R|qdYl-BoT?>cUr8gBn zIl>uag4MZN@O3MRuY)Cf3tZxyJpWxc9M&L@Bi@}Ia0cn7sU5XbBLckAJ^Rq$Bz6tz zyZo5UXTb&#jZhHRia0}Toqxs{=b*%!vQD1-2Dj~U+xkCy!oyw(_>Tk zH6?nIwf@ZNEJ`$IqN$e@5n{s^_I>c&A zl6A50_BgkX`!>Wo&fn$49Nyx$fGfm%`R)5xC%-w7R<9IK3k{6}C#%Dr9EW&EY|~!! z1`e@Ld<-R}RU<&fWUqU03O3$>h2`8|McF_pH7>09N#(?CY`h;w@Rd#;U_8A2sXnT4 z@>_Y>j!*xA2#}Ht_c&OKkGFuqW5+}0!KC48<@U!5@$s%KsOIfe^k#azeUh5!@}XnU zGZgTA4sTf+yeaqbp?HIUv^7|GYs|jktc7@o#S-69@P6gwx7iEg{l@9@c=0_)((%;_ z-~8bNX@aK{7E)Gk9Xv-HgkbfybJRywx1yRmu3hYRQU`W z?~k?%eVebb0wHRgvyNac@){d&#ZTdvGv_fL-tVbCmf_@=!l_cytDWzs@vJL}Jlj%zBvfUE8e60Jcxi%tuu6i$~!JBep zDvG!3ejRNrynX6DmUKhBBaOCuQt)nmT)r^@;+;|W)zILf18Iom-TMBaSYXClrk(=v zMz-C#Ed}v@MGiNL1rdM@rV<}t!p8fGyF8b)7b|F_#znFsuFYq$@m71=nDgQ_x$_uWoZG!%$3T>qa-^-+$KpTyR{nwjsyU}F$> zVcMD*%)b|uml91R^z+^zp!Ah=VsSHmgA}cly=_6p1oPLRpILPI@LFpBYUrO&?3UBu zO}PXe#k*{?3I`V6gn4{Rogv;P@hwZuA>MgOQXP~7(h+T)$trHHq_>a8ZU!!o2dNs1 ze7WEdyR~#8;nfy0c**Wp;(RR}lo<4$;2y)q`%2c$Oe-mNP=v-U+p|e^CpO+u1+f7Y zA&iIjWvY)boczYl?h4zjB?6SMpT2%&Y8n@B?X~H%D@)zM+sN4zvtRf#NW1zUmHm6% znZ7})IYpljujzG!hpBTjNCg_aDYyEgcwhT8%Z7z_a)H(xe~7o{lFR-Syc6~t$~3?k zq~eTMhxcI@QrpCkvOPyUa6bJkVkyM?JMrpX6$diV?(_@(eK#Bo*<9BA#fd$Gyy<7~ zGOLpf^ity{&dpSQ`xm^`{Tq%18!{f=H>f^VZpO#Ex_4(rwSX@$XqT7BYNq4!mUYSLUzUY2|KubmlP(`gj{=|a`OQ^t zc^bSa@2;SD|I9wif`#{>N7U3wi1!Ccdje(kc4hhI?9C8wO}`vzxqI74;5E;x3lHMJ zC-qP9z7X$QFZT}j+LA%r?6VjbS9tzk=U89gU2MD`oSVuki(~_N)Hp5G`$cWD*prip z*J_KETN!V8tBUI508V~YTQA+_hW)=yL@%j&K0e+=-AwIXwI4+9@O5H^%J?5AMrU0y zkGC0Rdc4o8l+)$o5J5BYDf~F`zx{u-TVvp#u>W60Q-dfkPoXu)ugQ`Rs|K|foM#=V zy>3_{QnAex)}Y6mx1R8WcaZX)LzH$IyOZ8m>S&nN#{-L&inp<_|G#9h@#Y&hGDwj9 z!6{rG29B9`ugm?h3$qb0*8FAbKFSW_sd3F&@5^@H!oEQ|=k_JdIukL5>;D1O$61{G zPTeVX{Lv!>Kr)9sn7ikC1jO5eH_5`zoeYHDh}rj^3@>?r&q%rTMFi48YjJgK!@wVEN;?lm;9@rmHRa`Cl z9QW6uWvO-Sm#+IvkN2L%^!X6p%i$S3ok96PT8Rd4%G-b_-W!x%c(Cx!Db8{if_NW& zDbYj0TUnE}#dmQ3j+i|7M0#qcN9Uq zMYoI2mbt*&Tc^#RN(+aBg!R9ZF4$tP-j1ZHe@wP#2hr5HF9hF5)7{v3C!A+Vy?B-J z`u`!Sj~JZ%`jbu1sig^nBJ&9M=f(J&6V-(*J0#pqK+_@T_ZPp=(f_ZvN?&JV#`Jg- zCfC#D(|tLIDxZ0|mw|I-l;ijjm>H7l|Ee`oK_w+Ca` zK_NA6;pp_LxN7YFe{@a#z0miJhxb;hk3Ts1l^$iEkhm@a{7>rL2=~OtJ0U~oy=7Do zkn?AMJ}HYo_ZC=oP`!fv57YPm*&Ouw5V9j%&Sd`A|D(McL;r+BtU65%qP$;?)}U(* zYeleX5ZmettI}Zqk5v8mU<_-}-KLa@i?Bgj(juO9g5*ZhaJgc#s4E_5Yn+)r2Wyb< z+w~IK%b- z7E~W{IQeZj{WSD|qA)OclqJ{I`WLt1=^jZs(yZ!7n)vQ3V$4U!2ht@YZ0G)JGW`xx zv;}=W#%fgq*WQ>LV%2EyraZ`w;+-BSD2#>o3thsxOAzm)X&K8+Al_FcdI$0$-n~yc z$07yXNh=yck1t=ab}f+YgPr`xm@#Raq5iW+Nbq z8kaj0wzOOY8}Et!dwLI==P?}K#Z(_7IQcyzr}8`v5C+SIe+cf*!N;4+^W%l1r#(oW zLh%`fMEv6|PI)i<=MhgaJ>KO@=<_kO-&aob+#KGjGS~*fYpd`;dciUI_R?jqBa_eMO80Hr_<9jJmV}#>4wM)rTHVev%8;E?-e0 z47P{A?tU4BkGJ%dSD}ulJV?YpNOuey{_z$i7RDG0mR$I=GSHlZ zerh!@C!+(|<|l}pq9;5SHww+9HPd;TAIocJPrK7t}c z_RhaLSG`x$;H}!HnTX@dXJNa?dw55&98?rDYjSQxmVjqrU_#9rPqbm_JkQQ`pE)VOqUo$gKqyZ<-6 zC(ZM8KjW?5>Qj9fJtwBFTG$pZWP>)KVrV6Y< zx2C=WBUpo`*KLb>2bb9I@@XxWxZpxsW@0)N@-rUfD?X}6z()2J z4F}W9EvK7huxk)&+l$7;AWkqwje8Y!XuICOyg{1Uam)VF1;*?DC%*pU<2X)!)h#mV z2C)Bs`DDw68|Mgy=syqE&qEzYvTt%(f%lC>lT*LwI6*o}_~n+W!TdAGg)H>>IB}VS zI)l`v!CP|hgQwo=P&OxWZ9+URLA>+6yft5`>_+1L%)YB_ARg$R`1~Oo;$3xV z*9T*`yybN)`pr)J2(Z)Pfa=&j?EZi2=gj?PuzGt?hCc91}Pze zJ|CTJ+bg;M>Hjro@Ye2$H$?F+bKWhAh4+HtoeGB_-oMVAI7-1g|0zdp0mNIp^3e2x zAUD!ow$_=SaPHl%)Yp3v;$5oMdG97X-r^n{?D%PU1mH7!tJGnIjkgpb>CjhJPQXcx z+v2OfdAS2N-m9V)`5a)t>McU`u@Wag;;x;AeuKi`L)W^lSPp!=Z*EQFuhaD-ooY-? z`?3aqd289%{_7^=DokI!h4bn2q4Bfbq$u*g{vWG%W2ireGe`rP8f09s=`C7=UgWQm z#;QS^vg^EFKE7^v=rFMuz#0_Uq!73ho_T!XahCMH7Y`K0#Wt*lHE5R` z``b-kWFVMX|6Pa}2A*!6_t#-H_6#ztqVc1^A}&xvjngksx%_Ym_6)M%bzx|psRYAq zkOotIT)@dM$?uxC)q2O)%DCb%R#Jk4L z!l6&lg>*YxvWB}R9xVG9S)>Q?_AXRB8nc582D4He(;tU{^A*NfZysXfePC^g`N}R% zkWG!_a0q|;HV+%`+fL(r?t+YmcOccrO`QA?Rx1V5{X$?7Pu;v_Gx$R+d-;h~?y~Mc zU*Kdz*BBi$NSPsD-|)B0k2iUcE+4Yfs;#+S=XQ|vXz(^PZw^E8KF#@T0T$kBQ&mQz z5by2L;?{-`@6e>4tN$N+cOFhv_cjjvP(tP-Ljz?dDMFdD%qc^rWS-|rLW6S%QyLz1F?f z-fOo*-aXp{Qf~_Aj^lT$I70wIj|J{)pGM~$ zJoDOOyqF#MBI6pR?zP_wK7H{6E;ZY(<*thymwqk^Ot~!6Is(8AIiC1$%+-nhQ2(H2k%?v6C5CKT~St* z9548J3!Bn4!~_E9l&Bs|I*iWS!C|}W(Y@^82{O(=)MSdJgU-8)P2v^qBIEJig5=SO z5#PDh``TNB_<^D8{y`H8Ht)omD;67Gc!Q5A%S0@HWAEO^^z}|jonZdw|6^q7%OmW$ zfyBD=bJbguhWCb-BaKwvpG3SDqwy{{qI+l=S_s4_J>*fXShP<~tlym$25n4BNr2Yjoll`YG$d7t#?I=4g49Gt%`x9iGE zY~G`xmz2&FtYrGdiB$!Cc@#)T;8(?y{(Ju)tBGTTUx)p_0Zk1u%@nAo)*y3f32C$% zbivWxJP@uRyBDXk=)xLQ6Y=MHX&JnObk7NcDL;3zRDb2Nh=cLquB*jfHduocG;Yrm z3!s3G8>L-k&j?_j|N1Po8|YK)H_Cyv-!wTv2r`bRsCs%cKl&b|cfASmv8^b>_5VXi z9v&F+)hz8v?UEG$i+{gwx_%0~|1X#qe5m@K6Pb9IQZ%*>dj%=&s{GdG$U~;DL8ol! z%R^r?{!+s~D@c7B-W#1xRa1FicseAB#yg~98*4P=oxDZWVV3u^BQLv$AaCy7ygP6c zZe%Ox{LAN##siy&@3hz86F+J~?Q2O$4-T6^I{qo!jQjdnW$-2SyRNg+}cO}qx3u>HskP3OP zCUIPu<^5>ouHAa@1}VEXnF(EZ{_mx_c#~OrJQzJlvfzZgEm#zmbU@zGR^d-#q6ol5 ze*D2%FLd6dd(x7Nn>c_jGS1_R@t3-Pxk38O<}<(j`WbI~D-y{g7b8BW0WOoDN&EmO zI@%-=gw1=)uU{%TTi1Z%SK(D0Yp_?4^4e7!o5$BNegE&kOJ5$WjlL^nljnE?8s5f> z?{!mo$B0~9fyR4DV4YPV}b^h$`ZMEu=$EA>W?GC=ZZy&po!>VNRU!RKyh98~T zgdp!;BI{Qk$Xn7jE+S|T0mT2@l(57dop%$SjS!x~0iuv`dWqNBm&Kx2@Au0(_QjPm z9`Acd9=#ax-B=;u-`m0ul9OH?+wO?Xdxad~j#=>Jj^OwSu9 zOJ^P_n;#neb2y<(!`tv#*5AvC$w$4Hqw&@piR!rnc{_gi=rqf_ejt3KKHR;vni*XX zjdvyI$l@G7T#EQ0NLA@7pn6}$QTC?NUlT}|Z(0&t2yYh34#&bzkh$N~pf4q%In zTe!?i{$Ln7@45iR!LPB5$GZ~AgNzYh3~&5(t^|It?e*T`4qa^CJ6Udd)mS-zt2=)6 zCm>8U5$8t~E9lqy5eh_dx#!fgMWF4{NmV`Bku>AX~ zW3UGOA#yAP29dzPyRX!Y5B(XWr@Bc?k_Hw6Eo7Yf_0H;foSvxf#oOjvuPzx|%y9jG zE0TvbMtqB_(sj?a2!N)LWu(I^SoN^}-YiS=s=r1!l69^W`AsgOX@jJ`Yuztk#goSx%tOvBrJmHyxBE#>^L%c1f9eeTkk zm5_HsROPQ(-t5H_8MTmip^u1ri*0*G8n*GE>+@?ddC1%MS@kq4dz9`A=p9$PWub69uurIHaI zke^)ZyFG@zf*ft%cVhonAM!ba>VeNm*t~J#;mfp!Rxmwp+zLALs9Rf-6(ltKdW#Va z@6BJLPg1M*z5Xa!G~O;OX{iA6_7y#By8-fEvoObIKjdA$stcF?(4BmBa^A&sLOhT& z6%to~yq#h%Ja_>gP8_IX@2rI%NLL9i`?+frowp3@4VP-Eg+LJ*CmdJmBG-Y=yEwtA zkWG#8c#9)>T*8RY5?|5jP7nZ2qs|K+v|#f#k>}`~PzxbnI$w9*v>*{~rUVPj1=A z33ejm!aZ}6YqimN^IVV*->+#`L^#r|HY%NnKKCQR;vFKefCu^p9|gHK(aTc6-O!sZ;F3 zUEIoOHR$D3D#(Cig2kwpJI>lKllEj!3|a-<8(MT9Oz$+-v8H(^Q)dy zUdnL&{~;ugI~eiZOxSU``+@*Ccm&^5mx3}%PVM%(SvuDsnbGjJHNKrndi4$7Ak}-Tboo^h_?4TSIRkl@hKdNy52S!56|IUdgGAsc{?2&dG&=7WP6OWc zlU%?S8K<4RrFSVSI&Xs}t-#RnB@D;A6Ujp#BfgqIhh*Uo0-(mBMUFoKn|Iv6gEeU; zisbI!_d7`<*u1$~N?9}9nZH5uETk`w=%dAXS2O2$Z>HgGBV0a1-ac#{S?I~-N$$J3UPP;z1Qy7|_bh}f$kPfk3Yzfgtu~v6 zH`n`#;FbJ-^{{+&-koeOn~qmx{b|31Ct^m_j)G~PQ0!|!!M-pAbpGiP~U=uk?whrIjEZ}uC=c#`GR#I%AwlfXcS zp4TGC`+<#v?jhJ9sodGX(>+QAxh=ALOD?1H?mBMbksZwi(vWds3l1d}j-vDa@nC{e9SY4(Q%){B;vErq-{D7MPagSwVd+qgu3xZcMJ#Sod1$}ww+ImUC>iysM|8R`|AMF3FX=;#D;PfME4LTX{ zM;)yOoiy%#w+hyvZlN3P8n6as+qwkz!gr9!yZJVj=ev_P@Ndd8u_1x)2lna6zy_($ zjHN_pAH4r>$HdKJ(*z)H^y5^-A@n^+?(dnx<6YcfDKakEI!WLS{9-cNAE-#km|sQ% zNFG8M@#*=pt~~~?*lE>aHN887U4sG+c8+XP*agVK(h~_C*bP!l&QGC-!S|WI z2E|;ZFOM>rr$eI0=B8LH8s3hk1*}xw6MF4xXuJa)e(D%N-UnRLR%t@sNrRQ6=wGOPjUyl+glUF$l{ z4Xz^NjyB4E@5@Bzt;X73k(kVQyssg7ti_1$j9B33g6#s}!I&@q&=5B7yp^~kS{wF) zTgub(#J^*&AUA)`=oXJwV)_P&S0t0JJj_dF+4cWfL2jYp?I5p}LFJtnTcL`^+vHJF z%r?k7`W}D6EN}AyJxVO(J+?Jvp+5Zn-{w}KE3Td-fE#@MdJp6sF(F^RFq8s{AF6FV z+DHHjgcXZ6xuElwZX0f#@52pbka3Gux88DzN9X;=Nccm|Hpb(<0?FeyMtq%b^wx!x z34qYRv)}pNVDmO=h~0ZyYcJUUi~r`afQS=5WN70<)(i(0sg^ZK27H``45}o(`Gmit7 z$TA-9OeBwc81dykSvfeiLjY`gva0LbZEW6^ORA48RoxA)@QS@T{f>?U(t|%__3zwZ ze%^`nmn|{LNDM%g-81YH8ebaoh2M_vWOnd__VDqlsS`g6r zb}NXrirF8mfc@_6guQSid*4;2Uwiwh(3i)KZ6tk}nE&qo!!g5uu>ZHGsX-o|GTUZr zkOI6xx^Bc7hgO56FIR-$xmTuF%Kl(t9jrlTPfC5ChEuFldB|$jSQoOQs)3O7E)pn~ z_FiyCaD+UleTwD&0l3Bf>SOAX8w9X9nn$2X9DN0;u{CI)*%KaMij3PA6fX9$9({^U z*HPmyy0VPn4oKCJJWgT6SHYcd2iM0BJg*D#<@(Ii!=lsmB)>K9ge2J|BF^2wH*C3n=eR*66?C16=n44m^((rb-jhUiOvD&o{wa|Ejl=L0#khjc{w5{tQ z@A9~y&K7+1S7s5YCr1yk36BH z|4(dOqU2-3{QbW?eR=q`Y^+_rbFO;Z(C~IHbxNc1zMHAJ9*y_*nqgZJ$h+BKeBUf@ z)lI+l&x5?>b7Z3oE#1kk_7)xL<|HtBJ)n^V_W!}G^G=f@C}7pigDmWZL{Lyu{Jg9Q zoi`VeV7qq_4>*gAd$BLW(%}<2ZwXu^$B#dZ*Z*@Mc`V0>FGhyE^VGBexWiRj+{T5? zyZ7saLio~M;NLE%!^{lC$f0`28{ZZZAhq`#cLJPeOJ8`Z+sTmC!$$Liu3;MZaQ z?@UvJ{JiI1oUK8#{eRc!mIY`v2(O(RunDdp9rlhcQinC@_8F0P%i#*r3yog zJIj9neGf7+i+wN15o5UiUl+*(E50N451ysy;DO^$n?JV2*fpr=X6)5YK@+l(=Q)p$ z1udwJ=3il(CzLun9y5In!gY+(l}Dv`Yo+{!xhd9(hPSWOkQkNs4xz-6jk(vCE| zy}xr?P=Ov0<7(m zmxCa0r-h$gW)4z-o^r|KQuy@N$@lCPa*pULNWA;Z0-_x+NJhr3Y^}YpiU*x{slWQ7 zONxxgn-9qYE54&DI*SA0`TsHT>kn7|FL*D`sm{yT-;Bxo*gbvHi|x#RLAsO$eR&vJ zcxFcs=U$L@pyBOxPa~Sjdurz$Ry5u*&nIplhrF-bZcv*&oKRi;>1PS#U9FnDI#zU-y9OwoBS2z}z=qsR-Ik#XBZ z6+RVyM{ke<4u;-X%f@)T=OKCcW5hRl^ikGVcsOzS$mNQtcA+$^+V9LG)_< z3s33j|0THM(q0=fef7o_FQhAv)#o?<{`JqpiQ8y+d*(|Wq4IvNoyvm78@I70rU3HZ z`+DA~S>7*KlXYj$-rjzivZ~^6As<^;&^2!l30w{JCm)Br5AfCQeHlXmTV=lt$4(M} zrR3YqxPQ6ca@Wb+quTR$fjKhnnG%;s`UE=ftJYFu1#cK{dus=h$7PK8o^F#Y8?O)m zM+-|!x^`ppCQm11<@igHb&5}%Ok9fH|LYkPT^vz2VfwWbiVrAFM%tRudju zx7w4H8e1Gf;RmXgO0pl4hc&2-Qx-3DhyrdEEveNQCjyDzZ}6+vpf^a%eCyBQzwv?P z$hbv3>y0CN(N~bG&A$X0UKeM${$CWyV+}@p4S)JQ53}Myzqah)#)b3su*hh1uGA?j zb|iDC+FI-u$F4!RfV?Ft@7tNa2I2a1>B=KB_RRV8e?GC}PQ!b<%9DI5?~soQTxh&4 z<#-H+A#YjBRcW)l-#&GE>;rjs8FhVZwAe;=R2S#Vdr1P9+g3HKguI)QY>d7pz%BL# z*_V9liJ&R}q+8y6bl!qz#{x%g@PUWOIJ|=&S9CQxZ-qSKmwuuvk8KC!k1Rei z*C4sk@DBX?a_;{B+1*?9$`71qyq{g!FgPEsASJlYPt5YZ;{1lw0`lJ8tjrnpZX4NN z_^mceC+z?0zx1j@-ieaC+yLaArkmDWmqi582`T&ad(ays@lz4n0#SS*5*au1yj|jB z7CP@*ncu~VhK$F18IlK9e7$)=gxsG3z`Mlbj@KYI?<0OY7GA{bl4~t*R#oq#9Cylb@pdHpK0a#}(?9}e?nQ}NK;F{V*N!y7 zv$u{l0n(azL?FPC5LP&Z&ij~|Zd)lgAK*vEjVX9q?u$p~?c1{TXxIzJ+ulk<^6Zwf7-q@!kpxT)pI`inA0fBKHgLutp@3Qmm!{+c1fc9-Uy*$z5cTAvy?K3) z?je4lf{dGLSN0@=wD<*SQ;{eQ0>^7RvLZ^0ukw z7C_^z&}AG#guGSqiPvU%pY&NOEC{Dq%9G8_*I(I@zlNpWeei({{9s=kq$b$T(Ni~lAAR8IC&}|J{$#^fx7$L~pY{L#;LCCvOS%Q7%VG39*y4PLJi3pA_ zGiNz^5S{net&%Pa)cOC8%aUBC_^1HAdcSjZ@bi^qJl-Qn9v?8`D`JT>d%=MR>6{Ca zeKoLo;~t3BNPk*QcI&&g)tHlx>Me3qbD8{o=C9tm^yN|aD)i^X-MRkXlZN-sXg^nK z^`^)Zc+hw|?~+cbg}f~i?{v)aKB2p(Fah$`_HvONaJ45F8eWVqcuxY~G8fI0hP*G` z^k#R3XK#n*Uv#p8@Bb^=fO~@b&<`hm=k&UIE#U{Nka6l!;{qJQUZ`tK!P6I(dyg{S z_SR1%k3|^q^=P_Qy>7>Y-Yl7?6~frOA06N4CVSnHY(WuL4Jv6y{d1uf>CL0ue^QP# zFn#|o9#3B$Dus&;jpF`0|EK=_GxU#eiVdQvLHkvH&V6Ec_5>-dNl_H71~nXGRURdm z=?&KY@>v6GP))+slP6&R?_J%?r_gCb-rVnNs0_E*N7q#DyaXF0e*1OpR>>65KT$4q z@i_t5L@bNcZ9wn;H*dTWH#Er)ERk^yo+^vwZ=+AKIjgqLFECxfaQ**ABoD0kt}1!S zINid7ubCR_AHJV~yk#XK^zVz04lmls#zr~r6-g0~_5f5H3K8q;0onsmJX|HFM;dJXeW zv8O~l=*okurinY|%-jkxfQI*;4?Rn$D@Y~JP9ZejGfe@P#365DW3hrV^DVMDnf+zGz|k6(p{h&OAo#%-8<&{=YvB@9^^n=kEWXt=|0|d5h3^ zxA+!{u7kY&&b~f2%lqsTSM6rVyJk(Bg}^;q@+HpG?|!@{f!K(YHC>SR!~>^%tz#4* zo!4w)oJas&0TX-997125tc;yfkFVwj&yjI&I4<5?yaS!LsJ0z`J3r&`mPPVdj1k|& zVR@$?^Y9?(cMBWaNo?N1GMabnI!wvFYMrSz7IgIgo4ay%PFXU4|4*hbkD@wJ=a`DQ z>g`9vJ1q9x5Vd++D})H5@fP}$t!DvwFK~Q6Jj)yZ+;iC%$h(d6H2=HRc4UX*W4;^V z*;`(;*;GH|Z9F}#EOnFu(l?H-sVX7>vz+hlH?N@c?tI2JEM5Y?hlh;I<+>JC7>dsO zxVQfT8yw^DZbR}&!iX<6Po(>^9UidYo;W*`uzB|%)sOJ0(kF*xwrtH=jJ-HXY|MYU zdL{FJoT&c{eR&LOCb$j3`zQZ<|DT~d|9^sm{r@hS8WgQ!u1u{#?IcBUv>LR+V_Jy_ z`~O{~x_gvh4XOk}cW=WQWN8w0K;OffY)~0;f**bZ@?2u>vS3()9;{m!rgD-3NY7Vr zj9ef9nMUcTjNRxp=uq_w+x;#AKoS|ZZ)B(P`se61Xz`*G3ac+LUJZ&v^1zDkd#ed$ zdK(@r5UISNj%U-ulJjwj+tzr*pG(|kj$0LK& zNeYCy{y&(8cN9LglFEDcnt5Vqyyav4&Za`%(vG=Zv%FpJ2L)Y&ywy)H;<}J$P5vXb z)_5eB1l*#JcaK9UDFMtn=;4AmB$5CC%FFE8*dz~0>HmXJf| z{dCgk;!8CF0FZH+&9!P9Q_*>63^)%t#4sN3CrBQc@pWxaFzylnZHK;QicDayAl+n~ zv~HCfljl8mKBuIJ&AZO!n~IQvz>?w5le)aMk?;SL}2{)X_sl16Qxl7P^ z!?*3-??K+r*lwPlU$>S?bbN0v0B51eAg)SVPqu<_$}qOjEB5$B}jSXo}d7Z z14dWu%n5)k_15Xb|H3;rwyjb|LIAKJ<9y@aiCv9D=N-8r(1a(L@pxw;c@Qz;yYu<> zs(X@nklK24{nRIH-epD$JSTzA zHM|_`n16B7PhTDhCTmVDxcOiIPwl-J`bXIRhtt#`lA+h!_y1p*3V6Fe zI_sk!5foq6vHQ9N{Smw7iv?nX*9AZ!GVT{=uD3b?{TZbDHSw3(elT7QdWhsvhY?@R z@_Xy}hyuVhWUob^Ep~&{Eb@Lh_K*jtuGtmL&5M2hkIM*XXpw7V{u)$IUmgL9EyjY^ z=2nnlG`!uZb$f6}*~Ua%RP_sQTz&nHjWfbTu|q3;A9VXh!M z?80ub%os5J3R09vUmg>s!uRV*bK6^?G`wT$-u~Uaef6PQ0*$vUpG56i$XoJvjQ%Rf zyO!rEaDlulxicFYhONkFM%8MEi6n4mY+;i;weC^|1w1s;upny_K&|Ro&W3+^ zyruWT??S&6c%w2hZp2-6-3l`L3KDnuzNL02sX1upug3JeUGLGChr55Arr{lPo$o8Pdb_G;uR!D7 z;YP%pLEe3P{#=^nJ>zJTm;ia-mp}PNeW5jZWynF@oACYXrxIpmCXjd2yWY)r(rzOpE|ng^b%`BQNo;44rrHLPCyi1LN@yM)G)v5#P41 z$rbY(1;EVL6N}q)v3Xmp7gPIlzy_!{R$ly?QIA=@aZ)`C7bUJ`dfqrWI`cT`s*Lpi zAvC-Xcydipd8dguEJx$rr{uMwC%oDhpyy1y3kW=pl{?N_uWmp%%~$T>^` z>Lus*xI^AcIvyU7Jw*ZGqCAVrJ`jMN+mbBjQuM{i)M8uSMd1R#3K^&V!amiM4SjK9 zZ1+aX;11*Q{*L5<72k)7fn8GYa6(f}LHe*HHtzva_2zZAwvwA`k4X|f&~d$G#-B%j zV*d|(dn=p1Jl6VNcF;QgU;oe0eLpogIK@WL)Sx56)$-IDRJj4a60HVJMkSp+bhk|J z4og*l0<1xk(;Gi_TvpY)kSfqIB4JIoSlo0`(w+qR95uIXhW&q?x}Qn+1qz6;<#A&> zOaSTX4~{Isqt_sNt*z>~}TLYtSX9z+VRH5@c#xjPj!AcBf5;m8@({Ztyf+rk zfsprp8s3M0Z8`Usci|U#G~O-SzpCa#-dDv#+h%#M%p)xAfxJV;UbHOWu_pVToay=Q zL;_-4ANIII-WwFpvqu(CfCTBPzr6XB}v;{oZOuc6wR zcbT3yZh+1_4*aS?R*?H>cptjo_xA+J?PRqa8gGsO>ra)C_chk*S}P&%YW0fN&ye?K zuUr}52`jRL#JwA7@cVxb?WJjvkau;hY{A8I6!3BXmEyN=2w=zA!F81c^y>Xfw!E*p zM*#RC;}UIaCf3-X^R}I;sSy%mJl<1C9$4}9iY?2{mJ|Si-JV%u2e5hHPgF2{wcigs zs-Qg7;G^UIzu4liy-gdLzd<@oUmgNuUfGFP=c@N!8r}&<4yRD7_q>$}vS_@G+-d^b zAa9vm+4Hl!OS)WSenQ@R60={az};JRkJ@}Se-hX-xaxd9#1B0Vyp%yI-~w zz{ca`Sg9~{-r`|--PfK900U&4q30gadVtPbhHFuosvzU>UWVj>6<_%gd8vI|2t1C+(Fg6l8Z!X=c3ua9MU=uQK;m7U8zFO$KPo;K> z4s$XdZw@4nlNj;c6**b-zD5AB3FD*I24eGGE;X#a`#}JxKl(J!oBsj!_Lf$oQ}B&- z%)dCvqce{ep3!Rm-T%iZE$F|;0c%h+O$|zsB#TpPQ0@+XWwaVpEA`!o3)Y~r_oH@l zum(|f9@Tb%caVf_2;1i0U`77aWNVSMh6G|tcdhQ=A0gw#<>rN!!3U(jh*z1x1JbH5 zlkXBPpx2*Z+YAX_XCqd7N8tS^1ww?4oFRC-t5_ zLFHXJ(7hUsH>GFZNomMiMNQ@2EN}OwJL1bAZv%_9yf&|_$nT$w5!Ba_z;oG2nJ8P!paYxtr z34M8dFVGM9cyVq88A-$Ycp*iD%DYy(Knaca(Z+%F4Ul(4s?I8T$h&T-@wM3(q!%ki zef9rlMLumRIy|_61gdJe5066Lzs##^av|^4+I(l#+lXMFpZ1G0|MLAm-qePDQBruY z8yV;Rdhw7eKRRzwAth5yXU5~rjpQMM5#QcY$MmnULcrx}*iP{pY~Gz^de5)s*?^A6 z_Z+@VwW9vBr%v6D^M8J`t*0=3gJiytzC5~;ImGSi=00ypq~U!mW}=76+bAt!6&mmR z_*>%kkoSQK!?ao6=X(%PZ50C}6k7 zXXVm+1hC6O=a#zx`r_p29d{QCK0F9O#%WS z^o}AHQh-%kRf}{T0i--lxSwW<&iit6w#_z9JUEPubNlQ*;NgSLTdDB?rNNN#c$Xr1 ztj36MrYNhio^XKgK&J&7-M7=?WzesWqs16W2Pl8YB@?_x)H6e8n!Fq9Fro zkYmgp1I2PxJ&l;arw`=K$?G-dFX~nz0nLNABDCQOQgA$9TH+Q3L|u~Tygvg^kQ!}v z&bLLcL2iEjM_LQwd*pfvjO_;oclGI=J!&WMpbi-~Q}Fc1a&`0uDe<7BsQf*~ z<6VX1aR?*6nJY`oJRZUGe^;rzFACVaj~rjU%@jBQJuCS&tN5BQ8zkJQrpCv@KIZ4W zQj4xU%rDI-v=+|x|4A$~yiZ;y{C$Fy^-sPk8t=V%b}eMcJ8YdCUKaA+r8KZU4f1aP z8k6|R!IGT$yH8Jk6?}s9Mf`(k$h%9feXysT0uE>`aPiwm1n%qjKFGXA=l$&W(}n8} z;DG}&F0~}9>%AyC@Aa<_?D=?^@pyM2d8lE;C$gF-xHiglZM~e#!e-FGt8uG@`@J=NNI_d}A zDFT4AKexkCw|WJ5 z{%^K=Z6)L#R!4HszCr;4;!pP93nqf622X-dy+P-_)2J+u*8>k8A>$OqiWiGbqp!VF zxiz#Or!pSz?MNOe81Y?bs5qW2f(KazHHASqY~HFPW!%C>RzTR4$4;Xhd+lBRjlNTccoOoDr(v^oGD^c$by!-9H{vWH0V}M_WQ!EEf4a${I_%>UER>JrHmqfea&}z`z z8$acEVGY{BEx1ey)}R<~O;s^C#a8cF)YYM6OkQ(B`eNEj5>Qf}-c-vsLgpa-Rv5cW z0re}sm<_fOz~$_P<|b_DHHhcsyL}BG@Zb_ME^Na~6Bj=8DRyS_86aD`} z;6(DkiZ3x(>}=6`0r2Hv>r4Cn*fl6nAaTgL%$96@Qn~- z6W#0Q^=1n?Z=HzTvA#cyH^qKN^1zC3`iCRC#Si$!tN@Ef4?k?)3m<-1qdH>`v^*|t zBxp5Z_y2-Z4xuM-OuvG}anhFug=4M#m)mpw{{kA`S?5Lnz922GnW>4!J3-@&tUlyT zyzTmJmiL|2<4PwX@8}8l=IT2e$x_d^jcLRF|Kxb)+YgX;j*U{q>1qn#-!zjwwt)zK z=Wkp1;vhQjpZlLyZ*9SYZ^*a~!C#>tRnd9Rh&lPLn_xWN6G$F7@qdrcYysy%$2tLU z?RL8BZ+mRse=0M{wUurlw{M=E`BiM*X%^ca{fgYf^t@&D=*#1WQ&f=Wp}GE_jfQt- zz#BJe_4X<8&_LsTZNeqQ3Gx;`yuwo&^1hrc+cmp;>to(_{*2=$GSR!M&J^z6#`LT0 z`U82B8y4=GsiJ_jKIb(86^LLe&8YNkC_3+G;=VqIdOR3M#@S1Km;Aa6o%hf6+k~Ts z7>_pr$zuv5zJpO0GPnKV2Qdx)&&{@A^FD1P;hFo;4OCq|{wT1Np8j9t2YX5=)ANpb zOJ5!fY*bh!|2dqPPs2OIyy_5@_xkT^)}!&huA_A|4Dy!js%)9%?YXx7yazmcQ+ukR zy=;>i`PvFH&ym$6@Q5s5E(-hq*NLpF?QX-@TSVj}{56Sy{k&Q5szh|&mahWV3Dw{M z4jC8uUVPYL2|Dl3Q)1hRpBRt#W+V@+_@)hH4=vg(04kpYqZ&hO-s@@x_I*3%2fkW} zO`7Y_!Fwi)&DeHYl)Cyd|R7Aibd;QZD`bPBx&Sq@w=IW5O{ z{l5;92UdL9S4(d`3KRgzW6j^>PGQ#|ccCHog+=aUPKi?zr_-_T|4Y7kJotG{EYtV@ zIaT!Kp}2LDt@_H`3X+?KcYag(M=I~}1CnfLy!T#>Jb4N7PEoTCl7PI&)n>}xLf)39 zd{WL8`eX~z=YxktNnl&hWKRy{?XZ(vX9jtz>TIbRT|op|4U*nU|MCQBqvBG~i4z2> z$hh@YMG30{(0M=5lnowQ!FasyBY9xO7gERX)04*!xH1~E1yitjCvIyRIDEmKEKq06 zq27o61Szh5@@?VDqfE~mcbUFCTsGHsj?~We|6DY@&*Z$Rq4IwAVq_i~?|2q>o;t|e zYK{E!S>Cnw5qqWJ3DWSNpe#2p1G3e*-P)dFB#^m|JM0|fZJ%NM?sY8%@YvfczL-x0 zMFBUevhw{j`t@wPznz=|(|*YnxgAOR5l zL?-lMA~tWw;SbX#BM#*4mJMeNq?<6exBgt`T@i4Th3OllV}5HUQGUB{_4$3 zUmnY(H-9^RZmxQB((uk(Yx#xBJEuR11&z1ShL5!qkoWr69am;~+uyO#8Hc>npLaW~ zl{F%_#+0QG!SjEoidfl7$lF49^|L)>3h>-t{yUqU2u^PsTYYRjI`2x+V@1cm;Xx)c zF7=bUDT^jL?}$afwO5q!cvm2K?8k`jli}um&0VCx5V%)gs%OTki!wwqm57 z0tOm&qSM|G!ARR(sn}QOHR$sf;w{S@K`?-f>+`eUTrcH=I+Z-jd3$T?6~?PU)I7Q{ z;;Y?wSv0AaAKcJCUi`Khy9Swk{=Dt*9|ge2a%y=B9arr9D(-pvL*xe2*Pw?a`ts1g z*SZ+OJ4hjK0UF*HD-R!_^7d5|;X>mr^F{TT9OTV^$IWm#ck>uQf&D)Aw;|SMA1(3H${D~~* z1Jr-^e{1Z7&gs3!?l3)XTnC+be5+EC{O9o&ej45vjy__i@-||9$BD*!kqmdW{%rMr z&|ERgdm{VZ%Qm>ZHEFqb$<%gT@*=6XGV$yraLagkS0d!i8Mk;Zv5o@d^2J`+Cqx2& z^QoYt>FC#6#Iz4O=_CpQPh=e4C&q;8IP{J`?? zR*k+J*t}=g0Vml*N0VDH}Ib_nc}DAQ&7{vQ`iUmo}!eu9fm&Q)(d8r}t4 zS8Sm2zW=C%1C6)a@l}tUA@Ayr3aQz{i3Q(s3t}N}HRYAtHL~@{l51|PtKo;26Q>e( zoq)W5KR&x?3hv&Xa;{LyKN$%IYIL~Di_m%7?i&uOj1vSOka0e4IQtrZbl$J8EDsCG zVLaYeNFF^H@rm3tc=NbK0IdI%efZBsY~E%44r&@F?8zLydk_8Kz`ng@Rd8#fdi5yN zACUgpM_(SpUqzod`pj)_@zU@gs#9>_b&eSZoq@2a8h3dbBh za<7&3#%jphapRTPBapYXlmbT(tloK+Y5w`?MDR#c_-J}L`r?G&{mr$5f`Xs{8FzWG zFu9eC-v9G%S~1M8!g#!SkUaP>;;Rox98t>W2Y!pq`-{$C^L}Srl<_6ap8RBzJi4m9 z343w!%;0-Z$b9BsoV=qi4}8Bo-X!q9^Z&n#Q%3#?Y>-4~YEaoA-z2pL8L;T%(Q449 z6IoqH@4zoe?-DIo2B%n)Pn)l;gOAwh@7^cf;{C* zUmlCQ@0u++GB?Ev)9@~RldMPO{kBv_0FC#`EpOLeguJ8PY!?!Pyj33eeHDegQ(7v6 z)S4v8PfV;g4}XmVJ}t6>&5-v(=XUl23I&|gj;N^4fG0>iIKD6fI`6MgRegoqTPr@~Up`^JlDr&jG`~L<2LzS+21g<9cCkC9DlPB}(lcf0 zGw|yzer#u|oI=ofb6k1uw#Zlzcq8NP6|21Q3`6Igt&%fj>BM-v7b1D&V8rLsNGa2D zga@P>v+PYiV)MR!_Sd2^O;6y~`uMKhPVDWi&D*4oi7M7JJ#TkM`tn%zsZrGQ)Lj3+ zh=zBun|2tLx9_oXUNqhb)6xwuAn$7if#b8h#}^p4kRfjkj*_Xd(<)>u4&_arqj8`o zWa(}}*dSRH^i9uirhslghx6lE1R%R`QbX$yI&Z62W>M=61c4+n?#!5_GdUEU_bTxp zmIoaekGBnyhZ077wv;e?7T6$lmwY&OxEGuEK_cZEVVx&$m&uSniw zdfqq#I`i0VR3iP)?yVpV?;^P$WmMiTx9;OXRr8i2^wU!5WfAnaP95lv?JRT@?P~?=Rjct1#t7ki$`)rg4RnGahdiBoAqf_1#gn|E2Z(e=3H z_Q3OWi1P|gI-dW3A9}X=nHlr<|5xeDV_rbk>Vp~o_5Xhtr;Pj)xPn|pQ-dlxpFg42 zpa!?KqG&aUOHaCj4c4H-vM)YMU=2FQy`*mgY>+&j@&^9!kOV%W#XIeVNkAg#-uPXf z5wcNv_L$2X3gBDOMtYGE2?E6GzikLauR)dZSC>A1BM5wvaV<0QbqBto*PvTI!jDBi zFCX)P*m4qgcnG~TYB_Pxs??+BLa&RO2Qq{u(|kT=dO z>Pc*>FkoNLVlc{00xbjiQUj28Mu?thX*UIYxA>xVo)ii6xUR+R_?HXP&D7%ZihBfs zE;25Sr$agPEjn)z)qYQY2IOslUqrqVI8GG~Nqh z8kVa=-kW}Ns4RuN?{6R8vT>F-`vu}Ds~@_#ODf5qS>Wp}*Lrs^g#AB0!%?~9B?XLK z895w&H4?})^ocDdp;zzL#fcKxe*}RPGR}yHC+Nd3bl#a953+{Yq{xi+*Yg<3BMT$G zoQutOemL=i`I{ZxEoZP-kSByPqR&9y@rQ##P6cE0##!~~-6{=YdfqrY`tksGiC&vp zGG}=&rr~{6GuD>M8>g4K2#t4Aj*gTA$h%x~ zo%iavZ{<84jJG)HqvnAT-)o}Z@Ha&PkehshCGQtDZ=)5F+V>0h0-$?d@3dDlX7%PK zbsKNLQOooVlJs%<@>m|dXDL2*?r=hshWC|#)C4MT9mQxtG~Rv#Z@=z_ym2aL)n?D$ zsJw9x<6X1TxX5xI263~z_Z$ zPg85qM?pn#v>G%|a`o<*sxrOPt4C!;VGSB?Y;H?{Q!IzY@uhkE8vv`|u9Gb$B+#8m zte1ifl9XDq_*6dykaXBS4?HITlFMSdti$LvC@N3eJUB`a97M+b?C;tsycB(k71+M~ z)UP=M66N}!)}naa9YY(>Hg5weS9=y>Ld0ElC0OVamoFw zn7;oH;G!=N{u^Fu3*a3jkoO82-j#(jLR8*2KTIw|<1KrppeY;jwm-v?ImHFQ?DS}`K8FzQIa2MZp^y*E1tE2xugYkG%^T3Ml>>t^th(2Dh zZz+M}fgm<-!{3@=MKeJ__GEjwcNKPngxloizxMMprmx;Hru60ULD7H5WM#@MZ*dyl zH_gxdeK@g}J#z_K^-er2#L)(MFWG%2W-;VltK-*V2YDZ6+qd$#k1BZ6bvAUqGQ7Q2 zcf~b-$h+vmmDdd)D1fuHcJS76BDf$@={nMjUcIkeSB!AmCkP6Vaqn)HPOp|h=bdhN zXv8m;@pxZF^1zC(m-Wl3P49pf8W6^N&~iB+o5Q#AtZm5Dhs(U7RG|-o6-(cMboh{a+yOIP>@8v%KrQhA(JA z-d1le9oZHo55907xifp7kX%QGSGxS#^f#$E~-Y>H~%|A7d~*OV4kT|}?mQ#$j9 z#oq~ntH?NZ5ntD=9CY41lPcr-{fx)^7m^27d>WfLl^$sEgL5|t^M?emdHesq{P@)_ zZ!o01W$T1W1NP!1c(al1{Qm=slL9*P_-OiMDSW);zx)6Gr-qxs{y#Xy%F@&za=qw6 zY7Hv$lafZOLGy;@Y5l%kruT5G=CBZ~LGtamS0k_ni7q)Zm@Kdn+)OCC-sI7pPqBKw?n8CT z+)O{k;1RGtJ{O3_L9I@(ve+XAa9*})oVNkDIn*=rRzWOk>LGO_xB+;(0N~a z^di=+Ul6=Q#)+5nmfvJU=ban?LUTSc9`7O~k0gxvey^No^H7i%j5_7Ib1cW^ZD*IW zU(;NYY!XnTIwp(F8~4h0PxyyG=I8C_Nmm|07dY-6-V!?7AW75kuKBI~jLKVLOc9m0 z|CUVzCCK}zr^WqQ-iq;?lB*zZhg}Qyw&WTBp60;uBIuexgk;>}7q4Sn|ky)3{x(HlF#+_K0oc~=8oj2#R%-bq6jK^CZ$%6wUK9XhE z<vD18F*zVwaobH^S4xDFTwZ#O4_ z>-VlKSPXev2?$4?`%D2>hUz1&TO&c~gPb)≈e?NKFN*MhyspB4ixpZIz&oGdgb$ zt*^o4&y2@g8p#7Iz8_sa8Mz#MAZC$o)FyFk-o_=#sXgf$!0ikGD+w*eyrn{iL%@)erK%UTk}lmUl|uld65; z0F-NQY@OvjI&ovEFyzfSZ<%KsEhZDv~9`P9Qh4`@zQP}yxn0Fd^-T&h3ZSuOyfkIa7>n+@xR;r|N zC^LQa*4|5B9$%&Uiw5A=TmI|+8LZd;pTdDFNJW|&^x#uMDRqjyrn_V%S`C^GM z{(m^`W}P6MVntcClB(epYqdLUKqJ-~yb$3$`KN*e!i#dd0%3#H)*}#ZHbDVLMTmUM z9z=p4PkOq)yP!|8Q%35dQ}7Wx>Nu$r23BQf(5KjpkJ?vr?lImJ`xD6{3nRWiM{NsY z!uWuxj9XaxBJ3$P*CD@C(ZC)Eg(z%#t%O~Jx^KJ1g%&ga1?e;O-gM=Wx+OrTDShq{ zyOlJ&>no(psJxy12ISFrr(ey}OoP0o^av`8AaB?0tn6)&_t&nQHPPl)K=1QMwkvQ3 zFP1(e9s_x|SY^r%ex-o(!?!_m2N9Gy4aWgb^eNV0DpTNbi{RgJ0%zUt#Pgx^zG7O{ zu&IIZcvJJZiV!?4!00$^F`l z1LxV%c{jxrUjOxo@pyY9c{F3hCzvE$^A7NW3C{bU$s*X*`&YeiMY5VbuuVQvVR*eB zbyxfEgdIMacUJKKv3IBORBdtNz>jg8heJXoNugAxkYb54L`X76nL>&*nM24tSCk}$ z2uUg-r%|Yo4269!q~Kt^DT&X;~`X_fPbeqP)G`!j@z44iPmpsV7fPmKXDqHz!6%Z+h-?M^%`7(!b)(zN`lUul{~v(tj+(%#s-S+%6T^LNl6?@CG@c>Vhn(YXHP4PId7Rg#uM!_!;&Q^(#p7Of`L z${gtUE!Tk0ThgjsveS?8d0SY}l*bl1UGeIFE+>|u;(d3Vl% zSf8)zL#iGVHt)9TefpX`LV%aju5afUm+vNQ-V4@E4+_1cKi(abJn;JGQFN^_SeYN} zDZj#EB#mFar4_g535O^E|NIy`iyVC3tS<*wM=YITc;4}z{WRr~)85UV?f>8U|L^Ec z&p*KRzXDYadQvr1fex`Z-ta15)gYb?4+MTzmS}$fi_!#P4Qfo!t80UIkocXsdu{1r zE8rfv(<0<%1ZaN$u6%-fgj9KEP$6}u33z?l-JL`V1oeaV&yj!m21!&~ayKhU2t1** zTPoqnv2`tW4VrpcAKOw+e>EtQk_TS@W*#59-loe3POaz)TSmh>NOGH=w1>FwBt`!e z*9mH*;fkHrF{=WCI2gVL5l%ku;>Vp*;E0&o3n0%_(Vn^pCL z!06{ACfgdZ7f7J0?$noiLf|{4-LH^4m%sXB^Nt#5zMg%P{&;Iq@;HIhzlbbN>lH=3 z;Q2({%`MFMLu}N~-ErYPioog0@X04E_#335OV^GK_NOvD@6a+8n)2ZNtSH;+^k@CQ znu>RW^-3v}w?R$GDlFb_JU{$e1$l4Y&wPl?+won(Gd;+Af7|(erF|B_`HGnO>Z%BE z;8~-N2;_aObf!P>M-#YnV5NVUUJw{RWD;ue6r1;%4GKaAbwc0=rQPIwnY~p9uzA0V zu{z#UO@F*IDS33^^zU70dQi_oK5)fz`v?aYKJOhZ_YA{4O#pF7bKX6ZI@|@)=cM68 z)|OF*=Pe*bTOLL6;|nfa`@?$`74Lfempv%&`(feoSiBFg%vl>i-XL7&6PdS#ahS(> z$lH1(w%yKqJLporn2}r)0p9W18LfuA_b)6wGdtA;LJhC_KC=k|W1jK{Q{Q9rW){+~ z&1;0!o6>IidattFL)g4cPqvrI(Bb9;6D1Eboc=95et3CJIv;pZ&CFcFjnCWOJf_t? z*#y+cJ^JM?{0Nsf;m5)K#onO|fB!#W;4p1@C{=S)9&gE0@vfV?c?9Jx`oeT27VkNC zt>3#L?^>pE3-aFE^aXeCV#s@P;8Dwt7<1s&p8Go;PEL+$&D_$1yude zC)|gEK+w5GBC7v#drQE_Q%58lgg^+ToyLl1X&fYM-uX+*`YP|zU-kB<=EqP%Yj<-Cs`#K&h$ne#hVCFzm9vKsbv1Rb= z_ka8U^t|w=^bM~6*HYD>=jHN$U$N`{&8CV~gO+qZtrQXMR|N`m2Xt`N8%7 za*Zu7S`zJm`13t64R8nP=inl)+i?BwaJ*@u;qN98E?%!4tsVqqk8)>ZU&bC{%fH!j zMArxbc}hFm3$JcytB+)Azn|I;CBN`!)_Z+32_^Vf`&%?2K8#it~yP}x>co$IeFv97d z;c!a%f}>HptUvjN;dv8`Y0IP1;~U5C zOMezf%2d3Y?YQPp-hA%om9cp91)0hfldJcGyo~~o_cGsUzDUShFM7q3#Md@p!&l^n z-_-~psC*-&9`Y8*HGXOid51rj3%2120+q+kM427K=52V|T+Q~55U8fK8~Uz2uI-1- z+x?elhF~fE@z$s0f!DwC4fzN87V(3<-C^<_-|>0Z&1B!mEaV4cVRp02^_}et$5+6?v@Jr<2_EvLjk9M3NbIk_8jB|;`VVIBNO<%2}e$) zmRECwJrCwT$quf=UH^whq-FUjr7`^aKa`oaJRXMGrcT2Tq{F$lA{FnaQ?iaI@8uUZ zC}Q#6v|w_)7xM1y5s)J9y#cAx;S$JO@?6^^4rXicH0X>J$BhVZzU<4-uaI{};z@O$ z*(R{=t!&iD+dyz|u~@&X6*lkrVWBHa?h1h;ly;ZzAMx2}hRs`7twwmqb^7BiLdio1 zr+*T}=5hO1yx_#}LSvV4eBK88IZ1i}J4s%h6ZKE_Kf>odGbWWY@tfg!2Q8;9kARYQ zlU{lMt^e`XaCGtaum)*R)u7HM(N=N|S_yBEI`hndfK`L`2Hv{=<5r2bgud}QURZ-F zZd?!`z)$Q}z3tIq`{e+}veCJ!x|*CGetB8 z`-+{!VP_Jvkq|gcX=e~wCO;>HU4ukJ!8SJy`l~^)lsx9+^sn<|d0<8hH>mvb&hN(q z{2Fw*Wd2TXX9sYWH>fDT3V(x?(5RO;cq@bP7f9c9Y04vMSA&9T;-4XQ9To46bvBVs8eTL+uf&@QU3E?>jz+ov?X7yWXF10Dj)`CZ!!O-@(UDQ`oQASu=+_9o|TP zyc;Na;Pubo^m$H=^*lhym9*?a13qu%$j<~W8wWttM5cGy;`0vmeX{NPN&>?#kO&zK zH02TA;#(Fl;7^`Gs#Ec9k2xxW@_y6#avc`$>CGEdRzTjw@^)@M$a_8_^EL|d4o%G6 z@rvjGxcALlcQ-QveEt%wZ4G(v%v-g>nyne!PuR>NKOP7+7Z-fqM@_}$b;8onUqnRI^#+XqV! zvKe`JY|m5N86-h3Okns^FXQv3F%Ra(GrDG*63M*PsCc(6mfwT&EY@=+HK}~ zkoVZew~=JtNw(^(1CV$AlMrvUkexu0RO;ji&tGRWdoUk{ymhU=J&k2)2J4c(J?AY7 z1VN8%K=?vz-e)f*^|n|Efn$_*r5XZ8w+yj)?@2j+_qZYb@y?*+f!Dtig=eSqW%$83 z`voJ9xA@iDt5q+vkz@p}^BPB0{>I;&s41y5R~=|zc-~)%Y0JYsh4{2T@XzBdRVv=C zBuegL^FF%uc>f+c ze0uwWk_TS@TF;zwWFF!L8+h6eRD8hay*xG1ttH(EL~Jx!n3vmtU%fL{R~=G!VEnmv zIBj_dq}4C4h5r8A|EG%;{=atu4zYl$2E9&B+Cr{DXFh*%7E;_sXVls9OI#>HU#*df&hFB&_9$7g3``q&@N<@|$ z*gx@Ac~pvDgP7Y_Ie%E}0ls*yyZ-Vx{t!z@etuETP>$h;SV9kNc{FM5j_Zy5v;Nnj z;@#usEsye6Nt0s3;{D+L*8CL6dtqUPKbdz&d7)1zE*efqWP z(<8`RNI4_<5MMLMeId~B>laktz~@ao=oHu4<3QnQ?jnZ!=h4dNlU&SOB=n_p$cHX6(mXtZqD# z3pNRXa!NbWB1d6kL2TaF`;QDJD9|5o0-6U-{{p%XO%FtKgS>?cRBZnbyz9?%o$8Ip zpFvLkC~xd;E@61yFSlQ(DG!^`;j|yKDP-OosCd7ci48}24?G|-WAXl+)aFnJdEZ%b z#*PQ_u1QtUDuKLT7KA;5F zWu1CKz~;@F9Hir?E(Bgt+P%CQubSG0{q%OswXpmBa{A-VM#?;8*XDOZaVfbT|Y3Qu{$yH5#tBxVz=xt6zDHzd-7xF^}r`jVu0nIdMG|@0T43 zuTkDiC*zo~cu%Z+WBwNMj^6pak<5GCR$yKWU{4#{mKKLVz%0&J`RyJy?@j4%W%4!)0ai*oSskt6WDV@4}1K{*8zht-t@#F>rXKh_})3Eo(&7rCOmFED6Ql2{4_lt(ji56YyrSdWi&pUL@ zMw;>vYszpM{%`&N@9S=Q`CB-|ZlbC|?_+^6O~MEh5L&3g`5 zgUa9h+(?5q4#m&ks zT(CwX9Hr6tLu_%l_@3{Qmf)P*38gbC_%letTeHPll0O)}1`(QQ%Y!(}%QX7W0cl+- z-tSz`ile-vkBV|*@iq&%l_Lm;*vH?NY~zHy`?Uu0>mcs{|JbDmavi`?(KB6K@Oq1h zy@jl{kayP&{-R~`nt|R5pF;&sf#5aE+ANJ**t}1iTCFMkiwNFQ+Hp4D*v#pL&3o-- zi;1bv^v64jl7|XT{~E*%*Cs^qfLqGGUT2QYo*CDX$42(XZCZnZb$Egdfc+J&0IEVn1KJ)A+7MqZ3px`xera6*ht zUPuUBqqN(*^7Q@+cWmC?8$Ghqe$gNAFO)p+`lmV6V9WWP3v65>_L}K5KJPCzM+l>3 z4xntDy>I1KeBOk-OJ(2QCNey4!bRHh80O1d^K*LwnfFF2-n|na{w|Pa%5QRD@h&!Z z`mhP|<~!oJh70oMYm+Nk3>Qe!S{KyqL>$5C!L+H|US;)`raUs0=8eDq z=l(x!D&B8;t?r@KdwpdDg2g*spU=Yq^6nnv&L;DAW?uf<1@c}Vk#zmcE=Ry`X`MY@ z5CIUs6F<*G-aiE9K0gy^1_9m$laZS6?kxlBOx|>C-f1tVOrI}+cW+VJiDZ`C&DO)_ zZGUamyfK9S*8fSAJn;G#FT#IwPct`2mX8xnzJ$;Fu9e8j*pF5qQ%rpGw8kS`-h|>b zjm~t&znqBhiN-t%m;&d+$6NpH|D&rwI{p(5v4&JNXyBx`3R;7T)%1y2HR#sD!r?%; z{!e!9t7nHbC|m2ry*N07tnCOM>gU}Fy5|Y{Jc3v3Snd!gQ-C$-nnqV-_55bAWS97N zLzh61u(E9QSQ&N=dhQeZl-N!L$&_|q-gakij>E1&`66mx&(_f25Zg@2BM+y41AVp6 z*pqnRH(E8{>u<-eL6Y0U43&;qkSx08tG))&@Q6L9)C~jABk7Ix!UcPhXjmW-rn-4z zA2B{}X4>+Q6ibNfNemz_ko2i|e>SPUgz{b+C?tTzyP*E1&lSj9?}z^>GVi8#8?6M$ z+be89Fg0x_AUZ`QXF%R^PJ}CKA@7$h-z7XDZ<2kPSAcjBP$^hz(dvuMdp?jX&iG6O z>Xde}$lQSi!`Qqxev%QWXr@2j^C)>}8f&8G_3s2cR@U7?koRcT5^Xied%EgczA5A# zTEx7U9lpJla{Y#Rk|FlwCc>R+y z%uV7F#6eL(K3dw-eNT7VHvUC$S?5E;l#~U zyg$^;zDIe#Yz^ea;$0N*V0$m*tvknbl+2s|^!m0W$os?3tlt~9I)J^}u}^IwZ+~S; zj`ff?;q-WuAmn}MT}R($kwCD$f3!{PUtUgJxF_qj=`a!OptO7Zvbgo65jO7~wcB`9 zU(z3MaY`N*IQ_e)n6@#_pBs=0{oB-!;PbxhBc0=6Y)eX$)Yqw~qG9em9BbL!=EV4W zZ+$f8@qXt^mH*cNj4?>VA=ZSd28}e2&Y(3YC?`@Bs|Jl}M>x;jDA8v3iOFY$H7HLp2Y>(eb2f|*5LC#o0^gKrp%2bJMma<yKkB1Ska>GM%Pz`-ytONr7`mRY2dkSu zY&s9WAT``4b4C{O_IUKz&<66hwRw3-AUhBcHwTld2e5f>zP;IT!!sh7M`^dpd*EY7 z6*lj(gY3UO%IS|cn#Wa~{@qW$qkXoW7hIW9+;M&bKJUIgUCVsk_K*w;cXVuR#(%t( zp&gq1LZXS`d53D!mWNQ<%*$i5e~z~pQSlxe>FY#!S19BOWAXO5#(8H8BL=EyD7O6bAHZl-28;&keevZw1 z|2zrjq9!6}rL}xIQ@HdLfbk8UQV={x%b4BEpdj-qvKa!HQ}%S35zz6B;PwSJZ}P^Esw8V9+khLKUlrDQ1Sk9Rk#x6Exc}@ z5Ek#rGq2V;L*AVptPbS8wwbIFmvH^h|AVQCJojFg>!AM= zuK#Z|?6?(@83;{1w|nl(vhFowDIg% z7mcpUI%5UYTJx^{7R7%-T7XYypVjR?hJOZG-LsLVJSL7tGQE%cbH$E174M0SkE>DM z{>sdYuz2_Ls3%>3yf+5?N{g6Y`#C zyw=}!K{I$;u+!A}7<|O;{dxN9eQe&MN3}2URT6;-rQN}@`U|QgY~C-Yt5}mW>5sP< zC66|o{<)_e%vvYG16rGkWxa>+d5a2mH2TF@0om@v!^>*%7f6J3u5|_FgAC7`u!*)j ze(t#xzZzc953Bb!D&FHliBTx;4&x^auy_wS78u`#yyb711(12`zDeHN2YKhls#l%b zZV#3pjasz8J_3Z@PP-xqXONHN9{CQ5HG|SG5^oLm1cGzXp7}~e*u3w{%UGmU5kUr} zo!H?>sgEVtytf{RM($+MA8#~|Ejaya2zz!nFNzmL`)z;jIE~M{LGiS=)F~a3h;&r+ zsRaDnTLhSuHZH#4#PBo7MfVhG%H!S%m!zJkKh@ieiuboZuU#l_9iLO;SiBF7y&q_S zyoD$4ye0E)Ww}+<0C{J)?|UqzXAd6n{&>F2IRc!U7!wkQybS~*&pAQfY2F(KW~>6i zb3L)Ri~q7YA<{Sv0!I1pT$WwM%z1JZ}O*TOJ(ZGMT~f`xCHw zn^N%}y}s)2>n&0z_laTgPBsq<>xaCRT*UOrdv9uOp_>aK@2-7APM1~ff&S3?2|lj~ zu=(_s11ll#$3A|~_2J{KW5gl<@x6f{TF^)(?_bW|de_GtwrU`PC`!ATa+{;i3$b~B zIr!IMebXF)Oq4m5SVCDU8WMmWpZa19n>xK)YYo7~>cPwfKZW*WZ z+9m@)!dT)l!4=pu$gX*2Vq40HAdb>*9LL6n ze0hL#-I+#*v-mT}vkM>mOxD^>Qb>=Vj<2TS43brDAp45D3}1snEosXmbgPHqCyPJl z|E;Ka|J<*59_4N3y<#aA@7MQ*HpxKVM~ANcCi6}LR<4K%hj5xqGr2oA<9}8w6%<5P<@vU6iKlgGVjcyaRT~ zhCNB6Ki+5_hjIGHJG)$SYZ@=ue#E=7sRW<*53d!~-UhZLrW;-x9WLNM-rBh=Aoavj z62l*mUPxmeh+w}Q-)51%1##UPQybolhvsc~16LvbJ&98=2d`Gn1T+3&%7 zPAx<*KxxM>k-Ta68#eC*#j~HL=x_$PoRUX0PX7!O#JiY^dBEX>V13`~_`Hkd54Z(y zv?l5C@y})~#y|fbI=mw`U+pQw^LD2(kM`lmrl#zF&j0VA;yu-(JBjiR5sa6_;_YK| z%*+<@7VdiSn#}vC#!mN-khh<_yMNMZdl0A}qWKi^)^pd19EQAIgX3D|Aa8lE&K+{| z0)c(Pw!ByqY~K5`QkTS)5`hh+onbqVYC$|U@AJNUwr@(Lzv}Hx$>R)8|8!roo9cz$A$EAf5Nt8Zv3aW zgzDv{Q+h6pzc~>_TOLgXquY4k^{W59|4$DKe4IYO8RX9YsX^9EhtB-@#16Rz{k*NR z0;>is$?uuSs3_5XV!k7NZtk0Q{;!;26*$ChDj1z^%eDc7ud|M221S5Fm7;f_!y1&4 z**5SRE|B6BW=}j+4gm8Ox$(+b?ZK=mLwdo5esM$~L}}N5we8)jCD=o3uk-zc);;uB zgT7Mo=)vh<-7(!uJ>CfxWTPA+MCMU@p-RmjRge}Gvg{uZ|u=EZ`XuNj^NQl zu6Id~A#Ve27RTR^x54?%&Q_3jH2h%NteY+1)@ckF*b@O%lDkzqAn!BxMe{E}-tsSc zPwZY02vla{c=SxM7f3SCg%3+-5rHzL9qB;y<}10_ytR(M_pI=vKi+5_>u~y)J0()H z-j)YUOHPCd9>eF|8Ef*)*U62<_u+PTPAUxtq*LWToFdsX{sM`{JRHhD?3P~^Mdocw z#rqd&!AG=uJ2eF^$Kri&*9XStcbBdyoD(-eN<=dp0g-Kg#=&*VbiNyr{~nKre|sXr1CH)bWL^A!;H|{#670)? zU%l&Hm7`*IGyd0GI5cR><9uzq(Zuop*8hJer}X>-9AcgRrv_Og_V54R|G!sZkpfl? z3j3}|kcKsAsR7T)SvbV5w*AF3Q>?6QawN1nyUYscs0UP7-h&6ElbPHrU=6a`KJQ-a z;%2Z#cRIbfDgflY)GrKg$6g@C9WMB&25ZnoN;|XDU03V>Po*F_b(i zaQc@#`F$5jkOvHY_kVw!h(E+S228L2e8!37#Ug(*;L9W21(M$zxAlYlHVnT&de=!? z9?DCUUEMDHS^w{*;?2J5MhrT{mhpUAjm7&L(~(u{A#aVvIx}S6@?X_u*x?X6J*#s0 zgtRsIaazXIzbpbQK5ton5Ar^hcX$~|q8acNyt`9a7ytz4a`ku~VDo;X$x(s81JeAI zc7s=3LR-UJG5;Ci19tAiDfGwtH6@Q0oc>L&K9egD$OBBe(jvD?;PX~j_o%)BdDjp( z$P^!^;do2(dYMa7%VzcUEsooi9D3XAviHN`8<$-Fyi zcKw39v*q935{A4#E&Z@%xY!yDl#8rAmlXkiI^R0n0(n0?q2~1#&L9^(JX*I@I}nV% zX&buZj6H+gv2wCk{0R{ZQ`$+@KI3ohz~)^dHQLFWOMkpAD0vj&^zZIe+?gf4++aUH z@$d!>eBNBLgpXUboJj7G?dtud^_c(L|D8A}UT?PK`@s0TSJ9ToCEYl;+wk+MaB|{E z#hax}-vQ+yo z_qz}Bekxll-2wOi1AQO83f>k7s=Z`Ry+4f2J9u-l!ok->P)TW*FzTS!`7gJ(K0TgZ z+IOA)cn4APXu#>;k7ADpw{3X=XRfs6fB`;l(&9wR#7Q@j!}8Zc6P@_HjlQnr5w;mu z|I3|0fAAfoEsp{IsJ$TQ&-&kiiZ^rVqyozOo2}JKEZ&FYN>#%k?=UX8RpiYHl(%Qz z@Y`w=8z3DZ67m`HKDIRM7I|}`XW*4^6|COzLXYw-cLji$yQDmxDD24zd%NShiAZ?< zpVChBlih|YP3-DzwRrbsq7(h`W~1a`fzv-}C9M!HEpDK|a=3HQ44-%HxlPV`-`q%D zU6Tt1kKwQXL)GuJZvV{A@YOq1jkY|RgujlJ=Ki<-XNW2WhuA$-HHg=|W-nTUZg#M# zV$~o;V&P2L^%8CWda3N6um-U&F%douhuB=LQQ|UBOVFPiYSTCs0hn{Q>V1MW=#IL^ zauYbjCae)z`O`2Eoc1V*7x2LzVhx|(ChGVS!AVNH*41xqTmR+#|EVEe2Z9m()gXOJ z9(euR@MK--;*~r=Q8TjnO&zN?o}KGm5jmro;iL!IYX=879^=m-p9DA?9@@+BHHdJZ zwmjY}yQc08Z!m+r-Kco;@W#ADdFLs$s$lV!-+uYaW61l^jW(tk$lE_T+h`x;y}ZeP z?Sf=W@F20?ef4MrNS%uueh7K*y3E7A2d@9C3g0N{tOx``Cw;>jwqo-Z$osg{H<$?ozeTTexlPw#_yg7TdwFcqlMA;R)h4ZH@L8@h*saH<~P*m+d zSpa!w`F-D|FWC%g&h*?-`xppVa=*H<^NF=K$5#HWPTzoOT_7^^H`D*r*Dark$B4$!R9TN=)q;t&Uwfa6W z{Q948mbN@5UsqP;U;Z;Wai-$Uk;?h^?XB*ab&6QLeUqbVc;NcK-aTS9d2?b_b)m@^ zU;!|4RsMd7OC0KH(Oe{@?k3yhR*6{5>3Ey{KxC&_;_})uF|a@I%5eI5}AT8s73-VY)bsw?rMmQ!mSwW8gxlxk;Fk+`Ws@U zD0vj%^iTBLhFP1nLO^Hk_PL`W_(QCBI#_vhTLNjTitmd@T1~h!NQZX+m@Bio41dH< zyn(hnE~^V(5Y|6WoAZu+NYGCo+csHnY2jo4Sl_>NB z^1kUWCol+ke>qcKtrTPlDqH!4BV{8&=B*aUA*=w^<-gVAT z)?x8JIl__a33XL&?Jj zr+?Y+j}JT~@&LZ>8!MgT@vFD|X2Ywt#tEcfuc{wNDc9rjCYW(&tomTU@VrCk(Uyme zgKBAjXB@eDdr~84JW5;Q_%fH9ewp@p*gv7U*=_6-{b-H@q`t z|07)98Le`8=T|*v`1Swi4%+faTy^yRs*FGDe|IY0d`F!%QQk$&Dr#7~3umiz&p_Ua z=KI!@_uiiS`%m41yffrF3{qR^hWyQZAHl=8>fF~`{ZuCeZd2I z&ii{=l;HE0Oq*TfwlkXKY`AznYcmZmC%XIBlz6^oc-{mb8uM5eGe*ANf(y>h-m=^! z@Q?9-;P2qC=da=~=FjF&<`3sT#P7y$&A)|z1OIA%Nq!8j;76S)>PIA)+4O$thTJitXixJ ztWvDPtn4h)EMHi9SejVw@`UpE^0@F=@)+=F@W}H>@CfiQb5C%8;(p29$X&x-%ALcV z${oRdgxj6lmfM(Hi(7$Pid&eQookxw3s(+WnpI~FPft{oQ@++XcYA_y%KqbMv*0(iO5qliU_-W7Xje<`+V?iFFQIOoB7~~-u1q^8TBM;EX zzij;nKyILs z2d7E`Qh`Q$UeCrN*U`xBii;{zjz+E_X$0gN8oB80K82K_ku%SSa^xx+?d~csK}ykR z*H`Vl;9v80|!^pwZ5yEapfN8rgkK6h#Wr$hLM*4RRTcY;rU?kODNa z-fkU$0eo6h-9FV-eKJX$Z0g%yk(;qate($iI#3cPNI>{`$Tsn9gQ~DX&pn-&`A5pM{y(- zjeyA|c_ammv{p>6LXy#F!>3ELND>;YuiGt+B%+ZC(sAND5{*X6EZWj`QMl#VOB1kYA zE#DoMhXkR~GGUo*NFW+59lOeb1fY>rm7g`@k48(5Cu~Lh&`8qKFbp}0MvLv{F(F6L zXwjt2TjcQHDE{zQ6yNn|e?k)P%uo@hi~{30G`L|!W(?r20lwTJ9M zBl009#0`zeXF?EHG$L=IBQ9t}-f={n(TM!+AL4{Y{-Vva`SZ)G6c(1`qL0mKZA$TzVgrj*F~ zstw0hWCV>$56t{RhS8{aW@H)}LZd4KJORj8G%6}Sl!FYSQK2{2O5_U~T?Vh~kO4F* z5Zow)^rKPUD|t2KGa6mGVqSrKLZgfR;(W+QG|JT=u0=ke(S?<=_mTH#bpG{}5b_R< zvah__i}azDk0ry zbSf<8HPVGfC)X}Nio8OjwAl=Kz94OA zlt{=eMqZ#%{No67q!o?gN?G%f=V%nWue=LsL8F-UK5a-dC9)!a;TkbPBk~7PI{{#hG^7p;C&4-K%>tl)t3-`H2TCPT#x9X(TAGZ z_sC{6dLR2M1=)l~?_AG{Bf4nR=X_2P(Ltl$i4U)ljcD|y*XkakjYhANleQoLje6X? zaO1{fM}x8tC`qvWCI$#>_~WxtVg5HCecprrfwcV+Mt8?q+7KBuB0Uu4LYAXZ?fG0MWEmRWnO)z3NTX4W zreYhi6pgB;3%4UuXmtDOuV2U#G^#B4Jr9xm8#!8zA&b%Irt$e{L;{U&i2B4Li_qwL zduI!>5RJ;~e`z2K{zi(=oe^;~Dq9z}9T7vLtL~{$h$tGBeC3};=A%(@Z<015f<{*& zM{gkW(5T2^{Xs++jS6L^N)RD5Di}*Sju6o(zcTt5BKY6^fAqh`Bfv-O2dJJwl4mvK zXOQIm|GWZIcC2TRCu)8Uw3fp!NSPS+Ou}c7Ix~D4Z{RaX>FDw-X=f`C8fC5Ytt=7@ z?~{D+67K&m4kCTXn{5Ja9rw&$?+yeJ_M!@BGO!=9SEm>7B7K4&iqfubBCG3uJN7e3 z3E_gA$-9yydi#yvrsN@w)4%h|&7z~C0^r;&X1@=b_|G6Oudz6LK0_PHPOc30_H zKLvSLM-JP)hrIRty^2q4vI4)>ozK30E)tx4GhR>udGDIb@|c`!0?UW2CPt+KfsVw} zPwOnPc|Thcmni~yZ=$qw*x)d)tsI;8Pi<{hdgT3tlE-hH{_RP97f^ME59ATs8x3^u zd3TJ>q%HXpK|1VHqG+o@!|N?Z>HKfaGgSm z!|7jXTssfXPd<>~^DSt=0H6293}utD!V{$4us+!g5q#bfKJ1~<6IU3XckUtD@_0Qn zlHJJp=l;L_RJ_R#Qc&Kk?e)x9yo+!41`ELr((Mu^-^sj%1fP174=1{e@2z*7wgd}o zxzYx`B7sh%$u4)u`;GoQrCt{Jd5fd=tIAme!LMyc+5J_qdF!v7|7%;nAoxvbSDDi5 zEPDyNddIa-4?TKJf4nzS@<_tzpSM)S`XX0;P!;{umw7urZ}-*A1$kFakV1GkrM>Pw z!rlKTV_qFx@PI}`#O;zH`}I98}hb4eADePdozewu6wxrToCB`Rd~I= z3;XPC?#lZ=uNx9UH>I7=yw$lam$1*?D*6d?8ZBKycXRI?N*-%*`uAR6CiS#5Ke&HZ z(E<7!Vx=j0T*c|%_X`2{TKV~a%J1OC^Oob+pd&YO#}?#G8ytFMi5-0w0q@arSf$XHg9msWAj~a`s2+-$wLpPe?O%wmXbX9 zz+>BOE8i`}=dDwS{5*RxoMdCDv4T?tpEqHbTE^zkYKG@ch@vfzO1~`@tRHrhA8#F^ z<_&kRQQny+Pjg}M&dPayIu`Oa+_mijnRmcDWuJBM4N|V~0$EW9E6~y>^6qtCB+xyd z7;XxAo2E=o5x+Nq+#!#Y#L56LofVvTasaz}bCxb!SbISb{G_y#UKbjv?TXFYRNQM1 z5=DQ!xhZ+su!43zij(n=02-W%V%9WQ{qcT0*$k~b%w^2xr- zhP+2v65t0{tN_Q#c%G4$ksx-e)=CKSUfAP!0RNA@e@6`OWZBxc>h%=alEX&kA%*^PJw<6bVvtyPpif^*_7ggO6aQ30#bl zl2}p}08;O;J#_ej%{$jE^^QZhAUH{BXL?a7livordUq@f*{keMf4p-jd359SPkcsW z&^VY6Y`wHC-d+`-ce6S zMroIH;Ly(73fRveFWo%e=RHAxHAs+>M=?(SHgQ$_uDZh$cBkaA8mE6MiE(nR ziu|Bjzaj(|E9VALS#n{E6YDw6MMulr(7g zDEmhTK5xC5p&sJbj||WI-r5nG^6(MfXnQK^&+RQosd$s$QbKuuP(Q+p#XB

I!4X zyTWKJotigae{yKLg%!9xHkG6Sd7pDLS#$;Ro_d+$xMidXd`zm@TJx#O*<*TcRV$~p-cBX`2xc(nKXTI>+mDWVM~fTi*{?PP1rI_V!0Tsa5zx zEMaQ9*sVvdxBpiIjPxJ-Y0Ja5CY8`h`ZI$(M#Y=_;xWqmLfkJAEZz>kR>Y=5-c|L@ z$H=^WZ|sVB0D0H4SF^fX?Et$e+BoMatmrtD*QeNLR8=whMc9GCc2PBj0JtV=jl~$!yr48Dt0*Z}OY; zC~q@~)_GXGYZ8yFyaIU-5PJH^yvM&Ri+c}wPnTCH{dl|ss5zT`JI53SS|%446hPif zj|rZ2>umzM>m7{-PX+>{lkX(+hx-j55{wLa z_P4V{0S@+?T``b%#QQWh-M%I;UYS{ER}lzgr*7TO{Fe*T{SJlrzF{T;8A>~ipP^X? zxv;Buzr*?nnGf{GJCKscC{F*FHz$mp>f-|w3W|jrtnsV&`n=rf&#-#?xIWvcf1id6 z(nb${(p#m%_!p#E_|ulh;w974|2(}7qT)@y>jdQ;NC*|e;@vvAXu&JUd%^P01!UeV z>gN|MfxKsZm}?dvg1l|m<=A2MCOU_>IYHie65otT@0&p9NfY;j^MXKo^yH=K4cL>D zSYDTJR@`v!jneMH%NJko>0t9d6S?AW?jZf~PN3wGi_^cCpJoJ~>+yj@?e;_kBYfVU z7Ii;d;t)ZS;Rwwv`cj8my$Mrg4$HKkGCuFKH)+aa^DmC}pi}>?{~2Og1=s& zRt@AEA^DVgkF98J0zx6r6EYtJ0M_jz>-%0|pFtX3n(uzuRuC{#+8G<2;Gg)HGe~{JC$k80QRq$ocO+*5pue)S+L*BBJ!uOuOXaYN8LeCkN2Y~H0v$5|U zWAi@!l3O>_Nf2zKwCg^~ndr0~dx69xPqf!Gr$63jDS2?=^lwG@Gu@&Oyr8%2(Fy5u z_`Dl0cs}-kyeBL7s+33J^Cpa{sJS+8V|d<#lQiaWG~m-AH}VJ4l31vClkek0d9Nu~ zSct`Y%AZ4dE#$p*q3b&`Z!aI|jvC0DPbBbQ%CI?Tk+J7_IT;B8l7DSAhPX8o+zwXH zx5(p!r?<}eZi<$Ly!Q@jSX*^AffW)fQr`#!f=c)3Y+nUz-rN^kqRZU{K?SAVE$J$g zl2~lsp=H@x8J6_No1c=+Bql1}#jtqmD@L4fgS=00)>o2w zpY&hBngMycI8~q2F0=q&v`S|m%|?QxB;&k=koOCwrw)QIn}Fnv(MhgXf#7Rz#`ZUp z*t`>;*19^p5Cj91cHK@qF0%8m*Z(q2pS4DA(;x3tN*-%)`e(qDQralS56TzkJzf`x z&pV!NZI)a`C~4)l%#*f*5AoOkYkzU5#J;NhmuW3y{ME-<+VVJeqIxBKy!GGxe+=-? z3Wr!Osv1PTGa9WyOkv{EST*SOd*pR`S&6p!>QhQXum-8!NVk%OGsvg=7j4~r$pnlE zU*3tp7o>C6@7XEA55NECVRB{UaT8F{c;LD!I2i1&efpW}k|*Z>JC@$}f^MA^{M&9* zpzCkqFm??(@oV(-@p$^HLAI1Ul5zT{Bm8MweWDQ9ts`aI-hy9)9x@#`*mE?D)c0}O z@}`0o%-?qM->aKw1a< zi9x`$;d*f3a_mR!x&xf53o`|Q38kItaLTCXGHl)l4C{-Q#n2yb14Jz)-%g1mz&T>=d9%m87&&cK1;NN{vviSGcMK@OPL zD1awT;H6L2gK_B~kl5B6Dyfdmd&{A((H*x0K?0@SZ|^PKI;z;b348@CUU~G#+l-P2 zCrRlQ9Wv-!IrZ?(wPyM`g}c>?KQ7eU@CXKboeL$?9t zmKK(YZ;@cKa>0d%khe>3PyniNShB%iCf+|WoR?YN0 z(fQcCV-}wo*?6A*coP!;$s-k~e}{+%Q{(_YC_c2(sP{HL?_{6*rF;CtNLTj`s87z; z<5us)?NJWHp(KVs-ZEAiNmCv<>pERSPLNM;C9zZSCVzJY<$d|xuEkiq`$KmZjX~ad z?`9rQ^M0E;vTb+JHlW@ktVtM)1QIvCr)EOlhLz){x-Ct>?6(!MZ8`wNp1-x-O#plS z?;cvbeyg=0h^DmjELa+oa0L7D78jdZ7_x=_c<-a+A%xSv1HtF5BNIZ*WlK0(R| zjk`7>B>U(B_7WR)I;yny81wNiLhCq(lV6rWd-lj3A^?xUtWsrs-W!U3G`?9yLbl|T z{G66+#9d;OgeT`v+PPSMK+;(DouN7=i*$}f$ItNQrQ=O~Hz197%=;=?EZ#S(2S1uX z-WINPzo@+D&b3XBguJzd`m35_w}LaL)0zvrNZ{Lsv4X>p_jSn|k@odu;JHMqa^*%p z&~762)5Hjyx9+%DsxCYr?L^}u!Toz@W3YLL*a=M^wPQZs`e+?zaPs?U5?om_Mg(=9 z+>M^g@Od8=pIq0sl7#HG`s9)9&cF@QcOF08JjBQHya@^IjMY&z@5=I-8>C}-=y+3K zc1h!1mm9tui?=d&`P4zk`&;h*L&K1_IOik3eUSH^NB8+11dIU%Su*?jOA;6!)KWBs zynCLBKlt822GPFTiU<4sfu`h>#?E=zhZFIi9@{AH5&+t0oX3mFdpG^D=YP-IssuAr z=Hs1&*5QkjpB5$1{7L~4{OTh--17&2K$=$QthlQYifr!QtVI%L;P#eQ)z6w4NvzMC zM}?s}cB{vyKD#l~z30*KroO$E#+$&meHj*S-KCRv0wC}8r90cHy!&{sSgwM+8xrPu zIbJXU?*_R{``?j3#(44^O~|{g#zKgri40l-&CU)b1%b`>f67IkxnM4;V`Ig4I35cC zeKgK_tJ%pE5$tYn&|5gw$%OCT`i|DI9Vb6kTc5Esk_6E85P4YeKb*bUx_bY7uKEP? zbENIz+sKvV1J=GQ&)eZUV|8RayBx2|pYz}OKMepg|AYgQ5M2+VzQ3B*gDRbQm9Tn{ z+M=Ik+1HD-OMgYne1tvdSpeD0Jb$gWl4><&?lwbkJw2c~x{n05I9i&T@lz1tyGvi@ zmyv-`;D?xk8@}LO#ojq0W!N`JE4^9!nYU2@P|&!7ZZ{n*P-!Q(_weRK$oqWB@@Oh==i>X8fsl9W7-_xlaYMjm zJu9;w?jTdUii}o4-lO?Xa*4OdKt8elOtP{c==WL`a2#MSnK>%9XX>*Bz$Y~BYo*cL zT^`uH<&#|oe3v zEn%YP8FrfGmsmoKF++6>xYxUf|J^|n>3C}&9~7nW-l~0B0gHFgGUJ>s$or=Ci*YLN zv988PWsrB@_CzVoTtjfOb8GSe>I2g2P5S0R-UDD~8CxY8T%%OmpJVp}?2|6T0{?P? zt|6Xfm2BRBm6@-`0fk4SuJ2o$&F-!^+f0_zNYFTH^S z($w$WXG^NdKo&{kI<(3cm~w@MO)6q{2D&ZSl(v zF&}Ruw2n%g{Dz(ghxB?8LC$D$*{}bBcWKR&S;^}gF+Ud?neQ)4*eE}~v3&P_=Eztb zZ#ob8QsQRje||dNTC2V*(0F_Gn#f`CR*+t^a5kL(DO{xuRNkk_wWT|#m$%%niT{=` z0^}p}3wN}U0Oxk%i(8QQA+_?+T{UE2D-n0aTFw_JW<$f|9jYjwsFW^_J>QX$NWtW`I%e5?JsN6w!9{R9?R0Jiv=ji(oy1gS{@nP zn=4qqvEL5_T-W?~vKf0o8v0oz-c(8iVQAd3b}sKLf3SCuJ>v!Xb90s;%=TfAqIC@7 zCd&{-ehO{Nt;qDU^EZ&?AVj`O$?-L)3{i(b?^TKu>g}ggs#Vgn(3;;RI zPCFg)?p?oX^Dj6cSuA@}b^9tANIX8|lN9U^4hC=B$bA(14pO1P7$8Edh4H)}i0*#mh$v|jgt z%6sFN@y7=s@2KxuUGgOcpxk^-9vi%RYm;{G`*X-U$LOcVw`*jOxLEbfO@Dt78=**i z?}5#Gm!fBC0py*G##y8)czn0S=6z{4kE1FR^4^2iQGk=5PLKKp?Lt8y)|U<5+{5S1 z!>;$o;x-AHWhU0VX)XTct#__^-^2K%siA5h-)=|Mj8b?=909qu^! zxdm)~$2CO+Z7XFDncl|dEple%^|D(egGh4jzVm%t~b@SBMVDWZY(U^1=^5$)KtfuGff6#6H*4>7{a9%wz6!IQT zy0|e6@>V{(aE1L1GI;q-+3HrB9}r);DDq1R_TKx?wy>|e01+%h@4XF4 zn{qa+Wj@~QW`FD0fs^0%TD?_blSJ@S+bA_NAD{P!)U@`si%H0zKfLTAvQ4M4y>_Lm^dXVW0<1lIuQXrBJa(%TYVD+GY zr8Wx+is3cLg)7Gf;1X-S)Jrx6?jRSc?Oo2{qX!nJ|1NvgN&?cwEuag||C{t~>|c11 z49HtNAG(M80U7^GBW;JVdr-jC^Vp+XiC`rfw@uGRyYmKi4>IA^KfBwA`Faout-}l_ zzq=-_3R`%Ipk2(Q@`mAT?f>)t72O}U2p;VjdwLo%3Dod^Zj9f9R-JQ+KBFPS@;gX^ z8)J2Fwcffonm#iiNzm~&$#|1aTVhL-n>S$b=GI*nQxADxNs+P}guIm=YcDttdFN{> zI)r@E0|fuM-*$G8K+@AEw{sxx<6^<)i!PDj(wZg8YwHKDO6ad^(8lIHT4q@MPL~LZ z(YVV}#=C9Ouz7Puh^G#1Vm{tK(K>i=^1BkTO=Hn+A_y%nOB36G&)el$cFOhc(@4m~ z{>q078*!Idg8ufD_1r3~&s&ATI#LZqE&g8K5~t&Be17deueZp2iKt`ozLdI4?Iq;R zY1qM8R=MIe##a z7r&u@5%z#Y8T+8J)rbf_p>cL8ceZxV#~zTrmURz5&}Tm06KEZiIQgZ9PUrpDKm?lM za$C6t@p)@@?`Y&b6oIT=>Ud!PIR5!R;bO`Ksqz-q=bgk@9nF8SA5)n z`FOLb{;fj+CqDz9wUOo`g5b-}HDPCd;}1y5CpYB}<%S{ZJ4qIA7H*z>vSs^;a(mgzl_33?OficFX^C4jFiVdAaTjyFaMg#r`$_J@)2gi~B-r zgWE*VjK&oyg;b^rV0Ui`jnU57Ys|;n6s==9PJX5r4IKH4h+y|_m)NlXh4*uj^RnL> zaW^Libe{>9OqjF${C`n_u{xH7~yK-ezN4BG`h)71_ss=S#$1VnY@!yjkzSd_Bk=ts@L4 zzkT^z8V0ijz}47|^&9i>caTQ&7TS2Jl8~G8qNh8?@q3VO^2Y9M2kKeA2aTO)td4!f z1NTNEX6AosI^Gs3g2go6;p{7BVe#f{ZkW)8ygh#J*L(|kS5=)}?f`k~83-14h;0I= zyB&D$QAl99wN~{O$XiqLs-L+?eAi}=-XNna-*34r9uV+ zx3~04rr%jYW_jKOM(fDG=ce>`{$E1J+kD^V-!$Im$-^92yx%xyB-udT$dSGRDsRoh z?{Bz6-ux9$NngHf0*Sx2v?~pgz_G}ccUD2(+GXiYY3Ip+f5OxI>O4QdckK`N@Jnpo z1B2h=vdoD<2#sqHmI!fh#peCF;9TG0oy^DkGg`+8PJZc~D<$q1!W+Wl?dh5BEk(zB`!-Qo8gKrE zt?XF5xpL!XpMbm-hpR-WhZA>sHBN>=-VMhN>NS7V0fI;R$M3+ew>TQE$Pj|Oe|PDG z&PySK0>%2RyXO0WHMRR5&v}c@dt;kSO1T*ksG@Nq`Ko=J+_8BN$CmMY+s=HvbLj30KwK_`I#t=1z)AlaK`Vn0`I}`?%dZ zcuLFevq35AZ%!UCR!8V7^~d{D|C|4rcj%|f49@>6=z7qen!|T!J&4`bmd(hABlj&!?n6C$ILF>TFueggn z=Gb01|9`yySnwTw4|<{|cCV-96mo7?*sCEA{5wbqjytklj=y649%RZ`9nX*)8TO|$ z@Bfpf<876x$wlKmM@@bn7H^WVaNRw~d-ZZ*;Wv=C*^aemlpybgg3}L1x334fEuwRN zE(iw)UzYMULf&%}e@GTZ!55^FIyni|@D{t(yuxmQ*h{SE#N}z1!$cr~#@VOIe5h&1 z=I!w0M{vCd^YQjY>o|aupL~d9dWa$s+zB^_#?LEgT|SRK|$s)0^~^V9><<#fDvTkQ6w@jfxw&yB@f@BI+}E6BTe@HC0a z`@KW=@OsEQ@@Dz1eHrTTd;ifp8~MY5V6>M{5#;@8;_ReS3>io->$nz1@&jGXX3OQa zV)M4&)ZXf0PXy1wKHiRK9X2@msmQJ757id{JA|t>?zZCd zwza=qwi@yt4HjKRdDe`(gCrcvx~Y-8o8@^E4l`DVStH?-@P(QAe;FO`U9#)#XuN|j zmvLe7?r05r{vGnZE!O#!%6p4g!o^LH_esNtOVV~~03&}>yW`y9;G3?>uVl!(X3?&- ziLqob+$8@=E7%WQ$hZ|bWq{55r_MP?WFHY+MB~_x?D?cujLlmtL9X)}6Y}QJ{aeRk zoc!XghmYur62ZXSo}gv5_`Dq=+us|+1tWSts@*Ry#^0Q*)+JoKv8;*ZdE4tTR!5%m z$rFR8XU_kZ((&H;^GYj?_rcDHIas_!Y93tVhx5NTLCk@A_GZv~=Cvv0Z5Ew69ef^u z?v0eZDgxY`oB-RyAa66@lb|o{qO&NXE?LEvR2_*_%Zaz~Ze`a8q6z^4@5xJwW9x6KntB6s9c1&k0BlRtOD89>-1= z8Qfvu1gXI_Dme822j~CI4Ay}-u}l9wL6W26ZEG;{l-9ksh`!*%;;oEy6zqY#FWXpK zzJ|QP=9^1zK;9)|1};^n6~Hr~=GLhm4!V6EwuwRB!v%-`EQ}z7 zMDcm=ndDR44zG+8cq~p2y}|F^1aJAD1}(c-zIzi+Fj&X(uB^M4s#ms z(IX}Ev3L`@gDKvS_g9UK`&8b_ws&2QL*DjrRUOXLN}xsYkW-*yICwjFos$dl7Th8! zWgSTdg$u$THfq7kTVWOBePh_XFaKG*eG}yU6pecxZeike7Q1^Rze;nb{g{vURkRMg z{Jy80Z5Q1v01B)6eZqL~d3PiS78v9OBa@qZM^>=o^Io&mqP$AJoaK2pE@P~Y%(olv z9gUjdy^@Z%^>EBW8t;SFe!N(`t#d6G#6sTpmiVbr&))WxR?J!sdGlAlzg(QV7OeLT za2t~f2P>9%uAQbHPAroDx%4y{BIZ7}x(MXT$y#O7ho|1EZ2>Ea&n%ZX^*fc3M% zrt{dmM>(RBJeZL8W3&#u{EqF^r}!oafc@1b+V9!$c^{VLAMwo(Mjkqax9eYL;O4}p zDh2ml#wp_RE9Z;q9AkW8Y3$c1o+wmBy z%)%n=-;=vHyo5bS#G_%h5}f}DoR;4rwIsmlxgp(Q$>E^bkt2d2L_vbwzrWphk_>!( zU*C4x>j$iZG@NFQV=u95tX6oPj3k0xXxyrorMjJ&*gZ({S>&BX8O*oDu1D)wf|H*b z?+VBB!TdlxMRZao48I4(Y<=*3`eZob7JWyt_BZ|#OYqdb8tc@}@;xZno3T3L-wV4M zkY<+HHFUfW1|||{yhn|=MX-2(+y82LHRP>QAy!D`T^*@URDitg_01#|)=Glsy5a8H zXTm{g|Cfi);SN&a*4OO2zGUEFFuJaGjURXg)^zB$V)H)Q>SoviFK<0Z<36;qIl4q* z^S-GSveGk|`FNi|>nO*`Pv-O-6LK9th#89ioalqkn}fqi>wFpssZzTzo}rGqQEWd+fb78EGCzfm1i(Q%FtwhKBfd0PoG~V;Fo(N;{&Ydh2?1sEAPaa?V3i1wI zk+6LwmG_rf{c-hDpq3(?`^YyO>^^+2svPoWcMvfZ4j_a58X0S*Mf|{re4gC-<=DLW zz1nBr3Lt_(G;VF{@9F>_Y~IDE+*@|UGaqkZw2l&-{5Fb71ai$509IFAo+-NG^Y)Bi zSC$HS*Ra3Y+5dxq9c07Tnz&khmgh})$Y32)(Fc_OUfxEZ&O` zZe2MFdB0hm5Kra3AeZmpQpmf*rjBdD3TaTEq0qNIf0o7(0nQASKL_HQ)<`cWST@>pVAwny zIDF5I@r1lhKgmy=4uPAK*9s|NJ$^uL9SGhOiOsv~*p&^BgW$8b&^Sd-DMN_??CyQn zjVN`833>ORb=2VGcUC@CC;65DxcEusSNZ>N_NEtbc08a0|LH9;UeihnZ0lK`clZg$ z>iAlB>Uhj}(tqp|Vps}^JRAT^)zo`rCUwbwX4^&Ivf z&ZPO2@;o^I2TGN+=CFZQhZC#gYQn*+y>Hp-;r!qF`Dswa5i-yRLq~Xo`~myxfOlq> zv3t-7zSxvq$?$pjy?^6W@}#vsa~;CGQ&OnyEMIpi^DVJ~XdS{h`LUN3M~bZ%09W`& zoetc^Ut+J0?>L?MnS@B$+3n^H#J@qh)ILA2&9su`d(hND#_G6e@MG|<%{l7%zbYN? zBe!*h{|x4HJmo3FTl?$d?aH7mn`cVatR z7UUhVC*@g}D;Z23-5?dH;s-|R>IlWRu?M8~A&+79EFu^}<4Sg{IUJaPy~Or^@SlEP z&3wGO(K-fj^3%9|G~V?DKTrwhDjvAQIPcEW+a#_lHDms@r*$_~)9&_e@!KrV+tPxu zI?A4A+fR|Asl3(piCfq^lj0qlvyq(#f#C-H11H=1Kz5b)VVCTp(KNDYU-ZvK<{FV_#1ZHU5 zi>B;FXB@G4n|XU*|Cz&lysOYUEO7FZI?-)fR>Kb#_&A;6F30D+BdK_!DeT@}wYEZm z$qdZ@(kol#?fY2%>Mda-gLOPK;a&Q7{#T*n?ZmATP2;VanIekCduz_tW6qFwa!b}{hFSI@v^3Dv^IWQh83`7lc#qM2$H%N1xYS{{TZ&@yAVDAMVkpA4H!~B9DP>k}U zh$v!jPU1f{>^L1w1gp@v9ht(P7dK$@ZXyh}M=&Ap6ts>9IQgk~@vpxG4=3(zujX-2 z!{_b$X`ubR4SYEGhA}ro@Vs@S+$osI}#%3yS5u5i;%5eVIcAhe;P7(vrHoC*}u7rcHY7bRcK;A8{ zegjnyUsK+mV@l6r|Ji{N4a-GN>?g*wI1s1N;6I7%GHd z?;x}62h#1+iNFqx%k|Ri*%*S|gPImZEp$ehuLtF#bu{DT=l^G7MPM2q5b}Qdb<-j) zZ9Fs0T^EOCeNQ7F(tqa0$uY2ltlcbAdv`v|_aH(agLU||Oi29QL2jhu?RngEJB>Hb zdV&lV@41SPO^P6Icu=bH4D#M_jPtrEHS-bt)l&a$lA%2pPblBtbQ1~j>tv$fHX9Yj2yh>dJmiT_ME)Jt~<=f+Ze6G z0w=#$7qW@`Jbd7quglT=Df}gN?bQ`(18!%K@*ZG>+TD zEb7m{e1p^~Xvc#zCcM05h}L0^lV5bI-qDk1_&|qYzr@fGK5usunI`v+vxrh@=VSFW z26)ddnNzIJ!TJNzT*m4k8Xh5Us+t*))aiJ;FJ{xB@pcF=kiy~}`it+hPjl-j+Mkv`HvGB_t$pzP!12Xv42>u0~m z=I!e6_NFl0oB%Yg;m;AD2SwQ3Teya^kb?<%d!uzMz{yXr^Z;3S4nNq;UER3)Ek1AM zg_&`-jc1XtZ+$Pt7vl2{POlGJd!6;4-a@#-SRJ)7`PuhF1Hz$YZ^+{g5Lo4l{|W2Hwp60tnIEyV!;{GTxP-pxZsmG!Y>plOt2eE z`S1CEcq1Hh{Chb6Z=&l#Cr>#U(|V9lA8{2{4~k4{{x%2ppc9*?0=r-jQazdZ<7O^A zLE`XGAB0QYaMviu9nEmC-RoNN^#v5fab#RL&X^27ckR|%cE}%;IQ$WctH$m@<=lzA zv2z4LF&a0W^C+5q7j_Ra{^TZkS56vXjt}+!&EghXhY3!8A%|5qk{tN~5|ip4yAyx@ z*EhOcVysO?y?quWi99=+*llha4%8#0r$Qm`w#8x( zw{0VXE!p~OeKz<5>E+w@*Ct@|4oI($xy&U9q|i9ddKtr)TG+fx7r7>DGa+xdbDOE7 z3@5+0mp0ccEAxTXgX*MlV|?BRMPB&lQiCa8*a&B@!mT}JOn`AzHYw{cSGLEzTYLEL*Dj^y{VmzqKN(8 z^?bei!ofS&sSj3=_sLM1+OONmU~$peRiaA%VE5)*Y35Pbyh~oI_=(ID1eR!=q4hF7 zA$4rtzV9-A@X0e@_bx^2@W;uoHf>Ecu;m9@yVrP?0({;r8G^sWjlvNjw(K=s6ZpJa zoYzKPte9eX-tTrWR>vP+ZP|CeGu>N@j`uOCj+->z3Yq@Pv3P$|F_pK5yc;YOUs8Fy z>*de-4tdwgr&9VB3L`Njb(xJm;XwIUowGdTZS6OCvvmghQ~@_c~e-fmA^htJ#i zxKH^(lW>IJJzV=nK@)!W-sT$9{v-PK|GRBs(ceNCtHYvxSZ5-6rh9AB@%HMdpF`sv z?`^RRi?>IO#+&1iciASDZPc?j8t=^PyshsXg^~SN!oI0P-jhOAhrh$iTfcHhDmuH# zfaBW|KP>}4KokuWR4v24yyf?Dk=OieBH%;gmV_lqzrKWhd27<`(UAOo<~y7SMCWfOqjYeGFY+B>VQs3EFzI)Hv%UB(^ zlRvDRzWU$u|5&1l!TDdGt_KB1+uWx0AYzY@5>^k|fy|onD}d+!gphSlU=JdX2uy#3 zODy4gdm8UIIb_Fe9V_cm5-|PxHrY%Bo*;dY+*VUd}h-NaaleYyT>l z;jKr<+kd6^X&P_23)d8|ct^RK9xsEuLp%Jl)zMhK za4@#v6`K&`t@|O`L0g{;rWbWNaZdz*B`0++Ih#0R?tFImN<0LHfsmb-tu*JK;C1Ti0PS{;=*`CYbp;g@__0>tcTx*qdC98N44 z=*wMd`55zaq-~HLIr=4Ht5R8hb29Pg4MTMd@Pb7#OIZFq>fywWnC(0AAa8zUz7a7O8KkAhNX2(`ILH^cVb}vNZ#joO`Q2(r z1{xEZO0Vt*fFEbthsT#;ckkKe+c_K;2!cs8E)4O}*|`9_dmEha{2H^7`FL}obr|C0 zht$6uPuM2}rm_cl{+F}2g6k6MooCx|dAF4+ev{x&V0qq$t}|ALbS!&iJd*L>_y1}A zjhTPK9<-IN2Ze>?AEWgkOZnNVSUo7ZMfb_)t8j@O|M8{+_8^z0!X)bb|CyKj4rNi+ zAktMpYiAn?T>LucE#E>4q9&qnQdn)Yol5`E5ckG;?4`Oo6$J-LE124aA89lEr zNC|;~Y4!fA_4vGh{M6FcD?f!;?m}jtID>zCOHX@z(hCc02hgA!=bq28y~! z;J)n5iQABOK0n#{(MB>@*qIw-y2KyMFJCbGi!pZhKJuGmf!A9>Kt$ul2($W+Xkhbx zV?U-4#KU~NozOb)^2@y>_q5JP5R`gf<_Y>Ac%RBHi1Bm5@7|i8$2*^lvi=RyFWnid zBVzrd_^p4x-eN$?=9H8`*`ozD^R4FZgawp)`6FwNucMNc6b<5dT`9Zt{T649~(OP+`sG;k`-Q3 zbgF}ax3@g{y?ztl71lrhA7`+Ri606p{(d=e3mxyEs-B%R-k~I|HCViTU-Q1TgS-Rx zYSdDB|9Lm3ViL~(1mi;EyGsf39)l!crN5%f3-bPzX6V0On+z7EyX+*S`h(GT z;S0_^!RCE!^$p3;96>OS#)XH3|Gst-n|I0ZqIOan^YJb~>%hxzv^j83;(9^gDEQ&k zo_u`Xwkx$ZPpO0;4y*F!n$NqBxyk!y7V&Gl@z{DT>+ikO8LMM;TUY9b^#9KP|M~yV z%)h|--;AyYopCLFLG3|`@C9joKlc)_dXQFrl8gyi}-?S8!n^g53zfSr?pzvfnGsy z7mXWxIk-pG{UGMwwddtQOV$Z9-wyI9TE|nI{8r{7&$38FVD)HB2}p8lv(0<11C|!`V>;Sw63G&`X$NTg~k51YWo3Q`> z1}xsw4HZ(pkoUJb`yW)^&nJcA7C_$iL(2~*u9ioJ%$Hip_mO~-gd$% zB?C$DAZb^sFSsJAVz}TcHt*ivcNw)W1VJtuw3jZ~XB8)3GURRLE9un^c~@HLp6P@GQr`zZ1=nds#Jj1* zX6))> zgw1D$I6M|QC9HFR4#npIXQ>U=c&dcM?M*^x>$`r{|7gF zFRw_JW_jMhY{wX?BQN}tQRCk)NSn~{4u6*P&&`RSjykDf@$OYA{&^GfRtp^;rt;?G z+w&;^@*bJ^(O)XL2HAIe&)4Y=5^y)YQ0E4DUpoGXUq%UjLE3MftwxkDP{?ChtO+5pp3?;>3D58Xok&ufBtxhDnIjeZ(1D=IQgw#)o;}zA_%mSzOT7Dg+Cyr zDw;U#{uYh6foQKoy7&(#T5|TX&!BBE%kw_=n6Wy3&RZkA_wUPzjOlojiZ&Bz-TU4C z4ePOZuX*D&+5vg1@V$1Vp1rjP?HH#XPH2BfeQV;Uj6~@83-Pp&K%w(0S$)V`{82Zh zL75E3MRs(&I^qWwtu9X#2tJItXRK0TYicwQ0*leO>8a|oif^%bUkamallNji-n2T> zaq{~n@IAn_Ob{$ke^-5c44-#d|HYpPqtQt09*tuQW$s~qj{oevjUU-0hPtx;-rJVJ zI-HGL*1*eKyzm2<#g;?hT{2f^&VJ4?`0IcFFxw{p2c(^JJt)q8dgePw)cOBa>dx6% zJ!p1Vk$7u3#dMjtH%0z8-W2 zt-~HCKUwXknQq=haB$&|g*R>ScaRIF{btYGl7;jZWI8_`!(U>5%La>?=55J zCnC*XN$zTpcfi2Iq)(z0#4^n*j&lwfJRnA;*>Cg%yojTU|o{3kBc zZoIqoCiW6*Kkd8f+H&UOO{>EeC%@TOID-2&!3V-0l{5@A#pm6XWB$tGbvhEQu_gG( z00TEjU$6VjHnD@{caVe|jMZW85@*#p9ZKbGLB~6WkX18}E9kawWatPTp~ooQ6;e9%=CG2!U<)q}i;gb1oukaw_Q{uUR0GH@}k|H8J!4`i+M zlH!%Z=KT;+bE_H<1Xs|w9trcQq#SJC9pQd=ES4}IZ(1E>ocv_D66-6)1i|x`8%`s#oQ`+Y{V;PH zZzb`&>{z@HnFarlhP+$m@!5<>DtvhQ6Rexk{w=U(WLv77DMJej^BOp>Z{?3p6#Av3Z{ok`6jA&V0OS zbp+$&cjoljm|1&>fVjin=EDELyN2zPuG7Ot+yUuiNdC4re&sCBTQiKYI=W_kR@Vrd zIh@!|$NOwCXD*Gmb#^iv7Vr5rqz?e{-mTfmNj;oMf9VzN4S7q|oax~SlSO`2T;9G9 z^4_!Nk7^R+o$`EE>oN)I<1O_Iw%Ygt(L`sv5BAu5@A7hqZe@7)mKYj$WuL$3Sq*I7 zTT&cOmWweT?+Ubz%{ckZ8W-5IqKpVK-US{M+koG_!!#Bv9GRbtqzo-vX=Bg8-g`%~ zh#xnR_4nS+4A#-3_DGaab?Wy=RXC(E;KITTT~kIFAqr1 z>lGh3yqWoUx1)7r&8ez;68=AAH_%$wvaK+VYVtx2GhMM)A-83HO92 zs|`n3o;RV2u{stz=G+y#GqZ!-O~*TNIz^twTaD)(Hx}<-9GMcwA@2soA2n3oMsJP# zim1F#7G97D>#Ye=k&;{VjRXRtBT6eID9Ef`cRu+(YXeU<+a0>i;|FvmPZFv>WA7k2 zTP|+x{w@f%pmF_6s~3-?VR!Fg5%C4NTFl3r9j)UdPJXA!kIEF{h~R>X%S+&l&)c!= zw?ME^E>d@FT<)?O{^hO3TR(_7A3w7S?({e=fYdMX2zyi?{tylfLWLF#8Azv^40L4~tWfq`m1S z1%qv%c&9|E=?7oX+j4zx9T}T9|DHUj-xGqMAB`&t)8U9Xjm^6%Wx!iVllgehN9(wS zlV4~%*Zgyx0$|zR6Tb}|@p&KUDp{YzpNlBh%LfRv-N&8(gFV+;3G?h{dEUVX8LMM+ zLhg6tzmK=Dq~jf*A-|W#JN4$NIas`ps7B1b4tZ~6Z@Eh4Z6qOM8A&~y&{y`EyfIR< ztl-08DLDVT`ZgVthP>B@F0pDIYXgE^nd@TT`-1L6LHcb^uzBx^^w&BIHzzO9IM>7i z*&qMH+d=ku#k2RV#_$_KWj#Tn^&%w))K`{m38-;Yokr-Lc$q^XCoIzH|el5~f>|2zNxzejGS`cpXn+tKx)i!R_Ptp}Bz+e*ah zLA=C0TG#T5v^%y9hu?=iX#D5^SfMfwIJQnv5GsY4Rs;G(r|!>=AWaL3|mxa>ZEUfl-$_b2+=%z$J|$2(2>T?LIdC%1qA7Vog>X0K+*J6T+1n#%jc?BYfu+T2bZ>ca`N>a##|co<_hlHEejuS zfyQ-Q+H;d_88&bGoJF6sLYa@ZHd==rPJW5*BbVMg3j)HrJlmgX_`DaNFaMaZrWgro zthkspiO)Oxz^VBb5l2{l2l-Nhu{xGWE59-gn;DR7=y<0N=VsG*-(UBF4~w^=X#1H# z$a_iAUe9L8drBjoPn$ zM*P5!KEcR@>)5<09jdBs5<=h?8u!q%l;SoIn|ILg%3`x)%*T5Ot-~KDznA;j#0Bz+ zz;$WQd7D&x-cs-0o(NPdMr51|zg-i;zq}Q^WkAvUyeG@^CJ-5`gJSvqkzdM8_ufm# zJEfvv5skMEU%`AV-bW?*!`b10bl{EKJ1TE-_7Uy5)XQ6+=bD}K{#v8^Xx^%wbHc%q z;i9(4B@{$`bBvN>N*n0mF0T%F;RkZqZ;d>-jLmzo)Fs{#At7)Ljq|CnC>dtQ=55g^ z!1vpc`FM+=b(rDgSJ~$J{^d6!_-3oL`^Y(b-V(K0gYxUIAqSc}tZon7$6N(z8{wLH z9q!B5x3fHNsjzm2>UjE`==$d`Z)-Z<$qC%bG~QW!e!N(`H^23Wl7zgc%>P(Z&)$L} z`!hJGyjQQi9+LG&YkX^>oy;#1IGdwl86ibM>}<69c3o`)Iy_tFUwP&S-u-sAWXs3q zJ*?7m%9B?J45M)-Ck(;}v#@y!U+s;0WW#*CKcaOIaq^1{X6s$OSr8oJ_%b;WgU?(1 z_T>|ns@ISOQQh;RndvAXR>-ZFzmFE24{r|M~#?(LI{C|M12W4#_ zuA}v!u4hUMv3gLgWQDm1+(B+&WOItzfCWlXD(-0Jz!IN`CE*J^%ZdNrW$WEd*|%aly)i8V4?8_n=vt z=f8c~xfEfx&)N&EV-8M!#u-sxW21=RZZr2L>1O;MB%Ank`HpQjkW~qRfsSwRcaQ`D z?g5@#Z&<$v&1bBRZ26aG?V@LPko)O)UzS^OkH)*+evt?kZ_TcC-&G**1Mf8psk~?L zDj(E>yo1AHwl45qf{3-b?RlOW4z6?da$H)fSc@p6!_pmTU0m|4g~ED(+@Wmft~sl4Y!p*}u2$8IPZt{~hRfUwSnmNaMYq zyImNI_wr!1Ds#wNSXFds6Xabb8mz2H<$W#aknI;SMAK#uDQkZ?$mnO|^jbkdnx#I? zdngUB-kL=P$~5}}{(X_kZ}qWxw_4BER(mW2M9{c2b{q9aXR&$n2_}q)YBC@1CbSNI zocsznofiK|A_Ak^${$p#@p;SK^}J*Oc^8~F%=kUpggYP+rYK9F=~%El@8DmI)v>64 zphEfY>n--t@y@vR{0NQrnUZuNEZ()Xl_xwPZ|-jf7pc7KwDma_Lf-b}Cnj$y3nCAR zv)TKk;p;8Uuecb=!ne0x-mTWG+6HF1*lyHn_XmIC>u!WwVe^*f4!N1%E(B&L{EhoQ zYDqqL4x9Jo@{exqD$K`Q7Of)_C%^cv*FUG<5W#_C{SgHv_`I#G?N(XqmLM4(%h}3= z@p*@f$XC=|+sg8r6XRAnhUyUOjkA|NKeIWpr{kR-dM|{=d)&!O5R12x1m9FNyy|2rQz|2xt3 zpnUMEiPnRH=gBR`>OnthvIc^3i?om16?fl*J!qFrjl7?lY3?NzQpfAJHPk5m{VPbd^AX+eD7vp z{+|vbT#}Dv{T}pt;?Mt)b55(q32?FefYi#)SRIGttK?V3&CLIY>3HWnmtRlo z-i5Cph+*-5nx36`2l5^;Ue-+IZFNxfnGWP#TP~un>L!cWW_eeN2SosJsr!`kiWEft z#1k{#+pXZzefdS+4Sv9<)P`fJAU1Ey!Iy-1dm#{n#(mR&x=`XiHgD7Oys}>@%*T5> zT89}8JqI3Mx8#w<<39D}q zw_AY_&O{2>m_z_jF-OBdfr2#VJgo00w}P&&FE@`Pen4%~Wjsy{oA;9YmdiXGg@7g+ zcY<_;t*I58_XAI^wE;}ny~WTv9^&NpCuVg&n-UQ$A>(CkA2kCfU@e!R*<8ATLc@Y+GFm^2H2jqR@ zm0%5(xA7PD6FVU9%)=q3lg`VLG0C7q;goQY$Zoq^P@aN>X-A~a9cYD{716>25&j_5 z(XH`u(R_7w8~6t#GuCW}N&Ur)BZaY9oTz zI=i}7J;LYxQebaE^5#Ew-`Js z^knDGj0A>{gVdVUD9G(FJLg**tsrHVj`Us~KTw^|f8&EHc2BWzVxRr}t{}LB#@$dR z<_SwN= z8F8T1q z?+?*kOR#wNnbnIdgS_wm;&iKny!YfO#9xKH35Lex$BI*0nj+qV9gdM8y1%Zpc^w6* zJ9`vaq23DWZ|u(abJGv(Dix2dtHb8K_rpV{P4ES2d(b$cKqc|3&e*&s3)iG`pJG1V z)@U75IQi|;wc$~QkGHHm@oRm+TYTONGlmwPbuLGgg=Iq8yYZj@S3CDtr(Yt4O$TZ3JCA0ye0jb^8w@?ygyh- zc>nL37h5l!u+@(Q!j>vGG*l?ax$^-+$vaxXk7gU|=6qiuKluLB><(%9cyv&dp7u4scxqL;6+roWeqUSJFDl|>T4s7 zn4b%6FWkqwal_k=5SHhyHHWb}1P^qVG+daO|DEZ0Uv-}=N8=sgWhaTndv9fZ)IP|2 z`Cywh_3Z8IYVU$F>hu3(?H-fgiXd?g8WA-Tk)W(vU#Cf#f=FGK=<;%F1%W$D)>dTu zf~reX=(xIe^SPMgBsX_OovV_iiAt-irni?d$(x;KXF+p zw&#(+dizB48*K{G)BYkS#PcE8cY6t!Mvg!5=OPZwUwjyIX>chX4!E2s1Om~xE4AEm z+h1b$EVjAQ96J-3?;4~tS_eB$e)G;BEArA70J)Bd0aZWnd(gwK%J%mXl}O_(!u(JE zO_-nKKlnCI4(obHvi$rXtj<^+*8Kt;Tvuk6*rRm3OGnzz(|9Wei30g-GPJZ!cQ=jiXEdbbW zm`yC4!sp#9F6WZ9`8G0C`_up0Vf-CrzM}j+a?Tf)=UphrSREN^FEh%LXLx(k@xF22 z_$-b03Afv_SiGzACH-R|Z@sM8)d=Lhf^%^N1@cZ&to`g{wgy;oW>Jn+L;@~xeya>k z3i3j0{hFtR4?(4;=FhXI`~mkx?{j)G*u0us0>sDMQG~S&a2FtK`cdz!n`VjIih@LA< zfA+>7aVezpr4;Br+p6#r@?L6x`-Q^>3UZVZah>=5Lr_>VSJGb1A6VvSNjY<4^A5HP z%@^7z1a_lwMk4{PG5_*%B3{?Sn;Q6-k9QDS2R}}Jy&B^JztROjz1J<{LI%2b;q>mx zF?jZtVENJE;v#(BIx35L_te#~Jn!2IjMec>Q`gz^;(yQo`)BrI=3n3vdy=jPRY^N! z(R$G6doCrc9(3-KqQ;%O%d4i7jZAxV%jklZk8$~SMgO8gIzks|)4mAW&dH+~;{*@lQL0ama zZ?BG*5jYt5%0zfH64=|GnZC7!f;jpsj9mWO0yL_cJojY!frUO>BTf3SxeC3Xey03U z5Qw62DcNE2m2BAY<6;SSWyF||HxaF40w+JA?(^yH1N>mF=nC`FulT$_0%YVmQiXh) z$9XOIeIxGWEy`g}TaSnAEPsi87K3%%)1pXUJ3X_5JWj{^R%QMV8t+}Z3KXz-|Fq=3 zHVJu?l%9N{@-8u&zvCX{ZST3|ct)53=nd{NNQAr#efAZ7-wfX%ojP~Ra-oNyV`!x4 zB*_n)Tk>K-bq_XI_cNg-6=Q-R8I8L?pHlgi6Fa`C)MIbH2=noFMeDeali!!i-sG57 z0^q>xhL(Bb_`JVWEvYbuyuD>+{ahZ&K=)=Z85v^|90bfHcRY!u~Ggecp_H_z*lGttI?8`E$EI_|dxOFvnOV7+bcb zN?nhFOcWE}uTgmjaxUd6d_3j{MDH#yYJP*wm232u)C583pSTaZ;{)n=vEv_%eLb{& z5%ck$jn>hElV2V|PF{AH9}Jx>U$KILn-kNUoQ6FKRfzoj@*-`+M%?aQ_44}DUB1Uy zzI%Uv##kL6s9FnXKz|B!s2u&$kh?qb(Q81!B-L8?j&u0KuO^zl^0^~y*+Q0 zUEOe22#lg}Hy<9o=y?U3xB8d)dNJpikGDHo$3~p|exzUC?-M8hcFOS!l`+73dU7l0 z^q)$^vdUeCJC=c~w@ar3N>)wXX67-Fq1>bytV8h^=i>j){~7v7|343c^M3$c52{_{ zkxT1AJsI;&Jmg*n^aht^U%Ny;j?0yQkE8#25@kOnX=MMgpmp zS(S4vD2Rnv!%d~dEkJtzhR#dfen4zYWA)h>?4A;PC17CW61>qGjZ5uw?g^{Fz6a@d zuX^1=S?23OXVE(F@^c-iO=|Dq2PTg{#Xf7q-$All9N!my06}=Kzg^am#=s6TjXT-C z{}jt#gCtyFu#O8SH>mvGLHg72uAx{hr15s=d!>TK`(xs)CpwUKx{K@fD#$x_U*m=4 zIq>n8p*fd49vg$RD^F46`Xhn*X1Q7Ow^NYclHlHxJ)^2vwl-WOHhB@0 zARv-NM2SjJDL`^oGKh)<0Z~v9PC20@u46=_=oc!8CxJw#R37}x`rp#F?K9JTFIWt(uej65C z{;GUnjEd_m+@eZU?(!`986+K*K9aB1XG~Q7nL(bQz`L=&G6ThXd3crz7T(Ku9+YxL z@E%=m4U_QRsqlMQD1x_oiUxz!Z!;iSlIJ6g%ph4jkIO8zB*GhtD?$RjJHanMqak0# zAY^Aquxx?@8*gs=Yue5Yd|*2{&WO&#acmA7?-ma3v&}1M4{vs|k5-)gILjk)ba(TB zu(gr(<3sq>dxz4s2f{*)@VD&nt7fYBpSPSEks2HtI<@HW_My_p`qbCfJ%3+sJx+o5 zt$_Rm6mNPXZ)GgJ_a9C=7mDD$uwb|DCW3cIj<3=;1n=$g4m+()%t67~k5k#B(Lf=z zcDJ%Q5f0UpT)yHAf;Ypx-N$)?z@8^R&Rav+cu#%eXJR?Y|Er!M=SCg#6vD>aoO4p~!D`yWTb%5}5+^^Uo$WnWh6!Nex_YSJ7(U*2>VoA~ zRNRDD+1ShLNaN#uq0c6B{e_@KKlcuLMxBqrgJbFkk-NA4egE%&y}QRxAj&zBo}vcb zV~ge_4Y3NmQ65je+R$OupxLAsF~_j-pr z`%Y=>8pOIZuQE7?_G*wW*#};JCG<8Cx7~RFaJ4?0RDfTDvew)kJkfgx_A{!g9X`>C zJH#q$ol&dLVq5e>Y%!HSD&(0B9fC*~q$Mt)z`N!B#6L4ggU3%bvG6uXhf_-tyuYyt zYBV5tKh7GFY(VgS`LW3J;3*SOlc0FH{8KdWP(3SX*bUO1XoUdJT-w8XIoStZe)PFIeoaXKFZ8zY z$KL+}Z>3YEErBkrxOk5`)~&E!H@E1ASQ97ee56jC*w`3Cnn5PgQQ+MS0~54C$`>rx zz`|QCq2Nacg0~gB?-df>YZQ3Xs}Q_{2IUPD8cf0Vg~=!E@1j8?-`CC!jzrk=`^=1c zK?hhp6xFeCAP6YNysgN5gpK!!eU_UZj3aoH<95ls*HFVsF$D58?AFGylZ2r4? z8%lw9lRu{vig(Q>S9L7BE5d%-jv#oico;$;ZBBd+lg=+f@V=tP5%*2U9Gr0dqQLVa z8hoxlSte;ugx9UYLruf_*rPfnmj&|%NS4_L@?9Krkz>-4ez z9A5jxcubbj9^Oo3A9(rAzrO^1zDxk8z0TgxxQ37S=+NHP@@jYB%&X9)6NC5-QrJMh z0OM`?MUQt_A9X%nho4&Ced|yEA3}lm-Hp?pDBgYL3Tjw*n+y#oUFD)SZ_&Xl7b1MOfUN20c6{sdqQ?_V}@6}zTXZVi2S@f$CI$Z;LqaU++1xM4N|3QZN3^)$E! zSw;4-4ktgg$qTPj-3Z{?K%|1}Ui=!g@N&}5K%yBA(k=N}-cH2~a!5v}VIgMG*C4vL zRQk}~6}Rfo3^I|K0`JbYG)EL~?=Rv^n0W87^W#TmkW()t*VQ9)M_Wu)^DDdtm82o4T_Wb@S1}wZ|)?`=yzPRt-XNK)EeIkVRcz)Gor)H>c6(EH@XIXZVD%&=B4FsrK_u*_9e z3+n^{bt%U>ixt>-Z#jHy3yUBh*hG$dbS{g}Zxc4&!wyjl@-&FI9@)nSocuzbpXEQX zod8Ou$^^cJ;p43=<`=9k+5{`Hy&^ix;^Q5ZTNay73|{nj*IuU12Xp=&jpW!r%Ug^T zc(R<#1v!D}wjjvf^i{vWCFng^$r7a}3BC zZZU3iCBmXmPIJUuJ7}`|?P9nt2qXmDeWt$#8}D5={5ACD`M^1H+^d^h;JX<%-u1Eq zhQ2g7IoV0}ftMenVO)+Y(*IwMjjfl9!N=QO5V|ue(geTi*czn#sReV=_RsWJHm|#K z_whxKH=PufKB`XLll?n6VW7af&E@?;6z_%)`Ae|yel~odYd?bb+@mM%q`kMfNGs?r zvb;6h@^GK*2O}`@Ypjo9DjH1eD%+5?lL%M$-dowXsss3eOS!65!C-dZcjn0d;j!V? zsS@Vz$my+LS~yvqHz|Np1F(ee*S|Ia~DgL+2y zO`|m^ahpB|Rt>T}HpIW2m5M}8gxo!rOb1rLGtaJK5e6J0DRvo5sb28K+~L2 zmU#dXzCXCnu;4@+;HjY7u^XvD>)t+AWe>uxDXPPDEjjVLK#3f8{^xzpdT#6?HY4Qo zWnFpNYmnBHec*(Dg5ygj%_m*=@<85j1^A-=X54`*g_g~`N_=^BETN7sT?eX#65}$SH z>r^wGqb}^-whaG*bP@Bk5<}_4MUVGsDt$zca82!w{d2s9jRNnk1Yvm;Z$GxmY?Y1M}{@0mS+y=?!?ZzGA{EPpB^fD@a2uoSYF1h%pdb3jC{m8L3 z0>!)MXf=d|_qg@FFV_*gPds&8LfV`FC!`v8Ab2M(WSzanV*rG-=R_K;V!+v6i%lB) zh_KPCyDH5*?SSKF&mLyOAn;A%Hk(upHr{JL^XDXV@`4$1T)))VyNB%&lW+ z0Q3Vbo+io1fK4}p-G+ULaNd|Hr;ctr5FO2|*^aERru{LN)V;xrKj0K`1XoLEvjfibI+bb`2`KG4-jElNZdAU@5$C|Hxk~1-66+45WM4mUB3%o(g9O1 zg1_(m6$8p!g(N0}iSP+84-LuUd!Smm(?g;%2rSK0w)(Le8}A?HmK(*Td4VuFPDRX8 zB6%w|-Whdz)xX4PZ-|{E`$)&hZ>S}-;QD3)AgbxwB#GnW{i04($qT_dByGD?X-_k5 zgG3iSGs)G#vG`|@)cTOPGpYD@2FXo<_tVJYEEMk%)mPkDcwbpNex3=LK~`>}gGqR= zn_YUX0m0ksgVtE~V_guuENA<*;TXVhQDH~W2_n33p=8t6*Y|)=lk?UBm0+Nu#`?3r z8XNDs)h5JDZC(J#aWl8}F|W9Yjko@D<;EQ}_=0*uD~+t)j>q5GJmaYcps;pXyGJpAQOLxN`xp_< zj>u9@;YT(nPLu^zi3WqsPZ_nPTCnj(W+t1TxbOlUa$LG(Jm1<A8%RTJf?nD^4p@v8?;d8 zW6P-98qKgjlM_w~yq`#}7eK4G{MqB2Sa{21uFup)@NQEbu$tvD00==*=VGgSJJ-k7`=nVkIl{r^8*Htqg^^#98!YS7?F;Z?K-y*a)? z5UU0~yz0xRhBQdqh^wrxA~ncPeV5NGEM!)0}uv{!>< z$v*DmLcYz^UjAt=$?6mY75p>%}71TlAMq?L6BGbf*JX^|^-tfhPCq=l8MkRvsRZv*F_f z%gJ#z&&CKA$FcE#CS-TvWGe09y`Jm?FTaiFmvwxz=K*}|$F!ck#mC#IQJCU3DuL{|Qp7Sn7P_>^hl!@!TK0`6=*z5ge z4j_2z?s!U9h2Z@%ruObp1n)bw6%ezVCNOxJ$NXD87E}OesOvNlj+9beS=!zT-b1(D zZkdMwt?C=~=iXxD9T2>lVM?AC=#%5vZO+(UzJQJQ*4!JrJ8AHNw4-DnxcU9CRD>__ zfUDa_54Miu<1M6|n|TVs`$BD}GV^8p28oU?-E~|raM3qNbn|J{`M6EUO!FbV|Ch)| zf%kx&@;MZ5MZrvdEWC~5uW6h`@GjLFaUkLCaNmkJiQw%Od~`~!QX6ng4ajPW!~zYS z6>@e_MEI+~E4If=?tz0=9hG#tAt2xQbn?vqaG#&>2&3T=3tmu0j?1@e(fL+`jrUpj zmqAn-?Nx74vJbrc{DIBh4NnNb!Pqfa@i#u+K51~F*v@-!Uv>5u^Vj&dw_ZvgtY)=X z{0&knl|H62TuvqYx!y97mjdtpWv=`v-t0U5`LOUF`#!@_j^O>1slJjD@9Z-g9{BvZ8T~1Mh-VJ!Wqcte7N=6K; z2AOgeEX~U<*RDwbl@-Vk`_b!i+}Au6?S@%GwY0A?oak;KAleWM2BR5-)U{_=UhDh#8o~#m3`M?H)bQy=>1Jg4ba{Y+fMdz z8z;ZXnAnER6$IcsUCVtx8-IxP&*c9V!O{V{J5=56{76L&vifCEbK}P1uR)g7`DjuP zj^zCF#BQQ61>SEsVaZ zz_OgW<4zT^;7woArTkIqcp7ydBgu8p4xt+1`_RIg~{9T#{oF&I) zMEL8}?7_zS7ROIEeKp#{`w-bjBTjy?q8}|yJ`q5P<;DQNQhdC@z^>~BVeRmfX$wY1 z4t%^{+;v~tW+}Dk8>G}b)cH8{&G3$A@}K@+hyw37fj@quc-zOcFUP{0!_6c06@vHo zL_zevamSm@ZOfmU8DcsYHZD06`byY~Bq_~f>L_3N1*$9n{W zxsS@LF8>d!vCG$Zw0mmtfCX~gvezlapMtRQe#GG|aGC~Bkgg#6=)%eGD|@)_a^&^a z@Fm-s?pEXDT@qLG${N9&>&DCSr8inIN40}4V@fJY} zyoa_ul0fkmhHpzu6vg`_#{$2N zcgBm)5#fY$awD9tTfn9-JC6(*2ZN}6_30Bq*wx!<={nz~&OG2WIWA5m_(xzeHs0=s z*SwXY!3)w{$UZ!9@_QWjX6VTf0US^53beY7kM~Wn2Mp5Sr=R+yq>2=TFj}rwb@O~|9p^oD1r|T_*g?HNV$;U!S|NlG1Zk~jg5Ce` zaJ6;1`kn_QkmHn0%{lyJvHu)S3X0yAxR6R$0jC!I+?%d~N*^3)f@}WW|Nm$3rs*G${$HG;27P)i zDT&sg*#oPjuxik^$&;c4WQgTT>5?f&YS89ahVkCW5<8)lsPe(l1h(f&Km5Hr7EGty zR13=|!o2Noh--(NK=PF#IRS}apqn&Sdx8yn$h<6{rKrJ20NUiZn|dM5R~=k2XG$w) zn6u@cO2V}EyUr&2ki^Lke)Uu3{9R;-bsa9{K89a|EUd0N8a(fSb={gBYDcN4LCw9l z?==c7`XQDMrqW00-65&JGsqPbc#ovm>_PEXn4gfq!h1zqdfZwB?~nAA2T6FJNx5&a z3BjB9w!(7FXd~G7tfL3pqgZg}t(_Wg9ub})(9gV(X$I^^i&dAE2ZIODzJA3s*m$S6 zd3P?8CxH9pxE;oap64fFGIT}1V;nZ#BU8NfM-2%7#2q~OVKh4z8*f7eElcHg+Qa)3*@rPseo8ab zX=0msz%F-{vF12@yq)T^1NR;2fPd)k-TO5P|Mr%9bzc@jRHSdx+UWM*<^$DG=c7`{ z{(@TKpX)6|DexXvD7cB@?UE2Jj)k{kS&5q$g7+={GEUOw#HYrc>q(CjZD<=)c=6DObdO(X?Fs+N{-7; z-g9nyEjHd`%~R=OZM28CEZN5dPJV>V@vGPQ6Tqc`c{`4C_;~Az?S7+z;Js;+$7e?> z_W$V;MPH`cuUYhXQ|n{*5oc&k$)D9*5emFN2$uSxc=xpUtiZzi*E5p`Q3&2zE8Dh{ z@P7KcbYdrh_gfaL3+}4guH8fqic|c(F&lQ_4 z;o~i)50(+24*1SDd&6o8{K-j^0k`pEv(!b8_Yjpn4kZu1UK?`Z-~Ippc6j{Xh)4Q= zX^I*|?3&g^Ymm#Bm>gCO61wBhcl>g>wn)(R`ck9@4bk7(ejfRPG=kUd;r9&|@LO?l zvz&LafZsYl*euvL}jcLNJDZyp~CSA$g;0HNQ#cyfl zTM_JdYoBy++by)W1{q5Bu?;7`0?ky%vfBh8L2qK9Xp3Ki1n$;$@8Z4>Cp@dw2~DG- z|9`bJ>D}x6#lHqQM5T{6BP>dP`+q44yeDI2-=KJBhrE}?!dp_G{$~n;w_T?HJPGf( zA?`po1n+9US1$`A%;DYwo_F1^W5LW)A^K&NM0mZA`M}4)yWmnuv5aLz2yl5bYHq2I zJ;WO19k7$^=LXK?xEgNfFR6Cecz?@0X2e5-cpH&@;N@3tG|QxYoB&J6Qna;CrIF`1^lR>U`*i*sq^0_%nl)q`-T^?IEK6zTUd| zbImF&yw3`){9T9OU3@CZunfVwBy~Dp2En^M=;GnJcr)1Z);agw7qMVNsi93(84-?n z{=L?AWfQQO4)pi34goJ$v5uwMVdHIddgRk7ZUT5gj$@PF79!(^jrZwE@KZ{U_Nuor z*#};Jps*t(ONR%nXxV&J%oiW;lZVOIn?-CQw%7yHa;;2$+x!VE?oq8}H$OJ+eg`2w;pH zSF|alcU>Gd-uufdQ*%sc5ATm;AAUIbrMJh9g`FUPzKbipG!Nk8tzsXP^-7=<-lHM< zGwc`s=`A|0ukq2mMT@?Ahw)J7V@Hii`o_Q4Tdt(QdvrX05Ut+D^hVNHcn@zA5&MeZ z-M;GdAPH}D@2#`D)%3v$V|aL0SLjhsEI4;lkA1R`2zw}cjpbiy0&Dhss;E{90nOaU zSNG*&<6V-?#xb*#0Pd3GhCei>X;xw5z1LIw!QeL9!@HF1V;@d_heo?NF5~Kzln>`vJf!skVUR$1H^1~D! zEJ`%J^(z(>I?``cZY08tcGIn}#vO2sar4%!vQQ8`W*gY|0lTK?-af+bKE(yX$#Fji z9xBw$@50>wm+Z4YaP0=|)gaV|I8J`@ZYRPrTL~aOdqszbE`ALX7L~90eft4S7x7Ed zNC&?LvBFVv2>iD3n7B_fEj$>r@Td6CI9q)0th-KnB?ct63aKp(@tD(BomYD}g z&#aBRZGew=NY!fLGYH=6zIIIK^WvW%rAwOA&rMjm=<%jYq|(Rl!`H#z1s_TfG}r<0Shnje4vpDyo*^>WX} ze?XcphdLj9#`lc3_WY^dt0?gP%Gb9Q#d~#wk31IM>LpJkwGh0S<(1ZwR&N{A+Bt6^ z%Uh7#jr~_U%;6B@^0_r5vEUk8`BCwDB7DBBHo=$YE{OCneIhCs27*G*CFy*`#yju+ zx|I0$+#rw~mn*-F!7>&b?-f(^V;U{Ahj%X7hX_u70u54x(CQcv`V>d08=fsY$egFAEml5sZjryp@$&XP~2~s#o z_^c+*t>VwS^N<-NeZKguDKBHV|J=zCPSZH>Br77esGSJ!FFgEX zM|dO9yJDoT{y79(^0v*++OZ3>pTGafvX8Hf1Dq$vg&gc0V42v78J~1;KzOGn?bRUE z$61{GatdvJ8V?|Ekg^xVDhc8bu}!tp;~zIXf}M}-nDu#uzd;&Sq$4DxBDv@rB&`DK zd?ZyD_N+SnXNX-#f%ng-Q{gDyY<4eIvG6`RxGnS`g7-Dcc7GDyOt)stA0T*J8s7We z!C?a5b2zIYvN;Z{@;g@Ndyfd0aLxMs6uu24Z^*7n%LxJdcZl>Adtu|f5MeZRX@&#r zA;%rqnBFwOjvX&Je(6gX4dRXZSc;S1_UnGePgx0IvR*y=vj{%kkHcbCMk08h>kQX? zABn%bMHiIyxUf@x(c?`QNSzN=OV*Nwnm-NFS_-^>7_8<-@pjmlrGkaGdpv9FSp@Gp zAuVMjye9@!sumEuhd>>Q6?p=@DKKvPE*N^>NthPyu9&erR)cLqnUDbL&@ekhe6nM|d zi@Zbe{;&|HjD@#XRn=4(g7?;%_D>|dA5Pm7wji4m;bR_!Lqeu-Dq~*VHsLsM-Pdh@ z|6L+%nwQ#n$OHynMVA=md_usjA2}S}HQ2Z|?v@l>eUTH?k>gCYzufdS!j8A#*uxs6 zMSFOoK1^})6L@#ZQ!$nRzW=grNtMILJDa}YusMP^u>lgXb*yS zzn{Poq0Odnt_-YqjV=x(bSU;^g->W?QByypBfDU`_iq@#P;tdh=i_h| zr!Rtweg=8`DRn-&`HuK|U-~nHRH49|Ztnw4bOveiqg4|NZ<~BbcL>4z@EUh}65g{h z4$TS(-cEsWJjWc3;2Sd6SR@g=i=LRQa_%9*Pa{69@F3g-m$ox1?!FfSGQ^|43=U%B z`fKfo_nL$3Ab}j`obg>d|1oyFUQ_rvO+(tl`zP6l4o-f{`lI-}Ja~ZZs%h!!CHQ!6 zFqG&XkLZFUP8IDd6`FXE&@)n&Vl|KB%Pm^bm%KyRJVL|ucXB6)@lNU9x z@a9!%3;m7Y%|@qshJ^P^$(Jom2;N!ajAofRMsT8z$Co*~II!hTy zR|<^|!p2+cW5V$bH2C#aKG}yRPJWa2i9$C$dB87*w=Cz_@$p{PpAg<3^9c6IOJAj{ zkB|56A3SgS8rc^82hvx6QRkx|`AMQv$RE5FDe#_q@u3H;-qFSiYFK#FYo@$XBlZ6? zW^*LGgH_A~A`rayT?!7Tzkf4h6d| zobmSAiH)}!!{!6ad^vyGb;t~onNDj>AyR{))F=0>FILgk?O%x9*QyK0 zi^bNym`1+;FaN@sJV=B?^+H9Ql&=AKOOGjULMZ4dc|PyJ0!W zay54^{2ipG!Y54(-xq)XFJ45Qk0F@@tLAe446*7IcrynHDxr8^d91{Qg?FcGS(+Jw z_h6Ze6A5qTQ*-0|2;P>uf{#8;Zh_h408bed2X1bg7RY`n198kg`|plv4XY(En5GW8;zcq$hTf>a9kBHxqD) zMDbpEjL3k6_p0?1>OKhGrEbZwB)s27MOKa>{lDQ)zsK4_`tX{zrdwCU;y_39^_c8_ zW@5^U1 zTQl?x;QE{N)tA-dz?fu-ddhPmd_#O!ezM$kkaG2PY=l)Pm{@!I1{VQ)HP-L*b$hWG zHt?1lH*Pb&ykRYN{Lu^PK0=PPhxb0RkHa|mC0ZwNI?3|@#fsTN(;0lciC3?=@({Y= zd9L;4ne6y@zdS!MWOiZk_y3F+sq^v1>;t6#_x}I&6nN8j23w$b&o7T%f`zxH^-1r1 z1aG;9fk_hHo`HnOy$Ie+9YeFp2Mu8j!KGUtA^m??N19K}Qz9(fX;8N1(RCnoSx5%9 z4+V$P;tj@=uyK|DV$B@+jt%S~$C*ER$F3KM9Y3}4RpM6%+QWMd*~eF${I;F2eSYQu z4`?3CR$KoQAMd5BDq2UlyWy6AyM@uzyxw9HSRU5(f1v-jqtb`&u3x0PxBl(_@wzw~ z_~*zBQj4MnaYk=#L~9UqNuL9&1}T4QdYzI{u015a!J+`EL5yYw{)I?`vG6Y7_$^kC z;C(dy`B4(y6$Y!fUPAC**R(y+_MrxxKXV}!(u@V3;gQT7ABeD!`nFu&;9Bs)M!O2m z4+Tr<%%8fjI%DF^(6*~=uOx(&$iH!}L2sY=9LC05Y_2-whAZviy>RcZj}E>zKQRjs5ss-KE~=6 zptk7orkkYF2PgO{@ppM^BL&{9zamee)qDT>1_%r9tJ$yNuL$1s_m6gw@OF~_@X`;# zTaHgU)Z!z68_pQ=s^-Q5{}rpPJl_!Ej!Z&Y%0L}pSaPeYZB-bEnkFtUiNVIzyumP7 z|1AVU$Z^|si%Si8v6r{(W6jg7y=bp`8`WYCz=&e7sAuwzds^ z>V~_#3{hbX7#+2ju;~;a|^#UK8Ou^Aau2n0nB0 z%vnKWbr`6sQs2nTkB#e1K86@E6IM_{jx*k{XRqvb?D#gFq-{$6w1;;C*~dMc{0?|H z`?0no$6F%IW~%;+y|=o|l)Z1Lc)evf<;I5Erz;md-rA|u`M8|8ho3e6-~0b*pu5LU z0qOs@P}Cs4kkxz98q`pz$%|EkI6Ga9=hMrziG5Vj*v3LR8Uxp5zVi0yOj+cJH(2fmiZ z$ypk87xVY{4*&^z(%gHuFaG|&iAo<10fMT3XOOxSc=PUGZHVGswNi!$3vaK0-fj_O z2Kg(=x0;0a=Fz*1VF=zqvf09XnThy`tVv6aNHhSh09s58>sa$2;s5bv}YOZTYG8=}-T! zLxDGs)KL=@Z~x;1+*o**3T^J(h~Vx0AmTX*@BYlWUGWIssujO;wso$C&vSlT5ic48 z?2R`_!ed1ERoa48e|;6;y+8=;i3$bp+($cGeq!TozHuz*TRt;*NsfCoTdvT292@V} z;0YB?JKC$>Mr0rNaPs?n`1zFEO9J@hKYX&H3m@7VKG_ zy7-s3=nhcnqd<#U@o)7;P8cp>j*~JK$m4V*EKysI;{7nYk_!v(9i>}@oDjT+A`O3& z@cxwfB`pKN`*Xf`X{Ws++#7p6cXdz9aUi1ypUJ2@aD83Ya8)_UyI=uxb@aDR0 z;e+D6P<)&d3-1w;D;JL;c(0V3kS6v2-Q@U@d>O>51R$#jy zJVJyy>9<$~F0TQ4QfuSJh)$Og@>9F_Swu>H;PYYlHY2-M2-z|f`=dkgXOgC^? z>rQ)kJCJ=y- zCv?>M_^s$E`S1S!Kdl!{|A5pWBZ?X%6yfZI)*uZRO+l<0R36o?ya(z3_nGwnzJk;s z+f|yKD@s(f)myUNTu(}Xm;2&-pZ-1ts{Fi{1xzDvkgyEsPFfd(f`+;yebJ$yO38Y& zUyCi~5Ie`bZKZn*BPb%rJ^bD3P~e4Kvs7FC6mDP{C}#@b=x-Ecl+qvdBtaGD(VMe_RYk44ycZ?aptzN3Nm z@U9{IP{+w{oeH<4qX_aK+`+85xi);fMKpth-8VmmnUm&;bFcAdkaYY`FX}a4EPA}d zxT*7T{lG7Y+Pi=He*+4<1$aKvp?Ld$d$<$}??+xb>+=x2Q_a3BlkonfbsxHg;4QAh zIvjV10jMUh{~B*U4YaIS2ETkI!kbusKTj|y0}+z%Zt~3_-~aRQED_+xUcD`F{6@U4OFbtIQIu{eG0snz8ct$;(Y;1;m5-Jh}~ZE zy9nOnQr9j2EN|)c?ca~!Jycj8k>L9M_HPX-V+ONm;IL_?B;^Yc?mGPbD0^c$;A6kj zumlPNXQyknuc*hyo99byN=+vdI7N>8e02YQ=T+DZl0BCh@&PsN;mt|*VS|(3vD%*9 zHigLQt;^nLQdHm_I+rBCg5XV`kWiAkqX}~q{AXeumz0|y)!y)rUaUVfQ0c?Mu!j6N zu^t89{8uHDP`vYJ{Q0o(cDpQj`Za?0nRJ_dlz4}wx(_Nya>C}XL$jw$qd~r!T(ib! zU0%KYS1Oq?K#)M4pQy z_5aTv-f$wF|IeUPxM7*03U2P*wts*p3V^SB?kD_2z94N=4ca%H1DbA@TITqj1ZoCH z4vkvaU=9t>?6f4>BI$twIWF36cl(cE>?L{5$?-PJBHF7#kI6pRaPr$?>$c5xlpjRN z$ZayYhF^nfa$K!F(;vfCb9n~)S-LTQk0^vDX4_QXu!e;PgKO)*Gw2hlPuYM_?s~R@m3UVy%#h>VbCpqr!i35Scx!8DD zx-nPJXVD(sa%3N6IQjKU=`6j4TyJqKxi%p1zrcI$y5(cKZ}<vyl%KhIm3Qs6Brc&He~`)qH=axA>}k00H{iOeAN=F{s*cpv+jlFNy#-WE)6 zj6BSv1imWP@x{D}0>^J_3g4I|!rCu93@rw)0OL*X(xD|`pn3C^4Bj2scylh?cmHn3 z0B(@uPI3>vjCzEPclGb#13WeKG`avz6&k@qdALWYVf5SDxT6 zZ}|pVTsFC(vFP#Ef~oUys7dAv{ok**OepYP{z4i?@gDt}CX9*q(&v0@5WLMk>pddj zo%)V*jSGTzclZ6)vP0{D*KJ>kj6J8oi)y8=n(xT-7BPti{SF0S@=I``8B-WIe%bw; z^lxmu9fqf;SGO~O1LU~y<+%lwY}gHw@TE&?pRdv$-qvIv0yz17yC{0mdoKZ~^QFF= zYQUeIjHSI=WsOWu!b>ch&wAi5Z_z#W(u}U}T>SliH@)s_jT$zAQM#-#8y$ehOS=9=Mn>Lxd9> zyOV^U7XscjR;{sv$YvG?AJzVZ*5uVMtR$Z?Oxj5f%qVdL$5to2Sa4dR_g z_Thk&-)Yx!j~a0TV41b^tGR)Xw`j`m@JqW>IF5Vp+xlG5=&9XMV-p&D_LX%Ur;m${foa#Jrz*7xOk|J?0I}vdqHF z98B{}pPAk=^)lUKYG5j1%3w-h3S&CR|^X?yv10- zn9Z2P7|D2q(TmZE(Tq`xQIS!Ck)M&7VU}T(;U&W(hC3W#90xhvIqW!$I5aurIm9>! z9Q5o{?8EGR?49hl*elqx*^}5K*^jV$u{*Jwv1_p_vP-b@voo{JvW>F6WP8MRhfABG zn&ApVGD9@OaRy(89Sl|sx(uoeG7N$YZ1i*Vlk`LMkLg?J>*q}uRq=rXFp z__owSS*Qx>y`~3cqAECpcO#U6s-PfGUnm__Cp2|!p)^z-XRHf>E}<&$*#;gc6;(&G zf9gRgs5%mO_$ic(s>3>GN1%(S3gCGv238AAurKwe$JxV<-YuJ2H8% zK;fuzIlpQvbP`qDRX=h)t2ZB8PHx-=|TquARkm|50z*^-lziUJ{gb~s9jH={moSE0P^FZ6Y69AhDndwlVb_HNsFKs$X$;w+YBizO46;Sls^&FOkPWJ2F81<5)~J$pgC(JDsFG6pZ3%5fl_bYR zEo6nNm9N@$Axl(=r@!0|S)huv-VT|ginKflnW2ibngf}liq!lE7 zBUF(NIYEY~BAp3=3{XYdLWlHGMcQ$M^iW0m_7B>ED$=J?kS?l7UzR{Rs3IN2hqO^e zI=75mWkMb;NH+*UTBzbcE?j{&ql$Dt1+)oOq|f=Gji@4h{S0ZMigXV#q=72ZwXKjk zsz|q7LTacYT?zN34&Bh-MZ%)1Mc&^1(LB*!K}^{7gBuf71)p(;&- zVJ%dPs!PlBgPOiMS4FK zT8k>ubCZxfsz|T%L2FPo-B26`$)RfMyreU<8dcxyyeA-8RDI>^+X}5h)#opBE|3hW zh+WgVkTj|$V`bk!QmC46d&mq)qH0{WV;Yh`)#!NqAhZ%ypPoxfLgJ_zNwL`jtw7aB zuck^!3{}Gl1vep4RDBRE^@BuE^=`o19a@g6wSb9V6SNdnFM?zBA%0X1*eRcb_)yiq%#|PFMb-03wKRx_tQ>E3 z*)Typ=s$aQdoBSYpz3L4aTdgls$R=$6%ZGyo=C12fH+arGrDgY;y_h*>xtD6JF2=8 zgykVNR6TNRjeuBD^-yWl27*xafJfB@VnJ1BTbd)pjH-@;K~9JXRqdyLRzQrXYIAvi z5Mn^pJ+^30h#plf?Z59N zS*B4{=bQsrrchNY^;L%D8>*^5cO|oY{rCPq+VAn`kPXsp6l;*ASq-`dSrjWOg|!B` zVWr!ajmQS6&HH2}(i&tkCws&=atCSO*~lkt=9>V!9HCmFEF83K7rZt9n+S^)&Y5)P zUI017cjDhX!+>VI&w!$)73RKmx2p~PMu-lqC&!%>J03;HiT%ZCvlC15Dr?$XVt+vP z(S(ym^q zSMK3^j41-FTKZix0KxkiDC?=LOaZTXt!}uhg#q#XWhR;B*m#dAU3hZIiw-O&$Ek@} zcZH~6<2_ofk?f>Pdw72&`@qYuEICAbbU82JC*GVKqXKXBFWFvC=%2tgJQ2Ii-r(OL z742b5@8Y?9(Z3*d%9A=D8Q*2rW+nXD|F@#Ro78urcrOvSwGs>O6$R6 zTKwvb;_bV$@{(LD{s!s25&y4_Hk^wd@7_<;`IyRKf9m@8{Xa_zyh#fwDBfmC=f$z` zo~IXnb`il_wIyXY3GeuYU0*d3yoVIL4@EVpfnJ?xIfaiAKxtp-d07N+9o+-Mr*38f z*MKauNNwc)|5F78Y5`j@Cnw_fmK)G*SOPwh9{*+(Hx zesX-Zu3E7?;HZRlh%ytRWJS76~?UFDEdgW#RG$2^dPw>n?g=|}|c+E;3HX&xKE5rvqW4R9oQ z;xo0|{TC4?>}oRp<&q7UpK`e$>J0R-kdOSPJ8Gu}^Q+ zd{_`?E~P!Z`N=-6;^bHK;BJ*f1>UDJW>xl#K8E`xL^3#;+cAHS|8#%H z)A<`~dl&uwKV3C-J{}i36wM;9xBT1x|3d)n{(v+{_7pXUv^Rp*pp}-qa#%IUkw`4b zyHu|Ioc$p?sRns36ZU$E^#5L==MJ=o>H;B4XLnWSaG;Q)VV$%L-BSGdMS&AcTncOg}VseVS6gLDe<1n<0-7uTx}gn`QToCVQ$C&Aw1Z6+fxu<>@Qf8leaVL{7<9CzY#^1d}MuxF6x zHp_187N$MCoyb1$@;i3OA3m+a2l}2Tk4;c_y?rpKbE>R z*6&&LLoBsEX04^JFFW-IZ(9nyNxRo5-nRCwtFZ7c?#*=>Lh#P-;9p9K_h~zgw=Ct_ zfPOeR;v0f@5{Iz19D=tWQ=0p?8^~=griZTY+e-#_=)29y@lxHnyHId_H z^k0g}M`Pp7!svSLb2M_eo5ubZLiT}|A8#v{-)Aj8a9bx&wZ0y|dJn&fzsQW>T|z&w zG+PC~|EJq_`H|;9(4xniY9GXoF7o|LNVBuXMG1NAX;C+Yw=W~b%`8TBTC0|NCO*hK8x25-+t0wgLH@N124aD<}~HE^}N8Io}0&tiq+esK*_gm zj!)pbmn*i45~ElF0olDB!$BC^e@FtxvLh+Wfw2;QaJE>G` znJ8)X7B-in#M}7L!8E=0&7fxE_til=!h!Yt&GknRyh~0F)$G1_4y1U2Q%osgAbCPr zg!v*i-o>@bnm_Cov|`9{CT@`jghsLN3z%Rv-M@Js?ctq6_A!o=-wpF8^9;4Tz`Y=~ z!;1>M>y}5sJQ+`GZ!+%IvpUgkZKUj<+1B=zKVA0a~rvSTWvV;8CQWN zcQ9P3)h%keKm<{fCBq*wPJv5RkP9FxmB;;&Fbs~WKNrjYh z$P5$j-3@t)uZ(|d*^=Y*9a1hA`eWn0e#xHZZKbq_w-eciDo%c{a@H;vf6oV|zr~Nt z7vba0b+%hX!53NHV)U&;TG&*;{ulECL8@EA-WEHOIueCWg;k`M|su3pwuOjOQ||3T(X3M_M-tchDZ* zrDPxHaPm7G-7mYnn;*DFRox?&;o~iR+~CI-_g>h^$b6ISx(ArQM|8*@5lJwAD3!D5 z@y-{e&WCOk@Sw(X!i7T(rrS`vE@ysw*QLX-`Xvtx8{z;-=& zq}cezM#pftyKP3J7{OZ^oIZU1hCS$~vzEJ15&^uH9+~f6f_=P2vbsX7X<$KX7dZ}U z*0O@)YrXG!_kP#;{&V`CbFI#G>2t38zMlIT)@*Y; zZ9(&g6Lb{T(O}v>`Zas$>a8gmZ{kx*B;IEZXm3X2-Dn=|8Uyn_AMLw}oHzS)${>gP zPT<+}*;3m)3jAQnkS>C+-u~wA+A#3Z5}1E3V^rXY23#`qhGUHAy!BqCg(bfDqsffK z;q(WK`(n{~YZues*bS(Uw+>Q=7Dj$!mG3U99pM3uVkV)VC^-L5$k*xbh0or^R=*bn zi`cx?3A_?wo&7Y=`v!$|(EoYpTnN9M=-=~y()vxse}$J=JF*@`d`^?pgQ5pkY)9)s zJa;ai2+kGe#h+4@)J-wi=hAbZvqI4^k7-( zlLbcF#8#^nM}q?r-KxyDbWnFb8^a-CR;gJ{O(d?RHT`?|AM{J?oB7!w0{2FU+J4f) zNFA~m`8kSg&$1Zj1E>4awrCb$FR^hwI%QJAcxcP(Nmbt<3I?RG*^dF&*VF#|PiY-4 z@%@ILOY^@i8E@i)$0Xj#i9JeaypLVsbG-=j4qY9xfykRPEn)vQnD@q(@I@gj01b-y zf15oU1nsEPh)!A{fUj3#UfoyD0HYrFn&TUyL7{d+<(_C=RNkv3Mb@+B3sj&I`dP^HJ-oz*ANxbiuUQ$Hk{YlK$t_tQo z{+yGK$a^Bg`J^Iz_12W}$Hi}qTF}++D`wnJgg{5XTwf4eB!KHJvfV~g@Z$z=-a%Dr z(ZFr?{>7%u-Kc*o)wfl)s#g5ev_RtCU3(YocmSPub2{Ca#zyMnU4himf{|bK$99**FdtSi@qmR}viF$9M|pE#}dWx~A6BRbD?SEYb; zf2Py>a-zVef|)G`rqOwOK00CktM8{~FA^ubN&no*@93KoWqy$d@fWCXKstuhp@NZL ziPw%+2Ul*eX7B2j5ej&#R!x1n0(Wo6PaItp1r*$zn2;>f@Od@OcW=5x%IXL%rB^?E zVQK!iBI8Yb*9nRDn>KBEG~O=`#$1_%c^`Tk#7yKZy}MsD5boY?*Pn=toB&Y8E4z(r zuZBXL)6=&WVcr8W7v#LYoddd&ca_60MFA~oV^{Uay{O%Ld$!kpzNvXlMI^4uLr!iz zAA0xJKXgdDD}(xYZ$awVkCES#yKXI;?{b5~e%!eX6r8=qyIifl0iV4&9PfYg^(OYs ziFDRehT}}(G|$_E!a6SP!1FR$NB=wjlXj=n{8xDXcP8sW#J4>WdyqU=jMLaj8#=Te zq%>6?J8-c?Yw>!L2eAi@e0wRN3O|D+D&rqM!mkaz&D}j^;Oh;|ge7(Q&k+F6l{5RZ z-xq+cHfiY+&nR#*W6f`da7EM}R2~;v9e(herZW;Z?N$|`$d10m+UVn4p4_9p9#n+X zft6nfm)V^$UtZ9TGhZoJf;}LetGWKO@}ntMhi!d=H|u4t1I_j>>y?L6Y35&`C`{B<{oO zE4l2#=)9G5OXVDHP#gPE`B_-~cD8@S3qG7a*?GSho3}#T=|_eJcxc9RTFGV{ zdx;HdNqiA!cZ246zipF`^ji+$Z|?1?diCyooQEB=Np7 zW2=J3yE*c_uLjJ!Kz~e|$lG|rGr0}Ez2)XiwO>x0CKTQztCZL14+UlatakcE04-r= zw`6}@1?~-wZk*TQ*Iq1N9!q~#6P0&V)p%WF?X>2XWq;%R3kEE3kI{LD>@{q#QlP%e zTOmjtp&0pXaadhepv?!iw|h6L-@xwPnJNlQ@1^lj*j2+A`Y!CtTXc#}j9j=|G=F)E zPJyyIR-}kOGlp-FhWFm~WW0%QOeOKoKB%gU#yhnv+1&!>-S^_F5|Q`nu|KoNVBX~% ziEsFBYC;8-()TJ_10a3Al6^|>+1o21lMz~W864lpbIIyjG+0@lZMYhhq6@W)R;z}2xk9QE&$xF@5rA-2&8^U|TVR>=p$6fKNKjKd&>rk8 zg8Ii2y`6Q(j=3StbW$9*`Tj!#=)ChD9WL0ug8F#-BXwZqw+3hLV5Y|hiXPrQF?k7_ zcSFAP6#WN06yj&Q*T)EZK*9;fZWQ`dLHoQnP*#UYKH##lL@xa@Ht#Dzv6mBX;vpWAL*j&u z${h4&(Rm;C=rA_=M18#bkvg#Q%Qh*u$^Xs=M6)wK8c}dSx}qRM{}jxd?!@~5Wq{3_ z?rl%L{PHr|pa1(QtfMJ4^U~j!6CWevP5kZ(iT7{Z1$s2z4_E?5n_%7+Dhc64-hcXk zOMAh*r=JjJIV!Xv{O-y%-ut~EOL}{T{j&rhDEZdP{M2=@+oPh@=~NVGjrpYzy+;m} zH>6`sUw(K(vjT}z%Prd~&4@n#Uyl2%bg7m4c$Xt}VCA=h{&D|xc|K5gG$v~_K2nD(Mt;j481asx67Vq0_d|ySt3SgChj6ZmmgQutf!s)H@yhT{jY(=U;y} z>Gc{^-hDo20^>D%HJ>AK&AY#~vG$|$_BDhW&qz@p?}tboJ{b8mm1#%2p5z5rKDfVm zdIpfowQ6ezG7FO<_Hq!A9^sq^&L9zYk$nA9d=M3 z?;xa(T#WoUFER%WP4j}LlE6|Z37dD@tYq%;N<6e+uzpeh3ijk=1j5qOPmn7c8t(8n@y!%h%4OhbhlFzO+Ohn!vE^<4G!@PfZ&AMq! z?1n^rrWHGWIzmnwrmiO@2tX=(H{oY>IfxLqS1AjL1Rld|ho!UoHUC*W|G!`K=Ey2} zM}5#V{qi?1DWLmU&j)ng92&cLd=06OcLP!fR(@Jt>MM8o@d4J}nJu4Fuz3$}v|P0s z<}LVRB|e`Y`|2&-JbRtM+C19doXk;JhrJXN@_I`TGTy|mw~~10U5s0a#ydX7LSF{v z?Y&8DoH+mAVqJfO2j;!0_jk9C)^4c&UF5f9;0zt2OC?BtBY+|{dbWohW#H7k4pA$o zNHBl!o789?E9#!{`crY97U7SY-bfq-EN!;;q4U;$IJ7El8};$dMC!oGPtPp=MY<9n zs6ShAelG=QZ^IJ2cQ(OiZ}<Rgm zNqUfx%cR+EO#_JT!-^|d=2R1xbF-ZVlS~fA=_7p zZg}W%{V`55^b zvC_2%JYNG$R5c#jSzz-PtiEvY6wLeQ`J?L&y}@2$=??v@3t9X>aC^%E3hUthqc&*2 z^m+?FGT!>{Q!`1tg>&Dsqw!WVz+JY4dD|y%gowO<*Kav&2lK{FDsJMA+y_}Ux~YBV zG=@4&+7h}y5`fbQ?lQ*NbswE)ydPb3aGrFYP888dY-Gfs^M>(oZG^0 z+yC(N)(G2{j;Ma><1LBQ@f9P#?1G!`tDdX@4XfDJ3;AI4)|u^+%P_`6nuoH?-7>LH zkmwTaR+JZ)(0uo%J4aa^r*0&yCkQTeZ(lOr`!8IwBk_)WcY8G&Z;RWBizi^-#oZ5c zh`dKr&OK*?dHb^78zZ#sg<9H$n$O|Qpd(6NI^%=z?JbHW`#jt3fZ>Bm!9yn_fz0^p zRO268PMmN2-o2UmHyV0V;oVy*NF7WV`MJJvuVldUg2l}* z&yR;=^F9@Dx9E>49unHi5x|ku2C#O%9fN`NbN32qe*UlcL|Gl5-`F2BXbF=6R3* zrmT(yXv;-S_~FEV-~Wfz_^9BY!}EU#Sr0n8^LIR{2RSw=twrlWW33ip85c^l-ek~s z6X$>9TlN<9rHWb(zZ6#8{bd0CSfsDb#<4)s)iD_gT?F9y=K2OMqgt?+nZ2WN4-UkH zds)fK>7XvLd+8$9uiX8%As&fiw~x`_6+~ZR^%l==TN5CO`uqKF{iMy1I`(1Y7q6mm z{^}cU@TN&dgn1426028`b}R?JLHbNHVFkksb`R1$S+j3WhW6k8#}iIj9aaWHW{;DX zc96kjyp6tsKoW0FA4Wbj-c4%aGk0L#xG2v8BJUH7wt_)0?YJdkQSWR8KyAGRoRK;nbD==@S?}-(KmnfM3yTwyC z2T0NWfYd`_9fyoe760De5=6$^uzCYMiMQ^?-Zf~vU4E(ibiur5o_L24dGFYvvPBr? zEzdMDC!lx;$~pb|teMDmsNom=z?~NaFn-8R=wfj-$T*uH=_ZB)ZE0M;?PoMldAE1R zyKGj*H#|q;HjJ(1N&OFxw>-Ijq(wE4`gp%X>S)EtPtnV2`#KRG5L>tCq$!EbJEHMe z&Co|Ylr+VY=69qSx z@u2Z;%P?Fu0rP$y`^kXFyZxw8&#e+gt-8Vsmw!1OfaE{kzXAVk$oV4stD~<8;LMnr zqwmZ6Al~UXU%Mm@e8&0I|Kiwz$~#0{%jXH(^M-LGZuw2A%s=hu-MdljRa`YheZ0>h zbv(ex&t%ftXKNA8XjrV00pI@q|yniJP9i?+>ZV*P| z8=y+;MEYAYsE-_=`@TdN@Ddx>Wd~h{d(c!Tr(e)*MJ6p z0=WF%ogvx-0%|=gFGa7zf$Y;;fB|72Y7g?LGP*Q8`lTTUiQB}qU70=%y$7k~zc!mb zMtxt9_C@MY#mLX8(YWa8O)e0jA#|%~aD^7upJ9CV?(ynuJY>*%;`AX_>~E0bYz5N7 z=+tO`iM6M!j>e$u#^2YLc97v@yv>=@FOzuZ2h9tj@ou%r?~sIf+tzPBN927Wbxqh7 zn75I!dG|g>3uvRIt^P6Vy&&yj-NEgT2_XNJy18j~15nbbuS}ke05|H-2lH;_mFQ9qeSLZ3Kqx5^FQU2e{TPMkQn---ly+N8dAf4a( zWE~oBhcOZPoiOhwA`a$6-eQi%gzj>f_aWYV^=)PlG&Je~&FlojkL?SMS_zz#e46@r*C2H~ z$H%(l^v@R-d_H6#4s?8r8G>|wZg;M#+ zdGz^TU%PHo$Ytu|&4<*nA0t2C?40|}irm2SqUk+VI_v>Su))hcd=w8Azhv!Alf~}d zYM!5FCUPWc{`D5iyeO+;-`3Tg1EavQ&F?lfB_No79CjrD(7O2om)Pc8Obv=I+M1W#r z@k^XhJ5hOesCwgA51NUrJ%&3Ee_~fFptlI_L2L0f3T$u>Dw?=eG$ZB&^;f)e zzFBJlwA^>z;kiu!Pm*3G+veq5H))CW@t6`tz`T!%9y{MD>j){@E!&cE*9@4N5BXiYLjb#W)2pQ(ZUlS^ zR%3^qF1?kKu-`}Nq-m59BgHhM{$7nS1 z4$>3`GTzoXT=^v4PH*c((0CiHG)uV$^B%}6xy+>8-9Wm=1ot=+bT`!Fp0N+>N#OF-X6(C+k0T%9``p$6L}A( zweA#z=l`NzLPJ;T?V$G=)@_8gBOrGy*(tD=02=*G`IuuKfWCRRPD`T*(7-Rl$g+Pw zD(~Gp--v>y(S~{?ZXzdNH@^U#cfMLnb-Wz)@jigmk%y6AyamIJxBgsU*&XxO1s&MD z4-$F~+;ql6&u^bjdFh3Hc}qZDKAdSC?a%)@6xJ~!!@N@d{1R_EGTxR-U;cUamNC$L z0~&Ang$KhEFmLmWp(*0!txoAvqGd2|tN4n6y)w4YiifYw-qjukht7MvZ)qTa2={M> z1fd6D`gfZ6TB`_9C=w9o^cv!8BS@?0__ph;S=aY<3m)J*} zs!iCw&os;-aSt|}+%r~Y4$z8rOBWEz)1>l)N za<`Z1A|BfRef^#zr?GdCxFKMkme5V}_aISP$A=e&E3=pGAWdN+en|iM?DTZQpX$GHIR*iFPPfr{i}R;)BZSHf zDm$7uAgv_h?Ra(ZAKp*3YNgP4<5}+J%EG*pjvYxN^0wLVa+Cw+tvK~cg5TH$s+K%_ zM(VpgP(8u@w5fmqEG-fgtG_jY`hBYREP`-gZ}e%l_Gv@Z?!8IC%K6>gRKqSLZZ2Oz zXOkZ~@5DUy{3#3S<1LHSk${n3`=cK*k&Haxl8!!IRt7fj*#{!B%aicXvcBc%Rdd+9 zV;27ycpEg+JnujX>)>2q$Xj5&K;*rGjJJbV*)LM}ZvPV_iN?E^r_FyK%=_7uSOX&O znB^DD*kRstdY@DaJ~%^NdQb!F&euE=6dMz50DqfoZmy_|f-^xBi;yrg~ zuLK(J*E5z^9AVysAsQf%IIGqJU7@Y$Qk-fb#>_G0r^YS~=%>fAb-=k3-;SsmLf54QY* z-`@J~`9IpUN=1JkUSe01^&pR5D_)X%P*XOu99j<=yIQl~8=n7Legs$-!#!x<^KHV{ z;3r5EM{0aR(!C%}gQ+j~B0NFA*fo8ZI09Hc+jnfZZXCFz>*HHkZ-Ux` zKI}`sZ_qH`a2|={XPRD|*0DsL|JCRkzl49HzVrWnqz{xFmFhXUNWQG6Y8GXl^v{p9PIwd!T$Ul0caAcGm6H*!#H(;OGjZh3iB~4295WH1?SmDn0K#o zQ4*0ip?JrJ5tw(Btelp2rw4R?*{X_tf^OjZo$K6=7YN|DlSjah)JGs&`IF5C5t#Ro z>1r7vblzVNZ*x5OdA8v`5*L~1%ITts&Rb&0yzaFC_3<7>>cGlxV1!-LMx6`T$4jdoz>qc9B^$B6aW2 z!}~U)@y>W(zyBS~+bX&10Fk%7n?Mio>@EDB=q`>xcc`P=$KjZW3kZFDAmIEZ0>FQ% z_@cM@5onlM?me!61FURT*NlRXpmy)(unjvlkN;?3LgJ33f8G3b5&iO(%*VLXbxPF7 zyA7#B79+o{4DmX}NnD_)M<<%!d((ZT ztPY7SPjJ%r{+<7+Xv#-V1)l%8$$F3WA~sbra9}$y?E$8A77$*5cUr8yhh#8uzVYuUt%*UtV7xQ+C~Dy(g_k58E;=M z*PA5X-FhofdB+9tKVXEH*aFLnL?Z71#uvZ)VBYEqmFI$keW3m>`hpF6e87o}rb&RaI@%-)tn z>f>F6)Pa?sY@FK`^UIvT_gaeOT?%+77~#Zt_rb5&8S&q@q89u9e;l4yd+3@E&GV+T zj&stprv#(U5)Vi@$#{F8AuJ>D<~x+Dh}OM7|M=d!0p^`&<*rWT?Y#1P(i52X*7C@S z7(pK>_@dpr)qUQ8&;I?>>JS1rHz`wj`d2fMx~Ak4d@BN++85fG_sSHNH%qPOo6e|( zhHxbALSm-z#kc5JZqy*W&+a&^&KzTgvKKGa9tQHhpP8;vnPgWpL^YiFZJ%p8^_hzXr}Y zHJJCQ-6`LQS8v7N?<%i=d0)KQWiEKr8}gVw;BwyD8x;E5Bv?fd0O5<8CI5wHpu=$T z=wNLGxN}Zj=cyDr@Agg*dE?UWhB72hzaZ%H>$B**xz?O4%)3v0ygQIOI5F~jE1y4c zP!GQU|LZpvP6uq>264~7B*VPdze=C>oul9Z>AXhqa(_db=S`PSVI7W>j+>TVZ;`@I z#@lnf$5RsT{H;J9jrWQ1XWNg$yeFj03yHjIkNX&>!MtCy%P9;Ac|(i0-CEdkyg=n! zu7iYV0&rCtyluaw890?(DA2IOf#ls9S4*nUc^{J!TxU}CtKlpXSKLwEx4G~?@D?|G z_VzXP@peJ#;KayJq|8tC+6FH0RBgHBeh+NkIqQPBVlU#M52Iszt}n6o-gIyEXSTcz zqW$^*J!N%#pIJ7&sGcKY803 zp8t*0@0=)wd(c|pD_gqZ7o=qgl`LBB_k$Q*Jk33?`+{asalzxJ1W;?~lxo}X1e|M+ z%(P&}fyP@GrQDWTqwXM^Z|bXXh%i9aNZiN+(G9$}ZBXa`6~zoWZ4uPhgB~MwVCBcS z_^Rym8BVbG$np!~ZrD9&IBnojizOba3fh=>RQsr1^ctI?I0=9k#~HA$w$Wf#MOCS(h{55)ue{TyP%|>GZN;#YPXdrk@qf~x6cNc_uV1&V%AAtNL>4= zOVSBnVCBC5%q1%VkneIx`(XM6c)e*zQ(?jZ7pa86G*v59-g__BlnfNpL$*lV&QP|e zOuNu|=e`W*DNUn3-g}Tbu=0DKwdP1;Hzx?*_C#RF37fanmuTA?Fz=d@{Fc+-DcC_8 z{1DK8Dn#?V>5foXM^fD)@fAC8_vR(z9T*hQOX9uv#syV0-ur(Zvde;bPk6oUEP;6| zLr&k7;3r7^ZXORzkM@PwPG?88>G%S^+a(G4_5>g#@5Oy|x)ngKuSNE;;(+1PED>Cg zB`WU>-JNTe?VyMBkhrGQn1o&Ltx>!8srxo(MoXxVH>nP+{Oacf0^Bm-?j5wcezOfW z@2{)4|3r!6p$8mU;wsCrySL|Iad-DRMtjK>HOHAvi=Z>!$uf796VyC-GZ(n90^g`(JL2+JRV1Lrdi&+DH2Z3ia{cj@0oBBfr`~o-2KloFFIb;8(6xY~Bx-8|{1p^FF$k z<86Nr1+Un7+|povV-wBurh7zT9oOT6{(k>2WgQvsurOy267Q$W#~9IgYb+M9tc7=w zef;dcxOysvVV5_KCCMXsG z2u3#CEHUW3SDLt#yeC^ zXX*QY#O{51posyEck6D8T?#O7xvj}!MBZbWc3XGBy!p1Tu~U5H50wfw*G1&|g2vyu z+RqLU!1b`NPYdJQfGF?N{58rEK>z$6w#B#ThZ9P1O45TB4A5>QZr8-@pOq`oc?SmS z=ht;nA8$FN4y^oUTrO7dDZ{t7v>Au9QgHu&iSE<3^QZ6-i(-j|zb^LWEfWP6w{QV2 zntwrBn>=N8s|qJ|Z*%cvdNkhB)q;llFz*#|C7r~>iP6#T z1nUY#ty3oQaoOp9(D&!j-4;E*fM;NBo|F**Ge<=vNjDt<_0yQ#8(zf7xFV0N|L1NO-$k|{Y(2$uw7`&MP4AjgE z0;f7awm_9SOHer2ASaNaSeLA1)aB7@rbzm0qWy@0jUEk zzug}N?%x#S0&+h;Tzy-O&HD`t1H8Y64@k=+>OSRQ4@h(y6->Sl-lTcn6xShJNl15F zy1ius8ShBtA$t<G`ME!PC zn+xk@y2oQyhGwW+jMRv8t3|iRpH%|P|Sq6*y=)B8P9<~geq(0t0NFAjZ`R#opn&Owk0VZ8H z70nc2ckhgaF0>x>ZQ|>nH_0Vh*Pk9#z619lh|4V77rukka|OSm!-4qS3U!eH{MGol%E8-f--?dzwA+$*hCTj5a$O>&^08k zJpw7YcgNR+V3p7yl2u|6i7}I@DO-89Nm&&Hs{QyyMR>o0E78=QDGn@xEX!vik?j zTTOQGNhQpCL88318s_aiWb*3KY#7A*!F@fazc(22gT2JkzbS~((!fK6iGuQQCT!lCZQOGT0qQhAAjP#%R!4tj^2W5-CEgNbyyK3v z|MT?LI;Pj`XuPFAM8%KsP@lFsZuxL2neCU*8$-Xmm34pm#Ya)<<9!3EBL^ctPlY3u32^r|iVDxl{*29=S4)6b+6oU{ z?k}8R%X^HvX(R1z!*_VqWIw)5^SpCZDXYVCPi1g$?o#&_BjX)2V-`W;%^?%QhQ?d+ z#`$f#VBT8~cbz5jW-)mzAPXN(#P@AEW%x1#+Wtjp$cEbo3~L@qGv|lDy;akDBVW7| zZ0vooEo=THcyZ`Mkzo}&Z+h>=+ut6pfbd9M6V#R}UX9K>JHq|&Lq+Q2{mbib9hWik z`xL8m!|Nj_P+$Gy$LqJ)yd88Fr8QyRK@w4SQurz8-jWI)p29b1e*UMEqOcCF=h-s< zp8u1&8+HE`p8sXYdQftSS1PFo#kFi(i`Ii4Jn+*ofd{00DYrxJ!ae9cVXaaT{D|H0 zT0<`*UL3SxOO}O{pBLD{klbb3KLMa!TQAE#eGb~H%IsGQhk?5R=2qTG4yg0LK3Lo6 zUc?O5AaOlmQblSB4ya2BhjM%ugP|zu@Atp;hp-E&gA*e^v7Zudp{ATb_ua>=en;&2 z|2bYvJAOI*25G6b4OwFp^dJF#v$4*tG{3~st);Mz!DC;y{@p=tCgYtHa%~@pw?g6{ zUNqjOoP#fYVBU-=rVK>h1hz%p7clR&vEdbu-bFy=uEJ;7qrAX=vk}7V&;-!?z!jm9 z{Tu{6Q7E&7!a(VfM@McAq4S;`GgTdxVTLM@xF*L8>3zBAy#4ty<||F8kM{^tM*v2C zFPB-G%yV%9x-%l?)(5e9KVUDpV|=Rz68m=Q7JC&1kJxeNG!zmZ&^~W2%IdJyek++? zw6ueiCgYu`Y4n4{dsAEM8Z_Q65pVs@!Mtl!%g$E8yhpa_A0U1p&EEgsMxn?EXuGtt zXHvEo$Ow8Z={G(BtP2_wAGkjUAI;*X)NY3XSslyUdqUB9cf9Yf*<8K~+KR-*ZYBIF z)I5@htj}xpo!gqJ85;pHC`huoQcY7eWoxJOHA}RQK z%K=_H{@ZFae}i@nVl0z#+(@z z{V(v=)4j|WVvjxl%Uq4g)p;pH^Ss@zP*#WOa@o4Tq^0h?k&O4*`Iki`-j3%2xY2ko zOPZ5tgn8E`jTI2j-W)zIcHf108*E;w5Re=WnQskE4_WjA^D|HCRpuwa;zNu4B3&;RmdJt+O1#&J>)@}Jza9<2wBYm0UCCY5M?xyJwQKHP(Nc>f$TyQ!#U z7}42|FULXiMh(~5&wGL^Z!hH#>L$SbBd<;Do^*lr%#RLUJ`f55>UJ6B1v;Y6>%9j; z<+z4fAyV9!diq!Ka!1tpU;E`S0~0g#^`K`+9RMT08){u#nkzZMY+Awli*eXJNVz+H zc`s8hME}-|=X(YP^S{`+8$KD0w0{j!gu*%kcvVII&i`^`yf1|I{PX<(fk{RoG~SZJ z)u{xScN;I>hRC~%sYUn|%)5A@{qf;!9OP@Dwdce&PoSXmxcBg*36Qg|M~)@E3mkfB zw*Q-aD0t2C<3-ya^Z{wNDBGu6Usk9OiQ`FieBZGjoj2W$tKbC}_3_q1>iARipY!AI z;bedFfCJQy#{AZez~+6gQ|j)89z4_(QI%!xguR2b-o?1%Vu~is&;OToD62!{_vn#h zUQ0X3tz^8<@9zIZ>fTD}?d#BZkM-5mo{|o^{F?=uMB)n5 zR`f~DqtE}<1mlTJA?oA(5UJxnMt*x9HBU`4asqi5!%E$g*u2HQj2y9nc|*lzVe!u? z*g3gM{&XuKmLFYAfHym?ADxe<8} z$pr0Jzon=pyY7C0rZWyYBX(?~;Ac;e_}lsLt?mg>_5J-vXSpu$#b!2E`)Mf1#kbih z{X*x>#v}BdIe`VrL*jbW^&5Ja(YyD|``(Bq8S3M`5~*VvBfo3QbDq0Aw&h3TEp)#0hz87CBYXEG@o-}J)dF6-L{aNS`?>)K9UP=HG=GUj*b96YzxnaX z>j|L3F)`Yj5Kn2?f(SqlBx~=)5)OrEXqX#{$hFasIl8tYROdcW+TH*J>S2 z>f^19)Pa?s@326zG%F|ABH?Lo=Yq|9x65$XJ^1X6&$v3laU(YGQY`@`vEOnuKmU6I z%IfG3)=zyB_3!=v|Fk!1{slb$ZztTk51nv2IltQAL`*}FVJ@mJsUf%FNmPOv)vR%rdol zt45#yKR#{j7?fj&NOA6mU(t`oI-xEl!gSGY%uhs6uP6L({SmxD>JY-nujEsun@JM~ zU?0zIpRB>|L6whAkG!~zhmQGg@RKmYp8rSuC$6^m%hLQ3yDWgRIvT>W3gS|hme_4% zyt5oD&Xbnd`RQ>{G~Vl@HN}s^ye-!L8LokO7X|*>l>+m2OufHTCj|!`(o)zKRqY9+ zw`ql4xI6&_uQ3)WrFVnvJ1#m%FAD*L3EL;PZP0ngnFct-Rjh_4khtU00lPh9(Rn|5 z`ub^dC-w1;MCxe7$nQm1gViBAPGI;$K3}^6o44ZeQTj!g_w7uf=e*mRQ2(?4=RfPR z!asMLRcM|!T{(qy{P7Es|2rTlk@3z{Wt1iH4%qQP1dX@vOu5u)n0K&qgd>r+g~PK3 z#v=IcE%D;7^%*#*AYGPkbD<}=_HAvtcHsm_=k(z+bLa-CUa|`Z*+M|QM?j()H#+b8 zuFX)F`f8{aiF;(g-<$jveLzx>8_Zkvn)-O(M(Ws#kzZNorruxG9N_2Gme0EjuzCO3 z)+RUn8xL7)T4%jUX~g9HAkX`h?`#Fl^LELntd5Lf5gyTtOWj+MjQ6E=1z{xKnNtbE zXuM_4b?D^6ykF;^?XQM;D{gEMzX0>raL#iIzKVmm+=ecQWq5)tV{QCU$pna)j&$LW z>jn%2+(Pr|5TMy`ced{!I`6^XN2gyjvq9=eoKKyBUegD3-iy~abg+J=KHl$;I(}i~ zC+n2*Q+I&_wFj1;)^IQ?)?_cr%Y$8m4)%>l>m>pcNFa>b<;>v{kf z>wDxW9}GBK`AX{oolxiXI~#Y2Zm;2h*pRp~Td!NcTAfkeU> z{6-y9fBcB$02>BYJ04|X(!v5GWxG#vTW1gSzE5G{aTj(Ey4f3HsC!F{=9gHRmz34f zx;A!YV9wGGQjLsvuGxhE(h|$jIJgmw_sx%XGovtXm0qzc^)PQby7(#&nD^>sJk}vW z@DB31@Cw^fZ;%+KCb=zW0!ZeTNpha+0h(Q6^End1AX)#+fhZ1i-hLJbyH160KRPAC2(4*FrqSzqVs4WQZS$j=cIAjP!GX27Bch;CvqIaL%4&aj{8 z%5_5Ly(fNjq)CedI*r6hzZ<++<&DnUyw<2IE`$1b>mqfSVdVFn_Z0@`dQ$h6 z!$nA<@jg}0n6&}s-PFr`st)Ge7p16YAc3+v`;Iq$=v;{RF8)5hFjQTT#q+LpeaGne36XZP>gMm=c`)VBR5T zb6N(P9;5zT{@KHy`ItHxtU&X;ac3#31Ml!h{BYL4^Z!48{?z;nc>dQS>p?{q9slV; zjw^WN(0b5U*?lfY;Q?t)LEXwmxCa51M7o!759)rz-N1C(L_9)86j^%$qy6 zLnRI7eJ+bTD2W*!29lSe;v0(9Q@ zwjB`6nB|20k+?Rs<3&;-=)4_0-v*4;P#^C~qz*fb{EUaIQ|F#?0MA`K+P_t?c{A;J zndSoXF1qOzNXLWyfHYm7)Lfg^Et=;|X&p?q`sRxx(ZnxEX_E0SRFrik@ebQuE{n!{ zP%r0oEX@1n)w+)m%v*KdUP1%r{X28US?W0sI{T`=maxwk{Nz&|aW|a++#d3hgadeB z9bhfC)guI)$Kh2gr;nj_Z<|^B=P3{;l!U|unyszj=0)eN-P|*0)JA>0Es#1iG4h*e zdB<9Ki4&ZU?@DUhgv~puJeR$V9uH|H%x&TJ!tUO3x(*%X7PS9@bc0=#)lo3@dcF1V zQuo#%H#nbnh{zlFSYUexe0ggw;F?5c9u8U~vCK~3 zjt`LPeCM5II{|Lw1+lWU1%uDdKEYeAJEQWhJj8tRYYZpUkHnR1Ns{pS zc?@+CzVP`zH}4zj<6Vx_k%o~UKBMaLKr;tejo&A__+Q|Cms3%?T(BAS=R(??Tn#Y6 z@r|(3{D5@i1Z8#P9N5r$I&SImmO2^lye|^RNWAUEbT*^$cIj8rt%iBm)xU(u&)$Me zQ~M5j;2=DQ^0kzeK7davdRcABP^Z7P9@1JTHd8Y`}$9o%6$1FyE?wc8Ig>Y~Jmj1B^MD|7n_?LT{KNMRjm>nxSv+gtuU|0gv#D*h|HgWN^dgGwWEnMplp zQjl>wS`P}SigkaTP@>g&UU=mrc!{00-(|2Jz6Yt9u%+N9OBCc}_iXvxT7TfM>jmzK z&;;$RKP&@CFg=f*&0}_6u`0VTK zi!?tVX;N6nt`g4A{eeq6NL@1CB|&4pB;JLFFO<-Dvs7COeusJAV90TQ2=i`NXrC#A z?;xFA?wK9Y5ebDio8!xW`++Pr-FI%16X09j^txEDUhs2pIjg+SAEaJ~5;i&5km2N;Auk+9wso41;M zz1^ZQ9x^TCbxR{)pCHjODBWf&zD)DHDXpVpmu&0#zfX|vB;$Qc@No%=_l+G{ifFup zT&!4G;2k6@q5OFh%$w0vI`t3yc*|7fyypR2BqY!?8mcwm2O{ZKj5BSW0NW-%TzIG1 z3*HSbuA8zA0jRxa(-ascQDg?BsY~s(8MduyZ{$_ZbiyL}?#N8d!n+Uk) zhTgq1BIQKbMNwCS|E=wzKT^jmMt%u_Z$nE9;byNEcx9`U0 zUAr$RrcDA53GB0RG?c>Ld(#aWBy8iCp#9Cs7s~2LUG|`p<@Uel|Npc%YW@X0|Lc+U zpgWz>g~T4D$Q9$n>*7R*)`O%uHl4792c+I_hvi$~9^`Lj!m$^A#ZD4`NcWB>(GVBM zUbe`OK0wgt`|sq*aS+gQ$7wq01z?TnbS|3;0^ed-oMd;P&;Ku*;^%KB^FX6WoagUM zWBskiQJ0eSp9P1$t5RPN!XtI?V&oU6A9MCi5eEof?=O*-i`|2EH5r6^+4VrpwdN5E zK~GVCE+l$yZE6MeAMc|19VD+EWpx}BDYfV>&mavRMB|H#oaod1oJ*oTKxVo%=@^O(3B_4JLy9E$Nd`7(7;%`#Fb88 zu#o>#tAP=|y@mJwkBluZfXSG9p;KKDI4;j(ds+*92g#Rdi4&*ifn1O{`WM$v^fRDe zz3r2TTQFCrKHfY?9e9lVczY5)ZcF0;9n!eNo|mwBAH8(TFOJXyjXMo{@7#lZKq_}2 z@r=4Q?cd&#c#yI>(vI4O{rR?ZK)Q#F_wCg;)k)pkRd!Oh1<9W|{KEL}P*4?_huZwTjUe{i0?-L0A@K(C;{z@zS_SR<8LIyAz z0euLO7v}Ns0rj!|yMmZzftG54rtI%`VAHLkWuM+aVA~-ZYRiPoTUKL7@N@$wWQm)X zVVJgFDj)gw)}b+wY;%1%=p0~cAiaHW+OFMnG-}K^2?Te1XlT@|RfdSztY!%dFY<4hW3)-03|K3`DK1 z?j8t3UYx{uQ~9NRQqRcW*IUCNdvy6(N7#YQ*KS+(O+tUjJ|ZkMF%m`YXJG zJV;Q39!51?#P|Pu)2wKbYS4in=TpZL;TNRs*&h4~u0eHO8*i(@E6AgM92Z|$L_tr_ zX!;)a@C4ZveT;ja&j2&Ym8l%pPH;hc|E-jw5Rjpp$leg?0U`ZtZYphx`c}mY;pfR= z9+)h6dLcFf^Mbbver1y0E%p*z9#bgsO>wQyY%1Ue->hzKvu;PPK{S$`m{g57(2;`~ z=bD(B5PvTCpD%}d?P1y*r^vnr(G!`+6{q~+v+-*?NCpJFA6VSkh3BnxMwteQHy?A! ztzR&2>l~r>moV?)yMq>)@a?VdgU(SNGm#J*%S~IEVJ}eg#N9Hzbq1UXRA&P_JHhQ$ zyK?v85a8H;ujY{pGH(gVs=f+yUg$V(UcRSLmMlQ#edyPxVT$vl$6E}ShdxSt&Vm(h zzIJng!NHY}zn`P?PEB#VO|AI`>TjZY6j6bGi4D`-=NHVzN%p+M)QHQ2e()ZHVbxlL zbbx^O{a>xe@VsCC9;ZU$?K~Cb!VRw=DRR$A5%PYJJ)SVX7zuIRzZy*6-~~7@AKHrT zngJ)fTep;RcY^D!+UkkwA>jEXgSqa*?ugYpCUEk`sbC)HDQ;e8-ZJmQ5>Lb`6@K90 zp0^^T$2%IAM-WPUfu;ugc{;fOx8N^cl?Uj&gI`rVpDK9+h4k*#mh?v7L6SE$=sbTZ zmh5@c8WNX>!raG>3t?-#_Y?50>X>+g=grdgkP?aa7e!Y#1(>%HHa_?TLG|XT*w>u6 z5((MsQ$5;N8)ZS^H|EPDfOlKbN5!CfcL$N4o!I8uNW3NLz76hz zdAFZE-u`Fr4Zk>1-)ObGjERD3$7#1S#(RN#Rb49!lQZB;ZGM;k>xRfXe{=TtXMJ2yJZ_#&(sAldv>u4nyCnHzjkP-I_5W9Jc@&_;S3A(qV(Z8a zL~5JP8vZx--dc8V8GESTj`(xIuf16f)D((k_LBYPMEXJE@~9PD7dPu)@bCG5JOEPu z3fCYLf*Mp;b!P1aX@BF&dq$PJPnUul^p3BEx(9G8bKN_?i;)-?M)xIu~4mBSbctQHy>hg}%##+i2L zEd4W=100R0H3)N@>BsLpd$M0aVjdBhN2+z@`oFi>jR|-|Tctbjm)O>`V(@#oFqo5e zo)`xB>oGf@<2G*2?ym6nmsHbT<6+(@ihJ4q@OB9{lTyxC(GqevHLZI#2CAubKajk` z0q`D=oD(gY0S|T=)atT#f&DK>o_TBw2Dh>0A-vC#`~TXG&r=~DQ zh`+|2k$e1HJ4o*mTZ7AEJ4$>PjSnv?$#a8`T-GwZ^XMx`-4n}E+g944@*H*1X>Rle z2_y2Rz54zf`SX55TpoI!m!yJn)*7Tk1iWjRAMeBS{uMrpMdF>G9&_yq%=<1^o_jOQ zTd-wd@z3im*|Kk5&Mc3Hlmlg~JI0-WSszvR(efD}$4USB(qtz%Ga;=xBNPITOTBgq z+3pD;RVnI>-w&Qe@Im-_A^W8J3gP22Nb{-2q$XdfkzW5#iOb{HhyNU((6x@5(i_~s zV{5`d(MNRNpz)P1EzcXMR&>C;QEz} zm;QQONqW3RaCvB;#CLgRAd%mUA2{Br45ArD=k3ZOBF_)=?#-mL5lA4Sdb@375BZ5D z|LW~TWFECY_8xZU{=?glfcK+I!cXzMQ+9^aA@LTrnW}Grd21vcl>Eb6Q&R4;8hpH^ zciX*SlgcP)XnaU<;*2}sZCiObUONM#3Ysi_XLf={iuci{!a_lHd!IsI9Ww82%g@26 zJRfu)H*a_EWK&8IGVh~}+a2BVNsqS%E)O%5_)aV-zF*Gf2b>bv8%F<)y*JJSIz?{W zZHQMj{MD{It~<(ab2{1cen(^;6eiB??;0=v+yCPMkn&f!23Zi)plAA)!T1_fvTGX$ zQVn8AxN(FMu0h8Q3S`>h8boRMb?n#`6|GAaJ=^c@ii1i_8-8FyY(YwsSmGw184z=$ zB2SjK8||+rM0Ni}cL606F--G;OTC>e*mLI~;tNng6RO>u)|8MWn)seZK^cti^ zTpl(k@wwOW)ysr(gLU?*wO4h}`+tfe#jBa2?a-)#n1`P_`Uj+O`L{9%vmGJ(8uU4m zxIC1?6Z3B-tgRr;33xY(X0_pYZ_Q_5N8(-6-DJxT^G@47@RGs7^;zZe_ncY!E-0+@qUTRV+tj{T3HIgj4o~f?8F|$siO0qbPx5bfO#`U zPfOVvp!3E^oZYoG+llOXW0Z)@W7o!Qxh`ufNHYT7PnSy9J|OMS-CIuGAyy>b3g5q8 zQ-XPqsGWG!3iEE2OZ46Y^A_#)VW*gih1l3`40b2m0=HYLHd;|LfWqT$hWWiNpv!dF zTtg@j9QG;B)tEu%eL`CKIp2PM$QU>Q)~UKctGAC$ktZ-B*Lm zyV%m*u-}gKc&p;_C`5_R)PjfiMKl*UU3Oc!o&}w^-KgE-6wEv7`I5Z|6A{n<|ETDt z_n9So-WbMPMCIYU^7Fh;-rC~iFahuS{Eeb`-qs=^%t*Y2G@Ki(VcyT&TJ2uLytkk2 zes2QvW=W1PKPnRo9U8Zd$eFhTQgLJ5l9@9gBm1MbibEIRZs>b1rxOIipymUQUm@?k zwJ<#8Wzpw{PUGgaCz@o+Q6cyLuak`I?~all?zM9|0m_P|DV|4{{JXJ z4QkejUVH!lpB3aQnN561HK_K=zF#Q`Wm*cf(=Xq`HOP~(#r+n%f*iG;EpM)jhpO}* ze4AN13IeFdqpSDK0PhC}7azXv2ER@#HZs2O1COe)#dTj?5qFR#5;P3g9TbG{^E{k6 z>IG(zFR}Z79G>(3CWiR;{gdzi@Hb<)Jocc(#}ysOM4Qb8>KP7a&BUSCAhX`g3gxr# z{y)XK`JO9{s5R)=m&)j!-4kU04$^XW;_~Q{cRLi8x^{`RCg9z~9XE=<#OhuB&4a{S z``Jg2>oD)j4G)f%*T_$Z$^=M+q&2;tJ4ZX_<4J--nV>Ehs^uZ47N>*lJqXIHn==;P~vN& zH~rD}g$r!v@DJ-hgU&md{dA8E%scA(m!c2>BAy_P?5i;Tv_ST}F;qn65i6sn^!Ip+ z6#?&;L!SfjyfaU>a3k?9{(frZG0dAae(F#M%=;zfNqsK(?(O~~f!-?e@sRfJ(#D`n z8_?Y9T71}I2JCj7<1;(m4d(WhC9n(mgVQF|PpSU{@1;2IJ?sqv5PqJK!7JYN7m;~a zWIW9rV<$b{i?}>)pv33T;uIPBh6_YGyWFq$Lg)Qx=IW$TKs)qnjJbJp4mxk9GpzG^ zQ_f_+f?O?RAu10p+V**a?6vBBgn;)8=$9v+H&5twE+pPU&-1h1!n}R1+&cdT=53HK zclapG`+$fUR<9!t@)2iO=H{^l?9PQFG{xt!*=dlQg(ZwqfUZIdKD-rI0_sH4O;2yVpAYH)*_nm<3-IivFy z332?i7v|0UBKlWC77=%EmD68*4ESGg_f{;8xIA_j(8&C)-j)QspGU}b;(0%obK^wf z-E~jnU zACS&Hn&mHiBLOme7$oVo=?K`Rr8gZXI0H^-RaI-H_W+aOBNfIceF4WwiO$PT$PH3; z&U@#l%YqO)Zr(QWX1@hD}-h1+wE>yuvpkI%ytCBAsm=r`s$oWL}B;1Wv{dJXy& zH5NlP*9I-W>bYEh9eoE0Grd(OUt5dpSCE(~;_~p^z*=|*{tQx>_b~$A?F_nhc;2TE zeicIEZRs-fQ3d9GNHKh%6Xvbryv!v9^X8VdIHd2I0B!c3EQ#|y0xIP#*>t34z=Y1M z&Z1in@O-(aVN0Mdh<)wVwQ~b9?=!p17AI~BLil;CZWpcFrIC53{BnKWXFz(q@p&Ym z#Aop)j6>xl7s%l;?l6Ch&O21`%kJ;G?NHf@9;crt`U%qRRQKCSS8B+fw^bT(c?7S& zG}V>3_Ie9D0^Y5?LiTvxZi>$Zk$C6Yf2!4kdCRhM@crT4`Sw%SgFF>2n)^-FK@tg2 z@T;LW3Y|xQl9kk)y21>&A(#8wW_J&WV}D9>UD_AC5e>0DBaZwADNY9wC!XVi&|BO* zpr7m#0l%3-CJGe z!xOi%?vOq2GeqVgqV0Zc%isRrmVo!`;)6qY-s5pu0!X|wTev>h!MtxK>KeU=dB+dN zK2nBx*G0=QV_VKbFMiYNx;t8df>n81VYL~+_I`bQi*OGJaQ`~-%g7ga$I*`3OCs|Y zyqD);D=G;2;pTnaHorCX05b0kBX)_8Hl)X!AD72Dl=y^F51A>`a)EKH3uEzj(5ttv z*_jajJ?)Tc@y_1|3ZA0!#-!a7j{I6p_PmMCW6y&I*}wh24FT_#FlHG%?`m&nek9&s z8?BE7!MtZ)iJyH3^LAamEf@~>|1!f?%cmXBLZ9sIw*OGF1|Kv}8dHE7kkI{h;QN1klxAceSnt8(l&^T_Mhi~N8--*b)4{_>?& zjQY-xpk7WO-Vyy%JqMjP79jk{zSw9pjj z?(h+anQMh&BWx)I+|XB$JiERHc#86q{UugvH*tAfRHqEwUbxo(I}-5jq*~y{^FDp> zvjh_FF1k}iPhsAgb4TCz!n}D3g}a(y-dD4)_9(R{LUB8pi_3N!10H>;tHsOH!0TmS zDKpcs;_Ktb+9+)?y!6Mxs-lx6!9XG=bQl{2uq50`VNGtNWvSZv~ zFyCBz0#M9=Z+@KH*=c$~S^B{d(G9+!ybJv7@c#C(JCw_)`3+?pS)&uk2Rkx|+ zG0fZOn^;qYP$Fde6?_RbGzWBLa=|0m8PI&n+GF<~^Vj zP*TPt3{l|bmD5TxPCZ2Cy(&I^xb7n9@$Sdvv5XSmR+SqY-K#jk>aOvm=y~)83F`By zSITaK{4-SSMdZ+V7hTNix7x-;_6?H!CF1fplQPb>FKdmr0|D<2?-&2{|8mThqDZ_M zbeDPQ;Qn9d3%hqW%p1S=MoX;}*m^wy@(pEN7-&2K0#*tvb2w(eWzIYKdmr|IFz#Bq zoMd0HaZizee+n{h4No%+#f%W7h?|!e$J<$(hs=AEj-T17d!)yED=v=>DDl~Of8;$b z3g6!HmU`VchR%C$B!%Zun78elixLSF4d}PGm|e!{gRhbQ{y!6uc`%ky$-|2iX1Ix= zp}2-&7H80=v!{-Nzy0?=r1lel`~Q;!HE2Le;357J%NNNZhg5?~QoX!)!k5^D+jjSc z;2Naxky7_Uwu+WZS?-dJMG_QNAJ=o~mJA5}yzy>z!!)>JwG_%g)dxBSdQNgH`T!4! z8=a9^$Tetu<9czLa1rPvZXWfQC>?VaU&McFd2`--zI+pfNbScviOVA!CBA@xtlq>0 z4zP^*pfkN6eFb?@#UMVSq!oHiqo8NUir)WYc-(&O{4GfSD@bDVpc-7S{I@}JBjDYS zVGhFc9=bUpgTxyv?Ym?O^WK+kIXnpSe*D7caYv4dR?3{Sh=O?%ly~S!`<5zIP?CA* z!ReN1z`LA0I5N-+?)3)mdZp$ACP%ZH&X^(dmR+lD#Zu-*rex7e%; z=OPp7U1H^Mc?hD!cQoynd=bO}ZtkV{GQJ6&cY5ukua!J)(9%nGy|9hwD@YOTubjJO zvdEry;x6LyD7LLr();@asVf2R-scvMc;38Cx7Q=_&Po+H<_7aFnzUg1!@F$Pi|2M1 zRJ87l=VhvxB|)}SC2yxfwSa3M#YKbn(_pJtYp&VDUf_Q?NJaCY4{)$QVXUly%saN} zeb7+}5y%cVZ{<;H{HIuC-tN0iBTtBu9&dae&M5IUhB~$$<>dtFf~pxlis-y0sEr!3 zVcu6SW!v4EB4P!3*@$gI?h@Ja#^e#1$7YpV(toSB3jyz*)D7qGyce#7OC#}?s7)9T zhk0kV*JusEyk*QIzqsbAXcgp&mPD8)K`+c+44kvr1NuIld%H3)4c>=`nXb#~1zQ&y zmZad%1r(DMYsbnW^XBBqF=hHG42j_8x!swLPBcO0UC(4xRj)>Ryg6`rJVJ@jcjwnq z> z|D6eVciVGI;dzhI9$bgSn|8r6CL89xvY_wX5A%NX?lY%4ygAV*#}K3p^VZ5gpx57Y z5GZ6Vwj@kU1Dk&AMmg_Za5E!c^-h5g5D(GStky#2t=x3?a>#pONEA1(^R`^WPjzJ8 zA{#mG(;Jc=Z+sqnDDl0FU49UAfD;5~rd97FV()Dydx%gL%sYgAxY}O(J!&ZE*I`iro4uH!(HZ;_MxBue{ycrZMc6c*{>k4CKH#3tBa`Rk(9Lq z(q06-M?R(h^YNBvmfkBO@#Yn{eR&$@y+ucYwqj@o`4aoWTG4&)W>F{$H}64*{@x=~ z$hWsdEHMM?tx1n}GcFGq20K0o z1|ON+tVMgS=(Qp9{1(Phe}D0 z_Y^J=!owdVBT>rk0lJlyrk| zOVKFg`+gLecL*iV6zdS_@s7jg;e!(2_veo{1{ZJuUyR$aQEPPG65T@8+u^;p=j$lv zwjMyQ-rxMaj-}|akv;E>0OImU@{7+ftp4}>|Np(=Cb9n(?*9V_YS1U~*Z;i#k1?M@ z4XFnG(2pE(Ur;Xj-1BG;f(9}eF>Aua}S;pS;RYF#+=47vYbR`+wTjuaue z{r@mr9!n_kRoW@F>$q|N>I3z>R|Ofh(3I?LD8Cf>;T6OZ9Q`C-2)+Lwkg$n+5l;U7 zzkwKWd6YjMbNCpu*8lqx@SYsMUx>fNI=^e%jKo{fe|TdA%-d<+(|Ho+ZRc?>rVr+A zbHK5#TC`5~!#}MGyL%kE3x50bwtJBX(k9P(xkG&}Ijj~K0 z-28}T@Ae92SH;3J7f}qX4^UO==4bsmRC$7XCaItN71kP z15m7(qQtBCX}~`ALZJI|ABgzPp_H!d4b=RmTxI{m<1N zcovHbq7W5so_Bm5bABo^?;;hIw+RxY*Z<4l^0Ic zn}t7Xh7NVK7hV4R0&!3BpEdj~6-hd_TJqojze8LeIl1?O_29d=|DONIKBZQ6dKn9e zsoZ(c(`5tAzyI=5asM>XzwduPW3V6i{IJw$Df0wDK00mXrpOOSOSkFPm5GT#0l0a} z>G@CQs*!6@^?^Jw)o(&1*Z<4n@~A?IuktaQ<6gKyQoO0>t)7V9An`YBTGU$C1m&|> zM4Jns_y0P}A7!pCsFD38R`MHhc??JouV_ZC_5UFRyk`fKRq&Tsqw*&jNW6o--JRxv zd1rTz&QHU<1-5v4N5Z`CJKGqXT#bc3H_EYrk)u%Uc{wvqlW7p_B(j=Z-w$M$ek8KAO;QN<{bHas5lPK}E`)*EH z8DRrh4)5H=Gw8f`eN?JC4fFo4o|GopiQfNXu4l~GD3E{uk0~N9kA6S*N5B4_{|_eM zJySZgi04helCl+vcYc`wwLHvwUVf484{zP``zd2!-k(gIedaXdptjMsHeai)p}b!f z)l)~NL9%nvvDCtTU~y1`M(eRBNbTKeo4V+X$Z=f$lt9BrQ78pB@4k=Tqjm{o-VD46 z=NeT>kM}e#4|&(4s>lV=a|AMI^&v&L} zWM92UJ`tBkt8_suSNdB2A4I@=I{3#wFDI(hJ-!8rcf_^q%{yV9Z-0IU5&eG-XG5aM|n?J$4A@DUO3FfW;K6@&#I}XatxYoGgyd`uv@b&o!*J;oq`$9X^u^;f4 zpUQIC8#SK~dj%yp^En;uB%=RMmn%t~P$m1vTQEfCF+#t=CH%s_ z{Xgk8{RELkA4#Jis6k(;W)I-|{|0{(TBI7}z|qNkA+Agd`o1}F0j@#sTHl>gfKQN0 zKiKhP5X3^ICjF&~KaWFP3^y)YNKb>jmqAzeog9FlkUYLg(#sQ6abz3MT|urv&xWEl zDa?vNcX0Du><#Bd$zBy#~vMlaa{0-3y+vroR(|cH!o+T`+IzID^bv^hSqQgbeBN_QvHQ zgc6@jgSyeVKz7g+5YiU=0iE~M^nS<4fEQ48aj-~B2oWnt{}%IROL?;AjqxEe4+r0M z!#3Q1KHlOC0q?~tj%$y%{JDE;Cp1Te#QViJD$}Ph@4`DFrJrHmwTsgNn_=Egw5?j5 zfw9nq;neMl&h}7H#Idbio2P+B_?CDF^#QPHi!lA}VNc*dnYnf45c2+ikwNw9x_U9_ z7;c`^C*|OjkI1|m+1q{H_LCm(o47olpv32NPRJnLh#goJhO=FGhR)kYMsMs?@=K@@ zgf3g_px?d4oXGnb(O*UWyotl3I$mKfAhfhCZonLwx2I~?lj2KakN|F8IIrLK_GDz< z4zIlhX5n{r68c(t18Wm28rnZ zqx-H=w%j5A{r@Q9^2qCvt&4d4Z~sp!{|^3R9B_j~OHhM;GM@CtUt+yV^qG)q&;}Fz zi)wHU8r&D8`wgx^;rml4YTtVLsgd5uaIkyxqPy(fSd$$9yc#{)9EF1w?M>8$uyg(lHM5U)gVh;9+N2X znOe@ZZvDjuL=4Zl3~pu8`j5Xe_z&C5Px$mCG(xlXnir|*h4;pp(Sq zkxK1z>i)I0{-1_`_ezV#+DGjExx~hdi7+DZHdDN|R}bd>a^cS5uQ2Z^lQVUn;1y&o zze61TcnmaDZn;COz!}Oaod535I1L80dohA-1E8X$hU;{PC+MH&I5*UZ%v*hAuI{ja z1oR#^uSG@Gs&+RrZ?7K%4BI(K?*!>qTplM;;#=3`(7UY54h9mw76mAw^R60h3{pGS z2)+B6es^Fi`u=~I_a!O&Y!0$-kitBP%R{4S(1g2ejW;y`@9*i7*YMTb-hK#+#5;K- z9qUn;cXLYa@h>p%by{}oW8k~D{5xXjyA@-huXjdYTbG`IhWeF1cd$=`rPDsyPpbz& zk;1ew{2A;ZYc61$7A5itQX}1Cw>=pppj6yEQyv*FMipely|45MF z;jiI;?%q-n@Lo=?$;0zzfBT9ai8oeoo24hr`}e(+h$RBvVdh*iTFK&20&db4+(VM81G8^ zP<4K?=Z$eEGLPK->$4sH+`UbsB;fr`RqLO#w^Jvh>5zCEoo|ndhIv1v6*;{~!29{9 zxLdbmW1-axw+3Y}j?nCd3geri(}1c@Smayu0FW9g9#wYr1e9sdfoL6DX=u9Rqbms2zC$D1}#7K0JKf+D>Bl^m)L`QXzWL^6438gf9IVl?tz2{ zkXMkgH`N|k8k1fPGQ{N(g%aOw?E0QsJ2qhaO!OW{GJEMdDSuah9f>zpRQ>2U%vD1=G9>%{U!2H1qA#&jJ0|^kyd@3$U%V}TXBa=n z^R9K6U`66BxhE3y1Ll3&<*e8W%)4^e4#nJaDq88~?HpI?qoE(`ICTtEyrEl7=`CIh zQ(&Mm*2hb35Om3;wq2ux&;S3zepcZ{=A9W+4|U9mL-DwICL!}>OMb|_S5BKy+`d72 zyt8n5d_{>bT~;cG-Wh%(D6uwr(jJ|6B!_QwAIw|p*7PYaZS=dh7_W4?`Kt%Wo;Svu zxIFBlnQZOy*KTjo6YyR=+FOk0%}a5E1&O!MjZLN}XhiidL4{ z?~bbnVj%nG18-8NJfNG0tnTevo&tI_rYFyE4}uA+>a%CEJ%P6FpcNAa`S#Y)6CoKE zh7yn_Zr*oUVT|NFGVh0lZHJk1Nw5F6#pO|j5})fjslDRg*}yBq+xu#b(RmyDaet>; z-v}M>zkV}28@)k#p!(bFx0edpFHSBh6PE{8=7R72oHgEb1iXLA4j#kvey!!tjKupx z;v7a2=6zFEZObyuyM5!%lrETej)6hnY(Nb3^yZnUOET_|>sF(Rg4HP?Y7@;8zd8UW zv;2=W7kYxC9UE+#hmfnc_pu*U5gHOu9&Vnd0qt)3Qe@t5e(dx8^@#L%`{MF=jS`=A z-h;#6wy}fxep&ao`_Os2sO~%wqXbI z;r?IBy=wEjlYph_$MmC1$h@K4dfu2f;t(BfUUkmkZhlK--cfc2<^?OH$GaYvMZ{d=R{5wdTPILe93Lu*}+ zW6$6IpM`)oO|-Zwp7#lcHf|)|ylF-8SupQ!G2?W<;T2@=mm%jVnD@Sk?CKb76yz;v z87<};06}x*8S3w+K=X2Z`pmgOAhD@!PXFUcz|VR?t0^3rH&3~peOIG6#DSZ)A|~c! z#E;B7@cM1rA7X+eSH1agdHAEm_d1~LQ14|{@GzwEs#*&=@BHV@nhneK(4+3+n+v@} zRPX*wQ}GNtvgeKIB`y!9YX6XLg=-BGGXZaE{|#z*-eHJ;cz1vc>VbFhUD0*8)$>DTz&!34LM z&7mY@-eGj}<0l@%Z@I(G`=LYCw&NS}2C3Fo5fG|Rdb}fWdF()mPk(QU7b6cFn8}lu zxcvZ~chg<-D-Ik_q5ig~cS4qlXpnphL{3LSWY4?Glej$mSkweDp=-RE2zXN|ROjP) zv+eWaMB;re>SlC zFb`g>pmiPuhYwk>s>*l(>Ikh`{VN9K#9-mj!KwDAsf(Fpt~@B1D*G2pGB=3Fz*ZFYM+*hh&bL-)TQPTr$_#4 z@2f=Sv3ljnzx_WEy*DXLf%|`Mf*Qo!l`4m?K@*9xB1km|!^-iT39dn=Vy*17aDx=t z_cl;58b1F&I=ud#Uj(H2UU#(pa3I8Z=8@yx+fyKs-9ZCOKLl=L)K(Sv-9V)OXK(6L zPKY%_lma?uOe+DM!Odf@T<2nFgIt3ox_DGx_wytEegD6H)Ka)S#8Kkob$nZ+@5=@# zH}x~=>}A$Mi?{z~+(pa@c$e+cI=#b1M64k75}yPmb&!1x3L`R)iUUsVoj2Alv0Mba znFDDRr@^xq50-t zO;@U>K(a%4VCt_yAoJ;Mf&!l#5Se)2k$w=FcbqOne3C6h67Xh>j92_{fRz>E$k@hxK z-E(mW;O6x&76XHB`5+fW&)Ikn6-A znD?)DKdGo--cLR`EF6x3Urx-;X8d(L0$Ms;JYZQ82weyd;n`O|1!CCM&ii)3n-fLR zESL&6aO&RC*og^b-c7PKN$%z1P!Mk3@_ELxCSBy}Exi5OfhJ1QyL;P;%L6UGvwnsT zQ}WmVo&BM-F>Z9;`O-k{i;T!PohL*bZ_y0(4-a`u_PoQ0%tPvap{!}iTJ>fp z;Em-|a=`P(%Aepz;vGG|i}MJ~o1Rgaf)eI^N6EeJ3(ULD>zGB1U?kL6=efkz6bL!T zxAZ4Hn*xUKIHqZy4T5dP3YQw+xdFA}JSEyWWZw2lkB{|dibI=l^D5e~bmt_Id8eCo zd>7*HJEJka9vJ%9Swr6D%(J@sd}2@N`L`?I!c*6`ljrwB?0aVvD*R`(@0c2y~p z{rmr35Sd5eLZOcme0%HP^Z#gF90~k6-2V#@)F94hTj%jLC{>473aJL&x$tnTGzLCF znyjPB2-hH|;hc;0a1ELcEx*=*iGU2-`_hw&{2^?wC(nlLDNuJ}BxQ8-5SU;$jw^C; z10`ENYTrDAe2ZP%dv#&kkOXucH}C8xkpn%LV1V=!+cuJsoy<*oHAn}S2U>j5{t6vw zob2Gx$nE^0^XN55x>`ZIqPPwc@%3b0c>D_S=Ys!vUA>qQF!^zo?E8NMBJ;4!7<_CW zy>>vFpMW<|g^w1VdFv{~NsT>UY@b=ArlhpWi9l{A?d3 zd)^I1=0W{@+N^u+1?g#g1iaZ@W%cm9hacC7Bk@-DQCi;t^X`2;DvgDC$DRHVstEHw zmgF0kt{efm<))TQng>8kqZ9RZ`BQ)^PfycLatQ2>o2Z*-aRZenv2DUp$h_Abd{v-Y zApzaS&2zjWH(A|@yn@`u7FuhqL3+GpaCxA`*VI%NZxg}>eqWU{ZB0P0-cNTrh<}8u zH~dk#k9P?W(f>OfJ+RrGO^)nh|pKuK#&(Yq=@u@&16zqYfp$Z`5Dh zf>hbS-XC|eIi1jXAJ2XNoRO~{TDU=%)K-PwAYnFzmX7T{N%s9ev3XcA=}I#EeK`>i z0dH1Xc4vI`?wvCdMdJNpm>;tO^Zpd=#!CnD#_zrH-^w^iSMONZJlfY8(5l%S~W06=Y7&?!>@+p_0U7p(_Y>BMDX6ITzW*omh7u{ z7?F8Ij?Ne9z#mTZZ~u?)zDW2h-2aOb)FA%;q+R$L#5^r7hg5^sB~;ws57!{!ErkJW za1FZfH8O1sUP01UPy2oj4Tq@DNuLfs=Lc=C_?ddJ5~Kt#K!TTywwiyO$*wPeGS4W6PZWD%xLei zwe$ZX1ibmuH1^~ak=4CAvj*4wU zzQi6pS3ec>lk|8S;_@&=iH~NV)$7SfR&Z@r&fj?$optdf?z4e0z6lNMdoD!qUWDnz(`T@&F6K|NJPad==@rf4EVq$dJz{7QWocmkQc~>f~>w8xA7|I!4-L-y&h}&Bu{3buI*pfYO z%n*@zur6Q19d8jN;LXkYOc2joyuxT55^t>4Ez$EZZ+SH~Ehd1V?hO8(G-rlIwVGGn?nO4Z+^LlQ$2CWadZQKbz|9@j+&OR5xaHzxh$i~kp{*dEQrO9RY zDImAus9ize5J=xUBKSzk1!(h@r9MtazQnTb{>{uHEeUPM&C7erwtcl0xdx@*%5B{c zM|uqsJ1&n5l=x(4C5?in*g&LO+lEv%7A-U|`Yqbm%Ff=0qOfY;xpmR+LFSpB*>xOR zNA@*nvpI2jJl#G?Hy*dvAW0JN7O6b&&ntG?kFP2s@orZ>rHp|uv0g#ix4B^69(z)x zFT=d0l&zT_%7jA;@#V9ZPx?bFT&oXbyr;mPS04iJc@KfCKvnxYLM~uWPt{TT6Ue;T zW7T3ysU#sC+&qCTNlTA>k$H>lWN!KyOM1LHaCu0e#HThEk;*K^4o=nQsr_D$&O1w5Rep0|Jnae3Uhpx9^> zvvzt*oPf8G4E=pP?~9%x@<_bzYt&gu!@Rp?$J01q-tp|?uD@d8x3^ePOiSp8L+Zcz zjgN8oL+WikZg+yFz`}`ppYNX-0@VBH&?elx=kL-z zUVcID|1~}v#VnSR9&dkK9-1iewN+!;^Zz%9%p*GWg@6?NaN@uHKUx<@0)Gzo z|FQ%%Xx)9z&G<`fVhNoZQVp8ZdwBUA-2bm+XetQ8HAwb*>rPkr4N_$j>%N4234_jO z`%ZcX2SPPXhcC5RPXVKcR1{2^L!j!@en}4j7qGWZSD~*IxdzF3l~RBIDG6!g<}s}_ z8ES?hpZ~uuswy4ZLV7i511=A=_-qs}IAyuAf!FTS>Nm2`YtYT$q`soQdyqi9{FMXn z=SZVTV%fgs30HU%*>8|;Ng^%}<+x)D+R1DEzYGCysjzdlc;3uM-)=_Ytz6-LDIexN z5Xi(M0Q2s7ZQ*MS^ESK%e9M1^K~b)^_umo>g!c6>h)deRZ;*x(-lQZCfsxBzvUf#X zfM4mhY~O5T-p1VL9#4!(LY}yJy0OXp-TKJ9&#|WHeds1V-iL8{B%#FDgR#GoT>?KK zeN3g?D+--=E=x{D8_c_a^3@=d9uYf8-%x_ zFa<7_)ReKD9RgSLRCg<%a{)7!`{^Wfk#~^zcUYc!|5g(Eh@02BOMld%1(|pCTxzNC zEa~wU#N}}xCB8!H>bNQg`02P1WZ7d3$TU z^i?|-ws2_g=Zl{-WCEa>bH^-RJ5GVx-mHbQT1xRd9+)?N?=AlFQ6D;yaA>LS5Hm%*Kh&U6byeDR3VgKr&A57c2;@kO?2m^} zZyi5mAa@}QnfJ-YxZ&GXl8_y49)-l48=Vi4d0(BXnp-bHdb~Ywd7#CYeB9$;lOH?S zR_4ngun(R0L9G>6Bl+YoDd-t) zp5rzX5fi%*#6I^&>HMpjLeg77j^Oe@i?62jQtk;eb`W)IMr*1My#_gMbg(E^xeJM@ zKH5}Thkl6-Gn!k^+eQ8lNMquN%OipR(XYkZYyH0h0dG0)zVG-;tU^J91`=;ql}TY8 zm^YNUO|fI z8@7DDOnSWWd7#Bdccv_}=oLG-`8YGbr~#dK1m=o=EX@1Nwe5;ccZk>^WlL%;9yB3) z-WWY1^T-*s%Km%2Wdi|k8MdTkJnv13wp$Q+XW6}Tf_bZ6D?K6%^LC~<$m;?hZ#h0+ zdTs7w7_>L1i^aw+2-@QEiT9Y<6nJX)RA}h<$`1V$AYVzaExiIKXVOhUWb09Ry&pVr8IR#vgv+c9FFa#1d zKay3HZ~;NTMbnkvAy;qBXO>&#xuqa)+`JJjdh?`4WZprL|52I-(&N1imj_yW!W&KG zjw!*s@72esUqk1;o1s#VTjL(2J=&u^a1XtDhecmyi?aM*@ce%zae18E6-sp(e*XW@ zNufciIt=Rq>j&2NtS?v}vX-)5W=&y@VD)7^!D`N`$GVMGkyVV9gO!@)E6XHH4@)yk zEz2#I0+tMx7?wa57ZxiP0~Tc#DHa|Udgc}8Y32duHs&YHmCQxVIm~C7Lz&%~ZJ7@- z?_ySCmSGlPW@1`p`ph)K^p@!vQ#I2Krd+0T40jl=GGsBtF$6QXF&t$uWYA{V%plFc z$H0L7iJip`Vc%dIuvOS%>;-Hh_B7TLdkkxW)x~bX%3+1DELaTv0{sX2_w+C5AJUi7 zU#3r?kD&LZKS6I!uSdU)UXfmmo`as6?kn9ST@PI|T`k=$x&pckx){1ZIu|-CIs-Z_ zI%PU3IvzTD+7;Sq+5y@&+9$M?v_-Tzv}b8UY29gUX%ErvqE(}np%tKIqFJT+Ofy3B zmgX5vHO&p0T$*z?iGn5k$fc?+2>^ZY)(z^33wSN0@UVw3Ts%bVZ1V9()4xpSJH*d+YuV#|UCHW5F% zknuYbn}8pk*FU=+dlo;+sZeFX#^Xm>(+6s>arjZ@!^;?KEPj-6;gTgb20u#ATxdt@hx2w}PvA!&lC6SabZyDrrUmYla^kG3ijp zn&L;6lEdGyhw&rxg&h-E6a2_*^u!|87(X&inX|?o!jBF+{tU+&;YTKx>s7FZ_>nRF zVh#2neq{82*t_#^D!2Y&;JZXN86!hv-o}zysN0l8q$CQNZDW}$b2N%%PDmQ0A}JM8 zE1Hyuj--+ZQIayH6z|&3zR$Ja_j>Q=-oL+|y?@s^|2)2@b)D9?KF{}F>t5?#t2c2o z(Hf0x%7=~-tpMwXwDTg3HfWO3PyKr~0A^&!XZ z5!a!S`BvL0q8S>kd)4P5H-zA1yLN0D4+8a#n6cI^)qoP z8d1(6CW@jF<=9rD2pUmNxg-js5#>-oq7WKU&QK#RK_kj-Mnpk0qFnw$6hI@&T^Yp1 zXhgYMfXI(Vl#|$rd}#EzV_1n;fkuxqZd(wqqR~U2fTP56Gu7ABrUqgzYceiP54(TzbF4&oU!s=TXvgII({*E7AFh^Nu$nk&a0 zVj&t;IK+J>ox#B4Mw_I-GUn1x2?wchR^W}?wK?s;Lv3^Y3P_M{6j9gT|4 zzLq7Xp%LYVYa%ZiQ7!}~@}Lpr{!}728d0vBByyn<<#s;eA~c#e?V>>BL?c4O(`!Ty zYP4-O)Aliuh(4=qCz;(RokWcg}EoQFo^@4KCe1T-2eBuM#H7uW9+}s=u6~uKKoBJ8uB^Y&OU`kpQV~**ngnW;Ky5M*(cFx zpr+yp`ve+&%<-;dA4j8pC(lIoF*NF1<2=ni3dhL*%pM5;Wc1;4Mjrcjv}MoT9&`3@ zXw-dZa)NyXjoyb;*sy;^qb^y|8uno{dPm^e%l-w8-ag(&W*+S z1Nalf{uYfMCn&vQe}hJkEVoCpzeb~n64@>69cXlayfm8q6&lqKUG-ycN29tTRSEW& zXmsypTsV6h8i7@$zu5o!cmF>V%<|y+zXr`aNXn>&@(z-+{;$Eli4E%=gDk$Ec+BLiH|BYLt97^)T6W6t3fM&~wCYB68qya3a(1L5d$- zLsuU8hTRP&MRV)_>NLD5!*rDQ5)K(wEZ!}p=9PVrca!>2q8#MC@|%-!#y$apkEld}Yy6EeJ4}a=9YHrh_1$j7EPY=mPn8cMeEpHV$sTOpeFGJD^IT-X zVrsim_TPxQKQ`|rv*Bt3ZyAsG2WlQdIQ`4ZStQz(&Woh>*iEhA#pfOSo}l%d$hBsy2iSm|9{KA68TjQg-*AK{B zshjhg4CKB0$I~X81P#Lu)O{Yv+ zwGT2Dm84ol#^(L>mer+A=CWXz+HS?T;|_lWoA>ye(nm8N7?1Z8Y913f{o8jy`E9cU zA98B9WiN>XpSNlF=`VqD6~N7l827D)j?Y^@MdW*aGiUk*Qo?6C^N{afNj)HKB@J)N zixiaiCdUW!v3LhZ>56l}1ya$krmv(S@3&VUlZ_HJ3~!$GUeI404@RvVG(rTUfRK6a zL9g{g$g3>X@%=ZuktaU7$mcsgNYj-a1+3e!dAFSOH(jF+Hz!it%@{^4N)o{4{rU0G zI?iFnFR!n?Qfg}dypbt7Rns*Z1d>4PX{^{ILKWAo1Ltp4CC zE(>I+?f4Ym1sr6@=6xCrUDW)=c)Za(@cMUzthf%@&W8*eX&!$tj?epfd5y%Aj0$kF zs)htc{>G$nCcIBCHye zZXO>J21k%d$%Kc>umjfeq*c+q|vqnqCE@iwuNYAKw z9Kq?|q^0^~4*bMU<0CI=I0%0Pxj#iGR7dtQnA)D!6v0l%H%I|(hjx`bW&R1$%wP27 zv39qS*54mU>(KC~EcT(iXQl->v3SdQ>q{SkynO<*&nrRR9oHQzNbvO*@2W}jk%w{M zaLS%t=8}=1wZJg{vF;G^FsXMYx3wGj^xh(~(#99Dw9wu>b`X1uon`s^+;{SFU@h9N zdB?@mtkIaCw=8;88}FdVc)ZtB^WetmU)j>YYI|>9q~9!}MsFKF?`!TajvWyz1t(K& zWj%i3?;s^?U2VUo-jV4?kc3JDy7G`!Ws?c5oEt%E)9|LOUZcD}7xojec-yTy^(Yte z&JcWkND=bB=dQ)O9r6yjBC>yoGakr*!6m=_BSG}!<&?8}L&$X2lld9V-N>u=idA8D zzR1JiD}e^l*u2#`74-c@<-k2^J6W=t*1`AK)mt~Iy|Mu3^ziRp_qhB&T?-339@^G@B;duOMZiBQI z4R6YJ43szN$aYNL76yGMFGJpE-wfwUKXJGK@^-cR;j_{p9$0jgS4%&P1RY3V zQk}sN5>@@&UZSxZNlh``Ss&z!kX_m~?>UamJE8iomnR@^H)^{xX4)r;JF$7^SFYDg zwr4!v@zgv{;q-5#r|*Y-M|qKk$49sBS&h&8lCGtDA>_Tj)Aua77N0la^VtJY-5;5r zH(}-sU3o}OW~MpbOrl(Gp-ID=vcCxBJrx(Z5UYA?>sYq~$U9|eg^4`mjjp{#w_P!9 z4vz;bt)2?~P>ljN8`TrHB0~tb{sphWN8N~fRd#(>m@l%$Z1nJgBiOuG-CHWKh$siF zsqMTnw!HJchRu6H?Zfv1evHRkmzoC~PXAQxHwJKd@gd@J4{fbh;PW;+RU;GgryOvM zHSa08fj>Ag9UL62Toc6fWABw@`tlfzJKimnnECJde~dB1|IfXEHE1VVoFB0`=5(ix&A-Et!hOoFILfFVTE^ zhVg39Pih_`IQ`qYTTeT~krx?|w%y2b9=`_J^gmcOnO_V9&HwC@PsINQi7*^_>DYW5 zrmsPSuk_`S_*^1c^Y0U+3}|>$whW`ZgAQu)Ve!7{J1wjXc^8q()~$rRgLI_HJ#YjW zt>|eN*%1qL7nkcEk=YCOmG}7bsSY8IwJ+~&>FGx7Qw257zxG9>E|LlhUSso~Uia=* zYzPU6Q`@->uwPv`jLlnivO>*aDdQcn^NX5?JWl_D*Ho~2oaaT7D`%xRa`1VJJU_W` zo6H5!?td`HHVFUqmZwWz??c-%rsuuKjlMj752u7Hz)$R8_1351P1ysF^5zTg;KAY@ z5c0WoHRK)nI8j~|^4{2~dhQ*3d#gGB%^DSpIB?ll_1BsL_<{5rveL^-s*KKd91~ z$7CogWd#ZH)}!G~`KSZs9pZO}8;kernw_sVLf&V(<^h4?|?CLGU)~G{zF9(9C?KYURyq~>* z&HHktfkSi&;|)&GJj!tTCnMF)Ar!!iH2rxOQ5BER`!Xl#1z+ez;3aWq(_Jq7-CG2W zKe}$A9`wR~{F3nRRafbJcql4R6X8%mZ-LK- zYFjMizIeR+{56MA(I_TuwCMe_Q2 zQ|2<@y7z_GS`UBh&DIjfd9LUV)ANqrORetBU_1lV%mCbx(D z5c1(>VBxdjZe+A_q@44B5Avc_V>-MLy9V8>-kEs3SPnE(+m&f^53eU-KVns?S#0$a z8E+5LU1}b9{S*DNz*y%ZAJXAreCkdIehpe;nI(LB-x&}eUnbLY3;!Kt~-l z!_&kwK%BdQgsj zb!PSG^H3jzyd`AyD{t)Tox9(2n{2Ec@S?UmDmMR*TRk@Kl97+8SC23r?`&!wmvH*m zV9W#FiSQxOomSaWcky|Lwl;24J9!RVUKd){Z-LKy#%IH0ujnGC=e^gDzC5B5xOXhb zo0}jZG`uNCL!i6^&t4F~;_avDUNs7Nv#x49uK{_F^~v0M0Y7h9l^lF9|6mMYuW0Zc zdb1lu*Zww|r#ys|Ph@=mI?#>W|MpH@pTif4_r4`*!h${j*H)GOQ!^|FVyNw!Z^W7L zZ^a&*^!ls`9Fu3f36dr?kA9r~4V6AxXIH?7^wcR!8&u)*KJ>kEcOT^KHn{%YH+pVw zy=SN0y}Xd=c@ygC%wuBXg51B4w_HQRn{w6(%6pAj*kUZ+`TpBVSmFF%^-^JyI^^9s z)3!|&@>Ym64Be?13wT4Ho;2~^10Li~>awW}Aql4fJ54^q>n)}w#VAwjMX7_>i-!dn=N! z;PW=$7Wu#ruDw~e@hY$B#=pHqxQh7tP7(9J-s-BRFOS`RoJuo?{$2lPmihlWni@no z?Fp?xx|~YOFl&&9w6rsP#BLGzbl(8hpd0GMyK3+oB)5Y8C5wilz?RSPs`8-`fW2^Q zS-A8NvMqoexiQg=G|gMnYNG3dC_4w~5LRH1AfHOz{XNW10!q|&l>v7)e-^}k#9qrd z*r~OL@kWr3sd-$->EFzc0psi_KEywpTuOXhDhH`Rnmj>WsJ&1+~E%E07b`Z4yoC4vjn00tyS@OQ zcfW$`Bd0_8fP4Cq;-x%?d`a)k3@VS|JZlEt%X&FnX9-nGLDg}dMaX$H0325rmdKmNlCQk0q4d|n2u-qqAR z@cKvWOc;?E;6->`$|GFn;q!K}R?yN@IStN;eTV9Jobo=lUbJ zEw&iDde0|EyB>>Xyz0G{ng?G0>fA;}gXH-T0r5-ME=}W4kfuhT-dwo+G*~nkrn2}p z9Un+1tz0F!Esg1U6OPcChm`yh)xWp5n9%U1oS2I8o~|T|VDVP8xSw4Dc{ki%rJxIW zH;W(aEr-1M1Axj()@ZQhXSww{eS!6NM6 zj6L?Q>%UqNTqg&LsqGZ`E6ue0u*cq2H##+f4l^EaK+OZMf3a8G_e}NkBIR~@H>C#f zc`KEixFmI}2uQuzWbCDbKlUb^N=R7Obe-wf{|Tq*%R~5&bkqHl|E~XI4gMMG-^2C) z4Ky`~a%MDIgCv8cWwB}y-|HvQvk7H}t;P;%#;^v(zCRc97`}t7`}F>0R9h5iy$)2YsP@F1Aej!{-I(P^0=#Iuj_<>I zU$D<0IafMy(S`vhNJi8=&g1kifUHrp`7$5kv_@uQunhhPa&NV<#*5P_K%eEriNurm zk66vb3#R#O!c6~&-F%q7Ja)b1pNjtb{69+?-jqYoQQpxFQ_@(xC-*E@;)jpeLml;G zBgh*$Rma5wAF;7+roaBYiUM0}b}m4YBfx3LXLV~N;Q?uU?`sjrd)kaQq-`e|+3V+< zXLcEzx3Yby$)GI>L{QsB`90KoFjdwOCWEq z&&B!KQ{BkP3%aN6i^+&ngZjKtA?yhf@>pe)gDDAYqqZy7_1ss#9D9Ov;XrBrwQ$Dc zZ9vTfuYcwPx&?iee2DA2Mm<>(eBK&&QlF#qQl8-kG-_R{o_$0xr~c zYB8_Ro2X;+=F*Nb8;oK+-f7f4xN-WIG=9kbJb@qK0y*050{Fal5t1exv~$24X*Dhb zb^Pib-yoM>EKa=rPc>)KAG)5>mxuo88LJh^bG*%IcvJ3OL3y8dcap&3eYSA@S_{a# zep%F))sXim>mGh1`1ZDvJ#<)j0It1V5-XJRivYr6iEo}k-V<-!Pu!pEMg-rzsbFRI zK_31*oyq>d zs3=RgSo7lZ&aa8nRnyG@$3=g?mo>%bO?dQnZ2W5$^Uwe3&Er>6NIu-&!Ug|t%sTHp zflG?Rc%jFF{qVxe_`RV0A6v-R_sw<-<01`V=LTVCJAcs1x8H4nW08I}aKM>+E$qrS^O{iTIp zgVJv<8EpEV0Cq?k-j0c+;~gabC1tTm5#}F3^3a#ZwYZ(r*Z-dX+tBc)T&0Hc?qwNN zz~cQ&+-_whI8Z72pJjNyl+x>7<>L7k$p7h(^(Qg+jae{a4~Si=KV3C;e>=AE;O%S_!#m|Yph*t26>;pOX9f*d6yxsf;lBo;5QKA zFmZ|iDtwEJ-63yVjljYp$osq9BNNxXWJG0mL-s%;HgAC|7j&0rkpS9m!uVd%R%LA7 zT!@0@Ie*6E%}31xuYX-CCIyq`_PVqoO2T-YZ~5^%Pvvg(b|VeSiIE|Wr|)y-pM;9znDVa3q6k~bHT-l zzVXu7g}0-C6Jq!L^_~bIzskQO8S;+iPnLIvy!UbGo|26tBM}a@3tqNj^R}|Se6lc! z1j4E9IE{2e+hwqMO9{Hj?F?Z&-WJq6q;dMU{P6eOrz`o9-~KODO_t;H{v#&#=kuZi zVBXRnoOcTFc}JF&ceUJR{`tQqoq4EU`TE0;Zi}xG3qUT>A zZ?O)`+a{2A+|or?b0F_O@=x|}Y=yjSA~&wgivVrTW-qQn-o3S_yrd!T@~|^&wGWYz zrpe;fobRxCD;h4`ZInO)jnsCg-oj^;B(Zs4z5B7ciUGH`kf?c7;Ph`QV^CVimk-f6 zVJ*B|5uf+L6jO^wf(L+!HSem+WB7*?5nOklcRN$c{PTZr`tsOS^eIK>)W7Thj5gK( z|MmyY|F_cAAjfM@u>_}oc_LSYzJ2FKYMYd1SU2I9Sv{Fh3qKrOZ(rhz~UXrvz65j^8WQk zNX`oK78ww_P2s&Uz*s~L9<4k6<;M3-Y2kqHPt=EG$h&{*1^VzMk0~3TqiY6G z-cEX@%dvO|9XKKC19@+Allx%_dGGJx$fxkG*AH#Du{H`k*gfxtZB;l(jmVi-4tXbC zz3li1@@^mmd^_bvMp8s%>VosId9VKtY+_nTAc@*8Z^(4|v<^0JCoP^vDJRC`ZBESt zuYaUs{*QbI`H+Hoj}hW}eBQdpo2&~UZ}&68N7dNq7(p6lc{N%~GXMM^p)(KnfkySe zH%Qyk@V4*u9z%KW7LHWG;;rTP%svY8ws}r`Yyo*+=vos>;k`ukU96L96gc-}+vN6- z;b5(6-lZnU`+QtYQwHSCQFGAaL=734`u=t0NgM3NiH}6l_D#=8V3OJ{-JB~5F1%vy zQd+!fbC7`#_$aWfdVxoVI6QlcFR5r0@-|(a-?0_)4saJFiPn*k&7!K$fde*g&ZsuY zZIJgSYP-BEK3nysCnS^uY2P9$vQ=T#CA_`r=~7G@9N^-sO{ep zz~dNME5A?pixaUEWtL+^Zl>pb<~x0P98$W>awFm2@Bjb5^KC}^mvH{?NK=E{cAWZW z1Sv{hsEt*FVlJDV?%7vns2JE|yam=E{Zoxj9hU;de!0f5c&? zuR(-q`tr~|7tedAVD1sSorbroq`4OQi0x2#sfopV+|I3i9P;j1dug#PM^Yw0myw|xcCgwoiZ`r~E`QAqY|I)nY(r3az;)Q5G1oGarZsops z$eSzak7wJq#APqacILdqK+Oqw_X09&c`H9xOQh zt9|S6^6d(Kgu`UXQHAaJyn{Xe`dR)p0jPKOf3zNJ#N|ymxLtbQHx8!fO>Z6n+s$Lz z&&^eD2O8eam3aXuZ_h{{bu8W%cUSIT3VENrpnuH<^1fWgHdzaKZQSQeQr}IPoC9-HCmB zGcND%NpI7PQWKe;cR!tZOv_|>7uTJlTyJ4d!`mrkcsa`ZccOtB7Vo=?&t9y6ye$@7 zN!SQ^8)fScQ0D*AOBV>3a7F>6Kl_$~&EY`Cyti@<<{b;B8^Uwdm*pf8UL!{aMM{=NV2|9xsOW(;ePD@_d| zTR8SpYLGVn0k1owZUn3vly9+{KLJjVv<*~Mw!<2vZ5q)|*&r>uy6y_=)krWi=4+tQ z8v;58&rD8>4>~8q}KOZO$@CMjSIF*Gwg1*PsPq+Iuf1%7bmxcJE(0vsI>H zpFv_x{JyW50S`!@Pt9WkPXBVJd>)Cm@FDA;L=aXu;6GwZSBQU}cQFAR^*<=Ma4-G} zQu8arPAeTE)6f4qUecFG1IJaRTPNm5kS;X5z4=U6ppRJ9yeE2Cydypu2xURu^IqG{ zI6&St`gWzwU?9`e?_^iW_Ljv(7P??^1Jhy?K=V~IVsp}=lK-yvzpyJ^$? zz8jFY=l2afjsiZ&&7j!lkA|^%=aeQ8j_r^K*Qo7SOcH;mjbQT@)4O{Y31d9oS=2m4 zaQgRnc8&P$zxWUx$?W(rI^N#4yqw*=(L5IH_St@Fr3xLpx7v#jNay}9I3WEceR*gP zEU4I=GFQEwX?Y8za-+O0m-*;o@vg9YVsIPs{;Q(5Xe;E+^}a1e%vj0V3RxurM6Qmbb8tS z9-Ft>v71Xn81VEKerg^jIQb?7{?~x zB)sa#eAmeQ8>9*C^yR@OexYX7-nmDtCk^ia?yc68M=XW6nXfb}7ViNLuLs(Ycgv~1 zS34l@C!hKE4a51r-r9tadXXrQG~(tcc`5{yII}Fc4|$v9D1Wnty!$0`WSigwsb46o z?#^>;-lgN}NoS79gI;R8l5o#^IaAn=Sk5(vc!e175qp`M2N9=#jgtq1o8T6^CB=_k zOxxkV-m*60Tw%R99;AvpKRzFXzrE#neL|HDJM(}4FL{r?Jgy!2E5^QHZvEebhPU7A zNIR5wJK-w}7VmGH#*VCqyuY@jlsQA*Q9tV*ynwv55v>Zj-;uyr=V@}|xe(AB5O}B+ z@|Iq-%}W>ZCe>cGs+{M8j9Hq4H>KFT#n$BX*FxUksqOO5J<@Dx#^zmJygg=`0e6s! zQuDZl)4$(!QV#O|d`PGjhn|}~K5sWA&yySi@u2EnQ0|f{{12oF3&bpwCQmZ`1c~r_ zDP4KYm(gB!uwt%yyVLOYt$ZSi^1iNEJ0FX;|LRxkoFH$L!A1L>An)a8V#~`RZ?sS?j6df8hOqcYc9*nmjl` zZ6^{@Jh7(%oA;E1=-#>n#v7c}Q}dX>>7PCSgvw@9eq`Cxq(6tZ;qzwqVl_Szy$>WC z2*yg#aY5R%V*~HpFERi3{}Bi1%cDI(rpYXRu6n!C@b(E&n>%}(GB|0OO`3AI`rQvk#cfaNBJ;g8zDp@Xea{!HWXspZ^cjm&cvALK)xS=Pm!v z|NpO~f<}OI5)SwK+Y7tfq`tqqZ@^O5bVN-H#ofoV@E)vEv3*r2q zy?va#uR997NC`MocrO$fw*=mLLm5G?2$@(0YtZ8<70Uy`WTe+Lw{ZJs>@P^Uf0X#> zOpyTE&X3cp(S;Mc207}N^T$;z!Q8U<-}=MnqUPa%(?5F~Su^fqyh#1WKqD6u{6}p5 zrqJutKX!qNs4|7pBXo=)ZGX-#@ET?Q8e~sj9#u;ZPP*~WjUat#cn8l0{)LVpt&+t# zv3MV=C@6jndAFR|bjlO*4orG^j2-f}_@pn~`7{dnuT{@<$O;AI@6BdUA@Atvl}Gd- z@4aWQXPG*XkvOm|iLDl!cS)oFu*4V%#8cZnT)pDA`77)#b~)!)=r%AQ?+esCGI9F% zD@v<(z9t_cdi9;Mni)QCr^4iWo<6%l*NJJ76)*95i_Pmk!nZYq=_g1vEOh1(q5hz} zA)T^=)Q5(5&~x3n1JWqfdog!E5sUY0wQ8F$koWbp*$@xNTVO@OCJxAZU&0BwClyiP zvhqCJD;}ZXn4&u&AShImN+s(0voCALfZou zW}d?4-E#X;qpfD32PEB!WIy$3QU)hJ#jAZ}A@5tPWB8t8|UgsRW(zWCWg|{~i@16UEI#Ay4 zt8*7(@!oi>N1YGO|IZu7$htw^!Tde@cpz^l9i_hIAyGg@ZeMtIe+Ur&(>U)7es*Q96X#zWFhD77#n=vQgzl2isO;sbB?uvT{j)Kw``Q-Jy`s|;Cf4X^N97G;s1C2 z|Gzcm{Ga{4um{bo$U5#B<7sAFBqDqZ4%e;UhLlf75Y)Sc7bMTPIh-8gxn2 z#{K%CXwb7Tw61Vp7^tXkogIfYXqkDs@GxZu>5Mqv{s@wY6C}d#z7`e1Z_Gdcr!$YvnXBbL&d$yMchd0QJ^Fhba)kr?%7em-!HGg3bF>nf43rI>zIT=5Z3Ie`a5~3q}v| zA@*-I2FCU9c}I0i=?ja6fZ?sTv-)`Px3|3UUu%a5c{BY8GA@9=JaqhP{drU7R*(W| zct<>VJ9qv+W&WQO`<@4jcfir0^y84XqEs&83wifESnMMLdB50Gp|V#x8f<>8C-R;% z49t?IADw`_RkwVXH~@Kjmn!xESGYjxoFcvI9yae4ns=f*g zZFQP0jK>?z;}}l=^e=68i+aS1OzH(?f7Zw6UCX}D$O`h-waBOwxlhOZ|JdMQ|0_?X z=S@hZFAuG)hDGj$bJaV5hIjZup4Djec4#=ujm4W#G-Y)b@-Cl!y2JD?-~T~f0Yp*T znO(MjWbz-X_dV`>tIQ9K$6Jk>$6cKMxipE4d=cbBbop7;wyehIy_BVcpuRB#NGzMU zv!V@ugLDmBsZ{%ZQ>GuB{KY|E9=?aQ&n-PP$J?KVcUY^-MwIv6{3tFg-b6(XuN#oJ z)`pc|ylHsf?2C=M1$hrF9@=ONd0!M>tXT?q_Zr5l`$FDIzpOG?9>MD^^xYj3xv+WH zReSRy8S(&aw_bHuVaX=!wKv6%LyKRpV?5sXsCmfa^v@uuS;KxYA5z=uz%{)FpZ5k4 zv8@wUA>fzRO-oV$9rJ(fT~+xk+nAm=L7&b%ScSs7-2dJG|390E|Cd_B`F|Kq4T@W8 zEr8Y_Rec>{tQs_BB%QL2F#)&->DWYY>OF}VQ1~jl)yFg(6!*I7 zIKVqd?&n5{UV(Rz+)~W253ut=q;3ZW*q_3#K{Aiz5*GiE2a?ow8*kjn;8=z|f^11N zOv~KQcr{3xn#VJo{+;bf{+&*DqsArrepqpb2mHt z>qO?SLFeep<9LVm)9rts{})QbJ7)9{8RZ?-PZYx9eV%yxs}$r-_+Gv=2=Y#jzIcst zyhX~ptLGv)Vt}RK^A#+laIk89eaj2@iCs(9xh?zQ5xWcbdGYhvO~A z0*^lz{UZ;WsqMxZpRN2rz~=p@CnWV(3ght}rRMPyr+?EU{8cfcd`PoG?WH%O_>WjK zJ|6D!r}|(|SJqyEA$;B)Z#^qNtop_Dyu0qwm&fER>!?>-24w{)gobzYRqMIiTPX8? zjhrSyEZ*5qk!VfG`}m#N@tu(Ou#164E#!T?%tdkJTQnHV-F52e{BRI*Bhx({^3M4A zJo5|W9r((lZi}H0^7zX-(&|v`>b)b~c;h#s0(eAir+41x-I}l1BS_&Sqt%Y57>~Cz zH4g!t{%zP%b^fOhFCz0P?+@EDeBMJBMfA4sn%IR-Y-{{G&sV=3AOTd;Z?Rih|rr${p&KYc_SATv;&tZ06}WI z-x+@H$~@TBd#rp)HtQzi@m@pCV+5yv>05a~#0_5LF$Hv>P{?K;==I^ub zkS+0fugQ3J{7rY{fHkIi9T#Df&xK{UK0-Bv6?c@LKbFUH~x3eBH7K;E3o zM=Ap#@7k9hgjJBYyNHWIQF%0YoLsV6{c0Ex99McyIlX0hoH+3e{={HIJV-{kvD~Fzr9ZiyXPX z#feh^pZ7Z5bJ>A3`S%|4S44|KV>7 zYtUYr8gxKJ{+};MGjA#`!>U2k_4d)%(P?h$!=sq<<5d@N@PS~Ci?L^1MEFW%OjJQGqiqv-8 zZKA+)H})Q+T{eClFVz`u50V%)j{uzhRfT0-BTMoi&J$q3wSmVF?{9HUww6P6-5x~C zlKX}3H2x!&aOnKQs)eb{UxSX*mq+Byk>9z0uORKA;hos8>4iRG(+p?Duy~(dbminj z$Xglldln9PkFke&rb6B?1l$(OU5o)W{D(?7@4-iG;>}GSkT=p$Ht6%C8*wmH*DvKH zBO*7wYVzh`^S-(8gs^%U383xLgW_k!S7Gzs`!wj>0S(6ET}jO&0;hlFf{n*4Px2rO zi=Q=Dzr^S5Y`luC{LWrvs_OF;rxHHz2fdfpi{51Z`M=~>`ttaqrk$yGGVe1dI3Q z`K?cWL*CxQH{3!XZ*4V6HywEX-^XBqq^%obK=^DttICRSFkb&KYznTunLd!REBo1v z6yK^ec;HG#COLC;k~FXfCpNF{iz!&hgK=uR!#x?u+QZn@`~5|$cAj>|7zC~J5OwXI3NoO9nhHlCJ zJO9UX<&!x7{> z{@tHEvSWa7PwYyKbs->=v@R}DW(djju$Si^??#B4e}r~PkdY6I>6a^zW(+EE92FmN@^a4IQ@%!Qt@@Rj2kg^$yA98z<Y)bY3>mlL&N*Xi_EJi@4V|H(pbFR z_1nw*A#YByfln0VeQQaqR3hZfo&C(9<75nYV6g1%&zumTZ^aU@4)Q)b>hU4~@|Kr< ze6xW-M%+FvQy%+_J%apm<@@hS$lI0LZqc5~*8`H+ye(VL*m*5vJl?;ld6?t$PjK-W zkM*)V$aA^Yck^QLdG`u?yM1x+Ms9oVdB8i4KZ3lbcr|?YlX0f!-6l<69*(!ym+d<` z$2*#a_u;Y|Cs5u6iBF`kcnd_BpNN6HcR6mdh=jarwuVPWL*7=ILTb{dV?ehX$2GAZ zA%HXS^3R{rL&&+k$^paWZ(5`1NHZ?d4Cmc|IwC20%*I*=49O~6W9}^ zZx62XKI33K-ow;9hH?7W!fC1CcA5wAiQoQN@hCp;MZ2$!7w_;!?i3%IXLOQ|5hRP% zC9NC+^N%3s)0xMXV0ZPu=l@YOybtBv??QQ-e9Mu<;$62vBOn#>*65sAz8CVoreD+$ z3VG`Zs?LNK#{d!kdtlHf6g;W?z5Wd3ZDtZE9z4;Flo|SQTB?ze*_h>z*le%|CmnB| zjY?*a0NRdY(NSlsBiPm3Q9`@KLxAykzoO>hfYZOgZ#ysWi|`=(y(51smg4gkux0TV zs|Z5=h$yeI8N}bcMOgHxCh*x&=I6~uUmiONQS0n3&sFb88r}yt+K>-P%?OIn`cm_mb^X3hRK2MNjJl?|8Jh*WBx9tu|TFH(V z$uqxna}~hn9XZPV@%p_z$ZHel_^OroA15xzGM&6~;}_HOUXV;*9-Qj?B`?Qj{(Jr( zW6bdXb1x1!X0XuIpfvGi(P$02WhAbIRfDYEqJ!tb8l>`|ha&;jpzkK^%?R8zLV)ENQ4$T^Wb~Owrp+$nK7S+cj{lP#wc&n@lOg^yg$~S zndXPQGsxp(@sRf+4@1@$@D;o0>#=Xv%VL47vV2^JbueJ>V|7i1yoC+Sj=7C?BPZWo z)aUFbBO_aEM1U^#7CW)C-#_;g<-uoaJLg4F#L53~y`}i(N72Un7?1ZdY932*`ZuO- zGyh>3FH$HWqP|WMpZ8QyM`A^@C!(iPeqN#eG3LtJKef&1wM+TnALi#RMPDBIpD$e_ zB~eC@8S`j(A4~ss66M`KR4$LjJ5sr~To&>UaYl7r^y12Jk)( zNBYx)!P=?%Btyts=J{gq9`b&+0Gu&zB_o$*x+pH6 z?0z%70WR|RN!t2$*5fZu5V&(Y6!$YfZ^Ew=^yLvXqL$|;NZJ1%N5eaLdFMrx_sCld zIV|4NWWz1ykoN~Y!E-T?H@f!L$A3`A7OuU0-t$n~8m_$!HaJeFL*74nvz#X&@6Mux zBO#FYoy+g)b}qo?-M?3V;V*u9P)lvM`J|^wnHzTX_R3{hubRSm)w_?HhZ|1+N^1Vp z*}x+Y!qvJLm$>5dzGd2Z%VT6K^84b28wQ~NU#$K)LCRr*xDu-d{ZMOrbuqTg@P2Sa#35LN^u8A<7xxQBy&nhR>>Nqx=x^WkE>v*l;&uvHQBjF8GOEo^|n5pOQD`4$`QN zuF{P{@*s=aZgi5D?Oh!9Cw8Z78-EuhGhPjfq2__tKcO`ruXVNXB1La@r?S^@8{(1K z9aWWi_COr+AuQE3SPcJyG=fyU!}!$!rmsPSwe;oTZSitf;oSOv#zGq2Sv9Br*&u!4 zMf(aY-jA=d8Qq4wKfd_jeh~70VgJ>s8}fehF!UCoD;8`|G>gz04+6@zM6r6(5K=gu z-tg*cH*#^>Bh*CS2U&eyGTY-9_9OOC9#^;=uRPGEwp+7s$*LP0v3YN+E?T2_fbn=A zrsm;*)4$r+yC3}3y{%t6nR5PL1{)3U%##J%(GjFu%=zV5yax&fYo9^hETtOO2Ow|BYVPJ{$U8jj zUV&b9EI7MS_t(*pAmF+~(9i<%zA(C-FL$IHF%*;b?v(XGyhPos4>V%)4$Wzw=;f9N z&eV2W`6lO=NMZA4AGcK%VZgVyVbna>aQZj6a8~1f9WU~9Y$j6d9X@Z;F6EfypuLEl zSk`ls4*U@$p;SMQ|3(1QuOJcX>B~cuP?z$fXm0+`O2a!NOFjhU-DeP_g2lT&nnk4x z@{SG((%TPt|8=P0`Yp=fgq3A+R!S^55+8Cw=5r8O6@ELcQEmuXb@}rtuW#MR!*4(C zH%a&)w{6Z`=(>Z=Tjl!er`xPP?hIJHms9h&htt1?_~hk- zl+#;fuf9|o$LGCBVg8*2uLvYGbHjC40O;`oK*33JtZ z0S)hTl@I^S|GD3qDP!>#+!+3B1oD2Tb5+KB! z%^P0N*g@VgR`UX7;M$vgaHqnxdt^j$O&!O7w?<*8xi9P?< zk6K$b&4BZNG!I>z{;gDr?mAM-i|l+Mvh?`>fOl=^`=a0H@HZ!Jamq2Vxa7w4WAD<< z^yN`qv?;wCew@e!Co!z^&J(z#IE)v1EZ7f!{P!P5`xAg8NG_Thls}>$gg#=wu9~Nf zRfG1DmR+}nHE6Tp#oA<8gSG^3AN>Jq5dTi%QsKHdkW%E0uL7@L>(k&xte(4DO036!#HuwX9=&PfkCdd1t4IXn*C5GJ>q}yX>X^O; zC48nYk2JQ3{;hd)BgjQGyz`ny^-$h2?r$`)cz?TD``Hunb_n}WdKB^&-diOy1$pa# z>^nT~VjR$Y*1X;QKrmRnda1n`S z<*rMu_i^X{1cH>Z--{Ne=S}z}NnalN+ixrVy}gB#hWE+L*+i7LAa|h#7H__5Y=j8N zyLGEyVG`us`zF+a!aJ8^qc<4| z|H#TS*oMvf{F8K^08bJKpthU$*62^-6gKZoA+8F&?--9ang?G0qANvv)wOw%ZKX9c z&SChxo5p#k*pBT%u3UO`)Q<;${Xf2CeyQz%8`Dpa2#xgR(dOPL@a*DT_2!`AooksS zkMjO029EG|)q;2AemD_k~x_P7*jyZ5OiXU>9XtXP}+~ryWMj~%9-lj$kX>{c>LGmum7hn5{`|HY-D=g=UC~> z<4t5@@<7%cZz2uv6XjamC~p~CV>K+^N2JFRPC(w00?XqLL*9h#$*(EAyF4tuoG^<6 zGlvtlnaKx(d3J}>X5iY}ubxdF9gz2j{ijRiA@6Oi-3lMBWAo%E0&V!``ub%KCf^wWr-!t%ek1Ah1a`Vn^q%wuKWt`nMA{3+%5bEfA_7^E|gDWZ(jzu*7=x2Bx`v)>oa|M_WZ(3!U zRfD{?e^Z)?fmiHi^Uq6%HOSw-uht9Jpx#Bv7ZX0jgJXY6vb3f{K$U6AmU^Wjgwy`V z^oGH1#P<+i=R`RCK)N?Q?(-t-SL{FLuS>lt0k7Dlw#)T4{nES?`yFIk`|Q=4LdL5> zqtra``d1^oqsOS32TA!UwLpD_%MkA`F|UT_!6F$eBwFZWx7d3+KCyeYN$#+0*($vM zF2n!&T^qXc2mzuW@0ZR!V)$6;mC!!JMrL6rM=0Mh7fR6@l)e*$UDl;`(7dB&6~D<-;Ql$#MS3xjdoKJ%E0T#J!1@lswyF)H8xB0v5kwqf$4 zzeKV*qTH!^rCSnzfpqoe3;u%NrSuq{FHQ$-1&Zm)W6#I4s~!Jd|L3LQeLDP81InB8 zN!ltb-W57>>m?!Y+dJz%rb6CL_g*?3g}l=|`88gr$AhYMQ*w`vg#gWvUz=SZZ)1A zTx{MuPizSGtYkdiR@6KKar(FJ(T8&#a=gf`1F@2PEAV;eYu~bXXY7V}SH^YT`GG${ z8q7Ideyq9agPcw$REuy@i zra<1BcKi_ykhekJp58)IJP@1TJzO#!3|NHp)B54!L}#f+1c1C#yG@OC^~lImTQx$$ zf8c#TCyCT#N&@$(?S^dvS40Q#ZF!%LAa1FSr?!8 z%RE{3rRHu(>W$eI&-3W`_V&`d=ocV|>3I{f>CA&wMN#?R`9IE3k3oJJ&i{pIYEVfl zF`rU{DD(fjE}Ph}YLM48uiKa4{QpdBvR)3XK@W*DkELJ@YHm1E$5XWrta)W|L1Q8m zD3U(Q>{lK_a=spQU>WE}jxF#hW@{rOO6r|q4|ZYC{{xD`4>$zCGf1fIB)`e>`K4gb z|BHuSx4DckUJdf1=7HBg(-l^PHILyDJKr7kgp%;*|6QZ1&n6ql$P(2Hn{zwqnE$K# z^t}1z%KYOmOWeN4tehwJNL&OZn68mI9BC{F*fg$ zOC-&@!${x@wOxy5*()^?Y94s~tGI2{WPFhqDFF6Ud`0-Y<$rm^ zIX`eg+#JNFIhWzj|9yTog}1kMFg@>V@n*X6kh#Cqb>#2)zaS0oV&8{nP~OSoUs$ks z-#xW^@iWM~Ch(D57UUg%-!M}T^4_R+Mena2`+%;z*UJORp@8@EdPgb9TTx2x#YM>b zceN6yQw15(as9#BAdbyDwA}ghOd<(rP}{ktjCh$CVe|GKNY_kTz<8gx1W@z9>)&L_ z)^pr<;Pn2+6T61$`BkZ zLc!^q^Cc(Y{Qp|>UEy)a+n{%!Mfr6ylEAS=D@PQYx6GbEj_ynnh^4mM^XARhO~%-~ zPqnT$kzl~{|HP?z6yo&np0z>|mn<)0aycg5(KF2*T4CQSdnLH1RcWA6h!7$`qtSrx+0ePcq zZ+Y`Yc16Lpw=*Ujl}|%y7297^nkYdrTg&it<%Q68`ZFRe_pz} z)}#cEy{YY9t>*Y_w*#B^|6%VwgQD2Fg#iyiRDzO&ft<6FgEXRmBozTAiR7dp83aUv zVgeJOq9g?c5m2In%2q*8BpS#HCbEc1FaUlV?0N6}>C-c~WAz)tzvur`$b65N2Au!bko2IUCp3$%*e%Tefz_Ltv3gKnOCYy3 z>_Jz{j#;L`9z>yUkTU419q>9G3sO!UuB|%~1oD_RncS5fMf~2G-=_W4kK~tK zH;|O`K(sc$lx(|)eT#kcZTx!vt71S6jT`$TVk?)8eGihi&&PeO0_6=z185!GIQebA z-06SjH!E^vVud3ATKpcgPo>c$Y;qeyPiMGy4v?{eObZ=XAM>LA9@I!?9o%&SDT_z! zB&{alU6^vKop_1O*u}ww#d~j5`EgIkoB!nLZI>bM&NQ8Ek&w6P38nOl!LdMRTYMHn zXb_;&xN+zlZ!#0w%EMa zO&_^ZBTsp}521A^;N<5U>Dy^0&5Ddmmo6Dn!{>c*Kh2+O0xpR3(W<&9-1zhVc`N?6P1CaMlHyWc$khjye z&O<4Xw>rXDT>+vpi%Hw?&tphK=mgwWZ^eR^%$|kk>KlJcs^=ZO)R(L}EWVz11&NCT5+4cgo66_yh`g`p6feW# z&Ctbv`8eeLtabgSRLEPi&g@`0{H-xC9~Xx!{nU~&TsHgB;L-`lzMDUY`YS_fW!v|bLC zA2e1X>^DZ*EiLeQYajP+ytKjxsR)}YVwuLD|2x0+DBa6&p!)g0dtEPCb!^Nz-{n}e z$eWjhcRtIdz)E&@|EuZ{CewFgI7C7+>zF8+NsC+uz7DP+0*c+K@2paasC|EfujGw z`-;F0$NU|X$6Fh%11~@EC$V*d4_6{zfgop#Gd}Ndp07;3Og>2L!*-uNXULfUEkT|8 zH5;nuO*l_x9R}4pg8%OS<4xX_@jIOVg-Ci(S+#mOu?Ov<*}#s~gEstrU`G#okn$dh zkSnkUxvZ+|9F0`cWgdUt(e@%1Ofcz`Zn_f)PS`%6dkZhIgiRmUJ^9#=WNJSg+rsLB zu*@#yx^W%52k{5oX-iEO1B_^#js4!kKmOqxBrXmFPG(8U>p^^I9Zop;wIg$7c|xp6 zhjhD_Yz4C}9**;VsvLrs4}#r0e{MNaM#c(~W!rb}^k%AGK@!x-t7GXKM@{|g#Y?Op z3GdQm_a-9m+v#jH;g`wn8)@>oq>_oE^)L zww?SSHwds(tg4A4nxG!NF)$=B(l352w4{zGv<1P3}co$nA8X@xDzw7l1EZz*> z{i{_V?}Q&(2QnaUA({q{0QiBlk1MuvwB3#cZ*}*WB?tt8)jPiNazWlPxp7N;AaA;q z!DEN?JdnBJB`26ZWAhG*T$MYOEe3v~amm&vIrUnwd2`dW*%c^J9&bOi4o;l>W-ewv zVGUtLR4>;&shPs(eSYim;2*ziK$?nySLF2{of|}KT$t#5%TJop4>7R^6|vN z>8)!?c;A{m_>Rc?(9>WREZ$z-yUYwB@5wVkcIl9}Q z-+dY4?d_s^-j_lr$f`p)Vnvg{nSam!!<*qK;&<4C#7TNkRk1Zcu?MXSRpG_zK~_~~ z5=tWrb$#ds!mq;~bf3Y_@IG8Y+BfgibDoI>`>mI>uk8u|JP!;%pN97!RmSMs``|su z>P@Mk?Qc8~>y-@*uV=BJL5jL}qf+db7_dR(^p^Go7rn=R2B}aYegD}rl-Gm8&^q#Q z@@vm7$m`K#Lvk#QoQkaQFR|J7ne6davB2Hi%D90M|A2HInbRsB9m7;V|1U$xtK-C( zb|0amiyNe3B)lt+AL1nPUOT>w2aES|l2t}?1B3^_-6yamxZ?%?F-xwEH(-k%luJ-9p|#vPxxp*C$|nPn`X4Z7wvU4XxW zB$VWPhs}SddftS4^(=KRt?1hmH6Z$TGc>c|7u)(HC#b%`E$+p58NPKGhp(dtK0**;vmjl zd>OlYBgf~BTxi4rF-~cc>6ceLHt*co3WwSh%Hyqp){%pgpTa6vwOz_=h?DBEp}A;$ z-Xqsa51y!r1|!W?F1mjB2c+BU_D{uzc~kugQg|R z$%hP1EZ$e+Iq5z^-fll`Mr1?YX5hN!|%5v-^PN@t|Qwo_yvMrJ#k-mK;D-3Mv=_ozy*z~d&NF-YCksb`3(aVae#5uRnTVfUaVZ{N0e!bj|K(74**iLl4-vF|~?=}t10+eLXR$hkLv>*&SF zZ_9_PQQhzsyO=A3w8#S{UA%ubt}8osY%Goga&~2BUbd2PK)Uj7oq(2IRNsRLqGZ<5 z%}p!!cLzzDgf|Fdog(tCJpOA97VjOZ;c~%{cfpxJt9;12euI9cA>>VSw3F9NA`S@e zj~-Ck7XXUuA13aDykFeBe7*#}VyCFumA5Lv1KDsrEQa+6Ht%;by?RPd#egmvm#7ly zJZ6i1iG9t)sd3kt@_2Wnb-cvMFZGDB-E#POi((PQRNFy(-W9KBIz1Q;gR&Vzr%WdN zTkM2OE%smLKT$pJ==0>&aeVc~4cGG)SCCR9ysNhtXb^cP*FRZ}#XCPWv*P zGK<6N3NrR<&%XxPY-K)elJV66DqKI{()3zT=C$B}sTc5b$#$ z@)k}?U4_Lv(n(J{8S<`tp6QhbdCzlA1T2HR^)`tJyl066PIm3qy%z$&$6F`#nc>}A zhu*UJ68QfAjh%}5YR5c~L_xitI2UZ*?;kxE7#|P=r_s1-yO!xy*Wz7tmRQh2M&i%mlCo}%jTZEg1Un2{QsGc|B z8kuz<^IzrvE>0v!c;6dhqa*VEzS@Hii+9RO+oWvB`}lVG&|Jv-DEnKp4tRU(e^zTV34;s$eRGUf4>MeCr$$5rFy-P z>7PG9^_SQgMe^!6#U&h)8J)B6h@Aon?0ApS@6@P@L8!*26AVqn+z0o?XaPp(Mpk=eSloQd9jaJt9Z}5() zQ4hN}--OFs3`Vv2?=gstrygE`|nRhfj%~;?qPr|!ahko%3(hH}zNSjp)VewY+ z*&wS1dGkIkmo9?5z3(1-+6xDyk8)Bxm#yP~z5EjmJ7ai2diTvlKggSfzT9i!>#Y`= zHy!ux@<3iKS+$zc40}MbeOM#$1M()u>APFGf8xX*kVfSz-xg9JZ*#PcVVwNR>VCIW zRKW+Nul`=Q^}oUU`raQ0lsoZvkSZ${9@)6sfNuPv@s^V$P@!yXk4BBKu!)VHt*lxv>Yq6DX)81 zpmqGj$!}jLS7!dlm59s}7LVaG_=^+HeIegzH%EcNOV9XXkKo_linj5+>lNTg^}M53 zkyl54w#eM~JBzosWJ!2GmT>$J@1K3v0$9AgzFCFtguHVbDzpnAZ&gOQ3SY>Zp>b8G zsAe1p7z~WL2tRM(7kM}3Ipm!idSy=;lbHTm0C^Ibq z4j=s6TN4l0eLc!(O7-)<=oRwnP<+EVVFOQZVS&TP5}IoS79mExr7rY`;s5^oAEo^b zz)P$ONe^ngBqv9_#6HX9kjCmk#y`HVZHj;^$e^FM%U}=s)OXkG3>=V-_1tmFI2H#U zOT4i*nhyZ_?gp(X@DscAJ-3#p!!Jnl8-IxWXzPK{O&Kwqyn)?=ZhJd4`3{SLC1{-6 zD>GUvN9;?i&dbX>dyZ0G54w)lp^cN@WTgf(uR15v__KxON-?7@9uvVW-nIMLgTPEy zZX_MR??DMB7aF&C=urJ7R+EdoI%)=ccelGOUSgF=ct783GDhSrz&I+2#e28riIE=2 zyOZGkv=s7wc;DP42J-gHSK457Bo63&_L`LJ2>=>zn+&c&-W783>_;H)5yF?j=Vl(r znd)P<{c+g5_loVBoqjC_&Y^J=3Yl{{+St7NnEY$_f+&x-Gg`+Roctuck|*AWaw2X+ z{QLc$;q!i{<>%AN5d=;Y`krC7A>##U!#?fR_FJf)H$jxlI{E@uX#CwlQX=8qpgj^v zcoHy8dv&ov()X^*t|E6TzHg5fp>53 zp>-fQ`5`o?esw5wBKP)tvxpP$SCGtAC(`=wg#g{st3o0O{`^m9a@J`HentJfpOaTd z?Z<6Vd(SR*@AV|SpDmdSB=Y9k94C&&+w!hR^3R3t-9$H240&tZTQ*_|c~?8$=;(`# z1LA)sf31uS0M>*sI{^kW>4AKC>f6Y&5}WtHl%vbpN-^*ijk{sQ zAHTB&n|IQ@&E@A5_;6wmTE|(O{65iZmgmxNA$+-=$ziMUd7D+gS(DFv5a<#f3vtWf z^PZqHK2r5%lNR2hhthwqC6HIgq1)9wk*61LZ>=NYUEldxn#lW9nUxq8Z#ozG@MUoR zpDDh=vcOxI9{8+>yboGz=l2Ya1C#IS;xe`b0Egd8F7-j)rTXnt(vY{G2eWlKmnS0e z*1le80-N{J2elVXO2mL98n^jPYkJEa?9GWT`TJA5w^QEYWcL2wIy!LjYsWLRKA5TjbY&&;NJ+r}TEU zm>-<~HA#BVi}+%DVh@UQSgwfGgHDb=w~d3B*s1jJ?Uk?xUGNy&Jr3_d2H18!HaZjs z(th}*YL*9r<2NtPPf3g-9p08>m&W>$?;VqJl|`P2|BjiV$m<@M`~SyNO&DoiB|tD5 zw?y+uLV8LR=0>2@x5gCp-<0F)DoSQURj`Wnl<>;4va zgt178uUs`54@h^Ye)(}vnd(=N(XHgwu~x?IyzJle|1?N=w^@rlC-UCj&?}F{`@3um z(>chy?a*5HyO4L>o~9l(c!@o)H=sCrI1a48uWp>MKM<@eeD`}byu=d3t=k+R?<3on zG`_v%iG&xpHu0uo^N!Qy`2F5g0z{#4EZn^Us;97dPkYiT#eSqb-eG7RQ#kp3QJnKn z@8Ci@l-r^4m`dYp;?!xCimh#SK3cbHykWwe% z-73Fp8Z`0Y$oo>nGlttI<3L5xr*ghEfk3vj zfkqSZwoppHssMTG3#sS|J@7>2F2tYjzk$tLJ8b=*0W}Grh{l}{oIXFBj?MeP;rBl} zTPTmWB3efnPJYSL8YfNpxRGzKUWXL9;Pdv4bZ?Sw_6IvA&O61G<8P1>rsvd6vJ|L( z2Z?Z>%sO;ME?)lo^%gY}-px~MI*7dYKMj<{;?4fd;LI(^JI6xfL#H}6h<-~vY|Eb^(0G$63k{;A~VYr6a zgEkynqKegnST4S<)`C4~JL~-?4`2^U%WIu%f$t!B=op-Ax)2BG)0)NFCxgK~j(1hx z#YYkGASq|r@qWYvVP89D;(>U7v`Xw=f_;g7_4=ynh?Y1AK;yi0-b9RD$L>MrO!WDm zcTiprYC!8ai<93N&%LF6)|`lcOvTIY*yXx-a;`>({M>Ok6olK0yry}Ce~X<^Rwbm* zP(<}Th;Y4U7E$$%cknrxXYV9QQ?hNfv#^MdincIyZ?;jGS@9#t2YqKO+ z`XO&$bph?#({UiWYWBkJykJ1X9it)xZ*RGOx>qg9mcTc30L|H})kq zII(BqroK2xLE}CLJlQ;O5Sur<)Qg?j?>v63uLK&{@=ntULBWC+#lvSySRefK*GD-)#xmd_l53K zB`n_Jxu5y0A#W}1>Dhab_nEwGry0n*)ymhT3O?R)F+aid*_L2n=HwOS2YEZ6ETi#) zycPGa)~i$UK-g!5Us+UO^VW+svf;532YhH;YV+woMRwS{ua&QhnVXUl@sBCn3_mruLS z-d^n9+9bSRFRd&g^0w3sU5~|^_tcsr?vVHIZ?Sv}yn{GDpIWHtbDjhrCxtx9d*A<1J4+`B?NJ*o%`NPnYrk?h^;eXxvv_*ZS{E zu;>5m(_Rmv4p83wKaSRM1t-6y$ZF;dN?ge2OPR}7_u=!7llY|PWEc!=ug^8`XW~Dc zsP1s*)3u|QsGj#SZSv~ixmHip7{AC{i-h;f=M}4oy!XxOt;6DN8&~ot2=YFA|Ex+C z)&zOqHGZVj1Ml8SZtWa!boNBDK8G`! zabn-Seg3#OpW&bcxQ51ocRzNm`Gd`Shu+NFY7QREy*#|N?Elv9kI*{Iaq_!TMV}G) zjtc>QcIBk~!sp$%M(fiXgJ2M}wqEJhS~4C^96a)erZSiM*WQg}))5obB?});{CEEU z-;(`5_~*j;e=|uBdK(*mc%cWW!#7AL{9OrHJt)Ck1I#{WVud?HfDwa4%L%bj(F`pP2ukY(wj(lzcDjbAzotF zoo~>@;(a1aMUNg{V$U%z(|ZJY%id95p9Oh)@<>qLhOpkoU)t z?C;HA`Vpn1f=N#Y59CAkGn&hO*el5Aqec%0zlnh%G|tiYg!5Mh>`QFe&KdD5rzmeg zdW6;yjFVs0nSrmvJse08?FWJ^0sj)~|Mf_C_cD9EB=UZsd`1I{_e+s0^K6het*yMZ*VLOIe!aEC z_Vn6iWpSYW!{H$J^C7@4Xo)4BvU&`;7`>Y;uB5KFY3U7+z^RB%5-adFL z0)$+yGnHI||MixJ8KH|Gjz>{FZ)tyFvg-KrB72VY(Bkc_jU>Fg`}dg>dEY8Q zSXH%(6S=_Z*srt^pLY=-pQ_0B2$1;VwJv=Q{{BCqc6iOTn0-_~{}T*`$f~3E$mt}R z^NaJpE-7zqM^++lc~=EBEZ#QywAt6 zdDEU$qWRH6dAxsk{;h)sC%>>yIl^*`T!@B>$Tyn3_`J*Z^;;f~4Fww_M6#HC@E0d} zsV(0Ig43yf{;#;*OjaGCTzk)C!S4O<{ExTVqk!Mx{BK0kgFgDOSuOOSh50{Ta~lIz z4>~CGQm7Qp|7tA8R&}rkaobLJUO%9un@{8R>0ojk$QKl!Se6z7CIyeJY!n$qs%E|Y z)xN_WBpKRE?;pA&7k&$QFU!K7|Mzze+pP5$1L%B85zp*Mq## zIuM-vwwt96mY1?4>V>~7O2qN!fA1iJLz`k^faUu#&GBgb9i-^fr;abVVo3G#e{>mn zb%aaDyG&hOyu@xH;r(H=ZW@vIn^iJPuy~ufFFpMb^0qh>5%mP}u9WZc?SZ_xt+Njq z!AtB8@MWufK?o4pciVX|R&f|SR*7_DO+PJTNlSIVzv=0MiI=(!N7kIx&duwFU-D;5xH z+fO%;am3CNi&@s&oW)en+dY!JI$T}{6Wss4AZwaLr`$_7^@hB4 z%)75kxMK6(8ggczLAn^&jKXgTO3tGn%PJStFa!+=6aUk<_ zG9q=h_`JW?`rWDj9Sb%zeQ^jP=j$zoLiaa3Eu(tggllBh;m_6}{rB#z0SWK^9=#$W zZ{Og1v{<~^M8aZvAny;$=UZwZZ+%OF!BEIsp2Ox?;hi{e>1Gj6(d!V9`>OP473959 z@_kMD*M3Cn-HNlj89k8XElEN5fBge*y+Xlp`2K$?8uwQ7)Q*)$uoov|dpYm$TTvcw z1GJ7|ocvgXhU*y&I1sfIw^f8Q_`F~0RGeOubr=|gx~kSL$A5c^&=sS5u3CxeZ*LLY zW67#xrA46bx{Srei9QMMzTEUjMBb{xr)jWwTP2SP4MX0|r!Pz|?7bbXWGMd*d2?$e z)t-DB2fm9|{hpi%0WHAJn-y+O{0ObrOC^8IAhvE+u6QY>7Y{5$_szp5Jm+SjQm-oY1&z?fpd>cd;+A41vaa z$u~JE?ir+dw2nUk|D4|e$B}XkQBLI4`{?D!)up<4|7^#(8V21;4uCz|4MGFT@o%yJ z@HZcy4sN3Q9z-v;ovb=mMeJc;8NaxLWJbb!SaIWHB5y~39wsc_G0U?G4np2)g_b}`+t+`a~Q0;f`OBcTPqE`y>-!zlkO$gr=LH z&5H?}w~S);=#-!sphx3)`WcgCqOf@v_f4GmSV?)jCDA%=;^gPZpwrHN&pVz__m8F4(<57*Ap~aKGq%t1M#O%b!@@s9q>9SyVOOC>IbB7)pKOk zvH6Qr#q{5|w@gTQ4?MS9e7$91b3#F_bQu=!HNQ?+T!g%zt%xTq@SbItu^NZGWtGQ` zgy7d(jDN^pDKrQHW8=^NSVG=U)0de3hMN<`s|vn$HoGI1j(K}bKVkEx^RG=#(-Q+W zXx#5l@qFSA*u1T^mdYjcQXcPlzrS@@;NJ`CMzy_*coFuPUM^+u5&aaD+J^b(f zKi&*S5x>Lv--4tEP3*jGO6)=3eKpy!deFwf-%k}_57OcnifM*D=oG_D(ck37|#C(*;e&%P4y!g7Ow9FQ``}iO(X9=a$pZgE1EtW++HdQ zRM9wkb{39Z0oa$=-IpI$r5I6O4`N2^u*Au4YqQCjS1cSzd`4RzhvLFa3qlT}AQi{`6N*n=SN9VEQJsG9#G@^-w+!-mB> z_xIBvZOFUPaI~Tc@^&-uV~{`UzO3!Z{%^`amKjazkhX=b_(HgCz;H7&1pQy%Z7XdQw$`OPup zvCNyXBL(BuTUF`sSC9$0A76iqa08pTMzr?l;txoKI~Fm;Eu&P=o4^-FRvk@w#`$fU zM;3USlkoohop6N6JL_T3N-W-Wx6a+TEi2@xo?pGd5r|UmF zy*1^bDRsb)@_64x>lnw$uT#Z0zc`&8*>Xyc;fVx3?-(xiflc2eGi|7Jx zF2V45TgZE_^BtGT*Reo{&*8&e*I;nfXN2b&b!6xD5RL`5RiOf36XJya1aV_xPM#6hEO`ey?`+DaA z7A)SzMQKJZkav=Bhskru`?Bccp{H=~?GhWWh!cEhPWaSr*QdvWfyo-3-cHDSd5GMW zCdfOcbeqSIX?Mh?>1Fu*5$v`1wFhcJtC_@rJsQViC^IxUh0R+#+gtF}Rm$Ui6|F-V zC%^bg0!#6B4n(|d*g`)BpZCLu&hJcm_Je@@o$AAy_-k*1XzI5|f#%e|I0?B(RvlL* z%MU&&`gi}IBIbL%Bw!D+Ch0-bX7)>nJxE_cg%_&_sjs@k@a;gM?p4=K&M#mOl3H!q z?F64ea@R=}9t(&CJN?5R_7Z}@Nx=59Ux4R>4C+{0yoWj1u zUbDVx7H1#|TG2Sk(eCEY|1coM>OVfUriX*#_W!fdIu79E*E+>%JwD2g)G2o-uUBHg zo&VQ;1S>yF1p@X^KeN@>@Gr5|>vA>}j>J%X5AqvIC#w#IvjuFY+!r@UcaiX(lHFTQ zImdLaZ;pFDKHio*Yu2P&;)}ujZ(ZJkoOX) z9E(uM+k7<#^3~8C(N&fGnb?fY+fv=^+-+M?fS_@PN$=J#U5$N-bt`Jf$oN8eymz2= z*yH3^D3tQLOP2!~lR37w#t@(PSi;Y3U&SDAK4(6S^<*5e(?0Ow&BGnyP!+TLNZx8kgQbRFXr8Gbk5aYt5%>6!> zV)MTI_A~pZrIfdVR7dMb!pU!FqvJ^$4i1FF>UvyS3_frAbLBy=r`*Ahf!REhJ~D1^ zHSah1B2WFtTSV`3A*+r9^S_>26)tvfD-zz{{v`ZoapKL9&WXi4Yj4(hZpeFek1W>$ z@9F);kzMfaZBA>A8B|LS3-a!~^eR>f@)moy;kI3-JJMNsZK=RN z9B<)wA?q$fq9`E7rIj357gT`Fdy;jOF+!N~c<)E+7{$r2Fot82%Z~%8J$|aWBM+bV z?qtoaM-<&a=rK^pbqt@kL=K;gqig`x&;PM3jAYeu(Q0h$(ckm`EJ=8Oz1Vh)*u9&) zgE+8wYtPv&5rMqlmeQHEK;ASALv|-1@1vS2d0CKmOYEujsCk2v9ZU4}{?=-gT`Ex@QY((QyR`7ChJiz8{5k&j01fe|M zA_^X&aRS~=hxayO_aN_cB8>juDQ`gfGy1mtYAmFL{uL4MlHde|M&Zg z9(nOA1l$%ZC^DGDpZ^Izwmpx18A<&ElIV7_>QJ1w&hBblTtV8C@cyl(n@Qwtd7ox2 z7H?sV0ItW7w_rz^$Lobl?8MKe+wlB9{Q}wt!B^o9QU?5nrFk&e3nCSRAa93w8}5~m zcfs&(E59LkB#B}8Zo3fn5xbvmslJK~5e4VaIKjsiZXDs*=l^LtKlkFIzyaw4T89!& zeq-mpui15i0~wA~^mVSq=WRyQeIi#V zkX`Zj@fJH0-oI!SQ;EFqHTSH>;%(JiJ>CR)TZ^vGe+79zaIZF2fV^`=a{F2mV!_rV zSN^rK!Qgq+^wrCdx67V-l^4_f$hUUKhc?6T?rp5fVId}L-l=yDc)CuD0%F{U?N95h zJg|9B<#{<)3sT++@&a1NC{BJZ2OOizTG)}hUG;~ey775`X`pRp_6`N>yE5C7>+zo; zC2Wp~9?+bmdfo&+^6DtCyXBcxvDm$BNqGOreJ4TW{f7C>DlFd3{h+Z6@}B8W9D50Q z`&|@xc@W;-$}6cxX5i*T`Ik!M#GfG0abh6uF66D7XmtHL?p>_xaaO*X{gish;K&deD*`nFR-7532WFUDO3Hv1>-TAIQKJ zd`g@QXnRV1PPfPvXAax?)O~aICOXS_S_p2}# zZ}Xl`n&Xgn>6YM`PRRRu$jdc-#Kzjr>pdR$BI02#a^k!{y$|khjI13S@!zZ6k(X#S6E$td`6ha>fBc z+FFs>-|!1ZeES+dLEf&ky1|3+_Eyx`k(%RyZpamTJ%#my*t`P`O>cFd6#>LJlUMh5 zEL)1r`xHC#<3SP1F6MV?5V|-+G-QVuLhlKb1{hd3A-Meq+ML{gyzsDmpGa+xLA={H3 zkhj9UWyM@@b3$&7#COB#STL;I8rl9b7-$RVZ(xD*|9-QWZ8sNqgX-F*hi*vsg{B|u zKG=(skqgPY2XBdhE;KG=Y<2FY6l~r}3aL_jdX&d|5Ut}RPJYGLbDe@s*^!v|Hf=_A z{Q2Lh@fI9=NdXNugh=l`HRvU*JYl*c;* ztz$1vegk5a_dkSkAg4Yn8y#}M=Y5Ka-{cb9dz-RS&>ugEKmUVuJ!;>c`%!)OP9?LB zBG#++hX20*k9$$4hyd7wJpQW(*)3DZ`p*%&Nj$vLSUqTIqtGrx*n@-$4A;JaJxD2t zf3GHd28lLS@lnFrIFL3V)y5ef0!)1AzUK&xB2M4CYI=Y6BLeR}iurDELqyF?nl%Km zFR{a)47Y6P7X~6|+{bXwKMF$Fm)H)QOVJ~KlsEr>MC)k5$#3^;YNzxEHiWlfV({fW z9q#wYcx*`*sw@$~}IO$`Q$J-sPLj@9`;D2w0^NUdMIBw77J!Q3hhp7b949VCL)bxVfK&D6hwv>>mJ&4ssK z2&ONtAl*oKFM0bkmdM*C_KpM=@B1kXXYCWH{v>)$_JZC$Ekj9S)n7jxC ziO+kMp<(~WrV!v&`$Mz67k@w^j9M-UXRM@p-h@H&>iFY+@?Bi&V)u3-;Z2uevxmsr zZ@Ik~7VpQhQ8odP_q*^1uHBF~U+58!S;*U@Af!QKXB;qKUbTMOA_P2jGkp;bd0!l- zr%Qmm`Jx=zD^9}2$^O;0;ttrn4;I&mgqn$fIyA0WZ=+;?AU1D9;XO;L-cla#aI_8t zCqFf$v1E{g9hu0Rk=DPA&-+V)X1EXBdn@PqetKdKe{*7MZCUpL8Z)Y2d+XgGuZ|~M z9b}eW_;>%GBIbL%B;fqNkE92!kgSR%_Mmnh7DcQcR1%=($PRnZM+QF6e%OOD2~FCO z@Q58j;4LW#KajT9JSzRskr2>1-2%AbfW&cy=UMfye#EA^$VzJ56ej{~;+iZ|yEhXD1Tdkn-N zZyD{iS-FsRBCXtO`BqoN?d8Nv``_3bq&=b^6hF}m17aLMxWE0>%W%w%K)-XLtsxgE zk9Rv-hbK;c$Cs%oj8C#6N?SRSQ;*>DPCRj8%gQ@GVEr-e^ICKGE6C_a(mK`$2dVxN z8~vWVI%e6wg>wAeLGmWy&Gh8cIU?_@y6bXSyt}2?Z6zRY-e>Q57kJx-D@~?D-ogpY zUN(^T-Mc*mZpeG(t0AlPkoPH*+?I2YcX_X+x$i?)1QB|%V`D8gZ)0zcZDD-EfEcHv zu&-`?CN}So-rOer0?Om9kJjOflb;t$rb(qH8{#{zl@eHt&%5aI{wHOGaKPgEeaEO2 zK5yM?u_Y}N=2Sl*=~k0h$FJ%={J%~w4oF@kycrXwjuUz3Fa^tE@uus{=UxwaN7#D% zyoJ0!&Jr${L*55%mHe90;0Mw}In?yy;0Myr#i-gt-q)RW{@4b2yQuA&9j+r95A@TR|7Eco1%e~C$h`bMc zFp|OIEyhvuLL2gC4-B&#=?LYw;XXis_Kf(n_VW*ZTt=8@lHqUV8qGK zarnXQD@JU{hWI~ctUuxNw!NC#HPaam80lJE%s=DL|FbI|_o~v?Q9W-p8S?6odBI!P z9P{t||Gza;{*V5-aQ^ov=|P;LJWRwMRJ?&s6{`m+J!GnV8wS7sH@ETX2iSwa%(1G= z@C?%RJZ$Yt_Q!#9`)Ut8h4a7Urp|3O{G-S-CcgcKzx$CXV`Mbrj2q&8cSXrpfc*^8 zv0vjM$t#4xUNp{#W0hTRI`%V2OI}vkRi#m04?2w2LBPq6PB@>pOPw8IPrT5UUrnov z_ivn9=j=^?*b5YVVzLRbC*u*j82G)T*%#D5AVrZ^$3TgPXZPO^r1_EXW}o)ILgX!E z(yWZd`&+N$w;{-T-IN7kf%o-9^)~?WHu5z7C=EAAb@N|;Erh)9?d3oJ6!NxdO|{d3 zyob(Nct=OOA-#-UUqg;!^RBKhc#ykB7`#E__K)22+w6(W+bW3Zo77Fp<6VW;u?;7` z?Y9%II>8On4;@)?9DVq_ZwIq^@*edAd_3)L`Va62q*o3vdQDesp!!SffE{^t?3Q_Dp4j$oqXtjuIB{VEI_J?~r#&71!?fkoTLz2k(D|ym<@fe$>atfp_bw zYqKEl(C1xl?U48G9HA2ukau&PX~aaB8zM3oFdz62CrEw2!|-gUEPQ$kjgyEwd$98# z4oLrW-C14v9_8_#Km_{+BJXq^zx7zWt2J0nsu;2gR zps5f75Mgiujq|ln3!jq1e*gc)(hpe!&6LMm1FfSGCqGSx5Sg}kc4U>0`uYbO@CT#} zZQlF#vVP!N_wQ`^FV8XWYX4`E^Fk|K$d394Btk2Bb+m^DN^55=-rn*d)htlAZ*o)%lrSgy|>;sri3ST8UMcj|DXOw!T$s2{}7TMv}$?X;xkAZ z@Dsb)dNu^C9%N##mskidvCpbbRt~@(MELIJ#se?0(d+!y9F&X$<2kjrxP3!_@hFRr zHta!L+W2>f&h{hqrP7kuP2G^^e~c2m3b6;Ia4lmR^&%nAh{j1ornRR2!}tIC_E-sR z)uOx}6o%IE7AHR${?$z$@cDn`k)t%O?D#9l)ffANwuA)&_04ZICf?u=NYO$Oipm_+ z|AKThBYAb?5Q4k)t}R|-gGqSvb~|zqFR}HPYBjNVKhPR6xdVAC@tLhz;Js|n_}M%h zkgh+_dUj4Z4%{Exo%;+v|3A9V?tvrZ-JCM)G7MLc8vb58hjiVLAZ^*0#|N=_pLsdd zo(6>){6s;Zl%?#VIg4E#D{=*$a~^K4_g7`9ngvl z4(hle9WuxWs}nZwwr%~F?!FKL#JH5I?HkU@Ve>A{QJmIxq&(g&XdSn4@=IUY*X`@e zj>Nsvj;7s$&wFw=_wgI{K|qCmdG@kgGB!vHYYOTA=utgy!Xq;4XbNuO`aAyzlJMq^ z3bi2eR@~#Jj>TJ=#k{fs@?MQdfA|P_hsRl*uYkOl?KF_lvVhP3S5-3{hzbEEat$~DKP^*&dTI}8dB)qwtjy4f_4+iR~Ve#IwGveqg$UCE3M}L90W7g03D9GEmPrr)O zBMvxrj?Q<%`QLUfd-HwB+uO1cv4Fhkjcd2xy5)xOpYu%|fV7FuCIjGL95 z4&nNS%{%&GhS170l*fA+T1O;Ke&bii-Y#FpflQ{ly!xGo&wJaR%Z0L$UZA|L*y(f} zKJTk;30H~(1T!V{$8XN~mU ze2WFlNiuvhkoQ*Kgf=0_yO#b;{tn2S^K0=^=I^e^AAbLo?bg`5*~F5fUKj}hg23On zHq+@3Zy2z7ADWoE-qcQcyjP%g;N|zt`}x7#M{LMpRn0$-;_!I~g2S|9YEx)#SduyS4>oUyKVex)8$xeF~ z^6uYp{qPXvz4b!omn6tLjayo4Xg(HnRaM5U^9ljK1;ecPAn#AByLaz_ygA0EORA<^ z5xvbeuP<%J<{f0_>aXo01oY9k_Ne5c@)_*6x8#4NuTq+zJl+9l9eDXId$3IF;0ku+ zvfq<_qcnWpe)jxdm(*DROB%a38K=pZ{~ODsR>V>N+gpTH<>b|2Jsvsly!e6iFcRKt zVlsw^-8-W02`v`y;MgZdmlg&j^V?qrA#X`z*G3P>JLiVsZZ?)UFdQ%AlmL0Zp827< zzXD>G-DW;J1)E{i#w3azr2=b8VHQG-cdV& z;Lra9sZo8BBh)|tzjh_B4)YHKKF90+o&WJ>IEwiFh+Q&)qz8%po_j{@LAI_2%ve20 z({_8)cG!b5PxqW3gFT4jt-Ovm>_OjV8TNdC77H5sSRy9jQ*sQgvjxhq2i-Y4eO4Xz zpjg6th?pyQk8Weu4L;wJVsSAn&aP^B1_AV?pz$ssskD z5b%*9iGCyGZ9lcqcH!}s56asgp1k6UoX(MW-7164JFVF4{pr%j~}4^Hx})dfo7XDTqm`Z;|+dKmR))DBb#l zuaWBK{}2)K>Sz?WxufgU;tDc~gty3riVZ~GB3lNQWAT>m`O)SKd0(j)_8Wz~QyNSa zFF@Y%o;+K}Uc>?!+RG-d3`2m2N^qkA<2@ zG6iS-PHww#mW=s7%f`X}J@vo6MQ|pwj*Yh&6#sVbgCx9#ouzLQc`MTvFT>(pXI@#n z7xJ!K&D1vndGmh_m%j^nXKgK)&*_W>388oDUhWJ5meRqBn;~!8rC(>)Lf*R+rZp?) zU6GoU>05*izbvFE7ZL|LGl6`kz@*|NMVzH(7OfGg>~h%UktDo@ z3{$d*yqQ-XU5dqfq$2fk5ahkzsM&adcWCFwJ)a-^yq$U-qKn&S`s%X zk9Q|8Gon_mio2r256l z@-p)3a9c05_GRS1^FKw*_jpOb`F{yX50YhhAWrN-PABx)v3gMd%ALicum^<+$T)w2 zJ&1WocEwZJg9@ewHI(27(%YogbMrq52F!V^9ot|JVoI&xWrsazK^&hSsJVe6oi7|Mi>h zN9p1ZNcK`IPsx5=2l@^6HLSBHV+9%B&qMz{o9cTIA(+fM;tOW&oECPFlIcl!OFxym zNaWq+v4RbY_j2uT;c}2S!iY=DG4bHtb8RmT~t@TQfn>fyT8veEi;U9GkayzDIn<9m?ZP ztYaTee)mo1<@E*Fkfg5(aS9IjyyMIY+sp>dK|Eh+p~4S*-rW_yH8S^zQ2h!rrI@@r zw(YF0Iq4d+z?+VgH|xPvE3ROGAK0&;4@?n-kaMcrI!}-jm;7Pa$w~;-t&+KCV;P zyvtrit6zx|1jo?0UH)uyUpcV{q?#3Mv+-<{Hz1Xxb>QW9D>L8Onwbr`<5JVzcNL#^ zt7YAA*1c80-ifP!#R~kxiK17sH%UwEpnBfq)?sXMum9`7!u+31L&96a()j|B_lcrN z7A)Q)H-}ysLf$uevZNMxf4XRd*h1c>-(_|<*2MxpCJVmJ;vrz)XP?D~6R#u-3+!50 zoO~+D)c~#tmzjC}?F-nvi^4*!II;u*2O75|qD|RU6r1<^x&ynb}^zuZ{=IX%~Zek77Zn@4v9~aT2KEy z{~vGiri|ZV4`L+gLF-1H|MQ65nTyK2SUo87vFh}X&_dm#oj=!pgFWboy6(Q8@C#DY zpROOclNbwbI18V%%?$>|J&|s|;3c;DTVWL)dP4N^ND@eYsLaAw8s_#LBj!yFGNV{kJ_XMfr5bGw}RB z_U=5arZs#V{@%Mit+l60nu(HgUb%h~H({j<*6zw7Bc=UyWf@4Z=C2bge(eY}NR z&;-0Mt#>Ni54`O@9M{Hk#aOF z>tN5hWc=s)e*v!pZ_{xD?vcC)m9A2u;=OJAxPIM$x9-w?v7dmq+u2p_x1d4dPSmW? zEQ-fh&e(GF?!iU)LGF|((}B0f4Tl{q!25(<)w8wmaH6*0x$RXS>IbARC=Ky;T+|EK zl#SCEXx3-*BWm7j*A6|qf!X;Qq>HjT*3rz*%X*9Q4J{?CS!cTbyl(Uj(ho)HeB^;H z7QD$eGP;7kL1N@Bibyxm>GG>LW3GI4ddo!I+hnEyC3)9=o7;_w_tH~6 zK4}5((M_K}64%~H-oo4ASG9n*?)cFLw}5xn%bd!oz`If9xZ`i&y>MrC&f2Iz?D^7~ zkKO*`el`!3& zKKn9F=y@;k*~WWx%>w`aG~lz(S^CY%*sm5>&!^^fdEWgW%U4H_*!B-I|GxjfbM*Ig zvw;3z(qRp6QmKVjeAn9L0*+V_g;biKj7uM-Cto1Du3N#um`?Ds=e_*Qj9bn zf20?6;PAdhxYqS9F((;Ggr^`{bvU$?!epn5dS-Qh#eN#qD{s7 z?u?Y>w}JPP8eI)F zvD;@jd%Mn-w>lDdhYv7$JOp@aIVRa`-57|KEwCKjYXCLxLE0k3n5>R5H1jjqJ!Zl-6}UlK_wMEApXqsDST=QJSd2ARaCJmLiX7kn zi%6KEGBUTg%k$ovC|?~jo@UKb&;P?)*n#)JiK@{g?{CxdHK};ddeoHp3V1Ktp=d$y z9{Dz8#B|{OxnxD7U2;6Gj3i!LxM>mIw65a1JMf;Vlejq=cyBx9e6#U*Aa-)BS;mtI z)V%Y}#1UVA>)n$s_3MGEZz3}a_aiP`&)_sbm=54c}-^D%- zosV~wtPVSx`9-Z>ke8#TgdLjIw{_rHdfvOY)Qu<^H5U72dhu)C2m1d1eeR}!_9Uw= zzxSTtBVQd?mkc|x3EsWMVKA61R0RLmGTkIClJAlx$vep_$ur4A$sNgc$z{oT$r%YQ zsgxX&?3L`4lt?y7iX^Kfd6G;?ibN_|CW(^FmxM`zB)*c#k_i%5$tcM%$smc9#7xpp zq9^GgQIjZ11QL$8UHnu0Mf_g;O8iuOUwl)1MSNa-T3jVQBHkz7Dc&Y77OxTKi!;T^ z;yCeA@gi}!I7A#Eo+h3ob{CHoj}&8KJMjRqiP%8gTdXDSE|!Q9v4W^g)GTTeHHuz} z9*gdZu8S^-YDCqdW1>T%J)#|=Eu!_JRia!`x+qb!LbO=4P&7vrESe#jBJvcC6O9oK z7Yz~Fh%7|?MfxHgk%p+7NF?Hkn8Fs}H{nO&8{u=|L*Z@VRbid*tPmGg2oDH%3rmHY zgzJQb!fauxP%2y|j1tZlh6#g&zQW1E2|`!lDB&>SAfc7eOxRDTC+s0q6DkP>LXMza z@Kf+b@Lupr@KkVLa8qzaa9(g)P$f7b*eBR2*d{0ztP$i3G6l(kIKfiEB0;zyL=YgD zCYU5}7mO8*6kq~7!2p4Yz(CMjpe5)okO&Zg0@{W)qfKZd`VxJN-bJsYm(Uut8a;*{ zLieCM&@JeCbQPM5rlX1I3Uo2L5S@btqchMcs3$rO9fJ->hoCm71==6gM|DsQv>Pfy zc_wXAvB!Kn@_gky2z6vJNRkvXN9oiY!B-koia$5`_37 zlaUFCD>4chh73Zi5HqA7qKEWA)DR^^fN=Qj{Ga?U{P+A<{HOf;{G0qM{PXVnHPdWEFH#t{0=Q*c2Rh%Q7eVm<~ZJc7x8cseZ zlatJe<1FPY;)HWTI02k#oJkya&REV!4#u(L4B(h>3^=_xTAc122?yaQu-n+p>?U?2 z`z8A^`!4%B`x3i`UClnmKE&R`-of6&Ue8{|&Sj^w6WJ@+i`fg=bJ)S`8SE)+Pxd(W z81``X5Vj55g5963&(>jUu)E0)-ke{Z{wV%;f`5Mke}4jhe*%Ah0{>Tk0!-I56t;pc zX~e#8Y#RK#na-(8A&yCngg82NKEzR}vmrXA216W~>JM>5>NJSMQ@tTNrcQu3EY%Gn zmO2LF(9{tShor&@bLQYwdx(QltsvT`nnScp?GMp5wJ$`Q)ZP%SQ?(&lrK&+3n5qnM zKq~A|nU<-1h!&{|5Y1DTLo`cS4AC?t0-{MuI7H)=P>B6gf*=~D_(ANKG6kYxiWfwK z6nBVyQ(PeGr;LKwC&dw>Udj-Nx+%60d#4P5*ek^pqE1Rbh&@yKKBrSpXD`^qLpGor|{zwXg*qk&I;`gK(5Wgi& zh4?jT62vb_9uPk#xk7A88V&JN(r}0$lZHb4kYoq(ebPXP?~=?QHYOQCe4C^X@l8@M zh_92hAihdch1ig!1o35(5aRPB9>ix!EQn7NmqC1z7!C1p;zEdz66ZpEm>2@_L1G}p z`-#2~?iQ40PU z#ZvIk*dPV}jP+9R&nS|Df5ti~_-Cw@f`7&uDfnlsmV$rADk=D9tdxR(Mxhk^GYX{O zpOGIA{uz1k;GdBj5B?cB@!+449S{B)S@8i7GvmQOBO@OCGt%S1KO-$3{4-MH!9OD< zek8=?cn63{@!+447!Up#3Gv{cA&m$BjQDs1h;i}YpAj1m{uwLc!9QbpJmG&?JmG&y zJmG(FJmEh&j_@B9NBED7Bm6IlBm76i5&jp(5&jp%5&q}L5&q}J5&pyD2>)~A2>)~9 z2>-L=hC>XCBm9TP5&lEs2>-L<2>-!xg#Vdw`VfQSdO-|~Bm4)%5&r$-2>&zU2>*U@ zgn!>S!vA!F|1?7XR097L!oCkde=;H8n}9!waPLL1_axL$B+ySF%zF%j;7*7iPkQ{v;|!{WW-GVxaN2Jvcfo;X9C zB#sp?5l4vUif4)a#Z$#z;_+f<@d)uyv8~urY%K08?j_a~tBA#7zL+Iy6@3?d61^3@ z5Iqvz5nU5q6rB^D6jh22ipoXXMVm!MqLrc?QJN@0v|JP|S|FM&nkn)V`G_Wp+(e^A zj-tULYmvFgNYqEvQ=~3Z770aM5kvS(_*M8p_*(c(_&|6|STDRFJR>|IJSyBT+$Ag# zZWOK+76`M1DZ+SRj4)C-PZ%l;6iyd<3q6D`LMNev&|WxDXeu-m>I$`mszOB}Dr5_O z3w{Vb3*HGD1WyF_1UCei1+{`xg5!e2g1v$=!B)Wr!D>OCAVZKOh!rdmL}QbLr0^I=wQ?uHAjumK4?!=9aTn! zC>LcQzmTuU2jn&K40(XuLh6wV$Qk4WaunH*>_SSAjmTQ00Lem9ka#2piA3fhp-3Py z9q~py5EsM=aX{>mfru$$i0C5Ph$^Cppa`4)oBxCVng5R8@CO+<`}^zfPvGxQ;O|f1 z?@!?GPvHNLp8zYl5H^0Sq(a#Eu@VbmK9D1?n4 zYk47T{8-BhVdKY&DTIw5YiS{D{8&p0VdKYITnHOKR&*h3{8&+iu<>I>7Q)7lwWts_ zeyoT>*!Zy)7WRU;pb$2Gtoeno@ng*^gpD67ybv~itht4-@ng*?gpD6-b^+}CSYZXQ z^<#w=z}}A)QUIGj)~o{9{jq`zVEf0KSpfS#R!{+K09k;qZT3ScA1npyxmLDrN4*b1_I3SckDnp^;zL6&y`>;_qr z3Sc|Pnot1yL6%1WYzSHI1+XDxjW2+|7}mJ_r4ZfnBO$ux&xh!eKO5rM{9uUA`Th{c zrR85QpVkL3GGBhlu6(hd4C9FT^4F zy&(?H*M>MKUk##tzA{9+d=W(3d_F{*dIdFfRh)fV^;smU*ENE%JgO zn&m?TZjgE10d?>nL_N7*AJpz zULT0Mc{&h#=V?OhmDe4jPM#vfo_PX@J@U8^wey$|wQ^%1YUV~k)W}@`Q9XAKM77*m z5LI&nAa>844pAj{GQ@7V6Co<+j)SO_>kLsbcO*nft^-7I?jVSwTx*EJTnmVTTw{o6 zt^q_OR~I5bw+BRCt~x|+Za0XWTros;E&@>@mkp7XL-=Rr5dIlC;Gfx^1OA!6bHG2d zEeHHFTXVoavn2=oGk@iPf9B5|@Xu_{0sqYJIpCl9EeHHFzvh5{=9e7s&-|P-5Momf z_-B5~0sqX8IpCl9A*UC__c`F7`7Q_iGaGZ1Aim83|I9Zz;Gg+A2mCW%WrKfaLpJzl zzRX?-@kKWHXFksc|IBCE;Gg+48~ih$WP^X^<81KHe3T9TnGdtUKl4F0_-EeF2LH@^ z+2EgfHyivj?_`62=Iw0o&%Bil{+Tzk!9VjxHuz^=&j$a@YuPFguV#aPW_>pJXI{w$ z|IEwT42YMqz(4b17Wik@WzC0pJ`4OaYqP*VvnC7tGtXs#f9BaN@XtJxH38!3Ebz}f zl?DEp)mh-5c`^(9Gx03&&peR@{+U%-;GcOs3;Z*WWr2TYWfu5nR%C&H=Fu$h&peU^ z{+Wlfz(4a)7Wii#%mV++1DW8Txjz&9GxueJf9BrIaEN;{!9TM+6Z|uGXM%s`u1xUH z+?fgfnPr*o5O-vPf9Cc~@XsvG1pmyEOz_X#mI?luTQdhh+>&VuadRg4XKu;_|ICe< z;GbEX3I3TIGQmG{eJ1#4uFC}f%(a=|pSdOz{4-Z)fPdzy4DiofnF0Qpg&E+VS&#w# znfV#upP82d{+YQM;Gdb30sfiU8RH;kWq^NXW(N3YW@LbWW_kwrXQpL4g8K>4g6!>4g8q>4g92bi#jBI^jPuo$$XXo$w!#PWWG#PWWGtPWYdnPWYdfPWTT` zH-k7Qo$x<9o$w!)PWTT^C;W$`6aHtV6aItK3I8+G3I9Rqg#W-a!hb*-;om=v@INDM zE=0dH!oP1C;eUD>;eT2h;eTox;eSdR;om2X@IN_?@b8^Q_@9(U`1eX9{ClPm{wJmp z{wJgn{yowN|L$po|M6*r|8Z$5D0-5CE1YCVK1*Ie&tD5y`gch-NOGXZkC4oS-riX< z7<&3%5@qP+zl&c(4}Vd70($q&;sWT|qs5`ntGkIEphxc`Ru%I_zeMk#C$ATsf?m8t zv>JNw7|~qly*)%DpyxIeX^Mox-@;GOW8V;-gWkGKSR~9s_oG{(V@*MqK&Lt#9S@%aK5?FLZg9?Vj&jO4 zMVu^7EN1~HkmJP}&9Ubgb9!9b_4qk`vUtoyPUm|oySgKN3v(Jeb_GSp=@)u zE?b4oRrsOsR^frdWrdUf?|yp1Sm6RV6X7Ks4QC*Xg+1ZS155A~&N$o=T!1qT<${fH zh9N-^31=331TJt!!CasVXA-#R4>*JH0KE(Z{{6+=|L-6F{-F!}1Vjp4mf9B4lwG&W zKcVxGIA+wT``5(~P|7OTs6Euv>w)+1N zqoHKB#s1M;G=$7H{is-o&LXpo^;bWl!DLpvu16_4lgu{E)v8B>$ZWmUJX17~%!*X+ zTcH7Dw)RSX8|qJHYwo_fiOwLi)$`f}s2`cFvOlpF^(C{FT(@L&I++#Rw)%ojBeVQd zr+v|>WR{n)=OQ|V%yOq1l%YOkmSZI`MJJP4*5ls`QExKK++8*to%CwXm-LuN7EUaUb!li89o z=TdYOnJo@)JcK%tS+t#I7CMs5qBv*E(Gg@8$#Drrhm%>v&c%tSBbhBMxY>#hBeMk_ zX+2N}GMlgDw+zL|Y#u}15*v`T*v>%yyR#cxs4asccVy~5`0hvu0-eW4-m&`nLYpB$HYh$)8C51TdzU?ts1ljksrV?MieyGS zZ-+|AjCec=6_Xk9GzTgoGvelVR7hsTy~3z~%!s%4peUIUFF8RGG9%szf%3_Wc!VD1 zks0yCG0G(~;@!U}hs=mqrK0SAGkCKksz7GMi}+9$nGx?TLz!eod_f3hkQwp86{MZa zi0@M%zsZbvoj=k>X2jdikybJzzC(<(kQwpWR^%6%5ns7Pev%pSQ9$GenGxSmLz>A< z6FKLLd?z#Ydw$)JZ)B!+pn5s-mCRI^M@>M!kQwnMcH}ecVlQ`r!}Q-N%JmZ<|87{qRQEfc(lFZoac0Wg6keR}U z$-c;QGGjU9>LJg_j43GcL7vJopY{haddL$p`+eNY19|*!W*#^Yc|>Ndb9X;Q9+Fwh zActb)0h#?`nXf_ali82brv}J9GHXue9YF4q*>~5e9OMp}eKQU_gxn^xFYh0jBDcuw zb9)8{xk+YCtFNXYH^}UhSBVR9oyzgg7HK1e;8H5QqwBUi}m z?R54-GJ7#c$rCwGX3s}B6d|=_ z_Kb6H5K=>CPwqRGBj?EMaq0SM+S7-YP!1Mnq9iBlVb~WT9cB_P@ec&V)W6q3u3>1F% zpRq8=cXr5JIJL$2IAD=hDLjK@FIjEY49_6#G)=aSg=dh=Cy&m%vNawrXuo{O^~WMy z>40?UGk69G-L>mvCOrS|WIL5x|2hC;+|`WJ5gOv*MBdkH$s#9izC@_kefCls6aG0&k_k zF;QRZ1F+1(_YKn~QuE%tv1Y>1`#ta!**Na5#ddp_QuCf?aqVZ0f~eE+-YKgil4gFE zJI+jXa#6&dPCnXp^fW#1hSA#P84f=9@7|-c-EJvjfA90Pl^5IK~8TRi&BZ*8%U>%R&Q9;QfCo6A#}j zdbkMB8MWEzGVtD~&n(;nyfclk+6FoOJ0I^?vO0ok<~Q~!XW(v$5_aWszuya*>3QcMn6-|BKmM@kE@#&>dfu-a z%6_fO58J@k8S(h7sU`bwTwH{EjzZfm0PhLj?w1b%Z}$7KJ64_wz{a)Th?sy< zuimaYx~W$O^u))?#))_LkKSib&0Dh0)78SK^YQkQ)zOV+ekb!cLJoNL>F3+10DqkHh(<}4l{rUc1fno>V#F;^o zx8Eus9V*^-KQHa60p5Xq7Mc*e*9R|uRRz2w3$L|rj*rL1%}XxNJ+ufv;quyGC-9zp zZQQLlzEgVgA-1`*dr$Tet7h?)`A8WeJM`NmjSgCt)r ztoaFR(52nReRjYawDBq?^8Fl-zy7&!|IheHT<^?K<>|c|u>lwA_$PnB`~MmTc!W9! zU>{~49oF_Uh_az6n=z%R#Y!80CmRLwt} z`Sqz?G4HCDBKAX5_0h|Nt(0|=b!@owD(k}r8*D;R{g zDjqj~nLB>gyh!}o>fvi$f%p6g1ETH&?_h(#FGO z<8FQk*kQ4cn)h&iSm3_Y&c}O{td7w%^LzE<#plRLirB9i8+*iFr{{gV`i-_QXB}&<7+C)E1}U`;yosyVByZ()XAG!#|9IG3mJPhq z-RGD50N!iDW1bNG|1XtQ*$NNh@meHvgYlF|e8$2-v5vr7@NDLi55W85EnA&WX#rTu z*|?>PJgFO`#Xbhyr~1E5lb__(7T88SEwsu zSL_zG?$)92|L+9O*!5d+3~qRCNkhgc`m?u;s*I;sJ`V5t4N|szb@U2R+j9SCB5`_4 zwF7VBb_|lYb-uJO74MAT%+;%aca)b-UxN344+SS2Bk^Cw zYqgz$cSGLEn&-fqUo|Gza%li|X?MM%S#N6I;Yf>QSgAICUN&xu)&>1k18UySy;&1i z-0pn5qh)oxp_$*?XqL@{M~c|YFpc6_F7&)L)m8Og_4CG3-d*|Gq)8Zd;6NhfE z71VEQ5#6fDjaou}o^=;_R6xm0y|-VALy>sUK}uG_l5{Xf~Ob?V>Y5ZklE8bsV- zNv=VNmy$Wv8dO$oW9b8HP{dm!ZY!)oJqu5rm;r0h#>aCdE@CNOw1u%;@;wp{&bT+` zCagjC^hRp5H9x`fH*I+Fq$L1DjSM!wpF;hL-ETIZ&bC%-<9yjTi-~WaCr+h42RZ6$ zP((~q=R3r<$?9;SnV*wK|9J&%ikOds-@*JREwpP&Q;gB&%2lq|{?s<**oX92kQ@t7 z>$Y9%`rja7*~wQ&WB=`Gmy`b-VtaJpP24g}@^;_!(v*sKt9`etGl(6e!@i6b;9VE- zs_#PJ{h?I)ES4+9RkLFYpWTEnNI$t3ybpNyW?AgDfgPmx+v0sK?*p)x=ii>3YDCRj z*I~+4)3@3d2@=oe*ZsMzB&y0g`sOJ|D4{^?!cS42cF~|_i%>^ z74NfNYet6v?*`{9-3i_$zUkjmfp^NrRnZ=8@pz`fij%5)BXI@AH+~tw`=KT}J_2|b zA1HX6JAsl{Q}f=_Sf%hbG+4sCmJ2J3;7C%t*Q;XvsdyJFx}1sz-bIgxYIWqTU0An$BJei< z{jOXac&B_Su9^e9U&kA@l>qOcUMX#NE(BmI+!+r~J)l0lwY{%rxa62N-c2@cSQB3% z`zdw*AF%i1$qjEi-`;zVtd0b{?x9Q6Ns9o8V?IZbj6`s~ZLrdorJ zEVI351#8f+)Sjb%!yz_6fAYN@@QK~L6Jd5-3n|?BSzL5$X%s$w*NXj?y&JKkrmpk- zq5n^M_;Eu0u>ef#;GKe&2r!GY;2b3I*6qNXc<`9yZ9o6gKq}satkBJL5%9jSQ#ocH@IGmNL+G(H02|VtKV~OJ&D-PV%OuP7 zTDYBT-0f|rrmfMU=Dq9H)ep08c0S%dvO4zA%x~1$v<74l4SbE;Ccexbp*yx1EP8M8Sdqj>MWSW0Pw^<*%{0@@QBS5Y?Opkq; z_G!*-o&dRNZt<)FSn%PUDnK=Jr;OJ9hH6{E>3uynclD$c*ph{HR4%sDc%|r z(p)+`3ZI#`!c+{rkECqVDhA%09hs?fHUwbP&rTn6u$8(&3ZMIZ__iln_!QYVLHPXP zhyJ5MGTwn&Y*X!g4N|nM4s)9MIZtgfP@bfOg$1%jf@So)y-we_8x%JZ@A<>>dGTm^ z-bbglerb-I)#XobHAKo+NA9qb>}A=1cY>UDmtzdg{%I^Y;LA*PES>_gPsT<7nomtG_RPNV)wxU0uK-fQ9)WaFwm zZf3{pQm;Ydo1R8o>)-iykgc*hCeqCB!ewdqr>RPq@btkqUv~VY?f)ICQt}ndXJY5> znU7e|O^zF+m)Q#22M}-8?c%>;t%a^}w!1qPr?}vHJi3i@%XR!f~fp==3(2X(o0GfsDg7eh84Z~7aD~;@Yym!dzFs7N`%%w#i$74#^ z{ohaa3RLM&Z!w;jo7Bx3kF|W;f3H|wjvJ(X9vSDdd)Rkz-0&gI-iPxJdEAla5-(mqg)f z9M;$S1MkOY`CFA?2brA6zE*K909(KQ@|29n)T?(&H(hnUo)*4JHtyD($4#+i)Vwv+ zYK|uPc0S(OvO0Ru%F2G((*7j-WOMip3OIZ1Y zCe7R~&wFm5e0Ah$Ty+ah6yKEd0rJ$VyD;sy>K&y1x@uidp?a{Hfju*vtKHfiMb&RE%Ury?V<#WxIFdvoE_Nvq9dH;~{ zc3}QO+!6W)Y4n7-)BLY5?DD)PkCm^E5%$=zYgvC*?>-%P6K_l(rsy?N=`93yzQ20fcwHBgE_zcAD6SZWj=U~tG}81Q~MrTwTg@ZM;!uC5^} z0P}PlFx}-pPH!RJuKN2zwD9q=aR>G|enT%(^RD`Saqx*PosYMYtd5g3^Sd}a_xaHI zN?65EQ`XOPdfwyLj_Hwf3dODu;F|TSI79ir{lA+L;kh=$r=Q?E2wnWw*z@w$v9(XT z0qnj1KL6hZ{=T9AH|ekj5$}v9)*zz)XBAH1QmsLQ9uFG#C33fe^8VpVSkNG4{22F; z3#Ztz8%riETqDH;V_dO!!f5>KeDU{1x{cVgGrKE1zCFS8*0kO11JD0!R!99f>qfnU zbeeQOL(x(bSCx%>dS#E9*C*;V=qsNY6%mC{HeCNxe-mS6bu`n=FQxhCwuxhvu;hka zQzmEspj}hOE9s4i>*tGoh^ZduQzXY4G-TMBqYVSPe*a%8XB`(ECz}7${~LGUO}qr1 znHI_|()s07HW2>b=yY=FOV7x#^OZCeD_P^K9!mAoL_P?~@X7#O1Y}k2had z$7!1RRoJXB_{vto`i{E(cxgR7@AZO;RST4YFuO%H_U3cwPj3x53d8>F{fM?@3#%W4%Y2?Gnh@yTcL8qlj3EX_+Ht# z;Fz94Ys;y5yH+qRo1N@@yb)O)<7wuXGV++9+h`?hs_o&{?CSrUZ4s?0m3?n(~=o@`Z?Vr`#r~_}}GZiH7-m{LesCYlle&@*r-l-ww zBMIK9&Z9xZ&57zhAJ?pokm63=`yKjqFA6VvJoyI$c+WR!DN%y6x1(M+1uRJq!1VTp z#Cor#=55zE-k@}cCf-vvPSR^)@>ngA ziSMqEyro&$Oe)^ILjl!7;BDra^^mwYk$);Pi|GGnmLeXx0aEOT_lWt81-f_+j-yGKkU`H})r%x@R<{i~+A$oUP6W=czH&=7wXlFla-YUDlZ5*rC z`TGADSsm&$^Ly5RWR(I0g3EVP>68y)N*6z|PFbJ1NB#H#e1a z8ybzfj_9#>9q`7M8O>1!-q%^!W1q+Vn1AV)Z)P86z~1HtA^K3bJuwNt-U+8b;0A==qsfpXYQw-Y;c!n9MP$n#6<}^cxFk7#)@saAvj@s^7&n!}DhAJOF-q#&Mrb@VbhA+C%0vwE9#;7xq& zlH~0$Zy%qE_wj=|!dJlC_GaIq1n-@j{2Z47@0FO2SitzHJ(f=QWNRu?u(` zKi_Kb6L^>MGNUil_+tYNZ>DTtL(O~1B^QM&P8ztSY@GJ}4`&^9sCgG=Ec~%Kzw_~4 zE~{fL&HUmHCN%oRDPkVsb$8Ah((_iBpxGCx_rTTWMd_ctPv0Oh0-N$z_jK;^ykkw} ztK;?O-|DY6{#m_EJMbpH-b(VGy)~Cd#e2@7Gh^NZZ{vmwcZrJ=4L=8DNR@4nBY!B zT-HzeixcIA7j)`omvnjFU)|)ZL$rRh=dAUA`~Ux=KKy@bFzg_0I;=s&_p8Y@Xw7X` zWvVqOxc)`NAy|VZnN0TL!WyK4EKlG@4RBa?>GRI`cT&9jiq9oW+@kT);x$ieVGU9! z^+`GhhgieQdR1Qj{+Q|lZbSVv>NO~9aGcPguR7jMHg4VhS&<1xmr(Y_cMX$viI?*_ zUH_jgtK%Wf{A`0x-LBc9h_zk`A9HE^cgi|RCi{2j+<7*|53{SC-n76|wu@?7SMw=y@C6P}dme z>x%EXGNIVFU5*`OiPz(yhNrteZ&&&1m}M4!uGgVIJ4mYzyn_sWnvlHxkKK__@m3fZ zP*e@Pvzyxs2;S>Q+?+lNc$d929Gv|`iXZP^vI89(jjuoG*i;0(hptno6TuGBYW|qo z_Zj|}@g8>6lN@T^D~c`8=g(5d`^m=X*m=Ev_?>$7Hn~((_n@lt@s5?%VM#N;Cb*D1 ztWXi#ypO+R_Y->F+2W;GjgmcXJA==(GNk7n-)y08|IE0{?;!ma%2&q&$zsObls~)& zcHkX|Y;`1gpMAVrOvQVdQ&d9@@HXx9&Ya-A`2N245x{$dTibKZyHY&CW@qEK(b2eX zaLesv;63DBslGYz4!eRUk4*E&1{qhVlt)wZE_zUXXHtebZYLY(shGUR_Bl20u*J4h zMm_0#yw}U>2&b8!^zgzjN;ed-^8t^)&E(LZy`8mH(e`JAJ-%qeyqRa;$Z>Px)FrIs zE0$fJH$zX(I^tr3_5azN4Cuf+pvbe92OS%?I}a z??A1wlb!0NxY-b&%yOq_{Pvg|6>-43J*#DtJ@9TbJkx7$qd(^HHI}#EB$#rqY&Poj z-Qfq-@$s^8(oL6^_1#Q;dMh&Ect9n$^Y#DcvO1Q~%ugruTaI$BBDO7-p(~zA&s$nQ zXqO8s4EI&Nby0H<{n=Z_n8ky!QwO^~ZzuWc*f89q_eQwA9!MQzun-VmlORh zc4sDBE1zAoy~{U9vl_3;Rfp!OCHk+E|LhKaFW;vhaJtsh@M#Y<%px?Y6cxMcn zQO^V3CaM+13BWsHOUAl6EmGWj`=M5IxV`1^Gjnw(;N7i<71jp4tqwn${NScPrc$k8 zY8Xb%yKb5P0u?oNTuC-Ab9A-($y3yaSf|HhVy@5Ye7wmz#?s8M{)FiFd!{m`Sif{s zXaPO%B+JRxIZvFh1xJjfYQ^*o62oihy>O%d1vf~0$XUmr`y-0r6+5tc+jrm{X71-k z@-~UP*`12Fef+i~TY&dG`|t>Ycl8eM!CQfM3~SHbq0LhKu+Y(=_o!%m$FLa(jexgT zXm8JcaC+-VaqX?@^Zr;+k6kSSrjeaicJJC)Z_m_O&1~?xwdJO&l+|!@$ZwB7e&JFkbc-J4}r$4iG zv8UdgoUzzHP>`#Rvt{E7r}Qw|wvn3mo?egGRt=qx_gPsT2WjTFc*{$FzY;}kZ^iyF zrYZf|+f6zN*oawv*!NbO@BSh5*Z+@ZjQ`=|pws2|-nx47)zJgd-&y*%|L??2e}}2T z4suwBHE3bM%~o;^dgeT^C)FAh`{ZqN46H$uNJSjdf2AkClxJ zEt!|NEr$9Tqk&t0RJDetkL9liY48VJ@!SEH2u8rS1Q7{EoEM1^MAA zaZ&pvV){cY`hKnFsP7xP{2HWQDPJ9ttJolDE@EW)CXfX+=*w z=L!q!MmMfBh_p1dS_5|<2gUW-Z0`Ig3D%dbV0`8_D?D@+e8gEv5_#_N? zZ_gZRcM^D4c$xJ#o)>^gFT5E0wuYKF$Ea4nm%ch4CmUB%sh>Qs=Q7Gw?cL#C=ljHV zKHe-@9Up1txAgS0w)h)LnAH&eQqcu^-p_v3zCP~fh#z@><5}@QIj$ge%kyws-M8yE zNQiuO>_6FS?25EMtM||jyyr30ElJ+K<8m~qcqcZbKga;yJ#GA-q{n{0q`&X%XXGAnzN_10) zx4--|Zu^yWJ06=*^XAVCaQa%>`FN+w>JZY*@9?qVoMpwz*g2$c!Zn1x|9|0~!@v68 z71wUxVn3pip7$AT#>?8(hFyO3&M9brAx|9+79~{&{&_fYNC)0?Yuay+yvq*-X;ASV z*k@5e9`JrpGB>Fs@2NYl^e_S5rbaz8X8`XkyRu+n?|tyjo)2e%w^4c6($~NIF~4=K zBctyJQ|`S7?|Zq>_qiHAT{iB-dSQNLf9lQ2v~d|lGqBFb+g?`344U~(+dC=jLzWU2 z-;%m1&77Y15G&VdN=IDrcoxHkb(sFz8{@}2$E9EG)}0a;w1?%AGP<$F2If zIZE%QleqVQ!!J8k9xZ(pakrWL@O z{n;vQ#3_Hw#UeSjdkgg;Hhti{m+E&_adOo6XU=Hw}@p1h<6nHP>Yc;=s1}XaVN5?T{3AlUj zsCeZgQTTI{o$-;t+w*-YXAkhM$+)9&tkNHQSK81g=`J;Its(E0cmJe{ljBwvZ_Yo# zq2|5dTkMXNo}G`kx~z^Un)&suHfSF6QyCl5WFhU5N6-67oW;n+hXe4&J=ZU#6TH4-1wmB=|g(n z-q&plej8856@S?2Kj=x{|Fgb)9MEH4S(jhEecs7e$0e)T!we(-+}`5Yfp^5t#s9v0 z+gX2_4i)c+D@PAU0dGCahc*Onld|Dk0)e+vzz6$hJri(Moeftee~ZFDw)f8s2Hrb& z%&$8KyjQa?8dvKEU^c%lpJ|&xz4xwkwm5d-h#EdnHcri_yFIgndiAdK+xSgEt@HK& zM`U%JpqXEj=6)`7jS{9=U(`ETf&T36x;>5F4+c)g`<)fg_fmDbQnJm*0Cc zl;o>pQ0rP_JnwJ+Pxfk^`giF6$97nQR)h`y_Z7Rg6)HwlYf$Z(@7iNw4f5Z%L_q{= zkaE(fFYd4grCX#fvm26tzb&|aB|bO`KQ$q=v=6L7)(4KAu!MV%xbvA_+b#VuWgXw5 zOaJlxzd?)>u2*uqN%tKK5nAz|6iQe2>txU2M=7f)!ns*{ti-x-WTU+?f(T2NcWeoj=V1k!l%3cTtRZ~ zzQefj1*=Lm0eb zx9{o=`oKGGT3c@m;H^G_7o@B0kEN)5EmY}Cy@L!GadWfwzV3L2Y}|;otS2K3sChf9 z7!0+zcZ=3) zS5I~5@;k^$8uHa~=LJIJn>~kb6XI>N@vb05cDDZAP;Q0mt-pcQc(?a<0f;6Kv&W*;Il&kGT z;oW@)Z*<3PW#c?X%?Nh*ME!vDlOsK+?;qazc)QE$cu6zAbw1nAvVSRI50@O$|22u8 zcWX6j>uMf?tC+X6n3l@1gH(F(uMMmLL!{mNm!28!n}7;|exQPBHIM^KN(*HoA9k=i_}(R!1Yv z{G!?}mzH75*y_>Q*F#s)^H%;C!WmW*iihdoMT@r3-yq#8L{`LC?dkHo>+R&L!)nm> zh+&0)c#rD9dr6sdDam`lPA`2b-q){thD`_FwZAvl5*H`7)Q&&V47`88_N&Smlz?lW zpS1XAOcd_Q!^1+^R z+??pO&F%idU0t3x!$rISK4xXJ5RL)nx&(*LQy z34K`|Uuotyq+(doL_=llcvzMf_Irq>x;#}Thru4 z-Esc}oPqfJpZAW!`?amHP=G`1pv2Kvh$l$hZ*3Y?=HQP>j;#z7)KT-kp`)=Xs!;_e z$89?MqTH~8n)f^7O&SjVosai5Ssfo~=4XFE`)h845|%etZ%^qpdfrpC=J+M`n1ye+ zqS^Z*m;Un>4FAxAqEB7F|7T2*ua4ip-nWe_`Lly`>%cp{O;b$rE_2ysLd9Es$nNAJ zz&k>6^d52ccJQNb(F=jMPQL$uB~udc@6SUAmQIPnm!z0)5diPR+;KJDz}tqob-Fj4 zy|pi2F!$DfyuGE&+UC?6#qKyc?wS7Z8?Kquy!p1Z1|~_JkN0+29VpHGwr>5Xg6&hr z5?kFp`smT0y~RK39*jy0#i!Qgt@J|cXjl6?`D_--KGx-TkV{hKt7B@@@+<4o{+!-& z?Z7+ko%sWj_n>Rh##Fq;IX$_Kzjj0|6s}cM<=f;IO_w7UN(4`e``z>fILNk-5^YJHAXdu18D7^+*44aU!i) zsrSv@osV~mtd2~Y`F$=o)Oyyage~;88B*j;&wJILupwKdp?ItHpn$+q`s@D;`*HnB zTC2M}Z-%9Ob+BF?$Qo1nXZ3dJz&m!8xjD%@k~ykB74H>8(^ohFZ{NDLE(Gu7OD#oy zz}s*|)ECj11bpRQK`T2T3LkUsqPsEht`u18)d${(*XHE=_4CIHH$R#%_&=__CFb8+ z5gpJSUo9IqbyvAh>2&JV+k02o{0X-@A8)Cwj;S>BOVAy%zT0tS?C6Hp_WE7)yj7Ho zuO5HpgGW4%>KPwKzd5;L>h}5kJ@Y~TQ$5K4t^e+!zVg+v@A}mn$nt`}{r~^1AN>E9 z{~qZ7Jv*#H>F&Jg>gH&q=_i z_h6LX;Y8ur#Y0xcLjQlnquRs@-a-2AxzX&{?*7<a-3`R zN;9SZc!N|4+o)UM4TVnE|69uH*iJJ)zV5q~F-b~T{n_^(5jF2=cZ4&VN+g#u7vNFK znhT8L>8~Kg9{;xD$fc28zyEiaua4jU4|{hWPSw9Qj(?LvhRide$(SNSSSUj!C5;-k zDM~VAR%9koNfeo)G^tdQl)Z#RQWViZGDW7$MEu^1wa<4y=l877+Meq?*R}U^b^bY@ zI`?ticfCIM`+cwX8nis6eKKa2*c}wSBPBc-$h@=nzgvUF`|#5AN6P?jc1NyV2=8v4 zc|vCa@33&oExr*U@U9IN1)ls~u%!flehT2-6c@8J* z;5%3)VSF$-uK2-~?Je%uOYG-sMPdRBw70~vqIG=5$!}eUn4{nuZYU|#vr5#s7nisC zGLe#_UM_Id^DI#xXZ*`s3oq>cy}cou?s?a4p{|bQ4^t(oQfGLZQ}8~`aaotlTS4`@ z3Knl=7gaA=z*~bOL*j>zrAe98u!cZ=30;z}jjB6IP|>(mij2ER}WeiCBow zUcKE;!8`otJ0mjh9VRZySiIltJN!oh@P6=Spc%P(dzN!eW+>pT*tl2um`4a4P#L6> zqvZvwoA<^eA17M=A^1%Z;Jv5n*O>M`Ybc?8Ir}F8>>H%xR&uxmcksc9Xq=JOsXbl{ z*f&TwK6B3RCDI=6i)bB9IQc~fmE{22B^HnGV8wrW zDgq5J-&r3TJJY?*D0qjRIn_nxO%zaDjm6u2Uis@)fcLTR#!Sky zx04Px<}U|lZ*~^4?tMGG;L5e-A+><_mB&~8?g8F^ZkS#=aMT+59d>GO@ltHw=`Ppv zjm7w3a-6gFzTKeM( zID1R2y%Scx0e|n^WVbB*1Drtj-Md?rx;i-S7`LZ^&s+XI|Nq|{-2X#A8_fR}6g?}4kjhxnr;{rYC^|yxWTwsZHYYlrv@=(#0y)b>YCnW^lRHOT6 zN1P`-W!(FWAM_yT&lci$Fd&VoR+XEqvxb_Jel0)Yh~0zQkJn4T^5%t`(7076sy6Yc zV)r039R)u4HzWKX`cwIj{TOl`+i~(+Un1GTWXcO=MxK^+hJWHNu@6}Tm@BJ}z%@$q zOHVz`6kkj(lgRMp`$Soy0UY~}=MF9q-Os*6^Vm)K;N22Cv9+eFPi z@dDny6Sb}gZ}qdXqfLPKtCm=nt;r#9N856ffSaB$+ZsP#8Nhq2K3B9D@E&X`5$jlP z4M|wDoqMl@&AWzZv&=7p7beFokyK8ECa?#jO*z+!jhE8iuTJt|| zp*`N@I*M@e+m~dS)K|s>buChX4zBOUJ%?DR@WUy}h2yo2iqij>Y@xk%P}f0Ph9m;!FtdO?5fj3;^%e z{%ySL5<=iHzbTH#T)fceo;``lIrzLS7j3B>tvw2V z)q9$JBn5v!B5adNy6j2+ya_^7*1@>V?egsFEx^aK85W#bx>+!TV_!63zUL#j;okv18#RA@Upvyn5#D~D2eqAzLH|7cF$wpqb0=)084mxWG zc$YtYv-qNtHDpj#P<)vMoA=!(9!x#*eDDS|F6#BVohSaGdyi$Ek!-k0d%W+Vb^ON3 zPgwtytLs)C=ycsPxm;)bvp4tpB8|~=$Ki(1Q-0N7@E=Z0i+-78^;3iH_ugeKB~;ZB z(4h9K>(t-#|Nqz!`M>#t!2D07=s}k>Nr^}gLgs({HCq>8^&kbi;xtCkg9e?AL%2Z? z^8OrE84U&``7i2S?qG@CuYK@nd6x&g>9+;zZK*Cuk(hWoW~2$a9+$MqXv_*~kr0>s zqmSK#x;fV^GK}GY$#J(8)tV!Ru$R~$*LXNBg=ug8??LOp%g=*VvE?@_FSIu1){dYR zKX7-D->0Ha@vc7%ulUf*ePB8M{Ga!5NHA{Ub-M3CQ4+&c)nOX*v~IRC{=*X6|FyX449o+Q<17@mKRNImo3{nGX8CbL+T%Td z)`6E_B-c9|b!{Ff;9gT##~FOy0_-hf?+gyZy-oTzySwmrkO9NNt|GbgfBqk^HiW7= zw#C}byOTRJARVCKeX&k;kj$Hdp?e+{Z_$9wk}QCCacYB+pJjH{2K6n!>4;= zyiLR+&fMV;r2F~5-if+8ey&U4TLQiy1vV%9DR{>g6%)z4zixZUh{gL(Q1$3S!21Wg z{4_HETPIFzzXEt4Wbb^W1P&*RYu_m-?C^wjhE$3h0B^ZC$8B1GcWdcYv#;$|5J%FY zg@ zw?DrCp8tQT*!AE^TPJS!?%mq+L)O^^Hu^;@zp9SE_a?}^O!l_WqWir!L9K+UI?|<_ zOv1stxBs61|8EZN|Dm4^mRMVg9+a%=GIKzR%>UjyH?m{(ps`Ia9*lV0)m5?Bt-%9& z(8G-5qzcf3-jozrs>X)EE{Tpl{p(SgI+l1%0;_@Clz0yDCf-~%X=ZtpmVk&l!Z;t6a zJeWcEya_iQsjEXW)E#}jg*655#CNfO$h@1gzq4ZT*3r~cm;k)fG{lFI`Tt4C36W=j zw=yXx<;g|xg0!7lTR0p&;Kd&n5VHaA4Tb63A^~qJxxOIPvsRFE)?42;5;pH(MU^kl zBe-ElG)~z;)|I#yyL(Swt

uWT3h39g5cR2PePSQ)2@XEj*BPy~npAbn04c*WG0TxnJ)xqHPR?!yRK?*h}RusGwKK-aA^L`?d z%Ywywn{`zBAHe&jpTj$Z_ceyb!}kI2$Mf#{+=~M*Nc*Hu%!u%SSBJb&%>%qOxrj^r z0PkMeAC-)!tsvO|<&_p!v3bjw*(CNqB3&J+i9&b6cjtZRo z4r)6`pIyZZZ6CBaU-bo_H{s%mO9L$SaFi>z@01Nb?=gwRm-CON&^>R@RpM0D5p4hD zio@*Y#FB#dWtTr}WZp^oq0Csk+5JB262SZ~m8^0D;XUtt{Gv3#+gE+F;zw})pOfCb zN$a);oJ@F{^c3)BU68-T7w}Fd42d~|F9WXeVIl3kgw0!M^7GXBU)-u(S`jQ z*t{PwOFnyhlJRCF>yk<{3ZZ|&Acy5HqY7fihw&u3J!oPY; zX#afspz2k+=S|@JLS-GccM`$vEq~|#|JWG$zxRW{5_^QA2W4nBI+1%&CPU9d;NsxDzPktA;nu+yU#&q8D)0IgGk>%R z+T0u5*yd#g?dZ}uX~u_r4f4bhm6mvMF4!E6)9sR!agN3AK`BjTH-0%xlm7Sqp#En+ z*&nSV9VfqbW`zhIPaf!+(ep{Ui%qyasH0%7>A0s0Y`^_(>3k~g|0f)ff0JSw@brIH z1r7bb*2_>;$A*nh-!844*+Cwr;C*%M>C6q%$mOl$H#xYmc)vasFWU=vi>pXIM|f|~ zS8jd>cqiTObNZee0;~L9P`Z1{9ai`8o(e$*Bo14xcVLOFV-Tp5va*79Ya1u4eZXE~ zzYtifbxgV7ooHN38`JWl9oW2E(zdmKEvG%+jc6S|aPqtOP5a;v9bPEZw6gKpf$zAy z?SdxOFVnMvP2U#R+;YNy#ZKP&UDn2GLv+u(Qp%jFI@;64Dk6er9&fRy;GI@g-AC@; z4B`!ouy_l{JyQJzcxNqqm4xu#6eBx76Y$n&<$XPIKLmE{Yv9RP=mB5qxilRLcvpJ- z_*n^fZy`;KTrshNcv<)Hp8SW`TQsape0n*M3+6`SmJ=>7N)o~5Z8vUzgGrF~E^jrV zbsWaYuj=?Me=Q##$Z^MTTYMcp@58+%{JRaT;1;3j4(%8CcaRdicO|XU>Y;ny1nK=$ z)$v|zkDJi!1JZUByi>1;&%7WV>E4q4S)5qBk1Wa69ssn~(>bR5>po0PvRYc3`Umyicia?k)mXZ$$$_IX?Jccki(8r!PKx%moXf zaYh~AFW53*^XBC(oBwSi?eUI4>)^x5FY!R)>O3P}$eGjGDLu9sw|oD*cQjDW>wZHk zNL3QU}{Na&vNEi>K z#ALu3H;T`@t+03G`fl)Xq5^~4dKpyA|2bFJP4W5BJ#RuHb#+vv>>V~p{(JsULsJuW zDq#M1qUb@ll$h3%dr*9!rVv&S3S7zeqZRa^Ov&S$c|i|)7ZK^Q2Yeu1@I3e1wf!OR z(B5JF$F1%#)AZXN!;;_y>9J)K*E>nZ9i)1LdY7dQC!B!BLCd%QshWq)n>A1!j!B_C-a2RGCr=dFcx-?XC3dXao@4w@I^FXwb2v;@9T&Re|EPVQ zxxD2_!8@}swwKIXq5nNU7Vp|iSq(n`ZzT&;afJ8L4=PjIfVbGLIOh4^L*UGpIlH%a zy2E!mxbqhS-q-t^ESv!E%BO=$VGFIGlCeMPkB?&WJ|++>CsfM`7olu54CM{kfmO39nmNs-L^`s*Yree z9`GLgt{F1;F$9iC%oAVM?G6Vm{cNBLc&8Uhq?!QUD@Pj|>+P+e&Djd94MNz56Q<`r zJQv=$2;PLo{r>d27CwjFy&b|=+xA7$LZRBm2pK?+oE?03O zzdE5S&Tyq+n7;fx{HwQwmImFbg=_M$cd2ypzr6oSRUHy?W;fMmzuw|N!TXx^7$=#x zANMg{EZ$pH25$TWyxDdy9+RL|a>0vWIW*2Q-d#ld3^wmu;pW|S{j|qB1g+yf zPJTvuTjS#7d797Z=WPpKyVNZoD?kX2Sn^OXhOze!+eQ>5c8?)d9CBXl@7j4z1$@PJU+&i8Jxs=Z88U4L?`% zsl{DlcQAY&_$1^6f6`gCM$NGjH$L83Hs$LJZo2P5>sC=$$A@<%ft|uh$ozktg7-a! z{%A69nfF5CSiBEN99`N3czc%IibHstJ>B@^I^b&F_ z@jj2%u?{D{;{|W)Pn_g|xHuD%bGClO<+^LjWR{?a6P#8vnfP=Re~As~xc9y*U7GHB z2P9HgN6yPSX4yrt2ya&k-dT0`evx@cbhe0M@fIN-W&I9#KP@qeKzJ`$#?o^E@P0Ry zq>;)V3Ue6o-62)C0U%O{Ly`@xTi52zmcliWQr;WZUkxXT}_` z3mUhT@X_DK4V!mkgyn>PB<=BDhSt%BlVA9r!aMaYgI_37)@9PPB*vevZZ|^{(?Oi^Cp}9=kf+7$DHz)!Ub79nWy`ORZb>wsk2F zWM9vB`c546ygO2Ed1Z*>A5QRXEJ`Zg5=HmCHCMi%s*Zu+q4fv$pFwy#Q}DjMe+~H6 z?7O$3lN^MxcyExKxZeVJ$NW4-M0k_W-bzN95@ z`oa9qw`Z-F3gGSj`SH@tqS(B7$F3iP)Hz`nG_J{8FM~fEoA>9Yt`#Qkw8vWnt)mGi zKf#Pg+)N%kQ0gl8ZQOqKxZPW8nsYSqo-_R3VRuo+n_}E}!r|x3UcE`p!(V^1wF`{q6a+|-tSB9K^8o+OR;)TU&V(PUqBDKxh(WE(u0E6 z=KqNROKia51CAoALgC3fuHp=fJYazrnym9c58C_C`O?bqCMfV^!#3k?aD(*M$%kt7 z*gMEi)-{|*E!ki*G|ugL@9~vtewhER`Sc!qee&*anj4TB&^iKf^7EZqzwZ;cL3-#% zWPEV}{ybl1%K7pSc*Jg4=MjBmwyTT6{tNb!$SWjNL^Icp(en&X7&|3UKG3^ zHRSy3{{J+)U(#5-S57$1{|b0-SQGXU;eENM-6jq2&UUNNJEIT^`!DrQt;{N1u9e-wYM<8G!-UtH|vf&VF>SLql<45-V*GO zju!&nw`6aB+#(YSJAAmNCN|*?>qjojl>)rCq@F)F1qP%oOalh2`>mn8E`uY!m$7;8 zTr0znX2A|WK;zg|dOB{*^T+&aKlXab<)>F^kGBO{hX+o6mSd>{leN4MvFA*p>f>t6 zI>}wYY}a&o;0^~^Yy+ohQ7As|%UiV7ssj4yeg|2(jJi6q%j*J9&c40XgM#;ibDQeO zyjzH8B(ZpZ``miA0r398dAWd+x1n17)3tzim2|kh2jE@Kz2l?-;4Qv1#QG)R{q|=Y zoBww!X!?oZ9otmw&57d@I}SEkc6bbpTPqga@RAX`d-sRz$_RF)J>ITp9pgCp4e~*T z@ufTvhn?k$Q+wXy^4|W?SHxty1DyZsTHXU^{P~}-Iy(79D-+#!?*Ins>e#!HpS@!C z)~yXH)X7>6Ocn0=(l-zxI0zcwbo=wDt(# zeZ`r-rO zI(2n$P7dCBQ6Btv{wFW@wEW*-{`aHkLC+R<%8+|dql=InRu8gX7Ih!lLB8Vp`V#3u zAH-j!PJ(BUc71Q3A|UfW_kz~k{T{IAk|6e$#a)nUM4z%H7?Av5O!kzfTS5X$1zIy6 zVc$X8_Pkayyp zqp}W7pPdP_UywRM!8@;TyIvAUG@YCU}s!|qM0F7(^ zbSnN~F*fftCo+wfFCC+~?j45Kp@oxQ?#1R)w|??K0x^nD2~zkEJil6^(ls$?4L^#X z2s|W>KmS{l38deQSD^a?(p`_Kt7Ge!)Sc+?nFpkODR@7*RQ#{=|C-0q%dvPXsWapv zya#x^J|Vp8RF*bv2D}}j>m37CLgD3uRtXXc9`K#~fnO7#dym>J7uEp01u`$1#~ibQ z1|3{wNbJ}HlKb774DCu*xCf0hKdh`>y9fLBmZ+5+of1pOX^yuyT1OmCe&@d)m%DL@ z2jc!ck2Uf=K3DIp2in!gtYJpmwY!&p!+&~<@bJso1FS3Po;Sgjx;og7EFSB)GP61H zq2QgnIf9woz4^cFUWUc{?ecg7g!jcea?J?u3a4=yFTlGg@9}#nz?+H1bmY2#2V7`Z z!Z84NU%D8uXCvTkSd~=H*J}mYcN5vrQfWpSNk>VT;lW zjC8*_*`j}hsyb{2hd)FI|9$?SmdE~oOt=onO;M# zK^E>0Nkw`P%XP@I1H6M&F5HWKiBKrKdd;12*I4k1-R8<-BG^F&ZoPLS0bGN;?Q?Wx zg0&@NVzO+jPAK;Lf0bz&k3{f%*bt4o9k}VsnJ|Jm>N22=CHz)_q*y^43UZP=KmfC~QY+ zTsa--0Z)AAe`pAJb8aWbz5u*6HgTpn@3n+i_ED_-c(auL$&fg8BI3EzY&+BP&4bl*-tuO~vq z?Jb;V7^2_P|K%+LH??-4Ic{urT40i9@F2xHieE2!@@w0ol zyc2X%&TbXkPkLr1btw5FK5woDOHZ8|F1jC(Hh-h8j!!;j90oJp`{F4I-US|q?~-}< zA33Ff#oHuNFcaaOuAKP@;caSIGd~LOPKr3NdTMzn{5bK2$31rsSW@#=2shx(bYfIa z01QZ?4y#u#wy}h=&wW2=W{%C9Ur^sQZ+HQG2aS_73y&B&fz6xKJpSO;gCjK8y#>%Z z_;K>vzhL+<`%zv<_?G^)T@ep)c@wmkWT$dClGHZ6`K)}AimSIFEXjAZIOv`?;VhMP z+#A-Bn7ujCpMv*uUCX6p-oKx2lE>oxdIgaI;e9#&Sf~$!`M)4}NPIououqYX`{%osP^L}Ifu~=vdEeD+Z&~2Z45y)SQPtz3 z18mq=Z}WxE#>af3J>K`xI$q%9x1@x~r=!9P9j$3QqP5}~F7JTF1z?J~A+W+?j@7F^dB6pBKaP!pCDz${Y{gCR z4AQbR3DW%Y;QU`KXFOIJ`vfUvdBV9v>*m3HXx!mXeZD`|WA`8raq&0y&jx62iM@)} z;fa%-Y(o|HtIV>j3Y=%T_-e_p^j9DDSz-Hif;!R=&Fl>)f6PpF`s+ zNM6q_aAWiK-D>6pv_w6UE45a9O2Wj!?7FBiZY!LC3i9`-a-AsT1Q9NKrJ1$#i+FXeA#bBXqNFGuSj;^bGzaWr%C z0}u4>=d~D;#YJ4+1nYepqpRLMpBH{F>2o3e{Q?B*o*s$q%jups;TUywnW*)#Ot32&XCSJSU|omJTVHm2 z^@oMDcQ|nbt-}x}zm_*EVEI&DsIX)#`N-NtT;87=bo?3uO$$on3!je-;PbArbs8S; zjHP?t@{ZKi@$|aQCi$7Kx5Uk(;9cYz?MUW*>EMagSiH6JH}@ll6F~alsBJ?1yhAc*#O-$(1Xh?8Gb-MppCzw$s@edZ*uo2j_G1N6fc z*IOSfXiVkJN=?B(|0fuv_qLiZrTh6mU;%Y?@R*jA#$Eb5|I_l=|F7J@63b4}gWmM? z%=92F@QIzECL#f=2OZb?G>E)G3La+OiS(dK`|ArlKo9E4x6)E-41p8tSS${zdBOyP zkunLRV}6?;FgPhb91TA}oJ8tjH27f5_i(ycU~x@~`=299|6YD>TmL z<_XoOU$J>F39i_&hOwXKc&DLtNa5rc9nsi1kUMwYiw`xba;V_%AOkMme0%H>{m=h| zHtOn#Nr>$>%9xjn5&*tp8u-o(b=G?uDgaz9B*s0*HA3m1@MfjpU2gL%jm+DAg^fBEZ`)tGGq1Ni@xuS`%zzaBD=z@>cBv8D zFx?XZCs{B{H~sN|85VA-Qv$qStzwll1-u1MyZar_wuBy^8kE=+i_P2EkbyUH4)^QOhzl|*-e9v~zo%j1kE&Im2V8kBa}yun9oX8s#24`Xyt9323g8{g$;d*H&@&{u`ne@O9A_rpH=zd7-3C3STiud(*HbpG%A|Nq?$P5v6p|J)Qk=zZhY zl}Hal=6|k@<_oZTkR;2l1IR0OGh#)Jksid6knkh~^q_)oNs|mQA@IqgoVI)up77-T z5rzTKgDkHsJuVCeq<|I6cC3493H4_lXtU+Teg>)CEn9lE))Z*~jnib>-?WMu`w=_8 z$FjH0U3zG4KuHx{nMKmV_}UVY=~1NwjeKTj)lb=)~s zILjxODZ@P5C#=v^S-Efl%*i*#xTyiM)* z>GyS>u!`ckoG*a4{-OsJT7Y-8*XnJ2sg{uU&*yIns<4+>hAMWWlA$S*4;p8;-(=qE zQtTy`&nEf#rlq|!$D0+cV6yQybCST z%vp;=V6KGpe#qYw7R!ErBn$AaIAw7m9Pl2E*C5@Av4n&rIA7gL#O~f<(wr%KbO^8r z8fWpvdjIu*c>lk(Th{ke>3uZUy(7^&_Tc2l^=JjOpkeO3-*oYBd-H~h!-=B;KhE6@ zq z^SAlu5V$`pWY@9{p0MlP@8+?9_rhaqMDGLM8VPFlDRGuiTN`n&TpTuU=inpD+%gF; zIc_uO@72+<*xlQwlU=YvjrPvo+|W8aaPn)|Za5%zbMCwi8hZA;EX9BJcGZ&mYMTo~ z>Hh3(&28%H;NDi4dG_+(^M9J0_y0X9F#iis^q~4WV-mRsrPmm+WA&iYigirLH%Nx| zRj4C9=+WYmuVSDF*$Ngd|FAFwcC|B)d^PC>pSzp&cAsa|I_zHtsG)53qUHEs||C-Zw$YLE}2~8|K@sP+0 za`(Pl{hbwycVblQbA&gaCohEXUK-DlxE}C68CNA-q74p68>fewlD*(Nz9m*FfcN2O zle9;Gx0|1g?Y*Ox(Cw|EZpjJQysIY9FD~bpB$4B`nO5y=IfdQ5M?~k3k8bUvIo|bX z9o;zjX)f~@o#2~$_qNfJU-kAo{tnW?zc({!4gFue&j@1>5Htph{;mu3IyVizn z<^}0U_g=ZShy{yxSt?&F!h7C^bbW;P!5tl(mdJo)ze$PjUtD4)R8OLyrW09tQ9SrBu$}li79NS9))7_wj$mn#Lw@h zIo@$-9lLSzD@d_!xqfW!yg${+9@un;iupfV=6W_85B<;oIaJmWpOfJ_JOA@g@UD?G z|3vQIPvwJ|v3O^`>$X97>rF=)BE0hp4sjvp|H8(B%L+q6;PapF72Of`f|n_{`!WOG zg&MakM*(kH<*&mdHQ?UcvgP6Yd$G^nxZn2}W=H-ZnW1r(-+DE6Z^k}*>tkSXGAyP& z-oj`d?Kt_>J6 zVuT3nCD!QB$c>%9+i7lz{esq^hm+q8d`<$UOb?F zR{`+;Iv_VP2?xVBS8qEqeAyfR@UAK565uVta(bR1*g>vzGWu@1))LzI_zL%f!`Qs# z@(fQnmX49gaV7NxqO>+PZ!z|2m{+2M=6EZib@1clS7_*Zf*3q^-aDol=kMyppa1O= zMYmd4Y`dR{jB_EsSZ-d_|;`pDf|JpMK(7VlD>8cl@v1zSrMg!jb> zNJ$d#E{Q6Uds!b0cUC*F%Gh|r+r1{Q1Owj1mxcDL0p6bLY;RuGvV{8XSQZ=o1MkEH z+pvN|<0Nw2qpa%8NeG*F{p;(hMo(#vcPd&(HBNrH*OjY2)XtqZeDI68!g(s@{|$bw zRZulrlZyg@Mg_e->?ht_LIL*;RtR{T*X&vb$$i*{LjPaAw0tN zo1}!s-TG)BmHZF)-e#KW99X-L_Rijf&^l6Z@=LPt>Q%Wpciu5;R$Ni6r(*v1Iq1Hu zSCamDn^0FryxEzXtoeWEf0~^4|2-)%|4UNzpw^0=+sHjACSP3$s|U?{*?FrC^q_mc zHZmYR=sb7gIzM+6-H3bk-Z%FL!y&i09Z#P2fdl;CM9D4bf^4^SSu278sqId^O5hbD zG?b+@7tb@6RM-zk`IgsMPgQcMHw!Aitw^EW*i;l}IqP z)17+{64%u5Ac*46|2KU<5J)?GHU9mtpWc3bA?ZC;by)UhKm8UlGygB9;N21~w42P^ zV*RuL7Vqmk>$W1iSF)^UL3mr8d^!~icn9Q!c{;c*~J1|62M&k-MS1wz&6PtJJB!6g}O)Jgu-h|e1 z7AHTq$h|zryt(Im{{Os^d5n#k`Jb@tYpX*r-SZ}xEv2dsLk&$~vGkewUxI>n^Fg6f zGVjH5ANjF(&v$>`)e3mW6jUujcn=k4tix>C)tgC>{+uJIDU+o+1@qU8V z;f9l6SKOjUqww5$OP|nAK1Id+UnQuqD9o{g?s+TkRi~;BZO__k(Cq#H;uO5UuTah+ z^PX6d&WFXDqaE@`cqhg#5JGtW*#R%C0laVUpR)RMJQ%jiIyDty;scXPx(bHDfYfA` zP!I@s>vj&_{jiz{X@->sD_UUl*4-vwXg)klQbpqizh$5LB8bh~IM>v#me@vf-P-`I zV?9oO89(;iKVE8Co($n!(K5+Pkgy+qGcho5k z-Za3Q=sdh#`4bUZyg1is%LF#>lxu98TKz{zqG;Ti(1%4E3bA>A>|XbysEzh`UqkDt z#>ua9^chLAX71g)hhfCg_X8F4fA&gwrMnw7>20t5|I2r3HC1&a@@U+%iugPK|Ns8{ zXz@3|{J)H%2mO3du1fAfA|?tFSUqTm)b5MOfW#e8FwFyc(7|w>Rw1y&il3>qb2JKu zcdRAFZmjl!eGIHgR$vD?4lVsuGuQ;_D-)t_F?Jm~m$-!gJnixBN9#C;lV5n=0_Ig+bLVaU$ylkhlZq20l?8>K zS>ANdn@~HSx;no449d*zAeT_^?l5JtB=fGgP$7!Nd(*43RD`$jsM`$h_b_XSHsD?O zw*1?+ZQ%A69ia;vk9^=y>|Yg)0Ph_K6y2u*@8-7+2VL|np=RC8sZ$-;ydekYMyrrP z(ib$&cH?-+P#SjkzV`Lh{g`Rm<86S}k%p6>;_<-4Z1?8QyF5$Ayeu34>Mh}XeN9p- zBmM6nv#6`%WQfBa$F!O5Elt7uhxDe~WZuCa6GgCi-!@>mj_@A8`FVzSZ*`~L9>6<> z&HmG`ox!ksGV{hYX+CgYXtcBj;9b9}Wr80JNJk2?R^&q91?dkgBNu+c=3V9B8JjvW zNZNwNc^U7#z4#xV-qMy9F}UPLdxsNsXdN0j`8AbP8AkZceg2ne9cH}khyV4K!wVc# zEK`orJ@0M<>grgd@NVsB=*;1S6b0|L&IdhY-Wy7Y!kE0DkIkID`A-`Em$SF^_h--E z%x=t{y+!)Xp1t*(&7Qrvwr&x$*RzDG4o25TzQ^WWFJjH{#%qZ58jWLJ?P(Hm9=m%B zE9X5uOoL}{-_Sbvaq<&5I(_w9!Q8v|#~+n@pMRoa{!huvNQoX+r^WGaPC0cxp{kDU zZ#X;7fv>l4fFC}e;W~jsYN0-}4O0mC$G`ufwLbwcAjwhmpkFsn{OkRH0ShIUV)dZU zq%#`rV2M>J*)@pF|52UWc#6RiE4kN1wm>=_%iGsK^g^A3l(FRT4`2uG~a(ymQey z(s1$<%&_0Jym9Wl*X`YLteXvg2kF54$)x5758dw|3lCCPhy5SRQ;!NSAeXmfD0ufK z3eSAr0=fVH@Sl7sEZ&hnET@nG>F(KcqX_Sg!0j#ZPeN?x`NE>Y zPNtE7w`+xW{6)Y!%am~GfHM&aY~Q|LXg)UYNv7XF1)2Iu-e_F2m!5k@Cidkmc?PCK zIp=AQH^cndI^=NjQ!cY+3e=lB@3i;!nFrFT*g;yatlR%kg6??}f~cz_>{WkDvwR@J zdj%!$FwYa@0jVwht|S)kE&~r*VY$B2mv*#{qA~%impzD#0+rk9C2s#(dz- zTkZu00^VP}Q+(3_?>>HRDv49hY(PlapMbf1YRV^FQ+kV;gn_{O-*&aL-;c?JC{#F6*VP4%z2&4fEXN z5#Gxwcz69g_=?PX{(I}iSiCJF-JT%4ht@|=BD@ueOuLK#?qbs2l28Tnc(n zT{rW3Mc!bT#LXyRCgTgQc7Ao|5$HjBdAm28gC11ydwlXnpe0m&dFRulci7J$L0rK* z7?1Rl%Fwv>Z&vrpoUq?PLX>XS_;#g%=6cX(w2p%~`L*8E%{=r zmwDFuxabgQ&oWQxt(Z>W4vppEIDwO&-8Emm4Tf{yLGF3HvGl7V{^hNq z)#+QW?H;3h-t79+)p15v$n56nnG+;M3f@DTvJzaJ#Rt@b#=f8;$h2sGw1&b6ubx5zSJi3zE^x=ITr8Z7F%WxC%lR+{>$M6 z>%Q5;iHo0S4<}-pW)CNBN6#KkESU;~WI^|i<_H-Nx`NGn%$zVB1`a1e(733^KEXge zY~E0Q`$$?g?Hx``p>=5EgrGs zws^ZWa)!4&1@HdhW&UK|q5*rCVex*cwSI>8(j)u+3-4PNv%K$pndQy-eU^7~)GTks zgQ?}pOqNiISDOG&4))dC3)0m`69MmMXq=Nt?(~rz*k^C4msgjU(jf24XdTHo`Tgn4 zaqxOEciwL+_i)O+qvGa7yVxGX{wccWO^~=qT^(OoR29I@iGR=k|J#Y1wtf@L|7$3E z&}4$=VR8@Z+{(QQs|TeW_;wE2K|Y_B#qdl`(`AAubtSLuaMuQ-EY3*uSQZ%tp= z^ISgh8`wb}ir%2e0d|mUlIz)3K@W_qH&j+rR%MtuzQf! zpT;T2-cK|)AdR7Q=;GuTd_|_B^WxkGBtBk&$fzRxC6@4JG{EX%2>tIMv#6}&QsCXh z*-z}MQ1G7cIP{Lpd-Lj!l~}yx*)FCcysO7dW_a)EIB%Q_c*{p#$TtSO#Ugy$`89mu zlGY1>^?P!8 z%vqa&&osyT2wKNNocx?ODogDvo%<3i4pp;e3ggfJWu=WjiIS{ze~DfFCUtc^^9z>%-kFu(cfZUbLUoU#!({&91?erSP-tU56XpVO;T1Ny}f!EZ%2_OJ5+oNgJeQcynmhm&1Vf%66**On`UO(7A70 z*Z9Kjda2XpfVXF+dbSeatv7Zx)$=hC60>eGb&tjF-Xm{PZX9#(Ch?(hr5=Wvs!OnW z^VJhmH6PO+Z^lZr4xIc-9F$nr=*+!)|FAK0iyFj#y`@WHLYQ8%Bi-|Uex15H;Ae}@ zti3QZ|F5FpJzCRLOy;fEVLf=dq@-WX5*3`n~pr} zz~(Kx_C&DW=vSKS-j!$_GC29Yda0n^S3Gy#52lZV>s_K^{y%T9*raig{^$P$D(ev5 z7$^I8{->=uA1fO$|7-le9<-k^GVxz8NI&qLK@F=18J$*7L3+?r;;}Yl2YGwcOYSD< zLAj?7uXg|glA+n#ME+gAu-j4XN6bsRAY)>}Sj9jS#1@=#(c?K0;;z~)-V8_j+{jC;^|NN)Uhi$# zj`03M%JIJic*{&kzPtcw8wi0t-~89zgS0x-e!@xU*6Jn%o3H$ zz~4dsQtMjqZplTu=j|FrT^+0^_0@%AXLzrr;7w3+U?KCiU4Byqi+8<2O$@@@ItqB#wSClT2fVHINAq(ch|uK7&1;O8 zuz5=)$fzdtbdW~TxP1#axrKzVc}wfnuFo^7r@8JegVwPeCqK*DshG2S=g!;Od{f~^ z2`YAwjwA9*;6%FTO-Q1$j<@UXA}2_od#n9F-utG->|T(0=L|S1WAWw-<&Q*o7fY|4 z8IZP|;IJ-+uKSA&0p4B9*;>s6ETL=%moJTK z*aH&j_50JKCpt-4Xk0t@ql&d8Y~IZU`QLco(;n|Kw2pS1{A%>~Kxg^q&ij6g*91e+ zEBwo1TSV_Z?G&f``Jb?hx;pwF?zAwT{d$Wk1@AxQ9+70;*)ck+v3Or|8VNvnCvIHd ziEK{l>`k4Kx3}uDWW7`c^Z&^6ewV9SzVK+GIiVf!7T%HJ&j{v!osb5V2NGcZ-&54u z3t{u_kzpLJSoD)Ly?ZupZ|M)V!E$Wg?o+!fbF66Z>}?dS!y6|*-`s$~>OFJk?X#8r z+|Yh}-ig(b#GFT7bl<&?&p$&|9T(T|E&3Do_x^vZk(;J|A1tvt|E~w_XF0>6j`SdH zpr@vPtN~-a#hX=JgIuwUTpbq47%?@iYutA!!-KH)ull* z2c+5*yqPyy^N^R=)I%kjSiJo+$4n94yb`()9*RJ68nk7_R?!S2)5iEXIew_ zg}coZmTeoK$os=+tr-o0z<91DwzsCd1_n7sMJq}6oKoA8IaIvivQ z=PBNqxq7Qf!JBEFxC5E@fvaoRV)4Ew)?b6n|FG)ECWQA^$@jHRfcFi-bzRxa!Ei); z+d{$pzVMe#&}%`!dxT>&{2}1Yx?5fK850pIUiqB!pb|Fk;2)wtNDb|z0yJ)|o7Hgk zHEiBr$IZ4}H~dI*-8&ksqZubZt%?)YnvQet-fxS93+E5v^S)^J%Fxs=jqZ7S9Hp*~ z;Aek68-tq@|K9&kQ3xWLB#Q#Y3qR?IAC$!P>+ExEWCPG-A2%ZKCtbww*@_jt4AvQl`#=At?jD4 zk&WGhl74^77FgLrGC||=wWq>d1hEIC{2%s8>mIzPxgK;4tpmo%k8_P{L&VtJm)OET zmM7XOi*e_F!j7AlQUn?4e?W4fvW|kO@FlY+Nct4KIZOw?k$G#MlADjk`|~Ym6xl)U zfAIb_!uxV|9D^|6t?*XpE8k!ce9`RnS21uv`b=|hy#e5TB&6!>QNX)XhcFfd6QKuI z9~=gyu`jVFK78~n^GXZpJ{qTb>ExTJv)H_o3rlUvML*CS?{u_|be#NLB=2`?=gysX z<+UU0pR(d#Vkf{Y>N^NA^v}DEx;o?<`HlBx%haL+s}-T^Is zZxP-)uCFQ)-Uo%mT(|*mbL}A07QowSuVTP5aC?i)ygPxqfOn@T@9*P)_w?%5^}Fv7 zA;;XrE(T_7-g}sDWw>#)l8&Hp>3_J51l+NCXWZEn>=H?PyoqQXw{Y^iI(@b-=l9%s zyLfE4#Q@>oy%qA2OZTMH2;KAE#>7ok9c!}6UR8z6@Ybc^z3}_>9CG(gsCmJN#hW8K z_A0`AOp~D+;oWI}DTo>H=K1)hr*lhy$VpJm$Ic&QNQ4%|9Ri>MbFgi%qXx zg6_LFL5#XOjM?r^YhV3){{P<(+%)#PVE#9z=s|ooGBfueAv?%bzl_+idJwze+B#&3 zUCw-^99d$0iGj?!z!EESW$cB`&mfpku}z#&$rmQ}eA{*$EU}Y?x3iamCD#1f1yTig zK|1qkD-DU&*geR(`c%xc!gtaFG>+5p6?^(We1qg*x?RnBQWeb&NbYDIRyg@Z?^~;< zl{fbtq^`nRm3k_^|9948i+?PaFWvVb&Mp(G>ZpLmln%^(LE4CdH?Q7i9r6-e-z~w0 z#rttaOfSOQ&EJ1_tyj7W>)n7ilY(T3Dd4SC zmI=h`u5Y~Bg3@qX}k+T*|n%};_@qs=clMT#*3pEM z-|Y;!Z{`1ky|;(N{Pcul_?NewI-IzD2=xE`zt9Hi>L_E9I%xyGz5Vz6pT=hW|1KRc z|8Jq_K_V{VFUdW~$#ydjRu9^8#(pC*AT5+|dxP{KLZ^{RIk^A-&;IDo?;8HU_Rc&S zt1sUFPmDf84o zippGu-#$9$uIJu$&-Xm;TKBH!`K|ir`+c`Q>-+t@pY>Xwy+3>Jv$r3j*A!h<0&b8l zQ`s*N32IPlvav|#k2d(U{)5Ky7!$arcIK7nWfyCqkc&UvXjj{@<~PJ|E{| zubfM~IW>dSp}~8Bocz=SY3TA+L@_TvA>LvBrYPRuK8sD^U2^ugWCOsPJ!$1;r&d2? z@1~Ch{YyL$`EB=FuL8V7lYKkB0=(}#7aw@#WCFkFtoM2=OpJGlxo)m2(n8J0;_8I< zm=4$y)VdDQYW#vvdzaT z!Ul=)wzn+y(~5h=aMgP)=EIpJKd9Dl7njWR@%9`M*O%=hKS4?nw!Ut;=l_HLUx7X! zWx{TKGFemATbl;&c`rkj;dq}nc)&}9cPw>72#U8#k=Yd9j}?UrIYEQOGcpMIb^0MW zrtAhL%RCTGw+FdF0B@t;-+X6)2C3((li2Vl6IdWMvPiSZWkEf(sU-A2XZHVPMg ztF9-;`*6WTVV7YQ!{IH4`LH3$Pb1{)Xi5L{@$TkO8hNNhzPu${b$eXaERgB@f7w3z ze0&*}ErbK6`hP7NyyxC!*@@$=^l=q{!EWI zWet5k3eFtTZv%I4{q6t%yM~*={top21~fHjsqV@Ds6o+%^7Dym&@RiNPV^h3ZH9Ya zp)<($k`f z)wxIi@`4m!a&pAXutw@NEH3Hb@Mo@e;x))X$NejF+RGSjh!w(oTp-EsaF~Q#uFCY6 z*q=qrh`W(Pen8si^{=z7w#@(jpN}zpK2Gt?`O@Y+HG|Zr!CPeMnQVNBg$}U_5#fC& zrr>NEf&&a(_!VQA4n}O{r@lq%(=}E{H$g6zN*daCl$Ae3X#n_a;*| zLfmWmcv}b-Jm@zk$9tqv{y{FwH>U6Z!?fx1u_HW1uPZ#^2k7mx8i!0~nys-8=P zH|qiaIp_>>?VU4IcrOyOP3Qr5r<$0Y%msLBq$B&c3xVq`R=imj2k`DNk+iASmtn3M9r`jpgCez*NS=+aL3xNs`}pt6}@d zf$29$UpCz9A6-J;|8uM`&svakl<6BJX-WEga4eE=@BFj>uS+4_h0Oq)c4BH9Bk`^UiOf z4q$NxaDP?Mzr4M5HF#&d8UyaV>0mx0N%9jDH8|J)Kj{BeUb$QTcu!uveV&F+?v|Uu z{MEadJ|Es<*Ber9{O$i4tkeJR(*gbeKAIXNX}RYaUW1-Z$}b_RK}Tcn>Y@!&M9pv= z+W!kwZF&uZHOQ9Onyq~~eu&@6)IIaT6FX)nSzcv3vJCU#PLkiUl0)(l9Mhjc zJ`e3F&7|jwowHVEI{QvDe+>$t&xd5ElZ|A`RD-ma25$+$*Mm6T(ei_fi15DExa0_m zw{fWS+o|I%ryOshCrF3x>^R+)?}rqJ|4?!UPwdpY@UTAvc<&b}dG!?F9hTIZb=ANW z)_SZz;<=s}Z{7eOfsAeSRDCQ?$2|CS&?#cPcdAuK3dA!W-a?oUJ(B!7M#V-Q%BPPv zd%{MEt3Sv$NNu)kK0$dk!t{9a(&?k%yv6Vf|EV3MJv4ZW54TKRkcJ*_*~L@0kO=SG zagiVt@4dfP)uMQ>9pvqj0eCMu>yckt>W5ssIVt;G!UNHMTq2bL@Sagxvp5IfZJXom zZMfPL=2?Am_htcNytQ_0dRtvvPo0Csv5QGPmD^8@_sT%~yUq%w3|GDNF&_#f`TgQq za^UI2^c$o_vFRpHqUe}G<~}~;qCsK$28lwak4~lQKGARw1*h)LNCD{4utXW-i7%nCCN`w z&dID(ZTi(ak#d(yKZ5*lqS5kuUe=|?OpkZI6n#E6C(mndFrJ#67}DS^8pXFCpPZzu zI=+Ai@3OMFl_=gtY>88QZ^8mYL2Ll;)U{&w?}NR!hZif0> z(El6J)F4?^b1u9F?J8cnjHm`3kbdC%5!9er9KBO_kUsd8@?a5IVrTU<-t^wW56ODt z-#o|11JNm~mnZ`@==f@zb+eQioG5Zy zVp%Kk8Kl{f`x=rrzht}_B<6#kB)`?Way<4toc;__Mtk7N_Icz(EX6-J`ffP$zd=Gt zqtl0yi07L_Q!hvzq``ZId!8tc_mCYdPK3AdGB^gsTkz`5R_qn~r)&qK`uvMzCm!=W%5c@&-+wV!`I_fbj zE_-cSdg*oIA@=)cSu@VZjEDC(%m-P1g68JewtG$=Zx2|yZqk_ic?-&Am$7CWKBk{R zQr4cJ%g4m-j3Fh#0Q7;h12lNcu=04|c!zwf5hcQVh(kFa#an57b_!^}g+?gMzpJf~*#{2wE(ZOEHB8IEpNtlldB>4^NuGNnD9~^J7i|txpoKZn~d#ho| zjHOqNFEKsd!R_?9hp$-)9JH3yZP`vjY zQ`vnR;4LtGNz5(84_SUG7O4Xlq(4>U;wk`mYmB!>KLmIyr>)t}r)dgTJv8Q8vXvO` zSZ9U3mD2C1byys0J3@6jLyY&GjqLu{A{YlKjMZ8xvb|reD3+*i=yOHC2-0 zO=;-X@HigF^mtR6=<}g5lk4b#?8_+L`)Tl&Iuq@S;~igbDnf*J=?*V0wEtIAel+!Z zi`ASl$xi_9K(`GM+wS-w4c&I1x^z5{uqDS;UjV#Ii~K%ajFeb@wi^QXTuh9QN|9?+X zwB{K3^%jYI2@-6A{Y;PdZeIF)tjx}FeR}@y{r?Qr=MyCZYS1B?8njwrLc+@8Hax(U>vSXq@H zXFv_Q*sfk+t7ZmwT=aT;>Cq8{D6Q%jj=MEY-%z`-xIpo_=OjN9U$GPG-Z=9~djZ4M zpm&%LvizP0tXp%;X!VR_6+tzoOWpWynO0`IK^cf z)d9SNK3y-n0PueNRZ)E?)f6sNUi?9_ns^48C@Pe_t@aJI0*m8MZ`Cn@i1D_T`?2z| zK_SE8{RH!2Lz16Q$_jDE@afMWt!CH#wof8o-l~{cP?Vl=i0Sc;-cFy7?JGHT%1-;E zGe}b!yye#{pMm3@|Di~V2=AO69zzswS)<4f6mQNjb309dch-dsU+?PqA#Ft$*)5~N z>g`;Aqt^g$wZjKHuL8WiFB|by0=%zo>Yru^r6 zOA{KrZ}s*b=EIdFzoq55 zZv~R4k9YRRH&x#Q$iLpAc#A*PVgJtj8>F}B^I;q*+njQ0YW3Eb2Je+eSN%uzb{p1` zAi`T=Q}h(x12_Kj-di1pwJ;Bw;e>fDLqfBE)Sldp4x9pKGc z^C!-b<)vb0CGql>mE2gvC0&-?Nb+00Sykfaqv_+F-le?r>2~tdTRZB?#H}`% zGkx`*_(h)&lW;r5j_|+d|A~5AhWdLjgS4WlLCP|h-0&fm^EM<;RD<;5mzQ*c8Dy6A zKZEEDvLyF8wFAr`GY@*o4D|XUyt6(>hZ}ezn=8ejJ}`qc>gF%A0yD_>l`H*gx0%An z&P9mszd$^LT-mmShuT?9b;jZvZ}TGWpApxfHLcgLUvN0khY+~Td6eD498n5 z=HW^ryiK@AR->!8V!FzGDBiAAN(y>=>z9)c)5j@($dY$=&iO6(L>@JBuj&DKAG#D! zX%Fz;d!}ho6ptw!-|4?I_FpzgyK?WIe4bE4eT>Da=_zcAb0)?+*ksk$qwDh-u6lpP ze4Hc6&-mtyA4Z#}U%g$8lO+zzk_&xdUAa+mlkQwOBYY4BcC z=w^ZAt>oz=ON93cSvv<5@0{HkJt*EWFC~SZ0=&a>H|{yf?S~w{pPX&X=ZSQCDam&O zydPaJ?{oloe|g{Pac!O{tn)eAPhN|-dT(P7*%LLlmTG{-B~{H)Z+0if+dU^b?Q#s` z;jM%DAj?nXLEq8Jfa&8cKhNPnAU&_Qy#6{T3+iHeyeX}8`na)xRp!s~)?pgF6f@xLw0(bDRHY&?D9MLWRz zydd{Ko&fKYS;ya$8JfZOwG3l_y(3=Uij=+lD6X%TnuNtc9#=)i1-%Ie?~@)93Ii^T zxA%4z^Ffwh|9w#&o{;I|-My;JI2Xqv!ohvF-T?h&6s%9I=*O>=xr^}ym* zoozSST}XWXU+K#HG;f|43^#+!#(b4CSQkF7GbT$A<~hS==fSD#CE zv6;XIc3X3cOo;J@wv6W%Sih$3!QxW0(pbB^i1C&VfAshqE92qKhxw2p$?y5hxpu!V z&4!P3&bhQdg#r4ACckTydOdlAL>Vf!EPn6B^mtPimC)s*aNu(T+n?tx zY-#Y`Sgw(P<9+>7j3N=<0Y0;R+X3E55=R!GcrX5BcLTj3O>q7b_YXzB$Ut)(bzh<< z;aq6j6^w`XV$6p$Nq$fE%zo`(F&l=ujxTJ}iY3LnXiJdfDjjn~?CybT{t@!yEf&p^ z*ORY&VtTw)#_03mliz0V5>p>PK)j(3!o<7y(j+spZNI{@A+!4cdj-uw1F zVQ&X`Z%l{QvA_0377u-B9=z^}ymb1#pcCNzP0MAq2f+L6rI39yYK`Gf32#n#h!Ep_ zvwp3)Zux6!7Zz7v<#ka2CdRwT&r)NLCF9|J8}rdZlHZ$n_NAVj{IJXJq7tVM*Gcgf zFyo0`tZt4xoArBQ6FslD1nc`N7xywf-jp;teQaEzD*31Xx2C~+z2(+=9B+z*x&jg2 zG5dEcL^mhY^9m-X`u}kq-;V(Ay{qyrZ~u??Y7G5P(EmHq)F2JP zp-pHFQUy0ieO5E35Y?dHMhBegKn)5Ad0vDLvArG!9zx&_60a+-a=RjYk>JiNi=Fws zkXzl4vbTd86m>S_=W*}`Nl@jxiQY^TIBhZ`@x@BwCH9X)YW<;7wbTqO?)d?+B=LWF zgY=1p^uUe`##>_V!F`bA=YCOVi5qwz{lFUz_8iMsq(iJ~RM@`uOfw|Ef^A!44EYR_ zt=mgrW!he*A7UdS>GN^EWYRV0%+w6hfd+5&Z_*Teh%I(4-#~L0ID z9K?A0$3OY!r%??R!Q$pRRNKK4#5+jhoJJ>P`xtNkKN#~NL6RS9&(YS$YXo3*x54Bu zo)x5c%bS($x%AWw;jXwTDy|M`CkuLFHP+)TpID|SHjK1PH0=ES)> zaJ;#q!`2hwZOwoEp9X+;rnONpinq}Fll~Ndw;A`7)idtF#866UM_k z4)ftglHc0|_o(1reptL(YV4~Q`Eivws@!=6T!)dU>%sFL=aI)#1V$AW_%Q$T78C{g zd~n1^w+!Ezs@_Lw@K*B|%Ej?+X|_-%!kfi$NTdni-B~H*fZ{!LP$><4-qIyy;f|fj zzKGyCwxih{p2%ALj}E8M>V0OEx)9(!dieu2N758#^^>$e8b*xw7HY`yas6s42Nt)+ zaP`9WG-A9z@BH=UYd7OHNZT+U-6Z*i^PBj{$qT?UyB5yeYD-5o_M>##JhMQM%@Ni= zjLGp1J}{CV|9uD3H%LAn^!Zrh%WJeWWD0M48oXhHMN}N`jx1Ud&PlZp8Zz-PuA1m(=Zx?R^Zv`)vH-+~u?-kwvUU%Lj zyhgmbylT9wd6)6d+}?V?1U&20R)(Yk8!3gn78R zC%C_JcW}SqF5-U1{fIk~JA~VZ+lkwPdoTBP?hV|s+)KD;bF**_aDC!>&sD~i!n4c7rK9WGTac`h-oIb3Ye2=oPNf?h!{pfo5Bx&{S79*{j`0_j2O&>Bb* znh!yoW1PL5ZJafng`An34>@mgUf?{%>BxDQb2q0Zr!uDu=ORvCP723Qjt?Al93>oC z9Elv!9AO-O94;JI9Q!%6IaE00IF^E+=10&?K&Q=LcCq6Sy)=KHC6| zEA)^P^aWSwnGmQOSLhZx)P*Z_#}WFBEA-nx=o7Bc zPoc<2hZ^)ASLka-&^uhAkH0{5xI*8`fZpN? zeOdr|gDdnVcBmFt=$pt;4X)59WT9$Yp)YPiuW^MwPzY7w3VqKFdW9=t$Hgz9N?a|F zlQ)Mda3wT883vW(YTnC`Wl$Ne&{yH1Qe4e3mkx$Xa3#2ThbmNzD*+A}cc=(gv#YxE zp_jPgyQ^sk72=Bbxa%FL09QP^{jE?wuDAtal%PCZLGAa_p%=K~O!qwtA-Li=&!Y@c zamB8ESOCh!6`R1_Pf!l7X3Y$nfU!DzfV|JK~He?YuzacC=FMm`xnlJQgJo>rmX-< z!PU^s@<`}0t_JOuC!u6q4QQ)Spd?)NuY0)(O2pNVL5WjP02+qmj5nO_7&7(_~4O}&@EbN0KaMi#od=0vetM~7=Q=x0PdUxBI7rKh8I!j?G=nAgh znsaT2!g2LxsbM{I8CNweO>)pBTvaDauZ6;J_1blYG!%-fDxE{(PzbJGEht+7UBp$z zw{P~)1zeRQndZ=WT$TB69)*H&Rcf9c1D(TFiHC3;6ojjyNy>UC5LYj=E%;ym0mG#gGl;iL0mA3${ZZxXRoS#15UrRmK7%56B%?Pny%6 zAvav5#ng#IuDD7K)qV$^z*WkXE1Mw~Ts?LeFoc}{-v7@8Q#r7Mbb@9L5}nncYmn&v zzt5;H8_^o1ugb`_3a|#bu|L>$4p@VXvg=Zk221R@A~#hYU-d=04l2tgJ9r^&TUcd= z#e3k{hxK>=1WW9K>ggqS{7m4NQtDgZ&m&%g{MgNRGxGR5Y8e)1et_j??F!;G$XnM| z-G2Cq@vhkI!F)uM|CGz8 z3>qSt|NcKpI(;M*5~#0B;M`YAqD+c1qwA z4S+XKf&Hivz&rT8hU!~$FXZ5${02_2#6CHqp7R#qt(9CbFsf|=>jm6C^6@?K5jz#f zUGqFG>!^FMIF8;M^&bCn#4fbJJ~6G0@otb($9!BO$xk+Muj!z^0NiG=+H>{J8dAJ% zg!lVM3LQe&P4;ohIg(#*$!))a(%aU<^v7FdBIxt+_|BUB*5Ha=P`#aL@J9Pi9Pd(_ z!I?yOKNYuH@fzU0$~{sB#d}4G=zulAyF&0p@Aws8q`EL+meO7?MBZ>$=n{Z;xw6W@ z6M%R7xAP@jbHV2=(ruc_k;Hg^eBzTIV*8f54~t8Gw#eXn3h@b2P4BWF{$CjH{=Xi~ z$99tZl9!H|$N2EWW4SjJwmzvQ#oJ)d%_MfgLr7}N*xunhI!=%_AG;JfFv#?HQ|3C* z-#&D3L z+9?%#V!VGu2xVnO)>6-7ak2Y^vtxaU@wPg!H-b-^@xK2b#(db27cC}KU@{w z=M*hYj`tVYs67?O3=qrxF{>}e(y{;F)bZ}HjUChDP5D8e59;Au)!K)D&;K()_fMgK z8KehI4MO)u@EX+Bt;J1LgT|4Nb@`wMxwENo&jmF|Oxo=s`u)EI$5!_j;QYU%?AzwO zfnLbdc#dPoLI0ncx#muBe;ceLn;v+z-UN=_p*?fU8RGsw!(UxW?qoCdAr|K=Hmhgr zzdVq3>2+mvb7=*`egB_}`M6AypIV~z2;$EVJAFHUMA@^Bbco%(sqmy+=3!*9!QihU zPVysml#?fPHYp4;{~4r9E_C@ga)o2ti+fWu$dfd9qnmv=-pyA8xrp%Q%^clb2=I>M z5cz`6Ah(9{Xy*XDwM7nc$O63Moo(-C`FSDHW)32O0B;E|6TW)@?|tj+{N2(`V2;|6 zN~?dl|1Wo9A+>E=6O|W>8}7|h-C|F?ycOHHZ%^y(a)!hECFUcJBtJFY8TxPuKU~uI zievW2x1@L*DD-^(48EV3(XlnvQk8s&En6m)XP?CU7o=aG-S!FURi9u6%yVKx} z?q1_~bNYYeB*I&L-3;p@fVbieY6*(><(Jm#5diNQH6iMr*L@LAEw=eK-d;%Lt<&1~ z(CYnZ_D>gpcia80P~N*H@P^e5ZSiWv)qC>=m;4~1MyeVX=fjr1xMepn-V(ZJ^AK0Y zdqG+Y^C3x+-;q{x8obft7&zYhA7*e6;q9b)GqwcaJyLN$4#nHno%^>9zdKl zRle%FJidtd{{NiTu%LSDQiiME?U)ZLNq%P}qP1A~@(@XuAVZRkp z`rb^bn1y`xmZE!E@X-tAU%jPth0^6?X~CUm%Pvn6*@^JpvND=l z2Jki;%k)F>#`oUV^GSEU0GktfB+%!hki|&xaPZ&v|Cpu! zKTT7E&=Zz;4Vp0z79grY)hwYhnV<$u>YS)T`+p(v{!TvE+&HRvAZLxm*2#0fW{8-e_A`i>A?<0TEGL+nvAZrc&q99itMnSI`O zIzGwsw>tD9R+;H*5ak4&K6)Vsr9U4?pQ6DVJu-~red8CzPlR`JCiLVPz?-^M^FE3< z=gJAaCjjrEgovM+mwl0Zi6SFvqZguIDj32FhFGZe(QFrhx2v*(6RgZ zds4iw_Qi}0>scYHHWG@zpV4u=S)nhL8J4(}tF z53>BiHBwG^vkAbNo{P&OC*P6cEgBl(;%j&W5jh@^WO+4c_QS9XQ^-F86tf@aE>pkje#k7b^D|qj>AK)##wlTkQC!_l^Z< zkZ#}6QC7?HLLMqSblM2;HZ33hvIyYqYhl-I>1GV;%%T?Wk|Lg*?6BRM+ojV=)x+Xg z-Q*3n$P-Ua8uw?ouf6<=;qcbOd^C~dr~Zm}&A6d5usdx6r?+k?iC6EvK#q5o z&lmQWwF+SFjh_E!Wj#yb5rx#*&B4F? z{qy%1`1=d|{RRFHe*yo4*JjcTvFL}#_z*kGfFeXR#GZ@FzMKGtSjnCguX$jI4cFz3 z+5v{x*M&!GzFhQ0hVu3txuxQb9CWVecmS5Sgcm)X$2Qmouk4xkCP>5t-coil>{UPU z4Dy%$0%7efAE+8wT%6W+4%ucN zJ_X<%Aig+y1T;vwqV3lAMvUQvN{4m6#l(1LQ3q?TpYNn5VsSsDhVSotO^i3U(S3h= z@SxiN&TslZ|F7m?J|L3(t~fp%6))q5pE$0Ra9Ghqinm)}Se%dQf!5sTl585K0$tZi*l*xSP+6RJ>HakHgx$IExT#6@*28&dyPVaH+t6z zjYE*7yf9`dSh5Wf6MtYm;e9( literal 0 HcmV?d00001 diff --git a/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py b/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py index 36bdfc732ed79..9f0a5df7f3fcc 100644 --- a/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py +++ b/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py @@ -39,6 +39,7 @@ def generate_test_description(): {"lanelet2_map_path": lanelet2_map_path}, {"run_background": False}, {"rviz": False}, + {"centerline_source": "optimization_trajectory_base"}, {"lanelet2_input_file_path": lanelet2_map_path}, {"lanelet2_output_file_path": "/tmp/lanelet2_map.osm"}, {"start_lanelet_id": 215}, From 957e55346df22260c30d6edeb655679d2035fed3 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 12 Apr 2024 10:10:46 +0900 Subject: [PATCH 52/57] refactor(static_centerline_optimizer): clean up the code (#6794) * refactor(static_centerline_optimizer): clean up the code Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../bag_ego_trajectory_based_centerline.hpp | 2 - ...timization_trajectory_based_centerline.hpp | 2 - .../static_centerline_optimizer_node.hpp | 4 +- .../static_centerline_optimizer/utils.hpp | 2 + .../static_centerline_optimizer.launch.xml | 3 +- .../bag_ego_trajectory_based_centerline.cpp | 4 +- ...timization_trajectory_based_centerline.cpp | 27 ++---- .../src/static_centerline_optimizer_node.cpp | 89 +++++++------------ .../static_centerline_optimizer/src/utils.cpp | 5 ++ 9 files changed, 55 insertions(+), 83 deletions(-) diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp index db954b6ccbd47..b29f222b068cc 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp @@ -18,8 +18,6 @@ #include "rclcpp/rclcpp.hpp" #include "static_centerline_optimizer/type_alias.hpp" -#include -#include #include namespace static_centerline_optimizer diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp index 6e52ff98d78da..8c7c1e69e9ce6 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp @@ -18,8 +18,6 @@ #include "rclcpp/rclcpp.hpp" #include "static_centerline_optimizer/type_alias.hpp" -#include -#include #include namespace static_centerline_optimizer diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp index 242a76ae0d94f..5d9530a469012 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp @@ -31,6 +31,7 @@ #include #include +#include #include namespace static_centerline_optimizer @@ -81,8 +82,7 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node std::shared_ptr route_handler_ptr_{nullptr}; std::unique_ptr map_projector_{nullptr}; - int traj_start_index_{0}; - int traj_end_index_{0}; + std::pair traj_range_indices_{0, 0}; std::optional centerline_with_route_{std::nullopt}; enum class CenterlineSource { diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp index 52dcd171e8658..04f2268aa972f 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp @@ -28,6 +28,8 @@ namespace static_centerline_optimizer { namespace utils { +rclcpp::QoS create_transient_local_qos(); + lanelet::ConstLanelets get_lanelets_from_ids( const RouteHandler & route_handler, const std::vector & lane_ids); diff --git a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml index 10718150d1751..ed137367f3ba4 100644 --- a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml +++ b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml @@ -5,8 +5,7 @@ - - + diff --git a/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp b/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp index 150218b498ae7..571e98cdbe1c3 100644 --- a/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp +++ b/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp @@ -26,9 +26,11 @@ std::vector generate_centerline_with_bag(rclcpp::Node & node) { const auto bag_filename = node.declare_parameter("bag_filename"); + // open rosbag rosbag2_cpp::Reader bag_reader; bag_reader.open(bag_filename); + // extract 2D position of ego's trajectory from rosbag rclcpp::Serialization bag_serialization; std::vector centerline_traj_points; while (bag_reader.has_next()) { @@ -55,8 +57,6 @@ std::vector generate_centerline_with_bag(rclcpp::Node & node) } TrajectoryPoint centerline_traj_point; centerline_traj_point.pose.position = ros_msg->pose.pose.position; - // std::cerr << centerline_traj_point.pose.position.x << " " - // << centerline_traj_point.pose.position.y << std::endl; centerline_traj_points.push_back(centerline_traj_point); } diff --git a/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp b/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp index 5bce91be722ca..20b2027f39d54 100644 --- a/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp +++ b/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp @@ -20,6 +20,7 @@ #include "path_smoother/elastic_band_smoother.hpp" #include "static_centerline_optimizer/static_centerline_optimizer_node.hpp" #include "static_centerline_optimizer/utils.hpp" +#include "tier4_autoware_utils/ros/parameter.hpp" namespace static_centerline_optimizer { @@ -30,10 +31,6 @@ rclcpp::NodeOptions create_node_options() return rclcpp::NodeOptions{}; } -rclcpp::QoS create_transient_local_qos() -{ - return rclcpp::QoS{1}.transient_local(); -} Path convert_to_path(const PathWithLaneId & path_with_lane_id) { Path path; @@ -66,8 +63,9 @@ Trajectory convert_to_trajectory(const Path & path) OptimizationTrajectoryBasedCenterline::OptimizationTrajectoryBasedCenterline(rclcpp::Node & node) { pub_raw_path_with_lane_id_ = - node.create_publisher("input_centerline", create_transient_local_qos()); - pub_raw_path_ = node.create_publisher("debug/raw_centerline", create_transient_local_qos()); + node.create_publisher("input_centerline", utils::create_transient_local_qos()); + pub_raw_path_ = + node.create_publisher("debug/raw_centerline", utils::create_transient_local_qos()); } std::vector @@ -82,20 +80,13 @@ OptimizationTrajectoryBasedCenterline::generate_centerline_with_optimization( // get ego nearest search parameters and resample interval in behavior_path_planner const double ego_nearest_dist_threshold = - node.has_parameter("ego_nearest_dist_threshold") - ? node.get_parameter("ego_nearest_dist_threshold").as_double() - : node.declare_parameter("ego_nearest_dist_threshold"); + tier4_autoware_utils::getOrDeclareParameter(node, "ego_nearest_dist_threshold"); const double ego_nearest_yaw_threshold = - node.has_parameter("ego_nearest_yaw_threshold") - ? node.get_parameter("ego_nearest_yaw_threshold").as_double() - : node.declare_parameter("ego_nearest_yaw_threshold"); - const double behavior_path_interval = node.has_parameter("output_path_interval") - ? node.get_parameter("output_path_interval").as_double() - : node.declare_parameter("output_path_interval"); + tier4_autoware_utils::getOrDeclareParameter(node, "ego_nearest_yaw_threshold"); + const double behavior_path_interval = + tier4_autoware_utils::getOrDeclareParameter(node, "output_path_interval"); const double behavior_vel_interval = - node.has_parameter("behavior_output_path_interval") - ? node.get_parameter("behavior_output_path_interval").as_double() - : node.declare_parameter("behavior_output_path_interval"); + tier4_autoware_utils::getOrDeclareParameter(node, "behavior_output_path_interval"); // extract path with lane id from lanelets const auto raw_path_with_lane_id = [&]() { diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index 4f729ab5c8c57..073d30f5b5a39 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -57,19 +57,6 @@ namespace static_centerline_optimizer { namespace { -[[maybe_unused]] lanelet::ConstLanelets get_lanelets_from_route( - const RouteHandler & route_handler, const LaneletRoute & route) -{ - lanelet::ConstLanelets lanelets; - for (const auto & segment : route.segments) { - const auto & target_lanelet_id = segment.preferred_primitive.id; - const auto target_lanelet = route_handler.getLaneletsFromId(target_lanelet_id); - lanelets.push_back(target_lanelet); - } - - return lanelets; -} - std::vector get_lane_ids_from_route(const LaneletRoute & route) { std::vector lane_ids; @@ -81,12 +68,7 @@ std::vector get_lane_ids_from_route(const LaneletRoute & route) return lane_ids; } -rclcpp::QoS create_transient_local_qos() -{ - return rclcpp::QoS{1}.transient_local(); -} - -lanelet::BasicPoint2d convertToLaneletPoint(const geometry_msgs::msg::Point & geom_point) +lanelet::BasicPoint2d convert_to_lanelet_point(const geometry_msgs::msg::Point & geom_point) { lanelet::BasicPoint2d point(geom_point.x, geom_point.y); return point; @@ -131,7 +113,7 @@ geometry_msgs::msg::Pose get_text_pose( return tier4_autoware_utils::calcOffsetPose(pose, x_front, y_left, 0.0); } -std::array convertHexStringToDecimal(const std::string & hex_str_color) +std::array convert_hex_string_to_decimal(const std::string & hex_str_color) { unsigned int hex_int_color; std::istringstream iss(hex_str_color); @@ -165,7 +147,7 @@ std::vector check_lanelet_connection( return unconnected_lane_ids; } -std_msgs::msg::Header createHeader(const rclcpp::Time & now) +std_msgs::msg::Header create_header(const rclcpp::Time & now) { std_msgs::msg::Header header; header.frame_id = "map"; @@ -173,7 +155,7 @@ std_msgs::msg::Header createHeader(const rclcpp::Time & now) return header; } -std::vector resampleTrajectoryPoints( +std::vector resample_trajectory_points( const std::vector & input_traj_points, const double resample_interval) { // resample and calculate trajectory points' orientation @@ -188,29 +170,27 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( : Node("static_centerline_optimizer", node_options) { // publishers - pub_map_bin_ = create_publisher("lanelet2_map_topic", create_transient_local_qos()); + pub_map_bin_ = + create_publisher("lanelet2_map_topic", utils::create_transient_local_qos()); pub_whole_centerline_ = - create_publisher("output_whole_centerline", create_transient_local_qos()); - pub_centerline_ = create_publisher("output_centerline", create_transient_local_qos()); + create_publisher("output_whole_centerline", utils::create_transient_local_qos()); + pub_centerline_ = + create_publisher("output_centerline", utils::create_transient_local_qos()); // debug publishers pub_debug_unsafe_footprints_ = - create_publisher("debug/unsafe_footprints", create_transient_local_qos()); + create_publisher("debug/unsafe_footprints", utils::create_transient_local_qos()); // subscribers sub_traj_start_index_ = create_subscription( "/centerline_updater_helper/traj_start_index", rclcpp::QoS{1}, [this](const std_msgs::msg::Int32 & msg) { - if (msg.data <= traj_end_index_ + 1) { - update_centerline_range(msg.data, traj_end_index_); - } + update_centerline_range(msg.data, traj_range_indices_.second); }); sub_traj_end_index_ = create_subscription( "/centerline_updater_helper/traj_end_index", rclcpp::QoS{1}, [this](const std_msgs::msg::Int32 & msg) { - if (traj_start_index_ <= msg.data + 1) { - update_centerline_range(traj_start_index_, msg.data); - } + update_centerline_range(traj_range_indices_.first, msg.data); }); sub_save_map_ = create_subscription( "/centerline_updater_helper/save_map", rclcpp::QoS{1}, [this](const std_msgs::msg::Bool & msg) { @@ -220,7 +200,8 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( if (!centerline_with_route_ || msg.data) { const auto & c = *centerline_with_route_; const auto selected_centerline = std::vector( - c.centerline.begin() + traj_start_index_, c.centerline.begin() + traj_end_index_ + 1); + c.centerline.begin() + traj_range_indices_.first, + c.centerline.begin() + traj_range_indices_.second + 1); save_map( lanelet2_output_file_path, CenterlineWithRoute{selected_centerline, c.route_lane_ids}); } @@ -271,19 +252,19 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( void StaticCenterlineOptimizerNode::update_centerline_range( const int traj_start_index, const int traj_end_index) { - if (!centerline_with_route_) { + if (!centerline_with_route_ || traj_range_indices_.second + 1 < traj_start_index) { return; } - traj_start_index_ = traj_start_index; - traj_end_index_ = traj_end_index; + traj_range_indices_ = std::make_pair(traj_start_index, traj_end_index); const auto & centerline = centerline_with_route_->centerline; const auto selected_centerline = std::vector( - centerline.begin() + traj_start_index_, centerline.begin() + traj_end_index_ + 1); + centerline.begin() + traj_range_indices_.first, + centerline.begin() + traj_range_indices_.second + 1); pub_centerline_->publish( - motion_utils::convertToTrajectory(selected_centerline, createHeader(this->now()))); + motion_utils::convertToTrajectory(selected_centerline, create_header(this->now()))); } void StaticCenterlineOptimizerNode::run() @@ -296,8 +277,7 @@ void StaticCenterlineOptimizerNode::run() // process load_map(lanelet2_input_file_path); const auto centerline_with_route = generate_centerline_with_route(); - traj_start_index_ = 0; - traj_end_index_ = centerline_with_route.centerline.size() - 1; + traj_range_indices_ = std::make_pair(0, centerline_with_route.centerline.size() - 1); save_map(lanelet2_output_file_path, centerline_with_route); centerline_with_route_ = centerline_with_route; @@ -310,6 +290,7 @@ CenterlineWithRoute StaticCenterlineOptimizerNode::generate_centerline_with_rout return CenterlineWithRoute{}; } + // generate centerline with route auto centerline_with_route = [&]() { if (centerline_source_ == CenterlineSource::OptimizationTrajectoryBase) { const lanelet::Id start_lanelet_id = declare_parameter("start_lanelet_id"); @@ -339,15 +320,16 @@ CenterlineWithRoute StaticCenterlineOptimizerNode::generate_centerline_with_rout "The centerline source is not supported in static_centerline_optimizer."); }(); + // resample const double output_trajectory_interval = declare_parameter("output_trajectory_interval"); centerline_with_route.centerline = - resampleTrajectoryPoints(centerline_with_route.centerline, output_trajectory_interval); + resample_trajectory_points(centerline_with_route.centerline, output_trajectory_interval); - pub_whole_centerline_->publish( - motion_utils::convertToTrajectory(centerline_with_route.centerline, createHeader(this->now()))); + pub_whole_centerline_->publish(motion_utils::convertToTrajectory( + centerline_with_route.centerline, create_header(this->now()))); - pub_centerline_->publish( - motion_utils::convertToTrajectory(centerline_with_route.centerline, createHeader(this->now()))); + pub_centerline_->publish(motion_utils::convertToTrajectory( + centerline_with_route.centerline, create_header(this->now()))); return centerline_with_route; } @@ -537,8 +519,8 @@ void StaticCenterlineOptimizerNode::on_plan_path( std::vector current_lanelet_points; // check if target point is inside the lanelet - while ( - lanelet::geometry::inside(lanelet, convertToLaneletPoint(target_traj_point->pose.position))) { + while (lanelet::geometry::inside( + lanelet, convert_to_lanelet_point(target_traj_point->pose.position))) { // memorize points inside the lanelet current_lanelet_points.push_back(target_traj_point->pose.position); target_traj_point++; @@ -571,18 +553,15 @@ void StaticCenterlineOptimizerNode::evaluate( const std::vector & optimized_traj_points) { const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); - const auto dist_thresh_vec = - has_parameter("marker_color_dist_thresh") - ? get_parameter("marker_color_dist_thresh").as_double_array() - : declare_parameter>("marker_color_dist_thresh"); - const auto marker_color_vec = has_parameter("marker_color") - ? get_parameter("marker_color").as_string_array() - : declare_parameter>("marker_color"); + const auto dist_thresh_vec = tier4_autoware_utils::getOrDeclareParameter>( + *this, "marker_color_dist_thresh"); + const auto marker_color_vec = + tier4_autoware_utils::getOrDeclareParameter>(*this, "marker_color"); const auto get_marker_color = [&](const double dist) -> boost::optional> { for (size_t i = 0; i < dist_thresh_vec.size(); ++i) { const double dist_thresh = dist_thresh_vec.at(i); if (dist < dist_thresh) { - return convertHexStringToDecimal(marker_color_vec.at(i)); + return convert_hex_string_to_decimal(marker_color_vec.at(i)); } } return boost::none; diff --git a/planning/static_centerline_optimizer/src/utils.cpp b/planning/static_centerline_optimizer/src/utils.cpp index 3cc7ed5ca1fda..9448677d1bbae 100644 --- a/planning/static_centerline_optimizer/src/utils.cpp +++ b/planning/static_centerline_optimizer/src/utils.cpp @@ -45,6 +45,11 @@ lanelet::Point3d createPoint3d(const double x, const double y, const double z = namespace utils { +rclcpp::QoS create_transient_local_qos() +{ + return rclcpp::QoS{1}.transient_local(); +} + lanelet::ConstLanelets get_lanelets_from_ids( const RouteHandler & route_handler, const std::vector & lane_ids) { From 879358434705a6f8fa512c0b438583fd696cccf1 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 12 Apr 2024 10:50:09 +0900 Subject: [PATCH 53/57] docs(avoidance): use json schema (#6789) docs(avoidance): json schema Signed-off-by: satoshi-ota --- .../behavior_path_avoidance_module/README.md | 171 +- .../schema/avoidance.schema.json | 1465 +++++++++++++++++ 2 files changed, 1466 insertions(+), 170 deletions(-) create mode 100644 planning/behavior_path_avoidance_module/schema/avoidance.schema.json diff --git a/planning/behavior_path_avoidance_module/README.md b/planning/behavior_path_avoidance_module/README.md index dc6ab0ec4b6e1..aa7a3a42efdb4 100644 --- a/planning/behavior_path_avoidance_module/README.md +++ b/planning/behavior_path_avoidance_module/README.md @@ -760,176 +760,7 @@ WIP The avoidance specific parameter configuration file can be located at `src/autoware/launcher/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml`. -### General parameters - -namespace: `avoidance.` - -| Name | Unit | Type | Description | Default value | -| :------------------------------------ | :--- | :----- | :---------------------------------------------------------------------------------------------------------------------------------- | :------------ | -| resample_interval_for_planning | [m] | double | Path resample interval for avoidance planning path. | 0.3 | -| resample_interval_for_output | [m] | double | Path resample interval for output path. Too short interval increases computational cost for latter modules. | 4.0 | -| detection_area_right_expand_dist | [m] | double | Lanelet expand length for right side to find avoidance target vehicles. | 0.0 | -| detection_area_left_expand_dist | [m] | double | Lanelet expand length for left side to find avoidance target vehicles. | 1.0 | -| enable_cancel_maneuver | [-] | bool | Reset trajectory when avoided objects are gone. If false, shifted path points remain same even though the avoided objects are gone. | false | -| enable_yield_maneuver | [-] | bool | Flag to enable yield maneuver. | false | -| enable_yield_maneuver_during_shifting | [-] | bool | Flag to enable yield maneuver during shifting. | false | - -| Name | Unit | Type | Description | Default value | -| :------------------------ | ---- | ---- | ----------------------------------------------------------------------------------------------------------------------- | ------------- | -| enable_bound_clipping | [-] | bool | Enable clipping left and right bound of drivable area when obstacles are in the drivable area | false | -| use_adjacent_lane | [-] | bool | Extend avoidance trajectory to adjacent lanes that has same direction. If false, avoidance only happen in current lane. | true | -| use_opposite_lane | [-] | bool | Extend avoidance trajectory to opposite direction lane. `use_adjacent_lane` must be `true` to take effects | true | -| use_intersection_areas | [-] | bool | Extend drivable to intersection area. | false | -| use_hatched_road_markings | [-] | bool | Extend drivable to hatched road marking area. | false | - -| Name | Unit | Type | Description | Default value | -| :------------------ | ---- | ---- | --------------------------------------------------------------------------------------- | ------------- | -| output_debug_marker | [-] | bool | Flag to publish debug marker (set `false` as default since it takes considerable cost). | false | -| output_debug_info | [-] | bool | Flag to print debug info (set `false` as default since it takes considerable cost). | false | - -### Avoidance target filtering parameters - -namespace: `avoidance.target_object.` - -This module supports all object classes, and it can set following parameters independently. - -```yaml -car: - is_target: true # [-] - moving_speed_threshold: 1.0 # [m/s] - moving_time_threshold: 1.0 # [s] - max_expand_ratio: 0.0 # [-] - envelope_buffer_margin: 0.3 # [m] - avoid_margin_lateral: 1.0 # [m] - safety_buffer_lateral: 0.7 # [m] - safety_buffer_longitudinal: 0.0 # [m] -``` - -| Name | Unit | Type | Description | Default value | -| :------------------------- | ----- | ------ | ------------------------------------------------------------------------------------------------------------------------- | ------------- | -| is_target | [-] | bool | By setting this flag `true`, this module avoid those class objects. | false | -| moving_speed_threshold | [m/s] | double | Objects with speed greater than this will be judged as moving ones. | 1.0 | -| moving_time_threshold | [s] | double | Objects keep moving longer duration than this will be excluded from avoidance target. | 1.0 | -| envelope_buffer_margin | [m] | double | The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation. | 0.3 | -| avoid_margin_lateral | [m] | double | The lateral distance between ego and avoidance targets. | 1.0 | -| safety_buffer_lateral | [m] | double | Creates an additional lateral gap that will prevent the vehicle from getting to near to the obstacle. | 0.5 | -| safety_buffer_longitudinal | [m] | double | Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle. | 0.0 | - -Parameters for the logic to compensate perception noise of the far objects. - -| Name | Unit | Type | Description | Default value | -| :----------------------------------- | ---- | ------ | ------------------------------------------------------------------------------------------------------------ | ------------- | -| max_expand_ratio | [-] | double | This value will be applied `envelope_buffer_margin` according to the distance between the ego and object. | 0.0 | -| lower_distance_for_polygon_expansion | [-] | double | If the distance between the ego and object is less than this, the expand ratio will be zero. | 30.0 | -| upper_distance_for_polygon_expansion | [-] | double | If the distance between the ego and object is larger than this, the expand ratio will be `max_expand_ratio`. | 100.0 | - -namespace: `avoidance.target_filtering.` - -| Name | Unit | Type | Description | Default value | -| :---------------------------------------------------- | :--- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | -| threshold_distance_object_is_on_center | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 1.0 | -| object_ignore_section_traffic_light_in_front_distance | [m] | double | If the distance between traffic light and vehicle is less than this parameter, this module will ignore it. | 30.0 | -| object_ignore_section_crosswalk_in_front_distance | [m] | double | If the front distance between crosswalk and vehicle is less than this parameter, this module will ignore it. | 30.0 | -| object_ignore_section_crosswalk_behind_distance | [m] | double | If the back distance between crosswalk and vehicle is less than this parameter, this module will ignore it. | 30.0 | -| object_check_forward_distance | [m] | double | Forward distance to search the avoidance target. | 150.0 | -| object_check_backward_distance | [m] | double | Backward distance to search the avoidance target. | 2.0 | -| object_check_goal_distance | [m] | double | If the distance between object and goal position is less than this parameter, the module do not return center line. | 20.0 | -| object_check_return_pose_distance | [m] | double | If the distance between object and return position is less than this parameter, the module do not return center line. | 20.0 | -| object_check_shiftable_ratio | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 0.6 | -| object_check_min_road_shoulder_width | [m] | double | Width considered as a road shoulder if the lane does not have a road shoulder target. | 0.5 | -| object_last_seen_threshold | [s] | double | For the compensation of the detection lost. The object is registered once it is observed as an avoidance target. When the detection loses, the timer will start and the object will be un-registered when the time exceeds this limit. | 2.0 | - -### Safety check parameters - -namespace: `avoidance.safety_check.` - -| Name | Unit | Type | Description | Default value | -| :----------------------------- | ---- | ------ | ---------------------------------------------------------------------------------------------------------- | ------------- | -| enable | [-] | bool | Enable to use safety check feature. | true | -| check_current_lane | [-] | bool | Check objects on current driving lane. | false | -| check_shift_side_lane | [-] | bool | Check objects on shift side lane. | true | -| check_other_side_lane | [-] | bool | Check objects on other side lane. | false | -| check_unavoidable_object | [-] | bool | Check collision between ego and unavoidable objects. | false | -| check_other_object | [-] | bool | Check collision between ego and non avoidance target objects. | false | -| check_all_predicted_path | [-] | bool | Check all prediction path of safety check target objects. | false | -| time_horizon | [s] | double | Time horizon to check lateral/longitudinal margin is enough or not. | 10.0 | -| time_resolution | [s] | double | Time resolution to check lateral/longitudinal margin is enough or not. | 0.5 | -| safety_check_backward_distance | [m] | double | Backward distance to search the dynamic objects. | 50.0 | -| safety_check_hysteresis_factor | [-] | double | Hysteresis factor that be used for chattering prevention. | 2.0 | -| safety_check_ego_offset | [m] | double | Output new avoidance path **only when** the offset between ego and previous output path is less than this. | 1.0 | - -### Avoidance maneuver parameters - -namespace: `avoidance.avoidance.lateral.` - -| Name | Unit | Type | Description | Default value | -| :---------------------------- | :--- | :----- | :-------------------------------------------------------------------------------------------------------------------------- | :------------ | -| road_shoulder_safety_margin | [m] | double | Prevents the generated path to come too close to the road shoulders. | 0.0 | -| lateral_execution_threshold | [m] | double | The lateral distance deviation threshold between the current path and suggested avoidance point to execute avoidance. (\*2) | 0.499 | -| lateral_small_shift_threshold | [m] | double | The shift lines whose lateral offset is less than this will be applied with other ones. | 0.501 | -| max_right_shift_length | [m] | double | Maximum shift length for right direction | 5.0 | -| max_left_shift_length | [m] | double | Maximum shift length for left direction | 5.0 | - -namespace: `avoidance.avoidance.longitudinal.` - -| Name | Unit | Type | Description | Default value | -| :----------------------------------- | :---- | :----- | :---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------- | -| prepare_time | [s] | double | Avoidance shift starts from point ahead of this time x ego_speed to avoid sudden path change. | 2.0 | -| longitudinal_collision_safety_buffer | [s] | double | Longitudinal collision buffer between target object and shift line. | 0.0 | -| min_prepare_distance | [m] | double | Minimum distance for "prepare_time" x "ego_speed". | 1.0 | -| min_avoidance_distance | [m] | double | Minimum distance of avoidance path (i.e. this distance is needed even if its lateral jerk is very low) | 10.0 | -| min_nominal_avoidance_speed | [m/s] | double | Minimum speed for jerk calculation in a nominal situation (\*1). | 7.0 | -| min_sharp_avoidance_speed | [m/s] | double | Minimum speed for jerk calculation in a sharp situation (\*1). | 1.0 | -| min_slow_down_speed | [m/s] | double | Minimum slow speed for avoidance prepare section. | 1.38 (5km/h) | -| buf_slow_down_speed | [m/s] | double | Buffer for controller tracking error. Basically, vehicle always cannot follow velocity profile precisely. Therefore, the module inserts lower speed than target speed that satisfies conditions to avoid object within accel/jerk constraints so that the avoidance path always can be output even if the current speed is a little bit higher than target speed. | 0.57 (2.0km/h) | - -### Yield maneuver parameters - -namespace: `avoidance.yield.` - -| Name | Unit | Type | Description | Default value | -| :------------- | :---- | :----- | :------------------------------------------------------------ | :------------ | -| yield_velocity | [m/s] | double | The ego will decelerate yield velocity in the yield maneuver. | 2.78 | - -### Stop maneuver parameters - -namespace: `avoidance.stop.` - -| Name | Unit | Type | Description | Default value | -| :----------- | :--- | :----- | :---------------------------------------------------------------------------------------------------- | :------------ | -| min_distance | [m] | double | Minimum stop distance in the situation where avoidance maneuver is not approved or in yield maneuver. | 10.0 | -| max_distance | [m] | double | Maximum stop distance in the situation where avoidance maneuver is not approved or in yield maneuver. | 20.0 | -| stop_buffer | [m] | double | Buffer distance in the situation where avoidance maneuver is not approved or in yield maneuver. | 1.0 | - -### Constraints parameters - -namespace: `avoidance.constraints.` - -| Name | Unit | Type | Description | Default value | -| :------------------------ | :--- | :--- | :--------------------------------------------------------------------------------------- | :------------ | -| use_constraints_for_decel | [-] | bool | Flag to decel under longitudinal constraints. `TRUE: allow to control breaking mildness` | false | - -namespace: `avoidance.constraints.lateral.` - -| a Name | Unit | Type | Description | Default value | -| :----------------------- | :----- | :----- | :-------------------------------------------------------------------------------------------- | :------------ | -| prepare_time | [s] | double | Avoidance shift starts from point ahead of this time x ego_speed to avoid sudden path change. | 2.0 | -| min_prepare_distance | [m] | double | Minimum distance for "prepare_time" x "ego_speed". | 1.0 | -| nominal_lateral_jerk | [m/s3] | double | Avoidance path is generated with this jerk when there is enough distance from ego. | 0.2 | -| max_lateral_jerk | [m/s3] | double | Avoidance path gets sharp up to this jerk limit when there is not enough distance from ego. | 1.0 | -| max_lateral_acceleration | [m/s3] | double | Avoidance path gets sharp up to this accel limit when there is not enough distance from ego. | 0.5 | - -namespace: `avoidance.constraints.longitudinal.` - -| Name | Unit | Type | Description | Default value | -| :------------------- | :------ | :----- | :------------------------------------- | :------------ | -| nominal_deceleration | [m/ss] | double | Nominal deceleration limit. | -1.0 | -| nominal_jerk | [m/sss] | double | Nominal jerk limit. | 0.5 | -| max_deceleration | [m/ss] | double | Max decelerate limit. | -2.0 | -| max_jerk | [m/sss] | double | Max jerk limit. | 1.0 | -| max_acceleration | [m/ss] | double | Maximum acceleration during avoidance. | 1.0 | - -(\*2) If there are multiple vehicles in a row to be avoided, no new avoidance path will be generated unless their lateral margin difference exceeds this value. +{{ json_to_markdown("planning/behavior_path_avoidance_module/schema/avoidance.schema.json") }} ## Future extensions / Unimplemented parts diff --git a/planning/behavior_path_avoidance_module/schema/avoidance.schema.json b/planning/behavior_path_avoidance_module/schema/avoidance.schema.json new file mode 100644 index 0000000000000..cd3e29b8ec0b8 --- /dev/null +++ b/planning/behavior_path_avoidance_module/schema/avoidance.schema.json @@ -0,0 +1,1465 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for behavior_path_avoidance_module", + "type": "object", + "definitions": { + "behavior_path_avoidance_module": { + "type": "object", + "properties": { + "resample_interval_for_planning": { + "type": "number", + "description": "Path resample interval for avoidance planning path.", + "default": "0.3" + }, + "resample_interval_for_output": { + "type": "number", + "description": "Path resample interval for output path. Too short interval increases computational cost for latter modules.", + "default": "4.0" + }, + "enable_bound_clipping": { + "type": "boolean", + "description": "Enable clipping left and right bound of drivable area when obstacles are in the drivable area.", + "default": "false" + }, + "disable_path_update": { + "type": "boolean", + "description": "Disable path update.", + "default": "false" + }, + "use_adjacent_lane": { + "type": "boolean", + "description": "Extend avoidance trajectory to adjacent lanes that has same direction. If false, avoidance only happen in current lane.", + "default": "true" + }, + "use_opposite_lane": { + "type": "boolean", + "description": "Extend avoidance trajectory to opposite direction lane. `use_adjacent_lane` must be `true` to take effects.", + "default": "true" + }, + "use_hatched_road_markings": { + "type": "boolean", + "description": "Extend drivable to hatched road marking area.", + "default": "true" + }, + "use_intersection_areas": { + "type": "boolean", + "description": "Extend drivable to intersection area.", + "default": "true" + }, + "use_freespace_areas": { + "type": "boolean", + "description": "Extend drivable to freespace area.", + "default": "true" + }, + "target_object": { + "type": "object", + "properties": { + "car": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.3 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.2 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.5 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "truck": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.3 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.2 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.5 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "bus": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.3 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.2 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.5 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "trailer": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.3 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.2 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.5 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "unknown": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": -0.2 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": -0.2 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.1 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "motorcycle": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.5 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.5 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.5 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "bicycle": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.3 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.3 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.5 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "pedestrian": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.5 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.5 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.5 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "lower_distance_for_polygon_expansion": { + "type": "number", + "description": "If the distance between the ego and object is less than this, the expand ratio will be zero.", + "default": 30.0 + }, + "upper_distance_for_polygon_expansion": { + "type": "number", + "description": "If the distance between the ego and object is larger than this, the expand ratio will be max_expand_ratio.", + "default": 100.0 + } + }, + "required": [ + "car", + "truck", + "bus", + "trailer", + "unknown", + "bicycle", + "motorcycle", + "pedestrian", + "lower_distance_for_polygon_expansion", + "upper_distance_for_polygon_expansion" + ], + "additionalProperties": false + }, + "target_filtering": { + "type": "object", + "properties": { + "target_type": { + "type": "object", + "properties": { + "car": { + "type": "boolean", + "description": "Enable avoidance maneuver for CAR.", + "default": "true" + }, + "truck": { + "type": "boolean", + "description": "Enable avoidance maneuver for TRUCK.", + "default": "true" + }, + "bus": { + "type": "boolean", + "description": "Enable avoidance maneuver for BUS.", + "default": "true" + }, + "trailer": { + "type": "boolean", + "description": "Enable avoidance maneuver for TRAILER.", + "default": "true" + }, + "unknown": { + "type": "boolean", + "description": "Enable avoidance maneuver for UNKNOWN.", + "default": "true" + }, + "bicycle": { + "type": "boolean", + "description": "Enable avoidance maneuver for BICYCLE.", + "default": "true" + }, + "motorcycle": { + "type": "boolean", + "description": "Enable avoidance maneuver for MOTORCYCLE.", + "default": "true" + }, + "pedestrian": { + "type": "boolean", + "description": "Enable avoidance maneuver for PEDESTRIAN.", + "default": "true" + } + }, + "required": [ + "car", + "truck", + "bus", + "trailer", + "unknown", + "bicycle", + "motorcycle", + "pedestrian" + ], + "additionalProperties": false + }, + "object_check_goal_distance": { + "type": "number", + "description": "If the distance between object and goal position is less than this parameter, the module do not return center line.", + "default": 20.0 + }, + "object_check_return_pose_distance": { + "type": "number", + "description": "If the distance between object and return position is less than this parameter, the module do not return center line.", + "default": 20.0 + }, + "max_compensation_time": { + "type": "number", + "description": "For the compensation of the detection lost. The object is registered once it is observed as an avoidance target. When the detection loses, the timer will start and the object will be un-registered when the time exceeds this limit.", + "default": 2.0 + }, + "detection_area": { + "type": "object", + "properties": { + "static": { + "type": "boolean", + "description": "If true, the detection area longitudinal range is calculated based on current ego speed.", + "default": "false" + }, + "min_forward_distance": { + "type": "number", + "description": "Minimum forward distance to search the avoidance target.", + "default": 50.0 + }, + "max_forward_distance": { + "type": "number", + "description": "Maximum forward distance to search the avoidance target.", + "default": 150.0 + }, + "backward_distance": { + "type": "number", + "description": "Backward distance to search the avoidance target.", + "default": 10.0 + } + }, + "required": [ + "static", + "min_forward_distance", + "max_forward_distance", + "backward_distance" + ], + "additionalProperties": false + }, + "parked_vehicle": { + "type": "object", + "properties": { + "th_offset_from_centerline": { + "type": "number", + "description": "Vehicles around the center line within this distance will be excluded from avoidance target.", + "default": 1.0 + }, + "th_shiftable_ratio": { + "type": "number", + "description": "Vehicles around the center line within this distance will be excluded from avoidance target.", + "default": 0.8, + "minimum": 0.0, + "maximum": 1.0 + }, + "min_road_shoulder_width": { + "type": "number", + "description": "Width considered as a road shoulder if the lane does not have a road shoulder target.", + "default": 0.5 + } + }, + "required": [ + "th_offset_from_centerline", + "th_shiftable_ratio", + "min_road_shoulder_width" + ], + "additionalProperties": false + }, + "avoidance_for_ambiguous_vehicle": { + "type": "object", + "properties": { + "enable": { + "type": "boolean", + "description": "Enable avoidance maneuver for ambiguous vehicles.", + "default": "true" + }, + "closest_distance_to_wait_and_see": { + "type": "number", + "description": "Start avoidance maneuver after the distance to ambiguous vehicle is less than this param.", + "default": 10.0 + }, + "condition": { + "type": "object", + "properties": { + "th_stopped_time": { + "type": "number", + "description": "Never avoid object whose stopped time is less than this param.", + "default": 3.0 + }, + "th_moving_distance": { + "type": "number", + "description": "Never avoid object which moves more than this param.", + "default": 1.0 + } + }, + "required": ["th_stopped_time", "th_moving_distance"], + "additionalProperties": false + }, + "ignore_area": { + "type": "object", + "properties": { + "traffic_light": { + "type": "object", + "properties": { + "front_distance": { + "type": "number", + "description": "If the distance between traffic light and vehicle is less than this parameter, this module will ignore it.", + "default": 100.0 + } + }, + "required": ["front_distance"], + "additionalProperties": false + }, + "crosswalk": { + "type": "object", + "properties": { + "front_distance": { + "type": "number", + "description": "If the front distance between crosswalk and vehicle is less than this parameter, this module will ignore it.", + "default": 30.0 + }, + "behind_distance": { + "type": "number", + "description": "If the back distance between crosswalk and vehicle is less than this parameter, this module will ignore it.", + "default": 30.0 + } + }, + "required": ["front_distance", "behind_distance"], + "additionalProperties": false + } + }, + "required": ["traffic_light", "crosswalk"], + "additionalProperties": false + } + }, + "required": [ + "enable", + "closest_distance_to_wait_and_see", + "condition", + "ignore_area" + ], + "additionalProperties": false + }, + "intersection": { + "type": "object", + "properties": { + "yaw_deviation": { + "type": "number", + "description": "Yaw deviation threshold param to judge if the object is not merging or deviating vehicle.", + "default": 0.349 + } + }, + "required": ["yaw_deviation"], + "additionalProperties": false + } + }, + "required": [ + "target_type", + "object_check_goal_distance", + "object_check_return_pose_distance", + "max_compensation_time", + "detection_area", + "parked_vehicle", + "avoidance_for_ambiguous_vehicle", + "intersection" + ], + "additionalProperties": false + }, + "safety_check": { + "type": "object", + "properties": { + "target_type": { + "type": "object", + "properties": { + "car": { + "type": "boolean", + "description": "Enable safety_check for CAR.", + "default": "true" + }, + "truck": { + "type": "boolean", + "description": "Enable safety_check for TRUCK.", + "default": "true" + }, + "bus": { + "type": "boolean", + "description": "Enable safety_check for BUS.", + "default": "true" + }, + "trailer": { + "type": "boolean", + "description": "Enable safety_check for TRAILER.", + "default": "true" + }, + "unknown": { + "type": "boolean", + "description": "Enable safety_check for UNKNOWN.", + "default": "false" + }, + "bicycle": { + "type": "boolean", + "description": "Enable safety_check for BICYCLE.", + "default": "true" + }, + "motorcycle": { + "type": "boolean", + "description": "Enable safety_check for MOTORCYCLE.", + "default": "true" + }, + "pedestrian": { + "type": "boolean", + "description": "Enable safety_check for PEDESTRIAN.", + "default": "true" + } + }, + "required": [ + "car", + "truck", + "bus", + "trailer", + "unknown", + "bicycle", + "motorcycle", + "pedestrian" + ], + "additionalProperties": false + }, + "enable": { + "type": "boolean", + "description": "Enable to use safety check feature.", + "default": "true" + }, + "check_current_lane": { + "type": "boolean", + "description": "Check objects on current driving lane.", + "default": "true" + }, + "check_shift_side_lane": { + "type": "boolean", + "description": "Check objects on shift side lane.", + "default": "true" + }, + "check_other_side_lane": { + "type": "boolean", + "description": "Check objects on other side lane.", + "default": "true" + }, + "check_unavoidable_object": { + "type": "boolean", + "description": "Check collision between ego and unavoidable objects.", + "default": "true" + }, + "check_other_object": { + "type": "boolean", + "description": "Check collision between ego and non avoidance target objects.", + "default": "true" + }, + "check_all_predicted_path": { + "type": "boolean", + "description": "Check all prediction path of safety check target objects.", + "default": "true" + }, + "safety_check_backward_distance": { + "type": "number", + "description": "Backward distance to search the dynamic objects.", + "default": 100.0 + }, + "hysteresis_factor_expand_rate": { + "type": "number", + "description": "Hysteresis factor that be used for chattering prevention.", + "default": 2.0 + }, + "hysteresis_factor_safe_count": { + "type": "integer", + "description": "Hysteresis count that be used for chattering prevention.", + "default": 10 + }, + "min_velocity": { + "type": "number", + "description": "Minimum velocity of the ego vehicle's predicted path.", + "default": 1.38 + }, + "max_velocity": { + "type": "number", + "description": "Maximum velocity of the ego vehicle's predicted path.", + "default": 50.0 + }, + "time_resolution": { + "type": "number", + "description": "Time resolution for the ego vehicle's predicted path.", + "default": 0.5 + }, + "time_horizon_for_front_object": { + "type": "number", + "description": "Time horizon for predicting front objects.", + "default": 3.0 + }, + "time_horizon_for_rear_object": { + "type": "number", + "description": "Time horizon for predicting rear objects.", + "default": 10.0 + }, + "delay_until_departure": { + "type": "number", + "description": "Delay until the ego vehicle departs.", + "default": 1.0 + }, + "extended_polygon_policy": { + "type": "string", + "enum": ["rectangle", "along_path"], + "description": "See https://github.com/autowarefoundation/autoware.universe/pull/6336.", + "default": "along_path" + }, + "expected_front_deceleration": { + "type": "number", + "description": "The front object's maximum deceleration when the front vehicle perform sudden braking.", + "default": -1.0 + }, + "expected_rear_deceleration": { + "type": "number", + "description": "The rear object's maximum deceleration when the rear vehicle perform sudden braking.", + "default": -1.0 + }, + "rear_vehicle_reaction_time": { + "type": "number", + "description": "The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake.", + "default": 2.0 + }, + "rear_vehicle_safety_time_margin": { + "type": "number", + "description": "The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking.", + "default": 1.0 + }, + "lateral_distance_max_threshold": { + "type": "number", + "description": "The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe.", + "default": 2.0 + }, + "longitudinal_distance_min_threshold": { + "type": "number", + "description": "The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe.", + "default": 3.0 + }, + "longitudinal_velocity_delta_time": { + "type": "number", + "description": "The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance)", + "default": 0.0 + } + }, + "required": [ + "target_type", + "enable", + "check_current_lane", + "check_shift_side_lane", + "check_other_side_lane", + "check_unavoidable_object", + "check_other_object", + "check_all_predicted_path", + "safety_check_backward_distance", + "hysteresis_factor_expand_rate", + "hysteresis_factor_safe_count", + "min_velocity", + "max_velocity", + "time_resolution", + "time_horizon_for_front_object", + "time_horizon_for_rear_object", + "delay_until_departure", + "extended_polygon_policy", + "expected_front_deceleration", + "expected_rear_deceleration", + "rear_vehicle_reaction_time", + "rear_vehicle_safety_time_margin", + "lateral_distance_max_threshold", + "longitudinal_distance_min_threshold", + "longitudinal_velocity_delta_time" + ], + "additionalProperties": false + }, + "avoidance": { + "type": "object", + "properties": { + "lateral": { + "type": "object", + "properties": { + "th_avoid_execution": { + "type": "number", + "description": "The lateral distance deviation threshold between the current path and suggested avoidance point to execute avoidance.", + "default": 0.09 + }, + "th_small_shift_length": { + "type": "number", + "description": "The shift lines whose lateral offset is less than this will be applied with other ones.", + "default": 0.101 + }, + "soft_drivable_bound_margin": { + "type": "number", + "description": "Keep distance to drivable bound.", + "default": 0.3 + }, + "hard_drivable_bound_margin": { + "type": "number", + "description": "Keep distance to drivable bound.", + "default": 0.3 + }, + "max_right_shift_length": { + "type": "number", + "description": "Maximum shift length for right direction", + "default": 5.0 + }, + "max_left_shift_length": { + "type": "number", + "description": "Maximum shift length for left direction.", + "default": 5.0 + }, + "max_deviation_from_lane": { + "type": "number", + "description": "Use in validation phase to check if the avoidance path is in drivable area.", + "default": 0.2 + }, + "ratio_for_return_shift_approval": { + "type": "number", + "description": "This parameter is added to allow waiting for the return of shift approval until the occlusion behind the avoid target is clear.", + "default": 0.5, + "minimum": 0.0, + "maximum": 1.0 + } + }, + "required": [ + "th_avoid_execution", + "th_small_shift_length", + "soft_drivable_bound_margin", + "hard_drivable_bound_margin", + "max_deviation_from_lane", + "ratio_for_return_shift_approval" + ], + "additionalProperties": false + }, + "longitudinal": { + "type": "object", + "properties": { + "min_prepare_time": { + "type": "number", + "description": "Avoidance shift starts from point ahead of this time x ego speed at least.", + "default": 1.0 + }, + "max_prepare_time": { + "type": "number", + "description": "Avoidance shift starts from point ahead of this time x ego speed if possible.", + "default": 2.0 + }, + "min_prepare_distance": { + "type": "number", + "description": "Minimum prepare distance.", + "default": 1.0 + }, + "min_slow_down_speed": { + "type": "number", + "description": "Minimum slow speed for avoidance prepare section.", + "default": 1.38 + }, + "buf_slow_down_speed": { + "type": "number", + "description": "Buffer for controller tracking error. Basically, vehicle always cannot follow velocity profile precisely. Therefore, the module inserts lower speed than target speed that satisfies conditions to avoid object within accel/jerk constraints so that the avoidance path always can be output even if the current speed is a little bit higher than target speed.", + "default": 0.56 + }, + "nominal_avoidance_speed": { + "type": "number", + "description": "Nominal avoidance speed.", + "default": 8.33 + } + }, + "required": [ + "min_prepare_time", + "max_prepare_time", + "min_prepare_distance", + "min_slow_down_speed", + "buf_slow_down_speed", + "nominal_avoidance_speed" + ], + "additionalProperties": false + }, + "return_dead_line": { + "type": "object", + "properties": { + "goal": { + "type": "object", + "properties": { + "enable": { + "type": "boolean", + "description": "Insert stop point in order to return original lane before reaching goal.", + "default": "true" + }, + "buffer": { + "type": "number", + "description": "Buffer distance to return original lane before reaching goal.", + "default": 3.0 + } + }, + "required": ["enable", "buffer"], + "additionalProperties": false + }, + "traffic_light": { + "type": "object", + "properties": { + "enable": { + "type": "boolean", + "description": "Insert stop point in order to return original lane before reaching traffic light.", + "default": "true" + }, + "buffer": { + "type": "number", + "description": "Buffer distance to return original lane before reaching traffic light.", + "default": 3.0 + } + }, + "required": ["enable", "buffer"], + "additionalProperties": false + } + }, + "required": ["goal", "traffic_light"], + "additionalProperties": false + } + }, + "required": ["lateral", "longitudinal", "return_dead_line"], + "additionalProperties": false + }, + "stop": { + "type": "object", + "properties": { + "max_distance": { + "type": "number", + "description": "Maximum stop distance in the situation where avoidance maneuver is not approved or in yield maneuver.", + "default": 20.0 + }, + "stop_buffer": { + "type": "number", + "description": "Buffer distance in the situation where avoidance maneuver is not approved or in yield maneuver.", + "default": 1.0 + } + }, + "required": ["max_distance", "stop_buffer"], + "additionalProperties": false + }, + "yield": { + "type": "object", + "properties": { + "enable": { + "type": "boolean", + "description": "Flag to enable yield maneuver.", + "default": "true" + }, + "enable_during_shifting": { + "type": "boolean", + "description": "Flag to enable yield maneuver during shifting.", + "default": "false" + } + }, + "required": ["enable", "enable_during_shifting"], + "additionalProperties": false + }, + "cancel": { + "type": "object", + "properties": { + "enable": { + "type": "boolean", + "description": "Flag to enable cancel maneuver.", + "default": "true" + } + }, + "required": ["enable"], + "additionalProperties": false + }, + "policy": { + "type": "object", + "properties": { + "make_approval_request": { + "type": "string", + "enum": ["per_shift_line", "per_avoidance_maneuver"], + "description": "policy for rtc request. select `per_shift_line` or `per_avoidance_maneuver`. `per_shift_line`: request approval for each shift line. `per_avoidance_maneuver`: request approval for avoidance maneuver (avoid + return).", + "default": "per_shift_line" + }, + "deceleration": { + "type": "string", + "enum": ["reliable", "best_effort"], + "description": "policy for vehicle slow down behavior. select `best_effort` or `reliable`. `best_effort`: slow down deceleration & jerk are limited by constraints but there is a possibility that the vehicle can't stop in front of the vehicle. `reliable`: insert stop or slow down point with ignoring decel/jerk constraints. make it possible to increase chance to avoid but uncomfortable deceleration maybe happen.", + "default": "best_effort" + }, + "lateral_margin": { + "type": "string", + "enum": ["reliable", "best_effort"], + "description": "policy for voidance lateral margin. select `best_effort` or `reliable`. `best_effort`: output avoidance path with shorten lateral margin when there is no enough longitudinal margin to avoid. `reliable`: module output avoidance path with safe (rtc cooperate) state only when the vehicle can avoid with expected lateral margin.", + "default": "best_effort" + }, + "use_shorten_margin_immediately": { + "type": "boolean", + "description": "if true, module doesn't wait deceleration and outputs avoidance path by best effort margin.", + "default": "true" + } + }, + "required": ["make_approval_request"], + "additionalProperties": false + }, + "constraints": { + "type": "object", + "properties": { + "lateral": { + "type": "object", + "properties": { + "velocity": { + "type": "array", + "description": "Velocity array to decide current lateral accel/jerk limit.", + "default": [1.0, 1.38, 11.1] + }, + "max_accel_values": { + "type": "array", + "description": "Avoidance path gets sharp up to this accel limit when there is not enough distance from ego.", + "default": [0.5, 0.5, 0.5] + }, + "min_jerk_values": { + "type": "array", + "description": "Avoidance path is generated with this jerk when there is enough distance from ego.", + "default": [0.2, 0.2, 0.2] + }, + "max_jerk_values": { + "type": "array", + "description": "Avoidance path gets sharp up to this jerk limit when there is not enough distance from ego.", + "default": [1.0, 1.0, 1.0] + } + }, + "required": ["velocity", "max_accel_values", "min_jerk_values", "max_jerk_values"], + "additionalProperties": false + }, + "longitudinal": { + "type": "object", + "properties": { + "nominal_deceleration": { + "type": "number", + "description": "Nominal deceleration limit.", + "default": -1.0 + }, + "nominal_jerk": { + "type": "number", + "description": "Nominal jerk limit.", + "default": 0.5 + }, + "max_deceleration": { + "type": "number", + "description": "Max deceleration limit.", + "default": -1.5 + }, + "max_jerk": { + "type": "number", + "description": "Max jerk limit.", + "default": 1.0 + }, + "max_acceleration": { + "type": "number", + "description": "Maximum acceleration during avoidance.", + "default": 0.5 + }, + "min_velocity_to_limit_max_acceleration": { + "type": "number", + "description": "If the ego speed is faster than this param, the module applies acceleration limit `max_acceleration`.", + "default": 2.78 + } + }, + "required": [ + "nominal_deceleration", + "nominal_jerk", + "max_deceleration", + "max_jerk", + "max_acceleration", + "min_velocity_to_limit_max_acceleration" + ], + "additionalProperties": false + } + }, + "required": ["lateral", "longitudinal"], + "additionalProperties": false + }, + "shift_line_pipeline": { + "type": "object", + "properties": { + "trim": { + "type": "object", + "properties": { + "quantize_size": { + "type": "number", + "description": "Lateral shift length quantize size.", + "default": 0.1 + }, + "th_similar_grad_1": { + "type": "number", + "description": "Lateral shift length threshold to merge similar gradient shift lines.", + "default": 0.1 + }, + "th_similar_grad_2": { + "type": "number", + "description": "Lateral shift length threshold to merge similar gradient shift lines.", + "default": 0.2 + }, + "th_similar_grad_3": { + "type": "number", + "description": "Lateral shift length threshold to merge similar gradient shift lines.", + "default": 0.5 + } + }, + "required": [ + "quantize_size", + "th_similar_grad_1", + "th_similar_grad_2", + "th_similar_grad_3" + ], + "additionalProperties": false + } + }, + "required": ["trim"], + "additionalProperties": false + }, + "debug": { + "type": "object", + "properties": { + "marker": { + "type": "boolean", + "description": "Publish debug marker.", + "default": "false" + }, + "console": { + "type": "boolean", + "description": "Output debug info on console.", + "default": "false" + } + }, + "required": ["marker", "console"], + "additionalProperties": false + } + }, + "required": [ + "resample_interval_for_planning", + "resample_interval_for_output", + "enable_bound_clipping", + "use_adjacent_lane", + "use_opposite_lane", + "use_hatched_road_markings", + "use_intersection_areas", + "use_freespace_areas", + "target_object", + "target_filtering", + "safety_check", + "avoidance", + "stop", + "yield", + "cancel", + "policy", + "constraints", + "shift_line_pipeline", + "debug" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "properties": { + "ros__parameters": { + "type": "object", + "properties": { + "avoidance": { + "$ref": "#/definitions/behavior_path_avoidance_module" + } + }, + "required": ["avoidance"], + "additionalProperties": false + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} From 682a814961e100c2c49a1be3b8995f366c038276 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 12 Apr 2024 15:36:25 +0900 Subject: [PATCH 54/57] refactor(avoidance): unify redundant parameters (#6798) * refactor(avoidance): unify redundant parameters Signed-off-by: satoshi-ota * refactor(avoidance): remove unused parameters Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/avoidance.param.yaml | 10 +--- .../data_structs.hpp | 13 ++--- .../behavior_path_avoidance_module/helper.hpp | 11 ++-- .../parameter_helper.hpp | 4 +- .../schema/avoidance.schema.json | 54 +++++-------------- .../src/manager.cpp | 5 +- 6 files changed, 29 insertions(+), 68 deletions(-) diff --git a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml index 92f533bc63872..5d6044df64b2f 100644 --- a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml +++ b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml @@ -28,7 +28,6 @@ hard_margin_for_parked_vehicle: 0.7 # [m] max_expand_ratio: 0.0 # [-] FOR DEVELOPER envelope_buffer_margin: 0.5 # [m] FOR DEVELOPER - use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance. truck: th_moving_speed: 1.0 th_moving_time: 2.0 @@ -39,7 +38,6 @@ hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - use_conservative_buffer_longitudinal: true bus: th_moving_speed: 1.0 th_moving_time: 2.0 @@ -50,7 +48,6 @@ hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - use_conservative_buffer_longitudinal: true trailer: th_moving_speed: 1.0 th_moving_time: 2.0 @@ -61,7 +58,6 @@ hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - use_conservative_buffer_longitudinal: true unknown: th_moving_speed: 0.28 th_moving_time: 1.0 @@ -72,7 +68,6 @@ hard_margin_for_parked_vehicle: -0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 - use_conservative_buffer_longitudinal: true bicycle: th_moving_speed: 0.28 th_moving_time: 1.0 @@ -83,7 +78,6 @@ hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - use_conservative_buffer_longitudinal: true motorcycle: th_moving_speed: 1.0 th_moving_time: 1.0 @@ -94,7 +88,6 @@ hard_margin_for_parked_vehicle: 0.3 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - use_conservative_buffer_longitudinal: true pedestrian: th_moving_speed: 0.28 th_moving_time: 1.0 @@ -105,7 +98,6 @@ hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - use_conservative_buffer_longitudinal: true lower_distance_for_polygon_expansion: 30.0 # [m] FOR DEVELOPER upper_distance_for_polygon_expansion: 100.0 # [m] FOR DEVELOPER @@ -222,6 +214,8 @@ min_slow_down_speed: 1.38 # [m/s] buf_slow_down_speed: 0.56 # [m/s] FOR DEVELOPER nominal_avoidance_speed: 8.33 # [m/s] FOR DEVELOPER + consider_front_overhang: true # [-] + consider_rear_overhang: true # [-] # return dead line return_dead_line: goal: diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp index bc66598d3ee90..e74b546f31fc4 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp @@ -76,8 +76,6 @@ struct ObjectParameter double lateral_hard_margin_for_parked_vehicle{1.0}; double longitudinal_margin{0.0}; - - bool use_conservative_buffer_longitudinal{true}; }; struct AvoidanceParameters @@ -191,14 +189,6 @@ struct AvoidanceParameters double time_threshold_for_ambiguous_vehicle{0.0}; double distance_threshold_for_ambiguous_vehicle{0.0}; - // when complete avoidance motion, there is a distance margin with the object - // for longitudinal direction - double longitudinal_collision_margin_min_distance{0.0}; - - // when complete avoidance motion, there is a time margin with the object - // for longitudinal direction - double longitudinal_collision_margin_time{0.0}; - // parameters for safety check area bool enable_safety_check{false}; bool check_current_lane{false}; @@ -219,6 +209,9 @@ struct AvoidanceParameters size_t hysteresis_factor_safe_count; double hysteresis_factor_expand_rate{0.0}; + bool consider_front_overhang{true}; + bool consider_rear_overhang{true}; + // maximum stop distance double stop_max_distance{0.0}; diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp index 2e481e7c98e44..8d95e724045ba 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp @@ -148,16 +148,19 @@ class AvoidanceHelper { const auto object_type = utils::getHighestProbLabel(object.object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); - const auto & additional_buffer_longitudinal = - object_parameter.use_conservative_buffer_longitudinal ? data_->parameters.base_link2front - : 0.0; - return object_parameter.longitudinal_margin + additional_buffer_longitudinal; + if (!parameters_->consider_front_overhang) { + return object_parameter.longitudinal_margin; + } + return object_parameter.longitudinal_margin + data_->parameters.base_link2front; } double getRearConstantDistance(const ObjectData & object) const { const auto object_type = utils::getHighestProbLabel(object.object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); + if (!parameters_->consider_rear_overhang) { + return object_parameter.longitudinal_margin; + } return object_parameter.longitudinal_margin + data_->parameters.base_link2rear + object.length; } diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp index 5b8963c7ca22d..6dbf52c0425fb 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp @@ -70,8 +70,6 @@ AvoidanceParameters getParameter(rclcpp::Node * node) param.lateral_hard_margin_for_parked_vehicle = getOrDeclareParameter(*node, ns + "lateral_margin.hard_margin_for_parked_vehicle"); param.longitudinal_margin = getOrDeclareParameter(*node, ns + "longitudinal_margin"); - param.use_conservative_buffer_longitudinal = - getOrDeclareParameter(*node, ns + "use_conservative_buffer_longitudinal"); return param; }; @@ -270,6 +268,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node) p.buf_slow_down_speed = getOrDeclareParameter(*node, ns + "buf_slow_down_speed"); p.nominal_avoidance_speed = getOrDeclareParameter(*node, ns + "nominal_avoidance_speed"); + p.consider_front_overhang = getOrDeclareParameter(*node, ns + "consider_front_overhang"); + p.consider_rear_overhang = getOrDeclareParameter(*node, ns + "consider_rear_overhang"); } // avoidance maneuver (return shift dead line) diff --git a/planning/behavior_path_avoidance_module/schema/avoidance.schema.json b/planning/behavior_path_avoidance_module/schema/avoidance.schema.json index cd3e29b8ec0b8..79882beb805f8 100644 --- a/planning/behavior_path_avoidance_module/schema/avoidance.schema.json +++ b/planning/behavior_path_avoidance_module/schema/avoidance.schema.json @@ -104,11 +104,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -171,11 +166,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -238,11 +228,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -305,11 +290,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -372,11 +352,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -439,11 +414,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -506,11 +476,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -573,11 +538,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -1150,6 +1110,16 @@ "type": "number", "description": "Nominal avoidance speed.", "default": 8.33 + }, + "consider_front_overhang": { + "type": "boolean", + "description": "Flag to consider vehicle front overhang in shift line generation logic.", + "default": true + }, + "consider_rear_overhang": { + "type": "boolean", + "description": "Flag to consider vehicle rear overhang in shift line generation logic.", + "default": true } }, "required": [ @@ -1158,7 +1128,9 @@ "min_prepare_distance", "min_slow_down_speed", "buf_slow_down_speed", - "nominal_avoidance_speed" + "nominal_avoidance_speed", + "consider_front_overhang", + "consider_rear_overhang" ], "additionalProperties": false }, diff --git a/planning/behavior_path_avoidance_module/src/manager.cpp b/planning/behavior_path_avoidance_module/src/manager.cpp index 3261214d1b9b6..e3391f251e55f 100644 --- a/planning/behavior_path_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_module/src/manager.cpp @@ -59,9 +59,6 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "longitudinal_margin", config.longitudinal_margin); - updateParam( - parameters, ns + "use_conservative_buffer_longitudinal", - config.use_conservative_buffer_longitudinal); }; { @@ -170,6 +167,8 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "min_prepare_distance", p->min_prepare_distance); updateParam(parameters, ns + "min_slow_down_speed", p->min_slow_down_speed); updateParam(parameters, ns + "buf_slow_down_speed", p->buf_slow_down_speed); + updateParam(parameters, ns + "consider_front_overhang", p->consider_front_overhang); + updateParam(parameters, ns + "consider_rear_overhang", p->consider_rear_overhang); } { From fd032e86926cbd191f8fdca3b154f46cadad3fd8 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 12 Apr 2024 16:59:34 +0900 Subject: [PATCH 55/57] refactor(static_centerline_generator): change the package name from static_centerline_optimizer (#6795) static_centerline_optimizer -> static_centerline_generator Signed-off-by: Takayuki Murooka --- .github/CODEOWNERS | 2 +- ...load_local_cartesian_utm_from_yaml.test.py | 2 +- .../test_node_load_local_from_yaml.test.py | 2 +- .../test_node_load_mgrs_from_yaml.test.py | 2 +- ...load_transverse_mercator_from_yaml.test.py | 2 +- planning/.pages | 2 +- .../obstacle_avoidance_planner/node.hpp | 4 +- .../path_smoother/elastic_band_smoother.hpp | 2 +- .../include/path_sampler/node.hpp | 2 +- .../CMakeLists.txt | 12 ++-- .../README.md | 6 +- .../config/common.param.yaml | 0 .../config/nearest_search.param.yaml | 0 .../static_centerline_generator.param.yaml} | 0 .../config/vehicle_info.param.yaml | 0 .../bag_ego_trajectory_based_centerline.hpp | 12 ++-- ...timization_trajectory_based_centerline.hpp | 12 ++-- .../static_centerline_generator_node.hpp} | 30 +++++----- .../type_alias.hpp | 10 ++-- .../static_centerline_generator}/utils.hpp | 12 ++-- .../launch/run_planning_server.launch.xml | 4 +- .../static_centerline_generator.launch.xml} | 6 +- .../media/rviz.png | Bin .../media/unsafe_footprints.png | Bin .../msg/PointsWithLaneId.msg | 0 .../package.xml | 4 +- .../rviz/static_centerline_generator.rviz} | 8 +-- .../scripts/app.py | 14 ++--- .../scripts/centerline_updater_helper.py | 2 +- .../bag_ego_trajectory_based_centerline.sh | 3 + ...ptimization_trajectory_based_centerline.sh | 2 +- .../bag_ego_trajectory_based_centerline.cpp | 8 +-- ...timization_trajectory_based_centerline.cpp | 10 ++-- .../src/main.cpp | 4 +- .../src/static_centerline_generator_node.cpp} | 56 +++++++++--------- .../src/utils.cpp | 6 +- .../srv/LoadMap.srv | 0 .../srv/PlanPath.srv | 2 +- .../srv/PlanRoute.srv | 0 .../test/data/bag_ego_trajectory.db3 | Bin .../test/data/lanelet2_map.osm | 0 .../test_static_centerline_generator.test.py} | 20 +++---- .../bag_ego_trajectory_based_centerline.sh | 3 - 43 files changed, 133 insertions(+), 133 deletions(-) rename planning/{static_centerline_optimizer => static_centerline_generator}/CMakeLists.txt (80%) rename planning/{static_centerline_optimizer => static_centerline_generator}/README.md (93%) rename planning/{static_centerline_optimizer => static_centerline_generator}/config/common.param.yaml (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/config/nearest_search.param.yaml (100%) rename planning/{static_centerline_optimizer/config/static_centerline_optimizer.param.yaml => static_centerline_generator/config/static_centerline_generator.param.yaml} (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/config/vehicle_info.param.yaml (100%) rename planning/{static_centerline_optimizer/include/static_centerline_optimizer => static_centerline_generator/include/static_centerline_generator}/centerline_source/bag_ego_trajectory_based_centerline.hpp (71%) rename planning/{static_centerline_optimizer/include/static_centerline_optimizer => static_centerline_generator/include/static_centerline_generator}/centerline_source/optimization_trajectory_based_centerline.hpp (81%) rename planning/{static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp => static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp} (81%) rename planning/{static_centerline_optimizer/include/static_centerline_optimizer => static_centerline_generator/include/static_centerline_generator}/type_alias.hpp (87%) rename planning/{static_centerline_optimizer/include/static_centerline_optimizer => static_centerline_generator/include/static_centerline_generator}/utils.hpp (86%) rename planning/{static_centerline_optimizer => static_centerline_generator}/launch/run_planning_server.launch.xml (54%) rename planning/{static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml => static_centerline_generator/launch/static_centerline_generator.launch.xml} (93%) rename planning/{static_centerline_optimizer => static_centerline_generator}/media/rviz.png (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/media/unsafe_footprints.png (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/msg/PointsWithLaneId.msg (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/package.xml (94%) rename planning/{static_centerline_optimizer/rviz/static_centerline_optimizer.rviz => static_centerline_generator/rviz/static_centerline_generator.rviz} (98%) rename planning/{static_centerline_optimizer => static_centerline_generator}/scripts/app.py (92%) rename planning/{static_centerline_optimizer => static_centerline_generator}/scripts/centerline_updater_helper.py (99%) create mode 100755 planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh rename planning/{static_centerline_optimizer => static_centerline_generator}/scripts/tmp/optimization_trajectory_based_centerline.sh (57%) rename planning/{static_centerline_optimizer => static_centerline_generator}/src/centerline_source/bag_ego_trajectory_based_centerline.cpp (93%) rename planning/{static_centerline_optimizer => static_centerline_generator}/src/centerline_source/optimization_trajectory_based_centerline.cpp (96%) rename planning/{static_centerline_optimizer => static_centerline_generator}/src/main.cpp (86%) rename planning/{static_centerline_optimizer/src/static_centerline_optimizer_node.cpp => static_centerline_generator/src/static_centerline_generator_node.cpp} (93%) rename planning/{static_centerline_optimizer => static_centerline_generator}/src/utils.cpp (98%) rename planning/{static_centerline_optimizer => static_centerline_generator}/srv/LoadMap.srv (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/srv/PlanPath.srv (55%) rename planning/{static_centerline_optimizer => static_centerline_generator}/srv/PlanRoute.srv (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/test/data/bag_ego_trajectory.db3 (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/test/data/lanelet2_map.osm (100%) rename planning/{static_centerline_optimizer/test/test_static_centerline_optimizer.test.py => static_centerline_generator/test/test_static_centerline_generator.test.py} (84%) delete mode 100755 planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 256b617116432..a6cdc58f03e94 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -205,7 +205,7 @@ planning/sampling_based_planner/frenet_planner/** maxime.clement@tier4.jp planning/sampling_based_planner/path_sampler/** maxime.clement@tier4.jp planning/sampling_based_planner/sampler_common/** maxime.clement@tier4.jp planning/scenario_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -planning/static_centerline_optimizer/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp +planning/static_centerline_generator/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp planning/surround_obstacle_checker/** satoshi.ota@tier4.jp sensing/gnss_poser/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/image_diagnostics/** dai.nguyen@tier4.jp diff --git a/map/map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py index ec13df010c8c3..b8540550ce9da 100644 --- a/map/map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py +++ b/map/map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py @@ -61,7 +61,7 @@ def generate_test_description(): LaunchDescription( [ map_projection_loader_node, - # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + # Start test after 1s - gives time for the static_centerline_generator to finish initialization launch.actions.TimerAction( period=1.0, actions=[launch_testing.actions.ReadyToTest()] ), diff --git a/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py index ccec68486b79c..c7697038cc253 100644 --- a/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py +++ b/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py @@ -61,7 +61,7 @@ def generate_test_description(): LaunchDescription( [ map_projection_loader_node, - # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + # Start test after 1s - gives time for the static_centerline_generator to finish initialization launch.actions.TimerAction( period=1.0, actions=[launch_testing.actions.ReadyToTest()] ), diff --git a/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py index 200504d0ea18f..f75beddc6827c 100644 --- a/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py +++ b/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py @@ -61,7 +61,7 @@ def generate_test_description(): LaunchDescription( [ map_projection_loader_node, - # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + # Start test after 1s - gives time for the static_centerline_generator to finish initialization launch.actions.TimerAction( period=1.0, actions=[launch_testing.actions.ReadyToTest()] ), diff --git a/map/map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py index 7883ae6aa3c99..765f3cde04679 100644 --- a/map/map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py +++ b/map/map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py @@ -61,7 +61,7 @@ def generate_test_description(): LaunchDescription( [ map_projection_loader_node, - # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + # Start test after 1s - gives time for the static_centerline_generator to finish initialization launch.actions.TimerAction( period=1.0, actions=[launch_testing.actions.ReadyToTest()] ), diff --git a/planning/.pages b/planning/.pages index 1b5608f7ded57..942a5a0b32158 100644 --- a/planning/.pages +++ b/planning/.pages @@ -67,7 +67,7 @@ nav: - 'About Motion Velocity Smoother': planning/motion_velocity_smoother - 'About Motion Velocity Smoother (Japanese)': planning/motion_velocity_smoother/README.ja - 'Scenario Selector': planning/scenario_selector - - 'Static Centerline Optimizer': planning/static_centerline_optimizer + - 'Static Centerline Generator': planning/static_centerline_generator - 'API and Library': - 'Costmap Generator': planning/costmap_generator - 'External Velocity Limit Selector': planning/external_velocity_limit_selector diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp index 2dbefffe67738..3677e6c5fb075 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp @@ -39,12 +39,12 @@ class ObstacleAvoidancePlanner : public rclcpp::Node public: explicit ObstacleAvoidancePlanner(const rclcpp::NodeOptions & node_options); - // NOTE: This is for the static_centerline_optimizer package which utilizes the following + // NOTE: This is for the static_centerline_generator package which utilizes the following // instance. std::shared_ptr getMPTOptimizer() const { return mpt_optimizer_ptr_; } // private: -protected: // for the static_centerline_optimizer package +protected: // for the static_centerline_generator package // TODO(murooka) move this node to common class DrivingDirectionChecker { diff --git a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp index eb2d651cc967d..e0bdb326adb33 100644 --- a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp +++ b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp @@ -38,7 +38,7 @@ class ElasticBandSmoother : public rclcpp::Node public: explicit ElasticBandSmoother(const rclcpp::NodeOptions & node_options); - // NOTE: This is for the static_centerline_optimizer package which utilizes the following + // NOTE: This is for the static_centerline_generator package which utilizes the following // instance. std::shared_ptr getElasticBandSmoother() const { return eb_path_smoother_ptr_; } diff --git a/planning/sampling_based_planner/path_sampler/include/path_sampler/node.hpp b/planning/sampling_based_planner/path_sampler/include/path_sampler/node.hpp index a9002c8cf8a9f..50464f12114b0 100644 --- a/planning/sampling_based_planner/path_sampler/include/path_sampler/node.hpp +++ b/planning/sampling_based_planner/path_sampler/include/path_sampler/node.hpp @@ -37,7 +37,7 @@ class PathSampler : public rclcpp::Node public: explicit PathSampler(const rclcpp::NodeOptions & node_options); -protected: // for the static_centerline_optimizer package +protected: // for the static_centerline_generator package // argument variables vehicle_info_util::VehicleInfo vehicle_info_{}; mutable DebugData debug_data_{}; diff --git a/planning/static_centerline_optimizer/CMakeLists.txt b/planning/static_centerline_generator/CMakeLists.txt similarity index 80% rename from planning/static_centerline_optimizer/CMakeLists.txt rename to planning/static_centerline_generator/CMakeLists.txt index cc33f2234a50c..991d12097cc08 100644 --- a/planning/static_centerline_optimizer/CMakeLists.txt +++ b/planning/static_centerline_generator/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(static_centerline_optimizer) +project(static_centerline_generator) find_package(autoware_cmake REQUIRED) @@ -9,7 +9,7 @@ find_package(rosidl_default_generators REQUIRED) find_package(std_msgs REQUIRED) rosidl_generate_interfaces( - static_centerline_optimizer + static_centerline_generator "srv/LoadMap.srv" "srv/PlanRoute.srv" "srv/PlanPath.srv" @@ -21,7 +21,7 @@ autoware_package() ament_auto_add_executable(main src/main.cpp - src/static_centerline_optimizer_node.cpp + src/static_centerline_generator_node.cpp src/centerline_source/optimization_trajectory_based_centerline.cpp src/centerline_source/bag_ego_trajectory_based_centerline.cpp src/utils.cpp @@ -29,10 +29,10 @@ ament_auto_add_executable(main if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0) rosidl_target_interfaces(main - static_centerline_optimizer "rosidl_typesupport_cpp") + static_centerline_generator "rosidl_typesupport_cpp") else() rosidl_get_typesupport_target( - cpp_typesupport_target static_centerline_optimizer "rosidl_typesupport_cpp") + cpp_typesupport_target static_centerline_generator "rosidl_typesupport_cpp") target_link_libraries(main "${cpp_typesupport_target}") endif() @@ -45,7 +45,7 @@ ament_auto_package( if(BUILD_TESTING) add_launch_test( - test/test_static_centerline_optimizer.test.py + test/test_static_centerline_generator.test.py TIMEOUT "30" ) install(DIRECTORY diff --git a/planning/static_centerline_optimizer/README.md b/planning/static_centerline_generator/README.md similarity index 93% rename from planning/static_centerline_optimizer/README.md rename to planning/static_centerline_generator/README.md index fd5a58ef816df..00572b754645c 100644 --- a/planning/static_centerline_optimizer/README.md +++ b/planning/static_centerline_generator/README.md @@ -1,4 +1,4 @@ -# Static Centerline Optimizer +# Static Centerline Generator ## Purpose @@ -34,7 +34,7 @@ We can run with the following command by designating `` ```sh -ros2 launch static_centerline_optimizer run_planning_server.launch.xml vehicle_model:= +ros2 launch static_centerline_generator run_planning_server.launch.xml vehicle_model:= ``` FYI, port ID of the http server is 4010 by default. @@ -50,7 +50,7 @@ The optimized centerline can be generated from the command line interface by des - `` ```sh -ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml run_backgrond:=false lanelet2_input_file_path:= lanelet2_output_file_path:= start_lanelet_id:= end_lanelet_id:= vehicle_model:= +ros2 launch static_centerline_generator static_centerline_generator.launch.xml run_backgrond:=false lanelet2_input_file_path:= lanelet2_output_file_path:= start_lanelet_id:= end_lanelet_id:= vehicle_model:= ``` The default output map path containing the optimized centerline locates `/tmp/lanelet2_map.osm`. diff --git a/planning/static_centerline_optimizer/config/common.param.yaml b/planning/static_centerline_generator/config/common.param.yaml similarity index 100% rename from planning/static_centerline_optimizer/config/common.param.yaml rename to planning/static_centerline_generator/config/common.param.yaml diff --git a/planning/static_centerline_optimizer/config/nearest_search.param.yaml b/planning/static_centerline_generator/config/nearest_search.param.yaml similarity index 100% rename from planning/static_centerline_optimizer/config/nearest_search.param.yaml rename to planning/static_centerline_generator/config/nearest_search.param.yaml diff --git a/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml b/planning/static_centerline_generator/config/static_centerline_generator.param.yaml similarity index 100% rename from planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml rename to planning/static_centerline_generator/config/static_centerline_generator.param.yaml diff --git a/planning/static_centerline_optimizer/config/vehicle_info.param.yaml b/planning/static_centerline_generator/config/vehicle_info.param.yaml similarity index 100% rename from planning/static_centerline_optimizer/config/vehicle_info.param.yaml rename to planning/static_centerline_generator/config/vehicle_info.param.yaml diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp b/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp similarity index 71% rename from planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp rename to planning/static_centerline_generator/include/static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp index b29f222b068cc..30b2e55c36bba 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp +++ b/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ -#define STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ +#ifndef STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ +#define STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ #include "rclcpp/rclcpp.hpp" -#include "static_centerline_optimizer/type_alias.hpp" +#include "static_centerline_generator/type_alias.hpp" #include -namespace static_centerline_optimizer +namespace static_centerline_generator { std::vector generate_centerline_with_bag(rclcpp::Node & node); -} // namespace static_centerline_optimizer -#endif // STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ +} // namespace static_centerline_generator +#endif // STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp b/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp similarity index 81% rename from planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp rename to planning/static_centerline_generator/include/static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp index 8c7c1e69e9ce6..7e7cdea31e9f1 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp +++ b/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT -#define STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT +#ifndef STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT +#define STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT #include "rclcpp/rclcpp.hpp" -#include "static_centerline_optimizer/type_alias.hpp" +#include "static_centerline_generator/type_alias.hpp" #include -namespace static_centerline_optimizer +namespace static_centerline_generator { class OptimizationTrajectoryBasedCenterline { @@ -37,7 +37,7 @@ class OptimizationTrajectoryBasedCenterline rclcpp::Publisher::SharedPtr pub_raw_path_with_lane_id_{nullptr}; rclcpp::Publisher::SharedPtr pub_raw_path_{nullptr}; }; -} // namespace static_centerline_optimizer +} // namespace static_centerline_generator // clang-format off -#endif // STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT +#endif // STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT // clang-format on diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp b/planning/static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp similarity index 81% rename from planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp rename to planning/static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp index 5d9530a469012..c1d92c06a8e05 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp +++ b/planning/static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef STATIC_CENTERLINE_OPTIMIZER__STATIC_CENTERLINE_OPTIMIZER_NODE_HPP_ -#define STATIC_CENTERLINE_OPTIMIZER__STATIC_CENTERLINE_OPTIMIZER_NODE_HPP_ +#ifndef STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_ +#define STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_ #include "rclcpp/rclcpp.hpp" -#include "static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp" -#include "static_centerline_optimizer/srv/load_map.hpp" -#include "static_centerline_optimizer/srv/plan_path.hpp" -#include "static_centerline_optimizer/srv/plan_route.hpp" -#include "static_centerline_optimizer/type_alias.hpp" +#include "static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp" +#include "static_centerline_generator/srv/load_map.hpp" +#include "static_centerline_generator/srv/plan_path.hpp" +#include "static_centerline_generator/srv/plan_route.hpp" +#include "static_centerline_generator/type_alias.hpp" #include "vehicle_info_util/vehicle_info_util.hpp" #include @@ -34,11 +34,11 @@ #include #include -namespace static_centerline_optimizer +namespace static_centerline_generator { -using static_centerline_optimizer::srv::LoadMap; -using static_centerline_optimizer::srv::PlanPath; -using static_centerline_optimizer::srv::PlanRoute; +using static_centerline_generator::srv::LoadMap; +using static_centerline_generator::srv::PlanPath; +using static_centerline_generator::srv::PlanRoute; struct CenterlineWithRoute { @@ -46,10 +46,10 @@ struct CenterlineWithRoute std::vector route_lane_ids{}; }; -class StaticCenterlineOptimizerNode : public rclcpp::Node +class StaticCenterlineGeneratorNode : public rclcpp::Node { public: - explicit StaticCenterlineOptimizerNode(const rclcpp::NodeOptions & node_options); + explicit StaticCenterlineGeneratorNode(const rclcpp::NodeOptions & node_options); void run(); private: @@ -115,5 +115,5 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node // vehicle info vehicle_info_util::VehicleInfo vehicle_info_; }; -} // namespace static_centerline_optimizer -#endif // STATIC_CENTERLINE_OPTIMIZER__STATIC_CENTERLINE_OPTIMIZER_NODE_HPP_ +} // namespace static_centerline_generator +#endif // STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_ diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/type_alias.hpp b/planning/static_centerline_generator/include/static_centerline_generator/type_alias.hpp similarity index 87% rename from planning/static_centerline_optimizer/include/static_centerline_optimizer/type_alias.hpp rename to planning/static_centerline_generator/include/static_centerline_generator/type_alias.hpp index 1a700d36deaaf..2dcb9cbbd099f 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/type_alias.hpp +++ b/planning/static_centerline_generator/include/static_centerline_generator/type_alias.hpp @@ -11,8 +11,8 @@ // 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 STATIC_CENTERLINE_OPTIMIZER__TYPE_ALIAS_HPP_ -#define STATIC_CENTERLINE_OPTIMIZER__TYPE_ALIAS_HPP_ +#ifndef STATIC_CENTERLINE_GENERATOR__TYPE_ALIAS_HPP_ +#define STATIC_CENTERLINE_GENERATOR__TYPE_ALIAS_HPP_ #include "route_handler/route_handler.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" @@ -26,7 +26,7 @@ #include "autoware_planning_msgs/msg/lanelet_route.hpp" #include "visualization_msgs/msg/marker_array.hpp" -namespace static_centerline_optimizer +namespace static_centerline_generator { using autoware_auto_mapping_msgs::msg::HADMapBin; using autoware_auto_perception_msgs::msg::PredictedObjects; @@ -41,6 +41,6 @@ using tier4_autoware_utils::LinearRing2d; using tier4_autoware_utils::LineString2d; using tier4_autoware_utils::Point2d; using visualization_msgs::msg::MarkerArray; -} // namespace static_centerline_optimizer +} // namespace static_centerline_generator -#endif // STATIC_CENTERLINE_OPTIMIZER__TYPE_ALIAS_HPP_ +#endif // STATIC_CENTERLINE_GENERATOR__TYPE_ALIAS_HPP_ diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp b/planning/static_centerline_generator/include/static_centerline_generator/utils.hpp similarity index 86% rename from planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp rename to planning/static_centerline_generator/include/static_centerline_generator/utils.hpp index 04f2268aa972f..c8cf8f8b90590 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp +++ b/planning/static_centerline_generator/include/static_centerline_generator/utils.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef STATIC_CENTERLINE_OPTIMIZER__UTILS_HPP_ -#define STATIC_CENTERLINE_OPTIMIZER__UTILS_HPP_ +#ifndef STATIC_CENTERLINE_GENERATOR__UTILS_HPP_ +#define STATIC_CENTERLINE_GENERATOR__UTILS_HPP_ #include "route_handler/route_handler.hpp" -#include "static_centerline_optimizer/type_alias.hpp" +#include "static_centerline_generator/type_alias.hpp" #include @@ -24,7 +24,7 @@ #include #include -namespace static_centerline_optimizer +namespace static_centerline_generator { namespace utils { @@ -53,6 +53,6 @@ MarkerArray create_distance_text_marker( const geometry_msgs::msg::Pose & pose, const double dist, const std::array & marker_color, const rclcpp::Time & now, const size_t idx); } // namespace utils -} // namespace static_centerline_optimizer +} // namespace static_centerline_generator -#endif // STATIC_CENTERLINE_OPTIMIZER__UTILS_HPP_ +#endif // STATIC_CENTERLINE_GENERATOR__UTILS_HPP_ diff --git a/planning/static_centerline_optimizer/launch/run_planning_server.launch.xml b/planning/static_centerline_generator/launch/run_planning_server.launch.xml similarity index 54% rename from planning/static_centerline_optimizer/launch/run_planning_server.launch.xml rename to planning/static_centerline_generator/launch/run_planning_server.launch.xml index 3a8b88a021dc0..1493078317458 100644 --- a/planning/static_centerline_optimizer/launch/run_planning_server.launch.xml +++ b/planning/static_centerline_generator/launch/run_planning_server.launch.xml @@ -2,11 +2,11 @@ - + - + diff --git a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml b/planning/static_centerline_generator/launch/static_centerline_generator.launch.xml similarity index 93% rename from planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml rename to planning/static_centerline_generator/launch/static_centerline_generator.launch.xml index ed137367f3ba4..ae71b0ae6e925 100644 --- a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml +++ b/planning/static_centerline_generator/launch/static_centerline_generator.launch.xml @@ -55,7 +55,7 @@ - + @@ -79,11 +79,11 @@ - + - + diff --git a/planning/static_centerline_optimizer/media/rviz.png b/planning/static_centerline_generator/media/rviz.png similarity index 100% rename from planning/static_centerline_optimizer/media/rviz.png rename to planning/static_centerline_generator/media/rviz.png diff --git a/planning/static_centerline_optimizer/media/unsafe_footprints.png b/planning/static_centerline_generator/media/unsafe_footprints.png similarity index 100% rename from planning/static_centerline_optimizer/media/unsafe_footprints.png rename to planning/static_centerline_generator/media/unsafe_footprints.png diff --git a/planning/static_centerline_optimizer/msg/PointsWithLaneId.msg b/planning/static_centerline_generator/msg/PointsWithLaneId.msg similarity index 100% rename from planning/static_centerline_optimizer/msg/PointsWithLaneId.msg rename to planning/static_centerline_generator/msg/PointsWithLaneId.msg diff --git a/planning/static_centerline_optimizer/package.xml b/planning/static_centerline_generator/package.xml similarity index 94% rename from planning/static_centerline_optimizer/package.xml rename to planning/static_centerline_generator/package.xml index eef133581622f..6573f6e439c43 100644 --- a/planning/static_centerline_optimizer/package.xml +++ b/planning/static_centerline_generator/package.xml @@ -1,9 +1,9 @@ - static_centerline_optimizer + static_centerline_generator 0.1.0 - The static_centerline_optimizer package + The static_centerline_generator package Takayuki Murooka Kosuke Takeuchi Apache License 2.0 diff --git a/planning/static_centerline_optimizer/rviz/static_centerline_optimizer.rviz b/planning/static_centerline_generator/rviz/static_centerline_generator.rviz similarity index 98% rename from planning/static_centerline_optimizer/rviz/static_centerline_optimizer.rviz rename to planning/static_centerline_generator/rviz/static_centerline_generator.rviz index 1e7573d561ba1..62b4c9b75ec87 100644 --- a/planning/static_centerline_optimizer/rviz/static_centerline_optimizer.rviz +++ b/planning/static_centerline_generator/rviz/static_centerline_generator.rviz @@ -130,7 +130,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_optimizer/input_centerline + Value: /static_centerline_generator/input_centerline Value: true View Drivable Area: Alpha: 0.9990000128746033 @@ -179,7 +179,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_optimizer/output_centerline + Value: /static_centerline_generator/output_centerline Value: true View Footprint: Alpha: 1 @@ -222,7 +222,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_optimizer/debug/raw_centerline + Value: /static_centerline_generator/debug/raw_centerline Value: false View Drivable Area: Alpha: 0.9990000128746033 @@ -268,7 +268,7 @@ Visualization Manager: Durability Policy: Transient Local History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_optimizer/debug/unsafe_footprints + Value: /static_centerline_generator/debug/unsafe_footprints Value: true Enabled: false Name: debug diff --git a/planning/static_centerline_optimizer/scripts/app.py b/planning/static_centerline_generator/scripts/app.py similarity index 92% rename from planning/static_centerline_optimizer/scripts/app.py rename to planning/static_centerline_generator/scripts/app.py index 90610755e828a..c1cb0473da040 100755 --- a/planning/static_centerline_optimizer/scripts/app.py +++ b/planning/static_centerline_generator/scripts/app.py @@ -23,12 +23,12 @@ from flask_cors import CORS import rclpy from rclpy.node import Node -from static_centerline_optimizer.srv import LoadMap -from static_centerline_optimizer.srv import PlanPath -from static_centerline_optimizer.srv import PlanRoute +from static_centerline_generator.srv import LoadMap +from static_centerline_generator.srv import PlanPath +from static_centerline_generator.srv import PlanRoute rclpy.init() -node = Node("static_centerline_optimizer_http_server") +node = Node("static_centerline_generator_http_server") app = Flask(__name__) CORS(app) @@ -51,7 +51,7 @@ def get_map(): map_id = map_uuid # create client - cli = create_client(LoadMap, "/planning/static_centerline_optimizer/load_map") + cli = create_client(LoadMap, "/planning/static_centerline_generator/load_map") # request map loading req = LoadMap.Request(map=data["map"]) @@ -85,7 +85,7 @@ def post_planned_route(): print("map_id is not correct.") # create client - cli = create_client(PlanRoute, "/planning/static_centerline_optimizer/plan_route") + cli = create_client(PlanRoute, "/planning/static_centerline_generator/plan_route") # request route planning req = PlanRoute.Request( @@ -123,7 +123,7 @@ def post_planned_path(): print("map_id is not correct.") # create client - cli = create_client(PlanPath, "/planning/static_centerline_optimizer/plan_path") + cli = create_client(PlanPath, "/planning/static_centerline_generator/plan_path") # request path planning route_lane_ids = [eval(i) for i in request.args.getlist("route[]")] diff --git a/planning/static_centerline_optimizer/scripts/centerline_updater_helper.py b/planning/static_centerline_generator/scripts/centerline_updater_helper.py similarity index 99% rename from planning/static_centerline_optimizer/scripts/centerline_updater_helper.py rename to planning/static_centerline_generator/scripts/centerline_updater_helper.py index 00a646406f14f..fec3d21d20bec 100755 --- a/planning/static_centerline_optimizer/scripts/centerline_updater_helper.py +++ b/planning/static_centerline_generator/scripts/centerline_updater_helper.py @@ -155,7 +155,7 @@ def __init__(self): transient_local_qos = QoSProfile(depth=1, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL) self.sub_whole_centerline = self.create_subscription( Trajectory, - "/static_centerline_optimizer/output_whole_centerline", + "/static_centerline_generator/output_whole_centerline", self.onWholeCenterline, transient_local_qos, ) diff --git a/planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh b/planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh new file mode 100755 index 0000000000000..30ed667dd3732 --- /dev/null +++ b/planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +ros2 launch static_centerline_generator static_centerline_generator.launch.xml centerline_source:="bag_ego_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix static_centerline_generator --share)/test/data/bag_ego_trajectory.db3" vehicle_model:=lexus diff --git a/planning/static_centerline_optimizer/scripts/tmp/optimization_trajectory_based_centerline.sh b/planning/static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh similarity index 57% rename from planning/static_centerline_optimizer/scripts/tmp/optimization_trajectory_based_centerline.sh rename to planning/static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh index 3967c7a4ca523..809bbb46a179e 100755 --- a/planning/static_centerline_optimizer/scripts/tmp/optimization_trajectory_based_centerline.sh +++ b/planning/static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh @@ -1,3 +1,3 @@ #!/bin/bash -ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml centerline_source:="optimization_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus +ros2 launch static_centerline_generator static_centerline_generator.launch.xml centerline_source:="optimization_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus diff --git a/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp b/planning/static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp similarity index 93% rename from planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp rename to planning/static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp index 571e98cdbe1c3..4e541b1aff527 100644 --- a/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp +++ b/planning/static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp" +#include "static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp" #include "rclcpp/serialization.hpp" #include "rosbag2_cpp/reader.hpp" -#include "static_centerline_optimizer/static_centerline_optimizer_node.hpp" +#include "static_centerline_generator/static_centerline_generator_node.hpp" #include -namespace static_centerline_optimizer +namespace static_centerline_generator { std::vector generate_centerline_with_bag(rclcpp::Node & node) { @@ -79,4 +79,4 @@ std::vector generate_centerline_with_bag(rclcpp::Node & node) return centerline_traj_points; } -} // namespace static_centerline_optimizer +} // namespace static_centerline_generator diff --git a/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp b/planning/static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp similarity index 96% rename from planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp rename to planning/static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp index 20b2027f39d54..7980ae4e8d2d7 100644 --- a/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp +++ b/planning/static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp" +#include "static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp" #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" #include "obstacle_avoidance_planner/node.hpp" #include "path_smoother/elastic_band_smoother.hpp" -#include "static_centerline_optimizer/static_centerline_optimizer_node.hpp" -#include "static_centerline_optimizer/utils.hpp" +#include "static_centerline_generator/static_centerline_generator_node.hpp" +#include "static_centerline_generator/utils.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" -namespace static_centerline_optimizer +namespace static_centerline_generator { namespace { @@ -180,4 +180,4 @@ std::vector OptimizationTrajectoryBasedCenterline::optimize_tra return whole_optimized_traj_points; } -} // namespace static_centerline_optimizer +} // namespace static_centerline_generator diff --git a/planning/static_centerline_optimizer/src/main.cpp b/planning/static_centerline_generator/src/main.cpp similarity index 86% rename from planning/static_centerline_optimizer/src/main.cpp rename to planning/static_centerline_generator/src/main.cpp index 96c139fd7ff93..981cf54fc9274 100644 --- a/planning/static_centerline_optimizer/src/main.cpp +++ b/planning/static_centerline_generator/src/main.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "static_centerline_optimizer/static_centerline_optimizer_node.hpp" +#include "static_centerline_generator/static_centerline_generator_node.hpp" int main(int argc, char * argv[]) { @@ -21,7 +21,7 @@ int main(int argc, char * argv[]) // initialize node rclcpp::NodeOptions node_options; auto node = - std::make_shared(node_options); + std::make_shared(node_options); // get ros parameter const bool run_background = node->declare_parameter("run_background"); diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_generator/src/static_centerline_generator_node.cpp similarity index 93% rename from planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp rename to planning/static_centerline_generator/src/static_centerline_generator_node.cpp index 073d30f5b5a39..ec7d6278e346d 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_generator/src/static_centerline_generator_node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "static_centerline_optimizer/static_centerline_optimizer_node.hpp" +#include "static_centerline_generator/static_centerline_generator_node.hpp" #include "lanelet2_extension/utility/message_conversion.hpp" #include "lanelet2_extension/utility/query.hpp" @@ -21,10 +21,10 @@ #include "map_projection_loader/load_info_from_lanelet2_map.hpp" #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" -#include "static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp" -#include "static_centerline_optimizer/msg/points_with_lane_id.hpp" -#include "static_centerline_optimizer/type_alias.hpp" -#include "static_centerline_optimizer/utils.hpp" +#include "static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp" +#include "static_centerline_generator/msg/points_with_lane_id.hpp" +#include "static_centerline_generator/type_alias.hpp" +#include "static_centerline_generator/utils.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" @@ -53,7 +53,7 @@ #include #include -namespace static_centerline_optimizer +namespace static_centerline_generator { namespace { @@ -165,9 +165,9 @@ std::vector resample_trajectory_points( } } // namespace -StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( +StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( const rclcpp::NodeOptions & node_options) -: Node("static_centerline_optimizer", node_options) +: Node("static_centerline_generator", node_options) { // publishers pub_map_bin_ = @@ -215,21 +215,21 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( // services callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); srv_load_map_ = create_service( - "/planning/static_centerline_optimizer/load_map", + "/planning/static_centerline_generator/load_map", std::bind( - &StaticCenterlineOptimizerNode::on_load_map, this, std::placeholders::_1, + &StaticCenterlineGeneratorNode::on_load_map, this, std::placeholders::_1, std::placeholders::_2), rmw_qos_profile_services_default, callback_group_); srv_plan_route_ = create_service( - "/planning/static_centerline_optimizer/plan_route", + "/planning/static_centerline_generator/plan_route", std::bind( - &StaticCenterlineOptimizerNode::on_plan_route, this, std::placeholders::_1, + &StaticCenterlineGeneratorNode::on_plan_route, this, std::placeholders::_1, std::placeholders::_2), rmw_qos_profile_services_default, callback_group_); srv_plan_path_ = create_service( - "/planning/static_centerline_optimizer/plan_path", + "/planning/static_centerline_generator/plan_path", std::bind( - &StaticCenterlineOptimizerNode::on_plan_path, this, std::placeholders::_1, + &StaticCenterlineGeneratorNode::on_plan_path, this, std::placeholders::_1, std::placeholders::_2), rmw_qos_profile_services_default, callback_group_); @@ -245,11 +245,11 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( return CenterlineSource::BagEgoTrajectoryBase; } throw std::logic_error( - "The centerline source is not supported in static_centerline_optimizer."); + "The centerline source is not supported in static_centerline_generator."); }(); } -void StaticCenterlineOptimizerNode::update_centerline_range( +void StaticCenterlineGeneratorNode::update_centerline_range( const int traj_start_index, const int traj_end_index) { if (!centerline_with_route_ || traj_range_indices_.second + 1 < traj_start_index) { @@ -267,7 +267,7 @@ void StaticCenterlineOptimizerNode::update_centerline_range( motion_utils::convertToTrajectory(selected_centerline, create_header(this->now()))); } -void StaticCenterlineOptimizerNode::run() +void StaticCenterlineGeneratorNode::run() { // declare planning setting parameters const auto lanelet2_input_file_path = declare_parameter("lanelet2_input_file_path"); @@ -283,7 +283,7 @@ void StaticCenterlineOptimizerNode::run() centerline_with_route_ = centerline_with_route; } -CenterlineWithRoute StaticCenterlineOptimizerNode::generate_centerline_with_route() +CenterlineWithRoute StaticCenterlineGeneratorNode::generate_centerline_with_route() { if (!route_handler_ptr_) { RCLCPP_ERROR(get_logger(), "Route handler is not ready. Return empty trajectory."); @@ -317,7 +317,7 @@ CenterlineWithRoute StaticCenterlineOptimizerNode::generate_centerline_with_rout return CenterlineWithRoute{bag_centerline, route_lane_ids}; } throw std::logic_error( - "The centerline source is not supported in static_centerline_optimizer."); + "The centerline source is not supported in static_centerline_generator."); }(); // resample @@ -334,7 +334,7 @@ CenterlineWithRoute StaticCenterlineOptimizerNode::generate_centerline_with_rout return centerline_with_route; } -void StaticCenterlineOptimizerNode::load_map(const std::string & lanelet2_input_file_path) +void StaticCenterlineGeneratorNode::load_map(const std::string & lanelet2_input_file_path) { // load map by the map_loader package map_bin_ptr_ = [&]() -> HADMapBin::ConstSharedPtr { @@ -381,7 +381,7 @@ void StaticCenterlineOptimizerNode::load_map(const std::string & lanelet2_input_ route_handler_ptr_->setMap(*map_bin_ptr_); } -void StaticCenterlineOptimizerNode::on_load_map( +void StaticCenterlineGeneratorNode::on_load_map( const LoadMap::Request::SharedPtr request, const LoadMap::Response::SharedPtr response) { const std::string tmp_lanelet2_input_file_path = "/tmp/input_lanelet2_map.osm"; @@ -402,7 +402,7 @@ void StaticCenterlineOptimizerNode::on_load_map( response->message = "InvalidMapFormat"; } -std::vector StaticCenterlineOptimizerNode::plan_route( +std::vector StaticCenterlineGeneratorNode::plan_route( const lanelet::Id start_lanelet_id, const lanelet::Id end_lanelet_id) { if (!map_bin_ptr_ || !route_handler_ptr_) { @@ -442,7 +442,7 @@ std::vector StaticCenterlineOptimizerNode::plan_route( return route_lane_ids; } -void StaticCenterlineOptimizerNode::on_plan_route( +void StaticCenterlineGeneratorNode::on_plan_route( const PlanRoute::Request::SharedPtr request, const PlanRoute::Response::SharedPtr response) { if (!map_bin_ptr_ || !route_handler_ptr_) { @@ -475,7 +475,7 @@ void StaticCenterlineOptimizerNode::on_plan_route( response->lane_ids = lane_ids; } -void StaticCenterlineOptimizerNode::on_plan_path( +void StaticCenterlineGeneratorNode::on_plan_path( const PlanPath::Request::SharedPtr request, const PlanPath::Response::SharedPtr response) { if (!route_handler_ptr_) { @@ -533,7 +533,7 @@ void StaticCenterlineOptimizerNode::on_plan_path( if (!current_lanelet_points.empty()) { // register points with lane_id - static_centerline_optimizer::msg::PointsWithLaneId points_with_lane_id; + static_centerline_generator::msg::PointsWithLaneId points_with_lane_id; points_with_lane_id.lane_id = lanelet.id(); points_with_lane_id.points = current_lanelet_points; response->points_with_lane_ids.push_back(points_with_lane_id); @@ -548,7 +548,7 @@ void StaticCenterlineOptimizerNode::on_plan_path( response->message = ""; } -void StaticCenterlineOptimizerNode::evaluate( +void StaticCenterlineGeneratorNode::evaluate( const std::vector & route_lane_ids, const std::vector & optimized_traj_points) { @@ -618,7 +618,7 @@ void StaticCenterlineOptimizerNode::evaluate( RCLCPP_INFO(get_logger(), "Minimum distance to road is %f [m]", min_dist); } -void StaticCenterlineOptimizerNode::save_map( +void StaticCenterlineGeneratorNode::save_map( const std::string & lanelet2_output_file_path, const CenterlineWithRoute & centerline_with_route) { if (!route_handler_ptr_) { @@ -636,4 +636,4 @@ void StaticCenterlineOptimizerNode::save_map( lanelet::write(lanelet2_output_file_path, *original_map_ptr_, *map_projector_); RCLCPP_INFO(get_logger(), "Saved map."); } -} // namespace static_centerline_optimizer +} // namespace static_centerline_generator diff --git a/planning/static_centerline_optimizer/src/utils.cpp b/planning/static_centerline_generator/src/utils.cpp similarity index 98% rename from planning/static_centerline_optimizer/src/utils.cpp rename to planning/static_centerline_generator/src/utils.cpp index 9448677d1bbae..ddfd3e11036ce 100644 --- a/planning/static_centerline_optimizer/src/utils.cpp +++ b/planning/static_centerline_generator/src/utils.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "static_centerline_optimizer/utils.hpp" +#include "static_centerline_generator/utils.hpp" #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" @@ -21,7 +21,7 @@ #include #include -namespace static_centerline_optimizer +namespace static_centerline_generator { namespace { @@ -228,4 +228,4 @@ MarkerArray create_distance_text_marker( return marker_array; } } // namespace utils -} // namespace static_centerline_optimizer +} // namespace static_centerline_generator diff --git a/planning/static_centerline_optimizer/srv/LoadMap.srv b/planning/static_centerline_generator/srv/LoadMap.srv similarity index 100% rename from planning/static_centerline_optimizer/srv/LoadMap.srv rename to planning/static_centerline_generator/srv/LoadMap.srv diff --git a/planning/static_centerline_optimizer/srv/PlanPath.srv b/planning/static_centerline_generator/srv/PlanPath.srv similarity index 55% rename from planning/static_centerline_optimizer/srv/PlanPath.srv rename to planning/static_centerline_generator/srv/PlanPath.srv index 644a4ea013557..7d823b4eccbf9 100644 --- a/planning/static_centerline_optimizer/srv/PlanPath.srv +++ b/planning/static_centerline_generator/srv/PlanPath.srv @@ -1,6 +1,6 @@ uint32 map_id int64[] route --- -static_centerline_optimizer/PointsWithLaneId[] points_with_lane_ids +static_centerline_generator/PointsWithLaneId[] points_with_lane_ids string message int64[] unconnected_lane_ids diff --git a/planning/static_centerline_optimizer/srv/PlanRoute.srv b/planning/static_centerline_generator/srv/PlanRoute.srv similarity index 100% rename from planning/static_centerline_optimizer/srv/PlanRoute.srv rename to planning/static_centerline_generator/srv/PlanRoute.srv diff --git a/planning/static_centerline_optimizer/test/data/bag_ego_trajectory.db3 b/planning/static_centerline_generator/test/data/bag_ego_trajectory.db3 similarity index 100% rename from planning/static_centerline_optimizer/test/data/bag_ego_trajectory.db3 rename to planning/static_centerline_generator/test/data/bag_ego_trajectory.db3 diff --git a/planning/static_centerline_optimizer/test/data/lanelet2_map.osm b/planning/static_centerline_generator/test/data/lanelet2_map.osm similarity index 100% rename from planning/static_centerline_optimizer/test/data/lanelet2_map.osm rename to planning/static_centerline_generator/test/data/lanelet2_map.osm diff --git a/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py b/planning/static_centerline_generator/test/test_static_centerline_generator.test.py similarity index 84% rename from planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py rename to planning/static_centerline_generator/test/test_static_centerline_generator.test.py index 9f0a5df7f3fcc..29ee49a11e3b3 100644 --- a/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py +++ b/planning/static_centerline_generator/test/test_static_centerline_generator.test.py @@ -28,11 +28,11 @@ @pytest.mark.launch_test def generate_test_description(): lanelet2_map_path = os.path.join( - get_package_share_directory("static_centerline_optimizer"), "test/data/lanelet2_map.osm" + get_package_share_directory("static_centerline_generator"), "test/data/lanelet2_map.osm" ) - static_centerline_optimizer_node = Node( - package="static_centerline_optimizer", + static_centerline_generator_node = Node( + package="static_centerline_generator", executable="main", output="screen", parameters=[ @@ -50,8 +50,8 @@ def generate_test_description(): "mission_planner.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_optimizer"), - "config/static_centerline_optimizer.param.yaml", + get_package_share_directory("static_centerline_generator"), + "config/static_centerline_generator.param.yaml", ), os.path.join( get_package_share_directory("behavior_path_planner"), @@ -74,15 +74,15 @@ def generate_test_description(): "config/lanelet2_map_loader.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_optimizer"), + get_package_share_directory("static_centerline_generator"), "config/common.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_optimizer"), + get_package_share_directory("static_centerline_generator"), "config/nearest_search.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_optimizer"), + get_package_share_directory("static_centerline_generator"), "config/vehicle_info.param.yaml", ), ], @@ -93,8 +93,8 @@ def generate_test_description(): return ( LaunchDescription( [ - static_centerline_optimizer_node, - # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + static_centerline_generator_node, + # Start test after 1s - gives time for the static_centerline_generator to finish initialization launch.actions.TimerAction( period=1.0, actions=[launch_testing.actions.ReadyToTest()] ), diff --git a/planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh b/planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh deleted file mode 100755 index 8164b521553c8..0000000000000 --- a/planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/bash - -ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml centerline_source:="bag_ego_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix static_centerline_optimizer --share)/test/data/bag_ego_trajectory.db3" vehicle_model:=lexus From 453d41c2f75091c32c21f48f497d11e2f99a48a0 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Fri, 12 Apr 2024 17:26:33 +0900 Subject: [PATCH 56/57] fix(ground_segmentation launch): fix topic name conflict in additional_lidars option (#6801) fix(ground_segmentation launch): fix topic name conflict when using additional lidars Signed-off-by: badai-nguyen --- .../ground_segmentation/ground_segmentation.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index f502aef017979..a307b192d7caa 100644 --- a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -281,7 +281,7 @@ def create_single_frame_obstacle_segmentation_components(self, input_topic, outp use_additional = bool(additional_lidars) relay_topic = "all_lidars/pointcloud" common_pipeline_output = ( - "single_frame/pointcloud" if use_additional or use_ransac else output_topic + "common/pointcloud" if use_additional or use_ransac else output_topic ) components = self.create_common_pipeline( From 9f3633d3c15f6e32d5d3bafbfef31ff7109f5d2c Mon Sep 17 00:00:00 2001 From: Dmitrii Koldaev <39071246+dkoldaev@users.noreply.github.com> Date: Fri, 12 Apr 2024 17:33:12 +0900 Subject: [PATCH 57/57] fix(map_based_prediction): use object_buffer_time_length_ (#6772) fix: use object_buffer_time_length_ Signed-off-by: Dmitrii Koldaev Co-authored-by: Dmitrii Koldaev --- .../map_based_prediction/src/map_based_prediction_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index e12b7c54c3a9f..56dc1c2293583 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -1360,7 +1360,7 @@ void MapBasedPredictionNode::removeOldObjectsHistory( const double latest_object_time = rclcpp::Time(object_data.back().header.stamp).seconds(); // Delete Old Objects - if (current_time - latest_object_time > 2.0) { + if (current_time - latest_object_time > object_buffer_time_length_) { invalid_object_id.push_back(object_id); continue; } @@ -1368,7 +1368,7 @@ void MapBasedPredictionNode::removeOldObjectsHistory( // Delete old information while (!object_data.empty()) { const double post_object_time = rclcpp::Time(object_data.front().header.stamp).seconds(); - if (current_time - post_object_time > 2.0) { + if (current_time - post_object_time > object_buffer_time_length_) { // Delete Old Position object_data.pop_front(); } else {

hgFw$T8${Ep`UU+oPCv|KD73SX>#+L96?hg^ZX`kQ4pR(sAeo>C$~%k@9E` zYM?e|<#IP6-`i6bov)`NK8CI0=l|vn5``x#FY~6$lfCHeMs&V?m;IYJNFMFC9sS+P zc{yk%J&r~u{VU8|uBE0rooOBapDHzcO+1{tfcXd#;?6RE?BF@&N05+g9!qf)^{G@- zN@$f3xPoIv=AOSJiTL#!y+-gm2bz;j@WI0hwsUwdTW28{@H^bkiNF5>Vgld zx1#5da#>VwnZ0Y)R-$^h>drC05l=-P3@K1N54sP4{aNk!&as$1cm-D(2Wdi>B ze_utBn=ev1uRsc-$HA4!r+c!m_YD4EXS-?4^=?-fd9kRhZOZGtZ|_%@;@B=f z5mcH_(|a0&-q^}E&|3w5IulQCuNUfbF}>wCn9b>!+;rupK?}D&7YO7XL5!?HXu4nu4>wibRw5>g{%4BPLyJ>rhLj2nB z>;DZN&mUBZa^CFiDta8u`d9x+3voEkzTP*8o|^ejn4kZL*2#KXroWx?dP9>lSc~Jf zxKF`f2c$(A^v1So0KLn9=E>mcT~Q7{!wRIbo)5J8KiA(gRsz*~YqGnRxIP8huegp^ z8Pz*RR%<{C)jQ*g_S~H)Z`^}x~7f3&U-Z*5*|B&gRCZNtzLe|H7$`?pszNRe2 zvHHlSi0UNT^cIOhZ*1=o&|6wCP#RBfy&j=xOz+@;5Zdgmrjy8 z<%5Rf=;DOR%s{F&Xq$AD^YoUW$HAI(P9u_5Xj?Y8=UE{V&CkgRtF~AP3zI)>OsIL6bqtxUegB=l506E=Zr@)4tpc z%|W83)MbK}6r|>?U)~71g0%DaJz)hj2a)oEq|(t(>`6-f$=%DM5Q~TI)*-L(3#87) zdD2hjijmFe?Tn|{SUq`!Umz_JpVP*Fne*=de@c(TkV*esmu+3Gy@dS{q@_`S{q+{+ z1rp?Hk?-TU?FvUa$WEsO5SHS|dp2+T;#;%=Ns>WtY&$W~+vC)*GM?UN2Ht(e3Z%G% zaGKt7rrREnQN0P<84r0?=@#JMQ_n~^1l;mtXK0OLK@JiyN z{~3I}F_tV?Gq;9->EDvArypO`iJ{?x&xDjM5Jq~95YYuzu$vwfo-kxiY z93JCh{)vr#^!!_2R^OD@`_uYnmg4X{UK$sMUa^B_?->kwWBcQQ-crY^mGJa-8!_m? z^xo02kf!&?EB=ocp?a^>2{+qeMnQH~+glz)^%f{gzl-T@Ib%X63)TC(X>hjJ02SG8 zXDPif7GLitC!2eAYDto}(c8UGlF|(c#MgVJ1|MZjks8P8-A0dtS^qpU7M@%_hkd>4 z7pWf#xXgTk6so;gzN4#m%IgjNtY9gQbzzA!t^b<6m0-{tJMaPYF1@x_5l`=fVbX1w z-d*!XXp0jXMB)i;RPVky(Lr6N6lCF(psck3_c{eR0WBm7hF^>+STrCxq}CRvW&&eh7}<75QB-gC4! zWgV2^yvvDK)8o)&(!VaZ>z7K;u&?*58)GtgD_OXE`-;&*xqA&${{BCx)RMJ0cCFbs z2fcgypZ))wn56!rPv{6zjv)tOXE;F)BD5=O;^m+t{Tkv}{ZH)|+=lHzGC$XQ|NR9$ zleE_xe`NV+2tAdIml+L z_npvjL2^93U6yn1=^Z=pbI_wlrOme|IqwB2D|#Fcne?wHUesuOq(T!>76m3o2GZO z?FYASsNQ*dB-?hO&s&asx#~YMf^LxZbl9wd>TNOh%^TfriWolmIlTE16)CZ{ZLssg z*V~rAz@^GYn0$)fZpkFKW|BR=-V~^Po?YQgjvGN*{Xh2JJe36Cp=ikqSvKbi9Q$ ztfs8K^Ww>I?|$yd2(v}UyT0T7y4NeE=niiILuYHvR*_a!+48R;0<3JLB{*>&p0JCyw7u$^22zKsEm{F{?TQ; zND<)ed>}dCtTh1&UF3KRkPe_Pz~!m!so-$Gc-m`DOZhy|oL`ft8v(@vF+#~Vjmjmk*Hi5Lam@I5GGyoVrrMKru)_HQCRPMrR7fQ0u#kH}Ip zfHz0YMIyf$0easQ=z0Up-n_)JG~wBs!ul&p$pCMD{zS3bCL#nb3M+r$@fW;%Cx0?W zEx?oGmU;`DFZxSy;x7_g>$6af?%cZz(Sem8xAww^&*Et>PC}WsNQ5U-(f=nb5IxuO z;qL#|c`@EUP76_|gHZ5R_22%VG5&tR5-U&PLGVpbWDj~)E3S>^LFKR4*1>O(Hc5OA zf&2d_UQ>d{L4#EK^FZl`00I=p+B!x284s1c+ffB?vCl^0oDKpHa>!&_x(h6^>7R>j zy#KPqPORKr;u1PybR3Bjk!hF7U538IzU5Gf^(vXEptt|%Lx_$xjQrMalihb_oc0Qm z`=^%24nFK97U$;CxpE~x*0xUz4e#wb$=hMP zKPBu9hVjl##5rXFydzY4*a`vOr}_Cm22RC8a~)>Ea0R*E^W@Dv0PizJR$MhPL`Za9 zMbvo_^d+|bq7j$t+G!(kB(B3{Tjot>bi5O5wh1gc%SCrfYz?9#9wWbvhGK(Ww`j+E zNUlTg_hRe;>Crvz`Hty{43GC%=U%FGRP0`@o|!saTptZ#Ye}H##(N4~HJK zXtwY@K*u|L!!emzW)A!#ByMMf*Q9qbx_kF^9&oAg5urQ0LlGUl82L#&j6D0MoOZlt z%TM(EuEXBF#f{zQUuew7@clndk~$q5mFEe?{P}uIngVb5HdQj->rJiH(eQqhD58wvr;MuRF{(t_4a3UwzgY?R<$SIB>Ko>qg=;#F=blm@#h$8Ty z-evi|a=?Q`bw%B}&BCEmEjHHPAJ9F>X<5qiZ&ni(XOKAK=iT8eU!Z%?%evOrQ%~pN z|0jw6H-F6?(b0jG-)zktmyfhxv6I;I%kQWac7ucq`>{{@Wg)|R5N-o?I&5S(w;LGx z!xJPWO1!}Z>14dc_Zloi!~3VXZwHKbZttp4xPsiVIeBylEU|GvkCmGc2~g={r$u`v z;-Q|?2lC(sX?3xBj2XcDl1(PW?aq*|mrc6O8;yI>Khp?xY>>&s%1Rio#U%|B?c}l~byW@80va z`%$HX&rqb;o%BHZA_~0WCoIT#ul3rcgNApJYO+`pz`I$+JPdYkFNfWehXLLL-RqUP z0>SQWqw5{#U*LL+V-8|c0PnF_bDm28@9RQ+cb!_op(9R7`fI$sQ44$ZzG%tD!gm!Z zNZdpxzseyOC)9ZU&K2`j1c&JkZ(~G<1V(VyZwpeQw z;}1xkUQ(qaZxaWPO;ceR9WO;Ll2ub%t zoUAeE?(Nw#!Q$H4WF(8k4VYhzJNcKdxAG6!7?1J1qr2JLazw`|jQox|nY9h7(~h^& z;l@OnGHkq8ExDv28GW1K@vfFGq)JCd{apBykobT5|Np6^ptoNG9;89xLGY_oum|x7 z#Baao=z>G@pkRm1E1!ZTwy^JOB)r7(N1R`99W1eqTb!?5*-e1>JxxUSfeBJa(LH{6 zi#@S&Q>`{wVtbF>U)ljG$Rx2NpJ#5Od(ijl<11bJI4Tbzai?F)$Zp6)uOJ8B>iXQa z6s5ZcX#&wPgpnT`i~sSBCbWCdVkt}h{toOtNc*L8i;ojmF?r~iB) ztxkbA{LC78iLEw%x&jUFQE8_xxPtWf78(KLZJ~JCvl`%it#4}nm=6KUAG;9~0{Z{u zUj&2U?X4+OO*3(TcbCG2Ba7b?A**(W&0_)Rc%KLz-Txt+rP2n8Q!NkXed&sh_f?L5 z7ZLV_bcgpzL`N=0e&$+VQ}+bXzP;6OT|l+d3A_KtO&lAXd$6A2@y2PSQKchzQZbD0 zBx(MyMu9i{ZXg-&83(#vIpH(C*%E`1S@Jo5IFh+_rVWz=j%z$NQY~OR99d`7Aq; zc$9R#g(?N!@I#nnyuSqO(nrJl!QdfY7;oJHNmBoBwyAxB2@EG5qwcK&@E-Qf>KbBhhW0Emb>3b;gq)*Z3<{f|m?w<)DbZ)h<( z-Wr=LRQH6i(H-8e5FOeW`LWC>6^DDZ|~b|vGTXRWJ;hWD}7`T6kfZS=8Z((G-)dGmvE0B>Au#Ov1m1nAaN zPS^Br;Ql|CJtvg`-ZGm_N2dVZuAe@>_6rP$*0Bn4vCc=|-nyv6_l`$&k@fb*|~`Bme|dRj%bYh)>xfn3(2H?iItD^ z-Epb84t4bK&tG{S-$e(JpA5eTiR+|NM@8F%#eYtaYE$41Kh{ph+e1)s9va@a6`YAM z-f^*GB)q?l`yF=!c%O4L4<^PCAYJ<>jT-^pNtMU_;q(7;^C$dw1H7-~>)IYWM}+)O zzPGu&1igYBms%EIv{JCr7l|{ST8gjsbs@mVsU1xe7ejS|NK90FLgQ&XSVj=zeTDb7gOMUIbdNO8Sh^AVHPyJA8dRW z4dWfg$rA;;H|}h2s}GE~NLN)8INq{;*r?z7#&3c+O%$m?^-!J-d!Q%03*j zFBRFLJ&um|uyfS+`MG?RTah>>=is{eAJE;~_G4<9>4pXiX9?eq;N0{{K(!MbAF~4_Z#)L3#BD{K+0P z@YIwC&4bojODux-ATK`j41z1jclo=OwgV4J*5Bf@tAGH_DjK#bf(B{OyQT!*gPd6{ za`P+LgUq?oyY|_)Fi3k!U+P92`Wqy810K8J9n%%$IISP6lHK>9FR`T!Q-*dmTy*C_ zrihLzjQm{slS}3~(e6P>VRo;qmS9(q8-n&PPX8Xr@D-%@$tbFHth9d7{3VOjAT6W7 z`}&pqL^9si`xUs+@LpXJkO1S|Qv8GT{r_UO7isPQ@2sB2qpi6F=+uP%B;5aJxj2Zy z1JaoPn(I^Hqqr?0vS%&UBi#O>TtFaARd9q$kLFyY1N zf^>&>0-~cIBfljTd3>)@X~+B41+7HI5h^OkyquKCff$Cz8z*~(Ivppjn=koOK`y1h zJ2!McX+R3^-dbyY;6%gQH(=8kjQ4>ZIi&OdA2#T_y8yg}TQldf{|Zc-4&{1!j<@KW|FUrac)MDe-XLZYApMg|@C5+x z#}0kB;Rfm5_}dT@fOkY*T-Cs0B4qD-MSFcMI^Hpoc1Y8Zn0xt^0MiOhq1Mc)Ukamr|v}-FfTN zU6G{YEjkok?{@{iDO5@doUjN5yo5T-9ggf#J%|2EOr2IEmo1#%_j*^^J>=G z&j9cHOkTtAaAL1O=&&2W`+AUDd!u_8BrDCStvj|0^{-`Pu>9In?*%KRkht)nd9QZA z+=d!ol_vjcrwjef-YgLvH5mClTizwIQH^%Iy&KCtn|EQ~y%m~vrqq0IFvH{h^5$8p zbbKu3P)%3ZQwAP>3BKt{}$?pOgCkOD?=j z;lP8K?^NgQsU|>E%e&vK0DF+KyzVye5j*uayGjQ@|L2*A5QSfyt4J^}i2D(UfQfcG)I!o@J&dEP2-;S;3zs{8F-8;H<+UZz7& zI?*f0^;Tyr_w#=?;zQz0+?XxW>(ML7c|TPh^Y;9ryHD&^Avz|e{+{36Lw17(#kAuc zS1Y^!?O7`N|AE=}TNdnOc)W2E6V&Noaj97Pr~fyg!271B-BvQ*$=l!0N5gvqr=AXs zx30wn65fZ|``H5k-Z7HXK_5y9P@nSn3Jx$Jo!4Q*3FG~XH){SDfcM33y3aCti4e2& zM)9RYbocJ~!TEM5^Q{pR5*Hh{Gw$&Y^a+wfp^J;#k0H9lyAIKT$H*@?=4kViU9{tE z7Vv3t&>$5Dq^B1Sxxf6*_;^nUP^BZfP<+wk6_R`FQ{Y{ogFi#Y`;*T#J~X_G+r8Cc zyl+XzlJK^2YSq{a@K%~Mz)9UEK&(1a)`tMzn#aX^;NgVfrWxB&fcNV|gmrRniBP`R zkH9oPbi8L9yc#W{YAUWHas8ij?@v3S z`vK{M8tG*^OR=}NIzO=Uy^Yz<@D0+(EHOq#tBTxpxV87hB+j(39EdtO_nd=NU`^+7XHXBK>}2t?xcM8D|Cb3@0wGdvF* zIrv3)c()-sK4au(evA9f2N&AiyG7xgs^A><>@8Z5$acV&iSgZgUN}`cd~SxQPJ`<$ z|9$_DPMXlar2+c?RTLg{_s-E;vIkvm)fGkapx^Dcjo>9V;Q62ae{xD!wHYk2wF;8$ z+iww|YZkn})W8!vFK_z^>wqQJ%O~@-C0JtX&L1)HCJ><$JMLaE=|yjlmKQaDoEDlk zI*G&;uN3V3@C3ahOKi_vt^N5r>;ux#{Hq6} zSOXZ}gHGV7(lIvJ7vO!FR6#-%c$XXuy+Fo0wVOi(4R0;eTcqu+K$kXB1)1t$IQ#(M zz46SJBjUvbXouL3=(k_uq1qest+WB&9}T)E_5i${cTBuqCrE_SpvGUtIp}zcx@ij! zkNq^tK;kr&y{x*E(ebX=(pcPY%}ICLTSADA8jSqT#<<5!?4cd+Hq+k+^<1&>p66dD z{KKM$;qgwgtENha+Se0RchgCD<0{*x=!23h*VeTY=x9p=4mYh#vkW;RKJ8LL9-m6=c zEw}kj8Mz>FR|0!8WS!CRj!n8bW%rJq?(oJVIwCRh`<6_2ESya{-j|AFJ!@*QD@fc# zna@j`FAR@2jc`)DQW=kzOV%AM*wf0{sSRD^TVL18!Qgf zE79@Z{rHvSZHw?x0Aq8;yFyP0e| zUQyxR)2q!7tNSoK-Z&Lws&p`I@9Uem@NfVBx3-&Z{vGK5*HU;;Mb0BNvIni5Q;|mV zpxVOo^I#7;ANZa0g4E~@h~FD{kY}`m;!5y=bP-QhWB|DTFRxwT3fv&Yt?hs30z8OC zO5A_uC72*-+v~pFg}w*5w8n++<|Z7T4TzGe>9<&6}u^cPE z!SyHZZl%3~G;7Mm@m5nYLAoE<-gasu<5!T0)aiJ%FU^4C5~)Elp}_lo@VkE+Bnz{j zl4y885bIn3j?1X zvr7&WyF!ElUcBsMH8nMBif9Zh^8@EcxgT?^HyGI!1oW zxAXOH6r%l!ojv{2i>Al1@n%)j7W)+VgyHe-a9vE5juW5EpFasERgh~a@V@7oYD{)- zj&F?;Xm}6)UMd6QEiSZ`g!kcP$?sDD-n&PBvL884fY#|3^WFmul5^?~!V-Wt`-)3a z_5km2BLjYmC?fRkI~PIwFCR#!c@yI97t9!SB5|AXTw$+&qgRlj{q1L#PxH_n-bWD~ z0T}s(oM>85w}y82=AS3Ftm7hf1sSb8x;yvvD~87#_wx%?I!yPUoBk9>a&Kb_yvudd zrO9~r8)u25;SGg7(uDEOyp~47yRa%o3GV-I-?rM?aFGC2^yU>-fbFeeQInf6-n;g+ z^Vk5q#e0JHZi^s7SL0llF5^dc?*sh1O>SiWHp)ffcCPk#+wl_}Z@r7Dal0qE=??EG zM28MWewuEC8sjM1@eU7{u#U*XKAhMz>a=(5M?;2hkc7WFP^H7%n|uG)+a$bKQ{Y`X zP;sA(w?>AW7#iN8AyuT=+t1&$&ED*#{7$|}Awmf;Eobx>q2v89zcFsc;Mh=G@W>+VPHvR(;(mO~v6vk6+QjeXkk+`+t^6 z>U8*&epCU66aSt6(@mF;o(Smw%_%&nZm_qA>_M9@DJ??tAYZl}>)|D~XgxdW1L>vr zIJ{556{KmRk4QQJG8^8m$Pd0j`pS034Q`MYc+?oVgC+L-#P`FSFB73ki|bkM^w2%% zke9qB*U+p{9TNBYHD{x^Jh}%dJ=znwU@`qQNO6b`8I1f6zdF&~_8&a4`{=f9E3HtLul47E^m+=sYr_+Nk@0@IZ&Dr&Z;mr7Naz29v};Kf zWa0*=)FS}z?zV&0Hb)6iUkU$JJikBfOYDt^vIl$E z8&N+!{Kwbw4%~cvqL}gVUKvM~j!^OR}E$2~bTyiex)D8laD z<{eDJ+bwt{AqL<*;%Tv!Jrx-;S9kT}zQol83M(D7Eb(pCFDMSpk)AUYOd%O0Xi$M4U%ZVPis{l6&%-j#1VzL4?O;)7s*ta7v-t+U>pC?L(LzkO( zv1*i{iNh>-ZbODIPBQq8P^F{6k*HjDAmiWu|DWoVj(-6Cza@nSJ-)gxo9saW zhQexS9&~mv@i=@3X=P3T=?+q!@H;L|z=QlJX4=NV4N{_STv8T;52PQgdKL-aAa!A_ zWVQ;pgT$(LGk#)4IApk*Nmb}2x(981_1v@J(x-~mNL;ImrRHcgx(E4O*K=%LI7xTk zAXy_iA~Etixq|<&2tVx}lta8L?GE_-fB8bSq%D`g4buLOThajDs;`DD z;V(!bxBF*)f+g1c${9xuQz9hSwpHA%1O12{B+jq)#wu>qCEGJ z6=JXG?gQyXhz>kPekT6AM04@9SCBHp4q+yHvA4H&oXd-Qn`y=Hc!yrUM3s*Hzh)g3 z4wEWK3ktmJjfktscq?_6DWl;X6}l=FzCmh2ZB00Qd+V|{pUv(8yc^do_-T5902ylD zw4DbkNG-YJE8!EQ6T0g=8vx!nxF#a{b%{{cA6tMj}WY z*VFq!%73}u;_xGqEbJH2%Q(NT+$Us0(;fBFI1@n*UHrhaS{_UWzGdrcPeB_$Xh zZ*MWKP1NXEV{Xhnney-Xe>(2^|5s|D|F@y=pq8TsYsnt8a}%dFng_|JF>i+VAhQ;U z`NI`t^nm)KLQvjcIG9Tg5poZ1G*XA>dlOYD-W3h$^xpXjdtFGX~iVC45(?4?q~8`?dn zI_tHX%1Z1l_F9&@kf}qJ4DUguXQq~N$E7UKYKowe7cV$Tzxnr+s?)1ZQ^UiobcyuB6T%+sL?@Ln@;tzvB* z5q$RIu`1~=52U~8Q(HeZ_^aYJ5_kIerLx^?(DB}r)>}MeN`KE=^ddTZG4k7&cc+kt zhjzU0*8Y50pF%|iS=4PZRME`vc;iBPsM5j8vB&boj|BJysm&C4Kh4-idO;e#|NqhP zd`&dGadit=;Qqh<*gVn$=~{UPM~493t!FPj)yX12&%d7L^#FJqsUDA10C@Z8oY|od z@Rsoj@x1^(Z~4gXo~E@D-MtUo8+}61nO8ZC#9a$5R@(NL&s!vK|GL{+NPo{;#3MSS zG4cye`R3KRiFUlZBnFQbs$f@;D(Q+D(V>jrAia#UrAmjRQs-V(B58ZeiURK@{^);R zZ^^Zb(Llrd%lGX+VZ5C>e~>OnZ~vI-(GBpfZB-9*y-a{wu3sFv33hLV0#;|k_y0%c zoSJ|iNNef2Wa*hrg!YV`;ONyy$NPoZUe=xi?3I2<9AR%+E=~d6z3qC-?>K!E#{aLX zi#~p8Lv(D#$nT_s?!K2PwBwDN<4YJErQ(2eN%y%Mss9hScfP}Us&tq)_acuI6DaU* zeC5UTPjQ0VppJ(3l)O7fGr+r2Yr_G!_I|*t7W4w(J#HYfR{JUeS}O9c={5NF_UL}@ z2k`TjfqsMhb^!1F;l^_NL&Kp6U+*3X0dLe(N3w-RUZ$S26){NM(#PUb;Y?1b@mJZ7 zIIHFJ(jDH55FIx$^3%C($(r>axc9Gfda7~vuxoGJ)Rz5;KRz)2`TwI^snQXra^Fq; z-|zqF!{f2C02Sm`3J+?FTIfvnpo(v}I%p$tO`zNB~B1V3`3Hy>9y=cdKz(^uEXaKwax3~RR zn3w*X;qiXzOq~wLfESln{Fxwap}_m4o>Vj$@9z`mb_{EXa7jv-8(M!~1LN8%r2(m8(;GVfPlUj{Nit z;O*$O$6W%P-pa8#-smNHi)}{dxVPG zTU%)9;EWODyZ1&}s&rJJf3Y&{>c8`Utk#<@{ypgbohdx%ZG!(Y*n@b%1Zg125r^hM z&Ayv%*8>mo6m{7Nd(io$Q~C-;x~pCh#Eidz0ck+PP}e=+LBW#+j?%z`oUd*qCIb&z z|6)_(GQ)7_-i`dZBdzEjl-mBF^6u_M_=iZGA4m7z&{}j4+NC@()ik0@cOG;U(Xj&~ zKWm+)=v}{P_aLJ=^<1qn>xD5G z@8|2{SPuZakK9w&{2>?)NuHF}u*pZqd%C7h!d_1SuY|D# z4(};MM*&8DBi-71b9%HlNPBZq?k0+1>J)GZ(EEoq z@iG8!j&ePXAb_{!>zi-i&k>=dPnrjApFqc(wJt~?cF36i;nj^{mUGC zBbLw|-rR@|W{ms>Jae9@gwl?;WqX2#K?4;7(y>p^zEu}6Jl;6N@6_qIFg&32=ls6| z1>Wu5$99tO-f8QhkA}CU&wdETn|Sx!F4(U3m3Q)anK zDo(ah;Qgv8b(D;^DxaPn8s2vEwuZoXTj$5@hVkCex-&Wu;QhV%faxfB-s1ixubQju z2~dC4ivk$$wB+lijsR~-D~+UQufidlQq!nbe{{V2@>e}U zU)p8ANrUe2?nQL$#mG;aFP5nTw-EJw16sLiu9a_BK7oxl|B^(n!W|9_@80k9sMB${ zu{mrY;@|K8(YT?jUkCla2Zaaq9Jcxddl20Jr~BEkp?Oe(O4@dK5Ar*Qxex3?7eZ}t zWuQU2QtD(bn@WIs=USUpz!{{+W-X->aD!yJV7451(90Ds+xotOD|WwST}e$uuORKk z4=$dsrhvbR#5r63GP)CpUO@^w^!wM`p}z*n7SXW~BfoD)Tpw4jroDnpzsKotVVH^v zlBo1yfK7$rJqUOG7Yj|(R+ws=T{ex_C4db8Tp{54N`&M-v_z zj$?oSUuk=C*DU)H|wl9A%G}4@e_bkZu%scgdN*A-nhGRvarD-exy4j>34K zDStz%AWaGhnTG)0h7Z489|yO$TC2`1r~-K3;XGOf<83;ywLcf&&C*<;Rb4`a?htqT ze%XMI_rr~&E2Eng@l{CNQ}LRD)aB@S7aq>mmo;BTcX-z#ItnoI+q_2OgSQdw?#-bu zp70GEnF~u4{WzUFV`UB&9e6%GaB9lxeEkgyxWfS zk+!#vdbXr`0lYUpcCB(aL4e+^y=fv1&i}vZ;aDXF@E+ah)t3eEeq%aNsJbT{QgWB* zDPl!$kdm(C&PY2d;kA)C#lD-LTfU*=t)skC*S(eg@IHv>Sd5XMUgL<$!&%yg6O}4n zSA}}17?5@meXLd47{C7yx=NLf7!SvYds!s+cA>!gU5=+98E^le$xLW?M;Y@Ufrk@G zODcB2wRhh(+>imlTXf@ggOyM#`~wY*|C!V@AjPUvu_WCL*pCY zZ}=>Mj(5c4Cj|KrMf`6hE_qHlAcGsd|6j@-dFa)5`YTR|h>j%~`L(m}71;iScK3EN z?%q?Rf!+TL>xHyR`DyCYRp0j?B-7fwo+=$g@wf{w!0oO7-v9p}{73$8{}#~ydr^4M zC+7}4*@GsQtmQ%Tpma$aeYpSU={`<6Vt4D^rjJa;x~ukIXWttdM}S^+Hpy(6h=(#g zJRZXX(lyWQx)Om0B`>rs?duPNmP)ncEek=vK`NQQ{=8$VBz^@Fx3es8ZM`G<4N_hg z8xE@Us?%Ks8H4EXz{pR-?Ttv(9om=JZ5i@jVP~kQAPLbBheoH~e;cp=<9}Xt2%ah( zab{h}Cw4n2@a|XL{}0~vl7if5c)RIbC7mD@hQ5>VcD8!sH4T6nKA}^EyIy@6g76PBgsNIQ{a1-JAW{Hq!2`%HS3EZvbzfv6sKo4-z2u z<-ep8r47j|8@$zds}#_$#@?NE95}K+yCSJI2iASZBIyeJ1Vy?83cHTO7lu2B!SOc zW`{K|0lYuX7+1pETRWVZqOJqHnQ)5Mwh~0>db-E$xB2LJ-SsEMy}%|_x7Z~`@=PZS7f|@m>yH80)*yz$ou`Cfv@ zi9-uxxE=t!AB-t5!+2lHw?9?_@E$A6+14*jgtncCcolvN9q+v==?=`R8g} z(d{SE@lFzaCT!E8O?U3S3(=8)k)KiL$0dAsX~%oQu8k<9iH$d_%ZTntJ8OggS3@1qX5Fi34zV!Lmc<52|o_!*~gLEH?uVrHecaY?)nF~4_ z21Q6IJm*zI_n=iFDopADlK2=TZal5%X)`an2Su}1*knJVzy4nj(Luz>&+fv~6rWLk zn$I8!IpG6#mQd0Emur^{Ox|St{@+~jCRI8lnAp|+RFK{jcn>fB(nrSoPSpGbXn4D= zx9W%SzRd@b=Kt5eMMo?Hc(34mxWvJa0JVJ`5e@|pq(7MZ(IN`)Hc4t8839Xd)0G3i zEk%gXdbL$teb>Aq0=Mzb2z0!w@84&Qn3KS#A#vU3jugweqvM?+DZ8i4mj3WAMRXj+$Zw{w zouzj#?G>ar%g0RC>)3c}t*}|3a=(P(@jlS?f`b|zO|p{D_xySPZ#MOx7P3lZn!~GBfKTyt98ma*hEd^oXr`Jq2hXrhugibT`XsKym4iE+o;hoeIq13{vye}cTwOykVCK| z<6Wv8#fygbmE~V#VZ5u&my(7PHL8KH1OeV7(!2Hj_Y)w_$XrFKAMwzPajHJNd#mI5 zqTw>Yd#i?#M`H;uU4Srt>xhESm;Q9c-tU4 zR59`kKbNZ3_K9}9wY%p&tXYDMcl53dDP=h!hVTDz;wQPO(Lo5zd&7C|-~RtUX~+NT zzX$aH{uCbc&2B>h*@N2l8Hl2J5YOo>8TkHxmI8A>_zaSQ*|gVM;6b97Ru);y5}-9H zS412};vr|{ZT@ioU&Um!mJ{^-j`b@g^?nfS1@XcLiS_V8^^g7L0m?IsOKZ@5lz83Vk>WY#Nm zt|CCX^{Ky~0=!uoj|ahcAKJXVoE_l(LGNj1ObiivYiz{cER2qK_@;dPlM@p7P9#pA zSMP-@4jpf;GwM%6N7d-gy#o*(${6`&M=_m09ZY-wubnPsHzkkV|C_Fpe|C!_pW*S& zy!Ney8XddqR)(2Jk}gQwM}hZf`BKvBEim4=r8;1yX%N7> z|74Xr(Ut&R2<{y!9gBw=gyxgnTluHqG(4Pmw#0SEGG8L3(|=|^8!I~Aexh>&isO>_ zhVB0Q&j`z{Vc3rc1QuzBwoUebX#n@lmTfom}zo{+#;T@0Y;Ks<$A}+a+bDVa( z6MIhBF!N&LJ#y>9uLsI!7{2yCy7=99YIH>1Jr?=#^1uE6f4!IgPyRsA|A$a`&`&7( zp9ZNkN?97sgI=|s)`pi@{(a%3C6+n0*k&78V*MAnzFVk4fXZhMXUPo2L+VG|xdlK4 z`CBD&!%ncoR^nCdpMWQJUT1~!D6ByDAdk&0PRp(>#J@q}O4Nm_?<_*EAcwAV#)~dd zpt}mv3DMDuk>B-=oo<4x@t-4h z!4!B;DWqH@FR@=8eoLa^{U&u~0F1X8Yci=psuOBZ*#hv^Pk0o;!69#@krvHt7UuWXw%DYk+t5;*(6}as;SM#OqGP zP&{NIESf6_@bqDCd6XQ>ira7t7 zQSzw3&E?O4G>`)CAJ_K^lihp%rc`k>yaNoFxZ&YMIm=Jd?rr7xvknV@w{!l@d5RJQ z=<$jI-0#ovkQ{3#n=rtexaYwMd4Tt(ga-q*65&wiqi55h#prmaFYs;RowpF*g~Vmv z{hT(Ig^stTW_`xMG5T}wWJHG&Mt&35t#I+lw7Yj=?Yk;Tp(mJl2b3BZeBl$S@Ds1Q1%8kA$%Yb z=lr_l-kT@r#fe2etMhmQ{XI@}2+^??BfsgeBxSyPw7WOgy+>6KzG4?A+s=;v;MbE3$-q( zZ;(P?VxNle7`8VE;RTU6=R0rCTCk%pvAHKqFP<<_q`M08A)+G-BR>m5`*sTp+Lzeh z50){rzQ?{|C%a^_O_c8d!#7AA_7ha;*q$EICLK;%V#6u$p5^<>PR6@w?z21^-p93% zE5LX^5HTU)&7qX+t^)8rbdAd`dKm#SdSA4?05nL$ZSyte1H3og=$y&`c;Djv=C#EV zY_S`i`dRe>eTfya-P+|dCWI%)70!NZ-}sj$wn(8k(0C91;mwQaxQ>zEgQ69@ykWF2 zv8&Yc?gSjb-rmBwRGAlOBr!bR(I=?W@#;*Mp=vT|{!gU9`}bQd6Efaxl~rdJl0)O6eU#B&dV<`cunjgV_8*Fdo4LrUHo*WnH^eQv32)%;z-t*0DuLu3%t&iyNz{oE_V#R)yBHHnu zyb_YUAq2aEG&`nZ^D=Lg;qh+mqfSRd*>aZI`y{->DDa-Xt4w;m1>W8wW~9ra;oZIE z3oDGbnnVNX{QqOatDoV+i7PlaT5Z%JKn`Ww?)-S2xgH(w2wz8=l_!PpU5I5CVjr-OqG8s3X{ zXnljf-nzClnuIq~!ugMm0Pl@vr}yh=6QD&u8n0@6iidVQl6nH;y?Fg(VFbW?)gjOC z#oa_m+uiQVp%C=iJL%99hbQL+!S$AZ;yCkcGA?_d*WMDc8q1!@(qI1{i|AO0k)L?t zc?seb+VLJPfbvQ?u+RVF1Y4rctKk?Q?=@{y>5%jZU&5XKZ~srvZT~;H#XH0@{Vxx) znzw4vB60<}=(&&@ng`uuw!Z=IK^hHY1i%NR%jB!ub^;ID7B-?WWln%zKn~6`;E3Jt zE0dM*fRv59+TH|s&~$gx7v=yWbnsF0@&tBt4{A|3DKym0gpWt!J{oWTDfbn9iPb5* zcXCnC0=nz}s}LPB82Rbvn@Ac>)879Rn$HXLJ7HIlxB*i_PBG*6|F|qFbtpuL>X4S$ zSR4i3tUPjoWV{Ph##PYp?y#@h2jeZ7agwyf{_T!qfHT0`@l3snju`dc0w{A$8;gkjunkd)ouB<|@Aa8K(JH2252mS{V_e^J`r{yw{1` zH%p2Vp*y_KBRZC1r!tVb+OvSB9nww?#CAJ`(Ivx1Iz{|VN zkQ$^Y3cQ&+I48(>o2@NVM#KBT>+c#c-VU$gNMCP7#3i+D26*3^$2!EamH_R`Gh3bj z&i}il-ppD6@Rn{AKIsMUZk2v?Z52llSu!~aC$V%CbM+zdm< zyES$}oms3D-Qk^q=%~TS@7UO^|LiB)@outXvbubm3ioCXOun#=gW(6HxcmU>baWhu zMQ(51Pk}ennUo7;yuV#IpoE6^=)CriaQ{DT=SZ6W-@MT&XaexghPni8RuiDGC6kxV zfsYf1Z8YNH25Icv-Yek%Z#C)MHlJriC~C)|P^F#d#YyBVD^-Qvlwa56+z)c}j#{3ie-4_C&`!*Nb=Iw?#tuRwQmSGqa2X z0UdARxX9%r+4R@{Uqp2HVdOXPtLMuyoDepq|1?d1e%N>4Wh!+1Ddz9n72vwNJ%ne) z|MuG%?jK#MT&U9VN-xOf#?{P!@Bd?jzhTh-vr%{u_nKQQ|9DUeuQr+ovGEI5!ydF# zwVdQZMujK0gn&Cp11+})TPhKtF1-&$MDT)CzwP2&A>cv$H>*@+fd{2u)9DFbMueg# zIBuslpjVK;&nK`J3QZbCB60FV;r98r&?`u2KGZICn2qi#$PPq@1V(-%Z=K#|+tR+o zZcM)TU^X7RL5h~^FA86p#_$aiPVfU&I&^A$kG33zm)O{O6nJy~zQjkyyUn~?3k~lv z=c-RI-jU~BNEPI6+`-8-fcH7CJ)LRl1gLo3x@U*M6}ugYtQ%mw59OWgQ-bmKXd0Hs z5uvB|ogzOUL&sZa+4^yOU?t z^B4brm)Lp2uyi<9Sx2xX)c)ObT|GcyWyxtmZdv$9+I^H_-T@-(bv(O#hZx9{482N3- zy-8ddNju)+{$Hxiw5b@7e)@hWK{t)z@s8e1osP2_76TTf{y&zP0&g~l{F7w7Pq?g6 zN5gx>n<)s!J6I`?G@OVT!RLyB{{IADx;iV^-nzWMXS@nrP8?cqvk1mJz;jiGA;7yi zM#)pgoe2FpwH<;c(D6RId1p$G@s!ad5~nm4wa32;9d9dR!CL=9cDlnm9MPeHk>92F zvS&uhX~$cnbL)Z7Ane-vZEcwokJ=c+<2}GlosM&kt&cMg|2zL@g!Uf?8YFHC4_crm zv6bvW8;-IqNAsX_9MdB38Kf8E1EeQ*cQG%|Ee1>MRM`hx86g6+YlN5U2^f&BQM23v ze}lwRRAdX^|JTSxoHV{hgaoIp4=u%`??IYHCU7R+;m0pP;#$gy{#vT&dyv7M3x3Tf z$kLq$twMC{#mH~CMSaPo4%$6vqx_QM9Ya*y|2J=wH7kb@rQ$gU0q0JG8f=&^ZrqzuP6ah4-97&21~5T zLeC%Y7o^sNWw-eN-nZ6=vfeTZhZgLXn^@b9j<@X-LH}`x3(tqdxvaYNYUUw2-c?JM zq&&(JqdUA!5FIx#^2;*JdNY_#JKi-f_m$LM#=am8ci3Z%u1YrJ<9$7XDjg3#TyU(; zBW-VSQsB*3ZP-9|Z^;c8bkXqUFOTbh@!ofqiFAV0Cy{vNJiz-SkI|HcBN=wF_dmL$hLAtu%IM~Xg5p#mXT;FMS(MO!&E68MX*7elr z7~&D-%_rUeAIm|3H}Ad7ATr*sxcBLx;a%?6VG8fw?mkpc`n)Cj$VkKyfcO27C(GY~ z%ZXioy*up)wznQzd&t0e=SD3P69;%ZI!xM&iiATIpVqUK-bBZn>qnf^THP6=awM)X z61O7kJUZU<9Ud8*#PZM`-k-kz(J{R3@A(y!)kYpULA!g~?%ds|QH=d@BF?@h&_Yjy z;qk^`a*Z=??#82TtA_8xg z!5+j1zCrTtbi|=~(42F`Og&g)PxVET`u|O_(|-M6iPbq96Bj%moFLtGaJ|@YJcRdB zkcQtNSzuhlb_2XYqIrGChEdsYNPj}<*vm3>56W@e@a*elF}xlUx4-%-^x!JG2fgFy zjTvHBr8^JGM0C8w$gkB;>7lR^?H<&1E?&ei8M}hqoOn;t(uwiU|Ce!5r^Dw>mW}u+ z`1}9Z`4o5y4JO)>msp|sPgkJf{nq#H7>u{#Ju?#C2WL4BbpgB=)yuYmeJ03)psdgc z@a79%*a5#FB`KnQxdz~UC1agscrSX9|KJtC+v~lo_bGk?bjURG z#Zerw@oWEl#_8XSbiUzNw78y*2e+r!>-!h2a~dlSb6( zaCxv?N5Plm-nCrG@e-2@M3=)^# zKk3K01|4seR?gc&G4%KSKOWH`gOT5=$1?8)ZD@CI`3iv|%Mt7WDXwW!!@QcA;qi{P zpiW2PW8&TqAtd+ap}<>UQ}Q7)-f7pg_0aGZVe6`e@xEezh=ljqJf8jc0N&r_$NBIA z1ZY@cT|^%Edh6mc&D-$o?Zb?Y8Y|e|s&OyB`S~>wlC9b8A>@aS_l!fF5=2Tn|2S9GWcR} z;~^C%NFz3H&0I6h@OO~n1nsEPk*%u2^Jo4qNP)M+bE`5k-Y>RF&qKp|{vFSyFy70C zoJe?k9}nfa5AbFcv3i#N&=Q&~+NK=`2Bhz<$(&RKc>l_|L6iU$8$o659 zL4yJM5_@+v_)fqcF}w{D=M(ZxZ2w=Lx3C{!%Px6Fe|X$26kJJxIB=v~l`;oXiVOl@@dC@D#<})j<;!Nmo_qGbr@dzV7xosnU+t(vxkF53G>M%F88+mOK%Qzypvpf$E1$XAKng#jsqC^d8B!BdtIg- z?>^qs#q&m~IGo6R^rb>PEBl*Sg)kvJrp~O40z36y{ZCJml(~th}9zb;XV&oV6yon>rop!vN zPI0}wTY|lNi(|XO0_J|{bv$Su zq+)+c4)&nJEIv{Nx&7sq9{BrzVvW*Ke;fgt-?}S)*ROaey`txu7Vw~D89nt;p#L9g zKjxQTN`ykBIGD;ep?eS$``3+TEy8$m+?oEus>=rG9waKfF38nHiS8yyGi-l!2w>#* zIiA_DuAX)es*D#}`_Kh@{$IdauWFy<%kUoL#rA|M9XZMg{nN3e36dBE-f~TM;>mdP z@`-Vy;eG$yT{Rf*A(N#fyu-&XsYe66J?EmY)_k#q^rM2O9{!An=2lpxXack|+hMPlhV!{c4GV~8ppd9zLn4~CN5TZ95{8J{CZ z$avd3lyIQo-PRHd!S3D3a){*KYZZtGP652{-~CzcTww_<2tAUaJQWY!IGAg!4)B(_ zS|eNz@OHdu%qb0CZ>ihqTT$_s*IU*c^|8BJB!aI+;$nACebfER>n&N=(i*qQ)8FwH zJfh1$*`~Md!#-7?6hP}NNT^(25YWDv?|9>l%Djlt#4j&yLz1|WlOo6ww zo{|I^?-g|i*wOIbrRlQ)#@kN(9trQT3D@0u0B`;CvDcL|EuoX%Or;Xw?yb76Q}fjT z-p|KmyPE;t@2Yi!*gT2QTw&%3ohfwpW>Md;Db-RGKa0fqN3qwg>_K<$H_S)d58tCd zyl2(^=xD{rkM-&6(^nVM?%p{p&bd5$urDWCp_8qzD>TaRvp2yFSEWh-Ad;2sDI^FR> zbHWMTgBoS3F2}y+#FOLJOv#DfF-G^G^d?#6RV(T51L-D2$3cwzT3;t|K5C-9L3%dy za>~yTdxpyLh_3C24!Hf=Z#!kg3K!;6^Q2ykoFAvG%{ zY`kaKBM+Sp<~K#-76^@35tT$`4NZAF%;;4P={QPXZ^8J=TVIZ@oqY{~c+aK@Jr0NPF4~!^!6rpeq+dmRcvH!5`RK&`#1#6g z_r`6qj#KQ4D$At6b0T&i}lF&|H1Fxo)94N zVc~t~qw-D|?}Scu^5sO~Gx36U5Z({R-)v=(CxBm~BadDFoe0|gFj8L#;mvX2(}oZT z@9Sx7tuJOGz>%uyHr;e=ycgfLv%a-V)D(@g67s0G3dY7;qHmGG=1RtUy+sf4F^@`q zf*k7A5qIgY-T;?Jgx(1n=KpzK8V5J}Fg@NlOHZ17l;THx?wz)^Dr)F5R^ z>Nu)FHE1YK{`7mO21WKg$_Ro6q~?y9)@SEo4@i%6$9=Nd1DLKx;&_yK4krJ^u0by+ zil2XEVZ0lp3J@PpsN~0OU)^DTo&Fkhs_<&;%{w&Ipak>tNxiXE|B(S^`j;nY^RZs) zv`hMV@(NOs0&nemetS{8^J0FBV&R?nX_vQxP|5GCmzT`%Ao^F3T-yXUo}=M<3kl-AB=*CzOpo{QV%mIc zD!tsgD22R&RG`3HD`n&?Q&RUR2{*A=@gj3B&MIencSOdx=Y z=X$pra3_I_Jx?0L6C^L!=f2et-h3fW&$BEez?qezK{hXaFc%-a@4e#E{un3Uv{~HnKov#DoJ+|`d zlckXaaE14mpyv?Ymy^eg;rYMA!nnPcAiOo41YXqZMu2?Z%`8}Iu<=&CkYv`V%wmeh z^)6g8QCo@wVgV!R0s7@N#0twf6F*qfC!C zuKOx&KAdtA)c@?>%2D90A^Z8C(_0zByM?jv&Uyiuz<9rz$tL5y@@m^PIS6ml+UJ7L z0|;Q&)_{T-o+NNw^vP=Y^wzt^zTTq{-Vf8V+fP4;09B^e>IXYuFHVFeeqZkQV>3nL zE;~OL?plJqIQb-K`qXtugyD8?g%Ka`sO0D1v7DPTlYYE^R=svJ<);35i+WUy*beQ9~Z zGx!nfJ01pavA1p*8i90Z3-jA#Fhp3+*#WgtG-8Mg&`5&=$wE3{#qpY~6l)QpeqriJniBv0!x694% z(pY$(c*pk{{=^PGHZBy#J9K!odk=*7IioWZx=#t<841Mc2}c)vWC&{=0$uc zP|0t@-RVb@2k7tr8ywCAP3u$N-s-Ll%af7BGyNmB{4{MoIGbJOrzDd5e^m;+^`m4~ zqIlPwdLo5|_b^NAY8Y>=o;LCa(xQCl`R#)6zO9_vA90%i^2e6sJ%sS~^{v z#K$!%`2}Q^`ER~WfAuz9Zu_fvhWhEPnD;O4AK1*w^myam(&pp53h+hq9JzX{P~fe% z22Z}d6&{clNgk2J!n^jX(LuOD3SBcsKAfoACFs5t!rQB4U6RU00(j18W-5p?33`hw z^gTSBFfI)-dI{k@Fuy3yG>-_5v}O6?G_mnc=-gGeppeCM9EsaBmTw;doEX*H>yy_dnik5@!{RunI7*6F4}x#>1(9Tc$4u~ zrodZQwrm$#y$kz1C9v?mY%uRBynD;?gudCEwb5dMhtRjT)_R_d`E7!Yx8%XHq0t>I zrZz|%`^(y%Z>rdM_viR+`aHyV+gs9zk9Sn^v%5P}BY1BO5KDN9@b|S355~CV+x_hx6>9{(t;wYASp{I?&^BKYaeb`>0E1 z@I&Yg(y+|iid(R2PFPgZNOR zk{|mMVf`94`fE^y$~qw-9_kY$T#L@pe#sxF|PKhT-sTKzz7R z$xqGn%Yn*|^sgW%6o+~fxau(n$N&80WA}He#IZ5`3KF-2HXqp@x39&dkXMje6nGmE zEy?%)!wu5S6?f#Z@UA}E(gfo@o~|5DuHMCaEnFbHT{VB<7q$?thiC9O1#(H8WgnO~^p2|A5BNAI?Sl#x zc>Zs{WP`><2yc;UjdSyM5y52e$C0yh*aOlhCBOHxb+M7skT^oV^3oT5*aK45I)$~e zF7p`otha4deL;Wqw$V7fdG93k#Yu~G+R<%-o=lIo-$B}ZXqnl@xaE?o zw+02?hJ3T+ueZY0`v}!Rvt9N2hn)<4Q*_xwB9B1;1g5Vi! zykjJ6MHOEOK-0EFGL;o+bM(*qVN#^hW3D&gvNG`U4 zUrzkn|NpZ*W!zst{r@708f5nEB_H~T?G%vGz^XyAYmTzP6Qto&^?`5=@)@??WeU}x zx(@=s?p!B;PIaMbyV#OIu?yx3@GExK$HRN0p&HZ?u4EIL4PB5{-aFT(f?b0yzw0vp zrq522LgKDGy}6SlfW3kgP@CU(=rZFyV#`n;RPx&u!1+~@i~bt4*HbXl`WOv0=ym9L zb{QA*_y5=YY4hP9wNT|x|F2JhH<(j?0L6QHuv-laZ(Wm@8)3XBLZpLXyn9cMq`-LJ zuF=eOuOfgJJIx%AKzNt6eN}?-c4(S^2*!J(APfGCbR;~ne5+bUBW{e zN8(1Ch)p+&uf@h5-EL@ z`SG5VrpX5ZmmVN@ioAlNO;`}>c?B`O}nipRE3zn zL9&_qK$8!4?nmuT>E!-jmjZ7Sy_-rX-nMQrDp+`D?MoGb`+v(&#XT_IM>$*iVZ7`2 znO>K^O8`HtS$>xbYLJ$y=&QqcS9AG&B42MI`s(b!XCgQ*c5OB}9vknvfv>|cmxM^) zkvPr*<*yI?vGHE&SRi4vLZ0F9evJ44spR)TX5@uaIsMhUc?)l&Bp(e2q_>aUe#{}r z^mya)hG_D^Z7d+3UPi9o3n}n6=Gu{s;(aidpp1q0;VZXeV7$wVK9bMgUMrZ@0U^B0 z6CxWz9}vLnG6Lle5Z<3(L}y4f3Iu<`b&(UDEyW<0!CAwGPlH_a+UxJpUqT_+jIP!dpo` zXfurWB3Tad2~x|&+Rh6hyxmycBJZ6ifa@QxaJGT2w^ZXyIS=DKmvA~7p8xA`__}YE zB7(D@C*IeV{tMpno5~|^zo_|*#N8WyJCvS{jkn@>#@-M1T@3enixuKyAC>$(hjve_ z-AVr=_Tk{w)dufr=>IQhy$xYM&h&WWbXL&hk8BBlRdEUjs*4_aI^koIJ`>{9~Y?PH;?08 zlbbUA{r~oyy3YrssrUcqQ%Wwg_lYungB16?h9(~?%4*Gz|Eb;v6nL*x-z16R{mmyr z3k&awU#f{P-sjtHlkwj4?#qkC5Z-4-Yu=qHC4l`OBy+bwx3>f|G>|VR&bzFkp90~{ zpUit8@L2>nkvi5ivIQIO=UG|Zd&;M3rjR%@qm|E_OtJAM^|G`DDR3}c|KEi8cts_@ zWty^_77p}R@0{wEd)4o$H%Pdu0GV+PS*FJumzznG58s+cc>-6-{r_SLyv@0XVo|*J z_pR5&!h4y!)Cm~x9C!HuczbKw`$;Q&drPlUd3^O10*DhRUmXR#y~P!wQ3ap9bstKz zPJr-!n6#Y5{AmQZ+cEk1txec?FL8MGfMq$J6oABCP~{dlY>bU}Lh{VX)K)=;!`le) zaga)W@dy0^-el2_x7pJ-nXe|OA8&bmo?9&baun0!?R!d>CLdp>FSe}7_}l+eblHsi zOQ`=hp{PMN_eK7>AdNqX)ex%&8FpDMhW8-%n4ThUv0E&9cB2rgK@T5S7_9wF00+{I z7Gy&!$g%C=@8A{WCXeQZET{&ZoxUDjstR3@cBFvU_7-*xx>qGE@Z|BEnte#zhrK2O zYffUMlL*k>c)}Q&mF$Lb%(bEa&BQ~t6aWNL&isJlF;Q{HdOM~PAsd=s5`7{Xcc^_x} z&vg*MdEc6rDL_~3B2}@jprmEZ}FJ_>Sic} zce$T{@zX{E=;`SH?kR+KbncO3Fy7%#$?Fb7c)#vHbYo{65$s={RJ=kI8}DNwZ*9)J z8!#C};^xjhNl*HPUA=ownkv|=`oVB`A3=QFrjlRAqu*vX|BL(odx-aqWYwtSokNiO zb!=f5)8pL}tU{BI?dd)7Pm;)ZFQdSF&BFE@DBe6d!TMNuUx{&Sg&U*^{~27%@tQ>LA$qkzb-_;cnkUAByu6VFU4Di^u!Rs_PyFWZ;D{!Egtiz z%}{N`F*84hnz#K%c0`RyTH?78!s{_1_8cja=+AsP-R zj*X1yuk2=eym1<1wD}P9QP=phI9W=8x8>&Mk3mnLiu;!w^#g21ykn07im>zFj&34*+ zq`eNw{Ih~IqrjWsp=poeeKzCDQY^f;dl=-vc)MIvCgaULW1;^H!rOeqOV@U8J8)-A zPlpeLcgcmGT6luATcRl>7Q%bmn)S-8>XG2+7f|H&J#4&_e!oqLtiqAdxGkyfYzr=9 zS8t`glP69%Fx~_y1@WOxB|qJ?0iBjI`tiu`P@1pL7WV|ib$f=Vcyg!3_yBz>K z&@}Tx{Y?n(%;sy`V7xC#`#pm%C(1MTd^y1%2^#GDbV=c$&dH5_ABQQ`j5AmI+-38NTZJTiJ}! zr)cs4D*4Kv`SW^+xPX!d4yplBN2-rE1BQz8?>o8zu)iu6VzSgTPq)-{Mdd%K@ES=`j~rRF{o zXP&)a40wUPI7wNd6ZCE2oC!r&!4SWEg!s5ZB|nZ1mf}UH=&#<_IRc2`NVOn=(mSfM~{+}WK5>QJ5dc;~%)SykLY{(4~-2XRm+OuQTAem)r z%HTUlp0u2agwG(Yu_MV@S1vNEC{WIi{z(8!8?w84p?8qx9Z<8>gKE%Q!{@wfpc(}1 zV3GZ_lL+4C>i7CFgI$AGg>Th-=?T4qgv6-_kB!-MW7nXHa9{t~4Dc_x~0YcyA;cjlqvt z81EN3s%%(zYk1cOzMQqT&LD0tk;3_4;5%9vH^LU@me zKDM=o@D50kP~W(M2!6>A+8@=5jkl6{VB3NX0;I1<-1?e(PQACV@iwzaYh}r2y!-#O z5g%4m@)K%m{C(;f{dnJ7@=YZspN0w2_)*2gXbYyt8+YLXZ9e)7XW%P#pz6Jv0&k~v zzsT2Hz<6&C16Z-}PPwO|1>?PHQzrQaDJ_E~OO+wKXHq}9G;!I1OWsuGl|XoB2%1a4 zcrTGR8rlls{XR);v0obz^d1%dkT`$i*6W>O zy!-#IBR&MF#{K&`xq7dn zzVvCLUgN=(q zbE3rcUH_k6>iS-{r~58nl$-Hn9Z2I z6HR_OaU})b4n2}lDBd{|X?QHWw@vnB!FcDqD~8_Kc+2m;7iS{OK|*xOOddy$F*=h5kBe%in z&e6a9Keg7IA^v}81!+T3gItPQ2GJU{uXimkRt+M3X?+f_AeY5S?}Hnp&kD6oyP-$y zXO~+hbu4zE=7uN%B0dSk>lgRKkJ#-W*y`P(8sv0~ze;q72zs)rKU@}rU4ycfy_D0! z#YkRA+$8tHgmb&FYfy{u(@R4`DhyYH@(>@dspRJ(TW%E@On(i!VdZi57BBTHc5pm< z+xq}>rmsOUFQRDjp<)@kEbh-2q^v3M-sU@b7sdP188IF#yxn=?T4B7mI2w}iUVnph z%NxSGe^$h79^MX&nVb6%1|)&|uk3Y!8>9sV?hbH+WGoB}_K}F-q8s~a@s8MdtIxZg z{Zv$pv>1sS>u+h^VSIKqDV6-xMY%d_FVT;8fl1f6vpMxg?AHTQ z4{dYHm>zGlC8{*}D7RE{aym$Ekk(S*?QHbW0mb{;)4iY!INN(_hh1H?xJmHZY*3GZ9+UkpeakEHB}2ND@sx!iUzmt*IbaZz~GCH#fvppm@*tL~>x^UDvr`0LDAV_AnW5 zhqdj6n;^Wkgj4eFeTVMR4nXXg{{6jxZk^ zZ}ag-m!l+wNp?t_*O*jW0LwPazYfN-ULywQ6&Mb0OT-6ACBJO1<`U7J^lxto$7DGW zgq~skT+sf`H*CUiQO`=Iuimp+97|~NA=Q1j{X|^O-~0bj02uk7Q2%d7QG+}RhX2`O zf81;~532@Qj+lr&hicF+D=-S~|HZhpLkFNeNTs)GkBZ+D!1go_+hFJh>3FG#G58G9 znLS4h;0w~0#)!%6=Ocnni8cI|C$I;k`>(gJjXoew+JwYCNV*=N6puY1tt__<-cSJ!fr@h*7r==BtYcSi+ZL18xmd}Q6X{~ol0 z+;X1B8$LmL(zTX14Z{1pL}1X|iwMwWRYTu~9oTqp-TJUDLsOiz9*GNo_K;Mw3L9@? zf%Dq3ql}05cEm?CmHgs_ZqD=gKtJA_B>YZVc2dWCQxv-^k4hBN<1Mbb%!3vm7P1*u zS5n9mBwGr+-4;vfqIgdwz8Ap4TW}reC%l4uee?x+1=*jF)Xfd8AaUmgb)yCept`l? z`*EoMPaa>>4dd;VD|jIu!n^5Yo=e!V2=L`I%##iJB6*Bz_5+`kPl@=fG z-{Lh_|M|SddJ4Q|9P@KeiU8-DeIE=7W8-}&XlYPTv>53(68An%U?TGS z7R*L~M=$pC#SzBaz0E^>2vEuIglp}$_2%^Bt+!n~{e?gE?X6y};`*|5ai;J8Sx4o9Qu$GiJhiSeRl8t&e5l1Tf&r^NJl<5tPg z=0h&qUme=L{rmktnmU^QZ4lJ|J5ki2UFUj5&>A#!beT9-4T_AvEZ7LuAc+lNEZqO+ z6+BE0gKCh+&yXzf#{`h8VE^+-sQ>T%)zl1sgLLwXbrt*#Qk6^Gy$Y#B@bV4MMI#Ha zCrE50;&@oa0@76^E<*FIZ#x_I7W)akXKR&zYcX8^&xQCXrjnn?)kQ{J4fNNbT?=%) z1No>wVsT-WX)){GF8SZW_W#50ek(eiCLgauGY$VtkTy`@?PJ?%h2ouJ$0CM>_ezc% z?Qs9^RkT>ozHfd5R6320@kS(SZ8}DOLvd6DEYcd?(w-6siRPs9&eYkbr ze){qDbTa!iz+R8Jvi=9C8{;9;qFzkj|KqI2LTT}l{k6Ta|0a0_=}3XMw^HnP6z_5S zH}kRZmLBvy3F94P>AxSw+vlfqIlO{&x%`7qwwVC#C>^Zd3*lWp^zJQ;_jCbI`WXms z|MLpv5qyzgTItn0L1(b5_cEfL#(Zx{QaTbhIo$E_WEM8wO%?{LOP{DS9Ns2~kC#;P z8{p#{(lDieg7jY8vr&tM`UFXB+n(V*jrUBCchN1aFSPi`zTQA6NFZ--IZ)ue6VSbi z;{7bISOg1i-WMq@Fy8M6+@oQ^N+-2g2KXg@-#loOt%3 zDESzKH~;5VOI4h8x3+Y+(y?i1Uky@;g7aCna( zJ_f1emvYNpeWxG&)jQx*CI8_f>gWG)F2M~ypR_SO-Z<9cMp}GS{{YQ8&XB9OJq6yL zmAjHryd8MGg|YDVaWx~)-ges4H+w4(yt-tDGZIX8%vFAU5*zPJI#K491`?zcB#y&U zTlPyTHr{U@?l+JxWIVhtBR<|y$q#h7(Xm>W{_1VGtYD+b4(f}O*LNOkYrf`Vdc1S8 zT6AdfA+p-8@LSa1`TswQQ%3#;)cH{fXOtT`Fn#EA|A*JTLFZ277IWd&Dk5d{|M*&$^+m?;|(;HOP4< zkCWH|>NUt~{f;%~wY-_W21P9NqRB_c*VFikd`8GJEgp@N_JvzvD-f~ntJ!1@$kkQ|M9VrN`C9Ee-$6r zqkjb{YIBmaIDq>0*89@4|iwX9?NC@v6t3Xp2?~AMWH7B9_{}O%!t@E!FYRon@o{uiU2qF z>Rat{!5)x`TF%r&P0Ns6khp-88I@%#uoovwcAEt3Hf21#r4b({RPx(!^z5XTH2rvg z%TRjri-U%j6A!)%8Cy5P^wk@;Vwxr&pIzRZ_9!6t{~Iar-hH>?HHtS!sFws5-ZqVw zlwiE8Y_rICTkP@|jEC?xbD#Vg2H|~dl}j53^!|TD^DQG7Z{H7m)iB;4Uj0l;dmI6_ zY#ZBm&Iudu%k`<{(_S*9H%Qzs^K&=uEXBq<5^vqL{R-nPPAU)|F;w#7ywvOX)QNt) z*Uv6@V>hFIdaFWT)<)fB?NUZ=18K?4Wq}V(KF+S|d%ZmM@B9C>{7nDnF;M^SN>PKt z{LQk^8dSbcS_!KL0Zt~d@Cs5i>nnMS-SOOUi=|KvN{9s~TdN3Q_Kh6kdqL=mU7LNG z@EN4z3rvFppc-^C=DS<%01@0TY4YLzaR`6& zPyfH20`EOb6t|#wKUzPmfQ5I{hnHC}-h8EMBwLM1=-V-vUEZlnJZyKM`J=fE`eM=WmDiP*6C^-Pa9E>bX#79WZ# z>iNpKT`N)^aG`tS9csW8rPpc%3}|cjxye;~krG_nIw)chSr7Wo9)5(Acqg zCp(0i^)-4|Jx)|*U^cknwKIa+*- zKOa2P6Gg^*8wK9M0~yUI-iIFM%3kKLud z_QsVdZVJxtVg9qXr&Ve4A!yA0q_6gG|NlSl?P*B>>i<0{YS2EPu}f$Ta!?f2z^XwW zT9ujbBNkLwB|l;xpJ9n#2R&kqt*`5Hmk>ZTp#70Lw8dW6%C!%^L8`N`I?)k&#NOU} zE7T-0666qy4N{cFzJui5gyg-Rx1uB-B+ew@*L(#&>^n%R#x{9$tY^G;kU9|`_o(C- zBpT$vbB6vJw6yV=K?yhY`9IFd_*Bv;p^6qH7&=CCIZZxnDrXA!<&am99u#;->X_G} zcz-PKRKvo1@!MAiV7!MG3Xt)3-PxOs=0R#^DFMtm4@@OO1JV$|_0}-nmx-q? zI6-(1Jx_PUZH@%pCeQf39>spdZns`;yK@b6y(JPSdBiWIwgdYS8$bVc!|iIu!`lP# zkxC`MN7g0Dmag<~Z*5nWv|l9t4D%cXifY2ssP?+ukC`6t>d8o&e7H}w`}Q0pA8&D| zz?;Y)`_KIUNy`;gEWCetM8v^(H)($-@7~VxvM+(Rx3Ybd68BvpfUm+x98%En7B0sN zqA=b%T^GAHL3l@{e67y%B!XT&8>SO~U{8>yLVd*UJQpMFM&fqGMqUW`h&@5FXWcja z&4lsZ|DQ#CY^IW*+7{d%`2+M<@7Z}t@>Y}7kGHV-S9ZuBtz>$d#gbC?CLUiB6$3r(2{~lY`h~X1WmSwh?7nsaRCdv^!9zg z#`|vKP2bXwjE8qL;-ijAez{Vs7Yp2{AMeJqB7SbPe7z+-JWc%2DW=C8*Y87{k3Oa2 znt%HL9Ta%)Jy-nC{Qv$r2W2e0cU-Rzf$<)bzeUDd>{hh39)$Onspy45Hwj=<-@~2y zLP=nEJogD0Z(9}XliMJ?N4Kr3xvvrlUUJD-*h#`(oET-@a6aKCLArv(J$BrkI==CT2LF$(i;k^9IG!{H${{DX}i6$R6 z*he#U%KrBM=;D;2{|P-}cTv=!xMQ~e+(B};L{Jy22Dz=+*bLu6QWq{mzJuh<(zX=1 z|BvyxTy^$30jwD5GrTsJ2V|5^mqpev>#j*3tXDk#!)3fV^lKQF#_dQbqn2Cc{t z8$6DiM?&M4OU5OePhme|E893$G#!>_xB;mp;-i{MeoqZwju#}-UxQd1hU*{GaK(5o|MdSp6nMvKcK)-y1zkz6gN64=32yQQY5e&OWV~%8 zl4RFIc=JA~;`{-vAmbFq6T5#Wf_GC)m%(_K)`djtKzMik79PL11$w>Z=WvzJ7wi>e z=JS5pOCiD}{Oq4N;mX2aW3AYD>-f9G$^BxyD|T}bABI%&6D7?yS>B}|Z{a(Y6MeKC zkp8IOD2v~~^mya!Y4j0s)fT>D2dduQ6nMw54Btl^q=4p&+E{p7synH}D@fBlDdg)d zrDINgfbqV+?ab!)Q2)QCxftgQecr-(mbhCV!h2!mX8vUm-n!c+jvwnLg4KD+8#BYP zt9P5Hl$y;C5z<{G?!Zfx+Hg1Q6{Mncx_Utb<6V&6f%wp*lAlZ1`nlmf^y3{Izo;vn zn}!3@13{BNayytG@45h*e6-bWEx+}r|KCZ0cXZvtlPKP&?IX0X@WyE@cP2MTs+-9T zQm4K28~Aujn3-Xq0knI&)BOCjH}w9$oX)~S@CE75Ki%Q7fbh1xR;KZ)g9v`G{x)0@ zij8*$hf&)KDN#}v5~uO~$cE;xZbRF#QE-jWPgDK2D#>cm4PWZ!ZeGqfVE1@3}7h@zxIByO?QoH;%O8*gKiulN@=L##=`u1-Ki<4n z(`iIn?%vYsQOVy>dy}F2Kw6S})J>ZYNx={$XmRrQ{y$oNsQ=>_XayNSQG*UxA9Y7- zQ0k941FRZkHYq3v_y3u^1o9W8!xf9JorG!-QPj^RxrYEse>&gNJCg{Wmy;idYtX)@ z+_4*>8kALDs`Q#A5Eup*S3O0;86+KxAKz#7nSTZO)`%t_{sRvW85WW!Nd6Rf zC#xQ2L-F1t_;N88-lQA7CNSR0@lVNk`-q3^&W7-AJX`H7`wp5QDRYU=`8z(h&-MV)rx>=d$6P*g+?3y!9HM?yhIR zPwe(1K2}i4Z_dP-J6)6h`G1qtt_@#2>Z#8E_X(w`vH?|0k2kwQEKNSn4X_EFOC`_$ z{V4EG{ABEf;@wbmY!MdT{$buOFy1<|>xl3LX^Njq(_$gKCzUTR-td9|ayoj{SwMK- zzjp5t-2aPI>!~h<@a}ne>hf0T^%kWz4F%v|UT;afch({63O7jwiF;hWpfg1a8}EI` z-^_yWan6z@IuW_nn7^O5iuVZ8Yiq9ftz4XzjyglBJMEX6Z3(EQ)w z=m~`;2ycGYL$?=0c!xGVPZ5Xkj?Ai=Iay8w@3Jdg-mn@Q@5e5RzVlK9Nwr8^Wx~w! zv443vasE(5FFkg@CV)S0*7Y<($6HS8883w&u_I^d7Ro|+ z8xs5~!$?H% zCBttl#lrjP=xb<4>9X1Lhk0bYCm)jx+#$TzhrFv7gTCHs`r*gt@!3Q$^VqX)xc}El zpByuQ@ILuU&hT_P5j@q_7O_hX8}Dtue-)m*Jy}zX#0`#I*pK7H#(R3y*7<@iJHz1} zjQ9{A`}h2gq@1;x8=@cYwF-Tf`?IK@|Hlo7xZO2O-6MO=;q5J>jDaQ3ps%-{HaR*r3N=U*&(dPy z-CK`&x$)~Dyl;uzFHtjz1T6=vpD%uejdytA$&E(FGc{|FIPamZkD9gEcuy5=*gwCJ zi{bE2M|_B#`uF_QZLVGG{4YL`COGc@^c{}+?k({F#e4PjMN6>oW~$(o>DBtwRLRsvncsBskR9tSR1)jraEPhgL7tailLu+}0%}I*~2dc)w+9 zeta`afZ_1=Mtn?D$*=e#`}Hz&`nR|C+)+?G&GwAya3Z)N{Pj$kcoieBt7*y2p3jjc zAIr5jsk}@4d;dQzKhytt477rbpr}DPfo~R~{r_<7Zg#91^zz1Hn`clBQhzzL2d+Vx z64EsuPz|b6-L){ioB+mTtu8Z}NCX9lEG%&UudB2$L;|Woarf|zwOb=W*QA%cp%d6O zXm3-O$tA9y8ZRV{UBycg--TU+_yo@;>*tP{{Lg=$|DOcTAU=$#ZV+slrf zg7MzKX1N!}yK#i)qZ5R;?n>#QT9Yo`)H#pU=TFy06&E!V z37&cO_9ojA?CUMO4vij{ogJyUfW-B3oLv*2jD5XD%5eqGz8oCGJ!1DEK2B4~Z>R@n z=XrsCyj|?9_{>9TINl;2U}Acrh57N8_NU3mk9qgppHz~Mx9p|B`%trn5L&&@zZzh{ z!g~1$hK$ytE3!TY)2f1J8W|XcBa~*=wCsGb=g=J3Q=#6l+IaCnp&AM{SDGf_pPDHhn?@*==E{r0cjWo-Un~TTA+Bp z)vE%q@b0T!>jgJRqq}{`!--!lggcrL-X&eUZBEY#V58dCcpd2NtG8%*1kvUrS?5T;%ir_=|NQwg@-LwNKboQj6|A_;ht{Cm6SllqHAv>Ivvxi7h?TC} z5Ck_!OMC6&lb}be=`|L$?O_Cv*YHg>FpvlisQ##g2c$XaO@JD-f-IJkm<;eBg2t&6 zTjZy(Yf!Pj{P^z7ITKSPPSjfO;NE|^V&{et$KdRHUJ|4Is51~Br>NvNOJp^$FQfkv zJ9}0q(De`v{eQ5((47Ncn7;9-}DCY0~KU>k{!z0JF)+U;~g4{=e_mRG`w>P z?JgK^_jUHcaP^MWc5#OXq%))UylqklU?8}xUU)bW^tx{40OS3Eeg8*I2=8wiJ?xDy zh~V^`$BfcWY`nkdZFsrn?x4vW5+~{DaKn&*jrYFrlUIwBr)wCkdf!8Q*ip&v(?V|* ze_8tb|2tONuUWOIZ*MJ{v+U8^J;C&NH;HJ|a{nJmfp^~317A_RS3Dqb zV&NS#t&|DlePUS;8Smrbu0>H0-r=ccacgo3VB3$$AFN*z!KVw(O2K%~$eozbhVZ`f z{GinC8X_p)^J{puJvQD!v3`kGqs=BNNZf9bqAl;1VdFg=$F_D$W+%hpEsFR!MJ2x| z&**V=8~Ura!06d;K3y~%kWOioVZS!c^myZDOKI}4*jF-2?-03q6Djb{4K;?;pR>2) z{RcR(@NO#)oP+UhX}K5*SMR%|k@Eo%-m7|!oIG_Ay57Rkb?b@IM6h#DZU7nY`HyCl zAiO_{|I{3ai3FALW#&rVDH|(eKocH!H!o9H+y3b z{Np3*^}pvQ)ABS%x|V*tw@hRVS#wgyTRL=6k_OI<>G8Iir$dvElbeisRtWt)|IcWv zng5ti;?@KfiW*e3BHIkDLCRlO%)_cdg~j!T@B~SxDVse1SGl17I3B7&tVibvhhqs~ z`Le^7``;&mfh+kRs6&s~^n3OX`rsAh^--6fS0lgxnQ3r`8Fv34FSGji8K2)KXdJJ{ z@`EcCu=gNM!{@B8Xj94WCfk*dVgJSb|EAIdnnUZT_y69@2G~wKV*d00 zHi!CX^0C_}K%6rLe#9mK6nLMMlAlBIR&|{(goXFT3lo#@BUY#(gZzlS$>9vgnc2=am zg2efT&0DPXh57N;r_G1Q>ha|d_mitPjsoxFM?CY;>dl{6%8!LNJ~z)3##_Z|Il2FL ziYJ_hhZE-(*^f1Z62Jn#pVsj`iD2Qi(rNho|H{NCY4GPQG7jDnbKDULwtU~KBsGJL zw*Y5EcM=P$DH?YxeBRKxer&w!#?o#sOJh8|*$^MqRPwX58$JDC1>%dh3M`7pk%)~laQ-rm|zf%h?QV_6jM#z%*>n)KzPr@efNFjPXGy%J9j_sPXsU7mvoSa6H2iLDiGc>_EXt!^NHX~O;d>m zEo{7Ry7RU1<>O6XA#rY3``vs*u<@QrYq`Hghw&CCrHGFaD*2`N3GZ9^U%Y#(w6XrQ z_c!WqZ)q($cc-qRlj&z~AxXZ~y-v`)x-1mr#SmNl}B&X*?mnAPuh| zH=bN7j#YzXY@)Q_8nke+6L~%sDIq>CQ^{|U=hd=bR`fSW5E z@jiNqj^4oFcN2h%Z{dj-vOG*FAO??F^2%J(seS!I}w_xQzNt2KE zr{j@p$pg{^HVV8?=T!utc&k*L7s0~YUvx$U9!``-bCHJ=w-b~#4nufr{j3^p-b(=M z9uyX4wIzZ_yLhr-yw}+6Oyq^|ett3ay2Sbja0{_FPp%ys??V!q;#_s#O*SKO_>aH8 zW!=KYyDxDgYvoGD!+SsC<29B1Zg2B29=t_A-frs>-0eUb4oJrw4nLLpnCYuGuIM0b zJ_PTd*Z8x0%SwUwDfcU%P`qb(Lxi#LHfTH%M1DEZHa-mQ|Lc}7(Sv7i<*J6;&L=?c z-VPUeK5kD0{jc5DhVj;44!jhC@E&}3_6YmO2=JM*;jUzV?6r4%E4wU9>5NG|68D^~ z@8tnI?BPUuQ5piCM&(_QXu_!f9YwITX>&(^^R#77ayq|VEX0HrVfn07}j$9U8MqC!f`us}#qWqkEGkl-(A`#yGmc2{}u?i?7VEh z*hbj8*yuk1-t|{39J<`7SIup6PPE!%0J0Jz~9c_z)#{Y=ReJ# z!=J<-&cBP_nSVWm0P;UR7Ir|an9ttyR;meb097Wb2a|zhR2heEYygr_wOmG*A4o*i z(l6i=AOTfI^{M-TcvLOP^6UiSP-VEe{}>R9Dg!0XF(3w2i+;Mk1@@y#zol6ih(?v( z(R@)L3RSv6aXr93R4p{#M*<>IrNef_93Y}f>($<)Km@8ZkH5YMgriEsH!m94iz@ZK z#BLxARciCsT?h7{N~POo1_(u!^7&tEKnSXolEQ<5U{onu*cJgns8SG?c?krfN^VTB z1PDNtY?Glr;EyVq%n$njKU6IUDk}qgQ6;T({2Z_wRgzOj3xQpzlDOMa3;3W)JXa?l z@J5x`#si(ePE?8NgyjQXsG1KHrU0I(60Wyg2Y8@r-W#0-fIF&$_ADF$+)yRxw&4Y^ z162b2UxffyRPi-!eg|wv6>mr3Gr$E^Jd=m60NYT-9j_b(IHQVdvuh8q6;&Kx>h1tr zP{n@V{4TH=RcxVGQh`mVVqI5l3T#9bi{ke-zzJ3O0WT+D1FCRW9^e5-MA`j5(tZMP zK-I6~JNyBARLyCo-3RPYH7n$&0T56%^Q_Gnutn8$Mr{YM9#ucQwI_gesG3r3mI7>0 zH7QX12CzoeMEmbiU@fY~uZb!GYfv@jX)z91p=xybDsR9NRU@*ECjkpoeeG3C2Uer% zOM~}GU=^x9hwT~yR-$Tn{c=yh992Vn7pj33s2cck<1Ao?s!x~M%>WQp{SnW-0aH}< z5msgZCaCI_;RpkaQPpENyBb)Is;-tXQ(zgYI`dyH0G6WaBf+2!FhW&_-s*$E5>$QQ zzG(*-qUv4Ud1t@?RqdxGyn)52YTJ?L4=h5}+qF)TfIh0;2o{(DdZ>E!T%jG%Mb*m! z^(tT?s#^WL?EoEAwJev<1+-DsJa=p(p!JVpyCDZ?qN+*xU_79Ks^^wDO zd>^VJbG}r z7f|JX!O;OYk1Dqa*=FDzs&<&Ks|U`a%2lTG6>tVsE}y;z1I4J?_ISV!IE^aj6dya_ z6soooKE?t?sM_LXn+u#o)uu1oZGaP~+IXK+0VqV3Q_ApK;5e!_L}%{@j-krY-m~tyhL0kcX=E7GNfji>h_FZ;n6?s;pbfM}Whq zT6=L&6Uau@n$R0pfkUXWGIa|D4x-9ZTXh?dg(?f2M=6krs#TTg=|BdmR_;0S97so% zxq03!kcO%inyW;CR8)ceL)<_LqU_)a7r==scpw09pbFkU1=vvqZ#MyKsDit5fE88n zIaz=ORq(Mw06-Od3Jbua3O=*~;7|q6`0>9{1;1^J|Ai{}2s|0DcBl@SR=wX;i^i9N~YU3ce8rKZPpz0uB5ms^I$u@ZV7d-~5fAKoxvZGJYIY z@V&D5F;v0VaNahTA3+uT{V@DDRKcHH!hb~-{B;`q7gWI?^T2;b75wc3{4lEE zuaM)1a5#Jg+CBXJCo}v6kUu~Bohw-LfRexW|1-g#88rXrqu7Il*Er}Nq+_YN4AvfG zc(8THQ)r95{Idx83{r%BnYPunMP>u#4HGKR1WBQ&)LNt|5$ws?KCA%kL3VG=)7$~= zK^~7%2?(+vf?erfKU{l@y$5+iy#p+r;xI+yWLAhB2_|9hLGrl!8glIvW4JxY62u2P zmHfQ7S;Vx&(Z2_|nyV|HW9}*D;P@W`91*G4=peDR@y>G7^;dO(v8Ab4ueBIt@;sCx5I z;0<@7DBh1dA4*~2eM3#Y7si`YRfmkXg`eP(c@W+(z{iwIqT{wm+Jc zA-tOqULx&S%RlGOhUM7NvW@jDX z0qKxq=t&U>Z~cTKq2a~|uwtX`HeDBNyc=`49haH1m|jKV0#|7-=rhB{n{Z+;i(UOZ zhQs?I;$tn9{0<(wEmO0I{^~8U^U#)i1nSlM_S$7DZgZ?=`t$#5iwtS<;h1n%+arNo zy}2mxhW80kyqi9|OJL!x*`PcO;~l-shKzT0@{X))5Z>NDmqo1HKmZpR8CO|CXK$aX zUG0JoCtmW~uxc7Qd#kTfb=l!@1Q_UTR^{e|jrVOf-+bOKoM`|O=W*2}w%Z6B@74c@ zy*Cf1a&6{dC+o1#|w=7*3R4LqZP%E+35T?N?DpCu}6fkm)L;$IgiFfUNL+H zxlZdeRXSKXm?S$7la^RM3cTUb9~tlVym3i1ynlbocBlh*e?Hx|6UN)#OQvlF!21S& z2+w3R0b1z4+0e8;781~lQ-txZnJM1t4)Eq=>Wh8#g$U{VxYoHX4ju18a8&(rF+W}x zi95>q^jY8@^iS+^S9*TBrY}i%c;_QJPGjV^$28Xeb_wkj(i9VapJD?Df-IDd$Cyyb5%d$K?h8}DHW%{!yx zmJHt@U6rOzhvt$53BD5~ym=__h7V_u@t)g$SON|2@lgwFxIt1l`NR*#JM>BQ;xzzo z7Xg>8F(Cv;kft}`}J1bd6kjL zV`dDGH*O`BIuuPxGJW9ZEn~PT@P){`b3Fo(1iZ*Hb->0V&wPb{@z&SO|-jreBf*GY^VXVW_R%M z^mvwF%J9XBK3^bJI_$4@$y7!Bd;jmhdo{ZJ8FdPgHXdZMybC()i zL6(JRkQ$`5!(OI!U=Pw!?xW@0DFVbP6nen5E*3iaax6pzcu;ds+__s|53=aPk9ku> zA{5yh>DI)J?m=Ds#6eY$W%y_$uCCN&)xvM+dyp#W>4Orb%5=BHzCd(f<=3_P{#O=l z+Lzen%CCRy*TJ43eKU{yG*|PH;XTN|K7lG7Rr{JDvuslTzlZ{F_y92(@3Ke3@@RN# z>}lhN@mA8fPukwuztbK|O-5Y%1P11ptpTU#)J~bz3 z$D5_0_sjVu*mytCVS$)8Z(;ZbY5o9pI);uJN=Snnq(E^ZNP#!}i3b_)efOhe(eQqs zw*EPcx7&$Z+u{D7SuoaX9N_H}_QX0njR2KAW)nXI@a|Yt#tRQfOEY;bctL~2T`>Fe z`HN8K#=gYcXS~qy{%IJsG3=ly{uUCqUc>P1150$gCsswOw6!SFU2*aQ(Sem;@nUAT z%qH6LUNg4kSj;o*%ZYI+CC4*yo(zvS&YemfLpxu~{`vl2fC6v$n zrd|T$-Mv+ugm-(-%?oUx|JTvgsOUaMfNYFKIvoqvZ;=R0|2O}q%YOgAlLAYuD1`^XUu}{- zD5G+@I+_Q`;4_n94-!kr^oEz%;bhZVb+E+B5)>`>f-82mRdIW)0B4X+=V=wg4bs|A zHhuM=f>gWcb}y_n42mAV_o8VH`Wqw%eY1+H-WORb{#RY+X<=Q@$6yy$qFo|St(Pm2EV zmO*r2W#? z^<=!wg-TS=@II#aE?MwQo5(-o|p$2S-ap@%=~~XQXhVJr6qGac;BUMRD|pw?3i+ zE5E>7BK{jjXvcegxagLMaqJtUu1@H!C@bn>c)VZ5>r5Q$BB*d z=y=DNK3>Ung8uN1Ms#51cck(zuZJG(#Yx~Vqcc3|RP_H6EZR=ejf{UlnwNt*9s5@o z2>b|-3hxcAY2UdRB!q4XhuF>w^TQkNYq~Btn-oizguDgcw zVtDt)saa5^qg>?C!(HI@mVe*>|97)Zhd+bsH*!FNBAJ?PNh-`Z#%WU7A303MKT zIpI#4|BDHo@i`AF$j@W%uh$zBpjx}n8U^45srj=v_P|^0LfJt^@Ha?7Nd+Gy^NG+K zgJTPR>!R;LM&5H>Ys9h?KY+wZ=U?(ymq7QRDb~n|qwb1yw+9)9=)lTv+uS$5*4MOq z(37$+Njyuj`~U8oO;>cy_c6Q&MMc?Br9(3GUPWsXssERtz#G2IjEpz`iFPeCy!*SC zGQ)T$qy&>1qyxbzK1bl~t-bF$N>>q}>}xM|+j?W63C^@B7;mZeFY@q!^z6-te)s)} zP`B{aYFlP>ysfYLiJByd;`@-e2e+Or)BA`%LAum4f?wB5e-k7tL`N}3etf4cK5^lr z9q$K$na^T6sObN9h!uu#{$J4l`^!?LW8snCJRN`fe{l-D;oJGhc-v*?tU$v%BPy;I z?*FrHhmy9p0=LU8-45_R@OotF8*2hIJDmUV4S3#iu4hFgJpa#?S8N;tcpv^`aIw^x z2+cHS%{(4OACT_3*->p=xeSkc_9w1trzw+aJ38LXgN=3^oGNtZ-n+;;F!Fn;m6woe zM?2oC>mROg9meke<6=h>Zu`Auc=u+~o}fxcyk6ad-egk$FGhhkeBC4&Z-WO1HPP@6 zB`O?(@jjyINg7Tl7lte}0C-=Y$Z#ofB0z0{u1l+4$3hurB>5Bp-mB9(B>Mo~w~p5w z)pR35)p;8X+{V%IR<0Gf`O{Pk{{)Gf>o;wA)rpR`(kedZbBXkaw=AMV5hK6gg;&bU zPSTEd*E_4ki3BS8e@nrbr6X?`9&em9A9Xrxs|;qglFt7xqre-!Kb4I4z+wXpG`xpC z5#3?Dn<`&>!Lzr=jjDGA0Nw@UXO-YRUPO2^32SBsdf{`LQK*zNzHDS`f9mcoPJ8>C?m z;sfvhjcwk7L-U~3_cp7--yoSynUOxRPPe7O86?kl=5iN6gLLv~^9`%NG)R?m_XWPj@!?M+arU7J0V;oKkXDN2&bEjy zr@IQW9MOT5UtQd`;efNWd(g)gL6K?^?EatKTytTg%Wjfx?Oi{z^aWs&sHVx_%E% zCE+bafj9hU1sU%$9xpvKya(ch3ShkVOA3+jR_ohf48PvG?hKRiNj(A-mRlEd5A5Cw zdwt&v-~TuCqk1nVz}wf>Lc39n2tDBzUl?)~9q)q<(L-HHi}8&}+|7*g@h$1-ct>0l zk5QkKr91ZyMs$Q@M9Dw% ze@P0w;a6D5c)Q-#(nZ7j-j*DH81Gk7x;}7mLg;PQt$^|7<{KK-0pH$E@#SoO8w>sJ zk{E~ae(TN3$pr9D&d=9B`U-q|EAa75YXJIiqV-bo_T<&V_&6kP`V6c7ZWr{~TQW~> z@s2C;M1HW}6QG4(R`tC_JbIyh8&pWHgJQ~9=#**_y2p%SJak(J;?RXna}S(778`qg7a@N;6VUyMGCy(ht; zKR>)@Kfv45L7$xoJa6&f;MaXO!41+{K}@{x0cqUcXZs%kycgBa)E3)?Ld9*{nWEqB zM7^2RBB3NlUvw+;pWK@8|2H zMmSoi=>NCXx!pf%UrrlK^cNjz@Qf-Q^A>FjS#LzbTY&;^_@zKH-py~n&qKqzmzhHz zo*&TYIl&ZV~ zns&Uo_>MS!Y{uTb#kC)OF+28*;qk^XZ|a~%$ISQPjB?Rf*uCW`@P?nhB;!5%sEQd4 z?~`$|tuWrA_e)5}TM~C&cohQhHhnP^_`#6?Da$b{M0UnPZ;Y0Y!>6~bD>$6K1H5a_ zY&g56F%;6~7!471LB~62^Dc?ye0+F)B<{?}8lxY0bi6Bl^mUtxB!Mvf|ABhcRgmnzOlQ2FH8pDAA^*&%f9)9dZlOkpkEF0;Ml@+SAxD8X z{FW;j@11T(nb7dIYG+M=`~O|Gd8Gb-TjKr3Fo5@bvrK~(>j;p6s6)0nnEwkoN?O7F ze^CfNPeQ`Y$y3~`NHfDm3_cigi8CSiz@mG+zx4qR*6{XSfZnCH_ym*EF zZg0Ja=xD&mFT6sjiI7RVdw=&Kj7fD;(f_A7A7!^wXZ-K~FW69}gQ(IdbMy4S{+}Ui z3@owg6dnY>W=-}WS)%0vG!Gh$|JE))7r26)uf){$`Z{=nB>ngqha>{T95|BN z&=U*2d|=)OpFujhOH%wHSYms;C#%0t5TWOGd4lan(DxvN3twIvmy^SHB5^@?-^zX5 zhrS0n#kGH+Ek}p$me?Rf$0SC6_w_0?p6Jo;L2*Z~Rb_QiQ9*W{)l!>xm+|)?KU}6t z$8ZvtnCcNygQP}*H~c(18Sj{l0$gZ#;~rjL1>>FAY2pgwEuFsb%@n}9Q8hK=Wjq0z zI$H>7cgI50aaJoy-~aDEwxkl^z1u~`Ij5QkS-!ZWXt4<$?{NLo*OnH`;H{Ck3VGrZ znU&~xztcBbFi%dK?(jZ<=;+7D@1jPGbkPj$c%KuIzGd|kyMnC2tK{xmqrvbEQcoEV zRXXes$}5PZkt#@43cTC=c5EQy{Y~c+2O8ejU9W}1ct2}Va)a?UJ@;UTAgCbuKXFXv zMiHRpRTD`rUEq03NtX*S-WD-An&K;r9ffgSQJ8$#~ayUD6n02o-{tyy3 zY`&hy!wS8EY&R{}vz=N&cX$sWI@&PuOa9X9z$#BW-ko;B51$oapZ{03R`y$6V9M}# z_xXrXrK2gIbNBl{ySFM7ct1B>o=(PlVbdLUG`xLErS8FayRpe{f$`p7%oJe+@HQWu zvlXf!Z>z(ey+w*CT61j(Vffiwr2A5;bR?HpnL(HT_5Y00|7%ltP|xFwE@TgC&@kdh z^Ps-X!mYJniOsFrxfxz!TLrK9a)Bjw&siJs6W|7EhX{?-Ch-0L7TcAfYG8?dmABzm zG+1J9zT+sBY$QToHqW=?*oy8!MejQgd#WnpCy=<3J+&i(Ytb8|yIxL_Kac9uod;b+ zbYSK8aZ63(CqddhsK8zd|KuYTdyoOV@k&MW^%#Q5zb45?m5vs5$k-6vK?=6Fv?%cI z&J!lxAPpaHG26k%hlaP$dE5&a?^_}vB)kivxqsjQ-g<2dQ>8KpP>mqVoXn$?Ub|Vtz#E_`@LmdpLBwPdVI=yOE`U&p_gy@Wd_&8bq%kNA2YM z+J5QLoqL}|bYSHdeW@>Pa31Y=b1`vk;bX#{2%VQf@T7!=8-3hVf4K&L-hK*qCL}5AdFu6&6iMB|sY!7rwRypSMKB zh9<+?TZv`9Oz`7Gd#>+1Z{|US934JpXHBB_|0%WtONfgU@UBRlcux2jXAe5wAEeVC zT@I%|yps_f?=kX=@xOUugDLHJi+B8RDc8n6y;YvpcldHg2gBoi;Z`qII#LhB1&RMD zPBbX+?&LkWl8kp$RK!9wy!V+dcn9Ncaqlt-Z;!ky+v@?|L(xPnBXIx!t!*rs%HZR~ zq}!3P@a*lrS^l>t0Ppw)ZT)OtBIFgu(yH|r_vX6(CL?95Jl+S1>(yOnGVuW&Z$7_$ zLrl+f>CU~$I(RYiGbv8TZ;7TIZ^5{s_QOA@*xqVyJMho~V*J@#_s~JAbnq{m5eM5_ z|L*_$Ya>G+zX=*70}2m%`+NdV_8@6{-6d!qblttz5cZ(2YKxrU{y#XlglPhJP*CCZ z{FzMzDA>9Ac<1|AsJ!x8zzX0&%9Z`ac;G=ciq99mEg?b?vzom#rsx%5l`FKYGO4C9R(K0(4;bjj*{-vQpt zr~KX=@+3g1XC`cZ4#Yx5EMd1b0p3dZaKc)Ex3SLE>s;%?pcA@Bzs?Sz<82ffr17Lo z5ub^~9c)l2Skj7)w^u4R2gFZ*cpD%(wqfKqGxGTvVPbwX%(Cs-~Hhw)zKCFTsf_k#5%u5$qI zj+I2^#rp`*E3qefzuv_{IX0!=GyvXG)2cfh0p5dWm!#p8!=RL!;cC@dbiAK;l>ZvH zRm7(vaXE%j@$seTcqf)Bq+czgzwNCSM8^?~{35^K4wIOr9q*xK_C0R=4VVX{B|i14 zsInR{{0Y*I({HHKu|+8Omw60ndrOxB?>8E&j*;=cbfQ2I4et(VWx3V0N(bhD!Z3k5h0dEsrH>c=>5Ns z!CZ)=wj!PbiMyk#|17H-y+P7{v3y@$2L0i^1JR*}k>8PX1*hZwhXE;*VkW2E40dr+ zr>|9Ep{d09cu!NOLu>8XCx`yL-l{`^_iN7E|2e%SaX3-{4evKImzrR_yEeI!`v1_6 zL$Bfc|2_yVyxyJ#zTV=CIKC5n|6hEA*;5_hEo0@gU_Zb+wA{4l#wM_PyT6O2ZWtZ! zFB6BVMAj7B=Md*?e49++}34hHWmH9 zL|OH2_F%^E|F==8Lr%9w`d|M~AN@U67NGx!C_HGeWd48lAP;jZh@p9qfdI4#_8<{_ z0;xfg*Zs*a0V>Fr2Yrz{))Jr)z3)G!zQjUJ^8&KrJxH;Jk)%7ogA@`6yWbxmLYFlQ zo2q!xE6Ag>b@<2=iukKYoL~LQy7cep9yGh}c5>|m{drIVqT@S8ez(09itf+xU{-?v z{hxDYsO+U%JoXklu2f)$o8&8oKZArDzV1nljwtn;QXd|W8YDag-XB7n{xknC82u)S zhWFUrw`*X$1H(6w@b2F9Rlx+{ZTs~^V=cftgZ*-Z%;#9>b%E(=ctAQVWgM6d@Rs~) zyk5eN2+4h4>i7Et`V!mP$+7OjXGOdc5;yCRzoxSh9q%xuhS-N|>97B9M0A8;jzCO+Lu^f{{Ve$U+fCfViQMhk@d>*|Nh^D(SAN9)SE+%4wKc|dgh5Fyp1XFeort< zCO1f3^IDdo;Vt~q<x0qLl;*@3q<{in{>b2^_2@ir@>v&>!A~ zhz?VX{C-$ey;IpmJKhonzh$?zJj8bWE3%I*L-ZLQZyavRU8;1XWd1@9NE=b$Js`#w zM8-QTJW~V>?}D$nsxaO*iSHcY?Je&7_eOaD?{ytHGbaJw8Z%MHlRw5nmibTm;r?IW z^vO4SfOqeu)76W+iO~3G4mJ>Pd|dN%+jaWG zI||X^jgeo?>F68M;+ypM9hE0J*n`iL+}n@> z?{^!1t|H@o=*4znG`wTRg2iCGr%cb0@UAKx%NYfD;|yBf3a=+X2Y;XC%J>iqnaTvq zYXQ6$mv!vX1bF-Ko*Et=B0`4wnWcUa=y)rwtX+BsuY|`VaSxtt)MVd@j*XFK-OFu&4V~jXRy}*54!(Kf&eeEaa#}fX#)?EcrO)HI%5Ml zJW|wi8jXcIq_^ILZ;+aBXn0o-JZQ_pW(OhZFi0`4|H#~3bPtNr629`iSOu?!#Cd;t zy79{ebPqb=GO;S=yAj>Z|059{M=|nyIJ&6r>QdUT*daPQ$L$Vpz^ouos8%~2bZKY! z3Nq4`Ivox(vH2%M)8X^~W)ygj1o;e;@veL~Dv5?SD?jfs7;l?3R<M17mIcFjm!^m-H3Ph_J0|++4iKS&`vLDy5Yh2A>xC|8j4R=b zk+=@Q<2>Wr(D7cjA-7h|(va@(h7cXX82R-E5z`&iXkTIvl(zC0ox?u=kK5ms+G!ZW z@Ob089#N$uQn;dAsen{Lno{8X$=cA1jCcI~JIm4VcEsIY_7LFB%9dyc<6SJ)qbLpV z=KQSC*}aSaIgi%A6b8GuIx|;wVZ5_#yNU1%Qd*L!T2oJmkiU~^);U*nyvNSfXgP)| z;`bqOk2ViVthYeNd!$9uNdG1M?cR|^9@D)g*^b(; zoBhu4c&ok+p-RVEPdnM7L!|k?2?gH63k&a&@qRLrD1nCemS?%;Fy0pg=52!U4xjrd zzZl@XGCh@Rza{~4RBd9_8HK*swVM2BodeBaXHx3~F-j&O|pGM0$St$Im2-YQkY@9TT9@m_qu z*z)X(c7~t5@d?IRP@}^pM}YV#A?@G!e@55=01c8Ag$I4Tu}F&SLEZk#6wy3rfmuT| z+#q@TFC{fdBP<uOATW1$Z~{>lDK`NNYJdefbRV{wVr1 z#w>#fz1SPYSF4D=#8xe0Gk#H{j(>^7z20SIt;~;JLE^SZY6Q5_AKqjgb8dgnPhT}K zWL%kcydy6e=2m{g-eSjnj(93}FM;tZNSRcsbi{h5zmEc2?7+QOQ{X*rX#St$Eh?OM zvY=<{oL26s`Zs-Si zr=Fj6aRH~d47>~-4gPX^YthXkisFsxcnFD;%{^2z_YK{>yPYSwV!Y`OZ?cY;82L>f zTxq4Sjdr{vvNOLNQ^UraV`;y4vcwp}@L1<4uvcywKxPexK3tt`C(`?NX;dyvaJAV&n(4 zmMu-mp&jqKh##s;`=~e|J?(F^^ub4l#~UZRn>rn8!b3~93c>EZiURM?1M*4a;$;4J zCmA%n?+Te5hws=b+!h0&se(gr#c~#`~1c>u&h_ z|KHC--)C+NgLrz?))bDQ<6T(R^kh6m4KIkqb;ax5sO>^8PMZC=OBc4_>8|#^faqwz z$WKnPXzIEP?RcNO8Rg2wioJV_Gq~0fU-o~&^_I-k=@^(=tsR;W{jdLLkpADA!h?P! zSHB^9P{RBL>S!J$tKcgNSCC)4Lr4{5ir}`54ZwqpTw6wPH*6r6WjRlj!T0|!#+L(Ht2%Y3yQxc|+?m;|#@(UKYsNv5bank+UETHA+9(1H-r9XoP=lIyv^Y3o zw|@@58(v}u6kXWi3R2?!2Ms8c2n7x=P!(B-j`wE&fiqe`YWPqjF52o{V#8PT3i60* z|Gp2m=?`ybL`N(}e*CL~@1MFtJKhOa0%?PvsHh-?Q<@DPg)%(exQe6H=`aw=RQj{M zwT=Ss?{Y0m$?iR&dqD*a?|VB_Jz%^g-HwyCw`MygDhdJKjTZ+MXY*|!rVT&4^#^02 zuOSzF;QqgzYk|yrfcJ4#mmhgzVNk+0vF!(Mq2sM{?wUy32{n8Q5?AE#s>JFXx_hsE z^zwIWJN@BJ)?tB>-^?;^pZx#f3({$Bwi@CMDvq}lxNtZO&1d)r(r}^F>9AcOugiIk zy1YN-UG~pXK%o8qVwI$EpbD! z&|&_x&G7E+?05UdDS)?U>VY*k`NN=sz1f+j#prk!%JgpR{-B00LgF}2q2p~Z zYCqdA1JPZBMAo5=k>81j=eW0s(SA5lL&YsVEgHK);+q}l+NKl2@OV$izo$yay^9-5 z{i8_7Th>tEJ=y(xoQ!w%xU~`*-uPn28!+Cnvi&5yAIa{D^#yoO#?7l}Nw$HQp_MfP zU^sEH`qxT$_V#h10xKJM|F4dxwd_9l{{NkKNmJEdzW=x0eyG=AtvY@XiCdXEI(PCf z-~U(4>FaN5r9ZrF5FNKL@@r3ib&hKd?ZwIGOG}0(y|6z{d@iR!sH~n~_}SaLa0{w* zT`WNGL9%4u#7~V5--e+|o)l6AX-k3k+$oR$T#&wOtX&HY@9SJHco^^f^M8== zwmoyjAQ|AzJ8>a5{GknW_g;pZIlz0e*!~rK|36=8m3$Jw`_ik;JWJLSA*UA$EZ_H{ zA8*;U_P2&JP95)z#2qe9eZKz@I^L?Y6?kcg{_yrebSPrv*ZEd$RN;SkAboz?ydS+; zRP_H%`i4^vH!wWjxJ^Xrbo`qCS@uu=zkvepUrLEJWcR+SaCQY6-lJ2RAu!(gX>ZrV z?yb9Mhg~kfyD{lv^W*~?NF(g~Z)SjZlfdJJFy0T1TJOQvTljn1m_B?@go>;2-KGc7 z-CH5}L5W_t8vYUzSO4w8_A_4S4bq_^Bhv+znkzX9o;^sFSX?Jfsoadda zVeAv6xC0)N(t+<7A8&s*s&tG9Sk|iMliZs?f%i{7KSeU$gT6tUXm}HMzP}CQ-MGA; zG$1{H-~A(1{#_QoW2QeZ@tJw)PrwtF}r*C=|zBdVeP@7u-8QB+|1YX zC;QOxE@gJk3YS;IpGV>rHMvNSyP)H}>s*9An=k$0eFf369V5R&-@rxg#I z(sZ%6w?z97Z@+NaiQ)VI@H4=&0P3}ER>i=yh@SbUSX+*|*gE3wM4ezZNT7JQJ zPb&Q+9dEH7KbqGG@V4A=Vj!r(25N3_f9(YD{`ADq1%BS5{_C6_{Jh2TY5jbtj|lDO z5MOjE2p#XJ_~f#ZwQBefB(8eb6~32S(D7arF!IYih5qn9gy`VI$ZyYwtKTlIrro`L z<6j*8^b33T7U{8vr|~rt!@GB+vKv)8W{dKgEy3>Xzx)3gU2!tD41;6VvCCTrjdlG9g^zX*8HH2d9o%&%;qs^mtuFW`xtH_7(~ zbb$xybZ&b+!vs7ivn#!K9L)dktWL;2jP5~Sc1GJwe^$rmAaT70l0M4<&^<__rzAi9 zF#R2|8%1=eV&u2r_o9vV1lm1FM2&CPVGb&;*jXy^$l>K~Jq951?W0pHJy$VZ1+$hLi9f4`q>9QA0UEqLpj-swH zc>nLjnQ{pofcLSSmAZ?;5}V+Y-Nsx;gcgi;=2rgY18Mu>ay{pF>iC67+=8CP943GH zKw81OlG*4W{o%b4(IJPCU*%Jq53l2C$D2>;qN0L1_7eMQzvlkTO)nT8@2j$^ROztl z$husZMQV^7DDa*qHT9BQK|Wu4S|1JXnT4yb!FV^x)sXN`ge0TV0p3ekS#v$xY@prB z2ji;24btX3>(|0JNPStAn4kslj=bX^HeL!QNQ0jZL|37^cSK;eM*1^#`~VV{uc7o| zfeN~Nr(8ZbG_sTa@D4|GBx2-eFOd>lSWP?L0Xk|qcNb#s-r~lt280MA zbi7QJPy(O5UAV#SR&S;r~WV{`jTv*ZY zeg(Y^g7LQB@Qj2v;gz@NI)L|@h#FxFLGZ-x%13+RTVo-G@cOkd-lMk9-!uTcyQB|# zoct9EZC=k^W|M+G|97?Q&#>R2j(0@jyo~I2=Ilksd(wWeQ`ZejQe@_G1ks&v@(v5J(mX2N)HrofxS$^9J}Z}a2& zENFOZ2opnLyoK-dknn!<@dthdz}wA{eW~_B0+i=kxpc5C7W&dSI${9ub|~<1Y5{nM z-BUU1*BT0m1!dJO@j%D>ra|47vKV!|C=zFvYgF%GhK~1iSwCNw1pVQC9nmp`k)N$b zRsNA@w7d6bpID``Q7Y#D$>TfbCj1#5Z`{*&ROxWGEX}a9Pl54vrofwR^zmIX-cm2_ zF{9yKACYqa#(NuKn1uK0n?eNmfwa&0Gg7};2vBbG%v4cFEF`poGYZDLnl;7#1;G2| z^oqHtq)^DpOI$ix1Rd|3qQm$0g75z=k+{57yKz#p&Zvz*iM3avng;#horUNq#>j8x z<;*fBY1;e$Fx#~TS^n7DTO;qhj3$M*GCbY|{^3;VNQ{wx{wkZad+S7j_xu{uDl*;) z#4}82c%S~(9znu;%?}dZ-UBCmK7#&#V9nU<*>5&b(N;nK;g_+{`hCLuFy1-AE$g}g z-U+U=Q@2w>q1pPIMIEB(cyGLA(((L)I(`O;V~daujQNF*_g&uAtg@!`hc^MyQI3({ zGD7e*oh`KEtz8Q}z0*v^-CGrfmm(xQ7#?q2Tmf}D-i+^&1iQEY=Kplv`Tt1{EU{ZD zJcut)ZH(+eo1|?Ppm~toquRc=K+xZzbd1wQm_08s4kYil<<_f6Cuq4dbnT{k_#0fcM$-eq%)@0(7Lu zjp;4e-a0+>#RSG%cR_aLnN-QcE)Al zHuNp_^L)~e4X)E4-ld3+GZ^`O`LXBvR0!=2(s6C=H=Jv+`+uCp?yWtyIT(J69XI6? zK#dN|=RYIf+$2?y?i6_QaDV0_<9*KR3kMqB7p&Mc;R-VKdzmGS_Z!=5)-eF@RAIG? z#o&31kH!l}t^&M!_)@>a+gnZxaMCpZZ<8Zw8?BqdAn_#;4kA0z@fI(A<$yN<{XY`- z_$If;-A(9t=d724=I+xU-lB+(42=BL0%AXY`5$g?4X|lZ+ZKeqdn@iySgAVb!SHy? z;`E28(XnvctXU(ObU=Cw1>OsvIrWh7eqVBh9S!fnybYw`#1Wo{qy~xF;l#aL`eLu^ z!=RX`7|{94uuL6042 zcki3=9GzO0RJiw~Pe^6ooGt^D%YRQ%$CN4^raz`){0d3#?M8w3f;Xod$asGkh-O2> zyOrw?-pdx!hPQ%ia_7Y!BINfzu<7z%^x2z5ZahyXnE&rY;?xt$r@WleYwvrN>grFv z)1P~rB09=3^0VXEao%2q_S*Yuz(B5GFt&R?uzYsm08AZ&Rg%Kj_#uPMs6~ z`v1S11%3Q3=>NA_G9}3%M|e+ zkT_n0RR?B{qk9l^KtP9=pZ?w;CF?N2$nPEDH7A!9?H)9>w@9cW344i6Rhwwrd5iJC z|Ifd1sGS-e8_iWOi610Yklqw{FH#N4BIE7&nu`w&@4l4OYw#y_L$7;CUy$0j>&93C zyblNkGZDVpK+-$1Ec?OdEn!Vp_QB`>9}mgg<_CD=t>fRiEg?b!7T@ARi_o{&Z|Vc)p(dVr=v-K&s*L=bSPuwSAOW}aixB4)Cn1y7uv3KSiE>I z_V!lQ%ds!NUTHCWgJij&af})rHxkZ02}>kZkX{sc3o)NQLdJXZk=HzEc;km%e!~6# z*6c~r2~yXQ+NPZVZ}YsB2`(RPARN#4Yc1Weke`ryvL3+u^6BjU3DE!7P4=$a#6*Nf zAFt>cI*yL_@`b8vX6~!vN02yozQnfa{pfff@9g5!XQ96@NF@**Nf`Mh{M_?c%9i#9 zscUGROk^h&6C}Ymp4!TK439TX9Pdq)4xO%8j%Fyx)WfcpIb> zp_Cuv#qJ8|#mVmbx%Syy>iA?NZs_coi5M?>aq`S#_8!5W{u(5IM8{K%{J!a1nG{se z?%s**-%kYyVtY|qrJTo2CPB5`B221Y_{=y=EXT?~wTL4SDfM|2#*$dAKf z<=szbX?O4Ly#f2{Y_LC0%+pIepcWI!@Uu6!R@+Ewbog-$k7*wL_x(RwQA<~UAN2pe z6dtr}@0BZL5Ar#tvjok9GFDGl!EcZzwC>mpPmp?cwp>vF9#kHE^Yx40Hqezs%X5w3 z25HT2t8p5@gSOT39`gnbQhkf0{yuOAiT1CXpB?{l2Z;bv+vAFU5xf=>mt==8t#?EB zAoDdk0<0?)>F$bMvJQQW`~rQV(q^a}D_sd)UeW=VVu5|{Hq z;kfcVbi5msmt=FhYSJCv1Bi~t82QyaDzfzX9|okNibvu~sCd0aP^(Fe_;ukOx~d%h zhhz>cXr)TW-Wnf{3&%-#@1($6xaxT|8SlV-d4gzoGvCw>gz;|LBJ2R;ZMn|-fds(& z!RSc>KRCUmxOK%gWq^0yAq`RZ`~Mf;svPYB-W3XGkGwxbgc|+N{*D$x$2)e;u3OJb z249cFb-Gm^E1X5&-a7yIK5N%IExN-y9?@|YBR@VzjU`$4X>X7Q1Jt9_K2vdftNPF8 z`Fq$I9&cP9>ocl!wD;Up`Ln&Xg97g*>8k%3PI#}_BY=jtr*6&!JbUZt!P&uh`!#E% zE(LhsaQT&$1@K<*J3V|Ce0%E-foK?SzF9#78-O=B)1~_my#M!8=D?;se|i6J*P+od z{G=TI2ND-?MvwTY6WzTP7i<*RwN01q@b*P?$YSKDlBPa0B}O~m7SbUPGpn&{Z(K$1 z%9Nr<4B!9b_WPMoqhrK+>*L3j|N8&`VS)Vr{vQGT|6U3YlCrQlOI~7Ql;p(FJjm%K z&b1DBP=UXR59~pk*S%nK03OtAoBL{=5&9ZjhQQ;Cv3>L6ZLH)ILApK|vA6 zAJi5Tp-|zeJzfy{65AYL>>3q5em@9_3m5+N2L;;6;}kQn`UzXT|lG`GqTRj24c>>GpT<7k;v7Drm+Z^N@Oa~&Qm12WN7>@;T#|eH zQ{XNBOh=Q9_xc4FM9}a)`Fte@jQ5g@*W6*ePyhZUW(e>;a6iK$5L|CzDk71g5Bh&D z{)@L@yj6vK++e(KRD?C9xDp|a%pdaBW9WD<83?Ir;^V`sAaTy~ZdFCTK*xJ*y3^OI zSc2~GUW({=kCC6fwTX@PN80i36$tFf%%-CMUzsF6JI=!Jc;j@b)S=FEP4Q3v??-{R zSjy`IWW2M5{Djf){$epL`Uv1HX*K8q<2{%AHChSaE$F7X*#ykqc*5L%X@ci1L-X?s zVZ0~U4t(7O@XijAD9n@yg96uV5aldKuf1cdjz-rM2;ui5aY@BS2YK?)Yw!D(jeVt( zGIWP`9HQeoMt;+$>(mX_(T?}SwxiChV^rMUa@R$lFISrJYi|};s&uG!RoI@X_}Bmc zy)&ef-v#}D5QPUR1QYwo9<*OrMjFk7PA!uWg8Tn#j~4HQJxI1jCCM6ikm@B@_f}Q{ zBzMwDYT4^pC^hw06#T>vJIhj)Lf}DKb?K?0rlC;qx-T+8%{x&G`!$!mjK^>Sm4Qec z5AUOm=P#q*LE@wotZkPfiKml4)&Hbnf#~qS$S?NPgSz9pX!juQAikaAE>w6BF57vh z3BY$zceC*R6zz(;4Lq-{w5jkC$GjO(eU=%+Ghmg{p<2w65h;5%Q*=E zZ*~2A?bYA|>62lbWr_gaN8Y;2zz?MDou{pJ8sP1y^xokhXDFn=spBV_j*hp?^Ec&U zV*HhINZfgW4{HYZqT_A%c=^x%tIO#QZ%IVQW{ms_hffjs{b}$2dkE3#JlnAG-Un69 zW1Zz?_zLo5>qDw^?0V>0S&~EQ|MyeiE!)3thK#p_P1SNVyg80dZin%{y2g*Rd#kDB zFt7pOEt-A>cT<1>4SwBiy9RvT5^DCd0ml1`RQ5@>icA8gHl@&2+ybr)Qm zRAh}C+X1|}`z8H0i4vdzryt#{y|EA*@j(#$IPs9`VZAtjcLdj$4-pL^(C2w~Mo-wG z;~h0B`AM^ALFFeT4%$Dq@0l7p-qC}F-_n0Br8~Ss5gi#A`30nZYQLIFJKk9jrZzim z#P0t`U&;zx+!V#|cyF*(q)LZG+8N2mIi%twfC6vnxR3xc-UfHJh@;_cwtV6#jCaUy zoG*;`nFWV8ZUT7Qx}UfkDNBGZ%JS9q1H7vZV`Sj|zhSSL8WG@ayK1m*8o0OKs=RvF zt>}0=uNWV7h-R(SM&g#=6ng*pFYdkN=jEnxCLy}Rn}F!phmqgU>U^y|Otcp#1xn6Z z?=)&qdzk+;0kPc2-?=e9-ngGs>e#+}vozS=`gi}|e+Z!8Ux5BUjKYJ|j1E+iJ;+d0 zP!Y|8#*d#$g$JbHW0^<;(%}thH|7HmstLLrND6Jx=<(6`vt4*iV%sl;DthQuZ8SeqNV9({{lVY}y~QziX1NUDeq zWsLmlyEdfV^`+f|f>JMg?q;Q;f;?EckKMwH@%#UG<<#leyf;bp&lWq80&i8;Oj9!6 zm-oDtN5gxqyHF{N_fw7_65c<#M9ldC-gRy}oNT_>K>K8qn&!aqmNEy6$1vW%UR_PB z26&g({|KsLZN`Kp18i zjQnyt9L}E;p&jq74Ko_t%dwBQtlIl9{bWx+!{aT>Tt$_R(CSMDxAI68WGDsR$}fVm z$#_TMZ^@zI?YK^$8OEE?H%Y=f@Voywd_Z~$XR@dMcN<87XG$RtJa38fwcZH7ARVZc z=5`0*oxMH%lQ(Om^; zhUhqik>8$yb!uh*!|Scq>sk%iUtl*#I8IUD@(&{nk2lVJ33WOOo=74Gq(dn1Ryx&D zM84=gDYMLt`xpy!H-ip2% z;bgp()>+D+;l0{Yfi!!o?VxS;R>0-Cv&oPMNfs7eZf!!x`*Dx)g(Zaol@dtYubWJL z%Gc5HZu%L|lAu9$`Wo8tmUZ8tc2cSy6K~m?ZbRN%5e)C%JL=w1 zrDF+C=ZoLI|K9(j-=?1;v)IkCI0_HamS&$Idr-yfe04MrdiVT}Pa{}jM~-$A;U)I= zdZ*j)1nK&*Ep4y(2vC?=O|T94K>CjPz(obH#7?J;r1ya(*41U*ro?=32dQj?vaufe z8KfK8(*Y{$#VdCraXSX;?I3aVGe~n)tKZH)rb>4efT;*d9cv$=kkXb`QgQ&{XjXs&w#wIx1{&gft+Hpul^@ta}$3Z@cc-s%UtxUgl=k z0PyDK_YQ*b-kA4T#vE>tcvL-(aS@9@M|ALEo1Th$Z!h0HJ`T#knzr$x~77L zcT`H6Ts^@1+V%9kFy40)g+FNmydCG66fy_;`3x0z5jo$V5WMff&MDUU_?hBMt&P& zGrm7tPdnajp2;G1Wnuf6arB)5;@@y5*vQKw@d^oRVP-P?l{cxz;5Eh6JRSQ@O1 zhIdxEVIMpoosD%Q4M?j5eh@?f-miQ+thK=QmJzc}h%)#<+NH%H0LEMC+!Fm40Pmf> zmG$m|;Cf3L`MpU6=y)$&>8ZN;7;oh;68F@7*lOl5x_h%MX}IdIOn=8)$U4|C^0R&| zK6wmBJKjQ@MdYgIW8eRWyCri>u4;zy@s3-4lo}mt&-kwYok?=<0~C0x?~VG;>#c*S z=1ORITOQdG0&j15%V&7Q?!BQ#*7X;7|8L00wEkGX4RmqGX?`{E^_GUn?0p#T-B*gl zTLIqg+TlCI7ZV}&aJF)XLUg=)n^G;mZ{@3GMdGsEeE8cE(ebXHXl&q{p+CIII%+ZU zdt1fMrDH%l-oEbTJj@XGaAH{I%#h1z2gb*HI-M#V{l_b6pMvKt|IPm?`fPgrCFuWI zDLlwfOr4v&#P-j}>7aSg?50ak;r{>h)b<0g2U)o)zF!Xa|JyG-o{om}P0TqMr%+Q6D6Dz?~}*&lXj1~R?}Z4sbKhvu*N ziz(OOB{r6Y0&o3MNSBN^2TQXS8s1#|&qiRpt2?Jic(2+d>efNqI zRXQ%7n!n=WVR(Bhb{+-Zdi4nrWW1A><*Y!%+st>GzX{+yC35T_?B0SBCmeMF-Ycu; z882Q$fHZ%{`6z+i+r|#o<8lCR$2%+5&jWZj9`LgCogW50tmJ1qaT*=(#{~+vH_s_l zRwHrJUit-m@#uIPq`fSX@zAF`yz3AhMi}}1{`n#>&6#%hK5(~D(r6L(=PkHZ=i6Uc zOffv(ksqt6(lMSdm=SfJ}qt+#> z0p3{?j&(%_o2 zUnU&`h;|QJqmrtgGlD%JRg64#A?mz0!&i`9{Ml6Lc&dD!?d+c=mV*Ls=)*84d5Jx$ zRcC;PcLDQC!c&0v#Yr81xPoltnp$KD@K#p~Dc=b2*7~|vmlZsaCKud;htK~nzvlY- z8NhqZ-~-m(r@-|VuiX2-DWc;&$Si*>@rq<+2oiVHRN3q(7dqbjS~g{A#+r18_Yk5( z2qQmPU2dtIy|m+P-O8IMolM06X_td?kG=#jJl?qOIO=rlN|MkZ4M=0zDe%VMNiZhk zZS^Bf9}Vx<&x|?Y`Tz53Rnq+5V=4Qcl>qM>MUn@ffd(nHP=DU;SFupw6yH<0f}D$U z-1q_D9n-ri@}4LW>OZimz~u@$-Vet()LeRGE8ih;vR{XnNu{FWJs12iS!@ISHAuCH z4yKU5=Qp%|{0QfA+VM_5S2BF+F%|v)ffoy&#V|2^gM_Q@ph|~#iA6-lIZ}hfMuE3+ z!m)TV-YlbDdT4md=xTMqcz;#dvmbVEdH*6;czerMLatmN;H|nrv&a~n|KERJ+6?ah z7d&!J`~~nXSiZY%>#tB~o~8IE!xVJ9P1mU|eU_kD$%4cUpC6de-HVR*>au`A{4o7( zZiaeU&$NdzC;C!{e=d^DI?5yls^)+Z`b7-p;4M z+i3r$Ml#+NE@rxDc=MKjxd9(eEC`7VCvH9XGMNm969b}>yh-5g?G5op zm*C;V=bgsKguw1?!+!G|tq-A){CRwb*FKThe3YZ~0Q}`9JQ&&>;ci0EWjqGUg*yI-(Lb?F~%$ zH~**0e*eFd0{uS^g$J!xk#mJT2=4!jQZ~*<^PspH;}Q4_Qq|ZY(kFHj!-Cd<@NMs$itxOjB9^~fE6_rQ3 zzuXr?;{15=pVAJY??HCjrsRAV`EC5)^8Ww+*%i^Tc;nymTR%E}vh;uG|BEsQ)wT>_ zFR{2hLuHk~1&rSyt>IRqMu+=RJwh_+1L;_93cM|Fo|nmZtMbdSqTwyGXucr4y~VXy zmURDLd`P(SB*6Rn{a1!L;PaL(XFu&y0vDt$SUjB#zC7ci5nu;)@qVXs}}y z%iJz>ymxaPT-H#Gs~kq+PW?Wr<6?)7_uTXFB0URUx?5uRAUe3){+{2G6#=I-SZSaC z>#%sNWz)i*|F_GQ9%nil$MATE33#PZql4MAGmkr#R6#DJz}vhmDT$2t3jDWuXm~p* z?S){xZKYn4@D}h}pvnm+I4XA|anV<_@nNdyct64`9k+BBraQd75gqLq`SJaVHq=wz$nbPB`cjWd?&phib{Y4G;S%cTB)0R`S>ftgKYyq{mY$Bc%z zh~uO`jJNC5Dbn?pR^AI+WdYt@>}%G$f(A*e%S+ZB?A{)DGrS5OPK1O$O{)ZW_m!Cn zhLsYb=Y<^5HFI>lC4Uz7Khox}>_Fn)y-pVwRYu2qv79^mohS5nIT2Zh7)E{q@fAuc zk+kFOy@%iXyaG1f^$Fj0SFK|F(_7Pt&jP5?aZg#0XqrL7n~MT(Q`3x}WW1ecqnXg~ z?wOD$&EA}t_R}w|%1UnyXJ2SMnfne2qNPHD>5|^M_t; zdZ#Z(ckbEVeieu zV(j1l|EX!;wXY;CinO9_=1SU8Bb6c~S{0QnO^ZsUvL#6rDhico5u#A3w5cdcLXo1y zl91^4y2ds4caHmbU-vchK0e>?XXba@|9N$sZs(K7{d}G0YrBr9{rmpk|90z1-=7cq ze{mWQT7?^Tq9MLAp_7bMM*V zIOuJ8bOpSFRKE6E)eA7inok$5(`X<=J-GgR0vpji$j$#wwal+yggzv0y8dtQZa6D;{6_NX6S=vphc<-t%357QuLHaz<0|E)5j5Tsv3)#g7^Qc z%k~}l435~nG%3czSM1(KM;Y`0ym2CKV$m67sBz!4)km?&Z`Tk#=C=K4WmxmWn@vik5)Fh581Gko*?*q56tC303h*9_xpM3~ z!28s0%~kOI|1DK~4lv${`B=~DKI2OaNK@?OpFc|Q>(kT@8d!mBm{G0I`q<3~FeHnX--5}xSjpY*_v;GC? zs4n_+sG6rebf%sk}?8_K;@6|$kv&AQ{4=2XU zCT3pJbz=Dq(#cf%bPU`ou{KDg6el7ycv}-aLa2DFr^Rxk;a!@xr~$@1o_Cajx83v4 zR-FKEH)oY4kA+B3ng4U#ckp`a+tXx^(nIPj&z8|LODK|LrKy|I5&Lki*wzJE{lGK12{j^PsJ1 z3eVsr_7&-dlqYs(?a6sz3_OTq-3QfN1rlVG9jP!i5eI2ICVz#e*u}D8{r7+e1!=vo z9(4(W_S@?>x_(CYAVuj;!6C63LM#$@bt*dl>kD)bD!HIvX|z^|=_*J`L`Nn@e&WUf zMFeTaJ*aEIDr03A9sU1<#Erp{d@SD};o5oW(otS($F?JrGQ~>M;Jy0M`)^ddtFFzO zg@*UO@YkU*-b**%qU<0I7(Ol`!BgzI`3rYTlOS{Ph}la&$3d^O+e2WyQ)F(ed^<;(uBK>^S{zyT#xC{4hj^ z8%BOsr>uwEdKt&t`I$feQW@<2za!18xz2Jw%j4Y>+}A{p4mau7w3xE(d2)o}&rc=L|Eb95;YV>-Nd zAv%7I{&Rj8NpDL0MHt7s$5$|ATPJq^ALTqAe0Y5<%j1m;Or=Z5)h5j)U;pg?OVZ$N z?{zqUiudc|7lhF8F8@)T4L3;ESF9)vQiSmH$YTKSt-1V0l3;T}zP)Bj^g|rP{^9N} z81E~0_ba~!c)MJvj6Gl!263kMC+j>$$6J^0_Q`qDcp@(n7bHKRDpZAzcfZM)4dDXw zxwj6YqZ1>)b6?%ach)eDci=BmA)XJ|{r}nUD_n;bb+defB%fVKmyXTd9OiGgQ;HJ_ z8occ+p(9kh-FHL_qTy|j*hIm5eH&wVKOpOTj&UMGn>w$4${IpH|F3iKORDK+HsTf} z4*#i7;!z9w@|Ip&-lp5%M3~OKwGbVu82PPHiOEr0%{bnL3E}oGC+X<_4aUCpRgJMc z-nfOM^yx_3c+&9S{{Qc_GINeW|390?gIq>8t)zO;6Mh|OG!HtP5b*-OVz(kBigLwn zLn~MDmts9r>lvfjxm+Y@;FlX)?~gdBsP8!&JjMF?j=qHV|68GxJ?4AJ(4xUE$z}ZL zQ*4|W;nRsnUn;ecxYpuI1>;ZX9u)G!>dq1uJdxS{l8+-g5-{@H%~et{w}kN>q*ps` z1e)~F(f_xGPgxwCVSNuGjnkz=_xshmA{QxBtO5<*YpZ#bsCcU!osmStTX{o!GK_cO zDT|%(6}$0|aHb#v5RRRQ>AQfd>F@#gU(7Fy3SLk6FVzNOtbe<4#+Wp-(+R zcf7mNr&yKF7n|+9dMZC7aXG8Kc^6fo>mjQpN9s@&Wf%=i>5 zwo(0zr5twuztw!nxoR?*Z1Nm zaQ{F0;73KHf4Ki&?@_qeOXDeFKN5H4OV^IcW9WD<$eCaNJ!6pRHb~PD9i7?#oZsps z+ozs6jJtRDBK2&mC)oWzZibL8UKPXgct^FIpi9R@=9WjN|J>e^qruxLGKKQIC44#Y zYV>7sG`wTX*!$tvTlRk469~Jv$Fh*qLICeW`212ac@kvptucBS;4S7ktO;+B)@ojT z3xD2n>on1rC_#pjwf5hAnuqS*Z~7hyUz_+yIEKV29p}^cNkYe4#I`gq?lAKmZ+V93 zn6mlj{MJcK*yO)v9B+NE^8~|D?Eb%ZuAgg;%>c{etqMJ*OGmP&TZvLMr8tqL!P}8A z<3n}tvt6NLXn2#otQWy}M^vW=z<672Dc`*S;4Lt3jlY}{2^zPPd*b>n4zm1^xeLZy z|In$na)9^lE3Z6XJtad6k3IdVxgEXsj%|7%mtF9Upozro)y)5#>Wsd;Wx6-;!Vd4LRr7|KD>fH9qEpu@Z&`PzW>i` z-ROVF2lW5*Xgp}+yRl%Z2PG&joQ>u|Cv;AEz!fCBYGg3%L7bYT5gp(`iblIFt~|Df zM&vj)sC|!v9`$BW_WyggtNenm*h#;hGq}r{3`soySXwlUKE+;>PyHaXil<5niMzHl z!vAqA`V<=wyz#Vlg%s2E|K*5|JsA113G#0{bcFFK_NwrvnUrZdDoCEFMx~r_*7u;N z6?EyCBGjE4__P17M1%K+`k~cSymhy;DWKs!Y;^w+jQ9Jynw0*3)`|~2Y5?!=TpB(1 zdhH<`bS_~Zz`OtW`n7O_q(9>Mr2*hQ-M8-i3pH@W&QYd(;ubpIhc+eNn7+(Y)r`cM z-t%(&at0l5?!*qGH{#Mvhj$91V-`k!Jmkv5CJl_^-MC=PL{k$RZ?eUc(uvQmEMGxR z^YfL_qoXCYnPX)JrGlJGgST6v?_YR#?Qf7n!&|*Js{+PbA$5d;chM3_eHnmv+w|=_ zYu?#IzlNVm4FbF`{cJCRm$!QD?pizscn9rNe`3f_hSq533ZKnH$9sD3j@l3Nc&eO{ zIPbAU(;G(_Sqp!F2B3hv;~Lkzb!-!sz)b#@*XH;f}R*Dfa3uu4_c3 z@bWv>$9uodEP8Zo_bU*;UqW&3IW%~$^Rhod#k=>{78x|WJ2jM*;rIWN&gblcYj4kn z0}IB$=0xfSzE(Fj5@aB?k}wYNR*^sH2tRLWc>a*&Fu*%^_-k8g4H@EmJ^px`D>~ly z?|$vO_jIO`8;M)+)g;Ph89Lr38sw5#DPg9=y9Lo_#9SjOG^ODFG6MRFtN zM~yrR-ajDj{>1XNH{MFNjvgJut12tiBUAtF|Nld~&2&EkQ|x>i5Ax(Mp}ZgsFR=&A zl2u0Ypp8(y4eUV|Idv%?NPq7|?uVDyw~7|#rGP7T%jetrMgNL}c()zs)CC?iKi^@Y z0q~%Vm8SBF3Skh*LBMD3b#xDsKhwrj*~4G88i{M^PiUBZ4&8%BMbo}-)Rkj84^l#O ze8tG`&8S6G;D7PNj(T!SdZ}0wrUzZ?$>w&{Ud!@RtYEo04?Q~apM74~8Bf_DRinXs z%O%G()G1cs&A1X8-mj|2LNMOj7Z52^tmucrslm9!24v$%6c65f^=fho~IfA@CE6sdDFz64ZKxJNZifjFh{aaa8^p z2R&@dTd4)`-tW6FKLp@y`a@Ex<9jHyW#ZC_xoI{yE^4W0*v=WqZDO%3;%X9O9S9N5j1(I=Z!t|lf7X2 z0%(xzUkZe10=yj$?b(wG@IKsBa%f*B89F&fT5X#SdU3K|zDj0tAy-v864x?gHee-< zUYxKuZDSwEW4``>GophZBfs=}nh}9#8OK{F+xAn}J30<0?!R}{WTJ!h@z#2LjUF8i zc{;^~=PB;3OoO-k>{p#symQIx=b+)u)^ghz#yg0omvVYbh$riY5y1On+SM&BP4(d(MfwFR#2}KKHgkbf{zGw|+P*pwxr${=Z!6>4cOX_VQNs!_CTp9j{rw|5wnC zp-abC-2nbe`~L0!nXcFWPYHqkUz5gz{QAUiQawn-U0wstgLsYzn89a|TnH~IXOMbh zJWjF!58^rT-93qi1l935#c}?QgU$<_zXC6@_qUuaf^HVb^XEF$KG#FYr=eAeo#`sbCy0)n82MF;8>YKmWPFNMd^He! zxwQuM@8z$5@{e`Pw~}75ya(Zu!sye{xK~o~PX)P<25;XBVt+l5Zr?aG9}VvmgB#f} z-pej~?|_%sTYA~|umimPk_N6?@R6V)@y%-`0N$s4_Lsp^tg^ZldlA5Um1XDmvGGud zttCA%BMKewahp+HmsPl`ndU!ny7e>qyj##4B+=$grZJt&x5WMx(V>KqpJHHi2d^vR zcrTq>C921V{fXTuU2dm6=Ym+if{a?0=SYu^=u`D~)lX0=$OSZb`&_M*03>zype+-xBOa#|kVvqBmQ3H63YTRjt8>Hu(TlEeCyp=;% zsxPk&g*^CnJ9n){$9v$Vgmdj6SCu;wSL>%0t*VEP_g1~4aC`vxy>J*W-S_Xc<$ zINdV!JvS6m_m#cyQXd^}?yTmvOfi8fH6+f$aP(=k1UlXwMz38y_%h$-gdn1$8za9C z+>N3IO^oAh@2xW!B!azqi!;*P<#X;W%j1pX*&9Naj^mqe>HjHC)M@bc5@uUM#oLtZ zsDg%f#>JE0V7&9IUQp? zzd1dJJ@5J458EL$Y*tK_WeiZM@0G5B=5+^&fj~*RmkGKcS&;0xSzrT7fX8r}} z|8;3RD6qf5mFhtb_vdP(c@Uquv>E(@)bcyklozC?wF3m-fHO#$CPtB>{v@c9Uooo) zy#IG+^KdKtiJbthv=ZEk?}Rii6HUU*<0!Gpoz+nIrmnw{1kg{dpcb@ z`k$?@f1%?QPd%wvX{CR4u(5(d?2_W zaT{e~&DuxMD@e802!}TJDW<#s-;U_u#>nrQ+_^2o1jgO_=>?TR+dew*PTE&AJGGtV z-8(vdJzY9J^Iepa`}4e|77gA3dNAyNK2Drj60#5tZ^!%MKVZCL*OXEoC%*ao^4&>* zcX^3PIsbeTRQTlBb`fyA<+7h!EPQ(_W^qMf4ZyqM^zysHo5;{?&nLn=KBG5CAByg! z9Ui++kVWFU?Ou(aeu|EF`H-M)S#&$o;hl)+Sd5XMH*a=LxIg3Wy>Mu<|7;ZY@)piZ zv#ZnY{|Ed3+eGNnG3Sv;{ncE`>g^&LythpTAE)BI!J4oD4ez_!@0Y=w6G_+l7}|R~ zXrasz6i9{?YYwRzbD+C-V8d%(kA~h#c_fZ7q&n;AFgo7tD__3fDm%h-j}zq}IwV&8 zbAD3EJ8@qxGmiI8{p5*sf9&P0Sl9R!ONJX+e(&wt4_>--M7M6qG&uHe|Icj2`hUy^ z^#4m~JZN`i%U|ChEjrG&1kHoQCKD9kDb`SKF{S@MK7DXyJeXpQayQMXiYGx{i`Cu? zvByIzY@J*vZ;;e;Z@CJl*r?=`2P>1wP_gu)6TQml9%R|7CSbTklz0t^J6n5NJ$m+2ZL3q;3pjQlKQW3QVRFz!LpKfX$GK-g34$SZA{Vo4b9k{EFc-fvHxR=f!CUTFgzNsl2x zkH6pVE*XYIO`KsIZ*#(P-A8P6tlkR0*VJpQWqrIi z(x+o0$p$ZSf#Tl!Gc30B=Rd@{GxS z;BexbGZqS9dF$b2wLutf^{U_#X8_*oPM?d|Di8+Elk(}EIFF9Ej`)n6Bd;J)5s53l zv1!l7!{~U2$G_FS?<&u9cxxg$c46eVstea3w1x5Its$=d*W&ml%nj1dUX~GtW(tNZ zREPY>RPEeW(xqdE;X>o|Xv*b8JsP}&@oycdcrV>ys)L4iw9qvn*uDML#(m(!iCGRN zOJ4!JO$|riJqjm56@AK2<-f#1_v(FP;L}@;-}+Qe0=#RNpVG|~41>J4aWw1aqT{WN z%lv8S%R}6X#8u5vi@JOS9q&gMy$W+XrI-%yg@}#@jQl1CEd+bh8F%mPg{S&gUBEv7 zkGmvr$Y9wcmhb;@f#V11(J^t`;htaqzy1Gz^ay7AA?W{2Xgnyqtei5%ii7+AV!Jlu z&^)MCi=!4kgLI>N7Uc|5n@=qFKHx#l`HO}cGf9v}FOQRvT{?Wu}AHy~!IDfcF83 zM_PD*_r)}kSYz%m$mH!@@#3@Sc-M6cj9e(=BN`%c$v=ggM-HIlE#Y*(*i1~8>89BG zhz%`xNGEm2)jX24QwpUyi&^YcoPT9>C&;1ZA5-=BBg>fqQRT& z%JEnKAARkZAsXI6+kB3~J4jpPl_=L+B2kyl(C}iN3sbCc1Y0 z{Y{EYhxa)|M>0;#LV^wzLK}W@ z$3tsXs?^}iiCmf4@8HXcwfQBj_H)Qk+zG{LVynzZnrF#vpMSD|riZQql1? zioH*_%`DWlF;1Bp~)6HE+^JJ-m$)*nC0=tt*fC=$HGO6 zmH({X8qnaqXDH~eZ*OImYb`~?`(fucMHugq#mgznTRfNMpCJRhl}6UMc_)w{N2Lep z$(->}iu%&G@bQ-Grq5oN0lY&7^pl@IBtzwkQl;89p%*8MuV!46%@-w>A#q6xLAHrj z=*7uWXSD}rhRlbz9->1JBR_|#Cl2R=8OK|9dE(|IE;=qJZcc2^lkHf_Y^@)o`9xjK zpi4)i@dGutw14}5M*n{QSK>kczl_F%V(L#Xg{N4!|4$gR<3jVGb`kO}xPs)ld~Z9v z1{v~v+NuJ0P_mQU$+jINNRQ`ObuO4<3;Gp;=K>E(&gK`OubXF@5!dw2A=zWUuHXzL-KgE>6$kVA4!1&nvcijjI-fOn>Qn$1Qb zGIaJ3=fL1Obi9w6e=rnQA0T8PaowC}FS6}N$6Fv$ZvCb5&rFAR7@}h|;-B-|RChmS zF(>2w|JgYK64wl{m$!Ic9lB|6k;n3Qi>JJ&ONUO)oAE_|4oE{ZctBYxanB?=XJHba<~ubc}ZY zbAC`;;_)&a#@#!{-^)}Khh0J9gl`8Zr(I@wym5+0w$r1dU@dXk`#=3Zkp}O5qRmNE z_g-`NHai;LU)h%JhVg#%tc!C0zwW+iY8Jq|ZgO$9JZO*tpVW>?fz?~V=VPm2ysLOM zS3m&o^(R&h)ZY$;(nQ3(Emol8U1oG^G{U8ua2$zSB78V-)k1W<$1?Tz9;+T=I=l}f zItnrJbJQ8rn)xrz|Ibcne&wl+eK@iCRfeSTDK?hBAbsj$sT4groT_Ju6=YM269Nt1 z5xxrmw?#w6k%9-z zcY7-o(V>iyUx~xUO?UGdcW>OOm@N$>biCdgRo3J$^O5zJw?=UE>EL10oDY__{{8;n z|77Fyf9byk`hQCr4@$@_@}+vv*UPp7Xdbkx(y#z-klb?5QFf4$^zSbH4m?Oh%lqQV z10-l9VFaOIiqI> zC0M_LERQy(OUJ=rOW1<|-WD`?AMknZPsRKDIdOh8yxX2F$${~1UO=Yc9kXSt^e2Ef zF;`^10XYAE(eo$&KDKx${o-Ju6u{fX^7YwCFvZ%)P8sv&lcAD;VV@`neTm)M#!IjG z$}hqdB#z5gVDyA4`VzZ}iNRs}DFLR#dp)8<5+lEf2g)wDJsHPa_RHGS*+Pw&CrELx zHG;uo^{kI~jr>k}bm(X5^J@RO|8Gu%cf84P9TjiC(mq}^ymb%lPKWU}&0kHy`_7vP zEBJYfk^SQmq$m;;9ty==1-G{(gx9gj0=!R)K&p=b-U7}pg}LEmC}flRy6+-xnUH9B)}pgLmAlBFYES;pMIO5#>B+c$2>WJ`CgC zX{buUo3r$=#0!A8ZPU=D$}kedbA(hmiz6QDNi6Y^2Y5qu)1*9r_aZ6nZ#Tf>#Gai_ zghl`GIB~-I*R^W}rU;vnIJSk_O7j2kIPvQ7CGTW*FyHGf5r_^mjQmJZ0mRcJ#@+jF zquF#G4!i%4+!SpU(k;gFc%N5wx28vj%B}4S7dKG)e={1q_dl;ZPj&ChJo~xP@OGZN zD+b29-gA<&_ZIvx-LnVXHj1b*^__x}?e%>$jl8>G%SSN2B-L4$N;!>^F9anR@& zV>4;sLEOiTO1}aRs{W~8qcs%@Evoga$v%kgK{{HSb8OqCh#E-T3X*YG(suL;QcwR8 zd9$e+(|OP$M29v;ew8|JYatzB%u4X@|N7_dZ`%|=#-3tv8!dj!solZ)Ymla&I>H@q^ z#`&xBflurllFw^``~R0Wy^W>;-V@r{()?Xys7*#Y|FJ)MgESTUe(S>r;>2boPJ&oE zXQ>l<|6kC}6&_@z%yf8vLv&oi$nV3Zrpf~c8J}XWCvpW`@@vNa-{SP%kiO70EPsO( z*T07@9r;3?&g-5Yf$_GX!TZqLcWzX?E4mUy(D0Vt&@Tp`AkEH`rJNw$zR!?M0C-O| zEN_cQB0_ZM{cKKLvYH}ye) zn2f|3%%6Vj^9`Q)5#X%=qV)G>d-VLo<5&{74{pJ!++ z`UxDw93)P8pi0;(5*=^nb)Cy|=xHj&~UOMH$5^T?kuXm~$ZT=@p>|C5%uQJ&bj_8?*)9^jqV&~@NzFbOI;Hpp`v;C)tC zYONT+TfwJG-WuSow9Yee{ey7m%TxajXP*Gnf0o%r8Ghqwio}md-2OKFPn``LQRBHB z^)8L;FdyFXhz<^n{3_L_)lS4S-XPhRoxZn#AG`k#xO=%!(BdG=UsK>c1LIxJx0tfL6<;sR9SrcsDc;|*0-XQ9%%w8? z1K|DR7`Ylgy`^yK$>})&?*d}H+pULT&@8DLoj5OlR9p{@?#iyWQ6vf>ang@ZpA~T0 zfEs^e&r?Oy7A>Z8?<7RWb&UMNw(?vx`!7y!5i394RsMjzdMn9|Z+z3Si{^kt7z~}{_wGvinoAMnm8KXl35EWn-e()KQgpAA=lv-J^V5Z>TbH> zr5}Ngckw3NQ0>{-#4aSRB~9PO)E^!1)(V-Rt#34$4(}pFM>9r#m(AVFE5{jckX-8Q zCtnI-b)cG!z@IB_Kn-bb4zLaBHw9rYJO!~5wEa|+&m zLS-Y^*ouohkC8->0(acF_yX{9JRq8}3HWpKXJ))#$qB10k7qVAan)8U+t>2c15BDuL=jrzUl0qj}KVz%7g6J4o!Co=|R(3hC7xO9U09^!@Dh((6gk zgMLFN99Uvcypo#B4=P9-hZ}=6pn^P_^=evs7uZ38Q&aX@NP?J(#QEsj zDFu8)UxOrOcfMI!#e5s2a}gcJ82JsjlcJJrHu!osK7V&Lu8yjpt^0 z55m2uqfbZR%UjZa&i^~o;C(7`;RY(+zK_)u(D2qDn%fI6u}|Feq1^vZ8!UD_3h+)J zw^TfyV3FH`W|!d!7XXx z3=*dkdn=J`6Z#Z;_G-qOzYrIx;Zw)6+aOrt*OC{{N)6m$R%Cb_E%w)}S60 zp33@o*YRo4qhroPnL~5`+#p>;gLk^ownQr4JUWeXXm~3(k;pLKKWDlrCrCFwZq0>P zZ}kIs-z5ONZ=6%*a|6d)G(0B-1pwZ}S1#gr0p7_Hb;Oq~WavPL*i73$e7!Y)urf_z zT8>DKt5=?CS+NQo?-#ceFSo2-z;t+DKy-9t_lU2nFpT$$Mit5ishxc^ zlm+nqDBa9 zf9KfN36{qj=W&-l9T}oQ8~+q1t7-5)@vA<7>fSo>UNUHScf79lfcM^RIBubQoLJsL zdBu5v_wI#;7Qfv|P%KHc`y+V&|4B!3g%H5ote98(1i<^!dG4Fmvm&55HBorOa`ep! z(tgAJWfF=+1tcz(%k`ni74*#sBQsszBi_undTWR1Sb~vX(N4LS)2jak-Y(+Am0onb zy+v~HyPzn<`gpIr?N5&mVoX_u8z@fxz5kEawK37pLI1yw#)Gm_-3_Q7^xb5xGMWdm z-w2-r_y1!Df++p}p(ze?AK*a=UE?X26~Plbcn*inV2X{^yAvx6dyvTc69<3?1>e27 zdJ|t5q_xtoRO25$vD38j{fuWbp11&s(<-@ej{Faw*ojqqer%N!^Bu9PMs)1Q$j>IY zSRyUH@%eg|KOi0GpDRX>4#(ExUnId9B!IUo4c_N0 zzGzeN-cmHGgobzCey=4k-hB((DR}3;E`8|_@E*~~)BL@F1TD9lbCWz72MPXkO@XJ_ zq)AtgG=TT->YjJEkAM%P34J8PCc#8;-C+N|!GQHV6 z<}T&*)><08GanDxQQiB>h5d?Xc;glv^@H)Q@yVy)owxXv7a8FFB(7&|g*6G9v%<-L z`Hwhg$EvVHaQ~mMvGT%ofcL#7d7Lyc40;qh?85#Gz5id`eo3scPl(ur#D$ud5%$%f z_y2?DN(Tq$&1O2htq>jk82JT8dL9`sWV}Jj8`fL%frx#*5a z=&)<%$vV29^1OvJ4c-~ogzc$##|yj8LBktAicf&?-qowT6TX~iXF_}*3-GSUv<_Ph z_TJ>hmVFie83$EvU9lV9oDllys8t8>Zu(WCwJ3`W5$sg6HI|^`ed1ux8Gjp5qA?Pu z>P3+IftM@+C<|)dEsItst0kV%WI%{(0!}3pWrpf!HRUs zCwBbKabLX(JScr_utc;R32N;O4_xsf4ib`?3WEFpfP$GN$-sk}Q$ON=g@!>f!L7{& z66g)mo}JZd$9HoRBayf$m)phf*wHJ;;b=^;s`n_{;iI`T2{+jjAY>jrJcE694` z_t9gwusuk3k+7Vq_yEhVK~7)drAtTprnNPn(kcD_MjE_xm#v|EVi$hiVuovUJ{sQd zzSUX6J4l0@Cn-Bf9A&qC&j7ru@tZ^RWx)$lC331yN8_Ncs}|J5cys<<-JJmNUbnfj z;&DJ2G^a$eY9TK=-ZJ+0#Nu^0h_XoBa^v;$#U|0G*gao;&Q9K7zU3`JM8__S{I2#K zFEDUl^1?r`i|xC#>J}8r$c~CRQt~k(gqs5FUSskqq?_^Xt^31 z-gUp)&ck@`cL$(hO_4bzgXwp`Iw}X?-om%C(H~rI={mDL0LFXc_4*Z| z0Pi`Q_AV6F42Lc#SaNcl%uc|<}%gaE8JKq0l~ya*axJ0e;V_bRJ~+*_vSeJh>so}OJ00>&l6AS|JT#t zo!w}AlIq?b1+FS+c-yCuDR}D?Gln;Jx4GXE@a=8w;JA+(9q9dk;{xXc`Ip#<3z0az z4c>1qRiYOs0jIJbBpQe^oqOLybZo=OuO>nL-p?7v@7@Y5@Uw{K$F99`PKBLWiJw^> zZ=7HNT{>Q9guECm{oIh9i?$SpK@7c9GUk2=NL6!b4b!<%E! z@CA&ws@($0{r~E#4sXu^yvxfs8@KC`ptA9b{wRQVNRR$?81GY-d;E_8ydR1kb}_6C zg$B#x@#~$?@jgAa$3NXkoY;@VJzG(C;`UN>ygxsexbwSv9@F8ShUoZ&k>Btox5o;# zjN>iww(?uE1$O^$Vly-S&^CbO@mA{jMVF3@kD^XWe;OnY8ocv4iY=&km#rz(M8n&0 zWgQ+~z4elKNWptO?*-v}fH&#qnzNajBnba3qF@`q8#pj41Kf;Gejp4=Z$58lvM(C{=A!6=l9JNaGM4CK&m>w`rdB zVHV^4|E5BjHzjiP9FRUePf{f z|Fl{Y#@kAHC*^UX;<_}i8vt+fPa45?sw8MTQLMlL;Jsm6nhcEhuWP|~(*fQ}+~cb? z+sM%D4?3$`z0n(_^V4=ol+&8% z(D2TCGUq&uce{r(<$23%{2N570NxWjPP{%NPl6Ig9yhmUYpJQ#1lxIibmdtRov+3{{<>s?aOYC)jA<~hfuBK6<%|4iBN|1Bxd z|NGK-P>F|E9Mywl=J72-^PrNkogJ_T=|zcB_Wxu0>yEkt4@$Z}GEW*JLC$&nzLo=V z&|?nV5+2||7jz$#339eV$L1=L#PUO-Nz=WKl}6|lq|~CGMjmkq;sg?RxO4PssyuoH zxzi$C>*{glyZQX{WBm&9hzeag z+LC?G3B03Jklr+SUt@QBPsMwK$VELgygfq|%wfEDEo-GTNaM#pOa=hFTi^elpAPW; zK@yIVc^d}}sg#Jq2c(s>GF_Vi-dcR`tjEO35cg4)I+aW4co#o7eR3vBn#h5~-4(hO zcZ#aYH~Lw9zwKHmIB zbm_2KVc5MclCnYSMT2)ywde{e-gOGwbkXp(@2mI>uij=`#88&E?nttYhXcIHr2(=; zfOn2a^txq(anQVVUUT8wTf;gMUY7yhDmCY$BH77MQvLk*M*r|YdRKl&`GqNIVgeGk zp!?H^K`6R=-!}c26yw2sueUr#bW~vEcOLH+OtfMg@B6#F&3CS&<9N&Uv)>*E?qYqs z1qqVH_Y`~wxiJmlgU&-s@q2gT>XRU*V_tz??Q!w70dn71(Z_5*01C9Z__xd=R zHxWosp@H0|9I(8#T36i)KHid&tJD|^@SeiWn)xn4hEl7!%I5#Wx3^cg_e*#dN)eAC zaowpi*5?kR;~gi~x@Uzv^SQSbq9Ya~zvAR}mt#c6S8v-gmF(ZH!NxoJMw?|r2rK;C-tS9KzAJUd&$foC-9({?{4|Vp#Qhl=DneCJ`_s3 z6-a8)L$4rrlo<(g$pnK46uVE{d1Kdp4Ao(LYc4Fi=)i1fE*qZSM zX-<7+_~&-)`~SFR`UK!f)UDc=XwDfY|kY9lnfZ=M&8 zgz;XwbdYj`be~%F%M$?a?PcL__su6kEy3Aa`g`IapWy~xE`ax-$9--CfcJpkP2yZZ zGF0bU`DJq!I^OrP=N>P0;2_o_aaRQr9(Ki|<6Z5Ywy*su^PT^%LUi26$j@2!i%G0J z<9H7oZGEf2iG6}JDzs^z?A#RA$D5~_E*&!3-^OZkDE+@b4c^yBc>n7Echw&=M8o^g zuSLQz-b=a^DF>vL&t2ONpZ~Z1^enn(5eedsyQsnWA`bedv|s^@w_bmknLfaqw`ekN z#YiZ$tTg#;X(T${bp2$iAdaN@JWYN9_V=6KUn7(b5V}z+`AUhVTY05#z&gX z!eqwr4vq+ylrg~GAZ;j0b?BC3{R*-q<^)|j^a5>FxOP$S-bRCW+2gToRQFym=3{_{ z_v4F#Y4G)yQ;|B9>n*#|RzKeX@Lu=&*DC;PaN+X0|Zi`*NFHwE^Cb z8eV7fy$*%e7jL>ScPBdD;qKlCfA5(^bVcHL*2L=iIiurkd{*H?g&^}?kPbt17-8f$ zzwt7kdN1R6OZ}8tiQ~mSoQRVj-7;zZjrHBzVT?W<+Sfjr{3%ZSXz(sg68-CXOX?%t zrD%BL-y6+>@iricQZ6SJ=c=uA0C-DEY3#NDdv6P33%Zi};~;@KwVp8E1MU&476QCS z-mDw`+!qQZHjLl=6o`&@=a0o#6<3H64DZwsExb415`b90J$aVPVg-g=DaaL35c z?V1()cm?Bl2YzfCl$FPJ?=9|CmJemOusq(P33TeHd-dvE^1tW*nX}>lTUMa|-$~;^ zRZjh~@DvO8|2kspxX?UEB42zO_MpH|U6cpX*W}{I7L|e{cEPFd->Q=!uVqBuoo#WD z%t9EMDuk@gOqZdher|Mot{6+X$t!P zL$7t8hqT8*Wg=VxY+#E0QXQ9b4B#Es84)e5O@e-e*|_p^hF+hM%b?JiQ5w^}}`qzMANMML%+ zTni3Jx6HE5J<|~f6>%=tU4?iAj~QTE;* z{%ZDl3h?$g)AVllToM$*{r>jh&NxU@^Kl#p!29;4<5Erl@1-AKTvZ+23(YSwZ`={; zi~7$p@6a`?!mc+2Wh8Fi@jbj1&g)R)x7+%~)1fQXbLD(Kr9s+5 zgLe%#PKSzjj+hib8s3*6w=o#+#{(BAc)Kee<>do-Pn6|NZCMHW|H6X`f;Dka?hoOe zya4Y4nT~J~Fvae{b>8-SM26Ci-#`E2A8wG|-zoCC_s10BFcSB8r1kCL)#!M;zKGGU za^_F%P2S)E%Rah=Pi`!)G@kCY2p1iN(H%_ z2JicC@B2~l4znNUMZW6R%}U~Am}4;kB|7fxqn8- zd+pAs`Yve>rgQIEhz=)={A{d`4bfqXkzeh6Lh+RV#;>=8rbp~PHGz$H zT0qF!BiYd`UwgYg*-4j<2qiZ{Ecm>|zx_WG_4#P2fc`&%#)BGHAEmq?4NtLpf~!T* zJm`k;v?II*SWHpTcSc5upvg<6hauR-E!_h&X6EM<8Q!bK<0r6WpX|L=hHlpUmS8oVEJ z2boc)SfN6(S!j4K=}{0-oJIcyy%zMBl0md`XV3r25{;+4Yp9L%01EJflnefP6#x}i_8Q|^ZY7D{t5 z9p3v99X~MgJ3q5yk766+OYC-bA<+7fcKH>+l3?(Ns!f+6x^fg zIOss`)N?6-cah{tF_o~bYx)Ux9Ls0p$R+V6=YUbf7#vQR!qE4M>d5N9>`^RynUqG>C&;p z$g(lJD+9)xOoMmbiB}R-ymhrM3!&kCedQGy81J2O>nV6Qa6xC<0p9+4rWbaGlOW+f zj$eBB6K%lkbouMW)CIw;^dxn+n#wQzXb zD>5AD#YxNJFKXwKm~V5U64B9&k)NsLkpKB)#@&0Z+_J!9BiO~s1>x`UXObdW9&ZQV zZ*=KM5f2yON~84up)`0u2tE9Yig%u9j364`6~DvSV7%89e4{LH8SB{i@`B9?({FtR zSpg)-jm@>q9_+on*Z#>T3hNMJ`#O1>b|xpyw2;|fN8wa>G^=M6EAxApS*j_VK7@%Gl%q)Q4tVJwd~ zt|yT`9XljftApz;|MvfAO*a$$JZ^nFJBpYJG{gm^)7ci zeE;92cFvdvm}2kf@d;f{B0=v>?`%8Y3O=zLDW0hSJV^I(yY(&5AgvfXu+%M+4CU7y zZrh=UUO`qgRX-Zd{6@$|;?C=8RiBnauOPYYrCtyPnQsT_I--LMBfpHc{to?xjQ9U% z47}SNBk0&ciWK+TByo@Bzd?#)6QWB;Q5EUuz2Eym1sTsqgZHC($0n$Fi_g`ULc_aq zAA2^8_wbV-$_-M^hva#S0p5)t_6b=ZAwlHjH*>n1RFHN}t#W1n?m$dLcH)Q&71I^J44xMIY{#t2)HxJT<34`shY$GggUB2Z2DH`DDPDI+@WVC1)^ z@W;O4M~vfb-7pq(WtfiFTT&B53qI(uJl;6bNcwd2or~7_b3u9^4c^U%msL>lu6E55 zN5k8o$y^L>kZx%%r}Y2jhP_H_0N!=>?Tvd*g2#zo*hjB!h=a_Z_VdGdE7`fp*2Al} zf=-K<^MygKHx-TLFQDVymdd}4WAr`20f`gZ#BHg16umf!9GM2|XDlmyI9i2Ix=Q#fC|3}i`-Q?Q!*Y%c? z<-THQcuywaoM61|zpI5I6HY4pKjElB)`)Sn}JT>oQ=9T~lBcuCs{@S>C;tlQx0A#Ga;h zb7oSEk4Qk`0!tr+O!c5wkmc4pp4jY?VY)TQ6Nrv7jQs9AuI}G`c^2kQ(BJT=R52ysKA_BadbR?lVm!)oe>?i82Ra#AD3D^!8qQW z-npKO2eJGA(75L_rDCi<#nwK3L6?qdSQYR&;|Bz&kVSw&PZS_tvj$xyRMO z@)nNmd+BX-yzh;+oIfheK`cY!9_s9EXv;#!d!BmwmmMdV@Oeu_$6Sp3NIwPd#F{Z) zL4Mwn#dB~U9Xm)Vjvwm1)mgrR#AP_qr^Alxkp`vzkLRGlyCb&cB^B=vgK4s8c*i`b z<%5^EMxO~&9!R^95)eHG@QzAeV@d+YTl{$H4adO!|BX)u6chp8V|o#<4g$Q79widL zHj|+_U*%fVJkcAZqj%kxYv$pIQb^o-v9+>0?a&(}_S4ZCZKfhj=iY}99c&o+ebBfr zd|#Mxy!{L!MVc?uaXInycKJTyRo2J*W)NLEa@eAG6S67pji{G=4Kw(*aIYp$LNie4tRU(Sx7@Oyu8J4p~HP0;JtAB zLB4l=;Qjyho6g7gpyRz``0l%P-qVDGNZc*%K&_3N(eZ9~s9w9ff}iQ|_C<8GVdR&Q z*P0PGz&PIVWxXFCJi^BNK(>l^ z0v`qX1)d1h3EULO7swPi!dJp~fiI0Ofsf4R&$p3}#An8*&!@^K&Bw<(%{#{XinoKe zmbaYu67Ol=L%fl^fxI5Pj=Yw<2D}=)^1MR4IG)cuZ+N>LvugB;H|8aeK86mev6q;SM??B?*{SjVxFgUF%H zp~NB1!G-^he~<6Qx8m;!L#IK`{mi9!>#=BBSOUk$S<6Wqu#k*A2 z;nz|}`pXw`;GL->J&Em~@lMo{&WCYLyd!m_ePfOkehqb`bwzg)??4?bBJH=pucnSP z)jwUrlc=Kwqqpzl?WrS;7PD5o9d)FBL^B1yiaMI_(P4>SNgb&zc+Q4jK^>_~b#&ux zsUzi_xQ{odjui5J z^YP26Bl%sAzTnNMBe~_ooA_nak*xHz58jkIl9?@0h=-^nse+4fcp`NqNglAn6R0Bz z>#oIk6Y5A@NAD=!m^u>u>Ukb-L>PSdQuLi$_ zIuiIikcnSR9r4%RiNx#wHIfV6j@P4(c)J28@Ve9ykJb-6ybg85^_z^tYg0#@pKV6) zTGSCoa&`xP5p{(3%8AR~vF?#U&14eIFkC7}kqI(77G z*Jd;PeClYLU}=a~qmF*gx^M)qN*(>^*5k&jP)FbM2CVVQ)X}#+Lf`Q7sG~{SWBPa{ z>gcPo#dG{z>gdadCpmaU>gaRD(H8t1>gZEm&Sm^;>gc1-#57)kIvQ6}^ux$kmM;(yd-rr_-u_kUV=J$ zo0aVT|FQSx@l@^6|Nn80sS+}iGS8GTC7q2FNjW5$63Q5v!x5nj4N4>prX&?nlm=4+ zNtz>5MWjeYDMh7z?|s_){?6m``0TsSx&M66`8>M+Xx-N1ao5XzKGu7!_j>R5n?%kCsMQnv+nU6WS}%?lc#>wK z)^j15A0$51>h7mllV+e+*SQ!D(sb17%s9(Snub~(9<|R%yr>25x085K3*Me2aibQz zn?vG4Ex7q5aiSL7E09R21)tg@5m5_1(@fT{r-~JJ& zPz(N4iueA%;QJ|vUr`JGoS!(3 zTJYD;#4o4?-$P9Nj9T!ut;8|Zf^WGbenKtyQb6KI)PnC&BaWgL{F)JQ1hwGDUx*)2 z3w|qu_#U<3rv-@bPz%0^oj8nGYeH9FTSD56S|KuhyGXlGD`+Ttij<04Tk0&zNGYfl zn7U}3l#E&dc0S)pNvO41@4`pYPSo=I6u?E=fm*)R?|zaJQOoBP`6(#@wY=TL9+Bcv z%S%Zuo3tIZHj%bukm69w^O5B}QY>nDWQ6`AZ9^^hdfP5i3~FuAzI=&9MJ+ew@mNwc zYPo)2^PCigS}wV1;iO2^a*nxwnY0zPoNQx@NfD^!$p0XU6pmUB{gVEqFw|OmeM2NE z6t(R4_)L&OP;1TdpZcU=)Up%KDkBA<7Ui3n1!)Uv*)+IBk^)g{^|n*vqyW@fb@X&R zX)|hBYnp!|`6HGc{K7TyEo#9J0uzT&3w}S9IEY&CbCbk3s0F{yM|_Q1XLm|j69-VM z)b#Xq;w#iD;jCCj>_@HB&pJJceW-QnlDHi4C2AFK6Q&S*QR}4X8arYSY86QheIvd= zt->~roy6y;b-cwYoA?a13J$t2BzB`#{<6>7#4gmz<2T$z>_n}c)}htJ4%9k!UciRf zj#@{L9!VuWMXe)on(K*esCC$A^Dbg5YGqH~)_s(io{2#m1%P& zh4>J)G8BAv5+9&e`n!+MiT6=!|J^Uq#CxcFu?DrMPMihAYSfCJ<6J|$idvCFA=bnzsI|53{!ij%)QUJGu0_0rTHy`} z1;i@U3RC}fo_GRxWCznSczIe$3A%wD^P1oWNHTSJZc5%X>$|Lq1NWF zp_#;T)bj5Uxk4;MEx#h+y~MMB&;PT2k4FFlQa-vpNVuv&_aMcV$S7j%K~|n!oZkrc zAT<)WT;TKnI;U(C;U{*V`@G@I@}NLcr;Zw%>py!Ce5oj+UbGwAS!%XAd)g*!jX zW8tmOV-|c1;N7~|)eXk`z^Y%~u>kJ}hKrUP`BR`;H*uK`fcN9gI^h}s@8vrtJz4tgE>oct$s<8Ll8gvg<3KFG1zz?{H_v`?5@Ugc)vz;WZ=YS z)Tw(;`v~)Rm(PD+bnz4Z{NLZp@ASC?YuJ8*^r+RJAsvlU#UG?|X%nRBba=ykCyMu$ z^m;igytA6WuW15!b7cMYfbka4*t{za;9Y;?@|u<56lm?k!KXpblOVyZ${Fea@8`Xa z37r7%l|~tFls`s8W@-Iu=Mu5;HhDR4YR?G~vJv9ki6d;ho6IZw)_?e%Ilv7mWAIUy0oD0PiPv++Eb-DNtBeSx@{jgEesww1_??8Y2c%;XF7owtb6F1W zM~IG5ocIO>bEd7xXCCkS%e;E2t@r~{Lhfi^O4tzl<88y3j`XAR_;d4V*_)RRZ+K@A z#e2-tLk0`)pUVc;!>6~7l{nDO-liVO5=;bm_dJ{(>jFMboOmRd`5oY0?R}$M72ur; z^+$aLc#C^BnZ})KJE(bod*J$pa1*MHI1$k#=rk>q4=HR^|B>wUwiX+wlJi_xZp_i(}chG|FJ>$ zPk{UXS#&uFo{gY6NXArJ9V-Xf1g5Ql8>Bf#@7BXhtf}U(AN+}(v`ySz8xwE_=|t7q z;rmIDQ*7<6c_0T3eoT9s3v!U}#1_*Pv#F3vXi7y?Id%mZGk>Rzr=<$n9`O^RgdUH{ zz^)**xJFf0*DPSU92AA?I?EF~SG~6{OqKjGUlTm)U~Je+%*( z#F&n7(Xd5-Do8;(yy0OViZ{o$H>y~8uQ6Fngz@I8&vk|IK78Hwk~Y9QZ^-M4)iMgS zNH$=1061dzaw5hT#`{F&0b(JH_js0_#2G5&l{_`o0AVk&zA}oF89^#!H^fi$byS&) z3icAK?Q~z_Kp*Sj?TzTr!ig`l+hm8WGxK=6T5t7lt-xPm39FNS9{oA<%D<7r7Js+A z;2R@4L|VQ0rk$o$kOFjg!_#XN?~jugRj}|*JYRGM-o3S=>e6;^_s6eK>5p z*h&hdJIWQh4jhnP)7VIY@lKdnw7wYNZF7BggG&k(BBkwlW$b;) z-ZCY!KH~S_p~?~2VeH~W^5cPAs=5Ko6(?4R4so3LN^^G1RrwFuJ1$npsAGVE{$IFf zcYf0qw#S<=t&brcSAy=V`*+c@_e?sx;qyf(-ckN`N?3S*AYblj0C?*LjIE>9-k-AX z!~neK28;CzJ5wOH0mZ9*-ANGFbE`Qp-b<^b%FhA3w50GQD!>(FEtiWqoP#cz%sI7d8puK4 z9%|3X!S4TE4Gnrk?PbZI5WgAY_jaz@j-7+zpT+Ny=x4q8zayd}6eqs3ssnYa0+?@* zCPVvoRc15L|A&k5evuks|Ng(|0}n$wQsU3a|LOll>F|b+45N6Tk$N!?3-9ZjwPj$u zr4v@sCP>0Pxt%ot@0;z1Vg_|7P>SME)g*Y{qH{>r6UMuuiL4G+kYXaXVgY-o&}5Ls zTWLA$B{uNZw;YEZ^5k*EFZb3D$&)~rz5FNZY@%{YyYO{?p^LYFE zpPVF(GEhM}b5C+9#jt<>fBoqMBRaYRgpMz)qE(P0ba=yO;8DCGu@WsTysKT8l)&@< zVDW&BaQ5DKWR2MwfVW%Dyhp(X6iB`$Z1UjkB&g=2#&H;L>Z`{CMF8*nH>DD~e5laY z!P}PAKe4m-(i?YrQ;#W6{G|IqMaQJKCwOC+waU|NXG@C6r1a5@bi|*!gP4UA9bL3`&^6B#KOC{ zahp1f_Yyxh+VPe&)8L+TxH!4!kr1$u0#*5_xkTSdf|9w5dttn*e-?%21H5G;5t_c;2#G;;i(1fcMR`y-$t+yltLM z?~GVWgqzv@mUq^ zF{|CkJl?+RtPB%X@bTW%5;$Aa@HE@k-amgSF{C4(&|f?i{rCPqcIp3T)8!!eJ54kP z4J@3#04oR0+Ltp6ZjgQ&Nz)pn_>IEc=fNJNY|mB0-KrF5jEl?B?MV`JPi#n12jrlK znxb0aAP0GLEUA7A&LG(fz3Tn62)jXQJUnMlVwNb`7V%r^B@l2^7P~>R3x2$KiI5V@ zRgkra4s)FNe4lA~d^2M{2W`5Tek*Yqeh#WuHId|z2xI#t)_=JfLpt7GpZT@nFs(t7 zqQe{h@EFBgMd_J77T%X64x7Sw2Rpx{;XT;4#<3URo!qRWU#CWaP84@eMLkS{TxD}? zv;p3;hQr)<0KDI5^}JscL50j#6PIcH%NF}Jog$8U4ly!>_>JaYlw41ex8F7Fy1fqFL}ciq{O~&!LvaHS?F;|NJ#_W9W-=U3OsLdFM3BJ zTtRvS`b%a4yt^K$yI+=zfqEyWHuhFyXK&6uzCACM#L3SQKaa19Z9_%a**mj6T-Wf3 zGRtM}soj5cB;mvtBL4F21w-cXp2{6tCpx1Acm7ZKsbci~B-d58s3`s|NMpuyq;oti zxK%{U-V$_p!&gI~c<=M_)5XGjTP5E)7;lA_`LyALYVkKK_;F%)X$!GOniS~R+RRt- z;Qs%U$we37{{NH49JdnyZ?DT^{CkCCp!}B$ynN1L>v4YL}nJ;!f=TUwZD6`vKf@$d!oS{p1h+ zuWPZ3lT)21yKEdZSq^VeM8^@F_ze21@3`nNkM~z{$IiH~_{GVKU;Ca`7xuG#|37o- zHimR~9SXkQ4=yME`~CmFErl%dcVLTMmM#auw>`l*NK7cnD{+|{0V@Y>)JQr7AF-R` zZ9qFgDyS={lLH#0qva)By^0h_*|NSN5}ZL=(J)d8e?hAB)iD@c$VT`aD#OE z6}`>>G9Y~|eWFe0`y6sL;&O9Nxn)HsC0thx)I#}uVV6OBYeHZr*__ ztW^-V68xV@v43LrqD67|+gpSPsBgF_gYEGq43HVpar4G)i;)Ag25BxG-tc{VDBjiU zjx55$+h$}%8I1Sobw0ESl1UypCJW$gy(8@aNtpuWz2j?@>r8@%o<%Cb4buI`2E^k4 z@3uh7hsuRiNWz6%k@Frl-iEf021oXblSL6fs;WRJ=Xq?r-zmSnwT_^|a@l(xqT>Zl ze4`&--h>G-pS@>`*T2yX#;+jFBz@fCmwaV=yoWY=Go-_)y}-@#&+hFUI=tZvCQ-Zt zS8iU2g?G;!BQtpZ-?*ZMHvfOj>5`TX@b3PhkbV*1t?IK)`V=_-Z+y{s65ie_@-AzF zcW>(*=5LZ-0CsQlTSI;BVB@Xp_uW_|Ta*kTe(K%r=9|i}@y@JjC)EkF-tMhBq9X|> zzF%hZzbUU~9`CEt1LbLt8F=2(sJDZ6lKqdj5bpIbro)Q719{#;nhtOH##9tcQp3)*1`Fk4Jq-WiI$h_~$86%UYuq*R~mhz_Pgnh(xLed5H+$*PFoV?KWFIp+L4q{CZZ32K+vQ zT|uTd7AtCQXFa^nAUbyA#OLUw#|v#^{u8@{Bi%gyRrq*cRCj7rzc0b|6C|O5bqwjS z8@raiGKIFir9g)_e5*f-_tjhPNLYB2ACuR@cpHoj(ms%$%6{?YCcrzK>Oi?SXahYf zKCt#Wxc|?5VoNmK|C{AL&OZ$B9>^{>QJRc~;;6@@Ztup%+xyh9h+U8ZnTq&Teb~5g zDgYbrtw-JZueY$?=PmAtj$oYl`ginbTs_Nt_SQOL^k&gT1}ey{pT|^N<=Gx@f(v6h z%pLZ;mHv~x<>~N-pQ%9cUbwWHh=sS_xbjLEZzIJz8s75~lmx2*-X)u22tFJXNTYCQ ztvkSbP1B27c=uLl{@tu9fcMDDUIn3^XsE*{6$lRo8|BhLUioLi|=sOh9NEHixZdqI$7(EF)*CqeKw@>C7JE{VZ2132P@w-;r^`X`%Ts6$B6Y0b!^%Mc!PR{51j$CPi*`ZUIt~@hYaj=i zj63P;h1ozeYmzTlf%*UFDgIpsAO|&EcipB0a!_K)_JWf}R7lR>Yw+~HJdnQPw9DLO zVe(`J#82VZ-713$>>T8M&t#PsiS;VTrHBp>ocQts-g~}IXMTw_6Lqc`dx<~)CwQM1 ziMVrw{rmqTjOj4H>e=k|=l*{+I=tbh)KI*gXG+Y#!n+Te_6c5MPjmUw@U9R^=eq&$ zHm_cF`bw+~^tiBCK^!cxHwHaA^a0+PoSJ3Y0PiQyNeAXmMMI+3AN)MK4||F2-{s(} zrl&wg{iKiTov#nZ#(T1?GWB{r>*4(Z(eW84KHqfPx(EvMOKjh8;ki&%{Qh6+?g2Le z1u?c?VqXk0rbFZQ%CzIVY5l({9p3QUfGFOZJo~3%;jOrH@(GOhsQd@o>8(mrnGFp9 z?@dQKhdOrIKvhq>7N-Eb^R{1~3*%k=ebn3-;Jsj)M0!eNG<11w*!gSr*mx&Zt*yDy zt3bYl_;G*f&WbR=#`|Hd+M}gDthc=tkLYN|iLY4Ks7`P@^V$2P$*1}4=n%t+FZemh@KG)Ecn5Q(9+)#7AMd;^0wurS zB(Xi-XLd2BgHyr5nJ0sWw=x~x@awH8-u%CJ@L=JsdNpnzjCX+SQ`&IC@uPw^e7z;X z&%yJ^X&cBs%X`)dfOp#arH6C@-YO#t8tehyr|*xs78FNAD^fncnzsNO@4%&2!MfFo zWDCU4TG%MZSPUC)13k5pBxBaQy~P*NF&`&Bx$x2#n*ZVR7TH=;Tk)$5+`Se2ae=q% zPPWIJaDqV{=|ko4@s_{m|Nlp?&59=I|L6bzIcN?1el?ndbT^p@VdWrqtJtOR8Kh$E z2ec!0dfcQ^NAL}jzNdHp>N7SF|D@`nZ;z9p%X@;1;ct+RJn%J#x7e>Aw`=+OGa4Eh zq^i6BOM~=&DtpD#hhpR}h~Kr28wHF1r9ldm^UYbZjP<@CeTnGUgcDz(qvtgT6Xus# z>o?DQTN$}x=lQR4VNDhG@BhCxF{I;edl1izQrZ$bj}CA6L3R{x4gTq~u<)jQ3K4+u zesq7*9X{T2i?4vk0^lv8|I{%1xDCWTAQP|%T#)WHy}Sh;kZ$=gmUR^1{q2)%*Wrd} zs8uvDqHqoN5-S(M{c*BclH7^-J@340EuoLS#6BssYVy)#z4QMfh>jMV_|m@HYdFU< zkGE-I(mP!Z{0g!@k+gOH6ZSv%4w$qNB2 zybmUhx5K-)9t(wOc<-3wsiOn%KD;-(>g-_~Xx^P8gQegEX_L@TFZg(ix7(5Tad7q~ zWsX%Hi-r#D@mm3|u*UqHW6Sinq1#%e$%hcXp`Y{0S53#pJ6B}7dy*pSeL?Dp=*Yr} z@5Z9!V2K9i@!l6Y%Q)g40~O@RVPRM0{{yGDzC(=Z*mQmFyg#?MYSQ6N)Spa2@owNN z<;TK1Y{kzbFy6K%Qnb%o%+rd(MFHML!3iZx_t`*s0fAqf!TJAy!3uu3L7Fzp*vJ#$ zop>lYIKY$&y^#uXLk0TJ9n}1p5i^XO7OHCSs(G^J3he$ox{dkFU0ZJPh-|Q-trC6 zF&`(s%c4uVb8VR)PW)Qa^<>fZ7R*%;ZTCbrSydV8WUxKnCZ|R(GNQxCvE3~w?(hBo z=>LC~{s}5beYzYpqp>y)%|W^A3?#5}5Z`1|0=x&=zCW9`2l-ZwH(w7dv9-%2Lmm&= zKow1n2d9Jg|IYJ0Re>K!uj4Zjdj@jQYvosqT|8nSCu+$)w;$N&|Bdg63g%ack=+qL zV?p7LU$6h=ik--a9d}e%um9IUbco=@clo(f{&{oebCA;V@0aSD@pF(ihq0}|#01;- z|2Op@hIGh1+MfMCxjoJ9-O>_Z{tIaV)&2X;gH=c)L{oq)m`wNBJ`s0lYcO z9z05WZUcRjEnoi&;Juq_Sp?&4w|bT56M*-Zy5Z8(t7D+xbq`Ay4q@ZH;aEk$kdFvC z67k!)ooln#6KuTKr+P@deW$>3N9^no9cyvo`w+WC)4Z7Z3i8lBwX-4ycX5|kf{9Le zh~`YTUt$T0x(w;K^60*uZ)Pftw=Nyt)7pc-pm_T@+lXP|?SEC#60RW6J2la+w-6f_ zRWOD7|Bo|=mOrq8qMjY)kOJ3R4wa9q!Uv?Usm+{m2jHElcrd0xBnHxZu6-l(Gh;HGetrT1d@HUnVeiKq>1NC5A4w_XRAdluCRlfOiv2u_@m%InO#IAU)MB9TD{9riU2Q0CxZ#FLxlLQZ>b*VTc zfGc(zxTN*r0cpZCo|ICs#Hw;TW!_Sbfi!tCcW$_bor6@WS1xMJn@wJT_(lBC2;XrU zI|r#A%r+o@Q)jsfat@+H7AHPELV&bd1sN7TzL(eH<{}CY3Zd@ZsflMu2 z7w!fxNR8~SD)C;k_t@k08->%Jdgf4rj@ z(-CoooU!!J1j&#NZvp4|{~VA$o8K@S3vd0hZAakkty}(IX}hBa@fOPE@Xg%Z z6lmK-nC#7#BuGp9{s6qaHGJ6FZ%Jz7h z<$E%uq8l(kuc=OBaHK5s>9C}C!3vVBzcgir{yOzt-K9C+gtng?az}x=% zipLS3ZJ^5gTn`t3=Pi~S>X*PDNJ~g4G`|9PPZu2Sb*PPj2&5UI`yH|Iu2@`OCQFbe z^B{iLxGH3Wmto_*-!ar)%Rz(Xijz}_juf2unkOxZX+-85q#LUhWCDLMaJoiO$ZZXNXL`XdMm3FfA9Z8TWps83HpCBT@Dg2J(Yy! zpsm(&idZ?QUGBFhyu=<3=A~7TM>Uf5oWT-XecGw-q6`J1PV3Ej240ZfLNc2HpFz4C z>0ROimRQN^#XPF7sF1#~P>l!`yZ<*<8H-=LRf=qk_)+agH;4So9i&I?HDo_NWxWH^ z`iPDUocJz$HI?&pW`2qNQj>6m%D@#n6Zd9*uU)#6?Q_s^UPXpOLQ$A9SNRY)5zZcHhOEdNVWqT{W;meRZ z>n*XPhz?nt_^zzp-q(1DdA!YYG!>(d<2Oizj9*7qd`xG1ya^X)9c4&ITq;*SxMBxn zZ(};VMJ?M6(Cj@gqgDvew=yq@jw9ckA-bp(Urp$qtC0W7lGn?3vhjM|%W0 zUK3}%`~O=I9l<#99T&gMeXND~3Q{}T-)-Lj{(zJ-YH!KgM)n_&R+OG(NXIz0!s)Jq zwCgPv)8Q?mqqiT$+rB?T77K6LDbWKk-dcgLX~T)@l}=~20K9Kr|8VpHc$}!G*oZ?N z;BCe^YbK1hJ@JxOEWq2G)8I)$0u>5}RwPP_VdH&y?EX1ot2j9p@te6uEl27H_5ta} z&8G6GCqApgd9#mBG5>l?_?Wxs;&=wK_lSk+Kpy+!9e>T6AswfwJo4B7 zJa1`4hqutU*9jDFInsI=EW8(M)?b0~&OW$@cD$vxIplE&z&r2hwL1l}6sSUDMpiDs zdra$^75uyfF-1WD{y6ak=V`*y6*15|9f6vPer&w`!=KAI@k)`uAbuuWV>rw1VP|ip zJ^JGt{aLT}c1Ltb;u zy>8^--~OMa`+hVyP(d!G%RzHW{7TRqbWcP~9V-VVXMfq(0CG^1Xr2T7fppHN_yZQ; z8>Ce24Ckx@8;JaQ-#_~>xpDKJm*D$<;jeSXV7#lSzh&0~ywfk24Hi~|8>CzEJsqsD z@z%Q6U!dbAM}CI-_08roQOCyH=xXCl$#K@ZVpk2(VTco-1$k3jiVXAp|8FhI4~}XE zCP*sdnL5uB*dA{}!Z*froV=2$@n?c$N{9FCrQ|Cp-ky~6Dp+{`-uJ5-#`{h4nsspY zc6@wHI1S(}a*XUZ2A;QAx$Bm~A#i(3$wO>{j_CM;6QB94J%0IJ%xCXM34EdD z`V35vsuNvn6xhE(A`s#k(&7Hte#5#y+1rE;Zz+kNz9`<}qN&PQcn2(A&<5kZtG0%Q zcXGw}NFBiY%C2Wc{G;G`i{r`9-aSZy>UZu~3gew8G}CAez}uRWTpF!Ih2rO@dJ8pT z6kfp@oAQCFZf=-eD-!ISSBQW z86WRUwI^RR{ocj)=l`vB3mMXJrmaDvbPsKN3v9e{aPLuEDSl$+8p*k$XHmSswp0vE^*;4Pw6 zt2#@T3f)<^>WgV5Hs0f*i+R@$%qBlX{34g8FSvdX8}C)?^&Yw|X1(Jr9}peOaN_d_ zzw~Zp2lLsx#DphQqK<*Xi30wj4nn)x9`E>rjOn;k%GX0)E)a}r#!(=yZj z8hrl$&T+$X_ywt5QLm)U7sWsllzXpLpJ4An?))q~=+`JimO}iNc@7*2s=?laJXu`y z&YY9=D#$2AM;=ami&7f|vPjG?u|dAKeqLbYik*`Iy-Bgr?B5`@Z)Qlx;Vtcg?SJn7 zx1hsY-e<>C6z{KtZS%13&VH`c4$uD!e)Z7i{~=NY^Axy(R8+~dueX6lrOph-0le$9 z?5f}`_Lr6u{iy)&cV@*uJEq4#t55V6W6sYTEVR+>MR*8q3u8 z<3g;ry_JCIu)&E>W0LX!y2(7=%a>WX)h4uHeiwnJR>e`S^;es|usz;!YK-X!UH9no zk5pO(xttDfIinp}DBkS{%CxZXR!rIw3gaz3WllT2CAslYV5o%tJ@6+;4sXNyu7(b>J>JCcp$zG` z++&cHc7S$zYZ)EhvRoY+DBi!;M{8o?efTa1H;lL3>J(aobaU|NmW=>!?Jw=(R%dOX zr)`k*9Dw)u?wz#bEiz-fi-WR>~ zq#|s*t&XmKn#h8$w`@anSm4ALGyXuDQ-k^Jov}DO>0CVnA1B7;TP7C0VSBs@>3NLl z_^#b1_hTwY)vF9Db zxnGV`q1@LCl9kf1bI^eoN#!PXBIG>8FX2*?_N8#_98`1U!nA_Rm2bJPhgRc{{mh{tj9NX-$W>s^^pCDBhv= zt@>Da*LPJ#!gvcU45s1zeXL^Z5`g!4Z@q{j(EqEtx*ZY*c-KrDmV&?k*IKbWtODSD z^!Jw^u`N{SO!DdFm)x=Ob}fQdX5SShmm+?4h0Zq(EU@uT5L&pr!9t1Uz96+jbj0Aq z7e#7+CX>K?1^GZLwn=me{sie~Ma?lMzmIH>ch}uZjOp;6`Vf&t>;G5M;jNI-b4XD)H^l0ck5byp_H`=|b^- zTo|T{g}3$w@pu^T+b6SWcprFO;2#F?K1}`{vb_o1-kNjtkPx^aeZA71bQo{>`Nx;Q zmlF+E$$e|gqe2Ak%ab4Uu<;(f(ENK|y(F24_}z7$dC^r88}AB_CPK74>m86DKy;Mg z#P|5h2Hv*+Fr2ut;ebUP1FyFXiJw0eT4>Am1JbC6=NQtFGIzpV`Oo&&3Oc+M??2px z;>}ZRs)L31aj$`$Fy4YM%4m3-kb>-T0p1s9mt0T3YXfDO%u~D#wzu@uo;-%}4)Gru zI|c9#jaEOXc7X~xzt}tQ$PydxuLr(wYm1jAyCQzQHSIdCZ?Wrt?`%8B_UHcz<$a9lkS}h94=4V8|Bt0R|3ATj z{@;!+2hA_j{R-zGaiJtH<&Ow8^Sy$i+QpdF5c-c)V^doL|XpJLw4!V}JcKNb2E;8z;skF(0 z0Ac4KUU^l*$LXRh*C17(I^_O6zSY)^S1*h*UqSi{8P;j=<4=$XX2B~0o4nY*K_c9Z zWlYCsb+P$>w%Bdy@SaE6u?$^eC(bn*Vd1@J>8KTqclqx7wC63OGNkO_{{PFhLs5LE zY#<3cyBr&UckLV*B^dA841>$(0p5~63S93u#y~y4rPudPVdMS2?rPa(^BH8+Ps`?` zyW$Ww-e)gKJ3h>pVmZ8f5FPnA@d+fZC=@JX9&eGzYlh;}@#p`9=lWFJy8iuP zbVx;K)kOTc|Bph4x0c$c((;jQwrf)~cy{81h4{XZj7qPYRUo3G{65e_gQ z4e_}eeHzAlMK1xyo1D6(r4rzMi1*j4I~FmJ&Peg#%syh)E-N z8Pnm(9V?>(UXTLCi47gz8Xs!@8IZm@?YR&O@6(9`*Wd=pTQ8ILf%JiBpGtLr_rzr2 z%&rO>Xzr5pva_BgLAJY7yW!!)9owGI@NmLMrRDH7KPqIvr<{Fa3VZ$^+tJ)IY%WAz zfcQPtO1pKX4}1Q9W|Ng(U_0yG{~w0vIDr%2+syot;&aSrZ~M2~%MHfyixba7n+5yM zu3>w;d0H6LA=~$HX*l>m8sNQ}4sZ4QW)INp9ZEJf#KPNTXKFBvch1#SwEll@xcfqB zfcN=@{bEnAz;ACS&ff>{=KtA9d*0&hRItHifcK6wMwNs(Dzx~T?niea?CibpDc=sV zqA+<0;`ex8)xfu}*mxhT>v4}hFVAw>TMN;#4<|m`LiwtVlg#5C@LkuU=P&~wCmO2m z%Pk#X|NeiL6k|G;`t62~xBTt@*`xnoN0);PB9xrb{{Oldg&QjeNf(rwHG>@F*7MvC z?*F@XM7V7QIY{XBF17QV6iD$Wv8lNy3A%sP%N4#sx@Fq$!WNK&ra~^b0GdZv;$jyeHJ4AcFFJZOc_yI&mK2ChI-n3_#sWYF0 zHh%Q$bBe>CAjLv)GRGgK4f^@vF?g-*XzW&U1W*7Dndt5n^$8KIF%i&!s{71)gwSSMV zRB~FFw;%I(lg5wq?efR3AfIR!#8ym%vif6O z(ijN~Z?8U528{RoifKMD-s%nEbzT5(&R&Bbqu_bV%HdQ(`ST>`v{LCBxIxlWlX0j8 zcvFOrG>~km&~4k#)7K7Q<9)=j@%B2Wp(Ra---)NwI~s3e<6XGf!ceX0TOF%q??6OH zAWnQ+%cWh6N}0!d>xp5}rl$-Xkj|MQ+F2LF_IMMvEMQE>d!ah=pWRz~I=pq>jcTEI zUzWc`#KL=Y!+;iyH*a&07mWAInAT(`fVX*;vCFONHc*TEyBbH(Anm@;*ahQl=6t*s z?*9+i-z4`9Q=#&?Klp|du!|FG-Tb*}TPK&4A%1ft&JU{lVHYRy`}m3uKIdh*21y^$ z;e``ljd7$@(SOL^gU3wHH1ad>f%NScKGgRdY~TOK@BPJ)4x8<>*ZEb^viBM~ytOaO zh@*HnKikWJg}1;Fvup6~?Xkxt8)3Y!-YvRg3Gj}pKg1=TZv#c_5N*8eWMRaQbNMfKJ1REb(FBQt&xZtA z4(~WbM*vQIr_U$`d7o!Kd+QwU?v^#duf0Fcog-jX@5J`mTO?kUAst84G!x`g{+|D5 zwQA;njR)*Oy3*yK#Syaw(HwL@---__2WgfK?Sq%t$^)FV3eqVr>R>p?L7j23>m(E? zkfmV4!0VwT$ob5L%Ss>zZHn5FElYX;@!pR6*0q@m2^S7MdGi~)g4`rk)12o@s24>1 zwhH;aCk|j&ko&V&td{*OK>lAf{y+Se0f>%bocQ(}?D7Usx8G!DVBx*ng{vCITRQOq4e!A> z^CKew-qulmrCi{OUCj!go{?ug+j6@a&~vTG3$;2mP0T;4qq4Lv`kSthm{ z8}B*m)n7dLz)|0g`1Q7YUbl8LHr@>>o|a|_tcSNUqT>Nhd}4}gQ}vfHpS|~Yl{wq3 zz{mS#Xtbr;;A^(W+jv$OLpn;HC_8o^qT%gChqqyO+*}mzGa8q8vG8sVyFMEpPJ||# z(1sJaH&%XuueS*8&)``nL4guRmYg6DBtd>ZpPf?$c+1LteL4mjq!R5D6BWJD(C(k5 z*H#B(<9$fOhGbh$s82!sK7QqW@ScK=_gJXw#?Ov|ESJ6W5gk)F@$Gsuvhm(F=JCG2 z`a-Hm9)5#FxS2yxG8$uhya_+E7}GH~ZO_p^ueUhT;l1F}#sC!Wa?d0lEWB^>`>%oV z{_#@YAMXDj4e>Td1H2CxZF>+dOo5gKlzA!kCqZ96Z@Hxg@a{Bh3G4@WYdxPM7x*9= zvVz>Wa@?@-exPsnqIPt$&I0lK)?Q7xN5;nc!CtE)SM8>;9NztijyE{*?W|fMH&MZS zaq{(DU(i4o{<)Gg8XMke@a`;E{TIZ~?$W&Shi9>Kkp45} zZ+q25SuO{CM|6;J;*%b~r1Z>*`6c%G9^=Q0Z!j=HQaRXuBBYT0&meh!WK74$c^lOK zOpx5^@HWxQ`)5Epeq`n>EWA%=zt{ug{l-~jGmLl22a+fsSYpqw;#<9uj{?>1vzcoK z@LpcD{jDs(`<2C)(O`i0WlCz)hSOBYY^3An*Cp6n>=%M$8j~hD>dA=T?RU2-^A)hS z*rkTo2%p@`dJR$yqC*iUzFH`(QGFKkcuy@pGtoWFKm|Fw+i9Z3i0v!L_;fjEMsygu z{@n2RPyfGx4sU4s$}ed4KJL{ofQ9$;g<=qlw{vkPtwGXEKNYJ4@UHI8{8}qSfjWsB ztAhaENxSMI~-UGD)fry_+vvQY`mX|WL&LzI#t()_%*!PD!X(# zHs05Nb-t38o5^z7dl=F26em8;aL!#qHq7I_pi?PPih(qP!MS!>AD;YaufcK@!6e*2;RA|+Yhq=NE*m(Dmd&Cyjey>}J`004O zv*qW-#=CPG^{SuLbe6;WBcfvjC%)dTkJe=GXCCkRTW!U2t}<{yI^EBDhUrDN$D3fu zpboo)5u`X-Plvbhu|5Kd_o3CHGqLb)^Zqk?JCM%Y>}}PK!V@o?W1zb;)4yH%f{l0W z=EU!(3a0ArAbw7~l(dE(Y`iDa=3S$F;A1(w?;<(`_WgT&8B3NPUALNfypzx0e>JuM zfA&VmoYA~f>i@v`|I8n^8PQQ2c06~i;P3pO;U4_|r6cJ7z3Fn0#kLu<(HykC-ckZ9 z2Oad5Ai+y)h>r^nOmLn&NA#AbYJ08@6Cp9b&C+c##hcVjT+cFXw2=!y_xzvESG}@5FH#F z{yn~D4+=hqX)?bDNj?@jD>Dp#f<%mtIpjdv!S+k+#Fy#28PTDCLUY!QAE1MAN%o?{ zdpV_Q9L4+7J6>@tyj>K!Vqv@mo-}*Icu$Y_HJuCael(%l$}yb+x!b-wIrJ(CT79;l z8Q$KKJ(1gy4DjwK)0x4WMukdy9`etT$Hv=_SbxQmVy5NWnlJ=%3`+1n;=)km=0OB{%u~OFy5Q! z@Lm?aj&?yBe0xj3!D2Biyptx~dSJY}@7d8Bq~el%o>>5I&%*0Lk9a81#t z#BRS_2IH;ST^+v<;2pPLlw7ta2J(00EBc@ufcf3}=Ib46kN5J{dn10frE88k39ZNU ze@fZZanDkM<+67KqN4{VzJ*#Z2s+c4uOLHmUxahrxR3dJ`KK_b%|2GWWacDq{DmZ&HA5c_BP}_DuRXgvGaLUczdfW>M?CVDku1={5Kd*I39Xw zYs5u?Dod3L-NEq|@0u$Ga{=DE`f1Q%fcNv(=DPEeG0;k5%~sh;?ChQY-tp9;jv4jK z5kIp%D#m3;v9tHkqnIe?d9zs#@6(8mF`W2*D6RUO+rvEGo#m|tsfjJPcwd#zSah&r zDcj>cCw&h?It;|*`+`zvhZ8;N@HV?W`OondjhjKjSa>(*Jr}wI@YcHu1;WKiQmOLj zAi(?PfbCT!A_bcN=)%tla5%AXXUVrY0Pm1VUx7k^_q>D|_riRrkZ#e6yGcK=XK#+0 z#?bUWDiBB`5kK^}$c$|1yjX~@wPyCM) zQ=gQsIq-cK+t1!!x>~PgM2Gj7%gd3pzy1F|t2ZnE0W7hb>2lDjqo?E1B{oY}Z7x<0 z%DJFD1>ZpuUU-IfgOm)nrrQ|ELFW?>?7gT-fu?B%juJox*;aW-Tn^+Q&J!m5@PM?g z(|_H5wHU}CsLv+rCiW70kjgpzvo3)=5AiFv7i}mh#a?17C9-5)3Iys|?N^9%Wy*!`4;pd=V$ATXCE_=lGIY`!hE<-xbkZ#!U2hk=-{&aX-Ynp#T z@#gx#GY1Rr<6A~G;7{yMEbyV-|Ch$qQosQkByByy8cszD6uHsIKF0bAR7v}NKyI84GQNq9kX~SjDLv$60FXiRs5@ph@wr`_JF8sm9N6yUu{)$>QQBn1*Xtn0lPY;U=mj*P>* zw_I7h=fVKqgNZthq{bNNq1lczb?(^xzs-jx!;bI6OPUeCPSYbxPprc3|Gj*R3%0HO z&T`-X%OW~f;KWBh5kBL!Ec19r$L;WMp3cAoY4(at(>^Qq-`;xLbbt{ZKix*^EfZ+j z+m{aS6&L4}qj=XBrb}VrEg@cg2*z9Bg#_&b>6{sw;yM6tefKZD`({!g11@`GF)*B1 z?-nr#T3ML=4%<-XK!ui1!2An=%{{R z?@~6D31@E~I=n4Y2a{2}4^G=8iG_FEw7WFCOh+peMwP)`C^8R06(!0)kLSIprcs)`Gmjaj=$&s|0gi4XoDOSOqYY!EdQyG z=AaAHWfZY;(B_=@RJi|7{C$^p2dP>%$#oCt|E)Z?YJ0DwK;)g7pEtivf^@f8aVvl& zmdE>dvNc#@`*bIQLeIrOmB;3EwXVcoV)yHsa(cB0kV_FigTdALs}^D}vEgcW3x;@Q zSgt`zLUaV-#COH|=6T7d%;zANdgBTKJ_d47;?(6iPbS$u2N43Y8PYM{m>9JPoIwJ3 z2hrheC!AG=;%(?UB9Dc)D`6l5#+&QnHyYmc*@ANU0PoX-KDAeuQ=p8dO)t~H3DS>m zmxRCvq?a|l?sfop8&_yQ3_chGwVPQDD`{inJ<>qFx^8eL`61$$*YGCq(`;~7ZP&?u6tsXbh9uI)GiO);@sk9i#?_%NXBsFZjzuz>B&M2Be_C)-+vV(^eMX~XY zpcb66_{n$t=2khM)lc?k(ZA>yb;}*0Md`1e0Tj8Pf5k zZWuWr9Y}|_O@m7$iud);du6fk-gnTg1jajhzB3K);o0|3J_mSv`$z6AF`_^>pKYPq zfcd|u?rLKgZ_#+IV*vo~$P0HzlQwUI`X@UY{rLhh8-m@%ooCh?@RFY+ek*QtF55GO zjrZ+4aaTVb7iYQby&ciffD_-j7n1fy;>_bM+hrFnIun2XPxzu9VAk)!{>90>@0%IX zAs=+`S7#nAdk4_ry?WcJe-0Z9OIKTy!9Mho!RwjNO?R%;SCW+Jf44@w=F50&Vx2b6fVjDSFQK zc-x)c#E=fJ;5kAbk$=DcNB{q`^iR+rMbPCSC)?O!bct2nEuoH;gF+i$yElRy6nlQA zGkgX~^5ons1+c}QJ`xzv3sInn4IC@HK?SMYI{!S}|685gDX|pfAdXd^%dH+!q0@7k z&e{544@h$lY6{7J7bPD@{4#^=cuiMh4@f0A#15v0v)%*gIfxDsocJ^==Ir+P4<|@J zloEyBFhmE(PT-_>YP?+3|_-VIoHGe6Ljkjo5X5+#w3M{w8E{pd%<15B(;}pk9R!R7lw2MZJx(nTSRM+Lh0~cdws({{r_UmJ<3>k zAK=}f0yjvqsf*Xcc$0u;r%{H#XkS!YhA&XcHu_K>SW>S6F=wm<*x&9j;z9dqUFzgzm!@D8EF+kTJF1e(34 z^LQ#@;oW;*Zaa*3>DD6JaALed;a&{DThKdDCcuUQP33HQs6Lzoh1`nDhO_t4LGL|g z0Pou4M^2tu90NtKb6!AxijBA3y}fc3rv=F&h~J65nid`P*u_cuY4T#qQr5$J6{2Gw zPJE|rZfne&%Y1QiDYN8|N(TdXZ+XA(Ry(_e?fZX%)j`H|1jVm|{=Wam(ry1g!GZpt zN|%E+XkWgB=AcSJer>EA)TUEC0#}f`d{)vb$l>=_(q@1L>5FRYncZ_JkW>1s?<(*& zNE@K9a1P?zWW)`D98|F1PGm(U722S$+}Wdwor4xhjo+*ql^{DJewV(rsR71&=Ym{X|Nmu6wU#iz``6-GT>HWE7WLB%3dI55 zp0Oi6Fy2nWJt=VipY2$A^@DN@WcVoYqWE=eyq_M;lXhs7Bx@snx6V%w)H;KWx3+ou z{1z28mczRp(V>YG-?>Cv{^26#@$Os7_q1*a{s~foRGZ<#{{I6Hq&1r_U_{6A;`~Lq z4YUd}iVknr?`xi;cpEM(*TTYE;Ly{9Fy5=ndT6`1(6(hS;1{I*GsKUfS5-*L5xijs}Ye;~cqztiw+1wP(#K~w(2>%Opk|9}5onI9uM3V*)t zE{dgXZ$;AK?UI`oj^b^+FB&}MN+1M!1QVu%pPn9JUK;}ZwrmD}rXJqz0pmR+&rid< zO)f7}4d9*Qy7k=yT?+KpCTzh7nEyZOQZ0k=?sq#}4-Y4n%A8HTJwb)c3k(_`q+{dV zeN=r0>9Qo5jQAzGeJ;2bg^hQ|#>CF+QmltJs-q1jzSD765gk`Nv)$Gmq-F1|ba*?*+`o+C{dN5c4J^C^*UGEGc%S&C>I83Z z5u>zz8v(rgl{ZP&a zUP@}&XbyUw^TPlu2lJHj_disSu@{Cfj3nS6v2)n9(=;#2lkIbmkht%O zZyO6^J-j0k9UM6EJ?*Z~65q@G65FE}uwuF|{shV2#<0Fn&zbG8kO_Hj9`hlRIF^0rDC?@)<#wC$~mx)rK9S9$x)%oX@@F0FJj}}li(tF?v@z&EaJCeYQciQY;3#@ z?%d0ES5iTFpP# zTWq7l+an|N7m9bOm7gva-k%oE?1%9#XcMOmCk#~U9fSbhypIWnJHhjo&V6fb@&Mjn z#(#Iic)PUMYMTPQYhUxLnqHzpzK2^ZE?8q1Cl@NM=bjuDBYPr#+hiWxo6yBBPQFPS zi%~YQ9^Mxb9iMUHJ82|t$h(bsyf@@}KXQJ}!10y{f1b}egY1vDJ&~6Y9qSKtIPA%x zW$zd|yxr?<|GB+&&GHpGSa_Rk*&qhb|NHpf)9_B7Cg#Nj@ZL9H=?n!tZ)xUduDJm0 z-rn*l;)9R3h!U=3E&+IppCp;iZ>B>1JQY3y8?f=tJiW4Th%#-`!pJz>;-b79a;XMY@)!mV!4(g}}!-i?J(6 zF9Wem(kxN(a>Vb+llRk9XJc28gWB8dB@ZaFT>p>i=*Nk#^6CRVM@{A@Nd4dZE`3~y ze?XeLwrk8&+?4H?Sg#My8PYL1qkq7dHbF`u(c$g)Dd3;yEqSlqGs402f-A@rA|2ko)$jhfAbsz&1BSRPCi@+#(RU*w=44QtXDyzI-GFgi@z=w^09z< zyvzJ&*ms!WpWZSh1`Ydey1@2$M;vENhoj-zO%cg7ygBIb_BlmA1*S*fQ)_Gp%$r50Mh4;KH@uM)_dEd*( z(_7=ktop_P?^<>xtqC0>d0rI^^+I42}YCcPH^@DBe-=3kp|5u%uS-@vH%WN&;cSB4(%|#fy|G&J6OQJ28@v?U{q9dD1eCieP#N^BL<1MiB z-h2OX8j6!Dg_bnKx6FU`HvS?_I@lMSPq6~U$>06|e-a$y{s1aSE{YtqN3JUt?f>iK z*0W>fpnWU-=fPL(&i}lDd_lU>QX!|cAO{J)Ty8SQo(Mf7kd&)H{|~*JrJxORP|lah zPCwR0Xu;Q2r>)n6_y6K9*YE#?y~JK|owWNF&1q(W_?^ytS+VvRcK<&xI&J*%3*%j} zlZ)u+rV^i2YtrK0fAK(CRo}bDs8Q-CNO38$nlBX=Gyf8Mer7%`I{aRYdgUJ>SCE_( zc<<^<{e|NFrcZ?p3-8Rcnr9rau z0p6{pqE9XWyfwuhYY8idKy{;L9-<}Kc(1w>XZ-abuUQr17bgAb-tA0my!+YVflr}!uwMDlXviVYk10xjQ5=fH*&~$2brcBuO&jR_kz!U z0C?9vDVG76&afK!w z19^t^t=Gueo1Fr0pCiWP3({b`E&3j_V&Q!xuH_z#w{!9t@&#$~uf$)#c(;#r9oP*% zkam=ol^F+kZxQ0DRD!d2;{ZQDXpm%W#IGM+91JyhH8)H&VB_5FRdz&CCNZA6sr|+GX-nfPc zeVXhN;y_y1$L`q}XLfBnwXqd$6rq4L$+zIp~?7bkh54Y}?_5wlXn@4ces zs-X4Q#mSUOHV*dWW zV>3-UMp_-!lEBA_fBS#NZTtU;3{;T(6geo6|5!JggV=ah@M7hl^mVzb;TNPA+~puY zkZ!+ct$ho~LA;vI-GbnXo$dQwEn>T(p<_G`QglHMGKjyaLIf4$E%V&5h|FN9Z}S`v z77gqiwEn=1Ftn@J^dsVzY$Ikg#f_bVL{C-i>gyP1xF>dqhz?dN@v&{axiM0o{v7ny z($>OeC-n-lr#rk?X_p|=FR{9s+I_U>P|RCi5g$#iAo(cp-q)s1z90>*ApI9g@nGQ% z`LGJXc>hY1af3gx^NF6n=mEf6#Ue1Q11zyd_FX?@!2@X?x7Oc=@y@&T>WdY?Tdgy; zXydM6NceuxWX&(^3i4TBSN^AnZ>9o>Uy-EZjlwtB6(kRS%-W0#&u~j@1EPbKN__Ve zLfzf|#dym)si94}iH0k7k~8PtD3E7*ym8y}Y13iPlV<+-r-WdS}*{o-$OotIa*+yT{hmP3UyFXLLm4Bec z$rZkPoLG2Ie_xsikWLinIy0dl!u0q5aeNx2Nyjg%M-lQ-WW2d4@beEIX2#EzM_reA)*Y2 zw+W(SE|vId<7=|^meG%Qc13#HFe~-i8@Ie$X3zQp=I{SMveBj^VP}@)-~0dmX|Wml z2hjhEP~@QfEHmUUNZ|_dBIi~m@QngnuC%BkRIRtJet zhK5As?sw6U$jmZs4UmJ5%bU$A13Bn^cbBi;?hwd3`RU7B1ne_Nibp#HN@9db9*Ey3 z6E*kBKI|MMDqoaiGE32n(SFyc4sj~+4K=ShFL{jq4bnufo@J56G~}Q%mqo4(O@@s2 z`=L9YQacNpbX>e!ull<|5~jdAw4t;PU1BY?1%s#~>nPq4(~nE5JLL(e5 zg#hnG%63I3cM>77O@o_l0p7Dt2rFm-yj2f4D8~W3XA}zJCvc$1H-}- z4OIWVoIU&2R%dZDeS^dm-%XQ_J~MkGENK3C$SybyQM`PsuwszmPKmjZsWGJ-gE*$gJ3q9TCLK@bJ=*R=zMLpVfCBHJMHxvb-aAwR`LOVI z2x~t8Z%#Z-e@EVX>-cQq(gW~za-5kTu^L=XTt0bE1>h}qXnqY~Y zMUjIJ^04hja}ZH>@hq$yG}k*|Gu$98dKyJ;kZgCU$h-tOs7mC$O9nYZ0Pxp*7eQB>u6f)TtVIQXb-Guu=8-q8r#1 zWM>qouf=w4hN~b^9n|8>TB&HaIh+0l$#r7)?DV%ZY>*Dx6y5CYV*VV|XF{6}j?p=q zzx#g)3cMq$=SiV>51+?LVBvj5P5Ks$x8=s6U2p}N#&yx90^lw4b@sROr-+ck+gT@9 zwnsyU?&^2Kc;BfOIWY>B*x2f5woP|Jq1ChZMLe>@eqz_ZQdqvJUY=x*_+1WR-~JZD zeqy&#dc_{U9gK%Js^ck@_(B(pUnt!`Ki*;H4lI)zG;EO0En3GppZTx1#7Q5fNypYw z!LWhLJM?JD-CUO}$UvJlHHHD~(qmc4G{ zyDK#4c+>6|UcH};w-^Q92OQ)NqIeg`rHf+W9rkPB0F3t$yt+S}y=MlFPDKN}w;$>_ z)EG~M?9a&;gnByLIreSkJVC}lJ^DfN4 zIdOi*o+cf6b~lZG7bl_=c!%5HQbX|$PS`1eiTA5oGTw~`)ab(d_=Ah5Yl=gl7=o|n z$ZG7`+k0de%glKR(m}+}@ts)wHErzLyZ>W!^GPvfhQk}xF-Rr8wMmLc_uA2qwx39USo9XekxyVnGjy-RZJvC1L?f)6G;s1}QK>t6RA_v79`ZWHNgCsR% zv2u{4_32~q4Dz6s(hhium3=epGXj>_DNdZv&Q>Bc6{J(a`YIZFuR6;b{st-hlBbg$ z=>HGfI6ta99Sj{cI~J^{jy;3KpEUf*dPtZQi};P~mm7V?g*}7xb@`=uOqB8V|4|*g zsKh6DMLu%<68cB%%VsH0R>jfK|BvQsIf>{oeFcfbkI|-s--RdLNetdWlA*vmruyC* z6z>cXw%J&CoBvXJ1mk_Hd6bN|S9rnZQGmC1I-l~#Mk2IDvPALi%VfUneKV&$NQM13iEgOp8VpAVdac4;J7$=n3r|F270qSH%+ zw!URO6xkXLO)RSSQ3N??WJmBTSCE6kG8b&m1P#)1n=#_kv)DOE^=lQ!+jIfaQp8Vb zG>U)I9~vaR#7~>D-^emt1*weapcdZ=0pbs$3jIs$3CX4JpxZR`|0bmSnk9+MzyDA8 zK${NP35nk?NW~~n;GIxVuZZGZ^>bJe3-3?Ddn@53cC(H+`GEAtn=jeL0p6__o~tT$ z6QP@p+8xyZ@2U58=V82CjSlKN1H5xfcF3RK9|C0`_+}g@j6GtPyInN@<2Wzr4C1H! z>9AwRIQA0jSP|=Xf29n=;XNDCK`lO(y0{ene)^Bt)nB-AJK!k|6=Y@iV&!*o%-{c4 zb1k7o$8&Gh{r!353R0c|@A%;9e@<_m^}nxxg|`;pWp^0w?sX|%aQ5~dA8XI>5#W9Hr<|jJPYBfGuXXn@3wHKaKIi^0l#`eA z0r3+ZE7tVx!Nyzf<@tGXF47E#H>yLQN_=y>SNrb$7w`Yw{33Jwa|8|d|4CnZB&T(R z>G8(B$)`<6mD@_)-~0cv6nMvpG;pAJ_n%xVhlO_}%K`G2{Gm8m5*#5NZXihNMf^NhdK>6{$Hu!~a6uw>o*cvBjp`Vn5?^KNp5txH=&!x2 zpw7;GGwRv<(|My!oe9ieoTSwk)1>3KjM?!2M^vEySEk58$vxbIXbxIe zDyfE*gN~1`SPUPrlaEyKgDXgXx7X*T!4k`Q;@$bvV2K@adE#LFG#WbY6zHk|mRPxJ z-ebXFiB%meQ~qce3OO$f9oyN2y~KJR|2*YXAWqtX_`MXD&G9Y4K7-`nvhthr93_U! zK^};XJyhar**kM5Po4f8wDabz&d+Mp8zgUz={TY}eS|GwVh=gld2yv5z-dGo+qA{4=%@JqQV8v0`U zJs-xq_sz^Ee}Fe@rXi%M5DK-`kKR!z!N$AlQ~0V-Q8Cgh#80eG>s?X~Hr|ff3%PVp z&1E>eA0s-}QHk$$Nmu_SZ~E~*dO7M`)h8M%$X-a^uLsZk6{PMG+H_>U>NWgbLC&MV z`$R~BFN!ytN0~Af-q&I(@4$GAzxhG_yyg0a)W@;_Z>4D8*tuZ5^)b6oJn(rmv?O`) zD2%t-dg(E5fOqYhY4#kEP{{4@h}fb6Y`hiEZ5hbV79nj%{L&BmvfCzO<9+c#iI=I` z9EQVN0nu@RN_>kC9C@kzFQ&IDzFdRHzX(~B; z&!xcoxY=@h6z?^ALY1)a#*ajL!gy~wa*zCRqIuR0NCDtI9H15bq#x}68x6f*0dG#E zjTyt^t@^z=8{7fjL!OFB-&8`Oy_)-nc^_fpO~_w6Y;#SRCkz#S?zcB zo?9lQVMY0TV{^d0g0qTL@HS%;m2`VK72^tjJ>ODw9Rn@W8C&&ws!meaq)Zm;&S zWbL4S#ZF_q!)IBEV5YAiy=$y#($QC4!}0S7`GGWb3cS-v-~M?)iktLN6ASP8Sr&sZ z-p3|xkoW)9YnDDd4)8Yf@R?lpgb1Z&441tGc;A#{*Mjj*IMjSS65xIK$bj{d*&)#O zaSlJ0B5b^u>>u#&5)>z)ej%D?f;dlLjAb9 z$R=xv$>mgRyybTs8ZNS%MMC||lLmQ3gR$}6TBJ}LUCwx4kjf!CoT$Wi?^4sfCq?w* z?OFDyV7mwP3evo$zUyG}N2bTSbflUl9i8l>)d2})yj3aiPF?CziQ>IM=YR$l-c#|D zyzu6PL;X7P^wuMzaEmp-djvo6%=8%%>hd!1cvB1R|4)hhBQj)X_@iP?r(OLNiyz8_(xi%Lv-sdfTh>jX6@%4VOwE6yp ze!L45R;aSp(r`G@#^ytf{d=az8z)Yq4v9uJr2ki;z&nL&m=nc&X5$KVEW9N(Wy4^+ z&u^Vg{{H{2pKXd1z}sNet~#q%;BaEvl+CGzXh=Tt$}Bj0^PNgOb^zc#cQo49%QX~o zN$$GxYYKb3r6hZMGH>}Tk~8ABCmsJ;s26*@b%lSj^4oRB%ii-49ha!Y=QMfoX!;QS zc-J@d*^N)rQk?i+)frD_`u;z{E|?}AF@fX4dIf*`e`e|bbtrOBc8&8mnuCU_*$uFA zkcdtGMfeR8u5a7OPwWsYwri_`92BnBlfDcrvAY)ca>#=H|Ac4`4fukz%XO)mTp$Nk zjV)c(a4Qtj>gSa_W{Z8r&bEzTqD2nBFVjW*oL>BttTn^FVrR>)ytg`%BMf)Nt|Owu zgi3tGy{Ws}dg$-}7nOC!&oQLo3)1*3|1VdAn16{C%A`rh#v8MCY(7n{Ahjv*K70Lr z8j82aj<5Pycw3wi;)OquW=-NCzyFsCd0w;vc*g}fo4VB#q4$qf#J|@^Lyzv{O~7A} z8u7nhp#|{vIZ9kwni2}_GupKCzAiT24;;LOs>*+q1tEUlA32BX$YSFyaE9y0RwXWm z8?oO*bWCUcIljmbi#;A*rvDQ=^>P=#rFW>~-Jn*Qbjsli)8nmgcAq94TRz=;i#tjl zZ)s8Bea6)z7{zPvw>55(*myryPMw1+^RF-o&3b~c;hVVY0_aV z@6l-b`|}n}3cRxv?q{KRo6K?3#lm|@V&^!Fw{39^`TRd&BfrRffVatUe6!ypA~g10 zI^4NB8q!f1+zK~HGy8@P!VOY{&uS~x*ih(fa!^OzTx`5e+`Ds&ytzo{5Wk->8gF|A zu<_mzG^y_Vd=|suZG`A>q7t9QJH<9}Df+WFx9NgKr!1)BeWUTX_r6n|Oy3|)6vxn{ zV>qxzDdP8dYd!_ur+<3BM)59bGtt4qdwb0g8Sj!2`tY_duC4IR41xSOp;#MT?Ee3$ z=l6@}QUyrX69blQT5* z|M6C1-w5BB9&g-obJ}#MMD?Ba5`*}_a?i$c5yz*%y_91c;Sl)o?>~(88vy(N1{68y z(x`1ToP#96`+u37n{ik<=%(r?$H!oaU6s!71fTymY5(=K4BSCd+wLE5vw;Y4%*O91 zYL14~w%3=#FG!W%5q^IJT(P^%Le2E7R0!mrqSUtOD)xw7oYRo?{!(r;FT^jG?Uvc{ zW7s=LHA`#X8=jXWG1{+J3enL-CB8NXBM*~U`YTA?)$0Uxwo>0g+G`&nku>SU^cCcj zkRY0L-1j;$cINjJy9+4rzL+HZ&kNFPG#X5>@OF?$4Tkal{wtM?_XbDKAMguO%Y)53 zwml_60gH!K^8ns+MO;TU0p6=UzR0HlyeC)rvT%+ELmy0dHF{#O@s^Ga=xc0dGwVhC z0y}rE81%r#+i8?dRm@t9;qaD6bhuNAFU0qvVd5kD@s4KAz^|yFVFzg{^@-EmK&HnV z_bQn-9r#}_4St^>)u+Jw!Zv|J`ICZiePeYorx zX-g9ks(L)xnFH`{b9pWg<6XFIL+g2fccP*oajRbl6t#Zw`xPA6737Aca~liOXG{+x zesw3GJ@gpF##>%`S>Mbneul%_1<|2RCBC3YDOdg=`th#qPq{DFO+y7)AOCQ>HY?NL zAcfOQph<`3*=KqF=g8ArJqo6T*&Km&l;v_lVNN~MHR7F#)&L6I~(68D1Loj&6 z^f2OgRfQ*8;XO9qUT?3P-Q-|pIJ_4kIzp(#r>1IT?0k!Uytz-EygSTB9q)s)UDvU$ zc42zF)3(s2gN5(Zh5eyqymcw?J~w?Y5XC!kJ!FW5cg%$4N_g*0!?tHDoV_>IjIM%j zZ{eLOxs?I%p3frbKK?8kk{McU13zyeb8O+}Zh*IQ!leVp!RIZlIn9;b53#eiKkurb z(-v)}ZHV8@iXU$2fB3wmNI%ZA=UhL-z5jO<(J@9PzTm0J1Ve55`+xl#Jl4efG<@Eo z87@^>+|T^||D7P(bSNHf(*niG-~OM`y3zlSctHQZkRk^a6x<@8L4x~#uYs}%D$NF;ljbR22D*Y)%wd5JZlz&k(SO&vPk@?JKZ z4GZt2<=2AY9i$tAPstmk5O+lIZh*IJh{3K~!9?g%i{5k?xMH_a#cW6&;Jx4zr(7k# zJLz$N#Jk-gkZPIsuWUB#C6=hW{m``#4zu})UzyKL{jq-R3Nrgn&@S~);tYqkJ)+|R zmH58VG9j^sZ*~Ym+o*LYA8I!^ms2_vxO!d+0{BfOHPpSHm1Nk&%5*! ziucu2E&>+bRYIF<;R^E5z8UiAt(%E!_eTP}A2pX;FG(Uo$%Rje>EMF2%`vKOaD!yy zq%u+f@V1=RvJqMz0=1OsEm`yld%V>d#}>|O&TsY#@%tig!k_#U8}E&!Q?tDjXEPk$ z?-3nNRO0JCpP@l)q95;oXT0^%gEUl-OO*%NvX3%7-ndFd+H_Q`N}d0Eyk$gzcdp<7 z9>qIauY?r~?{|CEcwoF0n}=QC2FY74rYRNRefUi>$IE;oBxAJ1$@xVz6t5yQ1dq24 zSGayn26ziTptE;ylhm#N3GVBy`_8)O8Jw>Ga%+ydi0>g?=!8{jQ3soQS~4kzZW>Z!X0##?#N zuEW{@@8K7>M8W{xVgd^YebS+j%9H#9Z;G+;{?Wsy(4@t0rh)h+Sy~j!W?|z!lBJ2u z3SzwM{R`3YgGzjCCFKfAF7)^R)<(`eIuW&)r`phNYoiT8;PH-qOrO0UvrY5UqGKTQ z$!+HY$$$HQ6aYs4U(o+ArpQ4z?!4QM<{+HdDqgG{bY>_=4qjp(MlU7LAdg+>Q@I9m zkhs~MYxaSl|1WR(kPaS5KYTMc8SejA-`lGD3gn<=PIB8<0=QcgiT!28$Dhyz0hgQ3mmPC-4w*mx`2 zxXfVzpQ|__eit6qzJK{;Bj!?~xoh3ozC0F&!&@EEp+_Y?XUzu<+DGWed!6UU%Vx&Z zPmo5CBoENiyZF6`IxRZ*PCPcW`@KPGMuB(HTGfvz-uY`kb7A3qbIcKWBzsEEP@!P1UY713=M}YUc1)}CwOM;