From 1d721dc8ce340bb552db664cad01959f37e3049e Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Tue, 26 Mar 2024 17:01:00 +0900 Subject: [PATCH 01/56] fix(out_of_lane): calculate path lanelets that we can miss during a lane change (#6600) Signed-off-by: Maxime CLEMENT --- .../src/lanelets_selection.cpp | 41 ++++++++++++++++++- .../src/lanelets_selection.hpp | 7 ++++ 2 files changed, 46 insertions(+), 2 deletions(-) diff --git a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp index 3c90a8cbf0dce..738ea22106b29 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp @@ -24,12 +24,47 @@ namespace behavior_velocity_planner::out_of_lane { + +lanelet::ConstLanelets consecutive_lanelets( + const route_handler::RouteHandler & route_handler, const lanelet::ConstLanelet & lanelet) +{ + lanelet::ConstLanelets consecutives = route_handler.getRoutingGraphPtr()->following(lanelet); + const auto previous = route_handler.getRoutingGraphPtr()->previous(lanelet); + consecutives.insert(consecutives.end(), previous.begin(), previous.end()); + return consecutives; +} + +lanelet::ConstLanelets get_missing_lane_change_lanelets( + lanelet::ConstLanelets & path_lanelets, const route_handler::RouteHandler & route_handler) +{ + lanelet::ConstLanelets missing_lane_change_lanelets; + const auto & routing_graph = *route_handler.getRoutingGraphPtr(); + lanelet::ConstLanelets adjacents; + lanelet::ConstLanelets consecutives; + for (const auto & ll : path_lanelets) { + const auto consecutives_of_ll = consecutive_lanelets(route_handler, ll); + std::copy_if( + consecutives_of_ll.begin(), consecutives_of_ll.end(), std::back_inserter(consecutives), + [&](const auto & l) { return !contains_lanelet(consecutives, l.id()); }); + const auto adjacents_of_ll = routing_graph.besides(ll); + std::copy_if( + adjacents_of_ll.begin(), adjacents_of_ll.end(), std::back_inserter(adjacents), + [&](const auto & l) { return !contains_lanelet(adjacents, l.id()); }); + } + std::copy_if( + adjacents.begin(), adjacents.end(), std::back_inserter(missing_lane_change_lanelets), + [&](const auto & l) { + return !contains_lanelet(missing_lane_change_lanelets, l.id()) && + !contains_lanelet(path_lanelets, l.id()) && contains_lanelet(consecutives, l.id()); + }); + return missing_lane_change_lanelets; +} + lanelet::ConstLanelets calculate_path_lanelets( const EgoData & ego_data, const route_handler::RouteHandler & route_handler) { const auto lanelet_map_ptr = route_handler.getLaneletMapPtr(); - lanelet::ConstLanelets path_lanelets = - planning_utils::getLaneletsOnPath(ego_data.path, lanelet_map_ptr, ego_data.pose); + lanelet::ConstLanelets path_lanelets; lanelet::BasicLineString2d path_ls; for (const auto & p : ego_data.path.points) path_ls.emplace_back(p.point.pose.position.x, p.point.pose.position.y); @@ -38,6 +73,8 @@ lanelet::ConstLanelets calculate_path_lanelets( if (!contains_lanelet(path_lanelets, dist_lanelet.second.id())) path_lanelets.push_back(dist_lanelet.second); } + const auto missing_lanelets = get_missing_lane_change_lanelets(path_lanelets, route_handler); + path_lanelets.insert(path_lanelets.end(), missing_lanelets.begin(), missing_lanelets.end()); return path_lanelets; } diff --git a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp index 9c3aee46c8be5..87757a0cb2230 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp @@ -41,6 +41,13 @@ inline bool contains_lanelet(const lanelet::ConstLanelets & lanelets, const lane /// @return lanelets crossed by the ego vehicle lanelet::ConstLanelets calculate_path_lanelets( const EgoData & ego_data, const route_handler::RouteHandler & route_handler); +/// @brief calculate lanelets that may not be crossed by the path but may be overlapped during a +/// lane change +/// @param [in] path_lanelets lanelets driven by the ego vehicle +/// @param [in] route_handler route handler +/// @return lanelets that may be overlapped by a lane change (and are not already in path_lanelets) +lanelet::ConstLanelets get_missing_lane_change_lanelets( + lanelet::ConstLanelets & path_lanelets, const route_handler::RouteHandler & route_handler); /// @brief calculate lanelets that should be ignored /// @param [in] ego_data data about the ego vehicle /// @param [in] path_lanelets lanelets driven by the ego vehicle From 297b48606a6589f9528ace1ea90ec193732e578d Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Tue, 26 Mar 2024 18:45:39 +0900 Subject: [PATCH 02/56] feat(goal_planner): add general turnsignalinfo method for goal planner (#6629) add general turnsignalinfo method for goal planner Signed-off-by: Daniel Sanchez --- .../goal_planner_module.hpp | 9 +- .../src/goal_planner_module.cpp | 111 +++++++++++++----- 2 files changed, 89 insertions(+), 31 deletions(-) diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp index 1cb0a3b98c8f2..21ea06531c2f4 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -37,6 +37,8 @@ #include #include +#include + #include #include #include @@ -525,14 +527,15 @@ class GoalPlannerModule : public SceneModuleInterface void setDrivableAreaInfo(BehaviorModuleOutput & output) const; // output setter - void setOutput(BehaviorModuleOutput & output) const; + void setOutput(BehaviorModuleOutput & output); void updatePreviousData(); void setModifiedGoal(BehaviorModuleOutput & output) const; - void setTurnSignalInfo(BehaviorModuleOutput & output) const; + void setTurnSignalInfo(BehaviorModuleOutput & output); // new turn signal - TurnSignalInfo calcTurnSignalInfo() const; + TurnSignalInfo calcTurnSignalInfo(); + std::optional ignore_signal_{std::nullopt}; std::optional last_previous_module_output_{}; bool hasPreviousModulePathShapeChanged() const; 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 c2902fb0bace6..2ba217ccccaff 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 @@ -893,7 +893,7 @@ std::vector GoalPlannerModule::generateDrivableLanes() const return utils::generateDrivableLanesWithShoulderLanes(current_lanes, pull_over_lanes); } -void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) const +void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) { output.reference_path = getPreviousModuleOutput().reference_path; @@ -966,7 +966,7 @@ void GoalPlannerModule::setModifiedGoal(BehaviorModuleOutput & output) const } } -void GoalPlannerModule::setTurnSignalInfo(BehaviorModuleOutput & output) const +void GoalPlannerModule::setTurnSignalInfo(BehaviorModuleOutput & output) { const auto original_signal = getPreviousModuleOutput().turn_signal_info; const auto new_signal = calcTurnSignalInfo(); @@ -1573,43 +1573,98 @@ bool GoalPlannerModule::isOnModifiedGoal() const parameters_->th_arrived_distance; } -TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() const +TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() { - TurnSignalInfo turn_signal{}; // output + const auto path = thread_safe_data_.get_pull_over_path()->getFullPath(); + if (path.points.empty()) return getPreviousModuleOutput().turn_signal_info; const auto & current_pose = planner_data_->self_odometry->pose.pose; const auto & start_pose = thread_safe_data_.get_pull_over_path()->start_pose; const auto & end_pose = thread_safe_data_.get_pull_over_path()->end_pose; - const auto full_path = thread_safe_data_.get_pull_over_path()->getFullPath(); - // 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; + const auto shift_start_idx = motion_utils::findNearestIndex(path.points, start_pose.position); + const auto shift_end_idx = motion_utils::findNearestIndex(path.points, end_pose.position); + + const auto is_ignore_signal = [this](const lanelet::Id & id) { + if (!ignore_signal_.has_value()) { + return false; } + return ignore_signal_.value() == id; + }; + + const auto update_ignore_signal = [this](const lanelet::Id & id, const bool is_ignore) { + return is_ignore ? std::make_optional(id) : std::nullopt; + }; + + const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes( + planner_data_, parameters_->backward_goal_search_length, + parameters_->forward_goal_search_length, + /*forward_only_in_route*/ false); + + if (current_lanes.empty()) { + return {}; } - // 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; + lanelet::Lanelet closest_lanelet; + lanelet::utils::query::getClosestLanelet(current_lanes, current_pose, &closest_lanelet); + + if (is_ignore_signal(closest_lanelet.id())) { + return getPreviousModuleOutput().turn_signal_info; } - return turn_signal; + const double current_shift_length = + lanelet::utils::getArcCoordinates(current_lanes, current_pose).distance; + + constexpr bool egos_lane_is_shifted = true; + constexpr bool is_driving_forward = true; + + constexpr bool is_pull_out = false; + const bool override_ego_stopped_check = std::invoke([&]() { + if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::SHIFT) { + return false; + } + constexpr double distance_threshold = 1.0; + const auto stop_point = + thread_safe_data_.get_pull_over_path()->partial_paths.front().points.back(); + const double distance_from_ego_to_stop_point = std::abs(motion_utils::calcSignedArcLength( + path.points, stop_point.point.pose.position, current_pose.position)); + return distance_from_ego_to_stop_point < distance_threshold; + }); + + const auto [new_signal, is_ignore] = planner_data_->getBehaviorTurnSignalInfo( + path, shift_start_idx, shift_end_idx, current_lanes, current_shift_length, is_driving_forward, + egos_lane_is_shifted, override_ego_stopped_check, is_pull_out); + 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 106ee3ee5de67e8b8208f422d58b17ce9561307a Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Tue, 26 Mar 2024 19:18:51 +0900 Subject: [PATCH 03/56] feat(goal_planner): add param reconfig to goal planner (#6646) * Add param reconfig to goal planner Signed-off-by: Daniel Sanchez * Using the Warn params is bugged, wont fix Signed-off-by: Daniel Sanchez * add comments Signed-off-by: Daniel Sanchez * add missing params Signed-off-by: Daniel Sanchez * add missing param Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../src/manager.cpp | 405 +++++++++++++++++- 1 file changed, 404 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_goal_planner_module/src/manager.cpp b/planning/behavior_path_goal_planner_module/src/manager.cpp index b27c604536e8c..bca5bb1230f38 100644 --- a/planning/behavior_path_goal_planner_module/src/manager.cpp +++ b/planning/behavior_path_goal_planner_module/src/manager.cpp @@ -423,11 +423,414 @@ void GoalPlannerModuleManager::init(rclcpp::Node * node) void GoalPlannerModuleManager::updateModuleParams( [[maybe_unused]] const std::vector & parameters) { + // TODO(someone): This function does not check OR update + // object_recognition_collision_check_soft_margins, + // object_recognition_collision_check_hard_margins, maximum_deceleration, shift_sampling_num or + // parking_policy, there seems to be a problem when we use a temp value to check these values. + using tier4_autoware_utils::updateParam; auto & p = parameters_; - [[maybe_unused]] const std::string ns = name_ + "."; + const std::string base_ns = "goal_planner."; + // general params + + { + updateParam(parameters, base_ns + "th_stopped_velocity", p->th_stopped_velocity); + updateParam(parameters, base_ns + "th_arrived_distance", p->th_arrived_distance); + updateParam(parameters, base_ns + "th_stopped_time", p->th_stopped_time); + + updateParam( + parameters, base_ns + "center_line_path_interval", p->center_line_path_interval); + } + // goal search + + { + const std::string ns = base_ns + "goal_search."; + updateParam(parameters, ns + "goal_priority", p->goal_priority); + updateParam( + parameters, ns + "minimum_weighted_distance.lateral_weight", + p->minimum_weighted_distance_lateral_weight); + updateParam( + parameters, ns + "prioritize_goals_before_objects", p->prioritize_goals_before_objects); + updateParam( + parameters, ns + "forward_goal_search_length", p->forward_goal_search_length); + updateParam( + parameters, ns + "backward_goal_search_length", p->backward_goal_search_length); + updateParam(parameters, ns + "goal_search_interval", p->goal_search_interval); + updateParam(parameters, ns + "longitudinal_margin", p->longitudinal_margin); + updateParam(parameters, ns + "max_lateral_offset", p->max_lateral_offset); + updateParam(parameters, ns + "lateral_offset_interval", p->lateral_offset_interval); + updateParam( + parameters, ns + "ignore_distance_from_lane_start", p->ignore_distance_from_lane_start); + updateParam(parameters, ns + "margin_from_boundary", p->margin_from_boundary); + } + + // occupancy grid map + { + const std::string ns = base_ns + "occupancy_grid."; + updateParam( + parameters, ns + "use_occupancy_grid_for_goal_search", p->use_occupancy_grid_for_goal_search); + updateParam( + parameters, ns + "use_occupancy_grid_for_path_collision_check", + p->use_occupancy_grid_for_path_collision_check); + updateParam( + parameters, ns + "use_occupancy_grid_for_goal_longitudinal_margin", + p->use_occupancy_grid_for_goal_longitudinal_margin); + updateParam( + parameters, ns + "occupancy_grid_collision_check_margin", + p->occupancy_grid_collision_check_margin); + updateParam(parameters, ns + "theta_size", p->theta_size); + updateParam(parameters, ns + "obstacle_threshold", p->obstacle_threshold); + } + + // object recognition + { + const std::string ns = base_ns + "object_recognition."; + + updateParam(parameters, ns + "use_object_recognition", p->use_object_recognition); + updateParam( + parameters, ns + "object_recognition_collision_check_max_extra_stopping_margin", + p->object_recognition_collision_check_max_extra_stopping_margin); + updateParam(parameters, ns + "th_moving_object_velocity", p->th_moving_object_velocity); + updateParam(parameters, ns + "detection_bound_offset", p->detection_bound_offset); + updateParam(parameters, ns + "outer_road_detection_offset", p->outer_road_detection_offset); + updateParam(parameters, ns + "inner_road_detection_offset", p->inner_road_detection_offset); + } + + // pull over general params + { + const std::string ns = base_ns + "pull_over."; + + updateParam( + parameters, ns + "minimum_request_length", p->pull_over_minimum_request_length); + updateParam(parameters, ns + "pull_over_velocity", p->pull_over_velocity); + updateParam( + parameters, ns + "pull_over_minimum_velocity", p->pull_over_minimum_velocity); + updateParam(parameters, ns + "decide_path_distance", p->decide_path_distance); + updateParam(parameters, ns + "maximum_jerk", p->maximum_jerk); + updateParam(parameters, ns + "path_priority", p->path_priority); + updateParam>( + parameters, ns + "efficient_path_order", p->efficient_path_order); + } + + // shift parking + { + const std::string ns = base_ns + "pull_over.shift_parking."; + updateParam(parameters, ns + "enable_shift_parking", p->enable_shift_parking); + updateParam(parameters, ns + "maximum_lateral_jerk", p->maximum_lateral_jerk); + updateParam(parameters, ns + "minimum_lateral_jerk", p->minimum_lateral_jerk); + updateParam(parameters, ns + "deceleration_interval", p->deceleration_interval); + updateParam( + parameters, ns + "after_shift_straight_distance", p->after_shift_straight_distance); + } + + // parallel parking common + { + const std::string ns = base_ns + "pull_over.parallel_parking."; + p->parallel_parking_parameters.center_line_path_interval = + p->center_line_path_interval; // for geometric parallel parking + } + + // forward parallel parking forward + { + const std::string ns = base_ns + "pull_over.parallel_parking.forward."; + updateParam(parameters, ns + "enable_arc_forward_parking", p->enable_arc_forward_parking); + updateParam( + parameters, ns + "after_forward_parking_straight_distance", + p->parallel_parking_parameters.after_forward_parking_straight_distance); + updateParam( + parameters, ns + "forward_parking_velocity", + p->parallel_parking_parameters.forward_parking_velocity); + updateParam( + parameters, ns + "forward_parking_lane_departure_margin", + p->parallel_parking_parameters.forward_parking_lane_departure_margin); + updateParam( + parameters, ns + "forward_parking_path_interval", + p->parallel_parking_parameters.forward_parking_path_interval); + updateParam( + parameters, ns + "forward_parking_max_steer_angle", + p->parallel_parking_parameters.forward_parking_max_steer_angle); + } + + // forward parallel parking backward + { + const std::string ns = base_ns + "pull_over.parallel_parking.backward."; + updateParam( + parameters, ns + "enable_arc_backward_parking", p->enable_arc_backward_parking); + updateParam( + parameters, ns + "after_backward_parking_straight_distance", + p->parallel_parking_parameters.after_backward_parking_straight_distance); + updateParam( + parameters, ns + "backward_parking_velocity", + p->parallel_parking_parameters.backward_parking_velocity); + updateParam( + parameters, ns + "backward_parking_lane_departure_margin", + p->parallel_parking_parameters.backward_parking_lane_departure_margin); + updateParam( + parameters, ns + "backward_parking_path_interval", + p->parallel_parking_parameters.backward_parking_path_interval); + updateParam( + parameters, ns + "backward_parking_max_steer_angle", + p->parallel_parking_parameters.backward_parking_max_steer_angle); + } + + // freespace parking general params + { + const std::string ns = base_ns + "pull_over.freespace_parking."; + updateParam(parameters, ns + "enable_freespace_parking", p->enable_freespace_parking); + updateParam( + parameters, ns + "freespace_parking_algorithm", p->freespace_parking_algorithm); + updateParam(parameters, ns + "velocity", p->freespace_parking_velocity); + + updateParam(parameters, ns + "vehicle_shape_margin", p->vehicle_shape_margin); + updateParam( + parameters, ns + "time_limit", p->freespace_parking_common_parameters.time_limit); + updateParam( + parameters, ns + "minimum_turning_radius", + p->freespace_parking_common_parameters.minimum_turning_radius); + updateParam( + parameters, ns + "maximum_turning_radius", + p->freespace_parking_common_parameters.maximum_turning_radius); + updateParam( + parameters, ns + "turning_radius_size", + p->freespace_parking_common_parameters.turning_radius_size); + p->freespace_parking_common_parameters.maximum_turning_radius = std::max( + p->freespace_parking_common_parameters.maximum_turning_radius, + p->freespace_parking_common_parameters.minimum_turning_radius); + p->freespace_parking_common_parameters.turning_radius_size = + std::max(p->freespace_parking_common_parameters.turning_radius_size, 1); + } + + // freespace parking search config + { + const std::string ns = base_ns + "pull_over.freespace_parking.search_configs."; + updateParam( + parameters, ns + "theta_size", p->freespace_parking_common_parameters.theta_size); + updateParam( + parameters, ns + "angle_goal_range", p->freespace_parking_common_parameters.angle_goal_range); + updateParam( + parameters, ns + "curve_weight", p->freespace_parking_common_parameters.curve_weight); + updateParam( + parameters, ns + "reverse_weight", p->freespace_parking_common_parameters.reverse_weight); + updateParam( + parameters, ns + "lateral_goal_range", + p->freespace_parking_common_parameters.lateral_goal_range); + updateParam( + parameters, ns + "longitudinal_goal_range", + p->freespace_parking_common_parameters.longitudinal_goal_range); + } + + // freespace parking costmap configs + { + const std::string ns = base_ns + "pull_over.freespace_parking.costmap_configs."; + updateParam( + parameters, ns + "obstacle_threshold", + p->freespace_parking_common_parameters.obstacle_threshold); + } + + // freespace parking astar + { + const std::string ns = base_ns + "pull_over.freespace_parking.astar."; + updateParam( + parameters, ns + "only_behind_solutions", p->astar_parameters.only_behind_solutions); + updateParam(parameters, ns + "use_back", p->astar_parameters.use_back); + updateParam( + parameters, ns + "distance_heuristic_weight", p->astar_parameters.distance_heuristic_weight); + } + + // freespace parking rrtstar + + { + const std::string ns = base_ns + "pull_over.freespace_parking.rrtstar."; + updateParam(parameters, ns + "enable_update", p->rrt_star_parameters.enable_update); + updateParam( + parameters, ns + "use_informed_sampling", p->rrt_star_parameters.use_informed_sampling); + updateParam( + parameters, ns + "max_planning_time", p->rrt_star_parameters.max_planning_time); + updateParam(parameters, ns + "neighbor_radius", p->rrt_star_parameters.neighbor_radius); + updateParam(parameters, ns + "margin", p->rrt_star_parameters.margin); + } + + // stop condition + { + updateParam( + parameters, base_ns + "stop_condition.maximum_deceleration_for_stop", + p->maximum_deceleration_for_stop); + updateParam( + parameters, base_ns + "stop_condition.maximum_jerk_for_stop", p->maximum_jerk_for_stop); + } + + const std::string path_safety_check_ns = "goal_planner.path_safety_check."; + const std::string ego_path_ns = path_safety_check_ns + "ego_predicted_path."; + + // EgoPredictedPath + { + updateParam( + parameters, ego_path_ns + "min_velocity", p->ego_predicted_path_params.min_velocity); + updateParam( + parameters, ego_path_ns + "min_acceleration", p->ego_predicted_path_params.acceleration); + updateParam( + parameters, ego_path_ns + "time_horizon_for_front_object", + p->ego_predicted_path_params.time_horizon_for_front_object); + updateParam( + parameters, ego_path_ns + "time_horizon_for_rear_object", + p->ego_predicted_path_params.time_horizon_for_rear_object); + updateParam( + parameters, ego_path_ns + "time_resolution", p->ego_predicted_path_params.time_resolution); + updateParam( + parameters, ego_path_ns + "delay_until_departure", + p->ego_predicted_path_params.delay_until_departure); + } + + // ObjectFilteringParams + const std::string obj_filter_ns = path_safety_check_ns + "target_filtering."; + { + updateParam( + parameters, obj_filter_ns + "safety_check_time_horizon", + p->objects_filtering_params.safety_check_time_horizon); + updateParam( + parameters, obj_filter_ns + "safety_check_time_resolution", + p->objects_filtering_params.safety_check_time_resolution); + updateParam( + parameters, obj_filter_ns + "object_check_forward_distance", + p->objects_filtering_params.object_check_forward_distance); + updateParam( + parameters, obj_filter_ns + "object_check_backward_distance", + p->objects_filtering_params.object_check_backward_distance); + updateParam( + parameters, obj_filter_ns + "ignore_object_velocity_threshold", + p->objects_filtering_params.ignore_object_velocity_threshold); + updateParam( + parameters, obj_filter_ns + "include_opposite_lane", + p->objects_filtering_params.include_opposite_lane); + updateParam( + parameters, obj_filter_ns + "invert_opposite_lane", + p->objects_filtering_params.invert_opposite_lane); + updateParam( + parameters, obj_filter_ns + "check_all_predicted_path", + p->objects_filtering_params.check_all_predicted_path); + updateParam( + parameters, obj_filter_ns + "use_all_predicted_path", + p->objects_filtering_params.use_all_predicted_path); + updateParam( + parameters, obj_filter_ns + "use_predicted_path_outside_lanelet", + p->objects_filtering_params.use_predicted_path_outside_lanelet); + } + + // ObjectTypesToCheck + const std::string obj_types_ns = obj_filter_ns + "object_types_to_check."; + { + updateParam( + parameters, obj_types_ns + "check_car", + p->objects_filtering_params.object_types_to_check.check_car); + updateParam( + parameters, obj_types_ns + "check_truck", + p->objects_filtering_params.object_types_to_check.check_truck); + updateParam( + parameters, obj_types_ns + "check_bus", + p->objects_filtering_params.object_types_to_check.check_bus); + updateParam( + parameters, obj_types_ns + "check_trailer", + p->objects_filtering_params.object_types_to_check.check_trailer); + updateParam( + parameters, obj_types_ns + "check_unknown", + p->objects_filtering_params.object_types_to_check.check_unknown); + updateParam( + parameters, obj_types_ns + "check_bicycle", + p->objects_filtering_params.object_types_to_check.check_bicycle); + updateParam( + parameters, obj_types_ns + "check_motorcycle", + p->objects_filtering_params.object_types_to_check.check_motorcycle); + updateParam( + parameters, obj_types_ns + "check_pedestrian", + p->objects_filtering_params.object_types_to_check.check_pedestrian); + } + // ObjectLaneConfiguration + const std::string obj_lane_ns = obj_filter_ns + "object_lane_configuration."; + { + updateParam( + parameters, obj_lane_ns + "check_current_lane", + p->objects_filtering_params.object_lane_configuration.check_current_lane); + updateParam( + parameters, obj_lane_ns + "check_right_side_lane", + p->objects_filtering_params.object_lane_configuration.check_right_lane); + updateParam( + parameters, obj_lane_ns + "check_left_side_lane", + p->objects_filtering_params.object_lane_configuration.check_left_lane); + updateParam( + parameters, obj_lane_ns + "check_shoulder_lane", + p->objects_filtering_params.object_lane_configuration.check_shoulder_lane); + updateParam( + parameters, obj_lane_ns + "check_other_lane", + p->objects_filtering_params.object_lane_configuration.check_other_lane); + } + + // SafetyCheckParams + const std::string safety_check_ns = path_safety_check_ns + "safety_check_params."; + { + updateParam( + parameters, safety_check_ns + "enable_safety_check", + p->safety_check_params.enable_safety_check); + updateParam( + parameters, safety_check_ns + "keep_unsafe_time", p->safety_check_params.keep_unsafe_time); + updateParam(parameters, safety_check_ns + "method", p->safety_check_params.method); + updateParam( + parameters, safety_check_ns + "hysteresis_factor_expand_rate", + p->safety_check_params.hysteresis_factor_expand_rate); + updateParam( + parameters, safety_check_ns + "backward_path_length", + p->safety_check_params.backward_path_length); + updateParam( + parameters, safety_check_ns + "forward_path_length", + p->safety_check_params.forward_path_length); + updateParam( + parameters, safety_check_ns + "publish_debug_marker", + p->safety_check_params.publish_debug_marker); + } + + // RSSparams + const std::string rss_ns = safety_check_ns + "rss_params."; + { + updateParam( + parameters, rss_ns + "rear_vehicle_reaction_time", + p->safety_check_params.rss_params.rear_vehicle_reaction_time); + updateParam( + parameters, rss_ns + "rear_vehicle_safety_time_margin", + p->safety_check_params.rss_params.rear_vehicle_safety_time_margin); + updateParam( + parameters, rss_ns + "lateral_distance_max_threshold", + p->safety_check_params.rss_params.lateral_distance_max_threshold); + updateParam( + parameters, rss_ns + "longitudinal_distance_min_threshold", + p->safety_check_params.rss_params.longitudinal_distance_min_threshold); + updateParam( + parameters, rss_ns + "longitudinal_velocity_delta_time", + p->safety_check_params.rss_params.longitudinal_velocity_delta_time); + } + + // IntegralPredictedPolygonParams + const std::string integral_ns = safety_check_ns + "integral_predicted_polygon_params."; + { + updateParam( + parameters, integral_ns + "forward_margin", + p->safety_check_params.integral_predicted_polygon_params.forward_margin); + updateParam( + parameters, integral_ns + "backward_margin", + p->safety_check_params.integral_predicted_polygon_params.backward_margin); + updateParam( + parameters, integral_ns + "lat_margin", + p->safety_check_params.integral_predicted_polygon_params.lat_margin); + updateParam( + parameters, integral_ns + "time_horizon", + p->safety_check_params.integral_predicted_polygon_params.time_horizon); + } + + // debug + { + const std::string ns = base_ns + "debug."; + updateParam(parameters, ns + "print_debug_info", p->print_debug_info); + } std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) { if (!observer.expired()) observer.lock()->updateModuleParams(p); From ce6de02b3f2a1bfb75f7e3f4feff396f5e3221f8 Mon Sep 17 00:00:00 2001 From: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> Date: Tue, 26 Mar 2024 23:36:46 +0900 Subject: [PATCH 04/56] feat(AEB): add height filter for avoiding the ghost brake by false positive point clouds (#6637) * feat(AEB): add height filter for avoiding the ghost brake by false positive point clouds Signed-off-by: Shin-kyoto * docs(AEB): add param for height filter Signed-off-by: Shin-kyoto * feat(AEB): add max height range in AEB Signed-off-by: Shin-kyoto * feat(AEB): update default params Signed-off-by: Shin-kyoto --------- Signed-off-by: Shin-kyoto --- .../autonomous_emergency_braking/README.md | 40 ++++++++++--------- .../autonomous_emergency_braking.param.yaml | 2 + .../autonomous_emergency_braking/node.hpp | 2 + .../autonomous_emergency_braking/src/node.cpp | 16 +++++++- 4 files changed, 40 insertions(+), 20 deletions(-) diff --git a/control/autonomous_emergency_braking/README.md b/control/autonomous_emergency_braking/README.md index 4eff1583d5df8..28b7636ba82ac 100644 --- a/control/autonomous_emergency_braking/README.md +++ b/control/autonomous_emergency_braking/README.md @@ -26,25 +26,27 @@ This module has following assumptions. ## Parameters -| Name | Unit | Type | Description | Default value | -| :--------------------------- | :----- | :----- | :-------------------------------------------------------------------------- | :------------ | -| publish_debug_pointcloud | [-] | bool | flag to publish the point cloud used for debugging | false | -| use_predicted_trajectory | [-] | bool | flag to use the predicted path from the control module | true | -| use_imu_path | [-] | bool | flag to use the predicted path generated by sensor data | true | -| voxel_grid_x | [m] | double | down sampling parameters of x-axis for voxel grid filter | 0.05 | -| voxel_grid_y | [m] | double | down sampling parameters of y-axis for voxel grid filter | 0.05 | -| voxel_grid_z | [m] | double | down sampling parameters of z-axis for voxel grid filter | 100000.0 | -| min_generated_path_length | [m] | double | minimum distance for a predicted path generated by sensors | 0.5 | -| expand_width | [m] | double | expansion width of the ego vehicle for the collision check | 0.1 | -| longitudinal_offset | [m] | double | longitudinal offset distance for collision check | 2.0 | -| t_response | [s] | double | response time for the ego to detect the front vehicle starting deceleration | 1.0 | -| a_ego_min | [m/ss] | double | maximum deceleration value of the ego vehicle | -3.0 | -| a_obj_min | [m/ss] | double | maximum deceleration value of objects | -3.0 | -| imu_prediction_time_horizon | [s] | double | time horizon of the predicted path generated by sensors | 1.5 | -| imu_prediction_time_interval | [s] | double | time interval of the predicted path generated by sensors | 0.1 | -| mpc_prediction_time_horizon | [s] | double | time horizon of the predicted path generated by mpc | 1.5 | -| mpc_prediction_time_interval | [s] | double | time interval of the predicted path generated by mpc | 0.1 | -| aeb_hz | [-] | double | frequency at which AEB operates per second | 10 | +| Name | Unit | Type | Description | Default value | +| :-------------------------------- | :----- | :----- | :---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| publish_debug_pointcloud | [-] | bool | flag to publish the point cloud used for debugging | false | +| use_predicted_trajectory | [-] | bool | flag to use the predicted path from the control module | true | +| use_imu_path | [-] | bool | flag to use the predicted path generated by sensor data | true | +| detection_range_min_height | [m] | double | minimum hight of detection range used for avoiding the ghost brake by false positive point clouds | 0.0 | +| detection_range_max_height_margin | [m] | double | margin for maximum hight of detection range used for avoiding the ghost brake by false positive point clouds. `detection_range_max_height = vehicle_height + detection_range_max_height_margin` | 0.0 | +| voxel_grid_x | [m] | double | down sampling parameters of x-axis for voxel grid filter | 0.05 | +| voxel_grid_y | [m] | double | down sampling parameters of y-axis for voxel grid filter | 0.05 | +| voxel_grid_z | [m] | double | down sampling parameters of z-axis for voxel grid filter | 100000.0 | +| min_generated_path_length | [m] | double | minimum distance for a predicted path generated by sensors | 0.5 | +| expand_width | [m] | double | expansion width of the ego vehicle for the collision check | 0.1 | +| longitudinal_offset | [m] | double | longitudinal offset distance for collision check | 2.0 | +| t_response | [s] | double | response time for the ego to detect the front vehicle starting deceleration | 1.0 | +| a_ego_min | [m/ss] | double | maximum deceleration value of the ego vehicle | -3.0 | +| a_obj_min | [m/ss] | double | maximum deceleration value of objects | -3.0 | +| imu_prediction_time_horizon | [s] | double | time horizon of the predicted path generated by sensors | 1.5 | +| imu_prediction_time_interval | [s] | double | time interval of the predicted path generated by sensors | 0.1 | +| mpc_prediction_time_horizon | [s] | double | time horizon of the predicted path generated by mpc | 1.5 | +| mpc_prediction_time_interval | [s] | double | time interval of the predicted path generated by mpc | 0.1 | +| aeb_hz | [-] | double | frequency at which AEB operates per second | 10 | ## Inner-workings / Algorithms diff --git a/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml b/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml index 1a870aff7a843..82d5a4f12e002 100644 --- a/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml +++ b/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml @@ -3,6 +3,8 @@ publish_debug_pointcloud: false use_predicted_trajectory: true use_imu_path: true + detection_range_min_height: 0.0 + detection_range_max_height_margin: 0.0 voxel_grid_x: 0.05 voxel_grid_y: 0.05 voxel_grid_z: 100000.0 diff --git a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp b/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp index fb1973d777138..b8aad1c80dfea 100644 --- a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp +++ b/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp @@ -175,6 +175,8 @@ class AEB : public rclcpp::Node bool publish_debug_pointcloud_; bool use_predicted_trajectory_; bool use_imu_path_; + double detection_range_min_height_; + double detection_range_max_height_margin_; double voxel_grid_x_; double voxel_grid_y_; double voxel_grid_z_; diff --git a/control/autonomous_emergency_braking/src/node.cpp b/control/autonomous_emergency_braking/src/node.cpp index 2b5553971a8d5..8c830812078b6 100644 --- a/control/autonomous_emergency_braking/src/node.cpp +++ b/control/autonomous_emergency_braking/src/node.cpp @@ -21,6 +21,7 @@ #include +#include #include #include @@ -128,6 +129,9 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) publish_debug_pointcloud_ = declare_parameter("publish_debug_pointcloud"); use_predicted_trajectory_ = declare_parameter("use_predicted_trajectory"); use_imu_path_ = declare_parameter("use_imu_path"); + detection_range_min_height_ = declare_parameter("detection_range_min_height"); + detection_range_max_height_margin_ = + declare_parameter("detection_range_max_height_margin"); voxel_grid_x_ = declare_parameter("voxel_grid_x"); voxel_grid_y_ = declare_parameter("voxel_grid_y"); voxel_grid_z_ = declare_parameter("voxel_grid_z"); @@ -221,9 +225,19 @@ void AEB::onPointCloud(const PointCloud2::ConstSharedPtr input_msg) pcl::fromROSMsg(transformed_points, *pointcloud_ptr); } + // apply z-axis filter for removing False Positive points + PointCloud::Ptr height_filtered_pointcloud_ptr(new PointCloud); + pcl::PassThrough height_filter; + height_filter.setInputCloud(pointcloud_ptr); + height_filter.setFilterFieldName("z"); + height_filter.setFilterLimits( + detection_range_min_height_, + vehicle_info_.vehicle_height_m + detection_range_max_height_margin_); + height_filter.filter(*height_filtered_pointcloud_ptr); + pcl::VoxelGrid filter; PointCloud::Ptr no_height_filtered_pointcloud_ptr(new PointCloud); - filter.setInputCloud(pointcloud_ptr); + filter.setInputCloud(height_filtered_pointcloud_ptr); filter.setLeafSize(voxel_grid_x_, voxel_grid_y_, voxel_grid_z_); filter.filter(*no_height_filtered_pointcloud_ptr); From 93dfcbb274d6d4138c1363f8d46ef9963ba457bb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 26 Mar 2024 19:05:29 +0300 Subject: [PATCH 05/56] fix(vehicle_cmd_gate): fix publisher HZ in the unit test by introducing variable window length (#6665) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Takayuki Murooka Signed-off-by: M. Fatih Cırıt --- .../test_filter_in_vehicle_cmd_gate_node.cpp | 130 +++++++++++++----- 1 file changed, 94 insertions(+), 36 deletions(-) diff --git a/control/vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp b/control/vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp index f9f3087a6b69c..949ca46d27dea 100644 --- a/control/vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp +++ b/control/vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp @@ -80,7 +80,8 @@ class PubSubNode : public rclcpp::Node [this](const AckermannControlCommand::ConstSharedPtr msg) { cmd_history_.push_back(msg); cmd_received_times_.push_back(now()); - checkFilter(); + // check the effectiveness of the filter for last x elements in the queue + checkFilter(4); }); rclcpp::QoS qos{1}; @@ -215,52 +216,99 @@ class PubSubNode : public rclcpp::Node raw_cmd_history_.push_back(std::make_shared(msg)); } - void checkFilter() + void checkFilter(size_t last_x) { - if (cmd_history_.size() != cmd_received_times_.size()) { - throw std::logic_error("cmd history and received times must have same size. Check code."); + ASSERT_TRUE(wheelbase > 0.0) << "Wheelbase must be positive. Check vehicle configuration."; + ASSERT_GT(last_x, 1u) << "last_x must be greater than 1 to calculate the jerk values"; + ASSERT_EQ(cmd_history_.size(), cmd_received_times_.size()) + << "cmd_history_ and cmd_received_times_ must have the same size. Check the implementation."; + size_t history_size = cmd_history_.size(); + if (history_size < last_x) return; // not enough data for checkFilter or last_x is too small. + + // Initialize accumulators + double avg_lon_acc = 0.0; + double avg_lon_jerk = 0.0; + double avg_lat_acc = 0.0; + double avg_lat_jerk = 0.0; + + double lon_vel = 0.0; + double prev_lon_acc = 0.0; + double prev_lat_acc = 0.0; + // TODO(Horibe): Remove this variable when the filtering logic is fixed. + double prev_tire_angle = 0.0; + + auto calculate_lateral_acceleration = + [](const double lon_vel, const double steer, const double wheelbase) { + return lon_vel * lon_vel * std::tan(steer) / wheelbase; + }; + + size_t ind_start = history_size - last_x + 1; + { + const auto & cmd_start = cmd_history_.at(ind_start - 1); + prev_lon_acc = cmd_start->longitudinal.acceleration; + // TODO(Horibe): prev_lat_acc should use the previous velocity, but use the current velocity + // since the current filtering logic uses the current velocity. + // when it's fixed, should be like this: + // prev_lat_acc = calculate_lateral_acceleration(cmd_start->longitudinal.speed, + // cmd_start->lateral.steering_tire_angle, wheelbase); + prev_tire_angle = cmd_start->lateral.steering_tire_angle; } - if (cmd_history_.size() == 1) return; + for (size_t i = ind_start; i < history_size; ++i) { + const auto & cmd = cmd_history_.at(i); + + const auto dt = (cmd_received_times_.at(i) - cmd_received_times_.at(i - 1)).seconds(); + + ASSERT_GT(dt, 0.0) << "Invalid dt. Time must be strictly positive."; + + lon_vel = cmd->longitudinal.speed; + const auto lon_acc = cmd->longitudinal.acceleration; + const auto lon_jerk = (lon_acc - prev_lon_acc) / dt; + + const auto lat_acc = + calculate_lateral_acceleration(lon_vel, cmd->lateral.steering_tire_angle, wheelbase); + // TODO(Horibe): prev_lat_acc should use the previous velocity, but use the current velocity + // since the current filtering logic uses the current velocity. + // when it's fixed, it should be moved to the bottom of this loop. + prev_lat_acc = calculate_lateral_acceleration(lon_vel, prev_tire_angle, wheelbase); + const auto lat_jerk = (lat_acc - prev_lat_acc) / dt; + + avg_lon_acc += lon_acc; + avg_lon_jerk += lon_jerk; + avg_lat_acc += lat_acc; + avg_lat_jerk += lat_jerk; + + prev_lon_acc = lon_acc; + // TODO(Horibe): when the filtering logic is fixed, this line should be removed. + prev_tire_angle = cmd->lateral.steering_tire_angle; + } - const size_t i_curr = cmd_history_.size() - 1; - const size_t i_prev = cmd_history_.size() - 2; - const auto cmd_curr = cmd_history_.at(i_curr); - const auto cmd_prev = cmd_history_.at(i_prev); + // Compute averages + // Because we look at differences, we have one less interval than points + double denominator = static_cast(last_x) - 1; + avg_lon_acc /= denominator; + avg_lon_jerk /= denominator; + avg_lat_acc /= denominator; + avg_lat_jerk /= denominator; const auto max_lon_acc_lim = *std::max_element(lon_acc_lim.begin(), lon_acc_lim.end()); const auto max_lon_jerk_lim = *std::max_element(lon_jerk_lim.begin(), lon_jerk_lim.end()); const auto max_lat_acc_lim = *std::max_element(lat_acc_lim.begin(), lat_acc_lim.end()); const auto max_lat_jerk_lim = *std::max_element(lat_jerk_lim.begin(), lat_jerk_lim.end()); - const auto dt = (cmd_received_times_.at(i_curr) - cmd_received_times_.at(i_prev)).seconds(); - const auto lon_vel = cmd_curr->longitudinal.speed; - const auto lon_acc = cmd_curr->longitudinal.acceleration; - const auto lon_jerk = (lon_acc - cmd_prev->longitudinal.acceleration) / dt; - const auto lat_acc = - lon_vel * lon_vel * std::tan(cmd_curr->lateral.steering_tire_angle) / wheelbase; - - // TODO(Horibe): prev_lat_acc should use the previous velocity, but use the current velocity - // since the current filtering logic uses the current velocity. - const auto prev_lat_acc = - lon_vel * lon_vel * std::tan(cmd_prev->lateral.steering_tire_angle) / wheelbase; - const auto lat_jerk = (lat_acc - prev_lat_acc) / dt; - - /* debug print */ - // const auto steer = cmd_curr->lateral.steering_tire_angle; - // PRINT_VALUES( - // dt, i_curr, i_prev, steer, lon_vel, prev_lon_vel, lon_acc, lon_jerk, lat_acc, prev_lat_acc, - // prev_lat_acc2, lat_jerk, max_lon_acc_lim, max_lon_jerk_lim, max_lat_acc_lim, - // max_lat_jerk_lim); - + constexpr auto threshold_scale = 1.1; // Output command must be smaller than maximum limit. // TODO(Horibe): check for each velocity range. - constexpr auto threshold_scale = 1.1; if (std::abs(lon_vel) > 0.01) { - ASSERT_LT_NEAR(std::abs(lon_acc), max_lon_acc_lim, threshold_scale); - ASSERT_LT_NEAR(std::abs(lon_jerk), max_lon_jerk_lim, threshold_scale); - ASSERT_LT_NEAR(std::abs(lat_acc), max_lat_acc_lim, threshold_scale); - ASSERT_LT_NEAR(std::abs(lat_jerk), max_lat_jerk_lim, threshold_scale); + // Assert over averaged values against limits + ASSERT_LT_NEAR(std::abs(avg_lon_acc), max_lon_acc_lim, threshold_scale) + << "last_x was = " << last_x; + ASSERT_LT_NEAR(std::abs(avg_lon_jerk), max_lon_jerk_lim, threshold_scale) + << "last_x was = " << last_x; + ASSERT_LT_NEAR(std::abs(avg_lat_acc), max_lat_acc_lim, threshold_scale) + << "last_x was = " << last_x; + ASSERT_LT_NEAR(std::abs(avg_lat_jerk), max_lat_jerk_lim, threshold_scale) + << "last_x was = " << last_x; } } }; @@ -388,15 +436,25 @@ TEST_P(TestFixture, CheckFilterForSinCmd) // << ")" << std::endl; for (size_t i = 0; i < 100; ++i) { + auto start_time = std::chrono::steady_clock::now(); + const bool reset_clock = (i == 0); const auto cmd = cmd_generator_.calcSinWaveCommand(reset_clock); pub_sub_node_.publishControlCommand(cmd); pub_sub_node_.publishDefaultTopicsNoSpin(); - for (int i = 0; i < 20; ++i) { + for (int j = 0; j < 20; ++j) { rclcpp::spin_some(pub_sub_node_.get_node_base_interface()); rclcpp::spin_some(vehicle_cmd_gate_node_->get_node_base_interface()); } - std::this_thread::sleep_for(std::chrono::milliseconds{10LL}); + + auto end_time = std::chrono::steady_clock::now(); + std::chrono::milliseconds elapsed = + std::chrono::duration_cast(end_time - start_time); + + std::chrono::milliseconds sleep_duration = std::chrono::milliseconds{10} - elapsed; + if (sleep_duration.count() > 0) { + std::this_thread::sleep_for(sleep_duration); + } } std::cerr << "received cmd num = " << pub_sub_node_.cmd_received_times_.size() << std::endl; From d26565dee8fb25409d49cfcf0fa8c9374e25463c Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Wed, 27 Mar 2024 11:38:06 +0900 Subject: [PATCH 06/56] feat(default_ad_api): add door api (#5737) Signed-off-by: Takagi, Isamu --- .../include/autoware_ad_api_specs/vehicle.hpp | 24 ++++ .../component_interface_specs/vehicle.hpp | 24 ++++ common/tier4_adapi_rviz_plugin/CMakeLists.txt | 1 + .../plugins/plugin_description.xml | 4 + .../src/door_panel.cpp | 118 +++++++++++++++++ .../src/door_panel.hpp | 64 +++++++++ .../launch/simulator.launch.xml | 6 + .../vehicle_door_simulator/CMakeLists.txt | 11 ++ simulator/vehicle_door_simulator/README.md | 3 + .../launch/vehicle_door_simulator.launch.xml | 7 + simulator/vehicle_door_simulator/package.xml | 22 +++ .../src/dummy_doors.cpp | 125 ++++++++++++++++++ .../src/dummy_doors.hpp | 62 +++++++++ system/default_ad_api/CMakeLists.txt | 2 + system/default_ad_api/README.md | 4 + .../launch/default_ad_api.launch.py | 1 + system/default_ad_api/src/vehicle_door.cpp | 33 +++++ system/default_ad_api/src/vehicle_door.hpp | 45 +++++++ 18 files changed, 556 insertions(+) create mode 100644 common/tier4_adapi_rviz_plugin/src/door_panel.cpp create mode 100644 common/tier4_adapi_rviz_plugin/src/door_panel.hpp create mode 100644 simulator/vehicle_door_simulator/CMakeLists.txt create mode 100644 simulator/vehicle_door_simulator/README.md create mode 100644 simulator/vehicle_door_simulator/launch/vehicle_door_simulator.launch.xml create mode 100644 simulator/vehicle_door_simulator/package.xml create mode 100644 simulator/vehicle_door_simulator/src/dummy_doors.cpp create mode 100644 simulator/vehicle_door_simulator/src/dummy_doors.hpp create mode 100644 system/default_ad_api/src/vehicle_door.cpp create mode 100644 system/default_ad_api/src/vehicle_door.hpp diff --git a/common/autoware_ad_api_specs/include/autoware_ad_api_specs/vehicle.hpp b/common/autoware_ad_api_specs/include/autoware_ad_api_specs/vehicle.hpp index 0baf8531d00c8..4175a04aadadc 100644 --- a/common/autoware_ad_api_specs/include/autoware_ad_api_specs/vehicle.hpp +++ b/common/autoware_ad_api_specs/include/autoware_ad_api_specs/vehicle.hpp @@ -17,9 +17,12 @@ #include +#include #include #include +#include #include +#include namespace autoware_ad_api::vehicle { @@ -48,6 +51,27 @@ struct Dimensions static constexpr char name[] = "/api/vehicle/dimensions"; }; +struct DoorCommand +{ + using Service = autoware_adapi_v1_msgs::srv::SetDoorCommand; + static constexpr char name[] = "/api/vehicle/doors/command"; +}; + +struct DoorLayout +{ + using Service = autoware_adapi_v1_msgs::srv::GetDoorLayout; + static constexpr char name[] = "/api/vehicle/doors/layout"; +}; + +struct DoorStatus +{ + using Message = autoware_adapi_v1_msgs::msg::DoorStatusArray; + static constexpr char name[] = "/api/vehicle/doors/status"; + static constexpr size_t depth = 1; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; +}; + } // namespace autoware_ad_api::vehicle #endif // AUTOWARE_AD_API_SPECS__VEHICLE_HPP_ diff --git a/common/component_interface_specs/include/component_interface_specs/vehicle.hpp b/common/component_interface_specs/include/component_interface_specs/vehicle.hpp index ecbf7a21e1299..6358b35c3c674 100644 --- a/common/component_interface_specs/include/component_interface_specs/vehicle.hpp +++ b/common/component_interface_specs/include/component_interface_specs/vehicle.hpp @@ -17,6 +17,9 @@ #include +#include +#include +#include #include #include #include @@ -71,6 +74,27 @@ struct EnergyStatus static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; }; +struct DoorCommand +{ + using Service = autoware_adapi_v1_msgs::srv::SetDoorCommand; + static constexpr char name[] = "/vehicle/doors/command"; +}; + +struct DoorLayout +{ + using Service = autoware_adapi_v1_msgs::srv::GetDoorLayout; + static constexpr char name[] = "/vehicle/doors/layout"; +}; + +struct DoorStatus +{ + using Message = autoware_adapi_v1_msgs::msg::DoorStatusArray; + static constexpr char name[] = "/vehicle/doors/status"; + static constexpr size_t depth = 1; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; +}; + } // namespace vehicle_interface #endif // COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_ diff --git a/common/tier4_adapi_rviz_plugin/CMakeLists.txt b/common/tier4_adapi_rviz_plugin/CMakeLists.txt index b756e4686f82f..1cf1ca95b852e 100644 --- a/common/tier4_adapi_rviz_plugin/CMakeLists.txt +++ b/common/tier4_adapi_rviz_plugin/CMakeLists.txt @@ -12,6 +12,7 @@ set(CMAKE_INCLUDE_CURRENT_DIR ON) ament_auto_add_library(${PROJECT_NAME} SHARED src/route_tool.cpp src/route_panel.cpp + src/door_panel.cpp ) target_link_libraries(${PROJECT_NAME} diff --git a/common/tier4_adapi_rviz_plugin/plugins/plugin_description.xml b/common/tier4_adapi_rviz_plugin/plugins/plugin_description.xml index 02b18e5a51988..8b095c0e7d037 100644 --- a/common/tier4_adapi_rviz_plugin/plugins/plugin_description.xml +++ b/common/tier4_adapi_rviz_plugin/plugins/plugin_description.xml @@ -8,4 +8,8 @@ RoutePanel + + DoorPanel + + diff --git a/common/tier4_adapi_rviz_plugin/src/door_panel.cpp b/common/tier4_adapi_rviz_plugin/src/door_panel.cpp new file mode 100644 index 0000000000000..56c4c89befbb7 --- /dev/null +++ b/common/tier4_adapi_rviz_plugin/src/door_panel.cpp @@ -0,0 +1,118 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "door_panel.hpp" + +#include + +#include + +namespace tier4_adapi_rviz_plugins +{ + +DoorPanel::DoorPanel(QWidget * parent) : rviz_common::Panel(parent) +{ + status_ = new QLabel("Trying to get door layout."); + layout_ = new QGridLayout(); + layout_->addWidget(status_, 0, 0, 1, 4); + setLayout(layout_); +} + +void DoorPanel::onInitialize() +{ + const auto on_layout = [this](const rclcpp::Client::SharedFuture future) { + const auto res = future.get(); + if (!res->status.success) { + status_->setText(QString::fromStdString("failed to get layout: " + res->status.message)); + return; + } + const auto & layouts = res->doors; + for (size_t index = 0; index < layouts.size(); ++index) { + const auto & layout = layouts[index]; + DoorUI door; + door.description = new QLabel(QString::fromStdString(layout.description)); + door.status = new QLabel("unknown"); + door.open = new QPushButton("open"); + door.close = new QPushButton("close"); + doors_.push_back(door); + + layout_->addWidget(door.description, index + 1, 0); + layout_->addWidget(door.status, index + 1, 1); + layout_->addWidget(door.open, index + 1, 2); + layout_->addWidget(door.close, index + 1, 3); + + using Command = autoware_adapi_v1_msgs::msg::DoorCommand; + const auto on_open = [this, index] { on_button(index, Command::OPEN); }; + const auto on_close = [this, index] { on_button(index, Command::CLOSE); }; + connect(door.open, &QPushButton::clicked, on_open); + connect(door.close, &QPushButton::clicked, on_close); + } + status_->hide(); + }; + + const auto on_status = [this](const DoorStatus::Message::ConstSharedPtr msg) { + using Status = autoware_adapi_v1_msgs::msg::DoorStatus; + if (doors_.size() != msg->doors.size()) { + return; + } + for (size_t index = 0; index < doors_.size(); ++index) { + const auto & label = doors_[index].status; + switch (msg->doors[index].status) { + case Status::NOT_AVAILABLE: + label->setText("not available"); + break; + case Status::OPENED: + label->setText("opened"); + break; + case Status::CLOSED: + label->setText("closed"); + break; + case Status::OPENING: + label->setText("opening"); + break; + case Status::CLOSING: + label->setText("closing"); + break; + default: + label->setText("unknown"); + break; + } + } + }; + + auto lock = getDisplayContext()->getRosNodeAbstraction().lock(); + auto node = lock->get_raw_node(); + + const auto adaptor = component_interface_utils::NodeAdaptor(node.get()); + adaptor.init_cli(cli_command_); + adaptor.init_cli(cli_layout_); + adaptor.init_sub(sub_status_, on_status); + + const auto req = std::make_shared(); + cli_layout_->async_send_request(req, on_layout); +} + +void DoorPanel::on_button(uint32_t index, uint8_t command) +{ + const auto req = std::make_shared(); + req->doors.resize(1); + req->doors.back().index = index; + req->doors.back().command = command; + cli_command_->async_send_request(req); +} + +} // namespace tier4_adapi_rviz_plugins + +#include +PLUGINLIB_EXPORT_CLASS(tier4_adapi_rviz_plugins::DoorPanel, rviz_common::Panel) diff --git a/common/tier4_adapi_rviz_plugin/src/door_panel.hpp b/common/tier4_adapi_rviz_plugin/src/door_panel.hpp new file mode 100644 index 0000000000000..fdeb310736e9f --- /dev/null +++ b/common/tier4_adapi_rviz_plugin/src/door_panel.hpp @@ -0,0 +1,64 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef DOOR_PANEL_HPP_ +#define DOOR_PANEL_HPP_ + +#include +#include +#include +#include +#include +#include +#include + +#include + +namespace tier4_adapi_rviz_plugins +{ + +class DoorPanel : public rviz_common::Panel +{ + Q_OBJECT + using DoorCommand = autoware_ad_api::vehicle::DoorCommand; + using DoorLayout = autoware_ad_api::vehicle::DoorLayout; + using DoorStatus = autoware_ad_api::vehicle::DoorStatus; + +public: + explicit DoorPanel(QWidget * parent = nullptr); + void onInitialize() override; + +private: + component_interface_utils::Client::SharedPtr cli_command_; + component_interface_utils::Client::SharedPtr cli_layout_; + component_interface_utils::Subscription::SharedPtr sub_status_; + + struct DoorUI + { + QLabel * description; + QLabel * status; + QPushButton * open; + QPushButton * close; + }; + QGridLayout * layout_; + QLabel * status_; + std::vector doors_; + +private slots: + void on_button(uint32_t index, uint8_t command); +}; + +} // namespace tier4_adapi_rviz_plugins + +#endif // DOOR_PANEL_HPP_ diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 3733cd09682fd..4af7b3abaa2e6 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -10,6 +10,7 @@ + @@ -135,6 +136,11 @@ + + + + + diff --git a/simulator/vehicle_door_simulator/CMakeLists.txt b/simulator/vehicle_door_simulator/CMakeLists.txt new file mode 100644 index 0000000000000..fbe989555c4ba --- /dev/null +++ b/simulator/vehicle_door_simulator/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.14) +project(vehicle_door_simulator) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_executable(dummy_doors + src/dummy_doors.cpp +) + +ament_auto_package(INSTALL_TO_SHARE launch) diff --git a/simulator/vehicle_door_simulator/README.md b/simulator/vehicle_door_simulator/README.md new file mode 100644 index 0000000000000..f312216622a5b --- /dev/null +++ b/simulator/vehicle_door_simulator/README.md @@ -0,0 +1,3 @@ +# vehicle_door_simulator + +This package is for testing operations on vehicle devices such as doors. diff --git a/simulator/vehicle_door_simulator/launch/vehicle_door_simulator.launch.xml b/simulator/vehicle_door_simulator/launch/vehicle_door_simulator.launch.xml new file mode 100644 index 0000000000000..66857130a4932 --- /dev/null +++ b/simulator/vehicle_door_simulator/launch/vehicle_door_simulator.launch.xml @@ -0,0 +1,7 @@ + + + + + + + diff --git a/simulator/vehicle_door_simulator/package.xml b/simulator/vehicle_door_simulator/package.xml new file mode 100644 index 0000000000000..f65a1e07040d7 --- /dev/null +++ b/simulator/vehicle_door_simulator/package.xml @@ -0,0 +1,22 @@ + + + + vehicle_door_simulator + 0.1.0 + The vehicle_door_simulator package + Takagi, Isamu + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + autoware_adapi_v1_msgs + rclcpp + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/simulator/vehicle_door_simulator/src/dummy_doors.cpp b/simulator/vehicle_door_simulator/src/dummy_doors.cpp new file mode 100644 index 0000000000000..b78ca9973e7e1 --- /dev/null +++ b/simulator/vehicle_door_simulator/src/dummy_doors.cpp @@ -0,0 +1,125 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "dummy_doors.hpp" + +#include + +namespace vehicle_door_simulator +{ + +DummyDoors::DummyDoors() : Node("dummy_doors") +{ + using std::placeholders::_1; + using std::placeholders::_2; + + srv_command_ = create_service( + "~/doors/command", std::bind(&DummyDoors::on_command, this, _1, _2)); + srv_layout_ = create_service( + "~/doors/layout", std::bind(&DummyDoors::on_layout, this, _1, _2)); + + pub_status_ = create_publisher("~/doors/status", rclcpp::QoS(1)); + + const auto period = rclcpp::Rate(5.0).period(); + timer_ = rclcpp::create_timer(this, get_clock(), period, [this]() { on_timer(); }); +} + +void DummyDoors::on_command( + const SetDoorCommand::Request::SharedPtr req, const SetDoorCommand::Response::SharedPtr res) +{ + using autoware_adapi_v1_msgs::msg::DoorCommand; + + for (const auto & door : req->doors) { + if (statuses_.size() <= door.index) { + res->status.success = false; + res->status.message = "invalid door index"; + return; + } + if (door.command != DoorCommand::CLOSE && door.command != DoorCommand::OPEN) { + res->status.success = false; + res->status.message = "invalid door command"; + return; + } + } + + for (const auto & door : req->doors) { + if (door.command == DoorCommand::CLOSE) { + statuses_[door.index].status = DoorStatus::CLOSING; + } + if (door.command == DoorCommand::OPEN) { + statuses_[door.index].status = DoorStatus::OPENING; + } + } + + res->status.success = true; +} + +void DummyDoors::on_layout( + const GetDoorLayout::Request::SharedPtr, const GetDoorLayout::Response::SharedPtr res) +{ + using autoware_adapi_v1_msgs::msg::DoorLayout; + + res->doors.resize(statuses_.size()); + res->doors[0].description = "dummy door 1"; + res->doors[1].description = "dummy door 2"; + res->doors[2].description = "dummy door 3"; + res->doors[3].description = "dummy door 4"; + res->doors[0].roles = {}; + res->doors[1].roles = {DoorLayout::GET_ON}; + res->doors[2].roles = {DoorLayout::GET_ON, DoorLayout::GET_OFF}; + res->doors[3].roles = {DoorLayout::GET_OFF}; + res->status.success = true; +} + +void DummyDoors::on_timer() +{ + using autoware_adapi_v1_msgs::msg::DoorStatus; + + for (auto & status : statuses_) { + if (status.status == DoorStatus::CLOSING) { + if (--status.progress <= 0) { + status.progress = 0; + status.status = DoorStatus::CLOSED; + } + } + if (status.status == DoorStatus::OPENING) { + if (max_progress <= ++status.progress) { + status.progress = max_progress; + status.status = DoorStatus::OPENED; + } + } + } + + DoorStatusArray message; + message.stamp = now(); + for (const auto & status : statuses_) { + DoorStatus door; + door.status = status.status; + message.doors.push_back(door); + } + pub_status_->publish(message); +} + +} // namespace vehicle_door_simulator + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + rclcpp::executors::SingleThreadedExecutor executor; + auto node = std::make_shared(); + executor.add_node(node); + executor.spin(); + executor.remove_node(node); + rclcpp::shutdown(); +} diff --git a/simulator/vehicle_door_simulator/src/dummy_doors.hpp b/simulator/vehicle_door_simulator/src/dummy_doors.hpp new file mode 100644 index 0000000000000..485586fa8724e --- /dev/null +++ b/simulator/vehicle_door_simulator/src/dummy_doors.hpp @@ -0,0 +1,62 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef DUMMY_DOORS_HPP_ +#define DUMMY_DOORS_HPP_ + +#include + +#include +#include +#include + +#include + +namespace vehicle_door_simulator +{ + +class DummyDoors : public rclcpp::Node +{ +public: + DummyDoors(); + +private: + using SetDoorCommand = autoware_adapi_v1_msgs::srv::SetDoorCommand; + using GetDoorLayout = autoware_adapi_v1_msgs::srv::GetDoorLayout; + using DoorStatus = autoware_adapi_v1_msgs::msg::DoorStatus; + using DoorStatusArray = autoware_adapi_v1_msgs::msg::DoorStatusArray; + rclcpp::TimerBase::SharedPtr timer_; + rclcpp::Service::SharedPtr srv_command_; + rclcpp::Service::SharedPtr srv_layout_; + rclcpp::Publisher::SharedPtr pub_status_; + + void on_command( + const SetDoorCommand::Request::SharedPtr req, const SetDoorCommand::Response::SharedPtr res); + void on_layout( + const GetDoorLayout::Request::SharedPtr req, const GetDoorLayout::Response::SharedPtr res); + void on_timer(); + + struct LocalStatus + { + using StatusType = DoorStatus::_status_type; + int progress = 0; + StatusType status = DoorStatus::CLOSED; + }; + static constexpr int max_progress = 25; // 5s * 5Hz + std::array statuses_; +}; + +} // namespace vehicle_door_simulator + +#endif // DUMMY_DOORS_HPP_ diff --git a/system/default_ad_api/CMakeLists.txt b/system/default_ad_api/CMakeLists.txt index 7b9ad47d3782c..982112189412e 100644 --- a/system/default_ad_api/CMakeLists.txt +++ b/system/default_ad_api/CMakeLists.txt @@ -15,6 +15,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/routing.cpp src/vehicle.cpp src/vehicle_info.cpp + src/vehicle_door.cpp src/utils/route_conversion.cpp src/compatibility/autoware_state.cpp ) @@ -31,6 +32,7 @@ rclcpp_components_register_nodes(${PROJECT_NAME} "default_ad_api::RoutingNode" "default_ad_api::VehicleNode" "default_ad_api::VehicleInfoNode" + "default_ad_api::VehicleDoorNode" ) if(BUILD_TESTING) diff --git a/system/default_ad_api/README.md b/system/default_ad_api/README.md index e605f9ca79c1f..7bc496010eee9 100644 --- a/system/default_ad_api/README.md +++ b/system/default_ad_api/README.md @@ -1,5 +1,9 @@ # default_ad_api +## Notes + +Components that relay services must be executed by the Multi-Threaded Executor. + ## Features This package is a default implementation AD API. diff --git a/system/default_ad_api/launch/default_ad_api.launch.py b/system/default_ad_api/launch/default_ad_api.launch.py index 57a8557eb7e0a..cf8fbe7d001bf 100644 --- a/system/default_ad_api/launch/default_ad_api.launch.py +++ b/system/default_ad_api/launch/default_ad_api.launch.py @@ -52,6 +52,7 @@ def generate_launch_description(): create_api_node("routing", "RoutingNode"), create_api_node("vehicle", "VehicleNode"), create_api_node("vehicle_info", "VehicleInfoNode"), + create_api_node("vehicle_door", "VehicleDoorNode"), ] container = ComposableNodeContainer( namespace="default_ad_api", diff --git a/system/default_ad_api/src/vehicle_door.cpp b/system/default_ad_api/src/vehicle_door.cpp new file mode 100644 index 0000000000000..b94921c8fd41b --- /dev/null +++ b/system/default_ad_api/src/vehicle_door.cpp @@ -0,0 +1,33 @@ +// Copyright 2023 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 "vehicle_door.hpp" + +namespace default_ad_api +{ + +VehicleDoorNode::VehicleDoorNode(const rclcpp::NodeOptions & options) +: Node("vehicle_door", options) +{ + const auto adaptor = component_interface_utils::NodeAdaptor(this); + group_cli_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + adaptor.relay_service(cli_command_, srv_command_, group_cli_, 3.0); + adaptor.relay_service(cli_layout_, srv_layout_, group_cli_, 3.0); + adaptor.relay_message(pub_status_, sub_status_); +} + +} // namespace default_ad_api + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::VehicleDoorNode) diff --git a/system/default_ad_api/src/vehicle_door.hpp b/system/default_ad_api/src/vehicle_door.hpp new file mode 100644 index 0000000000000..92e8918afcdf8 --- /dev/null +++ b/system/default_ad_api/src/vehicle_door.hpp @@ -0,0 +1,45 @@ +// Copyright 2023 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 VEHICLE_DOOR_HPP_ +#define VEHICLE_DOOR_HPP_ + +#include +#include +#include + +// This file should be included after messages. +#include "utils/types.hpp" + +namespace default_ad_api +{ + +class VehicleDoorNode : public rclcpp::Node +{ +public: + explicit VehicleDoorNode(const rclcpp::NodeOptions & options); + +private: + rclcpp::CallbackGroup::SharedPtr group_cli_; + Srv srv_command_; + Srv srv_layout_; + Pub pub_status_; + Cli cli_command_; + Cli cli_layout_; + Sub sub_status_; +}; + +} // namespace default_ad_api + +#endif // VEHICLE_DOOR_HPP_ From 2d524dcb2ff40ac105cdb44a00e88737ce23ac47 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 27 Mar 2024 13:37:58 +0900 Subject: [PATCH 07/56] fix(lane_change): do not return empty path if no valid path (#6686) * fix(lane_change): do not return empty path if no valid path Signed-off-by: Zulfaqar Azmi * style(pre-commit): autofix --------- Signed-off-by: Zulfaqar Azmi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../behavior_path_lane_change_module/src/interface.cpp | 4 ---- planning/behavior_path_lane_change_module/src/scene.cpp | 8 ++++++++ 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/planning/behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp index 0e2aaed2b38f6..7162dbc53c86d 100644 --- a/planning/behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -104,10 +104,6 @@ BehaviorModuleOutput LaneChangeInterface::plan() resetPathCandidate(); resetPathReference(); - if (!module_type_->isValidPath()) { - return {}; - } - auto output = module_type_->generateOutput(); path_reference_ = std::make_shared(output.reference_path); *prev_approved_path_ = getPreviousModuleOutput().path; diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index 03569aa4f3cdd..9524d47e522e5 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -195,6 +195,14 @@ BehaviorModuleOutput NormalLaneChange::generateOutput() { BehaviorModuleOutput output; + if (!status_.is_valid_path) { + output.path = prev_module_path_; + output.reference_path = prev_module_reference_path_; + output.drivable_area_info = prev_drivable_area_info_; + output.turn_signal_info = prev_turn_signal_info_; + return output; + } + if (isAbortState() && abort_path_) { output.path = abort_path_->path; output.reference_path = prev_module_reference_path_; From aa057b8bbcd837102e5b615a89b3ac7e909b8a6f Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 27 Mar 2024 13:38:11 +0900 Subject: [PATCH 08/56] fix(avoidance_by_lane_change): object filtering too conservative (#6662) * fix(avoidance_by_lane_change): object filtering too conservative Signed-off-by: Muhammad Zulfaqar Azmi * initialize last seen as RCL_ROS_TIME to prevent runtime error Signed-off-by: Muhammad Zulfaqar Azmi * Remove object that is in the centerline Signed-off-by: Muhammad Zulfaqar Azmi * style(pre-commit): autofix --------- Signed-off-by: Muhammad Zulfaqar Azmi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../scene.hpp | 2 +- .../src/scene.cpp | 53 +++++++++---------- .../data_structs.hpp | 2 +- .../src/interface.cpp | 2 +- 4 files changed, 27 insertions(+), 32 deletions(-) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp index c663c31537fd1..54a4a0c70486d 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp @@ -50,7 +50,7 @@ class AvoidanceByLaneChange : public NormalLaneChange mutable ObjectDataArray stopped_objects_; std::shared_ptr avoidance_helper_; - ObjectData createObjectData( + std::optional createObjectData( const AvoidancePlanningData & data, const PredictedObject & object) const; void fillAvoidanceTargetObjects(AvoidancePlanningData & data, AvoidanceDebugData & debug) const; diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp index 1aab806f76cc9..27c6713adfead 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -29,6 +29,7 @@ #include #include +#include #include namespace behavior_path_planner @@ -81,6 +82,9 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const getCommonParam().vehicle_info, getEgoPose(), std::max(minimum_lane_change_length, minimum_avoid_length), calcLateralOffset()); + RCLCPP_DEBUG( + logger_, "Conditions ? %f, %f, %f", nearest_object.longitudinal, minimum_lane_change_length, + minimum_avoid_length); return nearest_object.longitudinal > std::max(minimum_lane_change_length, minimum_avoid_length); } @@ -128,23 +132,6 @@ AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData( data.current_lanelets = getCurrentLanes(); - // expand drivable lanes - std::for_each( - data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) { - data.drivable_lanes.push_back(utils::avoidance::generateExpandedDrivableLanes( - lanelet, planner_data_, avoidance_parameters_)); - }); - - // calc drivable bound - const auto shorten_lanes = - utils::cutOverlappedLanes(data.reference_path_rough, data.drivable_lanes); - data.left_bound = utils::calcBound( - data.reference_path_rough, planner_data_, shorten_lanes, false, false, false, true); - data.right_bound = utils::calcBound( - data.reference_path_rough, planner_data_, shorten_lanes, false, false, false, false); - - // get related objects from dynamic_objects, and then separates them as target objects and non - // target objects fillAvoidanceTargetObjects(data, debug); return data; @@ -184,19 +171,19 @@ void AvoidanceByLaneChange::fillAvoidanceTargetObjects( ObjectDataArray target_lane_objects; target_lane_objects.reserve(object_within_target_lane.objects.size()); - { - const auto & objects = object_within_target_lane.objects; - std::transform( - objects.cbegin(), objects.cend(), std::back_inserter(target_lane_objects), - [&](const auto & object) { return createObjectData(data, object); }); + for (const auto & obj : object_within_target_lane.objects) { + const auto target_lane_object = createObjectData(data, obj); + if (!target_lane_object) { + continue; + } + + target_lane_objects.push_back(*target_lane_object); } - utils::avoidance::filterTargetObjects( - target_lane_objects, data, avoidance_parameters_->object_check_max_forward_distance, - planner_data_, p); + data.target_objects = target_lane_objects; } -ObjectData AvoidanceByLaneChange::createObjectData( +std::optional AvoidanceByLaneChange::createObjectData( const AvoidancePlanningData & data, const PredictedObject & object) const { using boost::geometry::return_centroid; @@ -214,6 +201,15 @@ ObjectData AvoidanceByLaneChange::createObjectData( const auto & object_parameter = avoidance_parameters_->object_parameters.at(t); ObjectData object_data{}; + // Calc lateral deviation from path to target object. + object_data.to_centerline = + lanelet::utils::getArcCoordinates(data.current_lanelets, object_pose).distance; + + if ( + std::abs(object_data.to_centerline) < + avoidance_parameters_->threshold_distance_object_is_on_center) { + return std::nullopt; + } object_data.object = object; @@ -233,9 +229,6 @@ ObjectData AvoidanceByLaneChange::createObjectData( // Calc moving time. utils::avoidance::fillObjectMovingTime(object_data, stopped_objects_, p); - // Calc lateral deviation from path to target object. - object_data.to_centerline = - lanelet::utils::getArcCoordinates(data.current_lanelets, object_pose).distance; object_data.direction = calcLateralDeviation(object_closest_pose, object_pose.position) > 0.0 ? Direction::LEFT : Direction::RIGHT; @@ -248,6 +241,8 @@ ObjectData AvoidanceByLaneChange::createObjectData( const auto & vehicle_width = planner_data_->parameters.vehicle_width; utils::avoidance::fillAvoidanceNecessity(object_data, registered_objects_, vehicle_width, p); + utils::avoidance::fillLongitudinalAndLengthByClosestEnvelopeFootprint( + data.reference_path_rough, getEgoPosition(), object_data); return object_data; } 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 a8020c4189884..686e4023bc7c2 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 @@ -371,7 +371,7 @@ struct ObjectData // avoidance target double distance_factor{0.0}; // count up when object disappeared. Removed when it exceeds threshold. - rclcpp::Time last_seen; + rclcpp::Time last_seen{rclcpp::Clock(RCL_ROS_TIME).now()}; double lost_time{0.0}; // count up when object moved. Removed when it exceeds threshold. diff --git a/planning/behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp index 7162dbc53c86d..46b65a3ef4e79 100644 --- a/planning/behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -80,13 +80,13 @@ void LaneChangeInterface::updateData() getPreviousModuleOutput().reference_path, getPreviousModuleOutput().path); module_type_->setPreviousDrivableAreaInfo(getPreviousModuleOutput().drivable_area_info); module_type_->setPreviousTurnSignalInfo(getPreviousModuleOutput().turn_signal_info); + module_type_->updateSpecialData(); if (isWaitingApproval()) { module_type_->updateLaneChangeStatus(); } updateDebugMarker(); - module_type_->updateSpecialData(); module_type_->resetStopPose(); } From a0bac37096604019cd1858a0aa54df3448e27913 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Wed, 27 Mar 2024 13:46:08 +0900 Subject: [PATCH 09/56] feat(behavior_velocity_run_out_module): exclude obstacle crossing ego back line (#6680) * add method to ignore target obstacles that cross ego cut lane Signed-off-by: Daniel Sanchez * WIP add debug support Signed-off-by: Daniel Sanchez * add params and finish debug marker Signed-off-by: Daniel Sanchez * change lane to line Signed-off-by: Daniel Sanchez * use autoware utils to get the cut line Signed-off-by: Daniel Sanchez * simplify code wit calcOffsetPose Signed-off-by: Daniel Sanchez * Update readme and eliminate unused code Signed-off-by: Daniel Sanchez * update readme Signed-off-by: Daniel Sanchez * eliminate unused function Signed-off-by: Daniel Sanchez * readme Signed-off-by: Daniel Sanchez * comments and readme Signed-off-by: Daniel Sanchez * eliminate unused include Signed-off-by: Daniel Sanchez * typo Signed-off-by: Daniel Sanchez * rename param for consistency Signed-off-by: Daniel Sanchez * change lane to line for consistency Signed-off-by: Daniel Sanchez * rename for clarity, add brief Signed-off-by: Daniel Sanchez * fix indentation Signed-off-by: Daniel Sanchez * update description Signed-off-by: Daniel Sanchez * lane ->line Signed-off-by: Daniel Sanchez * lane -> line Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../README.md | 8 ++ .../config/run_out.param.yaml | 2 + .../docs/ego_cut_line.svg | 129 ++++++++++++++++++ .../src/debug.cpp | 19 +++ .../src/debug.hpp | 2 + .../src/manager.cpp | 2 + .../src/scene.cpp | 38 +++++- .../src/scene.hpp | 11 ++ .../src/utils.cpp | 22 +++ .../src/utils.hpp | 8 ++ 10 files changed, 235 insertions(+), 6 deletions(-) create mode 100644 planning/behavior_velocity_run_out_module/docs/ego_cut_line.svg diff --git a/planning/behavior_velocity_run_out_module/README.md b/planning/behavior_velocity_run_out_module/README.md index c48f2a951cd55..5cd4b2708fd2d 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 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. + +You can choose whether to use this feature by setting the parameter `use_ego_cut_line` to `true` or `false`. The width of the line can be tuned with the parameter `ego_cut_line_length`. + +![brief](./docs/ego_cut_line.svg) + #### Collision detection ##### Detect collision with dynamic obstacles 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 196f7c6296cb4..15264e1e4e2b1 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 @@ -4,6 +4,7 @@ detection_method: "Object" # [-] candidate: Object, ObjectWithoutPath, Points 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 specify_decel_jerk: true # [-] whether to specify jerk when ego decelerates stop_margin: 2.5 # [m] the vehicle decelerates to be able to stop with this margin passing_margin: 1.1 # [m] the vehicle begins to accelerate if the vehicle's front in predicted position is ahead of the obstacle + this margin @@ -11,6 +12,7 @@ detection_distance: 45.0 # [m] ahead distance from ego to detect the obstacles 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 # Parameter to create abstracted dynamic obstacles dynamic_obstacle: diff --git a/planning/behavior_velocity_run_out_module/docs/ego_cut_line.svg b/planning/behavior_velocity_run_out_module/docs/ego_cut_line.svg new file mode 100644 index 0000000000000..de6bec5e172df --- /dev/null +++ b/planning/behavior_velocity_run_out_module/docs/ego_cut_line.svg @@ -0,0 +1,129 @@ + + + + + + + + + + diff --git a/planning/behavior_velocity_run_out_module/src/debug.cpp b/planning/behavior_velocity_run_out_module/src/debug.cpp index c0d026b5ffaf4..23764bc73fbff 100644 --- a/planning/behavior_velocity_run_out_module/src/debug.cpp +++ b/planning/behavior_velocity_run_out_module/src/debug.cpp @@ -86,6 +86,14 @@ void RunOutDebug::pushCollisionPoints(const geometry_msgs::msg::Point & point) collision_points_.push_back(point_with_height); } +void RunOutDebug::pushEgoCutLine(const std::vector & line) +{ + for (const auto & point : line) { + const auto point_with_height = createPoint(point.x, point.y, height_); + ego_cut_line_.push_back(point_with_height); + } +} + void RunOutDebug::pushCollisionPoints(const std::vector & points) { for (const auto & p : points) { @@ -160,6 +168,7 @@ void RunOutDebug::clearDebugMarker() predicted_obstacle_polygons_.clear(); collision_obstacle_polygons_.clear(); travel_time_texts_.clear(); + ego_cut_line_.clear(); } visualization_msgs::msg::MarkerArray RunOutDebug::createVisualizationMarkerArray() @@ -265,6 +274,16 @@ visualization_msgs::msg::MarkerArray RunOutDebug::createVisualizationMarkerArray &msg); } + if (!ego_cut_line_.empty()) { + auto marker = createDefaultMarker( + "map", current_time, "ego_cut_line", 0, visualization_msgs::msg::Marker::LINE_LIST, + createMarkerScale(0.2, 0.2, 0.2), createMarkerColor(0.7, 0.0, 0.7, 0.999)); + for (const auto & p : ego_cut_line_) { + marker.points.push_back(p); + } + msg.markers.push_back(marker); + } + if (!travel_time_texts_.empty()) { auto marker = createDefaultMarker( "map", current_time, "travel_time_texts", 0, diff --git a/planning/behavior_velocity_run_out_module/src/debug.hpp b/planning/behavior_velocity_run_out_module/src/debug.hpp index b28725a92628e..e9b269ee437f0 100644 --- a/planning/behavior_velocity_run_out_module/src/debug.hpp +++ b/planning/behavior_velocity_run_out_module/src/debug.hpp @@ -109,6 +109,7 @@ class RunOutDebug void pushPredictedVehiclePolygons(const std::vector & polygon); void pushPredictedObstaclePolygons(const std::vector & polygon); void pushCollisionObstaclePolygons(const std::vector & polygon); + void pushEgoCutLine(const std::vector & line); void pushDetectionAreaPolygons(const Polygon2d & debug_polygon); void pushMandatoryDetectionAreaPolygons(const Polygon2d & debug_polygon); void pushTravelTimeTexts( @@ -134,6 +135,7 @@ class RunOutDebug rclcpp::Publisher::SharedPtr pub_debug_pointcloud_; std::vector collision_points_; std::vector nearest_collision_point_; + std::vector ego_cut_line_; std::vector stop_pose_; std::vector> predicted_vehicle_polygons_; std::vector> predicted_obstacle_polygons_; diff --git a/planning/behavior_velocity_run_out_module/src/manager.cpp b/planning/behavior_velocity_run_out_module/src/manager.cpp index f2ef366cbe121..305d74e77f348 100644 --- a/planning/behavior_velocity_run_out_module/src/manager.cpp +++ b/planning/behavior_velocity_run_out_module/src/manager.cpp @@ -58,6 +58,7 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node) auto & p = planner_param_.run_out; p.detection_method = getOrDeclareParameter(node, ns + ".detection_method"); p.use_partition_lanelet = getOrDeclareParameter(node, ns + ".use_partition_lanelet"); + p.use_ego_cut_line = getOrDeclareParameter(node, ns + ".use_ego_cut_line"); 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"); @@ -66,6 +67,7 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node) p.detection_distance = getOrDeclareParameter(node, ns + ".detection_distance"); 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"); } { diff --git a/planning/behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_run_out_module/src/scene.cpp index 50b69fc6139c9..1dc86aa8bf87e 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_run_out_module/src/scene.cpp @@ -102,9 +102,18 @@ bool RunOutModule::modifyPathVelocity( const auto dynamic_obstacles = dynamic_obstacle_creator_->createDynamicObstacles(); debug_ptr_->setDebugValues(DebugValues::TYPE::NUM_OBSTACLES, dynamic_obstacles.size()); - // extract obstacles using lanelet information - const auto partition_excluded_obstacles = - excludeObstaclesOutSideOfPartition(dynamic_obstacles, extended_smoothed_path, current_pose); + const auto filtered_obstacles = std::invoke([&]() { + // 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; + + // 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; + }); // record time for obstacle creation const auto t_obstacle_creation = std::chrono::system_clock::now(); @@ -122,7 +131,7 @@ bool RunOutModule::modifyPathVelocity( planner_data_->route_handler_->getOverallGraphPtr()) : std::vector>(); const auto dynamic_obstacle = - detectCollision(partition_excluded_obstacles, extended_smoothed_path, crosswalk_lanelets); + detectCollision(filtered_obstacles, extended_smoothed_path, crosswalk_lanelets); // record time for collision check const auto t_collision_check = std::chrono::system_clock::now(); @@ -147,8 +156,7 @@ bool RunOutModule::modifyPathVelocity( applyMaxJerkLimit(current_pose, current_vel, current_acc, *path); } - publishDebugValue( - extended_smoothed_path, partition_excluded_obstacles, dynamic_obstacle, current_pose); + publishDebugValue(extended_smoothed_path, filtered_obstacles, dynamic_obstacle, current_pose); // record time for collision check const auto t_path_planning = std::chrono::system_clock::now(); @@ -810,6 +818,24 @@ void RunOutModule::applyMaxJerkLimit( run_out_utils::insertPathVelocityFromIndex(stop_point_idx.value(), jerk_limited_vel, path.points); } +std::vector RunOutModule::excludeObstaclesCrossingEgoCutLine( + const std::vector & dynamic_obstacles, + const geometry_msgs::msg::Pose & current_pose) const +{ + 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; + std::for_each(dynamic_obstacles.begin(), dynamic_obstacles.end(), [&](const auto & o) { + const auto predicted_path = run_out_utils::getHighestConfidencePath(o.predicted_paths); + if (!run_out_utils::pathIntersectsEgoCutLine( + predicted_path, current_pose, ego_cut_line_half_width, ego_cut_line)) { + extracted_obstacles.push_back(o); + } + }); + debug_ptr_->pushEgoCutLine(ego_cut_line); + return extracted_obstacles; +} + std::vector RunOutModule::excludeObstaclesOutSideOfPartition( const std::vector & dynamic_obstacles, const PathWithLaneId & path, const geometry_msgs::msg::Pose & current_pose) const diff --git a/planning/behavior_velocity_run_out_module/src/scene.hpp b/planning/behavior_velocity_run_out_module/src/scene.hpp index def90f036c440..02b17783ab6c1 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/behavior_velocity_run_out_module/src/scene.hpp @@ -136,6 +136,17 @@ class RunOutModule : public SceneModuleInterface const geometry_msgs::msg::Pose & current_pose, const float current_vel, const float current_acc, PathWithLaneId & path) const; + /** + * @brief Creates a virtual line segment that is perpendicular to the ego vehicle and that passes + * through the ego's base link and excludes objects with paths that intersect that line segment. + * @param [in] dynamic_obstacles obstacles to be filtered. + * @param [in] current_pose ego vehicle's current pose. + * @return a vector of dynamic obstacles that don't intersect the line segment. + */ + std::vector excludeObstaclesCrossingEgoCutLine( + const std::vector & dynamic_obstacles, + const geometry_msgs::msg::Pose & current_pose) const; + std::vector excludeObstaclesOutSideOfPartition( const std::vector & dynamic_obstacles, const PathWithLaneId & path, const geometry_msgs::msg::Pose & current_pose) const; diff --git a/planning/behavior_velocity_run_out_module/src/utils.cpp b/planning/behavior_velocity_run_out_module/src/utils.cpp index db989f90fafc9..f17f4c7251ea4 100644 --- a/planning/behavior_velocity_run_out_module/src/utils.cpp +++ b/planning/behavior_velocity_run_out_module/src/utils.cpp @@ -176,6 +176,28 @@ std::optional findFirstStopPointIdx(PathPointsWithLaneId & path_points) return {}; } +bool pathIntersectsEgoCutLine( + const std::vector & path, const geometry_msgs::msg::Pose & ego_pose, + const double half_line_length, std::vector & ego_cut_line) +{ + if (path.size() < 2) return false; + const auto p1 = + tier4_autoware_utils::calcOffsetPose(ego_pose, 0.0, half_line_length, 0.0).position; + const auto p2 = + tier4_autoware_utils::calcOffsetPose(ego_pose, 0.0, -half_line_length, 0.0).position; + ego_cut_line = {p1, p2}; + + for (size_t i = 1; i < path.size(); ++i) { + const auto & p3 = path.at(i).position; + const auto & p4 = path.at(i - 1).position; + const auto intersection = tier4_autoware_utils::intersect(p1, p2, p3, p4); + if (intersection.has_value()) { + return true; + } + } + return false; +} + LineString2d createLineString2d(const lanelet::BasicPolygon2d & poly) { LineString2d line_string; diff --git a/planning/behavior_velocity_run_out_module/src/utils.hpp b/planning/behavior_velocity_run_out_module/src/utils.hpp index c4976a119dd00..63576ca62329f 100644 --- a/planning/behavior_velocity_run_out_module/src/utils.hpp +++ b/planning/behavior_velocity_run_out_module/src/utils.hpp @@ -15,6 +15,8 @@ #ifndef UTILS_HPP_ #define UTILS_HPP_ +#include "tier4_autoware_utils/geometry/geometry.hpp" + #include #include #include @@ -56,9 +58,11 @@ struct RunOutParam bool use_partition_lanelet; bool suppress_on_crosswalk; bool specify_decel_jerk; + bool use_ego_cut_line; double stop_margin; double passing_margin; double deceleration_jerk; + double ego_cut_line_length; float detection_distance; float detection_span; float min_vel_ego_kmph; @@ -194,6 +198,10 @@ struct DynamicObstacleData Polygon2d createBoostPolyFromMsg(const std::vector & input_poly); +bool pathIntersectsEgoCutLine( + const std::vector & path, const geometry_msgs::msg::Pose & ego_pose, + const double half_line_length, std::vector & ego_cut_line); + std::uint8_t getHighestProbLabel(const std::vector & classification); std::vector getHighestConfidencePath( From e84aaeedc175766e712a3d7182e1634c6987910a Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Wed, 27 Mar 2024 15:54:55 +0900 Subject: [PATCH 10/56] feat(run_out): add motorcyles to run out module target obstacles (#6690) * feat(run_out): add motorcyles to run out module target obstacles Signed-off-by: Daniel Sanchez * check for obstacle type depending on params Signed-off-by: Daniel Sanchez * update readme Signed-off-by: Daniel Sanchez * pre-commit Signed-off-by: Daniel Sanchez * include what you use Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../README.md | 25 ++++++++++--------- .../config/run_out.param.yaml | 1 + .../package.xml | 1 + .../src/manager.cpp | 3 +++ .../src/scene.cpp | 15 +++++------ .../src/scene.hpp | 1 + .../src/utils.hpp | 1 + 7 files changed, 28 insertions(+), 19 deletions(-) diff --git a/planning/behavior_velocity_run_out_module/README.md b/planning/behavior_velocity_run_out_module/README.md index 5cd4b2708fd2d..77f42822a6b95 100644 --- a/planning/behavior_velocity_run_out_module/README.md +++ b/planning/behavior_velocity_run_out_module/README.md @@ -2,7 +2,7 @@ ### Role -`run_out` is the module that decelerates and stops for dynamic obstacles such as pedestrians and bicycles. +`run_out` is the module that decelerates and stops for dynamic obstacles such as pedestrians, bicycles and motorcycles. ![brief](./docs/run_out_overview.svg) @@ -179,17 +179,18 @@ You can choose whether to use this feature by parameter of `slow_down_limit.enab ### Module Parameters -| Parameter | Type | Description | -| ----------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------ | -| `detection_method` | string | [-] candidate: Object, ObjectWithoutPath, Points | -| `use_partition_lanelet` | bool | [-] whether to use partition lanelet map data | -| `specify_decel_jerk` | bool | [-] whether to specify jerk when ego decelerates | -| `stop_margin` | double | [m] the vehicle decelerates to be able to stop with this margin | -| `passing_margin` | double | [m] the vehicle begins to accelerate if the vehicle's front in predicted position is ahead of the obstacle + this margin | -| `deceleration_jerk` | double | [m/s^3] ego decelerates with this jerk when stopping for obstacles | -| `detection_distance` | double | [m] ahead distance from ego to detect the obstacles | -| `detection_span` | double | [m] calculate collision with this span to reduce calculation time | -| `min_vel_ego_kmph` | double | [km/h] min velocity to calculate time to collision | +| Parameter | Type | Description | +| ----------------------- | ---------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `detection_method` | string | [-] candidate: Object, ObjectWithoutPath, Points | +| `target_obstacle_types` | vector of string | [-] specifies which obstacle types will be considered by the module, if the obstacles classification type is not written here, it will be ignored. candidate: ["PEDESTRIAN", "BICYCLE","MOTORCYCLE"] | +| `use_partition_lanelet` | bool | [-] whether to use partition lanelet map data | +| `specify_decel_jerk` | bool | [-] whether to specify jerk when ego decelerates | +| `stop_margin` | double | [m] the vehicle decelerates to be able to stop with this margin | +| `passing_margin` | double | [m] the vehicle begins to accelerate if the vehicle's front in predicted position is ahead of the obstacle + this margin | +| `deceleration_jerk` | double | [m/s^3] ego decelerates with this jerk when stopping for obstacles | +| `detection_distance` | double | [m] ahead distance from ego to detect the obstacles | +| `detection_span` | double | [m] calculate collision with this span to reduce calculation time | +| `min_vel_ego_kmph` | double | [km/h] min velocity to calculate time to collision | | Parameter /detection_area | Type | Description | | ------------------------- | ------ | -------------------------------------------- | 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 15264e1e4e2b1..6e28b230757ba 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 @@ -2,6 +2,7 @@ ros__parameters: run_out: detection_method: "Object" # [-] candidate: Object, ObjectWithoutPath, Points + target_obstacle_types: ["PEDESTRIAN", "BICYCLE", "MOTORCYCLE"] # [-] Obstacle types considered by this module 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 diff --git a/planning/behavior_velocity_run_out_module/package.xml b/planning/behavior_velocity_run_out_module/package.xml index 606c63ea3448c..a0b15570f48f2 100644 --- a/planning/behavior_velocity_run_out_module/package.xml +++ b/planning/behavior_velocity_run_out_module/package.xml @@ -28,6 +28,7 @@ libboost-dev message_filters motion_utils + object_recognition_utils pcl_conversions pluginlib rclcpp diff --git a/planning/behavior_velocity_run_out_module/src/manager.cpp b/planning/behavior_velocity_run_out_module/src/manager.cpp index 305d74e77f348..9ee467feec758 100644 --- a/planning/behavior_velocity_run_out_module/src/manager.cpp +++ b/planning/behavior_velocity_run_out_module/src/manager.cpp @@ -18,6 +18,7 @@ #include #include +#include namespace behavior_velocity_planner { @@ -57,6 +58,8 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node) { auto & p = planner_param_.run_out; p.detection_method = getOrDeclareParameter(node, ns + ".detection_method"); + p.target_obstacle_types = + 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.suppress_on_crosswalk = getOrDeclareParameter(node, ns + ".suppress_on_crosswalk"); diff --git a/planning/behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_run_out_module/src/scene.cpp index 1dc86aa8bf87e..cd15a3fb0629f 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_run_out_module/src/scene.cpp @@ -332,21 +332,22 @@ std::vector RunOutModule::checkCollisionWithObstacles( 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 = run_out_utils::getHighestProbLabel(obstacle.classifications); - - // detect only pedestrian and bicycle - if ( - classification != ObjectClassification::PEDESTRIAN && - classification != ObjectClassification::BICYCLE) { + 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); diff --git a/planning/behavior_velocity_run_out_module/src/scene.hpp b/planning/behavior_velocity_run_out_module/src/scene.hpp index 02b17783ab6c1..090f76ef30328 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/behavior_velocity_run_out_module/src/scene.hpp @@ -17,6 +17,7 @@ #include "debug.hpp" #include "dynamic_obstacle.hpp" +#include "object_recognition_utils/object_recognition_utils.hpp" #include "state_machine.hpp" #include "utils.hpp" diff --git a/planning/behavior_velocity_run_out_module/src/utils.hpp b/planning/behavior_velocity_run_out_module/src/utils.hpp index 63576ca62329f..54aa3395a0050 100644 --- a/planning/behavior_velocity_run_out_module/src/utils.hpp +++ b/planning/behavior_velocity_run_out_module/src/utils.hpp @@ -55,6 +55,7 @@ struct CommonParam struct RunOutParam { std::string detection_method; + std::vector target_obstacle_types; bool use_partition_lanelet; bool suppress_on_crosswalk; bool specify_decel_jerk; From dd7c252366097713833fba21fafb1b21e90afc43 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Wed, 27 Mar 2024 21:39:22 +0900 Subject: [PATCH 11/56] refactor(start planner): refactor for clarity, readability and maybe performance (#6655) * refactor plane method Signed-off-by: Daniel Sanchez * delete unused method Signed-off-by: Daniel Sanchez * skip unnecessary loop Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../start_planner_module.hpp | 1 - .../src/start_planner_module.cpp | 100 +++++++----------- 2 files changed, 37 insertions(+), 64 deletions(-) diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp index a30d7c379f80c..2d661cf41855f 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp @@ -297,7 +297,6 @@ class StartPlannerModule : public SceneModuleInterface const std::vector & ego_predicted_path) const; bool isSafePath() const; void setDrivableAreaInfo(BehaviorModuleOutput & output) const; - lanelet::ConstLanelets createDepartureCheckLanes() const; // check if the goal is located behind the ego in the same route segment. bool isGoalBehindOfEgoInSameRouteSegment() const; diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index 3482618d9319c..0e6e5fae84fb8 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -508,47 +508,45 @@ BehaviorModuleOutput StartPlannerModule::plan() return output; } - PathWithLaneId path; + const auto path = std::invoke([&]() { + if (!status_.driving_forward && !status_.backward_driving_complete) { + return status_.backward_path; + } - // Check if backward motion is finished - if (status_.driving_forward || status_.backward_driving_complete) { // Increment path index if the current path is finished if (hasFinishedCurrentPath()) { RCLCPP_INFO(getLogger(), "Increment path index"); incrementPathIndex(); } - if (!status_.is_safe_dynamic_objects && !isWaitingApproval() && !status_.stop_pose) { + if (isWaitingApproval()) return getCurrentPath(); + + if (status_.stop_pose) { + // Delete stop point if conditions are met + if (status_.is_safe_dynamic_objects && isStopped()) { + status_.stop_pose = std::nullopt; + } + stop_pose_ = status_.stop_pose; + return *status_.prev_stop_path_after_approval; + } + + if (!status_.is_safe_dynamic_objects) { auto current_path = getCurrentPath(); const auto stop_path = behavior_path_planner::utils::parking_departure::generateFeasibleStopPath( current_path, planner_data_, stop_pose_, parameters_->maximum_deceleration_for_stop, parameters_->maximum_jerk_for_stop); + if (!stop_path.has_value()) return current_path; // Insert stop point in the path if needed - if (stop_path) { - RCLCPP_ERROR_THROTTLE( - getLogger(), *clock_, 5000, "Insert stop point in the path because of dynamic objects"); - path = *stop_path; - status_.prev_stop_path_after_approval = std::make_shared(path); - status_.stop_pose = stop_pose_; - } else { - path = current_path; - } - } else if (!isWaitingApproval() && status_.stop_pose) { - // Delete stop point if conditions are met - if (status_.is_safe_dynamic_objects && isStopped()) { - status_.stop_pose = std::nullopt; - path = getCurrentPath(); - } - path = *status_.prev_stop_path_after_approval; - stop_pose_ = status_.stop_pose; - } else { - path = getCurrentPath(); + RCLCPP_ERROR_THROTTLE( + getLogger(), *clock_, 5000, "Insert stop point in the path because of dynamic objects"); + status_.prev_stop_path_after_approval = std::make_shared(stop_path.value()); + status_.stop_pose = stop_pose_; + return stop_path.value(); } - } else { - path = status_.backward_path; - } + return getCurrentPath(); + }); output.path = path; output.reference_path = getPreviousModuleOutput().reference_path; @@ -768,8 +766,9 @@ bool StartPlannerModule::findPullOutPath( const Pose & refined_start_pose, const Pose & goal_pose, const double collision_check_margin) { // if start_pose_candidate is far from refined_start_pose, backward driving is necessary + constexpr double epsilon = 0.01; const bool backward_is_unnecessary = - tier4_autoware_utils::calcDistance2d(start_pose_candidate, refined_start_pose) < 0.01; + tier4_autoware_utils::calcDistance2d(start_pose_candidate, refined_start_pose) < epsilon; planner->setCollisionCheckMargin(collision_check_margin); planner->setPlannerData(planner_data_); @@ -856,26 +855,24 @@ lanelet::ConstLanelets StartPlannerModule::getPathRoadLanes(const PathWithLaneId const auto & lanelet_layer = route_handler->getLaneletMapPtr()->laneletLayer; std::vector lane_ids; + lanelet::ConstLanelets path_lanes; + for (const auto & p : path.points) { for (const auto & id : p.lane_ids) { if (id == lanelet::InvalId) { continue; } - if (route_handler->isShoulderLanelet(lanelet_layer.get(id))) { + const auto lanelet = lanelet_layer.get(id); + if (route_handler->isShoulderLanelet(lanelet)) { continue; } if (std::find(lane_ids.begin(), lane_ids.end(), id) == lane_ids.end()) { lane_ids.push_back(id); + path_lanes.push_back(lanelet); } } } - lanelet::ConstLanelets path_lanes; - path_lanes.reserve(lane_ids.size()); - for (const auto & id : lane_ids) { - path_lanes.push_back(lanelet_layer.get(id)); - } - return path_lanes; } @@ -954,11 +951,12 @@ void StartPlannerModule::updatePullOutStatus() if (hasFinishedBackwardDriving()) { updateStatusAfterBackwardDriving(); - } else { - status_.backward_path = start_planner_utils::getBackwardPath( - *route_handler, pull_out_lanes, current_pose, status_.pull_out_start_pose, - parameters_->backward_velocity); + return; } + status_.backward_path = start_planner_utils::getBackwardPath( + *route_handler, pull_out_lanes, current_pose, status_.pull_out_start_pose, + parameters_->backward_velocity); + return; } void StartPlannerModule::updateStatusAfterBackwardDriving() @@ -1047,7 +1045,7 @@ std::vector StartPlannerModule::searchPullOutStartPoseCandidates( if (distance_from_lane_end < parameters_->ignore_distance_from_lane_end) { RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, - "the ego is too close to the lane end, so needs backward driving"); + "the ego vehicle is too close to the lane end, so backwards driving is necessary"); continue; } @@ -1408,30 +1406,6 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons } } -lanelet::ConstLanelets StartPlannerModule::createDepartureCheckLanes() const -{ - const double backward_path_length = - planner_data_->parameters.backward_path_length + parameters_->max_back_distance; - const auto pull_out_lanes = - start_planner_utils::getPullOutLanes(planner_data_, backward_path_length); - if (pull_out_lanes.empty()) { - return lanelet::ConstLanelets{}; - } - const auto road_lanes = utils::getExtendedCurrentLanes( - planner_data_, backward_path_length, std::numeric_limits::max(), - /*forward_only_in_route*/ true); - // extract shoulder lanes from pull out lanes - lanelet::ConstLanelets shoulder_lanes; - std::copy_if( - pull_out_lanes.begin(), pull_out_lanes.end(), std::back_inserter(shoulder_lanes), - [this](const auto & pull_out_lane) { - return planner_data_->route_handler->isShoulderLanelet(pull_out_lane); - }); - const auto departure_check_lanes = utils::transformToLanelets( - utils::generateDrivableLanesWithShoulderLanes(road_lanes, shoulder_lanes)); - return departure_check_lanes; -} - void StartPlannerModule::setDebugData() { using lanelet::visualization::laneletsAsTriangleMarkerArray; From fe5e63ff79a845833bf6e2769c2da6a0fcbe7284 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 28 Mar 2024 14:40:59 +0900 Subject: [PATCH 12/56] fix(goal_planner): stop path candidates update after arriving modified goal (#6695) Signed-off-by: kosuke55 --- .../src/goal_planner_module.cpp | 3 +++ 1 file changed, 3 insertions(+) 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 2ba217ccccaff..7310e93dda4bb 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 @@ -190,6 +190,9 @@ void GoalPlannerModule::onTimer() // check if new pull over path candidates are needed to be generated const bool need_update = std::invoke([&]() { + if (isOnModifiedGoal()) { + return false; + } if (hasDeviatedFromCurrentPreviousModulePath()) { RCLCPP_DEBUG(getLogger(), "has deviated from current previous module path"); return false; From 1ed64629913a7e2883097d437e77bff467766609 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 28 Mar 2024 15:45:06 +0900 Subject: [PATCH 13/56] perf(static_centerline_optimizer): cleanup the package dependencies (#6697) Signed-off-by: Maxime CLEMENT --- planning/static_centerline_optimizer/CMakeLists.txt | 12 ------------ planning/static_centerline_optimizer/package.xml | 5 +++-- 2 files changed, 3 insertions(+), 14 deletions(-) diff --git a/planning/static_centerline_optimizer/CMakeLists.txt b/planning/static_centerline_optimizer/CMakeLists.txt index a2091dffd061a..829c06c1fba12 100644 --- a/planning/static_centerline_optimizer/CMakeLists.txt +++ b/planning/static_centerline_optimizer/CMakeLists.txt @@ -7,8 +7,6 @@ find_package(builtin_interfaces REQUIRED) find_package(geometry_msgs REQUIRED) find_package(rosidl_default_generators REQUIRED) find_package(std_msgs REQUIRED) -find_package(Eigen3 REQUIRED) -find_package(OpenCV REQUIRED) rosidl_generate_interfaces( static_centerline_optimizer @@ -27,16 +25,6 @@ ament_auto_add_executable(main src/utils.cpp ) -target_include_directories(main - SYSTEM PUBLIC - ${OpenCV_INCLUDE_DIRS} - ${EIGEN3_INCLUDE_DIR} -) - -target_link_libraries(main - ${OpenCV_LIBRARIES} -) - if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0) rosidl_target_interfaces(main static_centerline_optimizer "rosidl_typesupport_cpp") diff --git a/planning/static_centerline_optimizer/package.xml b/planning/static_centerline_optimizer/package.xml index 17191868b7418..363c88bebf0ea 100644 --- a/planning/static_centerline_optimizer/package.xml +++ b/planning/static_centerline_optimizer/package.xml @@ -18,8 +18,7 @@ autoware_auto_mapping_msgs autoware_auto_perception_msgs autoware_auto_planning_msgs - behavior_path_planner - behavior_velocity_planner + behavior_path_planner_common geometry_msgs global_parameter_loader interpolation @@ -43,6 +42,8 @@ ament_cmake_gmock ament_lint_auto autoware_lint_common + behavior_path_planner + behavior_velocity_planner ros_testing rosidl_interface_packages From 6d7cd0aad6763ef64bae9ea97e268c102ccbe419 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim <36835765+ahmeddesokyebrahim@users.noreply.github.com> Date: Thu, 28 Mar 2024 10:48:59 +0200 Subject: [PATCH 14/56] fix(freespace_planner): fix parking trajectory errors and warnings when parking completed (#6696) fix(freespace_planner): publish stop trajectory when completed to mitigate topic timeout Signed-off-by: AhmedEbrahim --- .../src/freespace_planner/freespace_planner_node.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp b/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp index c4ba1424cf45e..bd8045e653a16 100644 --- a/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp +++ b/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp @@ -430,6 +430,9 @@ void FreespacePlannerNode::onTimer() } if (is_completed_) { + partial_trajectory_.header = odom_->header; + const auto stop_trajectory = createStopTrajectory(partial_trajectory_); + trajectory_pub_->publish(stop_trajectory); return; } From c2f57ae48619acfe82059b87a3bba29b737dca03 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Fri, 29 Mar 2024 09:34:24 +0900 Subject: [PATCH 15/56] chore(tier4_system_launch): add option to select graph path depending on running mode (#6700) chore(tier4_system_launch): add option of using graph path for simulation Signed-off-by: Tomohito Ando --- launch/tier4_system_launch/launch/system.launch.xml | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/launch/tier4_system_launch/launch/system.launch.xml b/launch/tier4_system_launch/launch/system.launch.xml index ea2b47b91d62a..a1bbfc883de7c 100644 --- a/launch/tier4_system_launch/launch/system.launch.xml +++ b/launch/tier4_system_launch/launch/system.launch.xml @@ -29,6 +29,7 @@ + @@ -117,9 +118,12 @@ + + + - + From 61beca1ae47a9598c690e4909dd5b1faee9f9a3b Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 29 Mar 2024 15:14:16 +0900 Subject: [PATCH 16/56] fix(dynamic_obstacle_stop,out_of_lane,crosswalk): update velocity factor (#6711) Signed-off-by: Maxime CLEMENT --- .../src/scene_crosswalk.cpp | 2 +- .../src/scene_dynamic_obstacle_stop.cpp | 9 +++++++-- .../src/scene_out_of_lane.cpp | 9 ++++++--- 3 files changed, 14 insertions(+), 6 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 1c4813cd42f39..e4b9f346f4f6d 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -879,7 +879,7 @@ void CrosswalkModule::applySafetySlowDownSpeed( if (slowdown_pose) velocity_factor_.set( output.points, planner_data_->current_odometry->pose, *slowdown_pose, - VelocityFactor::CROSSWALK); + VelocityFactor::APPROACHING); } Polygon2d CrosswalkModule::getAttentionArea( diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp index 0b160213665a5..115acd7933da1 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp @@ -47,7 +47,7 @@ DynamicObstacleStopModule::DynamicObstacleStopModule( prev_stop_decision_time_ = clock->now() - rclcpp::Duration(std::chrono::duration(params_.decision_duration_buffer)); - velocity_factor_.init(PlanningBehavior::UNKNOWN); + velocity_factor_.init(PlanningBehavior::ROUTE_OBSTACLE); } bool DynamicObstacleStopModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) @@ -118,8 +118,13 @@ bool DynamicObstacleStopModule::modifyPathVelocity(PathWithLaneId * path, StopRe if (current_stop_pose_) { motion_utils::insertStopPoint(*current_stop_pose_, 0.0, path->points); + const auto stop_pose_reached = + planner_data_->current_velocity->twist.linear.x < 1e-3 && + tier4_autoware_utils::calcDistance2d(ego_data.pose, *current_stop_pose_) < 1e-3; velocity_factor_.set( - path->points, ego_data.pose, *current_stop_pose_, VelocityFactor::ROUTE_OBSTACLE); + path->points, ego_data.pose, *current_stop_pose_, + stop_pose_reached ? VelocityFactor::STOPPED : VelocityFactor::APPROACHING, + "dynamic_obstacle_stop"); } const auto total_time_us = stopwatch.toc(); diff --git a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp index fa7e2aa2099d5..067a5e3dc7698 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp @@ -166,16 +166,19 @@ bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto 1; planning_utils::insertVelocity( *path, point_to_insert->point, point_to_insert->slowdown.velocity, path_idx); + auto stop_pose_reached = false; if (point_to_insert->slowdown.velocity == 0.0) { + const auto dist_to_stop_pose = motion_utils::calcSignedArcLength( + path->points, ego_data.pose.position, point_to_insert->point.point.pose.position); + if (ego_data.velocity < 1e-3 && dist_to_stop_pose < 1e-3) stop_pose_reached = true; tier4_planning_msgs::msg::StopFactor stop_factor; stop_factor.stop_pose = point_to_insert->point.point.pose; - stop_factor.dist_to_stop_pose = motion_utils::calcSignedArcLength( - path->points, ego_data.pose.position, point_to_insert->point.point.pose.position); + stop_factor.dist_to_stop_pose = dist_to_stop_pose; planning_utils::appendStopReason(stop_factor, stop_reason); } velocity_factor_.set( path->points, planner_data_->current_odometry->pose, point_to_insert->point.point.pose, - VelocityFactor::ROUTE_OBSTACLE); + stop_pose_reached ? VelocityFactor::STOPPED : VelocityFactor::APPROACHING, "out_of_lane"); } else if (!decisions.empty()) { RCLCPP_WARN(logger_, "Could not insert stop point (would violate max deceleration limits)"); } From 37cd3f8c75fac954bfb4f427850b8fe3fa8a10e1 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Fri, 29 Mar 2024 15:21:23 +0900 Subject: [PATCH 17/56] chore(blockage_diag): add dust diagnostic option param (#6645) * fix: add dust diag option param Signed-off-by: badai-nguyen * fix: add debug image publish option param Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen --- .../blockage_diagnostics_param_file.yaml | 2 + .../blockage_diag/blockage_diag_nodelet.hpp | 2 + .../blockage_diag/blockage_diag_nodelet.cpp | 224 ++++++++++-------- 3 files changed, 124 insertions(+), 104 deletions(-) diff --git a/sensing/pointcloud_preprocessor/config/blockage_diagnostics_param_file.yaml b/sensing/pointcloud_preprocessor/config/blockage_diagnostics_param_file.yaml index c932e7f62d5bc..13ddd8a7c7590 100644 --- a/sensing/pointcloud_preprocessor/config/blockage_diagnostics_param_file.yaml +++ b/sensing/pointcloud_preprocessor/config/blockage_diagnostics_param_file.yaml @@ -4,6 +4,8 @@ blockage_count_threshold: 50 blockage_buffering_frames: 2 blockage_buffering_interval: 1 + enable_dust_diag: false + publish_debug_image: false dust_ratio_threshold: 0.2 dust_count_threshold: 10 dust_kernel_size: 2 diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/blockage_diag/blockage_diag_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/blockage_diag/blockage_diag_nodelet.hpp index c1cf1e59f0343..dd24c83761878 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/blockage_diag/blockage_diag_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/blockage_diag/blockage_diag_nodelet.hpp @@ -85,6 +85,8 @@ class BlockageDiagComponent : public pointcloud_preprocessor::Filter bool is_channel_order_top2down_; int blockage_buffering_frames_; int blockage_buffering_interval_; + bool enable_dust_diag_; + bool publish_debug_image_; int dust_kernel_size_; int dust_buffering_frames_; int dust_buffering_interval_; diff --git a/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp b/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp index 17085ec0a3120..773e6db056990 100644 --- a/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp @@ -37,6 +37,8 @@ BlockageDiagComponent::BlockageDiagComponent(const rclcpp::NodeOptions & options blockage_count_threshold_ = declare_parameter("blockage_count_threshold"); blockage_buffering_frames_ = declare_parameter("blockage_buffering_frames"); blockage_buffering_interval_ = declare_parameter("blockage_buffering_interval"); + publish_debug_image_ = declare_parameter("publish_debug_image"); + enable_dust_diag_ = declare_parameter("enable_dust_diag"); dust_ratio_threshold_ = declare_parameter("dust_ratio_threshold"); dust_count_threshold_ = declare_parameter("dust_count_threshold"); dust_kernel_size_ = declare_parameter("dust_kernel_size"); @@ -59,26 +61,33 @@ BlockageDiagComponent::BlockageDiagComponent(const rclcpp::NodeOptions & options updater_.add( std::string(this->get_namespace()) + ": blockage_validation", this, &BlockageDiagComponent::onBlockageChecker); - updater_.add( - std::string(this->get_namespace()) + ": dust_validation", this, - &BlockageDiagComponent::dustChecker); + if (enable_dust_diag_) { + updater_.add( + std::string(this->get_namespace()) + ": dust_validation", this, + &BlockageDiagComponent::dustChecker); + + ground_dust_ratio_pub_ = create_publisher( + "blockage_diag/debug/ground_dust_ratio", rclcpp::SensorDataQoS()); + if (publish_debug_image_) { + single_frame_dust_mask_pub = + image_transport::create_publisher(this, "blockage_diag/debug/single_frame_dust_mask_image"); + multi_frame_dust_mask_pub = + image_transport::create_publisher(this, "blockage_diag/debug/multi_frame_dust_mask_image"); + blockage_dust_merged_pub = + image_transport::create_publisher(this, "blockage_diag/debug/blockage_dust_merged_image"); + } + } updater_.setPeriod(0.1); - single_frame_dust_mask_pub = - image_transport::create_publisher(this, "blockage_diag/debug/single_frame_dust_mask_image"); - multi_frame_dust_mask_pub = - image_transport::create_publisher(this, "blockage_diag/debug/multi_frame_dust_mask_image"); - lidar_depth_map_pub_ = - image_transport::create_publisher(this, "blockage_diag/debug/lidar_depth_map"); - blockage_mask_pub_ = - image_transport::create_publisher(this, "blockage_diag/debug/blockage_mask_image"); - blockage_dust_merged_pub = - image_transport::create_publisher(this, "blockage_diag/debug/blockage_dust_merged_image"); + if (publish_debug_image_) { + lidar_depth_map_pub_ = + image_transport::create_publisher(this, "blockage_diag/debug/lidar_depth_map"); + blockage_mask_pub_ = + image_transport::create_publisher(this, "blockage_diag/debug/blockage_mask_image"); + } ground_blockage_ratio_pub_ = create_publisher( "blockage_diag/debug/ground_blockage_ratio", rclcpp::SensorDataQoS()); sky_blockage_ratio_pub_ = create_publisher( "blockage_diag/debug/sky_blockage_ratio", rclcpp::SensorDataQoS()); - ground_dust_ratio_pub_ = create_publisher( - "blockage_diag/debug/ground_dust_ratio", rclcpp::SensorDataQoS()); using std::placeholders::_1; set_param_res_ = this->add_on_set_parameters_callback( std::bind(&BlockageDiagComponent::paramCallback, this, _1)); @@ -283,93 +292,95 @@ void BlockageDiagComponent::filter( sky_blockage_count_ = 0; } // dust - cv::Mat ground_depth_map = lidar_depth_map_8u( - cv::Rect(0, horizontal_ring_id_, ideal_horizontal_bins, vertical_bins - horizontal_ring_id_)); - cv::Mat sky_blank(horizontal_ring_id_, ideal_horizontal_bins, CV_8UC1, cv::Scalar(0)); - cv::Mat ground_blank( - vertical_bins - horizontal_ring_id_, ideal_horizontal_bins, CV_8UC1, cv::Scalar(0)); - cv::Mat single_dust_img( - cv::Size(lidar_depth_map_8u.rows, lidar_depth_map_8u.cols), CV_8UC1, cv::Scalar(0)); - cv::Mat single_dust_ground_img = ground_depth_map.clone(); - cv::inRange(single_dust_ground_img, 0, 1, single_dust_ground_img); - cv::Mat dust_element = getStructuringElement( - cv::MORPH_RECT, cv::Size(2 * dust_kernel_size_ + 1, 2 * dust_kernel_size_ + 1), - cv::Point(-1, -1)); - cv::dilate(single_dust_ground_img, single_dust_ground_img, dust_element); - cv::erode(single_dust_ground_img, single_dust_ground_img, dust_element); - cv::inRange(single_dust_ground_img, 254, 255, single_dust_ground_img); - cv::Mat ground_mask(cv::Size(ideal_horizontal_bins, horizontal_ring_id_), CV_8UC1); - cv::vconcat(sky_blank, single_dust_ground_img, single_dust_img); - cv::Mat binarized_dust_mask_( - cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0)); - cv::Mat multi_frame_dust_mask( - cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0)); - cv::Mat multi_frame_ground_dust_result( - cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0)); + if (enable_dust_diag_) { + cv::Mat ground_depth_map = lidar_depth_map_8u( + cv::Rect(0, horizontal_ring_id_, ideal_horizontal_bins, vertical_bins - horizontal_ring_id_)); + cv::Mat sky_blank(horizontal_ring_id_, ideal_horizontal_bins, CV_8UC1, cv::Scalar(0)); + cv::Mat ground_blank( + vertical_bins - horizontal_ring_id_, ideal_horizontal_bins, CV_8UC1, cv::Scalar(0)); + cv::Mat single_dust_img( + cv::Size(lidar_depth_map_8u.rows, lidar_depth_map_8u.cols), CV_8UC1, cv::Scalar(0)); + cv::Mat single_dust_ground_img = ground_depth_map.clone(); + cv::inRange(single_dust_ground_img, 0, 1, single_dust_ground_img); + cv::Mat dust_element = getStructuringElement( + cv::MORPH_RECT, cv::Size(2 * dust_kernel_size_ + 1, 2 * dust_kernel_size_ + 1), + cv::Point(-1, -1)); + cv::dilate(single_dust_ground_img, single_dust_ground_img, dust_element); + cv::erode(single_dust_ground_img, single_dust_ground_img, dust_element); + cv::inRange(single_dust_ground_img, 254, 255, single_dust_ground_img); + cv::Mat ground_mask(cv::Size(ideal_horizontal_bins, horizontal_ring_id_), CV_8UC1); + cv::vconcat(sky_blank, single_dust_ground_img, single_dust_img); - if (dust_buffering_interval_ == 0) { - single_dust_img.copyTo(multi_frame_ground_dust_result); - dust_buffering_frame_counter_ = 0; - } else { - binarized_dust_mask_ = single_dust_img / 255; - if (dust_buffering_frame_counter_ >= dust_buffering_interval_) { - dust_mask_buffer.push_back(binarized_dust_mask_); - dust_buffering_frame_counter_ = 0; + tier4_debug_msgs::msg::Float32Stamped ground_dust_ratio_msg; + ground_dust_ratio_ = static_cast(cv::countNonZero(single_dust_ground_img)) / + (single_dust_ground_img.cols * single_dust_ground_img.rows); + ground_dust_ratio_msg.data = ground_dust_ratio_; + ground_dust_ratio_msg.stamp = now(); + ground_dust_ratio_pub_->publish(ground_dust_ratio_msg); + if (ground_dust_ratio_ > dust_ratio_threshold_) { + if (dust_frame_count_ < 2 * dust_count_threshold_) { + dust_frame_count_++; + } } else { - dust_buffering_frame_counter_++; - } - for (const auto & binarized_dust_mask : dust_mask_buffer) { - multi_frame_dust_mask += binarized_dust_mask; + dust_frame_count_ = 0; } - cv::inRange( - multi_frame_dust_mask, dust_mask_buffer.size() - 1, dust_mask_buffer.size(), - multi_frame_ground_dust_result); - } - cv::Mat single_frame_ground_dust_colorized( - cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC3, cv::Scalar(0, 0, 0)); - cv::applyColorMap(single_dust_img, single_frame_ground_dust_colorized, cv::COLORMAP_JET); - cv::Mat multi_frame_ground_dust_colorized; - cv::Mat blockage_dust_merged_img( - cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC3, cv::Scalar(0, 0, 0)); - cv::Mat blockage_dust_merged_mask( - cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0)); - blockage_dust_merged_img.setTo( - cv::Vec3b(0, 0, 255), time_series_blockage_result); // red:blockage - blockage_dust_merged_img.setTo( - cv::Vec3b(0, 255, 255), multi_frame_ground_dust_result); // yellow:dust - sensor_msgs::msg::Image::SharedPtr single_frame_dust_mask_msg = - cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", single_frame_ground_dust_colorized) - .toImageMsg(); - single_frame_dust_mask_pub.publish(single_frame_dust_mask_msg); - sensor_msgs::msg::Image::SharedPtr multi_frame_dust_mask_msg = - cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", multi_frame_ground_dust_colorized) - .toImageMsg(); - multi_frame_dust_mask_pub.publish(multi_frame_dust_mask_msg); - sensor_msgs::msg::Image::SharedPtr lidar_depth_map_msg = - cv_bridge::CvImage(std_msgs::msg::Header(), "mono16", full_size_depth_map).toImageMsg(); - lidar_depth_map_msg->header = input->header; - lidar_depth_map_pub_.publish(lidar_depth_map_msg); - cv::Mat blockage_mask_colorized; - cv::applyColorMap(time_series_blockage_result, blockage_mask_colorized, cv::COLORMAP_JET); - sensor_msgs::msg::Image::SharedPtr blockage_mask_msg = - cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", blockage_mask_colorized).toImageMsg(); - blockage_mask_msg->header = input->header; - blockage_mask_pub_.publish(blockage_mask_msg); - cv::Mat blockage_dust_merged_colorized( - cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC3, cv::Scalar(0, 0, 0)); - blockage_dust_merged_img.copyTo(blockage_dust_merged_colorized); - sensor_msgs::msg::Image::SharedPtr blockage_dust_merged_msg = - cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", blockage_dust_merged_colorized) - .toImageMsg(); - if (ground_dust_ratio_ > dust_ratio_threshold_) { - if (dust_frame_count_ < 2 * dust_count_threshold_) { - dust_frame_count_++; + + if (publish_debug_image_) { + cv::Mat binarized_dust_mask_( + cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0)); + cv::Mat multi_frame_dust_mask( + cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0)); + cv::Mat multi_frame_ground_dust_result( + cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0)); + + if (dust_buffering_interval_ == 0) { + single_dust_img.copyTo(multi_frame_ground_dust_result); + dust_buffering_frame_counter_ = 0; + } else { + binarized_dust_mask_ = single_dust_img / 255; + if (dust_buffering_frame_counter_ >= dust_buffering_interval_) { + dust_mask_buffer.push_back(binarized_dust_mask_); + dust_buffering_frame_counter_ = 0; + } else { + dust_buffering_frame_counter_++; + } + for (const auto & binarized_dust_mask : dust_mask_buffer) { + multi_frame_dust_mask += binarized_dust_mask; + } + cv::inRange( + multi_frame_dust_mask, dust_mask_buffer.size() - 1, dust_mask_buffer.size(), + multi_frame_ground_dust_result); + } + cv::Mat single_frame_ground_dust_colorized( + cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC3, cv::Scalar(0, 0, 0)); + cv::applyColorMap(single_dust_img, single_frame_ground_dust_colorized, cv::COLORMAP_JET); + cv::Mat multi_frame_ground_dust_colorized; + cv::Mat blockage_dust_merged_img( + cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC3, cv::Scalar(0, 0, 0)); + cv::Mat blockage_dust_merged_mask( + cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0)); + blockage_dust_merged_img.setTo( + cv::Vec3b(0, 0, 255), time_series_blockage_result); // red:blockage + blockage_dust_merged_img.setTo( + cv::Vec3b(0, 255, 255), multi_frame_ground_dust_result); // yellow:dust + sensor_msgs::msg::Image::SharedPtr single_frame_dust_mask_msg = + cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", single_frame_ground_dust_colorized) + .toImageMsg(); + single_frame_dust_mask_pub.publish(single_frame_dust_mask_msg); + sensor_msgs::msg::Image::SharedPtr multi_frame_dust_mask_msg = + cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", multi_frame_ground_dust_colorized) + .toImageMsg(); + multi_frame_dust_mask_pub.publish(multi_frame_dust_mask_msg); + cv::Mat blockage_dust_merged_colorized( + cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC3, cv::Scalar(0, 0, 0)); + blockage_dust_merged_img.copyTo(blockage_dust_merged_colorized); + sensor_msgs::msg::Image::SharedPtr blockage_dust_merged_msg = + cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", blockage_dust_merged_colorized) + .toImageMsg(); + blockage_dust_merged_msg->header = input->header; + blockage_dust_merged_pub.publish(blockage_dust_merged_msg); } - } else { - dust_frame_count_ = 0; } - blockage_dust_merged_msg->header = input->header; - blockage_dust_merged_pub.publish(blockage_dust_merged_msg); tier4_debug_msgs::msg::Float32Stamped ground_blockage_ratio_msg; ground_blockage_ratio_msg.data = ground_blockage_ratio_; @@ -380,14 +391,19 @@ void BlockageDiagComponent::filter( sky_blockage_ratio_msg.data = sky_blockage_ratio_; sky_blockage_ratio_msg.stamp = now(); sky_blockage_ratio_pub_->publish(sky_blockage_ratio_msg); - tier4_debug_msgs::msg::Float32Stamped blockage_ratio_msg; - tier4_debug_msgs::msg::Float32Stamped ground_dust_ratio_msg; + if (publish_debug_image_) { + sensor_msgs::msg::Image::SharedPtr lidar_depth_map_msg = + cv_bridge::CvImage(std_msgs::msg::Header(), "mono16", full_size_depth_map).toImageMsg(); + lidar_depth_map_msg->header = input->header; + lidar_depth_map_pub_.publish(lidar_depth_map_msg); + cv::Mat blockage_mask_colorized; + cv::applyColorMap(time_series_blockage_result, blockage_mask_colorized, cv::COLORMAP_JET); + sensor_msgs::msg::Image::SharedPtr blockage_mask_msg = + cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", blockage_mask_colorized).toImageMsg(); + blockage_mask_msg->header = input->header; + blockage_mask_pub_.publish(blockage_mask_msg); + } - ground_dust_ratio_ = static_cast(cv::countNonZero(single_dust_ground_img)) / - (single_dust_ground_img.cols * single_dust_ground_img.rows); - ground_dust_ratio_msg.data = ground_dust_ratio_; - ground_dust_ratio_msg.stamp = now(); - ground_dust_ratio_pub_->publish(ground_dust_ratio_msg); pcl::toROSMsg(*pcl_input, output); output.header = input->header; } From dd2ff22d450e96b964ac31f6c92d143de7054f27 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 29 Mar 2024 16:46:32 +0900 Subject: [PATCH 18/56] feat(dynamic_obstacle_stop): use a time buffer for each dynamic objects (#6683) Signed-off-by: Maxime CLEMENT --- .../README.md | 14 ++- .../config/dynamic_obstacle_stop.param.yaml | 3 +- .../src/collision.cpp | 84 +++++++------ .../src/collision.hpp | 19 ++- .../src/debug.cpp | 46 +++++-- .../src/debug.hpp | 15 ++- .../src/manager.cpp | 5 +- .../src/object_stop_decision.cpp | 69 +++++++++++ .../src/object_stop_decision.hpp | 76 ++++++++++++ .../src/scene_dynamic_obstacle_stop.cpp | 115 +++++++----------- .../src/scene_dynamic_obstacle_stop.hpp | 6 +- .../src/types.hpp | 21 ++-- 12 files changed, 326 insertions(+), 147 deletions(-) create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp create mode 100644 planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.hpp diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/README.md b/planning/behavior_velocity_dynamic_obstacle_stop_module/README.md index 5683295332dc2..ee44ac08afe96 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/README.md +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/README.md @@ -27,8 +27,6 @@ In addition to these 4 steps, 2 mechanisms are in place to make the stop point o The `hysteresis` parameter is used when a stop point was already being inserted in the previous iteration and it increases the range where dynamic objects are considered close enough to the ego path to be used by the module. -The `decision_duration_buffer` parameter defines the duration when the module will keep inserted the previous stop point, even after no collisions were found. - #### Filter dynamic objects ![filtering example](docs/DynamicObstacleStop-Filtering.drawio.svg) @@ -75,6 +73,15 @@ If a stop point was inserted in the previous iteration of the module, its arc le Finally, the stop point arc length is calculated to be the arc length of the previously found collision point minus the `stop_distance_buffer` and the ego vehicle longitudinal offset, clamped between the minimum and maximum values. +#### Duration buffer + +To prevent chatter caused by noisy perception, two duration parameters are used. + +- `add_stop_duration_buffer` represents the duration of consecutive collision detection with an object for the corresponding stop point to be added. +- `remove_stop_duration_buffer` represents the duration of consecutive non-detection of collision with an object for the corresponding stop point to be removed. + +Timers and collision points are tracked for each dynamic object independently. + ### Module Parameters | Parameter | Type | Description | @@ -84,6 +91,7 @@ the stop point arc length is calculated to be the arc length of the previously f | `stop_distance_buffer` | double | [m] extra distance to add between the stop point and the collision point | | `time_horizon` | double | [s] time horizon used for collision checks | | `hysteresis` | double | [m] once a collision has been detected, this hysteresis is used on the collision detection | -| `decision_duration_buffer` | double | [s] duration between no collision being detected and the stop decision being cancelled | +| `add_stop_duration_buffer` | double | [s] duration where a collision must be continuously detected before a stop decision is added | +| `remove_stop_duration_buffer` | double | [s] duration between no collision being detected and the stop decision being remove | | `minimum_object_distance_from_ego_path` | double | [m] minimum distance between the footprints of ego and an object to consider for collision | | `ignore_unavoidable_collisions` | bool | [-] if true, ignore collisions that cannot be avoided by stopping (assuming the obstacle continues going straight) | diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/config/dynamic_obstacle_stop.param.yaml b/planning/behavior_velocity_dynamic_obstacle_stop_module/config/dynamic_obstacle_stop.param.yaml index c18de5bd53f01..ac95cd75c8571 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/config/dynamic_obstacle_stop.param.yaml +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/config/dynamic_obstacle_stop.param.yaml @@ -6,6 +6,7 @@ stop_distance_buffer: 0.5 # [m] extra distance to add between the stop point and the collision point time_horizon: 5.0 # [s] time horizon used for collision checks hysteresis: 1.0 # [m] once a collision has been detected, this hysteresis is used on the collision detection - decision_duration_buffer : 1.0 # [s] duration between no collision being detected and the stop decision being cancelled + add_stop_duration_buffer : 0.5 # [s] duration where a collision must be continuously detected before a stop decision is added + remove_stop_duration_buffer : 1.0 # [s] duration between no collision being detected and the stop decision being remove minimum_object_distance_from_ego_path: 1.0 # [m] minimum distance between the footprints of ego and an object to consider for collision ignore_unavoidable_collisions : true # if true, ignore collisions that cannot be avoided by stopping (assuming the obstacle continues going straight) diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp index 46c58d6be8805..d57789d574ad9 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 TIER IV, Inc. +// Copyright 2023-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. @@ -16,56 +16,68 @@ #include #include +#include #include +#include #include #include namespace behavior_velocity_planner::dynamic_obstacle_stop { -std::optional find_earliest_collision( - const EgoData & ego_data, - const std::vector & objects, - const tier4_autoware_utils::MultiPolygon2d & obstacle_forward_footprints, DebugData & debug_data) +std::optional find_closest_collision_point( + const EgoData & ego_data, const geometry_msgs::msg::Pose & object_pose, + const tier4_autoware_utils::Polygon2d & object_footprint) { - auto earliest_idx = ego_data.path_footprints.size(); - auto earliest_arc_length = motion_utils::calcArcLength(ego_data.path.points); - std::optional earliest_collision_point; - debug_data.collisions.clear(); + std::optional closest_collision_point; + auto closest_dist = std::numeric_limits::max(); std::vector rough_collisions; - for (auto obstacle_idx = 0UL; obstacle_idx < objects.size(); ++obstacle_idx) { - rough_collisions.clear(); - const auto & obstacle_pose = objects[obstacle_idx].kinematics.initial_pose_with_covariance.pose; - const auto & obstacle_footprint = obstacle_forward_footprints[obstacle_idx]; - ego_data.rtree.query( - boost::geometry::index::intersects(obstacle_footprint), std::back_inserter(rough_collisions)); - for (const auto & rough_collision : rough_collisions) { - const auto path_idx = rough_collision.second; - const auto & ego_footprint = ego_data.path_footprints[path_idx]; - const auto & ego_pose = ego_data.path.points[ego_data.first_path_idx + path_idx].point.pose; - const auto angle_diff = tier4_autoware_utils::normalizeRadian( - tf2::getYaw(ego_pose.orientation) - tf2::getYaw(obstacle_pose.orientation)); - if (path_idx <= earliest_idx && std::abs(angle_diff) > (M_PI_2 + M_PI_4)) { - tier4_autoware_utils::MultiPoint2d collision_points; - boost::geometry::intersection( - obstacle_footprint.outer(), ego_footprint.outer(), collision_points); - earliest_idx = path_idx; - for (const auto & coll_p : collision_points) { - auto p = geometry_msgs::msg::Point().set__x(coll_p.x()).set__y(coll_p.y()); - const auto arc_length = - motion_utils::calcSignedArcLength(ego_data.path.points, ego_data.first_path_idx, p); - if (arc_length < earliest_arc_length) { - earliest_arc_length = arc_length; - debug_data.collisions = {obstacle_footprint, ego_footprint}; - earliest_collision_point = p; - } + ego_data.rtree.query( + boost::geometry::index::intersects(object_footprint), std::back_inserter(rough_collisions)); + for (const auto & rough_collision : rough_collisions) { + const auto path_idx = rough_collision.second; + const auto & ego_footprint = ego_data.path_footprints[path_idx]; + const auto & ego_pose = ego_data.path.points[path_idx].point.pose; + const auto angle_diff = tier4_autoware_utils::normalizeRadian( + tf2::getYaw(ego_pose.orientation) - tf2::getYaw(object_pose.orientation)); + if (std::abs(angle_diff) > (M_PI_2 + M_PI_4)) { // TODO(Maxime): make this angle a parameter + tier4_autoware_utils::MultiPoint2d collision_points; + boost::geometry::intersection( + object_footprint.outer(), ego_footprint.outer(), collision_points); + for (const auto & coll_p : collision_points) { + auto p = geometry_msgs::msg::Point().set__x(coll_p.x()).set__y(coll_p.y()); + const auto dist_to_ego = + motion_utils::calcSignedArcLength(ego_data.path.points, ego_data.pose.position, p); + if (dist_to_ego < closest_dist) { + closest_dist = dist_to_ego; + closest_collision_point = p; } } } } - return earliest_collision_point; + return closest_collision_point; +} + +std::vector find_collisions( + const EgoData & ego_data, + const std::vector & objects, + const tier4_autoware_utils::MultiPolygon2d & object_forward_footprints) +{ + std::vector collisions; + for (auto object_idx = 0UL; object_idx < objects.size(); ++object_idx) { + const auto & object_pose = objects[object_idx].kinematics.initial_pose_with_covariance.pose; + const auto & object_footprint = object_forward_footprints[object_idx]; + const auto collision = find_closest_collision_point(ego_data, object_pose, object_footprint); + if (collision) { + Collision c; + c.object_uuid = tier4_autoware_utils::toHexString(objects[object_idx].object_id); + c.point = *collision; + collisions.push_back(c); + } + } + return collisions; } } // namespace behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp index ccc3fa94df603..b65baaeb46aa3 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 TIER IV, Inc. +// Copyright 2023-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. @@ -22,17 +22,24 @@ namespace behavior_velocity_planner::dynamic_obstacle_stop { +/// @brief find the collision point closest to ego along an object footprint +/// @param [in] ego_data ego data including its path and footprints used for finding a collision +/// @param [in] object_pose pose of the dynamic object +/// @param [in] object_footprint footprint of the object used for finding a collision +/// @return the collision point closest to ego (if any) +std::optional find_closest_collision_point( + const EgoData & ego_data, const geometry_msgs::msg::Pose & object_pose, + const tier4_autoware_utils::Polygon2d & object_footprint); -/// @brief find the earliest collision along the ego path and an obstacle footprint +/// @brief find the earliest collision along the ego path /// @param [in] ego_data ego data including its path and footprint /// @param [in] objects obstacles -/// @param [in] obstacle_forward_footprints obstacle footprints -/// @param [in] debug_data debug data +/// @param [in] obstacle_forward_footprints obstacle footprints to check for collisions /// @return the point of earliest collision along the ego path -std::optional find_earliest_collision( +std::vector find_collisions( const EgoData & ego_data, const std::vector & objects, - const tier4_autoware_utils::MultiPolygon2d & obstacle_forward_footprints, DebugData & debug_data); + const tier4_autoware_utils::MultiPolygon2d & obstacle_forward_footprints); } // namespace behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp index cc5dafa218654..367a1c2be1d5a 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 TIER IV, Inc. +// Copyright 2023-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. @@ -14,6 +14,8 @@ #include "debug.hpp" +#include "types.hpp" + #include #include @@ -36,22 +38,46 @@ std::vector make_delete_markers( return markers; } -std::vector make_dynamic_obstacle_markers( - const std::vector & obstacles) +void add_markers( + visualization_msgs::msg::MarkerArray & array, size_t & prev_nb, + const std::vector & markers, const std::string & ns) +{ + array.markers.insert(array.markers.end(), markers.begin(), markers.end()); + const auto delete_markers = debug::make_delete_markers(markers.size(), prev_nb, ns); + array.markers.insert(array.markers.end(), delete_markers.begin(), delete_markers.end()); + prev_nb = markers.size(); +} + +std::vector make_collision_markers( + const ObjectStopDecisionMap & object_map, const std::string & ns, const double z, + const rclcpp::Time & now) { std::vector markers; visualization_msgs::msg::Marker marker; marker.header.frame_id = "map"; marker.header.stamp = rclcpp::Time(0); - marker.ns = "dynamic_obstacles"; + marker.ns = ns; marker.id = 0; - marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; marker.action = visualization_msgs::msg::Marker::ADD; - marker.scale = tier4_autoware_utils::createMarkerScale(1.0, 1.0, 1.0); - marker.color = tier4_autoware_utils::createMarkerColor(1.0, 0.1, 0.1, 1.0); - marker.text = "dynamic obstacle"; - for (const auto & obstacle : obstacles) { - marker.pose = obstacle.kinematics.initial_pose_with_covariance.pose; + marker.scale = tier4_autoware_utils::createMarkerScale(0.2, 0.2, 0.5); + marker.color = tier4_autoware_utils::createMarkerColor(0.6, 0.0, 0.6, 1.0); + for (const auto & [object_uuid, decision] : object_map) { + marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; + marker.text = object_uuid.substr(0, 5) + "\n"; + if (decision.should_be_avoided()) { + marker.text += "avoiding\nlast detection = "; + marker.text += std::to_string((now - *decision.last_stop_decision_time).seconds()); + marker.text += "s\n"; + } else { + marker.text += "first detection = "; + marker.text += std::to_string((now - *decision.start_detection_time).seconds()); + marker.text += "s\n"; + } + marker.pose.position = decision.collision_point; + marker.pose.position.z = z; + markers.push_back(marker); + ++marker.id; + marker.type = visualization_msgs::msg::Marker::SPHERE; markers.push_back(marker); ++marker.id; } diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp index 02f550d314d39..b134ad3c39628 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 TIER IV, Inc. +// Copyright 2023-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. @@ -15,12 +15,15 @@ #ifndef DEBUG_HPP_ #define DEBUG_HPP_ +#include "object_stop_decision.hpp" #include "types.hpp" +#include #include #include #include +#include #include #include @@ -29,12 +32,14 @@ namespace behavior_velocity_planner::dynamic_obstacle_stop::debug { std::vector make_delete_markers( const size_t from, const size_t to, const std::string & ns); -std::vector make_dynamic_obstacle_markers( - const std::vector & obstacles); +void add_markers( + visualization_msgs::msg::MarkerArray & array, size_t & prev_nb, + const std::vector & markers, const std::string & ns); +std::vector make_collision_markers( + const ObjectStopDecisionMap & object_map, const std::string & ns, const double z, + const rclcpp::Time & now); std::vector make_polygon_markers( const tier4_autoware_utils::MultiPolygon2d & footprints, const std::string & ns, const double z); -std::vector make_collision_markers( - const tier4_autoware_utils::MultiPoint2d & collisions, const double z); } // namespace behavior_velocity_planner::dynamic_obstacle_stop::debug #endif // DEBUG_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp index 845070347d927..92004b4b9f249 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp @@ -35,8 +35,9 @@ DynamicObstacleStopModuleManager::DynamicObstacleStopModuleManager(rclcpp::Node pp.stop_distance_buffer = getOrDeclareParameter(node, ns + ".stop_distance_buffer"); pp.time_horizon = getOrDeclareParameter(node, ns + ".time_horizon"); pp.hysteresis = getOrDeclareParameter(node, ns + ".hysteresis"); - pp.decision_duration_buffer = - getOrDeclareParameter(node, ns + ".decision_duration_buffer"); + pp.add_duration_buffer = getOrDeclareParameter(node, ns + ".add_stop_duration_buffer"); + pp.remove_duration_buffer = + getOrDeclareParameter(node, ns + ".remove_stop_duration_buffer"); pp.minimum_object_distance_from_ego_path = getOrDeclareParameter(node, ns + ".minimum_object_distance_from_ego_path"); pp.ignore_unavoidable_collisions = diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp new file mode 100644 index 0000000000000..55eaf079afee6 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp @@ -0,0 +1,69 @@ +// 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 "object_stop_decision.hpp" + +#include + +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ +void update_object_map( + ObjectStopDecisionMap & object_map, const std::vector & collisions, + const rclcpp::Time & now, + const std::vector & path_points, + const PlannerParam & params) +{ + for (auto & [object, decision] : object_map) decision.collision_detected = false; + for (const auto & collision : collisions) { + if (auto search = object_map.find(collision.object_uuid); search != object_map.end()) { + search->second.collision_detected = true; + const auto is_closer_collision_point = + motion_utils::calcSignedArcLength( + path_points, search->second.collision_point, collision.point) < 0.0; + if (is_closer_collision_point) search->second.collision_point = collision.point; + } else { + object_map[collision.object_uuid].collision_point = collision.point; + } + } + for (auto it = object_map.begin(); it != object_map.end();) { + auto & decision = it->second; + decision.update_timers(now, params.add_duration_buffer, params.remove_duration_buffer); + if (decision.is_inactive()) + it = object_map.erase(it); + else + ++it; + } +} + +std::optional find_earliest_collision( + const ObjectStopDecisionMap & object_map, const EgoData & ego_data) +{ + std::optional earliest_collision; + double earliest_collision_arc_length = std::numeric_limits::max(); + for (auto & [object_uuid, decision] : object_map) { + if (decision.should_be_avoided()) { + const auto arc_length = motion_utils::calcSignedArcLength( + ego_data.path.points, ego_data.pose.position, decision.collision_point); + if (arc_length < earliest_collision_arc_length) { + earliest_collision_arc_length = arc_length; + earliest_collision = decision.collision_point; + } + } + } + return earliest_collision; +} + +} // namespace behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.hpp new file mode 100644 index 0000000000000..cddff65da36d3 --- /dev/null +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.hpp @@ -0,0 +1,76 @@ +// 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 OBJECT_STOP_DECISION_HPP_ +#define OBJECT_STOP_DECISION_HPP_ + +#include "types.hpp" + +#include + +#include +#include +#include +#include + +namespace behavior_velocity_planner::dynamic_obstacle_stop +{ +/// @brief representation of a decision to stop for a dynamic object +struct ObjectStopDecision +{ + geometry_msgs::msg::Point collision_point{}; + bool collision_detected = true; + std::optional start_detection_time{}; + std::optional last_stop_decision_time{}; + +public: + void update_timers(const rclcpp::Time & now, const double add_buffer, const double remove_buffer) + { + if (collision_detected) { + if (!start_detection_time) start_detection_time = now; + if ((now - *start_detection_time).seconds() >= add_buffer) last_stop_decision_time = now; + } else if ( + !last_stop_decision_time || (now - *last_stop_decision_time).seconds() >= remove_buffer) { + start_detection_time.reset(); + } + } + bool should_be_avoided() const { return start_detection_time && last_stop_decision_time; } + bool is_inactive() const { return !start_detection_time; } +}; +using ObjectStopDecisionMap = std::unordered_map; + +/// @brief update an object map with the given detected collisions +/// @details update the collision point of each object in the map (keep the closest one) and its +/// timers, remove inactive objects and add new ones +/// @param [inout] object_map object map to update +/// @param [in] collisions detected collisions (used to update the objects' collision points) +/// @param [in] now current time (used to update the objects' timers) +/// @param [in] path_points ego path points (used to determine the closest collision points) +/// @param [in] params planner parameters +void update_object_map( + ObjectStopDecisionMap & object_map, const std::vector & collisions, + const rclcpp::Time & now, + const std::vector & path_points, + const PlannerParam & params); + +/// @brief find the earliest collision requiring a stop along the ego path +/// @param object_map map with the objects to avoid and their corresponding collision points +/// @param ego_data ego data +/// @return the earliest collision point (if any) +std::optional find_earliest_collision( + const ObjectStopDecisionMap & object_map, const EgoData & ego_data); + +} // namespace behavior_velocity_planner::dynamic_obstacle_stop + +#endif // OBJECT_STOP_DECISION_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp index 115acd7933da1..2e2a7bbae9bdf 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 TIER IV, Inc. All rights reserved. +// Copyright 2023-2024 TIER IV, Inc. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -27,7 +27,6 @@ #include #include -#include #include #include #include @@ -44,9 +43,6 @@ DynamicObstacleStopModule::DynamicObstacleStopModule( const rclcpp::Clock::SharedPtr clock) : SceneModuleInterface(module_id, logger, clock), params_(std::move(planner_param)) { - prev_stop_decision_time_ = - clock->now() - - rclcpp::Duration(std::chrono::duration(params_.decision_duration_buffer)); velocity_factor_.init(PlanningBehavior::ROUTE_OBSTACLE); } @@ -55,9 +51,9 @@ bool DynamicObstacleStopModule::modifyPathVelocity(PathWithLaneId * path, StopRe debug_data_.reset_data(); *stop_reason = planning_utils::initializeStopReason(StopReason::OBSTACLE_STOP); if (!path || path->points.size() < 2) return true; + tier4_autoware_utils::StopWatch stopwatch; stopwatch.tic(); - stopwatch.tic("preprocessing"); EgoData ego_data; ego_data.pose = planner_data_->current_odometry->pose; @@ -78,11 +74,12 @@ bool DynamicObstacleStopModule::modifyPathVelocity(PathWithLaneId * path, StopRe ego_data.path.points, ego_data.pose.position, min_stop_distance); make_ego_footprint_rtree(ego_data, params_); - const auto start_time = clock_->now(); - const auto has_decided_to_stop = - (start_time - prev_stop_decision_time_).seconds() < params_.decision_duration_buffer; - if (!has_decided_to_stop) current_stop_pose_.reset(); - double hysteresis = has_decided_to_stop ? params_.hysteresis : 0.0; + double hysteresis = + std::find_if( + object_map_.begin(), object_map_.end(), + [](const auto & pair) { return pair.second.should_be_avoided(); }) == object_map_.end() + ? 0.0 + : params_.hysteresis; const auto dynamic_obstacles = filter_predicted_objects(*planner_data_->predicted_objects, ego_data, params_, hysteresis); @@ -93,103 +90,73 @@ bool DynamicObstacleStopModule::modifyPathVelocity(PathWithLaneId * path, StopRe make_forward_footprints(dynamic_obstacles, params_, hysteresis); const auto footprints_duration_us = stopwatch.toc("footprints"); stopwatch.tic("collisions"); - const auto collision = - find_earliest_collision(ego_data, dynamic_obstacles, obstacle_forward_footprints, debug_data_); + auto collisions = find_collisions(ego_data, dynamic_obstacles, obstacle_forward_footprints); + update_object_map(object_map_, collisions, clock_->now(), ego_data.path.points, params_); + std::optional earliest_collision = + find_earliest_collision(object_map_, ego_data); const auto collisions_duration_us = stopwatch.toc("collisions"); - if (collision) { - const auto arc_length_diff = - motion_utils::calcSignedArcLength(ego_data.path.points, *collision, ego_data.pose.position); + if (earliest_collision) { + const auto arc_length_diff = motion_utils::calcSignedArcLength( + ego_data.path.points, *earliest_collision, ego_data.pose.position); const auto can_stop_before_limit = arc_length_diff < min_stop_distance - params_.ego_longitudinal_offset - params_.stop_distance_buffer; const auto stop_pose = can_stop_before_limit ? motion_utils::calcLongitudinalOffsetPose( - ego_data.path.points, *collision, + ego_data.path.points, *earliest_collision, -params_.stop_distance_buffer - params_.ego_longitudinal_offset) : ego_data.earliest_stop_pose; + debug_data_.stop_pose = stop_pose; if (stop_pose) { - const auto use_new_stop_pose = !has_decided_to_stop || motion_utils::calcSignedArcLength( - path->points, stop_pose->position, - current_stop_pose_->position) > 0.0; - if (use_new_stop_pose) current_stop_pose_ = *stop_pose; - prev_stop_decision_time_ = start_time; + motion_utils::insertStopPoint(*stop_pose, 0.0, path->points); + const auto stop_pose_reached = + planner_data_->current_velocity->twist.linear.x < 1e-3 && + tier4_autoware_utils::calcDistance2d(ego_data.pose, *stop_pose) < 1e-3; + velocity_factor_.set( + path->points, ego_data.pose, *stop_pose, + stop_pose_reached ? VelocityFactor::STOPPED : VelocityFactor::APPROACHING, + "dynamic_obstacle_stop"); } } - if (current_stop_pose_) { - motion_utils::insertStopPoint(*current_stop_pose_, 0.0, path->points); - const auto stop_pose_reached = - planner_data_->current_velocity->twist.linear.x < 1e-3 && - tier4_autoware_utils::calcDistance2d(ego_data.pose, *current_stop_pose_) < 1e-3; - velocity_factor_.set( - path->points, ego_data.pose, *current_stop_pose_, - stop_pose_reached ? VelocityFactor::STOPPED : VelocityFactor::APPROACHING, - "dynamic_obstacle_stop"); - } - const auto total_time_us = stopwatch.toc(); - RCLCPP_DEBUG( + RCLCPP_INFO( logger_, "Total time = %2.2fus\n\tpreprocessing = %2.2fus\n\tfootprints = " "%2.2fus\n\tcollisions = %2.2fus\n", total_time_us, preprocessing_duration_us, footprints_duration_us, collisions_duration_us); debug_data_.ego_footprints = ego_data.path_footprints; debug_data_.obstacle_footprints = obstacle_forward_footprints; + debug_data_.z = ego_data.pose.position.z; return true; } MarkerArray DynamicObstacleStopModule::createDebugMarkerArray() { - constexpr auto z = 0.0; - MarkerArray debug_marker_array; - // dynamic obstacles footprints + const auto z = debug_data_.z; + MarkerArray array; + std::string ns = "collisions"; + const auto collision_markers = debug::make_collision_markers(object_map_, ns, z, clock_->now()); + debug::add_markers(array, debug_data_.prev_collisions_nb, collision_markers, ns); + ns = "dynamic_obstacles_footprints"; const auto obstacle_footprint_markers = - debug::make_polygon_markers(debug_data_.obstacle_footprints, "dynamic_obstacles_footprints", z); - debug_marker_array.markers.insert( - debug_marker_array.markers.end(), obstacle_footprint_markers.begin(), - obstacle_footprint_markers.end()); - const auto delete_footprint_markers = debug::make_delete_markers( - obstacle_footprint_markers.size(), debug_data_.prev_dynamic_obstacles_nb, - "dynamic_obstacles_footprints"); - debug_marker_array.markers.insert( - debug_marker_array.markers.end(), delete_footprint_markers.begin(), - delete_footprint_markers.end()); - // ego path footprints - const auto ego_footprint_markers = - debug::make_polygon_markers(debug_data_.ego_footprints, "ego_footprints", z); - debug_marker_array.markers.insert( - debug_marker_array.markers.end(), ego_footprint_markers.begin(), ego_footprint_markers.end()); - const auto delete_ego_footprint_markers = debug::make_delete_markers( - ego_footprint_markers.size(), debug_data_.prev_ego_footprints_nb, "ego_footprints"); - debug_marker_array.markers.insert( - debug_marker_array.markers.end(), delete_ego_footprint_markers.begin(), - delete_ego_footprint_markers.end()); - // collisions - auto collision_markers = debug::make_polygon_markers(debug_data_.collisions, "collisions", z); - for (auto & m : collision_markers) m.color.r = 1.0; - debug_marker_array.markers.insert( - debug_marker_array.markers.end(), collision_markers.begin(), collision_markers.end()); - const auto delete_collision_markers = debug::make_delete_markers( - collision_markers.size(), debug_data_.prev_collisions_nb, "collisions"); - debug_marker_array.markers.insert( - debug_marker_array.markers.end(), delete_collision_markers.begin(), - delete_collision_markers.end()); - - debug_data_.prev_dynamic_obstacles_nb = obstacle_footprint_markers.size(); - debug_data_.prev_collisions_nb = collision_markers.size(); - debug_data_.prev_ego_footprints_nb = ego_footprint_markers.size(); - return debug_marker_array; + debug::make_polygon_markers(debug_data_.obstacle_footprints, ns, z); + debug::add_markers(array, debug_data_.prev_dynamic_obstacles_nb, obstacle_footprint_markers, ns); + ns = "ego_footprints"; + const auto ego_footprint_markers = debug::make_polygon_markers(debug_data_.ego_footprints, ns, z); + debug::add_markers(array, debug_data_.prev_ego_footprints_nb, ego_footprint_markers, ns); + return array; } motion_utils::VirtualWalls DynamicObstacleStopModule::createVirtualWalls() { motion_utils::VirtualWalls virtual_walls{}; - if (current_stop_pose_) { + if (debug_data_.stop_pose) { motion_utils::VirtualWall virtual_wall; virtual_wall.text = "dynamic_obstacle_stop"; virtual_wall.longitudinal_offset = params_.ego_longitudinal_offset; virtual_wall.style = motion_utils::VirtualWallType::stop; - virtual_wall.pose = *current_stop_pose_; + virtual_wall.pose = *debug_data_.stop_pose; virtual_walls.push_back(virtual_wall); } return virtual_walls; diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp index c7bca149890a0..21fca83565ee6 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 TIER IV, Inc. +// Copyright 2023-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. @@ -15,6 +15,7 @@ #ifndef SCENE_DYNAMIC_OBSTACLE_STOP_HPP_ #define SCENE_DYNAMIC_OBSTACLE_STOP_HPP_ +#include "object_stop_decision.hpp" #include "types.hpp" #include @@ -48,8 +49,7 @@ class DynamicObstacleStopModule : public SceneModuleInterface private: PlannerParam params_; - rclcpp::Time prev_stop_decision_time_; - std::optional current_stop_pose_; + ObjectStopDecisionMap object_map_; protected: int64_t module_id_{}; diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp index d6961bd35a22c..8575e4729d7a3 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 TIER IV, Inc. +// Copyright 2023-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. @@ -15,6 +15,7 @@ #ifndef TYPES_HPP_ #define TYPES_HPP_ +#include #include #include @@ -24,13 +25,14 @@ #include #include +#include #include #include namespace behavior_velocity_planner::dynamic_obstacle_stop { -typedef std::pair BoxIndexPair; -typedef boost::geometry::index::rtree> Rtree; +using BoxIndexPair = std::pair; +using Rtree = boost::geometry::index::rtree>; /// @brief parameters for the "out of lane" module struct PlannerParam @@ -40,7 +42,8 @@ struct PlannerParam double stop_distance_buffer; double time_horizon; double hysteresis; - double decision_duration_buffer; + double add_duration_buffer; + double remove_duration_buffer; double ego_longitudinal_offset; double ego_lateral_offset; double minimum_object_distance_from_ego_path; @@ -63,20 +66,24 @@ struct DebugData { tier4_autoware_utils::MultiPolygon2d obstacle_footprints{}; size_t prev_dynamic_obstacles_nb{}; - tier4_autoware_utils::MultiPolygon2d collisions{}; - size_t prev_collisions_nb{}; tier4_autoware_utils::MultiPolygon2d ego_footprints{}; size_t prev_ego_footprints_nb{}; std::optional stop_pose{}; + size_t prev_collisions_nb{}; + double z{}; void reset_data() { obstacle_footprints.clear(); - collisions.clear(); ego_footprints.clear(); stop_pose.reset(); } }; +struct Collision +{ + geometry_msgs::msg::Point point; + std::string object_uuid; +}; } // namespace behavior_velocity_planner::dynamic_obstacle_stop #endif // TYPES_HPP_ From 6c75c7bc4ec204aa892487af3f4119afddaab052 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 29 Mar 2024 19:15:02 +0900 Subject: [PATCH 19/56] refactor(image_projection_based_fusion): rename template argument (#6583) * refactor(image_projection_based_fusion): rename template argument Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../fusion_node.hpp | 21 ++++---- .../src/fusion_node.cpp | 48 ++++++++++--------- 2 files changed, 37 insertions(+), 32 deletions(-) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp index 814fc5eca087e..12129e23e87eb 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp @@ -55,7 +55,8 @@ using tier4_perception_msgs::msg::DetectedObjectsWithFeature; using tier4_perception_msgs::msg::DetectedObjectWithFeature; using PointCloud = pcl::PointCloud; using autoware_auto_perception_msgs::msg::ObjectClassification; -template + +template class FusionNode : public rclcpp::Node { public: @@ -72,10 +73,10 @@ class FusionNode : public rclcpp::Node const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_camera_info_msg, const std::size_t camera_id); - virtual void preprocess(Msg & output_msg); + virtual void preprocess(TargetMsg3D & output_msg); // callback for Msg subscription - virtual void subCallback(const typename Msg::ConstSharedPtr input_msg); + virtual void subCallback(const typename TargetMsg3D::ConstSharedPtr input_msg); // callback for roi subscription @@ -83,13 +84,13 @@ class FusionNode : public rclcpp::Node const typename Msg2D::ConstSharedPtr input_roi_msg, const std::size_t roi_i); virtual void fuseOnSingleImage( - const Msg & input_msg, const std::size_t image_id, const Msg2D & input_roi_msg, - const sensor_msgs::msg::CameraInfo & camera_info, Msg & output_msg) = 0; + const TargetMsg3D & input_msg, const std::size_t image_id, const Msg2D & input_roi_msg, + const sensor_msgs::msg::CameraInfo & camera_info, TargetMsg3D & output_msg) = 0; // set args if you need - virtual void postprocess(Msg & output_msg); + virtual void postprocess(TargetMsg3D & output_msg); - virtual void publish(const Msg & output_msg); + virtual void publish(const TargetMsg3D & output_msg); void timer_callback(); void setPeriod(const int64_t new_period); @@ -110,7 +111,7 @@ class FusionNode : public rclcpp::Node std::vector input_camera_topics_; /** \brief A vector of subscriber. */ - typename rclcpp::Subscription::SharedPtr sub_; + typename rclcpp::Subscription::SharedPtr sub_; std::vector::SharedPtr> rois_subs_; // offsets between cameras and the lidars @@ -118,13 +119,13 @@ class FusionNode : public rclcpp::Node // cache for fusion std::vector is_fused_; - std::pair + std::pair cached_msg_; // first element is the timestamp in nanoseconds, second element is the message std::vector> cached_roi_msgs_; std::mutex mutex_cached_msgs_; // output publisher - typename rclcpp::Publisher::SharedPtr pub_ptr_; + typename rclcpp::Publisher::SharedPtr pub_ptr_; // debugger std::shared_ptr debugger_; diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index febec4dbc20b8..fa2dcd2b0e7e1 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -40,8 +40,8 @@ static double processing_time_ms = 0; namespace image_projection_based_fusion { -template -FusionNode::FusionNode( +template +FusionNode::FusionNode( const std::string & node_name, const rclcpp::NodeOptions & options) : Node(node_name, options), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { @@ -106,12 +106,13 @@ FusionNode::FusionNode( } // subscribers - std::function sub_callback = + std::function sub_callback = std::bind(&FusionNode::subCallback, this, std::placeholders::_1); - sub_ = this->create_subscription("input", rclcpp::QoS(1).best_effort(), sub_callback); + sub_ = + this->create_subscription("input", rclcpp::QoS(1).best_effort(), sub_callback); // publisher - pub_ptr_ = this->create_publisher("output", rclcpp::QoS{1}); + pub_ptr_ = this->create_publisher("output", rclcpp::QoS{1}); // Set timer const auto period_ns = std::chrono::duration_cast( @@ -145,22 +146,24 @@ FusionNode::FusionNode( filter_scope_max_z_ = declare_parameter("filter_scope_max_z"); } -template -void FusionNode::cameraInfoCallback( +template +void FusionNode::cameraInfoCallback( const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_camera_info_msg, const std::size_t camera_id) { camera_info_map_[camera_id] = *input_camera_info_msg; } -template -void FusionNode::preprocess(Msg & ouput_msg __attribute__((unused))) +template +void FusionNode::preprocess(TargetMsg3D & ouput_msg + __attribute__((unused))) { // do nothing by default } -template -void FusionNode::subCallback(const typename Msg::ConstSharedPtr input_msg) +template +void FusionNode::subCallback( + const typename TargetMsg3D::ConstSharedPtr input_msg) { if (cached_msg_.second != nullptr) { stop_watch_ptr_->toc("processing_time", true); @@ -202,7 +205,7 @@ void FusionNode::subCallback(const typename Msg::ConstSharedPtr stop_watch_ptr_->toc("processing_time", true); - typename Msg::SharedPtr output_msg = std::make_shared(*input_msg); + typename TargetMsg3D::SharedPtr output_msg = std::make_shared(*input_msg); preprocess(*output_msg); @@ -291,8 +294,8 @@ void FusionNode::subCallback(const typename Msg::ConstSharedPtr } } -template -void FusionNode::roiCallback( +template +void FusionNode::roiCallback( const typename Msg2D::ConstSharedPtr input_roi_msg, const std::size_t roi_i) { stop_watch_ptr_->toc("processing_time", true); @@ -356,14 +359,15 @@ void FusionNode::roiCallback( (cached_roi_msgs_.at(roi_i))[timestamp_nsec] = input_roi_msg; } -template -void FusionNode::postprocess(Msg & output_msg __attribute__((unused))) +template +void FusionNode::postprocess(TargetMsg3D & output_msg + __attribute__((unused))) { // do nothing by default } -template -void FusionNode::timer_callback() +template +void FusionNode::timer_callback() { using std::chrono_literals::operator""ms; timer_->cancel(); @@ -401,8 +405,8 @@ void FusionNode::timer_callback() } } -template -void FusionNode::setPeriod(const int64_t new_period) +template +void FusionNode::setPeriod(const int64_t new_period) { if (!timer_) { return; @@ -418,8 +422,8 @@ void FusionNode::setPeriod(const int64_t new_period) } } -template -void FusionNode::publish(const Msg & output_msg) +template +void FusionNode::publish(const TargetMsg3D & output_msg) { if (pub_ptr_->get_subscription_count() < 1) { return; From 52efb84f121446677c42dc9039efc910a41627f7 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 29 Mar 2024 20:32:19 +0900 Subject: [PATCH 20/56] docs(dynamic_avoidance): update doc (#6648) * update doc Signed-off-by: Yuki Takagi --- .../README.md | 97 ++++++++++++++---- .../image/image-20230807-151945.png | Bin 0 -> 40217 bytes .../image/image-20230807-152835.png | Bin 0 -> 86771 bytes .../image/image-20230808-095936.png | Bin 0 -> 67282 bytes .../image/image-20230808-152853.png | Bin 0 -> 67033 bytes 5 files changed, 75 insertions(+), 22 deletions(-) create mode 100644 planning/behavior_path_dynamic_avoidance_module/image/image-20230807-151945.png create mode 100644 planning/behavior_path_dynamic_avoidance_module/image/image-20230807-152835.png create mode 100644 planning/behavior_path_dynamic_avoidance_module/image/image-20230808-095936.png create mode 100644 planning/behavior_path_dynamic_avoidance_module/image/image-20230808-152853.png diff --git a/planning/behavior_path_dynamic_avoidance_module/README.md b/planning/behavior_path_dynamic_avoidance_module/README.md index 5e8be9136886c..10276db0efab2 100644 --- a/planning/behavior_path_dynamic_avoidance_module/README.md +++ b/planning/behavior_path_dynamic_avoidance_module/README.md @@ -1,50 +1,103 @@ # Dynamic avoidance design +This module is under development. + ## Purpose / Role -This is a module designed for avoiding obstacles which are running. -Static obstacles such as parked vehicles are dealt with by the 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 module. +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. -This module is under development. -In the current implementation, the dynamic obstacles to avoid is extracted from the drivable area. -Then the motion planner, in detail obstacle_avoidance_planner, will generate an avoiding trajectory. +Avoidance functions are also provided by the Avoidance module, which allows avoidance through the outside of own lanes but not against 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. + +| | avoid within the own lane | avoid through the outside of own lanes | +| :----------------------- | :------------------------------------------------------------------------: | :------------------------------------: | +| avoid not-moving objects | Avoidance Module
Dynamic Avoidance Module + Obstacle Avoidance Module | Avoidance Module | +| avoid moving objects | Dynamic Avoidance Module + Obstacle Avoidance Module | No Module (Under Development) | -## Overview of drivable area modification +## Policy of algorithms -### Filtering obstacles to avoid +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. -The dynamics obstacles meeting the following condition will be avoided. +### Select obstacles to avoid -- The type is designated as `target_object.*`. -- The norm of the obstacle's velocity projected to the ego's path is smaller than `target_object.min_obstacle_vel`. -- The obstacle is in the next lane to the ego's lane, which will not cut-into the ego's lane according to the highest-prioritized predicted path. +To decide whether to avoid an object, both the predicted path and the state (pose and twist) of each object are used. +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_. -### Drivable area modification +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. -To realize dynamic obstacles for avoidance, the time dimension should be take into an account considering the dynamics. -However, it will make the planning problem much harder to solve. -Therefore, we project the time dimension to the 2D pose dimension. +### Cuts off the drivable area against the selected obstacles -Currently, the predicted paths of predicted objects are not so stable. -Therefore, instead of using the predicted paths, we assume that the obstacle will run parallel to the ego's path. +For the selected obstacles to be avoided, the module cuts off the drivable area. +As inputs to decide the shapes of cut-off polygons, poses of the obstacles are mainly used, assuming they move in parallel to the ego's path, instead of its predicted path. +This design arises from that the predicted path of objects is not accurate enough to use the path modifications (at least currently). +Furthermore, the output drivable area shape is designed as a rectangular cutout along the ego's path to make the computation scalar rather than planar. -First, a maximum lateral offset to avoid is calculated as follows. -The polygon's width to extract from the drivable area is the obstacle width and double `drivable_area_generation.lat_offset_from_obstacle`. -We can limit the lateral shift offset by `drivable_area_generation.max_lat_offset_to_avoid`. +#### Determination of lateral dimension + +Lateral dimensions of the polygon is calculated as follows. +The polygon's width to extract from the drivable area is the obstacle width and `drivable_area_generation.lat_offset_from_obstacle`. +We can limit the lateral shift length by `drivable_area_generation.max_lat_offset_to_avoid`. ![drivable_area_extraction_width](./image/drivable_area_extraction_width.drawio.svg) +#### Determination of longitudinal dimension + Then, extracting the same directional and opposite directional obstacles from the drivable area will work as follows considering TTC (time to collision). + Regarding the same directional obstacles, obstacles whose TTC is negative will be ignored (e.g. The obstacle is in front of the ego, and the obstacle's velocity is larger than the ego's velocity.). -Same directional obstacles +Same directional obstacles (Parameter names may differ from implementation) ![same_directional_object](./image/same_directional_object.svg) -Opposite directional obstacles +Opposite directional obstacles (Parameter names may differ from implementation) ![opposite_directional_object](./image/opposite_directional_object.svg) +## Example + +
+ +
Avoidance for the bus departure
+
+ +
+ +
Avoidance on curve
+
+ +
+ +
Avoidance against the opposite direction vehicle
+
+ +
+ +
Avoidance for multiple vehicle
+
+ +## Future works + +Currently, the path shifting length is limited to 0.5 meters or less by `drivable_area_generation.max_lat_offset_to_avoid`. +This is caused by the lack of functionality to work with other modules and the structure of the planning component. +Due to this issue, this module can only handle situations where a small avoidance width is sufficient. +This issue is the most significant for this module. +In addition, the ability of this module to extend the drivable area as needed is also required. + ## Parameters +Under development + | Name | Unit | Type | Description | Default value | | :-------------------------------------------------------------------- | :---- | :----- | :--------------------------------------------------------- | :------------ | | target_object.car | [-] | bool | The flag whether to avoid cars or not | true | diff --git a/planning/behavior_path_dynamic_avoidance_module/image/image-20230807-151945.png b/planning/behavior_path_dynamic_avoidance_module/image/image-20230807-151945.png new file mode 100644 index 0000000000000000000000000000000000000000..9d9b7ecbf8e3ae7bb4d7af79d253dd5fa1593637 GIT binary patch literal 40217 zcmY(q1ymhP6D@jhcLKpBaBz2*kOX&k3-0dj?h-UeaCg@r!3h@J-Q9V^_rH7JdS@+c znCa>6s@k=8O-;DG>^Brdd_)ikgd!m>rU(K-Q-MGb{_wEC5f$;JbKnQGqo{;3Jn->? zHx2{-#&i0j?xbXE;^b=J@Ev4oV{84L!O_U!`*#~hGh3%Ks4hX^BsOzpb*Ik`-wmA1 zZEZ-E&8@!!2SFfKW>&VHmU?FH-OMoHTWTRGGxKhG01MAfSO`1wUQxn>rRoF-L<*7+ z6H#`{JYI2kBe-*CdOSl`tpq_}LW)NuC5hKcOL8(S)vrv;CMN#nl$qwVt{axMnf7d3 zTl)L=$kSul$=2KBseX^2%lhwjfwQa@O=F_^L4u~t)<&OK8F<^5ZDl71nQt911{`3N|fO+=By04ead| z&S>Ify#z^icXzL|Vez^rC((&Lk8ASwl=-TesB)`Jn9-6*Ch1^qlG{Ucd!EnFnX|nv zCBXIJVdA*bvgjPlv4eq@^OXkzDAN*ZYPgl!EqQnB__7SA<7%vNXwZ-#zfck%^(#vp z#gew`0^IJG1*=MAtV+auI^4(B2!XumR;ApDF>6mX$pe_&`q1$^xds&m7qirN*B2#4muVnjfJg!ux}AIXj8JJWrl`_u$p+ ze)a2D3&$a^2O9xCzQsK_t)2~7)kk1nrb15|9YvyIV&K7Tu|Oj>X$41Z*I!ybq{?P3YrLL(d z>gm~b$dVqV>VRg4#K*x;jJ9mUrR#A(`Mw<9jRaI$a8{bWLx4C@;a&gB%ggr;)yDw? zp4oh{=uxL(g#1%Ey>aK6g*I2F+tU@TTTU0NIJKMwaX9v9W`!}vf0PWiW$G^khpKhm+z&O=Xw}_hYTpLapNbZr>EZsLM(h@ug`Hp zpa@v(H|=SWV7nuE3uSL_?~izR!%|;A7Lw;_I?ypVBz`#fgUAT=)5D-OB+W#TX(>$c zyL*Q&JtN~GFi1~#H|R+Q9k7AOF^5Pr`3fC58<|0fu^3Iua727O254zS7?@FdG3jR` zhdlq56&ubz3RXPE17bs!5CZDAp|8@Baf$TIw5m1nk zK_Dz_Fef`ZG)Q|+L?a|L6v8hV%h>Fo0NSs0^|Vf*;Emzy*RRdnfff}SOHj*>Yy~7Yt2h(FFh_E84b$2rPNLk6c{)1cqm0|lz5m+HPTdlN#1+oB1htZvW#TJZ}2yBdV z%oy_+13J8&1l)InS?Ggk34|;CguGW8O3b7fI!dgF=m}>4z&OJEBSh1)hoK8g z3njr=w9&)iu-gtT%$%Hn{fa{X?`!|R+3&#E%q;8$OpTO?RS;@47z446i7GiPtw_k{ zQhwUW=#n5UpCJyKp~OO@M2Sj}E@lUkMBLJei9@gP0&?O|JK*or)8PnUs$$j0$H(*a zK(tF#9vVq1>e3gEyk8IG@)^bfiYlT%Ym#DtS^Un%65H(td>Zh;eqFZuU==K7ssFj| z)?BV~lH!M8`Vsd%mULkd0P2G~4hI4-2gWG0f08c+pY|)bTVyaoHb_x`8Z>r+lr>gCB#^eBC;e_LjM<+*f0FUv zE*N>p1tR-(fQx_Nw;U8Mu6NG32PeR3RzYFQL9$O{hF;Gr=KEMHxC4&Dy!>^>t2w&Z z9f;NSf2KLJ@2MDY4+b%Fq%v@^<_!JTB&J&`+b`wyuD|nYpJl4`j!%U$7->hWQg~Qd zd!b=ic&5yN0Uq2sbb)2_Zq}kYB0@u21xbL^ITT_`iAIY~*o)WdO#e%B-Zv^<+n-3L zo;4-wVYh(K56RaNgxj%fQs#is75)X|+2wcdJ?1eGjEn?mn!iO9;P+!^cWgW&AiwNv z;{Vt~^p7e00!x84c-MpEBrM@Gieg_NH`pJ}&}cW?{mgSDr=`fs)h9s&=xm<99f1P* zl|GxaBN8+uxAS2VKmf8((9rUmnsBM)vgzGz7*6L17^rTXbMLI|O1gM1BqU`0?kPR9m@L1tL{2Y% zy2qyCY+B6{**sBJ`n-|@ucyXnkXcZ096ETo`hU}N{6EO6DksGog}UTp3qp)5ruo2j2Kjb-Q%5LPT}ukp=@_5*j<)5_Vv{=V6&`;BHm*I!{> zYf=>(JDZtYA7FlK&%0bGd_tup|8x1i{8+)#JLRxiJ1Vp*ga6(8Y6C!hc4lTENC57Y zW{EMH>X@Y%Lo9%(fDLg>U#*5UW9jV;`=^18pFgT7+XLW1@>x<;;O5VecptE^cYC+R zpx%dgcUQ|I6|Aq;F>2$^e-v!cbxus&3&%+SAZMH44+LD_(nH6BzOSz@EiH|CmXS!= zU0PbcV_h|Ww+Bc*1``NZ2A@V3StNypxVgg`8aN0Ay_%2Rlgn^c&h)%4zKqSU6M3={ zfWc-|K*9j|`4i8gfT>6QhY`q25$aB5(3D>pU-;G@WclBouiW=)pnSIeza%1V3f%Yp z*i;ChFvYTkSXlJ&MIL?7U$y`T5drKP^d7PzD)RJxf^O%eU@#c}7YnievcpqWOj*I| zs&4!Bv=k6i7Nci(Miv(DTyPvnWi6kvlB2^BN?oPp_w!X}`=n*r;cY(ssK8kh_Ink1 z=?R3hzd4*OH_{B;ySTV0b!p=gWnL41heJqzVI6BS$=RvDfBPtjlyPp;a=$8|As~L@ zI;u3;IhVCzjfsr~T>jsvrib1s@1y2&1rz74_n9Y2w$G#aSe3+0v{o2qx|*#mlWaDB z39zVfW)_hf;StYQ0G9LtTK<0^s+f4*Y^=4RpZvxyF@884ajH#WHCw-LlXuiD=rZGI=s>`0LLSgmS*p?7$p1J(E<;`iG&FZ3~YA0$U9`w zv}J^}n$w{R5tmK7At+7w$D)9Zff!u-C~N2YI4}TsLJ1(I)GD>705Ay@CiPP)l6@C1 z0Go(Y1zZteQa%53MdWX11d++DA*v0BCn_WQ*&WLGp*NjRr*!uPQ=LDfmZ{~=x>qe4 zOq|cC9M=Ia+q!x?;89fboD-21o?VtgHcBgRyGI9Ao&CPy^*3SBIOw zvhwmq04c`6*f_OZbNkHYJ{c(?&CrtOLR=kW)B=m|Hal| zdTy~&$UcvV*djn6!Bo-%dsp^FsEPRa_?zSW;JLqlp+G+#Wzw7p`24giVxywg4~lY3 z-1*YS@9()|NQ7blKFR4Fo`8Cq`SGc{f#=-46n1?r0!vE3?$$ zFv?rM8rP-8;bzVKg98z2>|WQdCmlfMz^WZ&@q`^}w2FYSuy29^Udy|E-J>j1W3hLFw2$2T=S9iU~?^5y2^C)jIY=aExj;Cz_t z10we*PNq^p8!`)BK==YoJYc~zKwNHA91nIKkt_LN#2323w?ku z(%*34*?h8)^%n*e$!5Jv^T3S_1HkrxAYi2ibl)`Nif_OOUsU8U0!oxe>g(&%+2Hwk z^{%}|&GD)_Km~Zxoq?Ro25?`+-W@`*9VuI;Kj7K{<=Jhq7S~>a4Mu@n0XN1y#*U?v zf#+xbO5G04WF8ERc)@p_(i}`pv*Cc6mo>bsn*`it@Np{EM|n29VKsx8nyGo-p>l4X z%TT|owiZ$Z9hrxVyfo_nqo@#1GHC>KRMfbsj_4=Lfa)W5-^Kv)cn##Re!0b)$RC7V zHWs%^)c-_i@c=(@tU(h-;o9@(EhVEW09&-eDHs|Lbz zsk$B#?~$MGT!c!_mY$LE*Ar3M$SOoa%=~})aD&%94^e{Zp}D!HSl})ri!brC@5~n+ zG59(g5(5K61qAGel7|3)891zzYK1WIdhp$UFWmV5V^>nVVWWV=NeUl(3@c^QN$)>I zcwymD*aK=3u1C!2!NEYeNccTM#=-@tMlB5uMS)_L2#{=)`K)5hk>6=29wD&n?~C~h zRCvHtRPV(eXkd{IeTN7DAr2^xu>+(fE$HF;`WoP@iAD~#USCc7OE3X^#lnH?2vk0d%27=3y|8e{W zJ0yj}voq5j=y?C==xCO3bpQx~OEEAGfSOKNRIC)A#rvXm99o){;1mL{{tF9>FrY#h zKEgX1?P?Sr#ne$BxK=f5I_n83CZ_zc36s*oYq_K^6Uf1nYiqGsRI>X(agX-D;uy_L z;YypUC2!9Am@aKM*^skogIhffmh*sy#88nSMW6IUEC>YnRVKf?;(vt-%K&OEhqaR* zgW^vije?B=SA~+YR8k)1-x?CbH3J_U25D6M!&0UrX)Dk=(< z;&q_-rg#>^kYBhKH(z(HGXluOEK@_l9q23JEtqT1O{DM9N3j!SeD+(Vo6a-POYTN9 z(AO&+ki*JHoU>RHn&XwZSW5IpE-+b=urJkEpq#-p2?M z9$iv&Kou!N0@<nDtJCiKzj32jwoT z#hk+-1e$`Jx2G@1?dY859_;1q59f-AQECn0wpY1HtN(>$+9Y^7!{5rE*hA{G3AJoc z@&gD-BOtDd?H{~=e~F0wN?3N~+m0bMjt$!G)KxJ$ygBunSb=!Hp;PLv5Q55W*VnZq zMN7gRr5hUy>*1H@&t<|Hh57^GZ9|%qLXehL-<=58c(dI`fUiEJjhb?hY4z2(AJ5Kp^TC1(rC_;Gi zP~MscpZvg>7Sh3dOSUlMc&_`AFjpWyFkFCYQz^%lIc~)_5H;MT=TesXhpaT$?`Jsjw8d)& zD-Y}qt_Mm+7Pym8$cN#hG4Bpdu4sJAa9FBi(N#4TgW+4Zne|X_*yB>ucBPr5W_cNkG99f(@|S2DnzbP&k2D(ZueJ| zAhtif3|O{F4K~?5{0i2EPqKFA-<+A>_q$z}2?rM!ND#B~|Mx+Lcz#yWA{E+7=)JFe zla#*#)T3s3#u}C$=nwpE}OZv%m&N-u%RoTg(JquV22l|!lEFk}nXA)S;` zfO3+PPbbg$buJd(^0mmeoHkT-cT9w47pvW*X*xAj?Pj@i^mv`FxEI2@32*py%0uxp zSnm2yAFV;09PK?V5vHLH#@iLTSjzi`3bx;<%an9@JL=xlx(M1J^x$|wF_`L=95`F< zROY*GB(uHO-!M+PjhTl!u~Y#1h!GC~xcqD~)-3XAH1UkujjVUNFC%#E`{#zu(_SI)0pRPUChza`ctMFon5x1ja3^l^`J&a|^3H|+|)*P-~CySXx4 zq|`SojQ9)aB1JwI`5nN!#eT_`jo%7Ctemh_;qtBbEKKRqJUJtl47)fJsJUWKsvLyynA6nSKd)^s z5Qk2??kerIvacjhczNeO-&|P?(7;@&Ds-39uOm9VzJ||^u^d9FKlOTO`15xQr-xZE ztrC43(QqF5c_`zW8w!vNd@(x(){OfmF?@huaKC6z8;}`KW>fyz#!A3kTg;C_b>HY5&aIgv>^4;9s0nu6 zFS-{hdJ3G4dJ5j$Z~%KVL!ujiJ7gY z)LdHTHfMsSsp<=JRV!Zh-1x0HNAF)uV01i`p7!a^D@n^ezN`}IelLp3d*0yFNy`JP z9FiGarY1GSeNQ(ae&}^{1hw6DR!-@~l!2#GiN*HSG$zi}V5%rWAa4*=Sj>{;B2RJ`s681IX_xd($1ID;-YKGT=l(-x6s|9Wl7gcdbimj;K5MleEN?LSC{Do zG5m(JzDbNfKVAqsg*mTK$%Pjv?lg`gR>3QawNgilMT!uECZw8>!MnC6e6K+*@`G1} zW5A&!!*}hb1V>8R;P>rD$}m*TcHVmP?j&bYP6WG|;{&(2DxD#ERFpYSg7jb@I&sWc zhY+qGiI(yX{4%h;77r&0w-c=FwDwS8Sz;LkX9ah2z;MW`5-n*Sq_1253lhivGNcph z=MP0J`7(t2S=jrpXzL|{%9lst({@bc{>Hy6wW1b-zSi_hcApIvd=z{Bi=ZO$0jvN# zR7Eb&(e&jx(`SJ6Anh9U@s$4lV;!RV%Tatq>}+LL)c}sOq|q$w)dARTX{)lgtBPdA zHkKwkyJd~PTVOBTB~Lk5g`P*AmPUTR;gcw~0!xgUqB|ZM2XW4NUpfE#<2smz;Z(!$ z%9y#Dg}3In!OrU7)k!BcpCeul)ZMnzRsx110OU9%gotdoDq~kBJ@G^2 z>6xjy6uKiI$St4?eNswF#7e|!snT1;|4%PKfjVTqasUMo1%n&tk4u+1mV!&#cFPB< zMrY?e3~=H2a&{I8TF`1~H=Y?h+nXI0EuDjv*3OwOZV3e>SE64y65p$pl zrz}&Gvr>pjA>oOsbY?x6nc1PrNge`$T?vj1E1B49>&$E2|1 zBqJ}yog06<^*s`RBQLEHwIxi(ga@kQ(uC+33Y3&V%9lN~dt4U|k}_Wgf93ezz$N9_ zLfM^GUpgMl^rp*E3+d6bU}E&S&AX~bjLYyd8RnYeU`*T8nvlC9w5&?*Yt-eSbt_bw^~gXo_|EZHpqS>D%fK)8LNp@eb3LbRa8A~!^4;fX08 zg$*}hVM=W(WC1jQT-9V`(RQMWr+5A}frL`xQ1O6jk94klg+1TYA3!^aiSt~P%PIkxxRJ=wZx!@FsqE?2{ zl8W6?9>Z zUrF06Ugs-#4pJ@?F~xw#ImULu3CPlnfW9fY!TT)`o$Wt#4m0)}vN-Xyu2=Kv+lQIyS$}h^#dCCY zgg3yGvX)w?GiB=4F;K^$H_NgN<~ta$xT5u$TtuCs={;}|{z?lmg}?+I3R1wq2>(VF z0a;$%b6`hmE}>#07EEodG4S{Y76-gLg>50~W(alLOfmT&pXoYlEJYdR&is$uDU#*}zYx}mxdy`&r+VnZj} z+_M%6#k#<98+s(Q5$9s2ky-!6?|-M|gZyGBG_YgOpT!*vjoA$DKmehWt_RMck&;56 z-}DO^>s&Ej$RcZ<4wUnUR)ITH)M|3KIWOQ(o0elord?=Wh<}naMKt9}nDrtJc_ z%1x!!&o%7nTzAB?hOuhPc=Jg8Tj|CQ*#*wBEuM&a%=+)`$S+kK&t4zb2xvM9!qZP; zZZ;chmZmT+40;Fx%u+Edvc7ncM>HA}WJEy5BpLzZTzZs@kT3hR#m6zb)wS!X7i%)Y&$2n*|P15E&?sb z*98H(ml%;VOsz%&DGnnXO&CBK(Eo{a)9`?~Qt!51e4~reJng<3R=7s;zBhWx2l?sM zykLUX-|AmjS1ASka1)r;Q?0w2oyTG|gd+6nUm&yPI{mme-4-7vDEI!+U2od&Aw+?{ zZTJzLH9n*J%{W8>C-E;%hJ4Jsk4?EVj9rK&`LG(=v8fC4BXZ%lc>5fLF_3>N)bE|* zdEs>l0~oKTuTgKUbzp0Ji<_w5^);6}Y~tS=Bome1Ks$fzUPd+pk0}!U zJ=b2Bp@eQP-LTsE#JI1Y+IcR@$^G{wrVYSx%ZJJqs80J*34H_q4*yMyH$Aud%Z5&x zE4L6m!6z8XHtZNi8c@ZZL+#O#dS+^v7dIzHC)j*XR?pp5Gegu@iNj<#$Dt05(P%Ylu_0q|?r_0a6jt{EC0b=C-IQ670@nYoZ!tD5c%l-U7pANGiUr0%b z`DnX9^uHsvv<|_@-@hqG$HvIpKYpdh|Gl|M4#=vS`uZSw>Y&0x%F(s7K4Uw~5jMIw z3WQS|u0^!g$=WIyh9}MSeb?TaB7{mU{`1Z{EVgisawGz?riPx?nJE9yfeRgFBrja9 zTb=729=;Lgp#e%jd&JM5)eZr*)GA!Ys+`R3!pb6r0ojspUn~N@t-gQ-IR4D*B?Ik6 z-=8RAz6kjfT%u@8Y7e|szv2A|Hu>#{C9eNPw@1bulHd~dG1zB0$#yf(2?Mt8B`%WbrJK>_F8V?B}dLBQpO;biVnS)*+* zZTSYP6(WHc*F_FKf`kKtUN#|~tNPbWvfhe@g?^JPy%7jvKbR9@qpdq#vgd_uPHg#x z zaNjOYO-(^e8Tx~|DcjZ)mh1(*psKv@Q0PaQKqrtu*C44T{ld;wk4ar`mnCky0F<~S zLQraNb-j8GXBQ%#FgbB3Dg3#U8)-0Qy}A~FDcjZ1ZB}qD5S$q(we&`XMlceVn4FxQ(PuVb%RxH)d3F!;NK}GvjPJB*}{lyssD5uc}kqR>w3iR6j z>d8&J>R*&Vwc!UP`t{;$z{GKkds97ezBU1?DGbhj^wHj{`_c#0jdwt=IT?VCNJT|x zw@xtb+e>-CIxev{MRzTVtvH{NQWU?u%ws6r{(+>%=cAC}g8`^p<$(6buLG3h`7!x(WgvW8E3Z=+f~{DKtVHUdxcYDsY!JS z;5h%Fv~FO(Z5jxB+Zcp`^djGQNkM4pr-MJwL73v35F;<#q{IvON7z|mQuYh_pUWmA z(yDca?KN5hd}Y0$4nol&JCW8fTkxB8 z8Pm6%$dI{qeQ>@f`Mg-4zhwL z070{lEUAc3$%3*tL98Yot)TLPY%{3dFpw-LZo|qE67-|GLweApiOho~qG`+a6Ha8$ zfrTi*AS#BN?Dki+;`woZx9OY>%(vBgw$0GFHz99;6B(2Rff}~3$!wrgXp~F+r&CGN z_9{C(N(C9^%ez=b2R{TTa`G>FQEwm3277D$Y$nsIZg1%vLs35FTQ49czRWxT?e7O?Gq@Yule`X?ZX{rWt+P_^O9 z`--@h*xBUFPru&C`B?&6Q?yogVAW_>+mhyJwwmm@g>& z8_%qOZfM>Zuw5kSK@0kJo_CGu^XHMQ9;|sDcOufi{jog{cm0KYHYV&FdiB%P;;xut zy&+F+l$&GwP}m6<#ia?kC^|GedTm#~u{#@D3U613fQmIX4(B92mo1p`kGo@{&Si7W zgNK9`q)QJfRc2V2f;#=?TuQ;T2WDjoYUV||=DT<>TB8G?gw2w_~j zn_j7i@ufFr!dW8v+nCs#(Lv0N`>hQhp)MT2DLabfI55#6;mHb0`Nd3d4p%b z$4Hj}<7_`Q%`h~prOtsYr*l>!A5GY>Tr&&xQyVZ*T1pWMV64bX@>kN=Zy>)j38s7% zvoEpe-8odRm`9iR<5E?d?bozGI+Y$uyf@se!a#psuyv>URbc*X|13u;0#pJr6UR5c zAAA6H6W5UVX5ACe8)EDgTs4z-gq%sO4W4YCs1Ne`aNT-Rx*oxk1x;-ueXK>^2;mR$ zmGQ#jV)1u(CyrF_x12r#DN3&jrlR3kTEm( z{IM~U0@LEC>>};ZCnP5}=)$WEW2@oz3LMq{9b3o0wh1J9!G8Olj}8sd_2J37AAPVX zVWOMqegjkIUi-PKnzpKkq1j$lu82-C*l%7x^=n?O+8_Xmx!JbmZRvjzRnc zQ3tvWkjPN+4{>k(;12+p0tgx;I)V;u#W?tne&ip8QQf8}`uh38)YNoM3%2-1VylK* z{Da=bg!kcab6n|mjfS;4TIDA~M5C43nB8440Ns()xn(1vF=BA#I0TjK9jZSkGCTW6 z$b*s(eGMYGVBiS`?qSt+bbfpK>T)W}S(=(p4X>g1vS#9Uq7+;h_^SbNSx`6A+cVP!Q`b2UA&&zz zE|ZB`9+99IbSmQxF<+EaDr2(qu@T7=H=|x>lC$>1!l2#3^mpyfOkPfIZg^0$*Mq~{ zk@s~z$?u(!)VdfnR8&JdJ9Ihz3$bA%D5yZU%i)vvpC1VcyA$OE)9tN5f$vA@{tZ@Y z|6A4NjUM5p&6Tf{xbRS9>*Dd`=sFdhbzw!vhe^^3u-OxM+|SfOmTQ-@U^ zP;CNA`rdAK)$KwuU8?<#!RP%2djw{n zJ!4AadnX4+Fy>k6Trf&l08CutCBnZg?A5j}Tm(Q#5yZ;*ws6Q1@1eNh#n?a!yhS3! zl9XO0t|r6&J40Wu!RTLIxmzcPK`@1c8BRux#jq`=WpYJze+5YK0|~3K`X-J#FMT&` zoH!WYC|#C-^y#}BFYn~klz$Uz0xEIFH+ylLTJkIPB?~$mS!pYkZcz8l!4dZ%Uhi+n z*?!-*JKv&1bsIxS5TkB;n%YC|t@@)|<#H(k=>9TQu9){%Qn`F$cd_X+N}NAJ7_aI$ znv?3M_s8a6`!PdQ8s9t0e)8F~pQU};6lkeOAon?-$*dg{SX#KXNws(IlR3?%D-jfpxD^hhC)2gSQGUj7rtm&ABi*QsV z`WK99Vg!YKkvblrqrW77gT#zsbH79)oL~rPDA;m$A`%Sw+>y7g?w~ysP4_ zc+g}*5s5R>vPV5pL5$kXxo(**HuH>KyDUCkk1P>YIr0ANIt~HAN^*BhQLvDKMiXO5 zNq;YvZ}vs4STN32zObf9f<-1azXwbch%k5cGQOGWQK<$e2gs-up^NQie5E1`Bafgl zK*ZgVDw!p5Xie?EbwJejEEx=G_Q$cJA~5Dj&K;5#4iZ4nb_Jt1{6=r2xywwVLzQ! z9-~>c#CCy-A8GNo_nz;EyieG;BcJS;ym}eM5k13iT|+PGL|^BASwOjixFgwuW9hu4 zb~*G!XD zVYU*gYw#|LQ;;A7sq1NdQ&TdX+xd$SA^mf=7iAcUsT6GhDn+}Qz5G?fON5elb^!TXe=3ISRch(kR`!U6I ztb%;mF#5B6y|Y`$z~(&XW|7AzDd5_DbmKel^3_n{gIp(+UuGBa>M`fs+|;SfXLzz9 zafXaA1Qu*d-VKMA#>Q-!n=$N04_SD;EV}O+tL260lN2ZAc;+Sj&>-=IpaKR2o&?Rd z_*E7$Y-lTJF7&m;?x4>bmPSgh)mm5WkV?T&o-*?a7nZGjX^sqP-%m$Pf5;lcEs5&a zL4GxmF5$a^sj3O|>#Qh&@x62PEpzAJDT~~OPDJOBKMaLWL=odtq$P_>hpu+f(2u9D zX0(DU!})*!!ypkVIvox}%GVO-&VR$bwY5w;Kh`lA98Dw_D$da`%s4W(NaephcYH>2 zA&W%M2D2MKbs)$V?=Yi83b8)yW6e?ctO@xr>NpGi9DKS-Cy?{xL1uuV`Y%Maeh2P> za@AM)dfYo$Mm%vJ!y_4ZJ;BUyo}!(MX=AY(Uzv!m7g8VdbVvj(*(Vd9%?i5+M%Z zTw-BrM^%e)l5EoNF;8nS?N1$>A|~=n5g|a50uI#8O5f`;hPbpj?jyEGiQNtpW2#n< z$q}?1B%Cd}v_h5)PtEaaHfS=byWTE39K=>f(7e=y7GRmX?rv(rH4^v<5035eJ}ZkZ z^I-(}Zeo-+Clz<-sTHwv6_**+sYCVrVdj3mju>^I_uqt;BXQA0UuF4VOfei11I996 zjnL8kR+An`w9+q3yTg3ymqX^FXL zEqf8k3@S^9{%iY4cPmf&K}D4oR7}bd4hJSGmc>RoPELSnki`BN{-YEYj4zH>dzDf< zD2Zrvc5R)qwM~J(Eq1uf*Y<-9SDeu*dIjInjBjC$w}{eK`;;d=DFLGBZ`<1U;{Y{k zytoRyVSgO23(3a}XXL=C%Rf=5dteBM;|X`|bKa{Gx!v!f4s~5U^N6Mnibks{PQ>Yq z|33WLw=SU{J$mXwv3Dmd;)LAS5`+WYze03BsB)1OjoX7W^i!MGxP0EaZ%4Q(sp1q4 zFzm@A*&goj_D;()^`zw2c5OZ{SrEj?Zd2toYH?UJe~rKMb*H?|_~XH+KECn*X=JP* z%A6}Wsf*0C9@=}>n`etK?n0G!0k4`_mhl1gV7uRC3jxCK+qM4Z#qQ}-%FL_GB@1FQ z_+HiD(40-^$x1TR`Zb#Nds$^#Rq-~QWFxG`5+PRcQ<-YSX%l38=#jtmo0e)C8$&*@ zBv+#siAC`YGViuSM9xNhA4DvOrtrAES(m&=T&x&to_q0zX1DxdI!Ey{?)EDGeit0>(k!z2P7XebG`W$}hTvnDVi3_FJphrp(w?o*oL8fWOK_*G#K zm9>0r+1rDCY>9FC;3Jp?qQ<^91;a;B!umyRcki~PoO^vtTk{cgd`5E5S8}CbgL<&V z?a=f=UrW96`bqjq6-j}|I=D=1J?NXF%F;kg=hkV6uD714ZYni?vH51hV(a7ZE6L3C z_2Zz|g>Tb!^QoH)o5*0mW%EO)iW{yV(B2{3|AGbb3uMFea%345OHNI?XR`4nT(D}~ zgVz<&vta{4+#jO7ee&7OplU>owtnq%!7YZIyyh$uC+)JgBdT=4#Z}?-^d8+!i})^2dHcb z(xC2PCxI|vaN6J89u|0IO`HO=nvc-T(t1Tw5>!G-oJS4dQ}c?A7?y&YF`BW)qO==) z7@`88Tughzcbfv?Ik|cmhS7gOi}C&-`#doA&pzlA2KPo#-;N)(Cc0LPHD^2Y57n$N z-DrJxfgoWeF2Vq)%U0yJ71W|G1nVo=_E}C;%NfL^abNWG-k1ce@_>b(hQpzTDrmc< zDS52S;qsmzbVR38c;#0AMR$ZK9`IewHmkO5CCG4!6ETS2`xflG?|>0m6G15lU#ut! zGWVJWX;vOcqHM5rzgD-#aWJwK=d3(C77CN*$f6^E<&uPbYxw}0${Y;kdZWjg+!IX2 zn@mOA_5TBN4YHfE=+Usm+Dy z{fb!u{lZk@uCo7SF*jxk{&t$(N`R}EBX&I|!H=@OUmmn#Ta@j&NVQqsYXM1;|y`!N_Z&agG`+B|=^;CK@TbsV=P5K`{wDf(QkqO{hCzq!Jeu1gz^WekC32UJk zhoc#5uy7(jl$Dj4*+^2dLyHJoY7x-mAhq)Hk%f^1zZlkhRK-cf(1sUnloEyx6U(=2 z(=oHL8Mr@|5l?`&mlU1`L!jbKry*;kkWnUz(^G65x{5?;k|J*IHYoar+8IL8wW;}q zf&S6uf2gRg*IKXUA)~@<*6#qdEd(@WR2@AHgIR%IVgxYRA7z_Mf9WD+)}C6mpqth& zEb-kGqR#A#n1~Gib&L9)nfhK-60jZEw86GDJM8R9jh}Z7Xdo$DMiAz zHq?Uv;ubsXRWPJ`VcS*kxD4F*Z^(OXz^JH3`PXTgex3S2$KMq(DO+*ZPB+8-R0*l7 zn%ZTEInv?Pns_lnW-_E_L-gUasSM?xHYvSh-pF{E_LfH+s}W9+aPONQ3-vV=h>_=q zzSjNOcOAzOZaX%?n4#`@5{JCvg5;w(@I3o zgUpnXspe&fOT=uSlD+0}&2Q+yla<2)dS>-&)JY{U$>ZUH7e_Iozt(hiW^1a}X{f~O z&XFOCmWo1_I2ua?Q2dF*a-fB%Z_%b8jwHj@^yj7$c8aj$B?6>H9yQR{k(=KKwN&~6 zgKqucHn*Y>0cnKJ>_df{Qftf?gAegBf7rt)UYy`OnDN+kZxlNINXjxJD1;bVd!>6Z zM=wK**aVB(D2iB$_B{H*G@gC@6{qtog>Qo=7X5Vg};G3LM!#J`_|jY^mRBXP+&On^{vN zXpy{G@>4Z8LACv`-nX$|_hN0R1Tq*2Q7gyO+0WWh!HP`%S35&bfiF|`FsI{CJpLWM zXH$l*dm}BM^rUO_H6BjA4(uhzO`)%jrZ}`wd`XlDenUM=IyV+s$CS{8IiVRo?0+lG z&Sh>jY@;ofjWJ#n$t#F+^xoSDAPB5!J9jZAl+Yr`^l#h9%Iu!bKnmmft+>R3L?)K6 z(9YNqB2E#YP7m86@in#yE`C10>?{-(ypguVUk0SAtOcY31qjs#OI-{eo7U z6L@N7DhSMtfn~HLBw?Ie(t@{f4y%eux1hcv>^O};aE#7Co-l&Iosoq;Cl-|27sejS z@^;Iw>)IL9ED$5V$66qOnJ3f2p&u=m#?6Rx1qxHUebU-tGlz#W`c*gko%vZ)`kL9~vQ_{HTuH zPIVqnU8&1+Y$w(vZ8DlwY|hmGAD+GfD$C}1`yr&erKC&g?o>irLZw@}Lt45U>6A|C zP+D5L8>G9X;oIl+|NGAIs7G(^o!y%YuLGfsKMpCSes$5@yU7gU;S_;4=bQ_Yhi{LsNeYa0YB`n_}y~QT2 z#h@V4@oS^@ZR+N?>f5*bvG~b>Cr82RHPzQ&<7YV28q-*@RLK!axi!V8vWzg|coe}V zvt^29(uUvp(Y2fgPA+V4a!qtpCyn9DP(KlpTK zfws(9s+`cnM4P=K@_Ao-tpM`5p{x<#F=t&cg;j-7gN~Mm9Y!T7jF!mdW4W^RM_7;k z1=Qm0>@8ni%QG=1Y6E5NXRY*uyB0ofjygXHx+~r>5or>a()wOWmp5)OEZI>_&-v9T zuOL;XbDuYrJ>FB?i?BZh8#fEAbsO)!s20TT^h#Ut3x=d;ynVJXVixfs+V)B0){K9O z!EQv}&Jwxn+%_pQOI6H=;yfUtveYTdZvgQ^?1(i=ReZ-w`lvg6oz*0xt!T|+mqK@c z{xi2DwT09!{A(^YNbh7~iLNCFS7_#fdx?AGo2xxT3&FY4Mih32+;7Ejey_w72R`Xq z`_USHp+E|u#|`Np=qoN;I`Ty{E(oyr}K2aY$QJge3}lB~h(!QDw%u1$m` zE*18YJJ4W7T2aJ(8X+&O#?~#Sa}#6wpnOm_A&PVU^^H8FL!vEU^Iq&xW0Ujr1zzP> zj!m`auL_SxZF%C;Tx<|7m>No0d9y3uu&t0=b`{sX!}rnQC@9`Ezg~b#{%Bw*qqGbE z%(sM|;UbT_?-eftbHik7`aZMKhf^b3g7@E>zA$|K9&jFBnQM~&d@aPmmV&Ard=}4F zqEaX3R>!}zcAmuOpcp-indY7?8{%$gQ=!^(MNjiBjv-M3$-)y6no|D0s}GK-agZHDK*zT;%@$7?{aU|-?YJ`&hr$RPWPu|;J~rftT6rEv#de) z^fa|u&sSy0VZG-?@^VtPHBAzSPhd;LmFvjtF zo(YQ|=q_Vi@9fV9zvFHlo^rpx#E*owqCQvThVbN{y{Ytqhge?$KvjfkjuUsluMt z?@>nqol9Xw2+NuE>Oh zg|&kr77$XmLrh>wa5miUWOKjx*Z&W1)Id_ae9ThynPU?;7zhnAPYgw%DtWsJKhpWr zw^0zoK-c%W$AvauAD`mNCX2q6QiC@8__23IdPnkw|J{ZrcU%1)KPeW4E0J(i@wy!m2P{*jyIICV~uizdBTbbX=Y zYE{aoV`dO@FT8S}6>l=@kmctKqp{0#+JS9ObM!xnJ^6#Hbxw6k3!G%XE&YB?lhc-n&gl$YrO<{_m zdj@BA<`$!6HbYJ*M3d9+sw3U8LWA|YYt}uJ#EaXM5;_KO6$(@Z?F$D68AWVJwP=ce z;^J#T4K93W+{o%#GjIFDpLCz^U;f+C@DBycjpM-NpW(x3GfbEtkl)LxD0>sg$j`+z zW5X{P5&!1HUM#Zjo;$*At2S>-4!CZ^bnAh(I%)G2(s%w=B=QVBc1e5w9c`ClFP3C2qm{}i<96)D=O zzYT`p)Ws91*N@%jMEwW(kpqubO%W8U^&MtdoQCr`5ZS>|yLjcSKeEAjn!#VJ7`t4@ z^BgaM4}95(zV^@CEwwP;ZQjhsA&9y7Rx-!1K44~&{2rw3`7J*pHngJePKO_$r)FO< z&YjSgG3OZHQhj!s-aD%5iw##HT|tdE_INxQ5=KkRfs5D_jhXGM{lOEqJXcz$0H16-{@MW|~M2GC* z;YKBDW^4pt$cB_>>-x8=Wpm6hOe3)tc}6Z6xzx63d)|di1lxA$B(YeDd|Wt^XN7zC z!OQ02=zQL!S>0of4pPi74RH>zp3Ie%NfNR_<=e|D*V^;X^Nl5o!-9TG`RBx;nad5* zJ46x6bMYDXO&_kybHyyz(qV*wb{xsCDC9~_{ro~g!fL>++&YAFF%vlV?1=j}vDG*F z*yU)ZY|D2YbDk_kGRDPBzvwYgp|dYqOo%ZA|EiV4x1TIZ)=Y!r%~3%WfVKWdyh z2Ls2#n&tial%MluiavuwMQmUvr4yHH(Z^{6ctHgoNIRk4wV^d#>9k@Tdf+V=o*Y*# z5|#_{jWAh=nyNg}2IO)WQ8alfN>t`v7*89#!^@Py6SWhvs z5YIK$7GEva&WU8k6MW)oEjYo*T?sIz75@4DTLpeRc%ziAP3&AujDT}hSi6H zb=eax8mwEQZwu?oIsElyFQC1@Q|a)gJ=$pXVD~`3pzkJ7-e=2o^{H!RLL?@H2{fb8 z$h<^tJGnWOmOHj4y27W;e5)>GOh>^{N^v&a5FT?RYn^rDrnNRR^m}^d+naLzPh5hs zd_)$EfvLv+VY=vxUVfl-+%V_8s=?YQEbNKVsWY?3ymE^iYjmFVsTf*)w!*QwF}sDc z-+A2(7Qa)e!M3z9U0Hh3t9=cLTyfW)BKUIT5IM%bZ_P}cpB-9TzyF}a?54-nibR6tTt19nP+a+^B0P zVeP)E%kvj>R!dDp4#mrdm%6nVW=Q5*jSC3^-*E%3md|vZYMmgXx|`VxaVX_p#E>H~ zalr!Gj%+6p6=u*DNF;Hw%6|%6^aR)QrVL8Z>nD(rvj3`M1@`GacaR!(M}t)B1vx3J z%9HnHaKt^*;N;NY#7Yfq$t4!LeCWP8J)hlQ3U44-hRuGLC|P&QwUH@Z8>)^bwPlc2 z{q%IW0r%U9^Y&eFF>ajrqP)A9df}1s(O~M=ygBp0{&#o3kXo7e zH7WK5wsCa=8Vy?GX1a0W4)=5SMWcP!GV1Xk1Xu6%cQlo~4mqZeLws0@CF|+cH^w!_ zv?n68v~0Ss58UhtKKzFnSFaOH{#6 zh~T>7zs(Y=i<~%7LzvmUoYP{befLI1HyS9zCgFo^au?fMaqKlI9+&{#SI%h0mp@6u zc}L$b`GP;>eo{HB{2EK{E;5$6uS0APdu65HCnn4GiGpgJ5GZA6M@i^7gC$=F7AzY} zYk*Tc4T0dX#6)0ag0-*(1(#jlR&A(p8_U_)SMTd8>jj=59Cw_EAf%wcG#{ISPg(k- zVtKlU)`z)CVkTRSF6d92;+A7uiV!eoCSFT3`plM-vK^C8s{nwd!ob?SCF6+k?hZu#@Z0=kSnP8ug3`eG&<2@S*m~sg+g+6 z^~d+q>mgrC)fX@oeY&;e?b89gt@LX%#Y{vv(UtOlwR1_0CnRzTvU7+wI;2WQ#UF*& z7i+4H%Nq_AJQP@tliXVFAL7bEmd_5M9It1NN~&UV$EL+9PZ#^&f&_cn&WBfuK01#L zj+TXm^)eBO6@}nYaB1-77B?e{dfjRLAxFgVLs)t9L+X{)`>4nB7p>=*W41EtDC6j) zyE6r8PYHgoH;WYkC;IO$CE~V~4VIBwzHFtMUU%K5iN`3I_%C+`$>*VaRik@0D|l6m zBn4wR?3S>oKBI6bE@6*T_sR1Ry}2UtjTz_DVX1dk9s^)dRGSw@pE;=_fR9EuaIEn4 zHcyoB|N#m zC;VcDvwVQU^9(_uG;+scr!zcLmdMT#w^#YgfP8ojajkKSbtT==J>j=o>ZSF$0Bo^a zmjpE!nG$Cjj}gm-zlPaQie*+_?3;J_9zs(d7HcaoROO7_vAK{^dKr&|TG=*BeTYpo z2^kp~t&eTXxC>t_pPGv4L~NXSrs$+F@IQ~bkkcvDGhDhnjnLVv&2u8iYSWH(Ak@S( zL?bd!n7j`#I(9G(!k?&MCB1mJ6^xrgOL?T8R*WdbUw3AIxnRn&h*E{8(Avrj9Q)Y7 zxYK9$7%T+or?o5gd~}r6ih-}?wr8BqjCS*|b&=hjzv;FYl6)cH5T5)Sz*nx-= z0xyAWc2#rR2_e;x!9F}p8gCAb29H5d&J^0W{kd7Az~4`O1!T1LkBFg^&+yU(b42qk z4oBTD;dysyI+x&F*Uo;K07d^9W=yh~K>3AcX-i<~ieqV0375u7V2E;NhEA38vzxv) zdoHbUC;B#e5SqZ4p#|fPyA9t|x8o9A_+0wcW#I75d)tNZIv49&*w}jQit()=MT^5e z&E`mlbIVFtk09lTKT-qRcJYb{!r@KmHY4c(6?I?d3BSgQHLb}i>7+=rG_PqNt<1ii zN6k$Vr%kZtmTZop9L4p8c|%kf*{w&x7&WuayyK35n-H#6SfRXo`YWol_(t*eYyjn` zZV9!aS7&seX77IO>a_EYyytJ*la-2Il8iZ3;~ z+=-jb1zVBZpySW>#eL-dw5mv3r(K|{c4GEGiohJ*rv4y&qE>iu{%W>F|8!b?7m*wK z8nsfk=>-f#>{_!mJhk$m*F6}0@J=!NmZU9t%Ch{(4YB^WC*qo`CrMp2n&IyDBPJ88 zH*wGY9%Gl2hY(vsm|&H^I_{?CZ(PC2pR!7Smt%Y0l)1Bfv!?YU3!l+1``GdIZ~@i* zMShcz{c~5$MV&YWrS(!xtXXftR9ywqfH$?D-(^K!_Dm~8KU?4t{d#;(`-RNaxGobx z^L`~!CrMYLJA7q?NO_}~^7uzNCT9)j&e75EZnH6oBgJ`v$PBs{N9@$a@!I9`y>Q$V zW0_ea0>o6;UAWL$`|QTSy|o_EkSWFh_>;Gz!U$-21c5;~7JTJKCOfVwml;n{VZ{?w zy-Zn8f{=ELk&#~V@X6$=`>)a8_7-gocDLIC22R_8#=Nli7hKwR+Wed+$co%HEs>({ z5iMRkhevy(CUV#Ig;{IxF-1m*+j@Mc+%#FfVD`fG>yQ2Lh4nXS-LTZU25Wp13ULxfnXDBZ8nEBWp3*Aa=vaq=j5Iux7a$JINAtCi6f+4ZjSUb{( zrL`ag64V{pR)lVV`MsXhtD*|$ZC94q&~BFhX{6?Nq5JJwfxn^<2zQ|mM(ltD&LzjX_)6N2sN8<$L@oH!!H4m!eKtH z%(Q1b9sTexlzR#O0Ke`Y1GciW4GzZZX;$53;sPu*KSv8Qk?O{?52u29_%u82?F ztb__{usaj4>3I`#Ke@lqK=7s}5Gm6->KGrnH@V=i^u~Q@d&@R0VAZ~7xM&&VGlkK$ z2TO&|JHYSW%o;K!pZzJWL`eK9 zuaR!ugJy1aySYM@Ef1MMRd;;>$vMK-&A{!On<%fdlhZ2bpz+#6ST1@kK+Kgj@Klnk z#AR8k`nxX-T&zQp34`fSTPyd`OwWFj%6a7#3eZJ)0kGQWNIjt z?6%c0Pv}U9Z5{DRENLYKlMDGWczHL?Uc6}#?)gV-PDA$wBt003YKU^YK z{XB+88{~z+DK*KO<;boavgYbsxsSHhyf6|a!fnBOElX-aXl~U#&|*8XU*|CQ+g3aN zhNV^ezChG@(E3k7>s({lUg@A)(GSEVI$b4u1(?mhm9}ccc?+)!-J`*+YI6~Vxb4b8 z-m^LDy}_!`Bs_OB5v?9xZGPL@$=2AJRAG<5-z{=~6Dbz;6+m)&AnT__RLUM+P6Oq;1CaoTUyLOy9p-&VU~OOYxh zF{s+ZSzD^lk|FmBXIA{yRV{nGvEsczMP3GHzI_Z1E3S_xGWH9 z{-Ci%_SrY>GgCR}{~3g9(qoq^rTPpuXdfY)_tx1i_?cE^TL|;YO5Ek8Lyus@r{=MU z8_Q51GMreA+T=45NW*fyCN50(w3$fN>1Fg2)saUcuaC~@AJK1T<8SnzUOSE!f2Tp?k8eH;eOX z(S(^pi$^cf?*}&#Kih1CRyTl#0el&Xplnv|T$KTGt*G1a7)HsLJH;kM=#-X)Ofb zJ|_KHzp2Au74{n+sP0N%>x^taeDx5B%d*Yfv+w_LyMlMM&#YCSo%?4?uMMs}@%sy( z^~Qv&<}h*O4yjg>yRxh_Q^(Bxpw=DS!h!lE z%~J&n?4wpaFTaqueIRh(aCg;3PrC_U;|F~)iL`X_MH`bsd_hf%d1n=GsWE&pezuBB@)ptssi?(@szDoau{B8fk0cww?hVX=P zxYWq>48DEcCSfr*+&*PlnrjD^8`;##y?VgPsr4&#Qn5{LL?+!w4!^tOZi^Y6q7R&_ zC3R$nZ!Ou}TiiMp1AhqB%;J3LwR+3h{L>o}a@V|=w}-q!vdbIS{i>-g=+nvETrK~n z{;eoMthSDk$J7I!n_`|T#^d@zG1VKZ|J4G_O(q#hX6@fW+6_Npi>BNngIjNB?xN)- z*QXz>c3a_k+MU(lYrRrKCw2osV?fZs(yigE3>!u#9<>Qy>`;(MRyIY_%uF@mLfvN# z-o&pf$I_1PIPYQD)99GmgBWIDFIQ{ zLxsytyFAMJN$fSWP~Y3y*4iAjJj3gLT4>wmyxuauV5Haf(+IKTYZ46P$@0#+(WnqH z>Js7Aay5F}=Y_-TS*q3JPtuZJaH*YxZr}0|g3Dg?OedPSrIIM?X-22kIcr)w3BezV>~u})j2?_x^l66|eni&WY2m$*Vtsg?3& zH-fjp48&K{?r~TIJqp67>^zSn9rZP{Rcy6t^yR#GGr69H0U4m?%ERW<=I1&7t zI$9MK!4}k7cXqfiP<6-J?m1FgAJCSUmw&Rh?*4r+RkloB-5g~Z@^#ATP z%byHEQAcj?$oPVxHECmKGFBcsZC>hd-j6okbUvNgD;jfVm%(q1hz^y8#s5*j~04F|59kVPYo)+L<*EB;_Oi>$Vy51;yN9FA)sl3l-Phl zeKOEs7_FmlO1`_{sL-Udgd=?TX%p@R1fu4>#Tl~bLV|X+=wJAFQmK43nq@RKA0i!W zD_vKNaeN&)vQA=4_Ui^SLrVWGnIh?9rQ2DT&zI)Q*Fv|`yz9Fwcbt&+Z?;~Xt>)OLXrhmAg=tg?umHrl)x#~CNe9^*kE3(UTTF1@($=v+) z6WIfQn{;)gC(lgF^*SMkh&0PeWE1hxc)YuMrch`iF1>HRC6EN}JS|v(Nx{<6a-az} zPa%m#r?W!mhZL(np6?XyUT$}!JBQp{``0iv?wrdJ#=_c>0Xqr0tZen|i+IQCU~0#L)@8&FUt}U+opgCfaj*C(G*n@s=44 z+gm}i;)+A zOd9KJh0kwnwg&B`buC@jD|K7KhKCiQ=b~qBe9>Z+10VRS#(C7fUgiAebM>Q9?S?uH zJfGSkRUV%Fo{?f5chMY4at4$Pe)hY~!U++|EcBmF3fmSGyWIU2&p32yD7__HrUct= zh_ALX&n~B~_c_`|hW5j_x^>UoO;92F&$OzV3B)JP(1{wR^IKS!maZ>7G}vzz!_&xF zjo($&p$o?nBoA$s`J-qk&=7vm9KqBAbOSrb$GvY^TWH)FX&_z5&TsEKT4R{}PzhO9 zPu9A^(C9C!zf28oCvXy>HQz3teZUQUYT4Vp5~t!QD!Ptzd?L6K`$MN2XU?ftqTo4x zCD*7ZqQSA`?11|z%1c-$#q{L8`kt-Hoo+u`c@SG|voEVgn#x_@@%DoNK0f~Sm#Cm+ z?A1$m1CEr{^Bd?v>#swXa9uw-q6h?1(JO99yS~<0SWU-YEsj=2${D8T!G=u!(_4ym z&0YrJrg6GrpKh(5u;`AHhEnF&A|>yYg^ee<)dK{$BS$Fe#!pE9C~r4+;wC;9=*~{jg$1 z)RqN)ql9twY@0f||0K#&{#IYXvabEbA#1inKi883eR!gCF;w*)va&K6mIOOMjHOi( z8Kx#o`3#?G$Nn9{2}`roU>l~Sq-2`nj?C*pm{L`>h$fIHJb4V;>U%o>%vKP>j$HbX&a{MWx#l!4`$;B`nnj*4w_AUz8r_~-=OIocWHU~Yb7O2 z(DW2EAE$Qbr-e=(3;|VDp6@f2dLxVps>ChuIB|wPirhmPt6N+plWmx1-(Dxmk33<- z2*^mX%?;-W;pY;9{i@zKT3Z*suL4}`D5#}3GF(qBl-x5I{5 zPu4Lky%AmzPnIhzh;(P~dr5nyGK?!2#&7FKGEpSqah5+F<+weJ@AyIDMA6+o1Ng%o zJ9#SZbu4)kBj50RvX z$a%Nbw9o!x*nAJErmu6fLn?4!PsfrGIL|zze)wLw^1irFl#W9evj_4oKAw;|TVZTM85tPKKkVQ7{elx`dj4c4?d_|H2jAQ8R$=*? zLln;AA->J?&DWNLPO1S6q2ht#TNY)t==kO3)MOg!#!433%9fUhi3AIRAr8GR7@J0X zIWXXmCL<%`@~yf8*6nbAUUXrJUmsnB z%uf;a2pIxjn%1lfz0&hKAIZ(~uA=fEA5=!`*}r% zkcF)#VIDjcWf|}!fbtL!5I}bJuVo-r%FGLKKH!z$s%*NbPbidDy3l@`d0#*LyWbI@MrV!Rp-Jm}p8^sRBd|~Q=X#R$g z=L`Uq+x=;;GYJmf#}9gam*Wb3R>cD8F^D*4kr~q;NjR)0{X6tiG}S<3kp|6DZQfmx zEKIPiCR%z;eWl2dhamh=b^JK(Xxyo9hU&g~9^N8TL}!pZha*^UH!5wOG42`s7@Hx{ zmIkNLjPQG#g_=`x+0KYx$NevqF1-^?lDWliCOjC#Q*;{bV1Qg(F{0y#TY?#gFFdgb zS+sp8cGafnT9S{;=}J)PRiEK}OgJ2^)n_Y8iL|KR{R`nO45fYg_~fb=XAxgPKd$%Y zBfp{=sslPFPFsVjR(Sb-3u7t82Fx#q1#&kb-fi1FWKNteq}{At*a-C4YV==ui{`sB zDop5w6VFi@_`{w>QD1qRhHsuQ2 z$%6hFetVC-JH+Ykj-ryTsJM7+3A@@|Hew?7qacymCoMx6W$ZG^-c-adq4YJabQ9}m z5O~nbIZn2mOllWkj2yp@M0nbbgin26?VKXFQi$u=TPSDR($W%?BV;FE8AA&Zm4RU54&Me;fIe-B*#PCD#>ZH(DCMZbJhAtxbAzq!pznvRku`OLl4 z#M)aRGUp-mc)jknlM@Us3kT+PtzBL?Qti%+eUoPA;R#Afc|P_whqRa}J!U=O2_2xk zG$8XC7zhIseGW(mlI7{9vS!7lQe(y$DUyBK~?dx|TaeI|sF2C1n=O>d7dfkEo|NpiNd{wjDlxlTtKW}2u zp%trIc^MBHHFbBtc5-#?ohLeHEFIxljLGapzBQz^`Az-hGbwp9Vbt8*#Z29b>gZix zy`!V8ep2F2I|*vgxY^y^9gG?x z2fCq~c^OJK@tn!c|Dun#Ep8b{IK2G(*U-WOg(d0b_SIOa_Hpxeb+M8s*piVzs|^_a z&$q-;_Xi{E9xJ!ewIp}7E9-Q6u8J7~U~*i=KYoz(Mv-+V#AN5`5STIJ`mob(A4 zS&^TMkB5`)CNmutGr)cW_Qu&(FAt4(`486jenPr)%* zH$4AR2MhZ7{cQ^kw2`Pn}&Fi(e<2yS$mt+W1o?*1?fJ-W07uvRk zk2`RadS>Tyj9h+@@uVqSaL5Fjnwp;UQAeNHa27BBv&J4K3Uouh9Cif-g;X@A0edrY zW$$AltTuaHZEYztGqawj5l7~x5wnTX3-lJ^{CT!3o(6r(JLVIjQXai`?HM=5XH9~7 z2dZ~!BV+4Jp9?1#-H~aMyRfadzke*Rstm2B#bjt~qUIKGzhD5PUmsVzVNV~$YFlaB zWvBhRuzgN`!=(A-+3NZob!oJrp~1+-XTgzuVDYa z9ad&RqWckivA>#d$27)3FrM;BvWhAR0`7dT9hK6YO~r(8Wor%$I92&zd&JqY{r7M| zMMo!6pDlT6pY{)h&}HnFBHqjNQHv(83ds|P&(_$#XDamd^~J_4X>!Ny`AB#625gUz zv9Zt@_-NuMC5XNIEnXbHv*L^0&$yHyVby@dgv+Oye;Y%hINuV%L&*WSSo-69e}BKx z{gR3IjF#^9NC<05NON*3x3Us5zAkNBF~NvPx98aYT$_U+{PhKn43z96Dhi{vp~3Me zV0dVFxVp|CrN`GVA*#?}=WSr^b4?FMAD*;RtD_S$txUa$p{K|U80|LimQTm@!qWX6 zQv5uZRD*|K77ORW^5Mky2ej6Gp3Q35b`~y<|A=UyYHxQ04`X$h{Ril-T(`c257Tc` z$6>-v_j|JJq0pQBui)ESaWhQ4;Bio4Q_ZL2cY6kIH)x&fOV{Xf0*VO(gNH6%Ry>?V zqm)U5-A%Z^I+E4Y0Q<%tG!)eYz`g-+f-`wEC2V)se9UsR{Iux{e!)bfsiR&cquKxypCk4ZmK{WfE|*q zt_?ezF^W*!i$XDB%h5xl=K|ha_5!CU;-_xq4s8qsFhkP2>?Cu!`pFPS$g0T$>7guz zP(uZ*ec`$o=A_Xmw8&k^k$~m|R9C^;F%)=ja!w{sM$@~*NQn@|7bOF=w>#UAh3Jck z(^8`wZmzzC1&1}onOsN{#vI6?Tr6$jkO1U3zcw90bzvEiO6iLd@&xCg1Y2o{_)}n| zjQm-j%Y%MT#bsspMLVyRPt`Ovzcn|fp3^(M5h$l7#R%6$Nd$UM1~LM-^diN}%S!`q zZ}Ri=^V}o}zi0m9&|^D54~K-{pPM8}Ok+*@!t%=a)q4#4obWloxaAB0Ohxw!bs9a+s(BrDpQOrSd_`L<^oBd%uQ zaA$81rv+_16vPl3D#{;K>!e&=c>(KGzXkFDR31C50&fsP)Vu7A{{ILC-p~?JmJ|aK ztm^?^xL+JU&=f$J1r0?27gVS&MlpOBGWwrIkdS)WHE9FG;dA+s;YcroR2(KTpAaYF z?CQGyD-<_5C1uSDdEj{$GF7C$Ww3}nurhtn5QmQx1G={oeaCS%Q<8dl1Q?mW!~|MlzF?~dDwz)L}O zE~VdCf{*kKA1MJa&2J!#0L^0z04)pfXE8T7pV2Td0Ja(Wbx?o|AIfS4?=KE4K1^K| z(2A_iRvA_G&cSArgOI4|>3BGu-+wTP6;&78939w`g@r{YXe9~8gB}fml|u!}uoi%k zGGq!m1Az%D4vmZ$0g50%Hk6zNuz^$+X*iRDHZB+sQ{^T2q$yI&%~H{{9uHCV~Z9 z=H%oQqKm*7fv2%x#iKD5n=6ZtJ25cW z+BrPjRF=;`4(@_ZZDxOS5t$6=vxTi~FQ7EqR#Z-h@uRqk@70Kp92v{+tG~tr#=7={K<}<>4Wy&5{HV+z(hFc&mm|%wE4gO7W7Ut_tN- zp|0!{HiSqfri94C(vmutP&|KZaxwt0v}rdx$zG@yMaa|Pf?Tx<4iQ7&&=3Hgz~6Q_ zObA3vkf9i`x2<37P6$nfa!HpIL2}h$-AhVhM1EW-nQxJ5@yJ*M9;G~Xppd{hkZvpP zqyY!P@VwaF@V{6tBuozc5Z25iWgVwXG@P=tKBeshm{NqkGkh_0l>qtUzt6ik?faLV z#vJxX0T=*HWDiLJ_!u9!2m&HCjMAxrJ>+q&&+lQZD#~JbF3+|Z7;9rBkcz1!Za<<> z<&|IsVdv4J(L4D{vWH&yJJKVq7Lz5A1Ko?p=|Z6p`3}L-G@-O?C4r!bdAT@oR%XbF}J&<209Z-z(XU>c70>EKtaq4)6ofrf? zMyv%{Kx%3#Gz%CAfl8?_FQ-(J{C&>KPg6ol3a=aNufLliB6I=D$qo-ek+K8|H(*;% z8$u|ZVsd8$?S#>csUAW0H0I~_;iOrB`%dJd=Rcc`!t5v z*^MXgS9y-WZ$S;3zRnd|q8=h;#3!DoqFbp6A~1^K3<^k5k z%lA6TEO1620>S9X`%Q`=eQ<#R*a=jK6n7vC0vF+q^cREcrx2ip%2sT2Dgq$3)+kLp zB$JY&L4yJ*V0UUgoy366^=F@(7f<;&GzhTatoBDMft%D&+?fTQ=_Nf9RM7;-?c@>g zz|X>VA!q#aDFLnjod^>k;DNX+fxFn<5BhR78#LgRqrm7x&_nY7q67w9j9!|5qDfI; zi76>XgNTR%uurj)Gs?vQ1|TqlGGG@FQ1Ob5oftV~VZxU~=-s9VRsd@_W0beJ&cAQd z!JduIWXPt$2oMv(JOj@K4w-^8J3`X1Vm+{qfVvm#83fTt_3!L5V5ZqLteFEn(7|$` z2OI9;0^KLk5|sJl&;*)eb?hMzgiS7Y_=4q@>jqysO=~)A8aUHOaqC^Mb_t=+ISIUG z{i0^<Lv%XGlEe@Slc0{aGZL_$w53pxi7b(NFhfqxvB+MOr_F@luTYjCK^ zmOh#ToFS;}C4$;q@4A5{B1}jh+&cSPDr_L{_r}H$(BT-GxugEW-mWz);L`H|ohyPrC4m|i zh{V5M6`$-J+mAd#f8+$SYAc<5S2`(;fS$cLd*tCBRpcpNh zkd`XflQxZ$5}2wPNaOUtaT@?tP#J3kBqazBgn8BtYDz$$l|FaqLJpOY|1FQ11W@8( z5SC@m<{16cb~cP28h)S)o-)0yRZvr?PP7;fAO+e=mh%7CTntD6VlqQu{2*Wl+dT{n z<3Ab7^8P2ow0NE^0E^gwDcl6sT{jh|<|fD$@Z&lF6bb=rbzF3DC~@_khf z62agc{{w%H5kOf-dhm8UK)I%dWG=Q9ODzpTf{+kAss%9gn@sx(QLresW$6^)lxG@a z9*C!ggwY2~LzcynZUgwpci{i^#ut&tdFx%2ss5#38cNE`d=&8^A-+55p%aBl+nyO! zfUy{Ukdlh_+`WY~OjarlST9O9ObQ_BblK>Oeb22^0e#s&cMOEZ32>zEgMtCDWAz#;%N(F-0WK2! z=;GqP1aE}bJCRA2}X0r5H^FzJQKNxXmg8lJBsJ;QS#1-qu}BA@(ED;(6ys3qU6nUe|hHsRg^mO_YcIoYpi47pGs zr4<@ONXTSiG8nb99^;<|cC4Sa8&-j><}tX0PxQl6{@(2$B6BliqV7{08w+|q<#7E(oSRyLO%ZC7vP5`GA zzJ6fz2=+EK6Ws0JWyl)546~d1mGJU58Bq&Y?`7hP9I7-Jq#Q>9G2R{Jy(E|WXu~klI zt$5y-YrKAjD;8(x2S8^E7bp&F?i6T*69_Ob4p;^doe2}VJ%RClp=3Gha7|0xLcc;+|2$4zkV6T;v+o|Php zPUnl4hzllU3nugrxhVl99OQeQ|2P22#56o*Xm?VLQuPyy5Sc^RXdgt#iGSNo@2rvQ zk~@h-X(abv%V0G?TBVg&tC0zfg~ACfiJn2mrIt1*XUY8oK^Dpbnq0mP#VLLm&c_*zU52!cNh zRNi;C zkJUmiD4ubH-A^3|1vSMEm4SEw;X|au;(h^)ICQD0^XD-1Knw-(&&iC>!wfj#1lrHQ z%G~CL^>p&%=|vgl1FYhs=rJN>(QDt@ZR7#7C-Xe?>ane;yrPHqP_+G~?N$g48!prH zFX*M*c9#*o+VOOg(>UX4;(`$U(9t_e`D5+sZx%62S0N1eyaL*(+N(q5nGgUuG>Es< z{(~amHoMpKzAd^<^xPKWJ0|+* zNP6=vngVPSDytGKMBCO4#vkTti8ElApI$fJ8$Hv<11Aw5|C6~@X9pz-`QvZBY%i^s z5j|&QaprX&PwN|6(7`%usI$T3A=3jSkXZrdfn;@YXx{ESJHVsW{Lh~y&iax2@knHwDmz+x!Ev-fw10B z7!f_)J%!g~T|243q3mAd0&7-Bz!eJ`KnAV~8Y;w)g7LHf)_t(r&UW@NcGs`lVxc$b0 zb+OWUr`^bN_j(5JpT3mhsOqU*{j*6xZA))ai7JB(o+kPCm{_73-%kFv;VYGHubin% zft!K;o%rGS^hoBnJ4S(}{Miay=V&4cSF23F^MDK=l+H8FF8?4+6bYhJ?=BJ$Fy z5VMeJ(O4f}PVzVaNNlm~%M#QRShy%*Lp?x}`eE)SQWFpqGHSS&Xhlx4p3~tJ74DlBZ|BR@F zG&p~7IdPS%?nk=kxy?pL&9N%6;ow&_5{d|7l9yWZe%jL+c34S(ld>_*SNbEd`RnV2 zq3FsEXX;$`a?hK+I@Fi>fS8uoyDUHD73fIgWQW)k;-lP!ekpK?LZ#dJNes#KGUWxYg>$8K*F05MANutzv>V9yuzD;+w-zg;%sh08%y7GW+n zYR$p1{0~hLmC<*qt)eGXNIFv^)aw)@>~JjVpj`)ooG6{w^79-2VEFL1C^JiDk;Lr7 zXCn1qp6$>{^Hsh&TTSqrv?QVA}8T;~X`Tb+x)x8sw-o{|t^_re?{VK>8+kbX#q4iD? z%nrZ!GOZEt8>pRm-$yOtifx0_z{7VEUDZPsb9H#y7603!-bHnDQu{SuAC@j?ryGAfIWqdvpkV1L}L9-oH-#8a1C+1zoQ{~J=nkqg%!RSZrW=os| z2t$yK4)L;zGt7>&%HUW?HWf5LYDRl`PP^SvzA>rhrE~Meo{w2EL!9aija#73`MEg- zd38`!0Y_Lob@{U>9SUs->^wBE1x;Z$&T9FU`K6^QmMHuLqxlqwvwAfd7Cr z;p4;vst^E)b+4-83xC6bBmeB30FU|iv)gu`4f}NR-i7)D2&qGf4M|q+AbGh99FI#Y zC5?XY)d-3nI$K}kJ4h2Ok^An4e5x$jy}rJ#>N$&tS;%e6h6xh66sPIl{7*A8V>IET zPhj{FG!n`yC^%iZB(uQE_)Rh%yDd0Si_jRNEtb4RuwCaX+-0j)R$M19>+9>2%_QTx zPnwuy0_T>H=#p3yu;4K-FtJW$MxxvW>p_3K9AB?0ee~Xz%^Qt>Vw`R+W5Dmt5fBUaA?dYqJ$ zlmgy3Qtd%G32>Rh)eW&PxLqzHLGMR-$K@xFBZDI54?MlV>1@}eY1&!LN0|Fv9+~Tf?ScJoejgD1WnB3Q(@5|sZ9nGU~td@DmN402;11$JjS2%!(laQ z9if296A@{WbH|lTZb+(HB-q;+w_FegO$@05u#u6Ue>-0|1m0#<)rk#?9(os*(W7PI z=6w)YKTuX$!CTAl$$>UaPUGLuAA}O`>a{X-! z&No~)cE_$O;JND0A1HhhjFyJu!P%a%Z_&?imC$}CHiyvH6nD0F1cUUvc>_jnG<<|} z6CG%m8~Jmm8dOOKGR)ZF;rYSuK7RyJ{Y!->enHCM6l~f>a~^X&S`lG+g6N|b3Ms!9 zxbN&3W}qnWioaqQ4$>)@tq$-@4Jtm6N9fODnJ|sb`3bwP|MACH6*=+9IBgp2DwOK# z3oj04CNVft)wI<9OiR=Ii36FvDjgQTeWRh4!oMUS<5&I+Zzqv4=+TiWDh|6F7Z=x; zDin67zpd;l6hG*R{&leA@myKZNJ<^HNHvqj6!k~J*XH|TPiB(8dYM}s^yX)^J07v9 zKUn86JD>(J9O*!x8pD|&@VUBrxqwBEPz3Dl?IDjz0q2G^ROO$XoD7)ELJ**pttj_C zNcO^AcqaqeU392aYF=nCi{e83HC1zK>(D!Qc7ZS|16Jk*f_0uTMGFmOg`ZNvDgk#1 zs=yP6<>L+9!QO-aLf}uj?_DdW8~8%OJGegUSwBLV!$pg?sHGwSVPV?<5ub*300>an zAF|TNo*w9~imjVFV=mhOw-2Z+U*D7#AEwvtdX%@cXBi}_gm;@&Ztr#Wa zY5Bs%Xt&^%D~h>N(ux+oKs~xS!f?d5u`@WX)5bVcheSRAe`g#VJ_0w$1^W-O8oOh_ zuo8HoFy&EqNGNU@p^$FeINUp1>y0B$)tF_f&vT%8HFCGC?9UMlK-qf$$z*%rU4hTX zo&BnHg^wXvONw2PjuIl6mhQE9jxdzE6GK-Mlwu2e8#cFMGL0!5Tm@ z4W~(VJRCL!C5EW%!v?dUYlMc@W2xwRnw`|PwB&>QxE>3}W7F*W@{w;oa7MOJ9YI(T zhL_cT=jvvK7rZCYo`9+(62@y}Zl(%Fe=*=%@P7bCBQ@s_)J`lYr`|mUD$_W8wM zwFOpKj#DNgQmX%MTWhOf7%xYhrz#VqZ0^N3ej1)KXqF_5Vkyc7W|CirBXi9#g9y{Z z0hXdtv{90!$+~r-A*Bk|kL2aqAq9H@ID`&mG`RCyrdqhwi^=Pwof$d;A|l{IW~>D)OcbPh*DLkPrcq~Q@=K$nXzwvac3 z(Jr{j)WZ@C^n|YV_w}`yY3p)up}~}sn+vkm29&VB(3uT9G_W~v($MfrK3oK7^W)Vr z_%rO9N&*8t^I}i@VY!cw#2SBthqfT_+nLv-AmHf~RnGXxKX&-n3ZV$9Ul3lnWz!uT+vLMAhVm3tf>CP8VL(EOpc%71nEM!9#fG=CIu zPK$W$$fhPeB=5fHH+qS?L12TW>G4Kc><$?t)qiDN*v{5gd+XduH^F9;l$1&t#Xkj= z^+UkP%olWPOM@aAWE(%@>^$EQq=VjhK*!zPozb~_a(dcXjd1Qwfjtrc(_f%PLnaW6 zZbwJQvtM9%Zunjwc2kXYm2hVZbI>4WL{2*5@%bmV&N?bgHNTfEd~vtHYPu0KXHukMA-MM{zulQICyHFBTIax59JD zbEVyd(W4Ow5{Js%?O k<|ZOAqVIh9E^rLC(?l<&IQ(d?4az}<~}36%WqPzZhUpVvGZ-A{W6real=z>OEKxC__(56O zZ(yHkF(R>WD1ZYS<|GRU2-LvA9DW^p2iW5WIM-gIG+<^ti8S@7*pdK9Vey)Nx~weQ zFBreM&xAk-)b;AUwdi?{1vHIo1o8@j!3KX%L{oY{T(7IM<=l?zQ#R0+pb`f0o}l|| zT7g?ZwM4tZ%6cbqMo^1jLx&s;GL&do>=z)lb6FzmfGZPv16kNWV?fk&n*)Lj`su8@ zQti!!EZD``v2j&*g4kvD(W@k7!!yItw1d9By7XaXBK_hwOe3(*Wxo>}E1H*p${Nv_ zSmS(JbRru#wv(J+y%-ihzVgT-Knx>e(^Zc}`id@cJ9v-t0~{ZKzIGmVjMDMr`yps~ zAkSSI^i@pr8pT4=7Yb{d$QvU-usGsv7PstH$+~;KMr*@u#hKhD`UG$`h%&nN^bduZ z3Hkq=tC(H)=+IBYIQ1at7KD9iBok>t^7#9u=em0pT3Y2q7>+C{Z}LK3Y9>6ShwuR= z#sVW2-z#U-FC-uk&`6JmijDd_(N7uUxC literal 0 HcmV?d00001 diff --git a/planning/behavior_path_dynamic_avoidance_module/image/image-20230807-152835.png b/planning/behavior_path_dynamic_avoidance_module/image/image-20230807-152835.png new file mode 100644 index 0000000000000000000000000000000000000000..6cdde3badbb9ee6df22227e57957ad391fb4ceed GIT binary patch literal 86771 zcmYhj1z1$=^FF>b!U`-1EDei<bgT!2bxJ$*by+f{!n$6&Clko1%f+BPSa-4~(ld0Y;_FW6kM$_ZnjR2>^injt-+TNh$vE2Y_*{VDY5nn3;s#VXGbE}GJ-`VRYSZ}NMxy_mRy-Mh76JrUz)b=tKUyVu>%ZfbnuK2)8Q5OdK~ zUvi!p^|CBkvV^G-|~5f08emKDV27Ry^cV9u_Waz=697~zFjLrn2^$NLIRV12GO>Ec*aG= zq%fj~0?+fq+EMJBRb*g}tCF|2U*mWJJWD}7Xoj^V*49|JJ?@o@HCqVYrMXbf8c^83y)5ZyvdE9 zK0Zt1bo-V6gp6GZI8HjhGUs<9`j!{b6rx1` z$#1NsqeCtn`G3EP62dyASb;Wh3^D+z^nz`;%!tBZTH$B@vL`1e@Xr1U+~|Qcl;C(o zX`sZFPV+M0d4d0i6HP`VN!#W}PSI8>;E2G-O2WU54d`J@ON$X(7%xBgmNC)Dr$z=J zC<_LhISeNZpl|<_B}WQN)$5KD#fdi71wsO5_6IWq1xw)gpMov^J@*%~<5oaJz%e2a zkEo(E89G%)?$^jb60~mKyqV``Y-wpZx$_W+QN^zP4`N53ln~#rEdboiPaU1v*V{`4 zC9ajB7{ynlh*&O|j9}M}lDavdpe=;4b91}7wKKrQp5iVYvA*z?LHc%5AkU{X-&D7F z8W=1irEgiz+??%j>uVpCQeziHDLk3aAhK@-qsW@Mf|vIh!$%+Ypb2^YX*;;NTs_#P zE62dt#&^GY!B77d&!S~3BxWa)eAd8WakxplP<&ChIUlvf1 zX?UlK6TDqTaCoF2t{7zVSA#EaSQeVZc9 zsoS=nU~9e@uSBImjRq|tLs=s~2m(Xf-Z7s67-{&q zwG}qM^CJ#9Mo5rOB!2T|cUwjZiI5g%;da%atHW#(vX9o;ieyY5q zgtEG7GOliifqdckn=HS$yVwOa;ch=vSWeLIgVga;!!j5=LK7I_?QZN|&cqQm>Cxk} z1bqdjdsFY`XFigp%jGvd8*m3pdA1mb)Mg||SJL+5?Bh#oz@D1zrz-T(yW`!qbb1N@ zIdL4CEUedu#SSaSykmpIKcDbgX+zO`7WUb-*FP`~k~llVBmP$4R>aCYD0kli@`%cq zyp(^!w0xxxWsFcrm;AR}2i!#rgdgdZ5?vZLnOxSG!j}wSb|&fxOy-R+rV7Dti9((9 zWi#i6QkPPqi4ksG!t&pnJj#1{I1w!`^jm#p*xWa#VF9mnMGy!-MrLMIK!9v-Z?8mh z2w6CufbzgmL-%d1v&dW4Az!FURnLy(b-K+w7sEUiV=ysT6?0%dBtR~wXdNUJZFs-T zUBpd`4`}PI#?r=UHPkqnmx{DoA?-Mbq6-d7XeA7h13!Nb4@E<@}Zjkw|_xNcr{(Q!Oxt#L2UL?i~_9!Z3&CIFCu{=Qy< z1q!yom&@c$?6rR&*f2qyEQ;V=^w#`diHLTj5-N|oGS6$i)eoGLq$Px)*fdW{|B^lD zF~#*7F6z|~%dJRk&ElRX*zLZ>45at7qMd3hrIL;cB6NUWrkW27AW%L<9^cnRr6gIY z15p#d!wLzZzY*1SOGR+tsKk0RAiEID6tyb~dUjf^vDda=vF?@BPBH0D%XA_YV$N;v1$7SDcIm z(jz~JRKOCn!6}GZ_d|M5O|7nhrKYNP-ao6n)=}uIOEai1zPz$40#PBgYzXBM%pP8EMVcP)&VV~e z@bA;Y;0#&MERI+#d&&Z z6!9VNcnVVa(j!Nr&weA3zAEQkummA+f`W=ucS3R%D(Uzf(u8TdD#fyrj%_b$L{|?yx z*ysa@TI+m|@TQd;6rFs(aXnSLH1s~2YRI%`L>3IR*3I=XIc^Ov=BTN^1m51SGEr)R z#L_CcZUAp5k_=;b`7az>^+Vo&YY4I2MTkB74-A>xF(Nka9an?pN-9HEY;M4im*B#NkVBy{d zbD|`~BInD2lsTQt{>Y8N8-WADI={)eMxUCrm%Lh8Piq2Nc?7{a0x3JpigW}!h?cUJOJ?p7|_ac0IlTEm2F3Ut?VEH^s zUnu{%Wo<1bycjUO7!)1GA)j_!c+$ShK`caWK_ymq5x4Eh%LJF{W>-okHinfx9)yR&^oLSl)PQyuEh=S91hYI z$r(rSFSYueda@1U(-9*56F3L2k~mu_n{Dk!DE*CvTZfwG{<|-1I_e3_9)!Exduy&q z|BC{Q;cBsY2BtQeEKF`#3Lr>hEZC;z_~fK}(pETX20+2WbPYL#3WUmW!ke9c0yb@E z1;SSB==*vfabU|$acivPQ@ZwLejbF-N&F`-+y1_Md3FV%<-XLRMpxGjp#YwS!#kWK zW)^~859+#lE*Pe?@0KRK#}BlVh8_@Ng6ZcUlm zAcE8(GOrQ9wNkZXGau6SgV+&c@m7Cp**17WXpDwfGz=3X7c*S;AIz0vxpi_5 z@UX+Y-fNJ&3)a&3?0TIfC_}S~J;E(=Q5%X`V=oUp@NipRcqUxMr&O?ZbPC)Q@Or3Z zTD_)zQq)i2r-5goH@GUspoK>x3!(lu{&hGM0f**%_>jgiY!y{21A#GwOwD1Xjk7wl zN*@wHvH~`gJ^e4^8Cq4QDA;6TocuP7A%XN}o|ujml;|y3BkRew1EfANVKmZA7?6fBJL)6c>XDMh4vroIuhnn~I1s#rK7@ zw#q>NDHk6VF)~Mhi*i~;JUMsml5~0O(k#1Yk1V(&dN@YmPKkm}m#2PA%%_cm&gH!d z+R^JEz;vwM<7le{X-10k7Sa{K*_%p>EA`%U~}LOai9!J-Fm2J zxG@xp@R+@O7Zj6Oi!qZuMR0~I#<19Uyck}}LSpBiR~6{B)(oyz*R2$#0}#G!xo*0? zv-6lgCkO=Yt8yd%49BA+JmG!RKP&hZ`F~m?_wNQLyqN6h_s#}aIRkY?#)N@ugg7YP zWCv%$90}$n1-OG6#E8cb>h-8NdHeV*{*y6?3{a9|jVHjq@>un{RN}z1`=7{5g9dIauwVki|v@nd!>VDbOeQS1>9Sf^#sk;LoYVT~&!C116c^ zU&*NS3w&?)+f(Z2#zt3rd*GyUHWYWqyz7|Oi0Gljqmz^2&Jr=s z5+w&NPhhysJNshvI|$N&+B!LWi)xIzzv+J@2+g|ilbe@?-Qb}jeOpyU9WQh8@ z64t%WXL8)z+qV=Cqt%vR4xifSDSY&+^Yeoi&!?(*=hnG?4&ksSFa_V)ib!i{-6W-|}Yi#C=^vEW5jsoJA95l>i# z4m(x*&!4=LWu`-^D5GRjQwuwU0(>=^K=Mzl<EJl;3M81E4`ni;h8cdeGIcNvBjwO(+=_7+{ zg`1p*q{Dx%%3C9}zk%2tMoQ>>yo)J~mnR;bAH7=Mlwh9rL>0Kc-P7}uU|TG1%$Xv+ zrH7`^n5*PaQA`XBa+a2yAjDNtQmT=mUdAxxtbY_n@1p60tz9bk~ z+B-d|a6ExVI8Y_<;Riv0k}m%KiTBI2$UzBxy^BCD@@zeg2FpHwedw_S(S(SH}w<;f#HH8txHd8we}{EF1Pv z>O`M+>x_n3*uJN!++TNt6P7^aVh&%GH@mw0g5tilgF{RymJtZ^KBD%pyJ<9z!|g%Hnx-OHHygGBvSFh~eUDGO^OIAX9jfpFlR zygWd!M791F6&C|-q@}g@gCI)(=SBel_1F*H#+=By^E8{-ALIOiZTHutHR;GZ+`3Hr{8@UF={AepfV6Ux}F8u3!e9O73 z`ID@}#{n;Pr9dEoIeDF@nY!eKLfKK%PP5KfatuSRsK)@19+-5un9~ z*HHk=(CfUTCy+2bGqbqV)YRjR1QkLEQd;^d#JRx)5*QhI#iZF&>)>}n9f<#q>C=DA zpJ*v{@O#@VnhF=zzFToy?T7^ z|L5QUgGS%m$W1p(=vu5VJm4U+T^&r}6&8MYdYGBX2&sh7#VRew^N`fK#V5E7v{mGt zE-g)8Yx>G%M3H3v@CanFtPb<7EFeJOh;dCFn7S|e&kw$edXFTo5XdLDhT5NSm3v=> zvKdvaudcIo|GC?Qqdh^E3)sJYO%y*4^b{_hCza&4wXvNZZY}Geh(rQ!gvvc&!)b-t z!$*^{1J4d95x7Wdl2sl0N8WBLGNK&#!~8fkln#~58_KI!uTFzB9#BdImg2*iQmmAK zP9!EFsg;Sc6$!MBk$b>k=3(j3ue9rX7VJ_7l-rYvfT}zS24e^!#Y9lDt+gTtL2Nkr z69kzLe<`1O^2tc7i{W zIpzbx_`r`@-GTz|RuZ1UM&iobED<5xs0Z%5s_w|xu)$1Sw$fj-DD)%6El7wP`9U*4P6+;&LG;*zn z&tS0w5vFs#(R~na`x@U=n0N$wjwGCO`ry$EgP78D3KP)xpi69 zC|<_6X}8nS-_0fEu^XE_GEke7x-G&!8I1MVzk3&!@V$~+={~R!Ujrh30X5xrW(pGU zlQYW8&CRVNMQd#zTTJ{la|$2wUE+4t+x7fBmFxIYyW;AXecRoAZ_me-5eP1jTtU#J zxxqk9q`)xD#K^JNPe0mMlzIt*r-E;PdaZfBtUT+14;hSaX+Hj~^Xfzem3K27sU4MW zvPl^$8p>b-_(H(k7Nfm@|D5|=wa!IvJKtb+Jh*-?@*b8T2k6E`ur(R5wGg}*H@R;I zV@2y+9@f9r>X*05-(R>ejAKulmQM6(#&L|^Iv`i{EQJ>PlZF`_4Ag=2;MxM zE_y=MM0Qo`wI4r3#Kdx!3ZIC0lbJ)1=311e$FK?6vN^|yIY(tLFR!xzU0vPxMMd%; z*f|TJh#&yJUKt^>2xyZ;hhz6?NeMqsPh)#~m4MSOjaT5NiBSiD88-DL6u=WPL~&|R zb1|$7BXzdh1x0&RSP?mRduP%Tz5Z-`oM}25`M#<6tsvG2qZo_b@3;>y3`(Mojnu6; zGpND`2w`~RGhR!WFr>b9-9;svV;W&;#Kz@R@*buoV{nC2yn@k2y(D126BE(UMk3lmOddv(6j=# z3&_ymJOl*=ZRbBh3ItmsgvG8dAZduj5$9-9&RS;QZADyA0Y(eFxbWZn`XPQOqZ(aA zhf+<{)YVNn+;Wf`kNe(5k1oSww&?`Wd5*q|DC_}%`VZMXSwUz#*_X{#Q(LHV(AV@K> zkiUPuYU8YJm9CgWNSqB6i=vE*ij0b)7>n&tBEVu8QLDvH2S1P?ykdM4p4!Q0uqHr@ zGXn@QvKD^B7Z0#BSh?6IEjC){mEi9frN^!gWvV)SpXRzO8E*?)%pf22>9n6NkT$GjMx;9 z;O*}hV(3~S-!H*QXmWB|kaCJ6Lw}k7XBRucf#+*uY7Yw_V%;=y$k1SA5{o-wk|Wk4LCT=&yKCF`C*~HLXxI;0{cvx~OX*;o%ly z6!le{^^hmKYU>9@e9R}aZy>BKC@45yUYhzb^5&r@+dz4eB(Ndy0~{al0@s!)W0(GZ z@b6~9+~L{|0D$_PNUcjpK>{`OfG_cS$EqtJ@k|@@)+*IUu#5KYiady|yBIdv;2B!e zig-#FQj$^X?f?ZmT+##4G&Q{n;k|J~?)h`^D7C2Na{9RwamcqvYpm21?_@Jx*-RPE4CA+0{KE zxS>W7nv0eH#*N6!Su;CjRn-y~dA{0QgQ}hY^GX2+!9$vd@qJ1Adn@;Dv9%=Zo@nDy zps`<=fXjoticyJL|L3=`AdE5C$kn9QK&gXF+SR6Jmk6?Kegfh5_YCN?+=u>g>2J2C0 zVBLb`4f$_iRu!mAAwF|EmHrd3J>qbrp9QUeG%<2864sUW-fh76Y7#v%dJ+_4$C`SI z^!7i@TxW8qGsrJ8sOm6lgw`caZ-8VsQny$>jK7u_wvdUJda_as8-egzG!Mm>bOHJDVW z-U2IGh|65vLlb=~Gm7M!?1`oidilHEc`3#7Z;D!yx=e2 zynGCAS_Lu9bfqPUS-|;oV53ll^b2RJzEycA6wwtz$%G+V2SJ zsF^nN-3dcFJfqnOQYGu99X-EgO{>L|Je$g?m%JVSx8d(`iwJ*MCCGTec+7oYHvU(h z`$h*^%Y}vu93{=`K{w8>tVs zD>kUK-UeohIYIVPDcLQ=AhBUKxd`-RnaN#D=^ShJT+Ih{8 ztyn&v%sTqK)dU-*zu$tCBNV=9$#x4;a}@~j%Xl3WO?LkqQ&NP8i_@?JCI(a}uR<{= z9W7`P;6nNJ%TQikMRLnf^o*v(LO7}3j9wioMg2mCY@#vU4npz*-VE9O{+7s^sUBXZ za-%TZ6H=+CSS=8+hBG#L@eP7vvD7C`gThQh_7x6+^xc*FBo@cP9ijFrG zqEDR?h>s8bAYA=Sp5s@zVT5P%ZYMboeU@`<{Lr*9crjMVjN)vDY~*(n4(_`23Abv0 zJ`%iy-&-q<&N-KbiahXrl~fh4e#^ z9)M?Pa2}!g8$7y72tTm-cQaB!$ zD0)MNE-NTHrWdLp1u6&QuDcENB1m5>hq}V~`T6t*r#IHPG4qZStzm(Ios?t!y(LXF zPkbSX*B6)8WrLOnwUPteuR#`$H+ctT@22khUYLsTcoD2r*`3!Ai+P=qk&$9A0n)bkqsEQq}SdZUKEr8}4PoJsomhsZa$G?*AP zxeIO^dQjRi>b0A-LbLa%zWW`SGPB4;sYv7;z#_>I)N$BX=lu0{Dg|*1c{Ukoms{uEe=f5agJ@; z)4o%5p2Rlkm$($=F|k0y7e|z*{qv^ttTL#asOB1B`yk}^IEDYufcd*{cvCRjqCNMg3bc2R;vi<;y z*K#ALF)?K7INzm?fqIoaX?4UdOhm|*yVhB&`c{b%ktL*>s*nAi!(Uvh15e*W=IpVB9DRc1-HSS1k=k?dmz?OLH!wsWB_gVdFd;^x6f?Z-Dr z?5PUxMX!!nsQ%t4Z~H{06lF>J=nXBs*h@R8A4p3E`?yr)ZEbHr3|z~T=oZQEoqeD3 zRcsN$?>#${avYzFC?an&*{#dSV9@2uJ^T!tR#4VF9C(@j+@q8A4!*G!w5~sWiR~*C zm?TJYaR)g**`#H-(V5SmCUHMYg)3W=S7xcTzB@cRO*kjJ7S@w^^&|hw(Qn^kNSfFP zsqD#xP}UB1c4Qz7-TmteXJ8mOJ%v)V&D_;)U0LpJ6@`n1zf7sz|n~_ z3?gR5a<_$uE3Uztu`z0)m0#XH>@%i~&R_C`5Ak4QV`AF>AH5$Yb4TkHsi|MFY(&SG zwyEQrYxEQmpizK|A_7JcQ7aP%I_uO`Hb5Xar7ufy<7VhaG27GwNOWV9roX_gSP{lp z1Y@j)jg3-L_0Ll2N5a}f<;#8XmY$yJ9nt-7QE-C5lY*0Dze6Ml1paUalbW{tt ze?Zsb=+uAliVm1;@xa?^T3EnwQLlFUr7B-Q5>0I~*Kwqz`cAlLz7ZRkK;U+^{kffU7Px~rLZ!XWiQH0&f_J+_?5wRdX6*vQWk1IsK)zV|6l4Oe*DEoA zQJSUH>XMG2b}tr>T-=U%fg&h|%4Z+9$AwS!mh40j;o||00~E}4K}ALS-_c#;4tI%( zjm>Bz>xJ0hdy|{zbc$_kk3VR~rR#Gwr@tztA6;GY*MIg*>{~3WM6v0Wj_9Z1s7X#@ zcL??a*I?h2Fl{$rxINiobh@Ytvg+z?J<{(01et~t06Nn}n4AJ-&URVoskzY@SZN{v zgrY+V9j{bNgw()-BFbgIuKOhADul{OjnE?G_Sj;gjdqg3`0(DJ!OBhx8&H$~VtI^j zf!9UHpa6?f2MvDiiABq#1fh>MFaKC|D( zd(q0soqF@P3?L-#c8+5Xdxi_H;F5hne%zSn#-AP@j^V!hCi(3Yuw$hX`fQckf&qd4 z`01=)#mFD9Hg7xYcNv=E)@TTO8kw<8NpsXu&lWSzE>F*o85B9Su=zrWR835UqAiY+ zMt@2A;(eYAm6fJg`26U3g(gtrVj6vhW-Kqyz-d>Yf$>srEEApp)WSk`8u*_HXy>70dD~iVlck7q&P799Vjq5j121*EgbCiu`ScL9TRE1 zk@*OALX@)ZZ{TWd0m@6Wwe~YnDn%I5M{ybSVq$>|p)i~V!@Y5M;IYmf_^VV}jNZb_ z)l^|Fc%g^I43$^2QhC6yUwfTUWHhRO^iLk0keyzfAugsNMkj+q#P0=&UB)Nn-Ehe@ zD~4wo_lCa1-s_{QL=hiVq=x0sekzI<4{S#?Rwo5nXXY*o#nvJ;G&C##G&v|-b6=Jw!*v){xrL#;+8Ff#_;3V|bh@hSrW zmQsO(US)iZ`ImQB-cRy7Bel_Y<5=G&ge0?lao?E)@!42u_0QKstMZQ?(cq%z2o`G% z5}BrbhVbtJ^x5p7*ECPKtE-DNJb1TW`seiLAY7v5+C)Gp{f7$h6QDWSS2PK0@hhpequR(cAA83Y`Qs5RM2-gY?ZS#@$DP*$NqgC0S^m1 zZ!)%vLj}ENtjZK(QKj>|0=P~z>vY{yrry53FG8-|eAk8Sgrr0gzpF=QM1y95{JMWU z=i}z@&;LsEOvt*QeyY(G+N*ybSNK#<@9&uXDF&RuWT|mPW}}f#W3lto?K}R@7H)f< zra4vPsB94_shFLBozvsFzP7#?L9(w^)Kb5P#XNUA0N2iF7zzM8Xi;Ih`oI=cg^bwx zt^uMH*LB;+3s=+m$5burw8yyZs0poa;{yTcwoM2F)CN4o722{H+Sj~%d{MGCY_d6q zwCV!r*47i3k2`%_G`i&{z1{-PQZe4{nY6+PQ7ISM&Ha?2<6PMjPMtZeuuoSj*}_5j z`~GsyTBqn&74I)P?Sn(Ljn8!q>`lZ!6q)yu;Xto=l;xeygs=uCAAC9aC)=&-J=hTtJa#fil)&Bo$Pj zqi%rm$(L_LVh!?$`ErOYvV2>gZ};OHT5+j5PUli=n^ zILg%Y^$jDKAZ_~}86p?s-;7@n0D9Y zWZ3p>{k3@|kXXUt=x98W6^gkWIa>B$yJQ{O=EZF)l0*cNFV%M0x7*0X&`E}NaDYC4 z{@jR-(T6JE(tZ@g+j(QuVh4L~1PDE2zPJym?mE8+myxST&pw{_X@ zgo&N6Wvf(^VT$CKWY3S@xb_pn4DU-&H#P5UO$R=D_pqmLl3uOn{rmU#fGcC&j0;0j ztiP29I&qd^4JYA8-$DPGRB-vAxHsh)hjCPBzRlv$umCYv|@TyH_GTs32k$<3jSLW$@?}2VS zu++5IqXl>90Z=LOj#=UTZhXG6q+4ES{|L^=*qQP0(|d1X1fu0iL>D++cyKnlnUA}7 zl0I$v^XFM?K>@ehsl}EBD2rxedxmih8}#Bova73UaIZ&LuEgM}TQ<%5?DjUmy6RZ* zD+4jnF~1OjcnGC7sv*-0%ga z?I3v_(YdA9U3YhhHbmO805DBA}QCu&P~8sc=UHE65kkl7rnuj4@>x2#|;M z$L+NjRr3q%Sb9?hzbH0k`~GP*TC6E7yaF24&s4y%V(0>)V24K%QL~K zii7_~$OeC~Bp^Pzl-l~87?M5>DDb8oQLL63pujNz#c)lf=CkS<3`|TRp#2|NzZ=2h zt-sthh>f6qiw=pax|Sd6K2#+45rcaT!;0tE2m!t*tanx1Z80g>=l-p91y&btC<^a*9-``#OK zS-)HxDgY!;UuU{+O7Tj{D^XY2h<(02#WvmU%>&=>B0d)P7>nZ112<`X1Z|4xFPQlJ z+s<8ACWoBQEU&-e_-lDZ)=h|nirk?PKeOJR_U1~&;ZWh&#!7C4c>B>^@XT+2o->OQGGrC+VOoEUGGau-w0C=GYUu|Z zW>fd^^Fgu5Iz=yD%i3Wh)T({g$<;k+jGC&W+NM_?3Da%IZu|0!0R5Y z)W7^2*~5rgV~7Cs(J%RHoxh#^8IArl{EB_&tK++wkta5+r;n~{L|nW&HwZgdWvlkH zVKlX@y!`IYb~jr1!8u-gXTX|zu{G3st#15YoLhKA1YUO$2C&6AMisOQNy4HtkH88q z7XBXRq3)0D9OagmKisgi`gqf$U9Zd}!xh?6PjCzHy1(Gw)wKWtPaouTJ_EdA&VdW$ z=kE)8&2%yjlBZOf_3d225u_52JR0!2J7Y+ZpOPw(DXLh$27kn_gXtF>wjImS^M0@S zO{*6wpG5UJ$_6~`+)<;Qw!jD;dQXK#?`d*hKIhIBpbZy&HdEnGur8GqV+4CNQ}vwO z&SU~t`2Y1ECyWaep%{k$UK+Wr!-U{R^NAR5WSiVNdfBaWKYtRR+2xK_e!tHrQ;yCw z-_N~|^<}#v*v?Z!ZV6bm?rk>{Ocj5!gHBAL3mT=eU6c77X!+Dv5fi5-XUk{T7i;bH z-^83R-E?lT`&z1OIZ->a?&@n|8W;b1NW|DQXve*$^X0iKp((vkj^82UW*XE0>2MuKyjP|OeVB{M_m6Aw*FxjG+u|2gEoSHQuK=eGkn z*_dlEEDeN0?6(A#)1@bsj(vxWz&Ug4)S{-T%hOC`F^%mhk%=2TR+r6@*#d`$wH4-Z z=d)h>?zQTnRWqqJ!;XgV!A2pI;Zw7W^!9$f4F46;7n~VVp|v$Vskf`S5~>y{V>{WT zC_!u4Q!E2=Rs%_l48tM84~o`okT7U`b22LGWjk2I~*16uTuqWfNH3^dX)Te;G+0xy70iI{Vzb zu-J-zMk$q`$zZ9geiwMu9X%9#otQ(wi=$57+d2C^eA8nnrW~yzkcX0qJlo&^No=CS zXoZREgqo(P?=M?Cu@|O3+!Yn;2Qw2R$o;RdI%dXXiy(f*Fty@#>y>r=I!@?TdUrf9V>LcxYp1>lGXl=;9>VptVm3u@O%)nYvFcS z%VDOBKU(Fa7u4Iq%Rrj?;Qglpp8IvJ`4*Ft3Jp3(ue5brmPYh1 zIb0I^IpyI(CfK#6U#Sp*zG&_T_BH;eBOjsd=~bw8M^#RolIKD39HwEoYF zpYHjjaUNG2)6fTaFH#<7Ka&jX9!#&l&24lI?>qgYM;t|H`TdrP@__RV04QppEcz_x z>L{st8%aq)0Wky#m{}vzYWV|xkX^lyu$WtQ6}v~j+ct^drkhTc*q%BIa|9PbY+?TVAEl{e##P7aUpWHuS4` zX7XRzib2ame-@Hjw7T1l_iQ^-EVrk~v=E;j(mXcyimHAyt;@h&(jvV*B?eDG)?&Kv zpy=ryS%xp>Pg;c1XTME>*~jIJ5uaA0g(B8=DOS&W-dsrHVj-Yfk}kpmcf`S4Olo(I zzeSr2zru^}v&3SUQ*GsRqG^pNgQn*Sp8V|35sYxXA1(~>3^?F?Kc)()j))Vu6E5TR znb?>jmeX{XI$Mpk-t4*Fa>}|Zvz?P_eV?w!%HeHigjI^EpTZHSrl~(ayWDG7eS)Z<}da!_L(G*-PRc_h0ZF4fT8*7aA0ZU5Ol>0mz3J&`gR@HV5AtzmA`L5jkFG8N z2?P(V1~)ZO+!_dQ}OF=vHWR>fG4sZO93&a9{SVbR@_;YlS=e92p$zE&T8k zIk@J{u3RN(`~j`_k?cEpZZdeoY;)%1=6}WJsO^KJBTMj>Ut?)-#+|@{2nAjS{Qot# z80DOZe?8ExFHmyc`*fMC1$oqXLIf$^zU1-U?=a_);-)l0SWQe!2$JgWPkjk1ap+h6 z%q`sw{v^SFe-|JP)RJW^%v`5MK>xbK=WtRRM2YzLR38Cjm!VBgtFT3@%g4l{CLl92 z=kg(c$zb3sq4dqD7ggdP`v_7QI(1uD7S)|P1SDf3@mLp|zU@V&KhZtQe&#h>1aG$< zY0$P{k1$bICb@IVjs1>z$ioreLEyg8AXxz~x&g1G_WATCinv0`un?plL@~3EWU*}~ zQDYP3jg5EIrFT8*H@>7jA{O-O=R>s{MUkRGNf>lPs8HP12snwf3Ax3%zCo`u3f2%> zNf{wCzT#^%So6{OeHrommQfQrI9sd86rm&d)su7a`C#1l;F;PY9{L(y{7NJ@pM|-Z zm1jizBFoHw(H*Oz5sV1diBd!Cge9~m{K**g0S?oEwPf6z7YAS<9$v^~l$#h|ns?*V zItLxg(fYOP>+1^?>Wc~^ruE08FN=svb-Mj)fJ5Cr?$O8PCiP6xIBx$?cz$w4T`eJ^ z`gEs-vVBX_X6^orMaRZW;n0&e4a8sfMSVZm3zpH+@@%e;`P2?g`hq%JsY6wiM%=5y zjF1o8>9*Gffx`Q>7_){19CP**q1!vDdQ(x1Gbg4 zsj+dXJlYw&y&MX)1AlVCdbPF8fGSCUQ0Dk) z$sLDL#lNdAx5&{hP-GukX@#dr|9ChM#5~|B z3|?&^OU?NH-3;>C8Wi*el=bYT2^}MZwH9GxvAH9MBT}Xd)K5bT`Hb!LWI{mnlPhaR zh#c{IXt9;@LGw#9e%slqFpMm`M#ji&MOPFy7^A~ARP%AS&Eq>uxu@>2zeZ=v2$ zj_*vhZyOu}GN*+%AHI>Ct|DLY^zChqTW_{XHLg@WCa(ONZ1Cxo#{QTM1d5^iK^a>` zR!1nkLnx*QQTqTjNW88n^Sy4ZHr1g1mBZxRm0x=ODyht!V_{}qDQcl*4)|%WvgnWm z_qGncymxTyyx$z1^iC!+pyMVdtVV|U1Zl=$|GvEM{K#MT_qsvB)9}mY)$d=QhVQ(Y zX#S{awy1sGIYZ>hD&K_cv;8;m!2v=;teI^G#ohOAot8bQj5l;Y;KBLC;gmADUlY@Q zm4!`u-NrO+(X^fidQ=2~xJYb}PSK01+S@+oz3)?lHo3~mKdw;B_1mCrpX7~CLUcyj z!qMq-$(XKdg4q8WJ8!UgNHAlSazQ1Zx4*B-0%$g|Gp-T!3n3e>e^y(bNL{C)yIk?- zpof7{Ha+sk^VEa8qvPKQeSV21zd5FV6j7d!T~CLvXDdAyn6eGu&t~MBQeL7ZsO6<= z)Pd3z6m+~<9`3NXhL^5|jJcAdxVLm3z~H2I4ZJnKgu!W+9;F5A2NGa!U2PXf`Z}lS zAfSF?KK1D?1~k}a;e$Ta)X($tsz5+eAfcm_a zO*(e`LI~eLb>uQ!c~G`9sKIA%#yH^Jfs30WYd;xFuj>^vpv2Bu%p`9g;0(Wd_oyCT zKhAa0Oe>`G={0|6>@&rpu*zLiN0a7DVVVmTSk~)CW=e|zj^TC7%@ngwucCaBB+BE) z^z>qnmEylp{ja&CKkd3IXdk}+xBj|n`kOa>!^7&|*&gfrP=ZW6P)%%5h;A|$lyxJn zF?JqI#OH1%y~+30Fg0b7x%@k_oS@7a^yOFg=g(9cSyGXl%5e)T14*P2U0$yj2iKgI zPl{y2K|N!0S()m&M+d0#<@xbAB#2BSW@Fx%e{f_Gs*#GF-8W=DUlDcSIR6$h7D8@G z?~K{(EOqZOC|+87@bdrT=_|vcirTJ+?(Xi6Ata@{r3dK&L8Lo}?(Px7eNOiC^&2oRvYOQ!y;2YE_T7-ROk7>s$!vDp3c#h7YSy zY~-tJj?l|519*cR=m+@Ui$8!SE6CU$Qo}XP*3NX_`>~O>gFfA`YcRZ3-K}jNC@p0k zeL?#8C(ruR&jxu4ta<@3 zmu>UNNFN|^Od&06&g-IpzkoSy2uU*|iV6GSej8ZE=p=GEq;=z+VA&Tc^3PKP*trcG zdQ6&+h7=XoK15+o7>OPhtHW~@K~K23hj+r_I^(a5h?;E7O394`{(nJF`ufQo9o|`) z8g5w5Z`=d4Hlj)ZzhiH2fBH76wKf26rq%J}l;K?XSl%W5qJjJ8KeoJt<-`#JflvSs z7!woYzVVGHs&BP}#{x&jH{qDfViM~;C*o;@oT_gFB{a5C_*1o)22fKe08oCVG>!Yt zb%0VYQC8uj*t85{(t@%*jD$lr1u`h=_M5g#j2)g(QSFP=uyXOGnhC~rPo)AeTWiI+%~3$JN9XF#XD9 zlO4!&b(i!V_pwZx&Ggu3WEUUd@Sz-|?n;dIHNKdx#|t>llx1rk5Ecv(PXt)07H+|` zoC*q{c7V2@HYHNNuBxf+{g4vm;c=}!x^%;eVv?eixE9?2D*U10e7BbA@DU!{H=8JI zu|Rzd3I$}|A`*LVXqs!gG*ZmA&$tMa*1K~&VKZ$851~~80faM zOhj$eLN?KxT5xXpO*-QCg;QfpjEK*j(ktnK-;OY|g)QX3(RmZ7071OdIg}|;dfO-O zOFI;@JFOKsN$>jO2yJ&-01lXD zTgBZ*;UhN5KU>!g!U6R! z;3B<0-=j&ZE7pb8tH_(;8vRjKmQ1@3_)%{mXk@R6Z_6B&E&D9>TaS$vMXPc{;7%wA zwB=%idHFy!{6f1sz>^j(S$$H~L=C{HDXDM@mv{iQ2nR5OdL^^9mB-?B@ZU^%@ zTt8Ur2)U^U4flSCDkXz=nBl(MEhSCpeT9{OqadH;0`k~!BtIzV(37!!@VHS7q;f501lmZ##bNymgr&@1rl&`b02>d zxmvluIm;`2_55viJ$7>|FalitFa0T-G+gMS!U5AI|HRc3r;9wA5WbKnO&8z>a8;Xq zPyIyH4d}a8%q`;q+LQryEdLkQ(wqD2{)zL_qt?cL$ZCC1nr0oI_}mgwS+_b*g(35` zoeFQi;Mm$ng8PU0;D&0KaqZXyLXf;o>3A4hk%A8@zoOx2WX|nhf#W>#*3IVSnYQ5~ zwrx{1zKvL&P3cnXClMYb5J#Vw2P_|j$5mw?-KakIU{|3;Z4~hSt^4ULuLwvlZxOhmN z?$ECPL462r`r~cBE065LAG7B!x$O$^8QL4$xEpkwi*n(e^d~ z-2gBACI0I#IBtj=cF;=9w#;IULpR=daK}@2?9E`i#{>A0Yqf5+$sqRxh z9xlhu*%J()^pbhTaQC3B+^QGmak&;^GI{TlHCmVe>DP&ItE4lNU2bK6j3jR|?)&^P z0;!?h!LRl!4iM+wQWsG6@>bUMMkA(+ZOM3(-Ni>i#%j^{*2Yv4;N=A)L&MLE{#eW~ zyT-7WTsGhSl>$F%=8@jOI7_B{E>aP-JCwHokJ-B93TTGb-&u8%6wCP7USx9O2gfnj zKL|idH+2b(z*or<_sd4~_pkci<;_h*HBRz4P~Njw{kTUN1k)=V4>Jgy?_zv}J9blu zIirAnK}1Mdlh|6Q?2}4(DtuZgcyv=eUUi*~aqFXf+?ciP!NTb^XqmQd)%IC3&9B+dlnMlUvH}L6=aGS8w$_tS8TU;%UeUBsG0H!`@ zXc!^^;{c<2QXr?%hg?GemDQU+F%Ah#w40loi3sVty;;+Lvuv=Gawi)<2v9BonNQ%^ zvn*dX$gAL*MnLu5zZNSlH#>G><2hM zg`PAUh7k?@gNuwK@>@$y;mSi#6wu<)-^l&*rvlIV!HEwH);m85Ccd18EG~G4_O8zp zM~XC3S3!H^srTLCe`hTmz-?j&3(=4h7uq2=iqIj=hZ{SCdclcp=FHHVYp+*N=E`db zlZ4P2!yew3o3+hKvx;YVQYJ~?k#P_H)jS|XWFq8=7(k5r=hhECic|GgbJ)58VeoVb z`Y#gR42p2lOGDqv(><=Ht^k~T&x0)F!8SI62^Y}JG7SG`7@}xzo6+UJKvMF5XGwPS zORj!x4U;D3IXOA$nVGe(oV-)%ikRX8Zm9Uq-k)hHPHmk&a~&=+W56MW(+l2bdn%B(%C$95+Z3z@e}9|9WPuL z_jus4briFqLaeG%1@+!DvYU6vlK1y_jsM78&w07F z*uE)v9V@Hv!(93g&GgaPx><_sz*% z-H>xT0Cj4^w0;N7<4-)SMPS8gq`i=mdf4Rv1gkHP3mt|aNbVrjN}*4I7KfH-cbk}p z;26Zp%EvXl#hIs5Lq5RlBEt|Ma&r$e-ro-DU8&8q3SZ4aL7ojkY{LzGK8? z&gp;_Jk%sAA~G!(-# zP;J!e={Uk!*;N_Xh7w+6)UJ=-4LJ;!P42*Qw!JJ6tYfQUnf(nu`;Q?H=?m}W4 zl}JGse##+j8aIVEP^=F8RNme#!Y7}fvlA{<-CojkyNK+h4S>rY1m;Y0XM(=P6Zb2n zJ5|J=(b7{#_?J$~d)T5A>HTpl9)0*GdQ|4x8dX+LmM<^MV}e}VDnwEnIU zgwqQM3X)V><!>dBHvbC)r9vy7Rdq_ZduwQ;SECNpy=fv3<~VV`rcQe=rjN;yHqn7tzK zWBQZO4g>eAK_DmoEG9cGbF>%YFVB&-6DXFjr9^OdGZxT{uH6TN0_wTjMnSVvg|O)Tr{UiP-aXN-8)S}? z3kx(tC%RA>C!=4rO)=Dy+k^!PtIsVpijOv zpskR-AhA*1ebJ=iA5CE{F;|w27uWSVL${f_DoMabaPT4;jY}K%^&Z*XqJU0Rx(fPd zi9nvTho?gx&A&_7!AF?je#sOoxwCj2e@}1F(Dd6H3Y%RmrH!;qqHX#mz>TS^N4G~d z7b;jV_6Dq2NWvEP^XE_b@v+OPK43K2`S)imU=Z5>?x2N)8ve#A08DxbooGA#42;OH zTTWnxshOUZ=)&F|O4BuJMbdQR%F%c8M({|GVz|Kk79;$)M;d|_zUYp&HmpSc)J>&R zecUOE%AxiAXxcfkxQ8b>G%||2#`(aNq=e>byx8M5qSTt90F_v^+@k78c)cOi>&&S3 z)kbPFb~45X)neICq5exnk&`y=)(yJk^Fd63<~b)pt|6|+K8oliRN!H6@s#JfplG<3 z1c-oeyyP@)O;*gXyw8KM14C%jLOpC(XwJDgYaETlrolum4Rsh;--K?;<70@H&hX}& zuSxTw@$C?ik;r^D69g>46rd+-KxLfRz%(}~0;k@YUwY%V<2+FM@@P2~+;uOsI{V&d z^WQJ;_oJ@~s6%Vopzv}`0qEj={@H6*MX@M%lsxH?=5NSaATh&yE^89CXvJ)XE=RVI zSx+<#$sh8|&m%fcX47PEz0!*ML#})9^eXrIOb8HuZ}U0(jji$OSX}$?*JLcc59~}D z2IBc&I@<~MJHN=WHt62hRp4Ix1CGCltfMJ?q2(By9N*J1UBeNShH_4!bo-E#ybageI3gl3UlzEwWvm8sVs|a=L zrukP$$TFH0#Xg7fpSu8_bKgrf|Dj>uBdH*z@7yGlo^n*CpQCXkhYc!LBo-Ch= z*yQBoxq7Ig`S+OgHIp{1tO^oWMT0?B#u;Omp}Cb}V#MKF5huAfMtSuwN}GfmTZ4bM zl7CLeTglr;<|Up@)D+js*(a-8B$QK%_p!Gpe4UpmKuqRfu-NaWNp3UA)^6^F@twGr za5HRmn1IEjraW4tpJO%iTO64`s({}tNXs1){&!PmSteAsd5$EOhx@(A&6f~f!+ z8x_xg9_v1ni0W z*<25RQ-Q8|_VH;S8ILieRWZRA%SgbUM;S)Xf!I0)ZCRh3zA(kOH;0!NAvs_SmWVxZ zzNv$J^Xy|xfpBKL%%Rlq{?0$U$YhewaP^kt)hen{?-KZvS6sJkWNm?)jqct)L4i&h zp~1_8iSx0@YE}lii^P*#)cC+ztuUHF(ky##=gu)#MY9pfJie{Z?bf~pboPl<(~w{9 zVKN2i9EtUd6+OD)=(ZJqBjVLw(+2C5GkQX4(i^7@6K8LGbMq?-l<@RZ&~i(NO!6g8 zrZ3)ZUbFT%d3u}$M4QrzyECqxb;z7-iqxS^XRZ_s6PK@T7SqznbvmIFh>De#A+Xyl zan3tgbR~7z*eosE`_^+^DM42$0x6`DP@A=}1ecvk+35Uu8Er?j8Ec^Ea08vXZdpn+ z=(2-k1=+QD&pT6^yTQLsdT1L#s6>~GY1{7GS+`Tfsw}i?wAeCCU;KC~t6s;7A05#3 zq;OTga+VHD($W}>Qc}YA5V8pk?c(kABy|;NN|Lp2l5p`jmskxWBO{Zq(7$n6rxj>f z!29rXx5cgc6F!FOt-u~`QA(bx{!3R*v|1hv&<2AhY<&9s{26CL!d~Iomjzj>nhE z@-FvVhY&9cys+eRo(9lTxXYz%V5id{TnzV{6vwEuU|FplT?+m4w})m(0yM+v#UGTz z5pstZBYLepqjqfy5*e0JlMb(fgbnUxoR(vqGt0a^Pe67t`LY3;c)JNvBZcy-mU zC6w*sH=b0~B!8a10Iz+B8s2AYK<9|FZ5vWV?i1~Nq{}Jap>L4fP||-Ms$AgD3B(sP zD8pMXB-)a-O{W zyCd`3lqf0rrd&(*^uPP%AaN;ecKRZ_II_56Ogvr?d(rzb^FVC_Sz1b1v zM~b+ILaj1zo}Pc;Uk3`Iuu(FooeGQhP1|QYdve>R1>Im}yi+4n2{OT0!3Fk)_KRx& zx(_T%Eg5>{)wqHj8iZv`nIi-=fTh>3Ur{Z80(mMnWArx|7BbI?``dc;EnzMfF8j2I zI0KTh3CAxxw1?}(49+(}qg~gIi?gH&aQPA4Uu!sdeDZ~wD0xeeW%`vs55;Uh7e~d{ zH}~cEM#g!R4u1X-3~5TMY+FELmFtCMTw~o)Kib83#+PW7EA2_e7o)6bq69FJmr4ng zUPL%&N)?B{Qn#sBeHS18W25JrDl0$RN8ZWn_Mi1RZr#UXhtYMj5uKf&?i^Mbef{ut zM?9%nXLJiaoC~*5;wupnWxsK~Mc7Y>@DQ4?88D@%XKE5LGh^Iw>v-SgWG9sBIsyWs z(y6sQ)|6gMUK2j0vR($h344qikO&}F!6HneJKrpdkWW;_Wjn+liQg*F& zl}MaDC;Tk7(NMGVmccvpD*}^8b3_j!&M<4l+xJcrvQ`&8{n4&QpiPCvb0mT(slad2 z6?T6zqz6Z`*1@w*VYLiVQfCvfEYcLuV*OqR5r}e~Q#l3KznhCbn2Wy3UtZT+hJ4Cal9d=P!?KBUZ~1^gYTE)=kbqgn z^^ymU&d1M`dipT&*wa_evS%d8KxCtWTxM+v;NwHNZI%aQ=FvvYE0*}eFHA}b>)apiz^L{6Ez`M?Nmz|K2nZCOwZ!gw%{$QdoK)MDLRF2@=yYtur zhlS@4lHJ^VV)DmTF~V5U?*f^agC)k`BY4VG}DCIqKnT#5(vebYy;0;eiI?MLRhwqpVJK_@U9 zsO^NzqU>~8rMoMck;6QoRCOQg`brdIr(mi=-{t5>dB;vSM+{`LBoM_gA&-VPKiRW# zbJuHI{wP2oo`F;LIW9ft32xB9ffj-JTSYC4CbQGl^mdsZ?*m^g%QMc7K;OfJ;i+g% zzYtKa2VUh&2mxqCs4m)xX+LIe<{o7chx&fT1MJW}ryXPs@50DEyboKJ3B;f|c}#C6 zZ^v6W87aM(v%Fb~d!mhcK5^p6Z5Gw;SWq7~oGac}3}it$d9L?URUW4s>f*F1ad1BN z*|P1gQHs#-t0`POMW6BCH^F3lmzs;f62GoeYX)sp(Ykb0PJ$uSNKaomCP`E$MpRetsYB-%5bH7hT1k zU_d&7U%b;;U#bThmDN8%M*|ZRx>I+Z&t6-`UiP0&ggoN3CPCz%J{i)ABZWm>{;Jm1 zGSi(nQEbIcet)(lFG6c^eb@ixi9#8udhgc{CW>HKKLBh_ZP!h-w7H)2$uf|qsJ@9#~dsk%=Hp)Yc&0v>^a@U#5RoNYd8 zmUgviClyymDb@_(4?Ht%%P|b^QKLnRa9I}fr5@QUFF*BIVcp~@w;x7$pWQ;!UX9|i z7>AP`cEl-VSm#g(@Z^+s=KQ(7-A4Xuv!9 z;_g$_pGk3hZH=!JRq;Hp&sng~L7>+`z+Q{Fbildi+fE$qxAb*){<+AbM@b;n36@LV z^S?&RYi0P@>@K6DZLaZiX%ydR%N%allSay3@I-a?=QsXgOG)RW+k5F7V$4*O%>AOU z$4m|ooJKjcjlfn+COO{eiR|qktG<^vWI%dE>0JlC69aBOw_CJll8=)Xzi zzcg&U`>2>tR+SpzAVWd=38>bb`yoZx`=`3-=xEs5D%*ZV>pPV7l8ttX6*eME@S53K@*A*PO2f{RyK+g0(10slR#Jj=)N!VxQJ33w>GUC`)c{_ z-8(MGoB>~|eCWmyh*CfUZ>Ph?Auu%Z)7BH-!%%9Eg(n*3_%mmxC#26B1Zmv5TP*KY zQhJRBbM*AeI99modgcawcTyg4Gx?s9fFfJ|Wfw^CHWWv27&gOZ>(Gj;t*cWQTit8iP8))HjbF80z&HK1@vCpxA1He z$U(Z&9^hP}xDk)2lhc-LaO{@=ERZn_Eirdn$%L2RWWqn-(BfsnK(4O;fnCv{Yrjmw zDp0(PjxxF$JFi>4rcp@G)(X#7i@M@~@sm3lq8xBcoF2u?WO1akHe&FWUPM>KGd&g$ zY{tdc5yf{4*Olotrwrx>W!GOQuT%Xfb-X}ECaOH5lYf0iEH$^7=fV7Ur=iTjB zEXQ)1!weolgZ8EEqy}cqr7niU3`rnn>RQU6jpcT&&vM;7G|z9tm*~#}Z-$D(ZBNF& zJ%7TltP3DL3;lv*?U0rt$oq4=PrKQ6XNGsMDnIf1D1+wYGMXXwL0ApV-Q64Ss(~$z z8JJbqGcm!;Hckd)9Q|Z%Oi_IDqjXoAoCxvReX<9sztg$hzdKO5tMLYg@UOpG>i0AE z_U6!5rYT{Ane6RB<3S;BC)wiXIU9+?+Y8Pq91fhPqjdAw^s@%o*&^UXUgEKN0?g`; z4-U7ztxi!Sfi^iu$KCft@vD?e0wtJUu0fOlEGuLjmCt8iWBFCmb}Is@yZ!FZfY{?L zjmc;K^uH0CoZ}bXD_x?0@(&ljaRMVD&}Y<8QI0NFaSofE?Qw!a9so1Ih*m&qSx648 z>15w*>S~?01pIBWl56f&m9zAXKF3W2pZHP6@3n%24CjHO_c|xri5fDqkzfGx?QtO}PAk z|4AhR>&^$V7D{y(75QFQ>qXhzh|1d5r^HnsOZ?j**xkrFWyFG8LH*Ib_tBd|=^#<2 z(2CC8-%va$w&nzwT-18KgZ7JxP zL*j^VS3iu}UW44&@2LT7K&2E}jOQ>cpDGG(H~z`TFa3QimX>r~#5#e7mUNGdHR8vBm-Hm z{SHN1^^w0D0IzZh$VH^cv7a6rt;$-2-P`>O z)CP`9dbr8TBD{cXL4S&3P{Pc&xJj78y!I87_lWohtssKCo)^r4Bc%rzINPque?#K0 zup%XxuVtw+ubBzcawzw%J(tH5{R;(dlYi=}u0)MV{lW*@A7sxJZ>`w`vZjGi49`~@ zlo;KY5mZU&SsN5(6&1<=suoA9&Y)H`Oz8C})+i7oLk5^LmjVVMpPD)|qJthC=O781 za99^M7V)o&^-_zet|^fZp=d*EaGN&KiQkU}BS(EJ`Tb8`H!oW4s%Ub_Zr@*(F-=2J z#B~y49N{Jn5l43#<=1P-;+{+qe}XR#z^J_LeMI{~l;0EyD*Z$ngdlbZzgEeB?g8)3RAvY&gM~>v9Wf zC%*LE9e)-XU+i#;h;T`5yW;s4knvy^b&l}A?d?D7jj*)p?)7=*=CfCADYlCY5|SrF2~ASe1{i^epkpx5a`dn z=c75?mFa1*^F7jVJPuICj=Y~Om0u}NdVZ32K_H*nP#u{lj1NV&0Zfr(oo~9sQJ~|= z==@!}M$64Xal~huV1>mUwTM{Q`@_Y0pqtTsPq5!?g-NNr!FgLm4IDJK{}T?C#3%4 zxE(S zIq{MC;q!9%%02VwoBs zoBj0D>o}tCy3qVZ-8K6p^dx$}a12I1?870}>4mJVUqlpQEeD~FUIy#QY&&^BYdqT` zwmBIXyAEs^?oWiDqQ-%tSfy3dH0H31o{K7unPbJQpW3{U1rj|XAzi=6S2MozE-sZ9 zKNsC1dDTFitd_VrSKmXEbZ**k8QjxiFCMGC*AczH6BREIe59rV)IYvGS=0#x8)@J9 zUQvt|A08fNnR9#y>dpbiP=;Jz?1@CN#m?^pdiaY}a9&@B+P3*VKTSPYZLzx5Z01Nb zCOclh#+PRA{Pw966t?E~D7o<^CR^ELvlUeKTFQEPmWQDq2gNy+Oz{oUtjUB=D{8;t zd9X)C?7U>yOHKsn8qcKJh{pefOmn`3Gzst9T@}SIZoThNYI8V8oHVQr+C~evcGtVW z+n5GXQ5u2&u4hCWU-o8)|6bs-8qcE$l<&3qycrws*;U>gOJbTnIHStlTN?jyy9j)q zEkvL)Poa_{q&qWlT*!V?Bp@BOK8|)I#cyAIVA^uVE;X(mnC00!UI*icS7r*sG86NbyFx>a6TzUoPY;@{n)~vS zLvxJy47k|@ds7~|Gvg)oc+uv4fp>25VPVyOxwYVJ1OXI}m@QDeEQqVBUJ*T*+^swL z(pJ3GB1R#Q+E<8R8GI)xI@i@b^xIU6>r_B4`+Z!IO7;l0X$j^$${-tK-ODEQEMv5S zpDE)htRHe?PqIz8#}VmS7n$l|*VJ^~cfXNkPeh)Mg>@H*Gf9UlXt|xH_5&L>V`N`A zwn3Tep~L|E?Z5~RPvMjc-4-Y|6n~&a8)C@vlF1jy1)MF(T@Fai5#Gu^EC*mu)FDk5 z3fa_ilM}(7A6PB)0t?8ryT8|L6>G^HwNsFbt7XXS6qsKQhcy#hS7LF#2*GVDCFgEI ze*h$NIb%atEUW)xQKsDTQY0m0IoOT3@dQZ=GacD(sIfa}D^ymoZ}qCO-s`uwD0BW%+|_e)^O z*J+$a-TL&Ps~qN&FUU^EgeNGJah~^C0l4rrswBqyE4Ma@`2cFPaXyuk9%b=a*L3As z+HNQIl|5tY;oO>?J@$uwNKqK z6hNbZf(`SJ$8a7@R(w8aM~T!7*W_E%0+9YlRjzGGiMfu_sGjS~K(;>;cgk&UEC)Lm zfxK1-sZRj(ZT8diEMma_^@f7JJ|O^zA~8DMb(XJ~gG=tn@SbI-j^$1T#ilbuSRj!YnI=@)B_3CEIr}Z(z9%pC5iZ zUu@J1+-Cp!3Zjc2`Jd0DJkrmrA@-Kwy#MsZm}+eCfMLA%a*9?&K-~uvyg`kx6u4^Y zMrJzL^|h6z9m1Y6TuyEP&kAbfw~-+=Kkpcspgf~4U%)qY>h5Sc>IMFgcMCy4ncGC; z1Q>G32;RM!55<>G#TY?EFOUZ_3|P`ozeawl{cP!`cBNUNzZx}-t5Mwx?1INye|+AN zG_B?O@0!Ho4?K>@{g6&C_BU&qLN-NSo%)Q3ekK~YQ2z8jTMWU^G|WlysQ}bSMa4PK z1$$mzFhOI47QgVk4s-)ag!igikO}ih?G=CwhLdQ&WD2Wa<68W3GsL*B#w1nQ-T(gP z&h-ybB5EB&5=*9%2>=RbRWPDIC;um22GUalp8mWhGx_aB4p{|21!2AtXFDBI1k zH?xJ;f%O%Ft7|;3`aAvx-Z1&LD?~evCe-saVixp?x2tP?HfWtI?P+}xr_7vZLk3BA z%`}Is#6(MqIv1OyNkB_xR$4t{Ik<@`YbxY(e$W?lG4mR*>>`CyXaOf(dPD8@Wrj2X z?><_daW&o?0QScEsqnM@rJm6_#xB?U!1hoNte3J^=0SM|`)71Em>K@a`*$b0#S0=@C5zR(~RY zT{-0O=R3Ns){EFf7HkX-#Gk-@KG=<&HC(^4blS0G+Huvlz3;MTvdt6F6NG_MlGBlW;vU%yeAtabc7XJ;RqW=Rq*3zx$@v|&90TVA27k?G-hR#Y>~#T z412fRY&)Fr4$x^{8}SHQbE*Ill#}iQK*XQ5!u#UkAbnQE{~EQclc0N!GZU2<=hk*L znePHKa>+miPrEA>Q9V-=ZD|!&vO0R_HC#@v+JcP8UiH_Z`Nw81TZZ0_Whho z8|GacoL=UpLumnq6yWKH$tfrO8VE8oJsmCiq0QQBhel&wGD&^*O>81@EZbXQ)8s#f z=6Abq^c&J@g%RQ>XpA-2YlYz4l1aBm$eMNiut$36#S{NrJVVkw_4JSVu5rKf>YlLf zt{m512L5{n0S!I?Afo5K19Yup5$w+SQW0(o1OPKxvTT+l+ghje;>8Q%Lovc;RKc?) zF!T*B2Lh<=m0sV#EMdE2vI%#R8BiKIjs98enjU-`3eYR(uO;n?TGxwpv&*nPiqQsg zRY~EeAU$@Gq%Q`PP9Fr0=*2W5N6ARs5-U=9`A;_Qz7l@9Mz((^z}_gEd7MY~TuQtF z5+9E^X4VpCNQ%5Y2V6&_MQy9z`t%kBoPj_*vK&eKO`9p&&lb(=wccV4{=?5`;9Yt} zI60A+7{XrT+sxk&QATcwl>~jFEBtH0kI+W*(fcClphgXt9_c0|he{{xE1vdy-gn;- zd_@N&vBwN-Ev3)l*sc+Dr2%KZ^aMb-^rEeiILiWogMy{Ja_gf3=No(x`W5K%#P8*8 zhj-QHrEzR`gvm;-tAI{ot-1`s{h=Sieib;skWF;qH!!^K)`(wYp2Eqp<@r4N4>?}V z!DI0!l{GnaIvSlkG?u(LY~u{dQ>pl~iWEE_*I?4kxU~>KnPF@$Q9A6H$*X#9-X!s6 zGcMme#zD|bj$57Av_tI>ZA5;5I?Tr~%zIzW7(R)~xC%3#J`j9ZcFvSm{;VVxx^0^@GQozts>jB5Wd z@?bC@VxS-^=NSs9HY!nWhuPUsVt~$Rvx9m($x3k8Gig1w!lnlfLN+t56O_UL0UZoC zxJp;Z5_WeQ7TdgOn+W6MbP{b^ej>5Kir z^jRzE>!{#o6|p@tn=QhViQq1g(mayEcrdbDL%h5qsaJ2*sY~v$V8y zBTi1=H-5^ArKMy*PF!B|P8iu4h=Cj&D(j{!W&;!;^=%$vq(KR*?>kRbe7tybqKZ|= zwFyUICl9~x?Ir_xeK828-g9DeXJd;hM4!2e0CPLX1K$MHgl?AG%+Fz!l?)nqrXeN6 zQLhX3-tT`oUenx-J5r2)zsBxqINbJ${=;eYZt74Shsg^+4K_*jH zIRNW10;-Y#0Wae3`K15Y=_JVy9*#Doq{`u?oD#ekl`#2a zPin`ELD2u#l{Xua%6k` zQ^AbftW!9`4;9eM$-CTf*6p)u!=j)BQ_XCvqbHl#YG|7J-di)V_&ULFCf7F> z!!X$KHLSLqT1x32gkDN}CDdZC)p39Qu$M&i-y6Yo>5BGu=`V&)Atp&;SynvwQ1Dym z2X{c|Bh_%s%-ZY}9L;R|u&SKbOKKj)RcY~_$I-f4bmecH@Gi4fF1+v5Zp3}d*>kOa zy~nkw&-$6%ho2>kR;eT$I^}mcuZY!J>_F{iT?wvUvZI$@x$2Suajm^qFPe!?7Nh4X zO+(t)8qebUO*NLCOy%0B>jctl4YX*5o&<1g=o)m^-KwL7oXC6^%AU=rkxfSraXS8` z?L@+l(3iB%$JCM-MQsgBepOD*j{TKZkDXfOHy5qjq&2HrXx^`80MBCP(%fKR3zY9m z08a+!*X3qiuOV{aWevQ&*7%?FmBRQ`c^?PpKh}t98G%=9cQcJr^1cUKgBEZqf9V3& z+F3xbN&^;7o#b`3JnbyXQ9;1#wQQs$UoUpMimKL}2!<|pkfxu9u?fc@bV@OJi4D2Q zc)GK&0pIx1(b40(wwSy3Gh1wX!?O#>Z3NTtey+ z;c6?x_?cw#3^>@)$lTcpK8V7{HJoEC0qs*X%CwjNR{BqnyJh9I<}~ZF@1+2n28eGK zVf!E;>!}xPW^4TmrF_k<#9O}DTbK%xz1f@^bPRiwshGsXkr%LmTcget6(3Y)Ek_wj z431tvOay55A`=8$wbZ0u{fj<6J)|-eTI?-5&A9dabF_HtYBO?Me*Hhmgjy?UuKWwvsO@^urmkII|K!C)pYugI}mfWWj6*U%+20k}vrs7||McvozW% z-UB1QExTgPbg9cFZN$usNAr3feMpWMvyjcCNf7C>ZaKt?un|wC(1)7WTc=RM;7+rX zoXOU@P25qsBTs!i0{3^J)>XejpbX~G;0ycjUVxH^?%!fnR8)b~3}}MO?|feoC;g3J z3t{w{!Knv?q^g@CV`wL6O2#31Njo?Gz{aYhQ9V=NJv&LyT1@PPMWvR!5bL%2({b(S z8da@?0Vr6rQVd>lAR;b<*d#0jDd+bB)ji73Fv)XrN0_zP9b*=_aMiO|u^9%&BM%Z) zVbKYn2nZp>%v$ClYRIjJCxYfr*OZLEyIf;An2E@1NQtbKO&%BE|M(#gPcI;P|LE7q zz&u4Jg5}X8WD(`TpJyJE7c_d&Gy2`Vr}1`aaH;xj+1m#ZNI!%Xpt95nR^!kSN18pC z!Du9D#i<%BmpuIjT8!&-Q zgzqyj;1D|cc;ql6%bkF)S^<4J2&jM zq01JH3d+DDwJKcqfdvCq%~ z#2bJw_zhfb94ltxW;hCj&+i>sxtq4eV}un4+J{yAeDJgiZZEzLoRSO!>VgS9tL*8u zM4Gxn*OTl-;FSNb{R4Oi;2r$ZS#?iDk0fTIOFwrRSUMvsAJXJ3in75)y(>hm-v~q5 zo^|p+8KApbLkOAQ_2(_$6k;wAszgO=C~t5+Zql0+ zi~9cH>+~nWgT7zHTI_*d=@YQVBRgm=99`dN)&9&t)0 zx+iEeXg`ZR(Rq5aSYmjTf1P`m97m$$ zRf(##S)U9}`CZYDIbh&gTL^$W!6x`qE>v=n4W2q}*7594%h5`=sms8pxJpWxynQN` zchyN(qfA(lXn_KHY7wrs9qJKmrBOi)=;EPA&yCg+S?C1Mk=C5NK>+sUe^Sx-J6-JY zZSgg;_oRiQJ`72n%<7__8YnKOxDl-xeP0JxCJ6CEeU%O|GUF4&eX*?;#~+`Fuxr%% zL>1_0MBO8i)R^o0bxmS`8@vkK;D>4|E$|hEDI5AvWcV_cBey>{&02xC zFwKLCI+I?J0Ux?Nn`FygihvuUyO)HG~zkrcFdbtp6IXA6t72)s3$Ge+QM3D%mGcdM+ya;9!j*v0OVwQD&Npw@c3A_r>r{v;X zVk^+UH{m=T6NkYk+`RG+fr$>Z*lEmH>Kz*Wz~!vy+gZMm*%%>D!Iw&RYG%V-CVt zzEW16xf)2X0^!3wT!t+K8vfNR)^G$Wpauj68kAWP;^o6ckqL0!F=~%A*AupO%aU{q zkrCDegfI3GS}-89CbH7!&vOr&R&{yt)X#ljw}`BE|1S#k;}Yw#xt z$m>YcZ_n{Q*7yPf+;#%Cql18bVW33Tr#gl3|uv51`}fh z;8zb`bzf_26ar#VJcU&{;%l)cYtXeP=T#y@bB!Tjbu4*shA3Ytgd0j&_r8#qIJr=J zg9aoRpr4TMna^b=x6+RywNn46GK%_d`K#Z5Q9! zT<=YyJcgElb91|p;9;5O$w}@&=t9uUkF*kcnO&m)i(oKVq^4|=P$7!TNwM7;fYQQ% zjsQi054gw^6`Qz4c-ndyw&;B1%Ul|l<({#PK zhQ;08T>}JyTObe!4vV{ckl-vDT!KSzg1fsr1PN{d0>NFsi~Fg!>ZAApKPYNuXQoe| zK7Bf%xrS&02*}mP1TXZ>4nS-W1V(1DChvstneq&ic9Ej8yY?!2=i?h@fBOcCpj}M` zvwvB$(L*a`XkLJYRRntg7>I_h{1(=K%LHi)+Yl8ef%~-}P!+V8#DBJXOl{;)WV*nD z+T?kkEt>GXP9?YMoV^@IUzMd<1zE`P_svkDA2XuLgI&rn`s>=g#iNr{gjDB-p2x7z zs7hp!4Z^SuR?ZZ`f>m>x&O@!b*uF-7Huo{xfkJ^O^(yWJ+cqR&XB0e{))JcIjvL=?;DM$%#$QNjn!0 z8FY7!N$@J+n=uHWh_jv#jt=IBPXLJf*CE?5|C!72`v;_dX;0$vT%J1kmR5l{K!?6- zPya&nw{M$|U!n~=2?$hFIA``Qs9A=bFhwY|vcrIl+l-0syJN)^1qy2%qqzLHtn!L2;{CvKI3TSrV?JnZd$cDy3ocn+rH~E`0^tHQZ)`WKvwk7ow-vEEfXZs0{SkuFpZJmUzc{6qttBC zb2HRYNZ2rDBd0xdvK_n_TLWF+W1cpW8}=LGuPsHvp}Xr^u)l6C)XIs2E3#-DhGi>x zJ%y#-E5$8?IBGslllfSND-g5J3!g1i0I2yh;)pW9kowgT_HCOq-Jfxhdetq81z>f3 z|IFdH&hXSA54@<`Zw`Eo369co6#*1nQ-B_)9uFu%`^zdjfZm0)TIed9vg7da=gZV_ zbD;FTk?FA(Zj*V04H-}nVZ5hj;^2@4++41Ye~7h|hcs z75>@*{oyS2zhby21v!5BYv)RPn~xe>H4;Rf)`!V3EehCz#Ba%2K(UE|tA0+`Yau=8 zAa+9hd(nw}9K9{54{ zRwR(%xg}SFJ?X$H3{t3X_4P_Uvl4p4(douj`;0?oA|J0vQNd_V2>T*%GjHAZhJ%|R z&O~`pxVbBApqh;cxCxlZlyWRc_XxPrel=oZV(x~=j0PZpifKa~;T6ScYX9 ztJ6}VB5^PX`%51AwdZ9I%1)%TyNMi6y&2Xvlt*2W3%iYfXvap=R}K2M_p`6z@T8AP zClV%|r)yeG`yb;?RQ?g#=TvoVM7n-FPL?W5fkR6t*ij}-9fIQcC0RVjIOeNmgI)6= zRQzVyJC{<@&wj!TQ}~P=)!&-nDWV6si$;m&O)0xbj}Q z$e+RS#Q-M2hJcSBC^`YRbvppD5DLL?VI~!@lmHy<2pC1Jh5en{+;haFfJxzX)?LvZ4zlH zo*^^69;ZPeUuRO%`FV?%~rzH)!L#8*k{nJi6Rv5R;8%lS~1e&|K#e zO4UCjfPxKf0S?mEiUebmsRxTFZ627F1wM7|s1g`q1L|VP_6dCSc@NjP0!JUt>Gw_> zFtP?%6Ocb8w2698j6&r@DV=U$s@{zvvnMb>{h}l)T}5-QP0yL|wM}?M)8WrU10Vov ztL;z1_^gdM&1o32>}q{UDmH+|n%e~1)2bOKk#+bdn`MIh%KHOHT4wE*e#`F@w=U6J zxjONOqeW_;rgP>d1=szrkE#Ib_^A7Ds^cl*C_);Bp(pu1gR`0u8?CYc$^5jV@&z>( z-@q7axA8+Bx@uEQA{ss2-?zR`5Fn-c(YW~a4QQe6%Na?yAE!NksyY+3P*;SfuY+HY z9%pSoYYNpL&YISwW^oJ#v74?f4-Iqqt_HYKQEt-m)j)8_)!5Jvi6bU62!-FVXW z6QDrCDUIJ@pW#_oq;Mv}sSUy(5N*fo&L0CWF=bdc&}`ac!tw#VqoFs*Q1LP-gk9PP z4q&``{>$fSlYZ!h62j!>ZNMz8j^JW*#R>su!t+`am?~@V<)DCfP1QZG#PAs7 z5ZDa!uVwvmrLcm6i-h-mG<+8}CQsHKCoF3-y+Ef|M?;a-#KP^9b@Mt4Y%u#mpW7h} zW!J7X(IYI#b9y(^=>lT`p)?pzZ!f^+P}4+=Cj{*i`>;)jb0syFR&~!$GNl}tayc9{ z-Y&zs5FE<|{JT5VJ+Foh?K zs2ZMk6cMtmBpectNLjbsOU-eS?JO!iDq9PJP11lZD&+k1bL0};$)ZgDQe zc=n42r8v-3OU!_{Sh%06m{#!;1Xyx_hgjq&!nOitZ7#YK`%S>`Zg6wZl5I>Ym~|T= z)$y8O;l}NB0EeTuzuawdKCUns0MAIF-#KdkqGs8|W{#DT) zm-8`W=<;tzGXEfL%9cE;3~`tBQ?~1~0f$Xkjh^RBD;vjuyoU<5gopiq+ju}-k<~FF znmyX_9IeJ!rw4G>bt1cc8Vy#gXGx?A$yhyxu?To_xeZ~5H^zY}g7>T7Oe9P%e`9pa ztDrd0eEpYd%{&TLY=ZJyFBCnxyG1Uuegj{5y>>|2m>#QSV*ZAiMBE+hn81VL;td{( zGwK$r9w=;dDz)yJgNr$d`S@HCbnD{-AB&NwAUF*DPspJF4vD)sOC&GMJF$6fR&}Dd z=2l^_pXMBTG6-<&QDkfZ<&1D6ufG56iZY4{)5XTh66^{l@Twr0%g#c=+_xta@x=64 zbpwdj*^E-boHg&PudcurG&z_eECI*h#q-~#m2K*A$iikfumf7#P0&e1Gfh@C;)V}B z_xgD3a+lr+IEGtxYP;cEZW34CXNGyc@iyWgBcNQEd48M;;oTEto3g?0_?&*ZFeJ>0nkZj%v7=|B)YYB!l z;{vdf9?Q^$xt)Au{;x|zUGG>Ego1A<{&)M2+1V}_PAIp5|>V>%0HDd_J!Xp~M=z;Y=vXBJru&1xoY+yl~>~JOTz{vOAO_j_zK@Fcd zFe2`|solEYjw(Fq{U?r~``yglr$nDJf@$WVXbv=#S5U@85&ReT0YZYhYlrY&TrYIs z2O6gn3ibN|0?}**!9A8~jMRs}%Xja{oDOmUs||XY8^xMS&grd4P?kSy#|#WZOW#3= zo>%U)6VV!xfTf|7j|jV_;Hz5~!_jVvVa&s1@=vHf7rPf%1`9v0R&cIK2#nLUi__4B z27iOVnT1&`#XOmhc=VNuP<2jRjF2NuDkR7;Th26uO$hfNPK9FAs5s*QsD*W75g@(y z4;h?Pr@;7SXn&f`UFOy)(#U1Af0{wNU!h+s9S#o>OIOp9Vawls)g#C`rK= z7IL*X{~_r~1{#0K(o0MT&ECa;;VUcrm+uo%OWa7Gq_)pptG>jv#&O!lD*H*4cSBtj zXVYju9S%J;Zx9Z|84niiFk(E^E7-Xof2X+`l;WvrtEC-0tEoOYOf_j!R0snKb9)Xs zMI!&WJt4{SKC={Ztih;>7K^Ff0pQ8~JI?A$KSNh?WNI)xA9~X$Ec|-?PlHE^IWYbN z0?PsDt-!DR+Hzc#7>tcLHTGDVw**S;l1k{#xNS+1fQPrd^Zdgn{eMybzs02DHkGgypqvnF` z$IQ;8HRrlos}N@!k1t(XKa(Dz?jJgPTly6L9O!>k6WheI(>7vtEPxVl7-W0`y3{s$ zMDm>aiJ1`Wg;#n9mzGQ4RNd)uy;cIU+u~{~7AHskZ1;0;fO?++O4-M=lX&4}45iBu zA|Fn9M#^>e9BT-Rh3}ZfSS9(l<&ockOU^mftw$=CH1Y#FKY&1Tb8xvb(EgNr5(2&N zCxK4Ym(@*>G=o<`!AG4>@v3If*9|D|O9)P_hCKpgCAUQvvZrRjz=fPyOdu4Uq|)%) zKl9u&(EK?JSGZ+BPiwHP6Pw&uNP%kM_e1val&h^NMIj0Au9%ixjbfu&P<;V`{}3 zkO30uFvhMltl|sI<$~>mHq}5xRirIAwF`yhfd1_H$$I6K$3n`8B=^2OP{{Q0t=g8N z@wnsi<{^>^?R|HJuI#piSU6gsT3=N=B-O3kUF)Y0YrD&G@5dMZ8gY!;{){s-C?HM* z-1ukReT7&h=|6q^hPYfE9?;t0CFe~L^yE%kieth9v(i_nZBNqd^{(III7PlUaz*Rj#}BL{g|Q-0 z82VlzO#Ua^P>d%$=APMgPBZt%w$B((r`pU70t9@<4?Nl1K%IIqgf2C5E3%?E!0ut) z*mdD4RmTMZ1nZW`;J7>;w79q)vOC*5rSzfa@N}cin0#%jHfE$r0?i*!zx3q}Yp(Md zD>3scyijtBfHvR*@XFjpL`0Ypup;lIrg`*(=IQcN_&2CEA|ln9u5E0(rqBt&Z`ysa zce9*Q5g)4UcW?pjSC5mmZ}$(K&zDl;-w6GX<3xIlQgy++g{|jJMNfU)3R3|bN)VxB zu(MneRYWg;@N#hFlN1@&iUtj`)tR)y&q2$aAE7V~8>F>c5{Rn|<`#t5I{(RY;q*D3 zt#JV%E)0mE41Xgl!NN(RpdT6!`{^TU|ArN2!aV2KR#u>RE}1qB<*}HQa`h>lK5*4) zF=cY~x)XHW|2R{*04eTb8?ESjCBuN0dd6A2oNle*2)0pBmPj4=B;yGd5GthpOOWrR zNL!JpT#&3>*o%RihZOtUd*NX`n>&oz3~fdBn_0r|0>~L3Xou|?4p%KtwGh|%Wz5RK z9Qt9#C1#gB9#62m{C{pm#Rr-;H>nA{b}&M*2uWdw)O=+fWVbe2ZK1 zTV>xVscIBjDfSUZ>6tD~lD#IQf#02($oUYBGm|lVa767ocnre}AJOAhuNtgrfM9ch zEvR@r-kfF}=60u5mOc<^XwYTIQF*@XQJx741Gy5-f#9qP2-0wK28`l{zlW@EX+kzI?o`cjWVi(Zm>_!Oz%|Hyv$$9KyD~Jot`g+{dOfP(G<{|=TY`-S#W-x%O?R?U5 zI~D?&M*-`6bjEkrx0DEE3_W`up21zqrpWkPG3bzW_m2Ibd z{ezda4X2aaA0%F(Q%zbF4&gN9eFA zEGSB!9IgvP_1VWKc-89+{;M8s532?YDe48*RH#(5;WJOCK{0o3en$jFQ$|TaSPA-S zD%zH!f+qsnuUG}1G2BKL!i)>LB5D~GIn6PKzS5P?>e1RR22jx)HK08TQU3?*>W@y! zyKOk@mGi_;YQfCqt1#3d|Z4mqu1mx&jMz9B80v*w@ zf}wZs2L8Fx;8Z~>AYsEbFwS%9?vd{9)l_4oNl@65mlzX)xvtN=Eh5NLzOmbZ&$uuH z44BS)DaZ+c-c}GO+8{DZEVLovM{t@}VgV|9=(}S#T64epl{)@2$F}^I|I-2#gaLpF zq=w%TcetgfXN~MnV6f6C9h& ztg5m#v!_SKV#=>v4k2N#8ri9B3V|jc`N+R970>9Ho70uN)1f51`^`^-HU>s%^u0hQ zmu?LG{m5a2(M!QE>=Ex0;qXf{s+LzcT6MXJB+KQYM08!x*D+*OS6PFV>t4cn+x0qj z@h6NA|G8xaJZOCU2vR5ul)y?o$3^L0sZsA5m>LY58{`CXtQ->DA<ROB=T`&ulo=DeP1RAiZrpv508c3AK7MX#RYvA> zu+@fC+Ux=R2Ss>-F)G0B?A663_7PhuVHp1BI|_@*?4W*Ql&=!s&j7EpX|`a1Sskeb zcxC)UzhAJB)ymh@zQu|SD5^*v2!=dPXUn!1_VkInl*##H%?u8VxEmA5q~`v(@!hSt z&113NXgMQ~a#)H8|COZmWfQic{RN|<_EIX*y!gvWNFqHEJvKX@ld&-@4i3&iM`n3g zI?I44K_LTdmscKP(kFaCQU9cdWA_Wuy}bLUaBj`-T6VtbboCAVN&++VAp4mYIFWP? zBBxwNB2~u3A8Hu=4?p@+ZbcBV7~m|9;oWroCIOXCj`V}wZMKYzX%We~mneli>58TSd(LK;XE zMddp`8yQil>$rWM%Yv)@FIUvUoOs+)05_)@f^x#ApVZX<$gFF!M{)pK@TdE>j=Q1- zfG!L69zkgg8;A^H)7Cd9L^-#u>f<3Gt430{7TI;q3n+xU?|yedM`OSyCj(E-AsO{! zC$_JAcGsgEBIwfO*5n&ii5qu%738#>l16B2du5zmiOaRfK+twb+GvPW%E zV*kqoFP|%c*}9C32~e}j1%02ZX@{|C6~f&}8HZt7Fy z?JEm_g1Y=GB!&E47CSw>XxZMPnj$BjU}9kZNatBy7b5mnee9xUOB)d7oa(EX0NO(p$wSq;J1M}wB#6W zsfv_`3F)J%U6x4vDmFwM{Kv`u?c2viWONxg`?hBp^jHW3z3ku`X*kPGfb*7dP>_3?B9G7Ha!5)7co2{N@mm0|wl+uSM_C5E}E zl|4R%$5*vpgM+j1GpvkuodeP*U3x&zxU7ANDq%Zx{lFAGt;@vOr| zKK*BLzyS0Zm)IcMAFNd$D;h9$a>RAXa}YZI)%Uoql+07PH*Ml&FC6pZrcEsShN0H7 zAbff_d^kAu48n6=cwL3rdW?NkU!YCXM=Tv@Cu7nBNP;aWcwJ_}PwIo=oP-8%3E5)e z3#jQ?b(LZxpx?DpvDytEg>cbOlYmqJ;Q2{ z+&F@bjYH&Rpjiz!-P-ERm*#Bicko?tL1c0M%+6?W90sz*ZKS6kH8eu@mH`hPznxm1 z=Xx~@bM7_TJ|+Ul@61{7gnlo>th!$@kD$L7HbUyKbzyCpi`qmA2JfCt8-|wa0af3` zBe&4%EWf8ojRM%>`z>lkdq9@(NwXnRR!SwrWDwV{ire+@?;hK=1=nDIe@Y*dgQ&9-W#@oo7_CSWgS1A-NIeIrt=dw+& z!+ZrUwSMXia;u@3ZoOjrS2-ZIo^fQO?BPvDcS!^$e)RR)YM=V$o*)(^(pi38W3t=vSP4m_ zh1>$HbXWv*Bk}(PX3n-2L|tv551nNAsrk*2!mA6yVz%w!3w@tauVe<7-b%ibCJ4?y zINc1xk-V9|?^DXqX?en&(YyvtcVmUZB(HmNqY2817li)6XZC(Eb8}^fFXTmV0; zRPEG*pmH|_={iQ}fc_oAG=vjU9h`0;O0J?)$+tW;19nj^#6J)-IKQ}XO2oT3J~IJ~ zvdu2_4kVZigIqTTi?5dm2UG(I^}ONE^ArPeH=-XZ)}z`>$ZBUl*e`d+9JVN>j1ZRP z&wWNz0E5dM%<3*3=|k+{7uNhA<|k)>l!D7MNU#1$qr#D#eo$0=2*t>`V>G`U)ndvz;^2Dz>D}^6#7VC;J_$C9I zHX=?tW(C=*H8Af~yHtWKb3Q=v=%0dyp?oY!sqhkn*jhAn_yZh@^xwBWVPVCe3?dIw z4SW49)wsqeq^4Jt;>{3_X*nX+t2gshcCVc~DNx67UbK}SXNj>*KyO{0C_i^z6Fc+k zxl%AAvo_!YzR~t7e^`zqc~xyuH;ieIz}ZyvS3AN16ZAZdkDU#eN;e+N_}b!i`>1T# z$qF~yznJ7w&xMI@Y?6JVYe!@;R#`^y*jBLk!*_{ zH#KA6U%!egDh4QtxYCpo+$X}RQ!3xvQhdEP%1bi@9txDn#}U)h0nu>zkCQEd@ z`i;2Wc1$5k>+w=QDOi_c|Ew<4TK~oSQ%?G2Jj$aF`rud2j(1j}8E8;dP0Hb?uV1fV zSFi9Xk~0s@+;k+uV4wB^%4|}wk9hjk?HH5X zSg*VTPCrQb7r=0YDG8A>mc)>L)J0-O0(o$xSv#k)RAm@Zm2a`l(E(Ob3H;Kv){#mUC8V3Lj)8ak%I}ajn zlPjZWNv)^P!@sn%&pG$TO~DBPCwW&EOND={^Q03*{k2S2_~f$|UC2J7@(76lY?M{)&QYW-;SQp*WDgu~Y)qb(%tNq5H(%0any z$X#Vc-pTp+W{udVi7KrxA8BA&I!^wMks{G~jWQk|o5*+ds&%Fm?5%H4Td(%Vp!0=wJQW!v{9 z<-IqH?Xq#q~Faqdo4M6*AOmW@xVh)&ruU z!=HfyY8hbznm5YiAAGD1rKpaZB+j>^T`Qy(G~y}VO`h>k2jbxt`Tr$)e#>0n$nE&c zjj$ai1Ey*G7a7q6DaKBdpqc{mW*noLGqm%-u1Hz^wwy`MPnQ7roxz2y&3Jr!xb1WS zBVS4uHXz-~8INMO!+tKd2SyQ3LWN|YvB=LnEoQ>gv02Y{tt}0h1DSY}hKPR~ zBUvk+aWKXZ75k_$nihQkFA<`(pz(`NNok#qsKBb)Yt0>1k##6i+b_DZ$5`}Ps z(RLT>KN#D$_pEfQ^?6Ps^!96%_OP52(&0Ic6+}CY+OHHlK1L0l;Zv2M(PxP&KbKX8 z=yMjOOBRwQ!;8dmcNh4b#J1ugr{I%w?>Y`;1o4>e?4GMVe-sfqnf;#5ob_h1Yc9CG zVdd*AfhzN%B_Dp38h01uw33^ncDU{B+ca|^r%GV&;yo*97g|Ws`1@pNB?b8Kn$A6q z{5hADT=q+>sZOGxXBK_@m0_)iTB_=Pj;<*5C$VI!atxyx#`;)M6vcANF zBzSXC_{lspdLDee4*q`ko7_PShW9&VM5i0?Uq7dI2-ClWjfed`iWc=h%WMN!-rcre zeFA}iiRrlLIdifx55u7NWI@xei^~Q;MO{P0n{|LMGsdj^?c3Qj zCM?MM{d}WwazQK7k%Wv($I9q2)$DVQDW6&9Eh-q&@m1+TDutZ=%DdSvC%x04CD6Y& z)Z|3oxv=Enii?}1E$$y6v3$o_b&j-`J3Du+9;MsP+!0&vB$&y1%EVU#az3 ziPw?fQ%vPH8>y7HMHC(;Z#gbjaksBjP2YF>UHPZABIO@YISCm*o@41(-U9w8mdZ6M z%sptvnN8Bam!|LKiUdcRWTFiSHok%vyzkNWkqz$T6TPmuV92^YiVxl^o(dmRb)Fml5cn!) zmk}Ko%A0MEyVNm0WVlL3tby4-iB8jfjUug{h)gqqph$nd^-XN1`JGS6SZCBmpp_Z) zw~_>#2#p4_xAOGbrh*Q!;8KPFepE+Xj50pgJZ+ym0p#phlfG%{6D9-8)0F8jI}+=W zU$h;_#pi%3c>NamOvdhebAjtQ(DW+S3|{4+H0dU32b(tDp08g@zil)K0ubafu>q-b z2V#GUfxVy;5GndoIv>qm7u4f;PKN%?hrN*2si;0?RAjK(XTukWhhf79fBL~bphYQr zv(-9g`MLXUVyWILzbef}`LQz1R53vc+n$OA!i7N&h7e$!CP&5RyP*Q^$zy(6w{9h6 z0s5kJ;2;ej#IRC~x4%{Uto(G2M@qgY{>Rl=&?DpH+|75iLa@nv^HeG?O!Cwdb6H0D ztfAu~#TEFUGSPq6P#dF=Lx0y!7um4Tmd~&?vEuZ6CXqAlW4orfO zmDpn0GA({NsX+wc$(LviPw9E-6l!{uJ<8z)^@&Ee{GQs@H}d+N2jlCX_C*z6ei!V# zyC~yo*4#DQWpWVK20ovU65c!BW(MsBPC3Bgql1=kTV?0P^O+Xaz9`1mG*Zx!S;CM` zzb8%0X=x#*JRAY@)p7St%i*@=Ci(7MKHIMx6L79PDbVPg%FqL+4!nvC;Qi|`@}3=6 z=}?x@4$RI8a3sf>X+C?$%ut1XYjH_Qc$@jY62*@civIhX^f&|5m-dso`Ln~vHyN=P zC|*G;&*v`X*L>T0V&A4(NY4E1b;oSB)TbFEcq6Di!a_A$GHh|ZywbU-Tk>c&_y*WI z^2pEPF7oZtSxetdU!)@`&PKaAJ#`1KvMy6(izDA7@6aFPC`##ili2;Uo0SNr!;a?b zJ|!gadX5IQWx7??(Wamxu0*2)jB~K~3X@v?2Z*`Bjt85bNSy2Z zQ)FJprEK}8>$m;mRcn>5Ex-}2R7xT@Z@vB7e31pc)j4=8?btO5z?0pg$zsHLZ*kqFpr;zi`g<`Zv)X= z3?)4GoePckR+kG+Z6P{SeVScH7Ngz1!1l}brF`}?15&_GK1n<{s|e}OavWk2cX5-{ zS?FM_RjZ#SVfFY+1jf71jZIIxduJ7yK+-#ZV>AUdB5`|W4nOe?&Y@1^mS6@%tPGIOF!CXMjMe+jH}V2uwLBR zT6!YmcuY6fnzZUfD)UF2B=!z^@Xt%m1Rxs&tLkU!6A8=GBeR2LCyR)?a{G5+Sy4Pa zsT+|AT|3EbR2r6xfhef9`I(BR`eI4%OR@U=w9B4oll5rR@k^EpW5;D(@7VdG$+v@c z$ZQ4{+*{?gNrDNno&?RWj57r0f*w92IM}j(kshYu%*jck3bQSnspK01st6@10iQlDO~++N<=D*3OkOKQTf$YII(W58 z^8*1D_&P)*_#Vg^`vK@+Vz2%IK}T#64EJnwxaNQ>G))=vJAqG!iJBH)b(&p^x#Dx4 zY>f+yk1Z|%YZkDQ!i}XOrk8<*G?xdqvF0ay)GQ+6GZ))!dL{4^*+8YQiF%`L%`_Qj zCR$t+YSr{g<^6eSRK|@&RPLnfr3iWwg}b|(`J>)}47(vu;iY83`PR@y0gMB!k0kNl z7)L7U4a=u)lBJQZcEfLD_bts{lOI>wfKQjKoq*L_4tL5)jgeMxW3M5Upal79Q%?+h zgXECD#X`r8!>S6bf}Hmob08(3Dt{g{0^5XECwnKAhRj>Oek5M?OSeq#`SCQN5&rF3 zr_uVEwds?V0^w{pf8f{3n) z5{ar55-Nhi+%0YZWCCO>;!TfL8ygc&*@hmS^eF+}o#f%^3y5slu@^MqVJ)}c_38{b zGmof#zj<(bMpQ-(32y7|_A+9>XJ3zcDdbQ-(}-CCUuT0;KOMIdD_R-1p&^F%YjAHS zMNqc6MX@hh)-}{uubC46NlyB@eHdp4TxOU1vm$QhvAn%Rt9|y=2_>puz=2u)ofWml zQTFTm^tJ^~KuwYyQB3ya@JWql z_8}=6NWI0^chhNVI~0)Knwa|@I9+^_d{jf2VOcyK7f&=|Qel4AeXcDb_Sa{uv<{%oCh^RV>`}!fd_4gxDAU!fC9@fXo6rLSY$sCaxULhvGxJa zF{TQ?jPYMHL+DJv1Qcf;cnm&eMJ+N$*zyqLTnDvReTcv^EJ-Gbskh}!dfK8n*sf&q zTl#0^+CA_VjkP0~tD{nh#Yp7o_S0-drIM^gsa!oe7foX$-&w)>ZU$){5{JcG|Ls+e z_3@!Ip6FaVF@>eut-Tx8pWQpI2_9S3PMO}R4}6}DylkdZPb21Mc#ezB)(>Ty+J+q; z$I3ZG?fw2*T3NyLSe5>E$vhGV^0ddBUoJY%RlPc+_$oLo`b8U*ZMOlV2hA7cs74Bz zRdzDr6o`+&V=MEe7xbN2I&0m0XP{Lw|E=M0);Fzq!refw{Xn|qZ}5Y1bxIF@+Vvy< zQbt5Nghd6!_^{^Z*Z3=**iOjFoZIu%2>BYv8XeDy?X`Wr6hd%I{=dw;iT#7Dg-)zB zw($UI)pTFVyI?P9_;rQVgeGMW9rW(*ZV}CS@F`C;X=vAmn(Hzj%a=glt>4;?YxKk8 z(qBI_lJB?9zmlDPU27&x+|P{a7UGLW(Fk*8_%JwMNTlQ7lb+VjxJ3ZGphA~X(cXl2 zp$O60`-HSF(nLT$@yH)u*aR~^OjC+mNi7J6vjC9Pcpc6&PXFBfNRH})R+%X^}LsJZhu!y-hUsEYK6RA z3fbHd<{E|ym)8%iQ38+f9Jy!=@VCID@NV}tdT+_1C}3qT(|;&laje@ML!{!za-x-G zOLCDtaTzS&9*AUM?;-}bCDeggSEFc0`eMuxtw({Zt`FU0-Xh?@RJbIWvQXc@fVt!E zDD&)>HCrX|I-Q?ZIFPiMTmm}D&&d?lKquq%SF7DH%$V$#rP2@p{SU4_@S(3hjUYd# zcR*d9L|)0A%@wRbI6vR{1zs7C?wXW+)4qMr`}FjiDpSqgI%tu~JlMTlb?0U|$^_d0 z^H3q0K2?TUTS@wo?zb%HSRnz8fBs#SYkoMl_ou;NW<^)mnoK4fNEZS{Puwx?pi=)7 zFgMh~?rzgFZ;y&p>;*uy6~DPbQ61HhDw6fYOk#B`cXF#jie7Lp(V-ZMO95udnNfg$j9bGpl>AwKz0LW+ z@(xzMj3*AxI`Am)Mr>8xK|0BNd=={_S>g`y+Sye(QaMwhgkPi7gBRp5mc;Cl3;Gd8 z6Oj*FJ5o9hy+8f_EaDyI-zLHm5?#(l7Sy`36kSbt;wi4?^)9F9M_*)uSmcXuq-0*iN7@Hf~g7*0>!UQj0sv!bQh`pCgxP+8 zcsi)OaPOkdoh1FL(@}Y{F)m^k~MQfe>2`7B` zAOhVaCJT;!Qa3jx@^H*^hPms~v}`UM9}-U+-Ri)WFnvM1q~nLIbFlfu)C`&44QqVk zT1zLO=Z73s0aB6|lkY82yC>W@%8k-&>IKWY6c!O7GIC?DU`xn4ja)nTG=wJDYK! zak>z`=#|jPzT#`2HV-^763#Aqb-t1CaqO=9v=75Vkf>mzsq}Lf+1)d``xNApC?~V7sc4kjSu+xH1m>VXF3Zy z`1{w|*>=gL{Vd81h&4bN0VBxN0eGy{(URZIiu*FF>a*F z(>9TCw0g8z%S;#nR~5UIa`IDOUZ5Fknf7~CD=Pe2qRL@O6$2!O2#i_H73s6)CB412 z=+S3S9Evp$3K&C5noW`=37;*a%W@7jdxO_~v9hwtZEn`)kQ{TaGnHb?GPn-WI(XZk z9P|Jx^pQ!O2jd$?+>UM7R+&B-Zp-sWB{Et|rfnxPFmos^Di(&bd!1rk`8>aEYL9wm zoc=#803}pQ#^-XN!tn~xxrm6pPGC7NsjMw(V)eudL{d!JA?pfCPa9tWgKsty<>Rc*F(jcoU{ zF8Bsg(>+UY#SoonCJ2>7GMPyS^zFjrx%SoLLDxxIXCwJ?I-N<&fT?Nv1HvXYFgb@9*olzx z$@>w7OU{@h2377ne3eeu|GjK;VD~!J9ZPjqU*;Z`G@4{vsIw2XG4*D0=_xiMg*4tq zDRz^IA7ylBZZ%dp@{EVCgOrcrpkpEDDJ>7-uAEJPrgqYp4`wHAs>Q6*eGB4ynf7VcBsGpRo6fbnMG7mWRoojB8-+ixd=NyYd6teeQ_T+cDjKrI9>YiA5 zLtH)l`KXmsv8NJ5U&ajKjH^e&&<1Y2EU2kSvo!4QD^8*>y?4b7W7Rq}Mb3It-CWII zjY;$E6Yyd9f4Owlgt$fmKxop!`z}|ngMRn+?iP&bpc$N5pgscTDAAfM^&;_d*g*g3 zn|W*Z4z-`!IZDR1Uj|-P99J6tz1%5sN+~qYpAi)~5K4(2&ZC`pR?Low?&~>jUv5sK z|Hu8UvZqrjbFQ4Z-^P||r4wz<_*1;a!e%L(2@n{7^d~VkkAd8r>kG%?803fNm%+6J zfN;ao^WJ8Z9cKNH&X}?7aWr5DZYJ;5s(>yKjnSg$21^9i5J& zWuj>}OpC}`7y-K+32AHl6~`%{`?}uc;)_u@E)LoKCA_+IYmQ7aDbD}(E1ViC_lHy= zf|PKVGNM27NCP<{AU6yX`ecCKhs^x}8q!Y~WQYLYgP{|m74(rbPhd(}?EMHCfoi<& zNK0WE{bTD0KJSg93!{gY4b7qJS(5L*z==7=@YaEY^%~qOwlCz(>QKdfeI=c`{do2R zrO}GjS1RM~Td89fa?tqmP9xkqWUvf^L$8}{n#aDG6W#5JyfjH`mC~{ZWk7EOsR)kR zxG2O=U}n=)l@!2>S`VE72H|KTuZlyI{^kL7&9OCmMdMn|E`q1Z?hzc#KI2WWg30&o zT($BtEMk|#Aqmy=N(q z73p(=kK`Es1m6$QN__Lyn6C#GG1%ZfgxvPdJh1c|&)R2+Ytp}ZEZR$*PGg-#K#G@NC&O$Phu2zVoJUyiAwa6?8Ob!+#{(k%2 za(L4c8nkWi>S_*aXP3_qrL5(Dup5@2aJ=#64Um=$zzPC|6E4Eq8w6FC4mGCtQ8C$u z#HZ(FLK<hqd*5>-18UU}TTojAk%sZHx{OI~^=A*E+zWIxzIij>7~x}-US zQ$+aY1MGUnV(vkiez{1hxN)cmN2NqT-9!H4lCmX{Ho_-4zqN(`x>@judaMNv9}KL` zDO*Y>{_wjwYuRix`@Vvwj|A?NO7Ln7ePM6r~Frw)`b2=*liW zL)`@s;)8W6EfRv*Tx61h+*BQTnU$_cjyro{qcBGZ&D#2YmX^z6r4M+9ex5^#ICp+^ zfKa7}`K_KPgg@S)+C<%_*v<}$2_cK_utagx9mvleh=5|Dx{RwSn zBnT0+1$w5xqmuKcncR105wc1LPv>tZ(9vVyn0?>Iqc+ORjU76OAkaBmmkn=hWlx5= zO)oHdpEjY^r<6!KK$8`nSy_@o`FD&~M^{%?Ng^W_G^-$Uxj8yK3@FaV??$9hjDay# z4HDk-$rL?{u!4C)rWlhi+`_AJ`RIlX-sha*pUhpq;p4{!y>fG&n=tdC=k?6kQDKIUZb6xp~a7# zsrzI;8oIFQTQYtr6ZdwCgMFn$l&Ai0^*3nT3om?Y?@E>8Oa6DxWw!P#dcr6rm!A`X z<)8Gd@lTB#eY#yA-ElP`mG+naOaqq%^F{c#pxZtC&+b}RevjNCZe@#wk7T2QPy$oM zU=7k-DsydRWeoO$bcuX2S_H$a^tCPabKjW6i8wo8Qb&7<=$4-qPp9jRjd@NA)r81a z0v61?z_BcIJhGter>uzLtDq;&4Wx}~uD%%tTE8&;=IEU&>tv|TRjNDHb_0pQnstYCeOGSM zzz?^?dNP>Ev0AQlK%?xn2HN(}Cm3q>)a%+Pz|5&v>DoIw*b?`OTPl-CQdf5wDi7Vp zhkU;!wz)H+f9Nd4Nkd(OGOTi4>f9MIqp;5=sb_E?PbSQ0VV|A?>6$q0nh))mJ=#Bu zjbG=&wbz0^`Kkp1&T%s*$X-JqSUIepN4P^aZqS z@bSnTULQTB(MsZ0D&pV)$}x{KCa?;bXP!yKk{e7Sm>D(Sz)yM=V?-BrHwpIm!5y-6 zFmO`k^ezCcFh613v<}Jk?X{nLeBvqBQk1k$^wm9(xG7zJwZhQyUfyT&pG{MT6-*q- zg&Ft`S13L84PUGh8I`^kM*9urgJdu(O!+*iQann6sYKi^ihk$(g9g3&M|yR~;Kd(` zl?#!x2U5vqQ4cD!tH0hGP=e`bA>3&)BJK^%hW^KX`jkh%>lHn^%qc??PC%RDF|+Y- zOC+WMR}RRm-eRr-rB8XiD(Gzlfx$WCo2KJOPb&%Lv}HWQ&w}yGcuMC`jO}97&UI+N z5f#3e<69ymG_d3I`RSXpVMd`S*>pI3(R*phSJZhB^^mYw_#ypvzOf@|!iETE7(Rwp z9t(?0b>Mq3VY@FUA!$Mt@o2*_y7Z)^mcN}X!o*R z{6KuK#8?y9Z4aRK9vvnlUR150LPIqYDh`u+`42i|WaHC8YZVn2{R9t$lK0i$U}*J=u*X_XcD2=I6ta(8>ex4^=EP z>t*>o2}CKNbh#5vUv0Whktz?p2W5T}w?g`@y6D~BFJ0FC-?P6BS{F1m2^RROVI^RM z(HxF~jVw=V0M(LwWB9l1uhfmufZvW^a;9&Ni}zB^O1ez>1Kz{D7yo}WeRWh-@ALJg zQ@AupT}qMeknRRSIxmfMcXyYhNOzZXmw1bDi@%b7p4m*)zix zmZtZaSWS(UQ2hAzdR0P~vcjnC(R-9l1kA!GugQS#DeE}QnI4a*$DD7nXQFc#J~&!* zDF$f57G5^4k}#Y@k(ddNf>MEU#XCUKcCn#B?$CoDtovV?IkRD;rlJGuYUxb=hNkX+ za<=R?F%jQ}v7t3L%-Gg&95vB)u-u3CS@;brScZhj_d$n|e!dzlqZ_xxtn;7XThW7< zG+7vE^Tjo5D8tQ@GoTXjIrKwpGi;t&XL1|N4$)~p#kkQ!ddO-r{Q)j_dgQCC*5}VS zX1~a49QdF+9ei2_`Uph0P@q4=*s0Os=2QCYdCKr}*LKY~;lUE{iS?bI-Us5Gz4a@XTi{oy7* z>960`?2~(uNuTlYai`xp(d@D@5Q*ufg;W1$6+u+E51xUdbtT}RpNOv<&SdI(|K|P zGIf5GQ+R&u_r`3_@|EaVMhJUc`N8JNeAvHWg5@w$7ipR4iz|IBZGjcSaX9u2d+n^* zj-_6QZu$A_eMC)gTnU$b^1=4e3qC)j)3;P9e)`~GLO5&&R7|< zRW&q@rmnt9=N&#kS$K-V26trcr8Ul0RTKY!_V4c>0AUIUkWfB+lHu^un2D(ov7E-lr=ZM@QD@*SB5^A*D0FJp27@j(U?MF0)&m(&+ zIhYc8{{s>wsGgV9e}8jfNG8%;&SFhYbQIdleXI88c`!`RT|I1rd;2Sf&I&fBNtX3< zto>3azF2jb{oyFQwocfF_yXb8#{pm<+(jz6nFaDyh-7R2f%*H=-;+`}gx(iQG=YK( zX<-oLp}J@YYT9KCl!)#rt^0Woxv-bvbI9Ub^OWc)poe53WXTuOzo);B;RI&k6-rFqquOaiyJU#3cg_dE4)3t_?8@wYnN~$G;V{yGoYaO~x`tfLG#tR#`+7$Ormo>!BJydDi}UNhE3oqF z*kjyXOSZ*1iVpS*V->krN-;EjJm#8jXNV}jG_p}$T(Jin_Kf69Oj-f;P9Br-p0gT5 z$5t$)F{&OiU+UhSyPPsQRMbE`fLKV7%2l zxkPoUP0_|SaKld~w>(Y77x2?|6wf3MWdRnWnw=~X8TvxUdk=j={-^abf#PV`)b^~#V}{6r0P z8Vp;zpVejYSdT1irUnY`i4`=aDx@q!@^1?v!KEDmP(=OsxR<5GWfB=z^ zku(rsgn*rQExQ0oqUznypcIGQKVw>7{D|%BJUuR5x^0XN1$2H!3srhJ zosi56tP}6_W#Xc9*&^mrbZCk>reDy4;Q3&FtME4*N`quBm>zm;N`P72LVKijLtk4v zJUXI*+<&|KS-dejMs)V6b+q#O;PYR6K1xggKk5>8)7fMZHN0w^;j{Hs|kwn=0~4s4z^M7&w)&&PM<{XZG^!j`?cyuNz%zfAXX z7o?KSjbJiEu4{_Z<$x>`z{N9FnDWLt-^Ke3Svia86U0(R_hfNT6DqD*JToi^Z0whg z3iY#eSwN^9HyNxXql4?#W4qNfj28Jwuo!#?NZ-L$fqMRA{kiP*Q=~NveY5NF%6B7B zLjBGZM#AOWI9`9_(v6JS7unyXUyBd_ol=5PH}8;Y7RP>`3PwoXZaTJ{dvv(3lJT$S zO0nRgx2fgRIHOmcebJ#h)y&vJ7aWe+WHZvZN~cj{ldD2aWo%^#4+LkC7nMOZ4x6s~ zN!S+S1>A6-m^Y%!8|B@)oGBfy0mB`o7K}DleB!0%^v3!2IkM(={&sv?q!K-ej5W=_ zl}IId5`|zI$JxBcuB-}Ds9OjoZu53@2qwv&fm!;20*ct+m6I%d)9}xq39vtLhZa!z zc6PQ${wB!Inq(=2UH`bkBkO+NVLhvU_e5%gsG0Rec!;nU%C^bw z4sK`jiaX6+I2Knn@qF?u{i#RvU9;q!MQm&$_mE^o2rr?iq$4T=;7!NOfRXjJ04T&? zC;RaZuDRcL2(EfCgnP5tU(|8VTl7`mL_$OreJCY~MRzU=v!z>JhR@DL1Qm07X zUV$Ux)?>!BEYC8Apkx2aKaIC_ce%;&1Epx{JS(8B8kvTyibQCJ-qTehPs@;sk*epC z`s%l~qZogSJA^Icc-jn&IK#=^?7V}@llDsb8WTPG$Sn~CK7Z(E&iDUIoO~ocf8Hss zthCvtAi;UJA9x|HNSj z6COEa*IqO)4>H15#~`&|jQ|@kq@gsVpkYox+HvxWqiJ$_wYS!IkY{1>cYxda)&q{x z%+!*Ixw*N#)``c0)^m%kt|&PONYcUsg(2YXqZ`VD;7~oM#w2oBtUIg1BiuS>jwJ7r zFgx9N0FFc*Rd@N8F^heK6AyDZ{xvVr%L9aNSwQ6G)boCW;2Y0}-=8%uVi(+DIkti1 zVK+%aKtFqLZ#V=FBIXj8ptCV-x>HJm+@n`U(sHUQzNjiSrGvo%s4@W^kyKJ$6RMPy zIYaa?Oh!1UoVlFjuJf}P3<;n-&~2V}GU=rW&yQjOgdGmqR0YAbv=e=n4cH8qi9#E( zGk^Pc9F18BYcxl<9J_h8!#=^4l)bO7gdp#tVXT{B>b)|xwzh&L5>is|#gz;4@&aRH zG4L6+<+GQglv%OR5zpQEHKVy^<464~Kfcat1syD}P);Q001o>z(7a&M!6!7+eDRxD ztIh<4&+XLY?sQGpc}hap_hIk96}K1e?k_hB9y>AIlqs&w6wI{I~Vqw z-7vSuOF<-ifuAT4XiCmY2kKd!n;-g8bQTvMKQy4>pYL~adz4?;?5i%+_^u&Fl45x4 zlRpvP&bV)8qP*~jAcR!tIiWaN?n7C14jo-DT#exr&NwOP4JqnR6J06{+G4xfuSn?4 z$zkx|jRjQ()Cen*OJu<<2egiNSn_HM6nEK_vyB8-yiY}SEleNaWtq$zXtga^>nO`jK$68gf-~*QG z>6%T(w9S%Jjlu5#@kyQA2Jue;?j+}zts^0E2L}}9=LZC)AKcjkQTWD*)Z;$|My%T0 zruNY9JQ+VRZ+}(Cfuq5&5Aj=PEALM(XUe;kGw8K!*uHS*@wlW0?xUciBh%w*|6(f6 z7gq%Q-(4(qcyZS;)Z1@~3SQ@8UaV}q;-`)b%xM^m9WT{iJa`|kwWW4=-Thvjttcxq zy4oKb&Ez9c#{FhvV|p;2$-&7P^K_S=j}wF6kCh#sRtG9CE#0~pB+s6dI2218j3W~e zV%x&*e;RDxnC@N-#YdV2(csbWT#`Dga(~w_&TnYIQ&U3;5v6WjphXrfKxa+oK@*zV zK3D-GKDFY~=zgahVFT!kUrkLjzy$w-AEgZCl$+>=EQEhuUB#rk*U2-|(iktUdK$RJ z&1x%wwEZq*QR_cr6yH89{)+HBBzn#E;PvUueC!9Os=E4RHyq~Xh5NZ@2ZLT~lGkZV zSe)PU&hbVUdH&Q8FpR{-w)4RZnBHMwYillelzUe+YZw3i|4a#3p#t*e0qK;6oRWUT5=Th82spdI4OcmD#EgF ztn&gFjSv;D$4HySC0}1HaVij7Yw;;yUkK;((}&P!?Se=-iV_g)en?Xu`cEmAJwtol z=vouJb-fL72Ny|Mw89_swH2)doV#K!ZRbtdkx3tJ$Ft=AF7sh2X8K<}wOs!SiTUUR zMn{ytA(ycA$k=SFhJn>d^$YIHR9LOu|GK!V>*?v0&TY<=sJ!i$?GZ`-d>yv)O04O8 zA=-K0WME=DMiSe#5ZnXZ?Bn)MYqRb8UhTVM)&8Q`tmHGY&p69mU2HVZ@GrG8C%-<( zNQxB?56>HVh5x#L_J*&O(o$03kHjeXYNhz@r)QL!hy4+rljdH@-mEflM@I)P0Rg-D zI7y@3#&{p5kUUTbPBrl5b#ZaAUTaP6dMxkCYirABaXN53>$sa^xR`8=`dpd^R!&pyDg zgnip>;w@`WF7>LXt21;7ul}Lw?1h-m^#p$NAAR+HhQX8hY3qxk;2Wj^AyCjA<`e8G zdrW>l>hjAFdfii^jqGi2xw_xi=<4ZuooV86-UT0wXGbj+Zv_v9(l=5jR}H?ce|Nw2 zA;l#U;V|y{=g_~(3!yI|m?=sORP9gRAL=k-4ddHUk{Lj>VyzuKs*EkJk*J1OhL zP(z`PLQOC7m_Op*Ne@qXmj8v8s+~}^hKGa3V>1k`BT@5BrEZy5bl+3IsDGJC&XBI} zMe_4m=ivQ(&|7R-*(hE1K(*g1z3uC{LVK$dpVYblY&2u2ej@cLV0*Gra?N)=N=_A@ zo;zC%*F0ZOh&Q$}4BkF8`Cabtv}Kl*iPrY@NL(>*=Q8_beJxfptkrZs?|gdb9~A20 z)X?iAf4xTPKb^M^pM{L1Fz!tM(G|QN#Ib%mOc}bgs%i<9BJ&8w^xlMfeq89qxF)gmDRS#Pk=F^*&}1=KsT{O zNva%eMl&0lUOw8qthwS`M}8DDvl=ByOkhcu-`(AXrkfY6oJ8}eP6g8Id(&VW_Vp8d zkwnN8J*sh;!p!gSA3XVe;ySazD{Pk&28H-f9Eh%L-iCY zYwUa{XAa<_NB){`l5TF?Tp2MN&->i%&zE0hdx4?J7f&yM{tsqrI>X@QpN97yy+K4c zvw!x>vH4FPhrl?WV`D-^^kne(sf8FSf^xo@$j$AI(OB)}D%wQtQ;a~u-dU!59F#>` zA`$UU)%~si>G_%srgR*+>qf+K>3qh8cGM??j(7fRjf9qgitqCJCutCqH>U+xDM~BkPk*-Iq!5I-sgJq9uqN^MXDG5(7X`B$bBrHbB3Ox z6T&~KkbU*5-9#AIh5KHbNV*CEo7~nJ!WAV%F<9&Kr`uO`GOwKlM8b zYykm|OkaL(9%!qyu(Zr;ZzstZll1i!T+nkPoe;Pq3Bw?bw07Ga!t%Y!*!ZHV+7Co& zfhxdrDRK-4@~B`#=jP@}_<01Q3_c2^Efd=_w;=(YYDisXAKp0>l&;MX{q2sEBJHkV zP1v_(#}5pE)X@Z&l{K%O7Qo82;Sjt?|H_n%_#*PLk~NS%3(6vHXFzV-MC=qHJ~ho> z!HF+l{|@;9^)%jURcJ*uA74vzfy9?8I@s>;G!-d(;uA3$;Zwrv(ca-H zXntuDpWCR`OM-255cch0LAR#I6d&R9%K9L2G#+bM99fSEo3i?QK3^I&0tV`^`;9lR z$P>OMsu9Q0)`h#%-_~sGcH`|sY;g;H5nn$VH(H$?LZLa?tq5BS9=RWn*MyPXHK$88h^kvY$Sc=Z445M<1qvYXuKvt zm;L}lfoETDo6Upw_Vx--v_BHJc)v4xT3o9xd_5;!@~67d{Lb%0mPnm@ZyL=7XI9Vq zxA6i)GjB4+LN;CEV`YL%1iX&vo;8#UF(?2SXyEDPRm*1$0K*1ppoEzW2KF}F7nZ)MpNcuExJ2HUBWYBGnSIFR+T38r#>w3}yUZH8j*Gu%m znk`+k1`2}_X1w^hZ9y!R^Y%qLG1_{yCgI1w_l_qmx*Ttm^A*|(Z^A-d?$-o6t*?2# zlt6SE4?aRgMXgC=#KpsVr(@1Rcrk>1+b!JOL{I0b|1S7T(3XcTmP0`xw9Zi96)CVM z8tMYA&<)A;#_GxU`!MSW4utG3vd&k0bUuYxDk0hF&i3hU82%}%7C-j*sk2^VKSlEO zo-!%dIBbF$-JmLPVIeMWi0}v(R&NV6H6Q@c|4cdKVGpRt8Hdvsc$<3hhFDj+wa!B_-|&v@?VXz z_rW_+dU}Q;seFpW_SgW(EgD?ZtsBp&x#vjcN(FsU#v;_$M~;Bw3FSgZt08Uo7dE=Ui=mAKLIngF*7Z}WpaHXw zEM`)i(2^w`Q3<1|tCVYN_2+c+)-EKy@ZG&VhY`l6P1iQS-T&lsi~Y~PKR+J`4gPgD zs$W`cb)g4nw7mR$s(nrcTnV7D#pn+<=dl^Pp2Nt0SL-&`;NGGC8~{2wvEjd%{m%bz zZFhKbLb`CHQ>lLXGAnTZ;`@m7Xgn_?iBiAx^E{|CkFL3$t_1@PKG^?YPhw2aF z8cU`4RL8Nt=ZO06@Vay^DS3JU`3880_EGHe8aWTBst9tI%wi3!vZx%wHXTxa5XUxF zFJFC{nsZ5I3H1h7T^t0;61>*b31z+&rT-PUWE``^v>2}^;8TSAbneW=|4XnYLfz=F zAWRq{EG31M{V;0&-~1=ak)xv{tu9{yuiN9?>T1m5nFxlF3Z14{;AhAcNY9_Ii-iVk zn+8c1vNGg4X^_-NJ+a;)208P#-Cr({ncc1DlGO~L5!71_$gW#@XLNRUvc3UqsA9Vy z^V99wj@{c9nmfN(p=Sn{^={kSrCqz1w>!)CjkCd}gCZkevb^Dd?SGNT6jLgZ7N5fZ z4X6mGpk(@l1sM1;n8nxqI+u+uluMW(lYIA>fbSCzIMlAi+bgpMV$pcFV?FdjGWqhR z?WYl?-oh{z)xZ*o1%e65UlN(A=a+fCOKIqa3-S!=%B}GG6B$wva87+W`~HEY4O%Ls zu_4Zzs$x$b&9^Jt;Pp}2_qE)hzkg}tGNJOhkDwD5N5YOZBVA1&%PBf9kFr9Y_$(Ve zwJdV2GN&Z?*zCV12ySO(i-t{%PtW`A1QXAPH~>1is(yQ{)^%MntpL`&pR6>+xo752 z&CUixkX2PxfdaLW_|E0t2;lF33i^189!yRVMI-^@ojSBiliKq_rLT{RG(aaJLtWLu zpX}+23!emiHk;p?T-dt4LPk%o4hZ)Dt0ADaX;AsxPjDV6f9J!r8j2l&N|fQBM{M!A z**5Y0hMAfC^A1l!X88>v=xiY9=ra%b689_5MPU>T4b9f!6I1e}u)9z87?IO4)Y$d) zPLS~(v)uI5RJtGuuVXMUtL5Lnf0TH%0|NukFB@+Har~Faz|dQ*l%)nMg2+63AnoW+ zva$nuxJ^e=F4{I;FpxI@bETfwtHW<%KK?xPS_5`Jd$}8)7%^Y}`GD1wS5g!HboPS2 z@wm**nvs|q5Endnw3mERZ9nxKrP<-=VxlT7;tQkkGMAi2jWf}4zFPAF8vwE+{RXQx z;C!I~A?~FKMx@`T;SRDOMBTD)`=Yx>D2oqSHpdLHNn+@4yb)rlZsBb2G7{H&qELK@ zb5!-lRBd)~V`}i)kaEcCYv0O8F5{r?#zpiRg@>2JN+A{u`{xoOhsEiJ&Z0W+IC6Xg z3dcx(Zs)IhIl|m_Y~%619;(S^Og0={6IkOQ^9~y$=2qtQvgkZIj$HCSd?fz+_h>K1 zN6cxnLYqT#Fe9; zbrgc@%_pW87l(jZpa7rXL^%RTb({B6bO;Fvp#Xn^BN!K}SO<<(CanSD<^|C4X1bf_ z{2^{imS98Q6?3c;N7EA%tm}&f7(_Im>|e?`m{FEaP^{xu1ey? zFCPT-2GC*rGd24h0f?HXf_RFs+T6~HYHJgieg4W-7<6R;)4x-g4aWZ@(?5*6b>g5n zc>>z_mdAhP569+0Bdsn+Jl^*#fJFPhMt|;g_aO6ZAAF|HL@B{9eJ=G!$Ss~0e-DLA z$|Sv(yvq%R0HpQ@?#?Gv?S}rZqigNqb_j!hb6WQEc7mbexaR%c+asCKQ;*U^akY1* zkKIZB$kOm-;fR)IQ@oV#Lw$i**4tfrar2AVf}z$MQFOgVe)DHm^(yh3+q~um9*NH4Y_~Sho1^}c>Vmv1lI0_Z0;!c+l!I<-uU)$L@_P@OrMKFiz=Xn zu>iOaf}J8AmLx`Wat)eiH5OyPb0OAIy};@DXzx>aNFakh2~$*(Qs+o!>YLC$V^^S4 z<$;#=ufYG{^~!K94bKi;Ujy)~_CA{N)2c5B$TjT%dFLz6Eo=+b(q#AK%bMLA;JzT><{hQE({yT|N& zdpWzho>98mj$($baoCZ>XVM)??Yu5ba~3DfbpEcA+NmGN!ybWeN^tj_zC7S^Y{Ut6 zO?md~K&-X#(>Aj<1-9hc7s$rAFnQeauZnQnWOis?*(?qfcXg4gsr^0qJD{D0Bg05i z8qA`dG>{KV`tQMTq~QgqNfQ6F=F0ecaw5?%6f8=y8!zAGcR2QOG2Z7i6_`Rp!;@4- zlV$z0w|pwy_7Lc&$6Q-m^S=C^z1#V8x>Gm8WZV;o@E>|?JL}94dfviJSl|Kp$T9AX z(PF`yPgPy7o>lFaf25@c-<~JlHl06j8J&mXj$fnOZ_ahG*v-B7uAdvyEXi8ee?8q| zc3fd>s&gIF-XBkwbCP2>c>c3-^(R(C>g0wfqVbmN)$jIHK(MN<9p~*}b-yZ#X5~kM z>2M42U~FYGj4Zfdl0#U`FQhk7_^_i;&W~};Hut6WnCZDOqp^BDMc;xVNv=mut5+rb zQ>tj91d0qw%Fjg^>qMReYdQ9Ly&q34-gj~NMBfUCzEO{j@|y2ojgK(P0hE?Ejnog1 z@hk7_1Mc-Z{neXBw@tjJb^zXWqBFEZMo>ZqW=Cpc>a2~9wPJ-_eLgr z4K5J=c$seyaM5dwym7NoertrX`*uPPcA7bVyXVV26+%rI5%#jyGW{33^#gx2d8Xuk{T-$I z!kH*Ff!wXX7LGB`(-J0?%L4OuGIu*_dOFGLbM-5B_FM5pY7&NR2pBfb`wi>)_Q?8J^;rd)5o*D(FDZU{JX#N5q+8=>KdhSDuW>GH75iSg!au`!?-+DNDEZue zl{P=Fn^656b76w$WGHlLiF7+I5Qpje@CH5KtM0dIgX6hxT`=_ZCG)%D_6vGCZNt>4 z((QT2z3Ol9x@RCsjUB)+()@C}a?x?-gZcIAS3+`fX5wfCMMcVV`CbkMWD5JsT^ZdL zM})3xxvpSfi5Q?P_|HF)-*+Rq@;{|muoELf#l*xoSDyI^*Dz;m(2Qttm!BcabuSmp z#<#;Ca~Tat*z=pZ|JB0%JSNQ!#nVIivl>rRUvIEt*IlcH)L(lYMJTs&B^Q`3@a2U~ zeqePvYC$p+6J}F#HJUz+_V1)>sYe*Y$YPrtGf24Jn`Qb#MSF1kIwD0SN$TB~huk^0 z$-gx5NYQa|PULA(y6x^*FH`CJL;$CWD1k!b5A$ zX0pjbeO;SPFcEWsdgEPX6LzsA0Y;W5}P|`I(KPT2NOHzTYb$3 zSzhO1e)nPSCsqbJtLE-2HciPsSpb4uqsi7u2?6*~k~pDP_obbPf8S=%H5se9Vm~n1 z_=0)!RNB-Eso~5v)RF&GWa-4W^}U9aWj59u$Dsc~ed-)NWaJzk|F(2PT&3|f8A1(G zH^A7Y;ag-?%m0ODluI>FmmFBSJvjY%tWk*mgJFba27h`8VpEh8!U2Imb#aluVHL#d z-|^&`eHrpscFOqDG4tqUBKv!cbY2$R=nAP5mho4&V0#{NA>#M+!Dk70{f5^hNc;% za|9k(g9W_^b0^4{){Dt~n5Vn!@t61n-@P1q<&yi@t<5V(&0m>6=a#jdJxq(h-&sh1 z_&xxVVO0gu(*%YP^vuPua}ob;H}`m5SoSd7BP*swy}ds9y}eEOdvMUOfI%4f5DgJP zXH&_*q3Q#jZoi05;i#G(!U%pP#|D=pQC8cE8Qj->;)^;v$H!iDu&O5e?bB_NSwAkHT5s(?DRP7LCv13WYIpVDZmyZR`so2>uuiHaH z`OW@$Vs8i)MJ$^tjMDkmUAuEIO?~ezNPVCI z`(i>Dv8LiyOFy&B3$;o{>%E19(odUQT*->1(a6xHkegL-$j=0q{sRl5MVP>bxorg3 zV2Sz)#+53cjWRF&fmlyfop>D_u|Gu927hn}exuR^}vRg|z68#i4xq^eyl!HyUg(N9L*zMlxQmIj}sj0sY8{uGln|uDz z@YF$P+EoS3TZHDToU8F<=g|(C)u&};g@R!_G4NWejE7~nrnwVm@m{p%_ zAeZPECbs%W*F@dM5l>SHL{v^}wy~N=a7Aj_LXIp!QkctH)vxq)wmzT3fj@M~@2mI* zm#2PitQr8}r|--h9CUgyD6ALtOFaBy(PuwtBrNqlF%6)&b&8aK~d$2G8$P1l7 zGy?o(IiORVvo9^e;-Jh@OsP^tnfR@%&sB~kx3nxDmTwe?i>Q zb3J!CN(brtn6(&weOIR&m*z_IJKu}V-Neq7W)arkD&_4I_RAqwgSQ?%sVv-G%A59w z9rX6__k|Q^%}8F4TteZxJ%8y9=2DpO1M4JRbg#d`98w}dKv=)NSa6llvQf(fG81$g zS&)e+etMK*-;ZsB8uQ3Q7%olEiuSMPjS4X#M~J)MlpFe1v9-VdNgR@$#> zc#(OK@59i?OZ1#2nuz)6jx&a29qXaHTzzl$PuEqYFV#g)cvuPFCBI&_#)ieUGXUmf z8YMEbwxMVHtM+p^EEki2E~#@5MssA({CY*^)W4q49(+3aBbkk#q827TH&XmqgPT*v zJTJ5JU6_2PH)}NyBI0EDQ3JBA5Zh*?XqxcKd=+9(Zd#32%^`nII?xK=eeRT}LvS*+eL)8`^bgl)S zcSNk{!~CW$;_FtlI6Z4c3fAa4N9}|4#$XE7jmZQL$4I7_tR6Sr1^8?=(nO!>G4V#1 zH$U;&to(5ls5?jXrgTAf((BHrL~B3mqc05B8&M(&CN;r(U6+3^j40j3pvMKG%6kk? z9cHovo}LsuTxp5to_SF@dalBq2G_{lP7KpUu3}#FOXjzuD*!Bpr2o1Q)l?)&3McuQ zuIe26Y8D+x<^~LA33x$*h5Zg-3g)QI%m2BYpMo7^mU_mf0=l(6i=xTXtys-3i5wuU zL6}HQkv%4cD&rrV$aO6eOn=+ANPp6ol*Zt9K$l`7GIxBL?Cfbe>FA{dFA7@n21Yo- zgAS?CJ4;$>ag3}=Tm|!qSN+5=X2j?j_s?F{(-ZqFf7md*eL^%S_c`u@weui!Kj}L< zqi<&zWq9kLTkJ&xVT1OM5lM307j65MCHb-3OfU$Q>FJ35Z|?5eUL}}F^s@yIAZBF* zdJS(I*dq12u3836cUMs^OVtXD=5_Op~~QX#fvDl55uW+z{X{nM|aejAfi<>*cTK$H@|w()V>C-nmIpI>ZHnWTA$v% zE_wtVkiBioiXrSG<1Hv+Phd!V_q{0`OLa%H0|uc@s@;c>=L7*zl`6kv0mv_mT%`@c zrze4@cM0m-xULatPpvvNjI!yNHo?`XAVJ6 zpY(R)jnaEB!e)5B%^y0iPb6SbWcMz}M*TauH+jn$E$EMP zifN)yFut=MGa|H(K?D_KX~B!8J~lUE>V*Xd(p}1dS57?sO#+IS!bpFxW@Y~%gYBJ3 z7Yr&$LN`ryJMi6W?VF2%g-|*MTwmZ$3pJ`>tX~L!B#WeX&#-I3&K-TO!WubE;i0R9 z*UqoA?y{};o8kO*SLxzq*M_EPEhG+liW#sKu#BK1K1=xh`*%VT5{8yaBNQV>c4*Ml z3nw4JoCal4fA{(DqR|7k-mVJ}Dr*8xfdDUKDg@-V+Cy?^3u=W!}?0KTc#}(7AU@2(Okzo)} z<#AziV`iWMOB|w3srGxzl@%)8U#^WnA4b?xXvB&h`(vtitTHL)EsV^YDy~jStVx z+&qb9DX;ZO(d@FS3BBijFyo5Dy86Y;wSumhY$}&~%QaC%#%%RK>eU1dQ~ialKT|D= zfxvOthFf6Fozk%Z_+`6&!=cYbMMd@(+Y<5$3QGYA6M+Wz<-S$c8pszqk5fJ;;3AgV z2RKLUOBKNRLDGNS$;c$azcG;qgU=tlHIIL;?NYB(8xXp9qKMBzamw20*ro@+YPw(X zgW7g$b^^v*5e-1`$)@sB$5pK%_T|L4=w`fsGjE^8RkfC|#haRPs)KC~OSPruO=7ry z@XoaStW1RUHzcfKKnpd@skDLdntHc3nd+B#eA(>?m##t2wOL|>sVQz11cDHwF2iLm z&Ml#^+fbA&rStjp2$Q+q#;|vX4_Q@|BXJ82QN)aTR^H$qe+cs_w>^Tj$MN@^|ETbL z2_c~*2jzn2|Fi&D^Bu-l+Gw76+7?gBuhsGdp;Y+y4opP8_-aa_VsdHIuh6 z9J9UaEShE^!JuNv=vi+uk%@1Z|L0$Eev!O)+1C(9@7?+6I#LJy@c~E}xH3YR4stC3 z+d`tJf}AznDR{UbYIgF$z9AAx=Q#qA@Lx|vVxQx06C$gqksy%g0b;k_ujap^B{+%%c$C}2!Vj}jJ-$0s8nDULd7LkahdXP-T)X^lwiEPvH}B& z>}6QgHdD#T&(B{BsS!@3F8N08SpT^$YU$5MVEr?C_uY%f^@Lj2F#ony7}yofbA}^| zCO*>eO((+p3c-N++nOSCKsd>EwhV>qrMy^ny>4n>EYfG<)=& z=!DAUv?~ZxCmIA|xs|5G;eU8{=xszceEvlp-3EM%jD$`KD&ALYzcTOASgg5%ckRln z(6+O5nIF9{3_lT-RKZb#UQ}RTmpFiQ&s3|1p>34~`x_jHTB}uxG19BM1Rs?qEM#+} z6u5>g?JE!Dk;=oPc1#BRnE9J$@qTP^OXaYuLT0Gttyb`dY{{ZK`@aE+!O}eF6vx>8 zuznesmZ{O@S44zuT-h-D3vlr?M3xKs!F^cm_J1GB=F=ybMHgHc6d99~gnpF42*IXp zu&eQ_lV9i~&a9fJ2LF!s7zgE-)hgr8^)4s&t&wl+Xbv0ldRi;VP+@eB2hP=#cHpdG z(%Za)SehLNO8=6z-?knWWa*j+`;~>bEE^P5^IpW{6K1)ao!V2Eqc(o(V3ycZwD5-v zNu7;-4NWIWjH_1&J|lU>-n1B04N)^O{;%F*uf_r6pOBgVT|l0$puyb%tx4;uies}n ztmZ;ETn(|qHHSN+xT?;(5&xLq%v}FUEr?BAMc|>S6jkGa4I^#yq*THFh3PDJuEMb{ zRLnM6FmRv^VZSoV&Li8ol#H|>GvJp_~L-2@$NkJvA?@LDMeiYCxB$qU!Dd_8bP zqp`JhbSC(l)X!r_&6t??4#5P8;|!7Eji!!{*i&kI9ST>mF=A<@>gwj*)9JVn7*S2> z!sA3tnMBB*sTXq^wasFnZv)^8*9Ltn{<%1xtRWc0p;l^yB4-S&m@d86j*akY5}k2x z4Y{>ljbUPO3UMcsqZJ-FLX(B9@#Nejj6SV?;6>v>s&K`=2%eF%UtRWr zKHV*AEQSaVlT{cIK^2!(&>lN<2z&XjL`gK1lzLdMx19*G3=*kFCnm&NBA<#%Txzk9 zINO|Zr_GdOEc->oZ{|3NSn|eH+oqaK$kR}y;~{QIh{9_fdaj70T{q~eoTR`WocFa> z7|^XBwkGxTdtr49R27ndIvaoNVH=&rCs^putah_Ty0%CeRUko4C)S_{$DOblkf^xX z1jokyJ5b^L&i)ErT0uKGlu(2+vBt@zG8rCA?WAR94vdbX*DW!anH{J06{z~)M0eB_ z=NR;f>_PC8l+Ux1ckp_RWl4g6YrI*AQjWpbrbRI%=qu@;ys zlQ?ra!*+bG!q$2uz3uu#7JX_+Re=UKRLpw`BYTEFKB#`}dw%9GVp8b)Se5~U2=bbY zqE9RFoFIgz3NSG-;R`V*k;^6qKMXlv+DwpJ78e*eR{eHgkHE~aHU z&L$p9ovWVnxdTM`k!0AE&a7MXyOJ@Yur!9Tr}cYMxRasigUJueSg0XeRvN(KNen+o z&E7!=Qbc%3^LqG_62Xw;&F)wZ>sM(Kmu_YME_tmV1g&L4GheN5dlEg1l?c3GXmAa=` z;gNAj>aZwE$vIVcRu&m`gM>IGmiTOAna*T&eVJ#C3QnB-hago!6dGzcnI~3l%@Br> zp;7aMckW&9YX8S>g0WhbaTZ9saTJ*Y!(9u&?s)EOaQGP2U6*}a*L?XFSM2iBxKVCoN(f(4fzPQj#zn_Qgp<|6m3CC;CeCnt8FmR+xVS0(Az&7-vFkM|BLy%jzB6x`2M}4C($ps{kcI92$L+ zi&lfXWcxt&E60+KS~{M(jRXsko709 z4AEBA{wm+Ve4jWx=(6zYKTlm^3%IP;SKsKE7~Tea%E1z=<;f@W0~qP^Z|@mK=u$|4 zk4?Bc%pbR;6`_M#hD8A$fI`r4xEvrh$A8= zAMEb-pBaJVk!rUIWt8C6z$Zlhf0rAhDu|>u5BY@6U??)jVetbq)UcZzxtm}reo95U z_(Wb+vg~KV^d7(W8r`+93laO$mmG=Nz2k*Tn>us~_(01c+i@&?l>O_3{d-pYP_<`G zj{psU2;kLtIS2W;?ZH>BwFo{QA~S)uyD%WqlM`eFv7t!x)=`0YYDlu|@*qMGSQG*Y z1byLxtkCk%OC=<$y}UyZbtD9m{5e&^Pz){Q_*s0n>zfvdSf}oA;6EOi^#eOO`*mao zTIc`>0`H8SSpn*5i$PRisEsc_A}Wm8hpNd!5MbZzy$MELsyqoYDjazE7Y73gn)bK0 znJgOdFsWZMLS*=^*vF;-Keu`5%K^cI4wE%-ooaocq^#a1VX-7q-{>ie<5WQC)$I0G z5#`wl!i|p)K)A^xch?VbooqT~g@skY`EZp#g$ zER_yRjl4VHg^Ld7S5$xSiVoKf`{=iWSBEaX;y~TxfaVF()E$LVH29maMGOqk{1?y^ zzMazpauk9Z`wubC66Mz-uwYT)@P8{~sZ_!L!L}TdPzL%*7r1zknnhZAX2`w25d93jDHQPabJsx$Id^$3!!j920k2KCq&0y zBzoq_^|es?2`glS@SGiCK87*>X(o}##U2d`hL?M%&@5O2GbNW zY=8?f(F&Lvdx;gF_5LucSez;>J`2ub7AeRyMti)OwI|%NC!AVShIYl)*0TO8TsAbV z*PJGxV1V=eym<(%b`=Ul+{Np3UEWT;7U)0h*89f=ClCG>H^w@TF!i zzX?VDyUfX4u{!F4Lh1qul;u3ccY@M&K+=?pGPd4Db8I-SA})+8i*K09_|FMZeps04 zyO>6Q*nKZ7ZWp?oCSbqjW{_w6B+V<+ZqFDGjtvb7@j1fD;!J(mmLWOqrvKpy3y#RC zDWJV%)W4zm_SO}6D%qJO^v~!xk>C87LSWR?Ay3rzbD)%H4|yV#|H=yu64yBdyaHhY z+L&xZkgjI~TZ%Amy11b#F4~?w##Gquz_njutZK+3flNS03OcM@y2N2?Y;ux0z$7MHHlWw#f z0S*yeO-kPc21b4lTiR?InH~#1IJ7+}%q|;NO%3vaL9;Bx+wU73Mh8k89{m?RLS(Q<1O-i2m4x4~KzCte60ydmYG~O&@Y8>BVPS+IGPk-+GJ)TI zxPGJX4|Z8v-#0~}{ej51BPEy}Qb#SOtm-9{#vq~z%WJar-RBD~LL!3*%5eDYov_R| zWS0l53H{%%dOp%I=B!;-_-!?4a%&7&z$Z?5S=NdK4HEEiISM>XCW4ZZl4@#hZt6Cv z)K65kF%qI1(Rm<9x!#E({}(w&*n+`8MdR@Ju!h)rh|NSRlv*wx(!+uda+Op^hS`FP zj%8q&2}ZzaorFO~{>pIn1`Ckz3?qRcFgiRq;q%tj6Bs?j-eiK6FcQYa099M|_qJ~% z;s?sSeH`|Ez)F<+Sm4ynbH5DT1msoxzoNb}D#|Wgdxq}rZi5!-mH|{iLTTv+>5^_3 zq(wqfK?UhXq=xS9PU-IE+q~zT^|99cV9h-H*>T5p=YHZpB*K~&cD#wZuiRl5Y}CuN z9K(>m!NX_e0-ISnzl`fMBaDVY3VLtKIIxLWIzQvcmWmQ}J6)DZL7_br->A__Za(Tw zFhVH)Mte)(gD$x&QkqT#4Ge}zo!c8H?n|s<5o6-`r-b%N^lP=utiT?~}dP>%Cvx_!p^=r?NJ`9+YT!e6Zg^CKWBW5kQZ;bzdsHC*u2U5r@yF(EA6U@*b+Y^ zR*`MV{`k9%A-UV{Im;xs?@BIG8ejg^8w~$t_~5#z&cHA}TlHC%_{BFRmr1WC64Y8Z zSLx5D7vzeMKYzkeD`AprX}FU+94L5BYIJP`D8Sk+0|(K(R5GHF+r72evm2oG-6i^i za9qeRw3jZuW2cp<*J_T7e}{zPqdGkr8rtA*w`}=^FoB@}_!yofQfwlh$yo!>^-855 z){ejJKVjBafd!9M)Nz+A36_co%q=X2>hsCVhe;yy`L@Tu+Bf6DVX)OmOJ$NnlyfTL zG3s-Fez>jzfvAW`ntq^--l6jH$BV~YD48vH^2I^EQ_arZF%CPEyf9B0_(^DqP$j%x zPH=fZ>HElj7!Rt8Fgl}u-IpL%4vMn+#y6TrZfiC*muSHd4(!hyGJO0SHDZ6q<~DXV z5%V&7$*HNb7CgZn`d5OhOi#4D1md|R%cL*hPBJ1X8s4c!FyVbKa^Xu6>^+FCkPLTgi&cI5hix36 z9%(Qh?elLI??n3YP09^EHd8BM1+yt_ZXg~LQH?M$CbfB5o)hfhG0|W%4%3Db`12^b ze65Ye{8duzhrdjbf9T#;{{{O&WO^VbwYF~*2?*od+l+Z5ql$MF4L&@biU;VDT!%F_O-Yx|)0%ySt~aC(WxX|}Df|EtgF_phle zC?+Z{tWF4F%M2}B;EH%#Yx;geBWGKqYtNjGPSt8e0&A3KHvLSTVI+PKWkxV2zm4-&B2rMoec3)h2`*E{sL?SR^f(? zx~?R}T+EQY-*2|{qtCA?c?8v-D|amEy0IiZ>GD@+|E?#Owf$@mb=Kh@1>L?c0r$W? z${PL~lP-7ET~G2ON8-a1iWfBk7dbM6Ec7>d^kj-JKjRZ1{jx%0W5A~T?SeM4CgwT) zcZhH!*c(O5I#XUwzZJR(X{Aw=_SZ@aY<=u}*1G24TU;-{nO}QP zsQD8wOJN}@;#hh4>7{4zRiM_9l95h714HxR7{_$dUkK)4B*cXuTMCJR0Tm+KZSXI1&kx$y;!K8imN z51N;xHUnW(6N1om6{k#%%A*f4Jj~>s&aOT9jWjUNMys3KxYQYq%zwl-hHiY?RRCy!*94kH6{)sZNG{$TT-_X$F2!CdxUS z?8cRb&_V=6%p&fKn;3gxg`55o$RE8#*~bVBumJ$yRf)0{aF~jMYUSe_X-v3CpAgk! zqVaY_dg!12;5;<0)(5IO&~<+vOG&7%Rf*MS%)x{}ZqzbC2cK9yNS&%rp<#6{!dRbt zH{AGHKPM*abnUihovU0Mtzg& zV972qtWoLAM8#=yo#&1^7Juj5n4=#N{#0&|OT{6{l9y?z`~|pq&>mC!J5n5v{~WOb zP?Uc)_|W{dGSH?qm5bje^RU_nOr~B(u-~E0V3m-B<3^1bzZgM zP>3=LH2w$w1|8&`e)1tkcgk5a2Wb4z|0?^Go+-bV4XzyfkUEc|N8rQv3Oq{JDsBj? zB;R$kLj$hZ-}^Kr8+V==8M$j)Wd4Lh(T7=v&ZR|kE}obb?WVKhq`U>8-^>X?)ZgH^ zT%8xs4*tfP?^h)Tu#!U z+R+^0e{TiLTx*N|Gy1fyF+A8UxX{lQxc>tb_m_;(6kR>gI3$O?CI6aC+kqd$xW2uY z*gqlCQRCQ(=7M{3e$!a20q%RxrTOA^Z9SrCo8FdXb>+O~!9fBAf^c}}+pM9-Y>yr( z*v%X~^W^L%kY6EpKe@1Wz?R8|tL4-OSs(Un9lSnCtq5<@Pa6k#B;MF&rA1p%x= z6}G>e`;(?WXJSqxsXwfFjx`dd-?BrldRy}yB`$aB!*6UR2o65JiKS(3QN%PCp3!^_ zXe0pewh*Tm2>Psr;K48B*5+#e*HNR^>kG(@FBk0W1Mz0$KBcbwwm!?vWN)acpS3n_ z(<@q!k`+3|12JL7%c64hQ;X^x19*T(Ol;@m89YU;qJx%}AUs8>28~9Fl#-_(Ion*o z?}BvuncM5pLn0`28yAeNe{_S|DQMfK; z+;p!Ndbw8u?0dk&dHI#J1OZR^3}@!h1t{hk3p;F4E&O-i*WB}_%nhG<5nifh@hWR9 z#2IFgtq_>!z3}ss)E%t$$E+Lyo(MvIn7Xi^;4U)ue?ZKNWO|U@`nc+OF^h)}{l z&mA9qOPK-b-qF`!6D9*Qz@p^F_LpbJapRm3mZH(C&tB>;yzTY@Ja`TKf>Us;ta z&CL^Ym8sX4|IzW53Gk+9gv+LH2L2gJrpPic+2w-!i^ooJf~6KdJ3k~Bi__%29-GD6 z-~+!z2%Ny8)~0YM#zM0y^)HuhJBsqPd^b=p2@~nnwinwP$C(X80PVryTX}izPAe-b zMbqeV6?*6R`V)WFs9_Z*AEcGv8Q69EmOdfoPu1e6s^@}_-Vhy*W4_D?cU!T|$(%W$ z7(-SPO2M`8R}}^snX~t@?=0+6q3sjM)~M>}hAk~Ex>TKFlOv!tW}7YNr(Au3RPi=E zc+|hlR}Tt7c<-LcTInc66|llPLG{M?nJ%#s&t;mD-6s{_>}4%{aOunz?~;p_3L1hS ziR=EGzgqGctBuhjbMK6Ya)E7V{W?K}0ZErbdR2nQ+D$D)5;m$8GC^gIfNu?OdLiIC zZHY)Fg^7%xub;fOah1mTv}=1%NRs?&80~z_u>RkwJdpHN+D{%6rrHzmho%A%%^&|7 zR|tYHxU>k;5H!Be;zID+G|l_JP&XIs6icJCS+Sl>KNd2nvK1e{c?-?w1Wpxg+b0nA zFM&dr%@laY-5!M%(>NueW_qpt0zSMinIC3LIQ#i_i~m1!MaGsLSwo30x@qHXH!TGY z*P%(ZuOQPt{lFW&UQ>uFu9`o2WM99uWRw{CJOD^LNUm1uYksvb7xjkl=|OUbJ?z3Z za5%74Gyd&BjDm{nVm1umu$bQ33hzE^0iQbi1e}eANZ0gT_JRG7 z4Tls3|AyErrJz1RogmlKZzBrd%zFI^`RA*Ex}(gBpA7X~H&qJAs(SON^;?O9rITBW ziCY?U#t0pjrO|QJGXCtFa*{U}Ahp5QIx)IHAXR4B?yu2PQ=9PN9if1^2~|gCRKeCRNS48UQjNF6F=&nm!xX^6F*W+j1^+-DPhfd zxrb50Q-2vyxq6q}&)e|T^l*jOwmOKNv3ha7c>KH1`baEylo$UBynot9LwXDc4vY2!xXUr5*8OaA5v z$qP;E*N#uOuf7knQ#X+P5B&pxdkXi*dm&t5Dx|BO+tnTaNec55vd4#yzNITO9~2IJ z@Z6Cr$T$Ke2y+r0(}bLE-z;_|Fyh35dmwM}!VFP4b}DxmdjD=IA=K@k-nSyXlOsPbI=iKZBw|>;PEx?oRkK^)gibgyy+Um7mdU!HUVb6+<4txd zU9~n_eu`q!*(#d5gjFNk$qCG{qv`g~LGSU$BlPthX9KOxPx*S4!zW6$o*2_(G8jui zIL)1vSwkD4tZ>nJ6}3%SXP&=)IXS;X-d50dEQ}iVm7#Mi&^m&EKa7)od@TbH4t&S4 z+?njYMel|5h`gcxcgqLenb>t&GV>})TyWHo;TAc86%d)p8=s~$3|pqgH)hLfH$f|? zd}ZzYUMs78hxD8W7vgNW`;Tz?5#1`I7pU#E(;a{7mEE+4G zq8Y%V+;=v3HE|8utmUW^=#ltw5E=t0%=RkJ_p6`VvjPU1%(dGqr_R2xP{S(@PHVq4 zfb}~lJaD1(JBl+{CGCQ=Ndn7$^)YOk<@-hh!;^qxq~pLUoSRj#;~E*Rtwf1(UfMmg`tk z#mzLYn5-l9lPWV8xcZ^Y#rc=4r$G3fl(W|77urc@_L<2ePYaFAij3r~f+XN&*l6 zC7zu220rAR$*R2Tck(d0SLdtzj_$8-(zMB{5_FhF6Xy*4)bA6|MC);~eyweQhdir( zsBVmLNzzX6Yn;e*byC z!J;gUQ;xOnAhIhSVoN;vYpzZWRUb4zsSl~*=B0B2y_${DSp?iVT$-XrwGy03Ix-K) z1OQMvN0Ds>;I)-AvXj074Vls|(F-c6)dCYiS{bpWd1$Zr5Z%MnR9vwUa>Pjx9_%#@ zj?2gYw#jJ{cX%$Ffu{c^Vt5vjx3sqSOCzIdav>I7p1K9jCv7 z$gD0=@u1v0H0}mMVQ#XhM3fqRyk;Tv$l0f45$Zl4WRQ5wn`VEH{bd+W&>Cqq z3Cf_G>8jw@#l9K?!E_JaYuVJP#!TBGYQ|||v&6VuD9s$Qz~o5vUeyb-f(+*-_|qv% zGz$L2G4~)aEwm+BL8f(CuPgw#ayM;%-Vj)-py8C18&=wNHc9u+j0_Deoe)v|nijm~ zpl8YBG;f5@f`QvMoUTFs1an?YAs|Rx9E5*DjiG4Yf5)HT$EJQLVT;X&NV6V|qql1K z^`yQXDY&WEwA}bCqBFgYF1Qp`yhi zKaS3EZd3NlR4xeR5-r#@+m?Rqj5s1Km z816VXydkb;^zp|3<#$T}{{3)CL(Z+y@X-Ll*t;sA%PEOM^HdsTr|JZfB7nWN_9m)u zG_+ySL1OoWNT6bgU@dO#i6n=G;tcpd7wvzr!I;$5oN}|!$uYn1ggGm`-BmKIcZNQ2 zu*%QT>1qPs2z&}r4EAdXN5E$#^A9fg*v_o89(^iIq({O-GenG^2Zpr#Y-E@fLFXXB zVkE&5uE)t6)|eg~=?9#CytTh?aUeUxl;7tQXC*pnap%~vF61^+x_na{Sjo9Dw%&mA zM6^76{Rzr@2!RNH$jPBNMtX`)&HV)a?#2zQuXAX@GlWBnFOli5F!K1*@rEf$5(AI8 zp|W+VdK#T<(0sK`*igyH(h>vcA0UvdUp8L4$JXv9fa;Xmy>I zTQR*sk$vmrq!us344fP(^~IUO$ny#FO_IV(v}+CK30iY(7xII?iut=1bAjj2g9rTX zK(sh0_qQeUeaoHH=Qxk;YJ!Wcfda{wpBYCX-Z6KNApY=^X+Imnlb4zYpc@Tzg7){; zCD(n7fmGGK^3dha^`XNSawELi=*tPc*4a6~$iX;G!-@EN+NNuRn4c5pOothax%NKT zWfKK;QD2VOR=?mmYkvEvd)2Wc#c`RUzjN2hSMuU1m+ub$pb6v2&Eex|y1zK=xyx@G z7eW`Vbr&xm`QoiPSxY_RKq@#Ighq+I317(-Qzw@ zsC$f+iL{{5mEf$4L;yjFt!+S#WqE(qqdRo2+w$iuI{xL&9YgOM$28pFO?` z%ZU{ScVeM>7q;==cL*wwf%=huXHH$9#Zw=?HIpXmTHJp0=zX}r#%7Zu_0v0Q zfbD=tn+7TCu+#X)fA>NArTE}>(pYs21L{%d%rM_$KL`tDJFb1$m-GPN8}~S$k$c#g z(j$f!svCm!=oou1#0bO0j-MCQ3o@U-%?$qXH4vkNp;`6iRE;r@2E!-=Lzjw0dFMWM z3l;~d!2ru#Amtn8+j2h?;h!zjUO0nE<%vi=*!mtQZLrX{P|!+<18}dz;9iU;3CPL>7cS2sX5SX zEncV~jk_un|8Au4!0%e~d&2?0rG*6MX$bn_^_^e9vqQ_SV=HAJnl*%Sll8fD*KVMb znHgJ>3Tr1NsuLR$;b?5_slMUT_p)s=UsR`lj(VjyMl&U?d?YS$s=&0VtGfqmCph)y zl2IiL@}VThekMlTaTx{3-;_L(AzP>xJNtyUiTu~c=N)z#2cO4*bhe}hKx{0G=pO1+ zd`~e-KZpPC2#BJ~^H_@kX`iKh2;_cZKTy~~^vBPmYc4MXM?o&db)&O8AxQ14isV^p z+x2PE9P%-OmIv=v?5MbbTqOuY@)@?w712>pW60Ekx1-0e?wt9<&n+!~G><80zC&25U%39qsLiF+IO9xbOt?dlg-_4kQ0 z%>^_c(SQDtL$3?(1R3|Aq8K~~?ScE^MvWUSpS>QH%xkBv+s_%n_utRey>I4Ev`t0r zIlMAekYhDb?Hc4IFjma=+Z*iD+a@1HH_hI%Ug)Q_-uc~gn$F)5{Ib91POe{4P?^7a zigVK~)7c;!aCURfdzRC|_ya6_Q~o;152_&Vr*g!k4T@7PbW>kKUwqs5iCGNsyRx4B?x4Hdit=~_2fIjAnxW?rgDvI45NvvScyz(j=z=Z`Nz>b)89uNm8 z-h7rKSoM@@>Q@74iUWxQM!6vG1=A6P5B*|Cd?D*r>d@R~!Zr5fx#8-kIg-NuZ3ge% zvkpCWb*!s6gP?oeMx-ZvZ$0g_kxvq|qhAO>ZB{h%2Y<7RURuLbqS=uj3=iNnUD4b3 zOd3)6JuSz%J{3Jr+l_nQXHc*ZBbDziI*WnM>qV@9A3m$}nI%%fgKF!No9R9;hT%Nk z51r35!Y8Ky=~umvOw9>TB(>kryn(vf0rBd_K@~!=R3%T1=U(YUFegJOr6kp^=#^|z5nr? z(c;g4F&(U}_ol2eo4RA9L)GSfT3tT3&Cw~=7b$PKFnXf@98q;e7jPo8+CTn6H}ADy z|AspRF2HDJL3oo{3^5d3;=!MV63*fZ*BspyI7s@tUiYp}IVTL*ni^K_qQfYh*ic*@ zlWuh$L%-9%AwBmYR5dHIX)e|IPU86C1J1}u>I6k?!Y`}A=Y6D6G9Vp0T|dyI|4IP= z%kj!^Ud+T!g6>$UX7qGi5@~e|H;P4rZ$8UoUGfS-50Zz?vyXWm(sAueACR-hHP7}{ z_~lotT9Tp13nxtXTM5|gYYmJSjko#!%QAQB_mYN`FB^|BYdz$zu*xK_A)`qRA&dNe zF-2keQa9;-F%8!e{wMqcOgB5crfB;iD!rWOCL9Wnil^+5@xI}Kl<^8TXK}2baNyRw z=+GeB z1hG?3s-Y{nT60Wbdy64KZAk3Im_WFt$0rX_MIs+aJ`LTu4G80Qxos9-hOXt9o+TwZ)sOJaD>_E zpR!SC))NNUPbv)_6<;W~T?dmP1*2YuOLEO8&PXD6sStV}iUeoW67J^M$!>){io^GY zZm#q+X+{YOk%#d}YRw!I*{VOMY6Bgts_6H_7ra5d6~S(B`MTA(blKMK@%r)88rhk_ z^*`sGu0p|6w+}mp3(QZ(j7d+?4-lRrAMD;a`9;5j>QB|$b770rcaWO}5B$;fMy!9s z=ie4?=pk+BkU_HIfP;sWL7W>5XZd@`^sL>5IsU|Q52I7%ZdE4t0StmRDLr|((vhy; zE;440z`91{Is$vyRot&4C#PuLUM|Eh9yz=RI8pMNhGm%Sfu{j#*aGR@s`bJe#W zv>z@Bg}|lA8S*i1jt3a7M}WC?c5V3n-p$hD9=gSsDZR#dAGnjcA6CbM&i5ry#q}c7 z3+#ngte7{J^>D@tl?cE3h@3jCuayrv+1iT2#>VE*!RIZ+s z8RnZbWt--J1VL#IupwNlcbC-mbicg>zJ!rumc0^=YeXaj`bUp zC%9P`l>)E zH8`pn64;h;SH%gr{cbuUyT6HA13`llsYJ6`@8dqOYO!{~_`npODz^34EJXam_|T(} zUEF6srk5K)XfE&9tr+C-;SuLXzL9G^&Xk}JwENf~V9bMay0NybhTXO0EkOef+rp)L zr@KVtSHW3>I{WjE%=SHHv2rISpY?K~@HCP_X?*__^oK04N(oj70}U6a-c`F`L%{s} z{O9qLceJu^Gl3hMShruc>tj>3t5Dbi;D$$wD?yjyO8S^$zI*@8#JSLz)vI7wO*Nm%qHs} z5-w|wsOl0dcRG!CM$85&3Bv1gjQ)i|zO-VTG%e`6U+=|8;zBwrZ~2gp8v}R7$f1+c z+WYkKvDaOV$P7?xf+;~?x`qyk;aCuom*Ffk@JB!QCk3g4U0tuzL|m~tV(2@%;vc2! z6II4$WIX;WqbjDJ%|=sbY^$QUhww3g&8veep5Oc)@WpGdw3h}#12W}%o!gp;*s~W$ z=18L8x*bke>AxpDyOCxTJ>V&*59+MnD~2*7-yiJD=+M}7dWLU(C!69%1VJaKqXU_l znIZnE_6;=`ytdJ{8}7df>v6-^r-DstJ)=;8N3AC`bjOJf*f#TgA5SPGZfgeKxfW2? zo5_12AW}Ye>~7?(Skn@>`{Q$L29zQ9P518d0}7)b#PkBSc%D5AoS)Yh_?P>F-CeqX zHIaTVjfVq-xsQN#3!u5jKxt~UI={C^w9m8;y~a;(|3wX(uS!3X5iHmG{Dw{? ze}{ariH#=J=xy}Ye-1Ad&HUP3+Ws6H-#d+z>~V~4?7m~U=G{q`pj`gl3aEU&UfmzZ z(=TqM>wc=omff?GsZJ`wmwPY!`YZqZ(JFT)6WSKe2R2-nVjm3raP!V+YrCJBpS!Da&9Hzp zDt`JbQ$JP7N~cC=9RC_YuC8s%_`R2anywz;T1DnDk^wf|xIq>{7Clb6+reuFul!~m~rJ#F2izsA>q zLv?kDmc`-YX2ZZOhq1Z2j+E>j>C7MQS`>rQ@jipUF0b64z(#-N8daQ#%xMl1cd?XR zqgs-H#6bsz;_^f%p5V)wsG?=6t2a<+Wb2~R#GbI%83&i%-(bK^Q$Gn*QzPL+M;DAT z6sp@W*G5Rr_~5|r5n7N0A2-GHwv^knylBPuw7*-z9M|;%=PkETmBq!I}-*(QeEm*8JfE48IiDK;9j6sOG+^C)+K!HHQeUwX9 z{(xs|aACMSLd7SNFeesQttH)N1C4y?npJDyuPkDi=pxcbuqGov-j*@N z51PZYvAQ8%>fr#^G=W7{wc`hsn{;QQ%Kcy(n&U=TKyf}2HQ&@_WUz0%;ty~v^((!k zY$1;m^l-c>q5O{gDg#+A7s-!^;Q1`@Kw z9{n}&9}qPpYYgF$?A#Y!ovchsOjKEHE*_w#Q<@HNst{ zhe7DzbR{pWZem}`?)Zzdfu}?Z2;8nttTY!UUNxzN0g4t75_(*VvMVdNcO1ISmJSLL zAhE9Gu-5515t!dBPjKr7e0uA>U-^>L(oDfV5`q&ELyzqIUwRjH^C=WDEaM6Gknfo8 ztI}_*s0eQ3NOFihUOp58GgkiEK~$!o^2RRB5C5}Q0bcUk)(m8_sYgdnuV3Yi{PDhg z_9j!J@4DH0XEO-BCOC+OJf_3(Y)AWt+7qx#nXhO#L%EAHZ_UCf2xkV&Fqo@LkblK~ z5QqR*22hr2DfSSU+e)8|2pa;fNe6{`29Yt&xZ=XySO!U4ddoFJFp0K*)UYF=8t;~7 z$ar8+5;yWu)5?E( zHwpyB64FY4<%O%7XFK`BF$mXt>aP>DJ0m(d!C8QwDm@MER}AL0F7Myc_)vYU_F>l4=MKR$TLwBw*Vdz{Ux;-Y>yUnN}&$Tni9LI0;&mzNFX8;czT3ZqSx6Jp4bFFD2F+5|Q-OyBN&jC`j9A5YI+)|M$81UJj+ zyJ4znpL;n@p%Fsc_L2yBX=o)!#e*F|)JVDqFWI0)^Y`#|v(V?q3lsE(Uwr6wYRAS; z8!n^lt4=+$z+xbfBwGSi%4m9lb^^IKP9~S3A@zRfTIV6ZpMSPYhpx#B{%tM%?zcYY z4mS9Pl`dxG=JFU&&}t{6YIx0*@D%II_49w!zL}pGT!rerTbQbl*A|iR=6;M=72@0e z+M0xBYiON&>HP)QP({GI9WLdDMoA=PKEDq&DnZtWd1|wOWzIc+;R=Aiq*{XZM((iRS>YhF8Wm`NhxkR<>KlJ zg-BpbWD+-A8h&3Jup7JlIs$5hxC|O1hlW%^_gN~?#NXL_yrN_Vu{OdcAgBo;DXFWA zjFR-CtBKm`8(8dp#9vIBTy)E)POEJ|`Zw6b*H?eClH-#5)|J5d!-~WSC6nD7F*^BY z+Bck>V1Dmn2zd?Z6c!UQ>$WbuY^fdz2fln4W|i{i<6)M~{-fvqdYP&1jW=tJAH*lH ztkwO@zucP_BCGT2zlS@HI!PV!8T+j=A&Oy+X247*!Q1Ow?`>GvH%^b;BCgb`J?1y zWRMEqjFInm)7i>l+c!I1+xcOQGPlS;Nc~$wYVcwSM_;(XR`mA9u8|a!qH&n?C*PuoSpz4Sz{)=i2zrf&$G+VY{q{f!^8q zGE`Ov68~GDr<7a=CA5(m(ODkGD7p-Z?GM>y~<7qoe(W+&^fc18lbcFE1=SDvR?-c z?M(_#55y!TW1_gc?ju)y#zSSIX^2$IdrfeFHU&!JkLPJ#{(cwa7lGg&ZqLrg-~l8= zl6v!}^!~8{PhG!#>+gNWf;VG-6)yD@b@*TeJF-_Cs9$n=Tm6?8BSShc_!$Qi+g9GAI8& zQuyHsRrbCpf1w7YwW%JQF~30aZwbR+(Z3gyC-BKT(dTxnhv%x7{WVB!fAxW?SmLgz zgtS{ADt_`VqAjp+kSsa>o<_B4Km#R71qB6E_St%B8n|YdzXkHnN#Vdh+IG@w(HtU?tw* z{?V^rTbakNSw0(449}-R6_FE6!oMp1+GMD*aYh~d7Cx!5fn0?y8PHc1a_Pb0&KY#> zU&&SFXb{1N5VCs-%j(+lB~*1CvV7NlYXCt`)+iWs1#+)!zl#P{;s!0CsO{sC1~)qD8tK54Blf2v`yek3U0qo{*-D((0Z{_c3L z1e%S?PG8#)B04jMOJVGATRQmC?abH0bq>_OrU~-z)E#Ei@!2#Es3<9=pC-I`+J-D1 z-l_fH!#a}O$8_&(L3<25V>@{(0#Qc?3`nfjfQhHX$YR1gvlC{A!R?&;;S9b$xtlnG zK8y!>X27Bx&&W;2?BHrs*>7vwi#V>a^jh`@-PayL4nVQi`XcG=wO;KG%ThQ4V#hdt zJ>8i8ICB>jx@X(8w|~`nw{|+=7sX)z+eX1a2JmRI&vxxy+ z3WWFK?F{9K_sx?A-y4i*Jo&>mHSQM%;_&lbnh%P)XEBkB`j*i1Llw6t@8r!owwpt+ z%M_TH=#3vn7_ubMEY?rZK}JpvQ@4|<6L&yR!MH}B?xVw$vw0UjMSOJU>EuX|jJgT~`Id|B3< zOxpU|PY!W(^ej<^M*7Qdr{3762>82}J@UAeca)MS&v6XJ;58n#0-7Hrt1H;gX2att zKDF`0cUe-l!iv73`^Uu*uF}DG{V&aMeSVrx3?AQcF%3fj3z&upKqJ@v`MDcwPt!MP zlxMkaH!C{~F8Q8UGB@tqsMF&|PTVQI0}`;a69a%{$ozsVZ0q58^ztIi>?zLV{&Q+yKkNF_9^y$PiVGvh;`}ptobZ=kJHC}%jd4kO zNFHg{D`7zT@PI<-n)i74bYii3-2$~o`4In~Qc2nSZ)sFHe0`2CUU}~qH=;u_Fiq|c zxAK8GI;_GG+B$*^@wb?uW16LJXXjJ67|Z4+q`0RLrEGwEcjy$Ypn})fTU)<&!(27` zWwi`CqnGtO&ensxE$uOlqR*@PU3!p^TX9~sM^62zjUWO~9M4onC+5lCLZjdH1*1AY zNrd7Qr$oEpR@u^n$;Z2i>;XwwM?3CU zv$1#6w8$AK&$jP)rjxRQL88tq{r0kA7lYu9j`h31b?0+lwt_@1o>fV z4}%K$=63rSitdpT-$!Q<@Lb@~nX?T#9<#kT-+NWmoAD^1;G&)s%m0zyGxjevL#)Tk z8{fyK%9=F}OOFuh!fG#JtM2bbm48T#Ja+^g$)?QS{q%;sy}ZlQnd4GNN}kYSj*!~r z(mwQ1Zq{NGEkB)h+nl}3BdvgZ3E_m`yobSD9d_%4DwjT~TMxnt>XIsGq{JaTrrR(>{t0a8c}H0yQEU5DmBuHfdpw#%&uQor&!+}^s! z!O?-ij2#cr;^^Md0l9^3_%!O2A4@wgiV;ml=QiIBX2pZt-9lL+zN%Hg+u?V+{&r($ zrxkR~t|E2Wsk7k!3C+7X{GJz+)L>xs2k8VuD_~RklfjADo$rkZ(s%JAERY=gnUEK- z^{~HHO80{?dieW&TeMns%AaU`Ne!($93>5v+Pe+o61>z`nT0e z9@cJ>7IH#pa{AkIx+t~qY)r`FGAuBr0-RWwq1@>IoKwpb81RRFBDaIekq;?p zX|1a)qJ}V-Z&T&*-r~LPD-^wEas-~%NXn-5Zx?zkl@Vla^`l*TKk7rFeJC^2QBdm; z3eXKyyf`v$m{nG!h<8Go3JFrOPCTFj;ZkOFaoU3^9hR+XD`MCk!{Fxb-oy31x4Zk( zE`hl#;vGixXoKK_H!*kp$>*JCpwiz6?1`y`#S}P`;5R_}qd{?0^0&YA{HwryHyb$l z@Z+~`nA0o33HC$e|1))*(*KFK5~X}X7}M0pY#ze6>IdS{FYszKw>TA=q&0*b*A0`N zjAj5}ww~#y??yTOj0tT5mv|^qD$J8!IuhR0Mh#0D+MMT(@btTm%N`#eH%XO023As1`|q~!Wv7Mw6n56P+@%RuBm`2ec| z`S*?iD1>qHjwi7%mH&ot`$HphpX9tr|Ez~ZNQl`EUg46LV!ZEIIquk z!8EFvq#os}3 zZzzp4i*@&meIsWrC{wi#qL;&WZ5i^l4mF~fe&F&k=nB=$dQp829z|8k(ESxlw{bB8WVG l05}`)7VFfBzXp(l`xms@sw@k{7!dIHO7;z`=!Ie6{{x*5Xk`EZ literal 0 HcmV?d00001 diff --git a/planning/behavior_path_dynamic_avoidance_module/image/image-20230808-095936.png b/planning/behavior_path_dynamic_avoidance_module/image/image-20230808-095936.png new file mode 100644 index 0000000000000000000000000000000000000000..14e0e1de9f8d98a3b2f310cb1977bd0adaa8c888 GIT binary patch literal 67282 zcmYhj1z42P7B2kJNOwsiCDI|?jid-jw;r9AqdVG6&buDw&s@(o)DcS6*N)7 zA0JfnaPU2;i;RxTYkNx5Eib3Q2ql&SH#xJ69fu zI^IrB$10y=&nGW7PPEL;%~7e*+6z()BUMGO5Dg3rG*Tp=kv1E~oeT+KKU`0>=CgHI z^s_Z$RJ7hVOjxKTa*$xuosKD0x$Wr|E73%<)Gqo7)!5BPmg&_h8ld&XpTn~9cG~eF zNMO;AxY?!^V_Fu1JjMP7@5>RvL50416`TJ5Zh9MkARE|N(zy2V%8P8FL5ku9fn2kY zg$i!Ne%2FIEUN=M>8T3kk@?xc1Os+z*FHs;1sm~w)`Pr_C*0so>?_?T%^X(Av{^mH z=0f)6Qm7xMnm6l&V6L~hlf=s%lf;raYT`JEr-*Bj8PMgq0Yq0yD zChmXELv_Z#V5^Dt3`tKce~{AC(_2|t1$3KAn3?5GSf~?x8MK_r!oHk?NPH4QDYlq0 zSsQAoP+UaIptdmpzdtzptDPm?O-&L$`% z1XdazZvL&bG}<6qS^`f>mez>|XJeYfRzdVBPW|9ZCh zkH_dRTZcryM;rgF@Y5jb?E6kHNPO#U!H`N1)IicF#HmB@_63m}D+4ET?6a4O#pv0W z-E6Y78%|s2ZU>82{oS`$CsqCre#QOS&(yWFLjU~vQ>^-ome`F`gBp3^T0leP77r2^ z$-}6OpW!CI|cw)1GKiWVp~u)s7F6 zjJ@Hn9J(iDn&ZUT8%O_EH_%wcUn&-!Fx(NDlzfxeQY#@Ql&dZb9#$$?bDCSXjnC_Nu zC%JN=kew5y^4QrwnmxaLO6Pqq;+H3h1Y%g$tvMiJ{-MWeaHqFrSqy@9a^k3?Pum@D znIPl8y#BB@J$JgZi3$W}(%z=asm+oGzzJXAM#Zn|SV6+~eoCutTm=*$uM=%Nx>SB|P{9JyctoCi9lGhet zX)Z-QmDhL7lXT;OpfgLWeRLKc+I$$cRr~guWAE?t)7vd!EB|ULHKv5>B`yqYF>FZ9 za#(!$^#*m>t)7}C;Va!t*0z~4Ce$DnKLo*zTV@%l*x^A~y_K725rqLoSZ zb_XUmb*Ga-l9EMBQz?=%Fvys&z)^=>1SwLK@NxSH8cCS{A~s@1p6b^Q%L&_QZ!0F) zwIBpvkixM4%F#^AEpH00H4RUXd>M%Hi`a*$1aj4)p4X5;4*SFWe4JiG0?v>R8bsNi zOTyzdUowillQSqGI(zw#lFca`UFIvvb0=nA83dG89NZAA<&KbV#l;B?7+EfY858ts zi6)G6>JGpA`wQ3t6UBRw#1J4W%gn%pDi!I3yc3*;KLgSW*lsGG6f(L)1dOjPHFF;0 z_={~OW{BkSov3K|jW~ngMLYR^uzt9y$x1c}Rz!}xaj(3@`1@bG(X^2Wf*G+&1_(*{U(F82M4|QmNC&S`_gOgkzV&mHpQtO1J-*A35K!?=6@r*3YBc4TfkIe7f zW{RC9?@(i$Q8ykVy}J3G1VQucv+)gwPHR3pw#n)K4Lgx&A@DX?jXh`e-W$2psBo@a z?-d81h`iOsAXa9;|Ni|u30vYC37r%Z`zvcT0mLGqwe_-HjN%vaZlT z#4TO6YDpOAgpw{cAOvN%Wo6c5S$E(@$LcaFry{2#n81GuPbwI+{9&WP6ILHjUVkv# zYcWB9_Lw*t8X7=?kau#Ty5{n~_i>|mJy4mHz~r!N`iyxdZeOb5>Lx&Na%ZomhU{BR zRL)H|?zdx0Qb@bVk zC6=k5&=v&+!GHK~-dxeNj-Zq6kJ_dhxmqN@50W2b5czEMLz+jJf6!u>Ojhi z6iGve6a(CFrdx_Q4}_qcTo?#J+)>22sDw2;m&K>OSL?{;>Hfq7ce14WM3fIsbZnjz;wLc@9-~od0{nXP0kv;y>a}1{J00<6+kE+9lw^hQ> zjH*FJ0Hpz4apbPI53GLs>}b_<6TMSL(FNnF^>Yl;i0~jyH8tv+JCc)=6H+dXf#gr0 zO!of%(nyhb=Dlm0?=gB)tJEWeh6HDD@m1Jv>i#Dd_yT0pRRD5wf83b(oHkB57JITU zl)jCLBECi5yZezdEEo{{IrxicD}H~GSaea#9YMAx-Ob;3qqX~jS#eZxQbt`lY~-7g zec~8I^HQ#~0p461@pT~beMYuird$160n)=;Y9r2Vb7Yr|WK7feaZst6^O0j^&Rrc2 ziLG_b0D!43I3>E>&ODvl5d9AVr|%F8WW)-i_nC42r4^9P|}6Vo2wQ zB_@KbBH3I;LK6TW5~Eu#;LH{5LHemSWE*UL&HS1FFocN%Y`81;@N##_a>FpHr@s|F z!e=5DhraW}|1q2vWBnFk)BgbXw4xPhyxfmWt?ME#2LQ!SpFUOUyhtZe=IQbE zm;Et=k<`c2Ey9G`ebKs4@LK=5^0Nmv*<2knM!L}n@Ocr1J2^-r3-#CyjbGI=j_mUb zVolAT5enq#LHsGQQ~n+hrhyV1G_NdD-Z$2)nh`g^e)ng`^`Ge5G^MWoc2u-)1{22`{b+C02tcdeqY>AohYJ`T>k2F}?DX;9”@}>nFgcq)hhBV~n z295toLIu$u9+W+`Q^01T2r{+-Oj??&9h6JCG!5?3v%mvRCO2jfUOf{15(9j3C@}}+ zo-bF3>kfJr8nyfW73HpZet`8aU6A0$SeTgF3YEX+vvo2eM-wPnSXk&Z zx`Cs?!Br=?OnkVgZ@t_B}0uB;pb zKB*5Lr3FX1?Ay0+I6C!!HLla{4}6^;`0~Dg|IOPL6i(Y|T4g*)w$V~zTEsz56dFx{ zQ>Mk@`b3%_;Ob=K$Lbf;pp0ng*Ji|Y>PtcMC|qN&7?M~{jW1}`T_Ox(O0+91watQn zd&8MINc5>xOyxB<8*FnGc2&HIL~`T8yMhHIti0(#DxpWedHi*au6-HD1Af{_(Tj3f z#=3JHbP8GyA@#&&C1FOSe>+J9k#p41#QAlegXzZ z4sb43;9TU@HIlrE>7ccZ4J8A3`X^wSxb$p;r9TSTXtw$1Lgf9r{*5yvMM#*Dn}Llj zJ6Y3SjsM>q5yVY`p^+l~%qAoxWG*gYCGBiv{fk(krPgj}3!qP5UNNx6F(eiPCIYu~ zy5-RwpAgOjp%b$upE+4)s4%)dNqz>(ZX-#=Ez|Sorfu?$O593m`!veM0^2v@D(RHU z(#PFf<3~|6bjlHrhFNRU*DV^)sj1Q0=3;sRT%uPDPypfae4?&8yk)JR=%}9St3B!pHv}_<)LRF13semHd9I zyi?KC&QTY>>Qaf(-E$&#!{~nY);ZU&x@A3$2Q5+H8*;`B7d%RjB{--pFHRIq0_Skp z{~n*c=@35CbDeba%xibCm8zhi019v(79sY(Kgmi+NC*TBzQeSNnw1q3GX61h7)*5w zZEbDwpA2wwz8fOf_c`hYX>W69r}OcbZis2cS43m}>vkF`Qlh}2m>pGR72S}KkgE61 z&D-RwI#gt7A9QtfA9;^?B9?E&l4$%&KuS-KEZ9W#=cJ_IcbT5Z0nTp^0lhP*Ey&Mb zGJ3cshO*1bFoBbt)*VC=vN-Jhnp!zr?!5dv)e;J#u(3t1@!w~?!{solm0)a9aZgVH z03?Ql4upk)O)lH9{Q@o)ys^E{ciYzozmCq%qC@--w zT;n@u8Yvv~87g71u~>jyBEkaMrSBcZWFy@*z(NRSyCe?clmKIv4;QqQW>elCh=6kV*QUZ`w#K&Z?2n$w zFI^f``1PR-^fppUzw?=Q{9v_t=fZT#otK$OnO{)wxI2%fK$J?yRat$n zt%ADy>m8FHGb4ZhMuN{+VfVj6r}VotnYshai_?BVI1a0;u#kc2lj4WzO1Pb=3KS^a zc}QTo+5)}i!%WbD&xTME<-;d!LkUYuhWm@whvmzo)!yD-hk3VI+uEF>BF5hp;+KEQ z^kCWQmLyz>MxfaCu~CM$;B>=-iq!;^nTQTAs~;2eA3x&fGiR3R*W(psxRDL;Z-wtKS9|;WPf!VM`DXJ^7W{5(ftJ-6Bwxj?QKpqw zRD@z{Yx{-QhUhUK#>?bnWe=}5vgm-hy1Tna{khcJvehXc&qgpqWg9R28Qle&Y+F4e zx<9V?s3ivpaE<4nc2#$Q92{6U5#1hRlg~zHY#QDM$DSNLcVTK&X&eZ{A%W^HSE59; z1naRw9o;uF+#4i&BBsK%S6ZKdl!K?8*hIoLmJASUg3p$VASl$XvU#{*VUMU;2vi~_ z;T(*wCP1j$|IJb%?dvNddbNgMfnWgQ_%UGut+Q)`x8)?`Uhe0*G1$*5AY$DkZB&-D4$^B~BA+RlmR z32Hl&PdnD*hav+1$^QA1peW1lI{ywIz&ALktgMXx?sWWU!TZ2uyigem*xmh*?lPv( z+t(-Y?j0jr^Qi{VVwWC$9~6i3hVAF+9xD+Zm&;+CzSk~L+e&v-mEF8xy61W-r*G`C z=?D`=X!IIBKt7M~CcXi&703sIf`a*ve)V{~Ok@CJB*M`p*q^Kqc7A_Ta+^6mI~(=) zukO^dozI_%FtD)!JfS$*7>339-?ck59P$Zy{YwN(c|nZ?B+$V09ZgO{$b2yvkkH!-*juSVbSfbFrl`qy@my(I*;rw8*2IR|9+Jj=adI!At#qG#Rnd68T&P?R%DHXF7LF z*6MN@LY?dlftIpArQ$coS?h;3e|ycPhGgQS-8j+imuy$K)tXmz8V@*%xkz=X=Sn*lOj7}a{Ythv0s!)$a0&AgF{1Euj zSHrkXo}dY&K>cEW95NX)4Fb|j5NU9bwY7EK)%w??eth@bT_PdBlMeUFhi)Do--U>x zeINWqe;*{GAps=cK`a-_%3P;;mvpbu7e20A6uonvG=4RQbgy0$E;Y@~9(5rMuat#7 zb-165I`V?CJET~nfTIXJAhzw=p%8;%@82`D@Lcf4H5?xwSH2sjoZ5Jo;Y!5Tu$lX% zi2)ch3?%aW@vX;TPfJfxblyboh6i5J1W1YcDW~x>v>1@p`eA<2Dzhe28xV(}V5Ij! zGcihoo2kN#=^8*(7kAQ4_%n?l@vCSKP$Rwg;fYObcb;FrNv3?@3wc<#t2Nu z6!3`p4tJ6--uU4MaKG{a z#Sabwg`+bF3DjmG7Bhigx)@~L{(4M;BmjMO(_s1L=$H`GB>OS5_w!PyrHUk%6E%Hq ziwx7#j$QLhoJRltMT_bVg8Qd_>o!QI_HHIe^SSz)H%Ku+dUfc;e7OV?1tK&Dtl+U4 z^V0ODYd-v;ki#mP5`-DyW0*ySiI7I*4jOaF8^9;*cI~WRNIR|AQ_25_0D^SJgm!*! zkNqlC02C|;`bNmy%UkTY?*1d8_;vk|GpZYgtI%PYy)XLqGWp!);LfOfSLnnCdO>U* zI4Ia{<2&s7+UwQS0L;d|947P559tv}Pib_Z_&+48==RnJ(5?y67}*MZ)cH@!>|_tqYUF!~v^~vs zwC$DE<>W*}hx_{Apr!|7c4(=soX+EJ@*x*&P2+~*a&(Vm=f<4Nx7UP~F{oBQ z_Jb`C3BHN3hOKtxT`DfKPTy&WaUCbiXRPnOnf1Ii(h;tCIiXw{1}_b-(5n(f;$8jihXt+Su=eg= zl-h(`dxakJ678sQC&SDFo;SD0WCj`n3*<1nx?NgXW?%yK6rz19`W}4QcH#&`M8GkC z;}9mms1>zXv`X91vELp}B&jY7r7Q-a*z2J{I)?=qOH*wJU)j4(r!spiv@^negAXJ# za>d7c*^I~We70T+?)tmqeAa%MSL=>-j@c4ZE80K>`zv^KWutYwm}aN%kV3SV6}NJ- z;q1^&*k4(-?XNTLfDRe=r6FTb=|%@jQRVr<{J>^cLZ8~Tl^Zn1r=)CrKT1?$lkoNy z0xP8Vj0rf(9yRC6sj5=17Q~C8rK6LIZ$M4VIzD!CadpipFIU;t2sZ^R)$CD(**9<6 zt?oa(-l0ji?cC>h397 z;vw!Y{!z5P&C*4w7H&v!`;wTH+-y1`%yXsRzKNTe(KSYfKXXvoFXMlC;axtAjcqTr z{9RWYWrh9S{#TbQZ|p3RAJ@6vcPURX$fRED?_NFFxp5_G1O5Z@ei^7KGpe5%Xmh9W zE=;3q18`B0$y|g-;1xlzoO1C@-YV{w zISK(nkUhq(vp1eV4oETF<0`>s_GIVHixF{|yE5bFxN#@gD&CWH`e`IQeV_Ww(_Bgc zzQz_lg!t?iqCtvhzlhBA@SG0<G?La<}E!2RCOEV)@SI-yq#whyLIZ(9M|v@W+HJm9~cdO=+h{{ZeK$PlQ%U z_gua6)vTAIuC|dc?}GosU3_ql&TXL(9bIs+5qvzVn2S6vnYo39$wHIo<>|QUUFOB$ z*2z)N=rxBwPE5M=`fmH5^&}tQi=1^$1<7_t#iiSdz>unmo`D*O(0NAJF(0&F=2*C|f@qYl#&py{@jiJD)uY z6T6kz<_cfQB#~UWygM*4m=t_5VeZ*He^wtCKXz7?^6>D=RS1_})SooGbruvfCue6z z01~`0f)Z#C30g1Q9!OsaGi+qBOaQ&0aDq2}06=AVG7i}tbcQiFh0@l_f4A5Qv~TMi zXs{@S!Lk^`qi6IN6S`^K0}Ku@0)Xc@z7BdUhY%O~yfA`W(==JvyucO9 ze7a3;gl!J)pf z9F@e(pFahAaU8xwV zjZF2#^a)LmGT47=WY}#~f`bS8gHK4(J$#>zyWICX!_>rBtrCkA0(#zN!{MzQX=%iO z$9L=dj~=SH%_T`R$o9J!UeQerPr+=y!S&m>ZvlPgiD%n$;s^>xG^<_WT+{pVN58D! zzXzIQCg30cX<-G+b3IBx3vrxcVp$o{1aFXo1A%HPO`r~#8&Hs{?`cH-O77)i6b5sp z?<<5RNiP6q1)A%*-@iZKf51GMj3BY1-mr1?UQ=ambt$Ug7J)G^Li6n)S_Unk^j733ojoZcr!H1A8*I@C{0aK#mq}_j7Pqk}`HyRunB+{*<8+G%>~?+`pdA(2Vhzy$U|3?6q0h=_6v3S_pq z56qi@o#{#?r}2s5=ad4M3Iq^hsXWwN(Q03NchO`0lyaTMvlba?y#2I#QQi< z$)d^DEt_YzKa)~GBTi9P1q)K{*cy8zJ%B0vbgbt|a9&c%W&MQ3gMrx7fYAKWuO${m zvT3o)=2CFK;V%9H<}8+(qeG#gOhBQ}pj<_Z92AHgd@so0yT`r7;tE+EiWuF=_6xG0L$*(1!A+(1Ein}x-Fd_%FlvBu)ph6zQu;6P! z6~{0N(P!E@F0Zc97^E=iN#z-k0gnIuTk)Q&8$A>_mSYf*@_trDCG-|IHIe&Yc2eDD z;tz6gjKoTCo}T=n*xakzabpiO77hz+xo2ZKuX~k-r(D@?&XJQ}Vb{A|!w{Ol#dt5I zt*+jFN6H8!U^d;d&v3|(Mjb8~OP&C&YAIPoo%Y?QRs--nKjab|{XWASsc(nc#5={0 zRs$LkR+%vJyLv3fq;tX&7vTFMOr8bHd*VvTy4ia_s_}>$8rDGhS!Rc0`hO0byw)-Q zk^|2q`{)(7TigJA<>abIWkz69EH_3zB8=*1L=bUrOX4zO!fS)C9dvA8?X0Yp?xW3s zvJ$0Ivbn$ODN$0bfS- zXOMho{4)N-JO~(lK9Nx1cetR+tZ3f{ul9)_*t& zxw*7Wx5xcCMggWnQ#T=|!TtFW`NWDiTdW_~5_gvz|NdlrJcIa$NB8F&#G;*t2}Un&l~8)Pnw=vaV$OO09$AL|h^SP6Yt zF}!@6GpQTbK7w_XPNmn`c0Lt+Ctwqah7uBiARj0wZugBj{e9`M!n@XBPc35z`b|(a z2-FqD@D&6hw{TQcJJOm~Uut}s0HDw+Uej=ZxRe2Tnu=CY_dkOth*_Ww=v2teOJ}zH zq5=lDm4b$VfxyfGkmIc=lS&A8LAoRij60!8XZKh3V{}tysbWyC()bVvktBJdVt`&I zZ7S%wq`y#B$KN;KO2%hHB0EwNt15J*Cf9dvQNrG8P*$PB%KPR&_ApwCgP}u;m!e>-U z(tkn+gIha7@lMsSB&G!;hnxOqD7`oLSS}BKTbH(Pz4EiX8Dqt?Bj)tPq=%C>s9ldH zH~n1tlBeE~ssxoeeoaBqq;qXY%g?$JaVbj;v7Wl6kfOT7rJH?-y)|;pS=}ek|K!h| zsLE;jpJvUA3Kdk^`otaVA?alDxlTEY@+aS$@TO~RDfH}YgYt@SEkaGTFY*Y+EB^5# z_MGXuzHA#EM+M+{cODZ^O@2j6u7-Y~3#tq;L(thz7mR3f*x?~+m#UkR+k_SZ2W($|n|Tt$p`ozSStSiE6LCH}h=di%Msk zo>-XWy3?t!D;AIQP_UwQuy_@b z(L=zB91J%(ISF)M_3Q!WAdU%42&WW5Z9OI|`uhhua#)<8>QB9#iO;c%>JT|>mZQ!Q zb8Pqu7o7H!cERvn`%>7*IxJh>)z80BzQ4UU*5BA+^)8?@6pYW9Z00c4ap}RX%c^CF6)EA#G zM$X#wA+&GD8?n(`963&s3}QH!A+1F|UygjE)vp1K18lG1s)w*Al}BT>=u5%_3ZoM&#r zekUKfO$L6;y6SO%j}r{rc~i@q_p6l{qz6cx1^VTPtJn{++rm=~)&<0qrimUIoX|V5 zn!j~SbBR3_gjFmG&sbRr-@C$n;CnhYHa5Dj??V^fU;JZcMqb*nJTK2|J1Jb!_@k%)!3HV=42Y!6n>ff7r(=^kw$hg#5&kCli$LKV!g9fL3tt`C#I@bx(%PMb-q z5lTThIXkglG4%XCm#842o82|SLb4E4s#cEQXA?1{{_m4`!e<0v64{-Fkkw1|{DEei zJl6wBTYW^moy_>{Q#lO2hx7KeSTRnI+pQpc23KJ>J3q|+jUnkfEo(t_ThtGgO8LkF zJ+{48KW0W}cjn%GE7>8Dl?{cUW;1UdE*%WOe`NkUec7E3vdVvFL=-x#cyi0iSW9hC z^I&wEm@>i5c|(&Ss8HU`f{X9&rghihkiVdqIun@0MOAjJcV3h!Ad4g&=QuoPhiiue zlZyz(AEZ_<4(wr@_wMnI%k0MX59A=*BFTgjZIdd2@kQ|jLCm{~`M^=Rg(rBfvm@5l_EaolQfc`$KpFsedYQUsHoLw=yg`MA52L*~V^0Vpf%zB>ic%Xq zQio>=zH3f-KXGvLQ4y5Oi2V7lR^?8-#$Wf?hN;_LM5vvBme;%Ix2rZB4RlKtU)ls|o*x4M!6s0nmfOkgZFg>755Ca( zS}S#NVmUo)!+AQonskt-*#7g=gZP0Fd#IuiddHz7`NKtRyuZJgAeAoE&KG1oRoV^4 zGqVAHkyFJ-+@bc$6h?8F&Tifbcp=&If6(h=SCEvG$kve-poy%u+Qb1}Lb*@kCTn+%8>hg0UKr>}akrO}HQpGbM^F-iCOQ*FiKQ(=4 znCs4oOtx0Q-b(m~cKBkX%UA^XK2K)OJl@6R9Vb%>D2yRj)8;Fb8Kjd$Ggsil|AoSc+Y;`KNUNk}RQ$^HhH z6>X%TfNBauBtzaPfc@#o@2#|{oI)a@rA^yVS}AmsO7zInrXvT3R~H8ibF|p-cPV(iZ1y@)m`=Q?YuV@ANe}_Tl|mS z+Gm;>o&GiYMI&9G;VHEvrYzW8(O)$J)Ys*Z+QIGhQT ziWJgTv$#A>sA~4pfqC8Uo>o??Ibf&-+2?A_2^CA|x_WZj`>L}}WHEG+-Jc*ekD_k- zS}vhHD~e2p>UzHzMiTi^qUSvd}>T`%=!v3(5_| z>SVrjm1bkXQ}`>Pn6*W3Y6;%OcdJcEG5ZJfEn1nf7k5(v7)7peC&TNuXtq7Hpz-9C4->H5s^`I4w6FA zh{RBik-!BpBdG1_=_!3ki1_j(zl=9xB^6xxwIH;#zAG&3*5^8c>XyApwviFG*iLaS z;GyP>gEG-MZJ7~Tq9X9LHhCd%CBbczT#CQjDo83RmJ#~_OAWr{2V3`T4#St5^A$Pn z*5HGhW;7H6HOcU;6SfyGqDxd{U5~h|EYmp6J$XtCoFi2B+q*Rl6z&BNBrz`w(Jq>h zyn%LqAXba=r?XRneel!Gq6AZ6TIdTb4u!4_N-Rz*f=;d@5>LkaMz;IDsoz4Mmd#t2 z&ECI7lKnpAnNH`oTc+oY?M8<83!apE^d=eByb#o3!}KKZDIJ&{i20NRzUE#{42$L3MEJ&E$zcRQQoOW8m3 z_GI^wG!|q$=WubW{WoHrwU!TJOv`OqSfY{Mk@jsySfcR1jA6>o`-sqO-9Mx`{td=W z?Skc*1{Adf*;b&{HyZ?xH8iIcew`$U%spN#vtU^8J`*9Lj z4g8I3Swz>v@BA=&_?fYZEkcW!U1_tT+re|TC4hgu~+Hs`P%&%J=U6ys>!_W{I$9>mZ01qK8ldG$jJ0aF)~@>IrbwpMkcb%YP?M zD-Rz#!J~g;y+s!Ces>sQi$>E}Jl|(-fy=T;7H8%Urf&X)0v%3m8TBk;--1b_$y@KL zmh%)V<@ps-^A~IgHofFrkKYG`}mrCcBH; zbJOPPjMcw0h`{!s1+nUJ!gUce>XWDolchZ)@z+flQhJ#I4VygSd68Y=>KNC%WsS{$ zo?6u!(z2#dka=T!mdpsK|MiEda^V@VTvQ5X-Va6K1@ga=-PIw8Fo@iTN!Hi2Qjdy! zB-nAlrY}OHY2F(o!Qj+)IRK;E=G$tB#9Xng32rbe&ilvBJ1#0IN&-kcezJJ%#H2kY@wsXUl0&pwkz zs!!;B{QUXz7ZJ;Eg}OwnY|9wtTQ1oq*&gLGyaG$yvlQhVBh6;Rxf%^YL`R~t%NS4K z-nCs&Gq_(xz?vPAUdp*$w^9Uf(V?8zh?KA1OH#4%QZcspcg4wU_*m0ZdaRJTabCAy z;3WL);u!J0a(;2Hmrf$7ayw^)YHb7R^+NRP)am)U_eV}s$M5}f@4S$RxtC#e~e16rEguYQ$|XLI9Kc7#nT$|bF znJx^++fs>#`XYXE)?UpleCIHpE|g$FB^g^rwd49uiW$|zyl0Y$R3I`hO?cB*_C z#!Aw*Wm6SL-${k#Ez(S5ril_*iPObH^Bop;mMRMD~Ro9PyA0NejFDcKtH0#BK zxnbbTa({HF$`BHtgA*)su`layl6T2pY(a=i6^eiAw51*bA4DyV^sbHn_n~5q;>T&b zOciPAqfRRx)6PC;@Ja5G8Ld~IwC98_nv?tV1A%m@c*g`iDQ%!acxh$2Ei3pWq_ z&hdnOmuOB)#*Vc1xtelC(BHTY#SHtucF9*Wo1s*3us@P;{u zO?SJVN`IEEX}^raD2ICKB}p{n{pa|86YKi)2$Q_4oe~5xMR95AcHGV;gfee6(Pq=q zuZ~WrTYi2VG;81%+{Nk&<>&n=l43)YUyh^6H+sl)oAIMLnx=>lBAjvC7o7i}^myvk zT$-Y^v9Xc&pV{Q_@D8rhSM3Ic_NIGq8@bacXcgVQG5&I+o17CxgW_9<3CtCaz+G}k zW`DjL6&LYaxK*99g%8*`HEPQZ^lF{zCA;~zWBi^7qUL@1v^kQr&b;R`|7<(aNgKu3 z|HN&I6I#s(j6AXvKB`%+!uC~FL6FARv9)z-UzVMlijhqKTYH3t4q_sJ zN8Im`mwpm3UcgLBiV+(A>NAnGqJV*5g7o{_gt@u#2M34lNN&E?#9-43RO3HnUP|`}-ZD_QH?pRE zP@b*7eTleYLwnyx%?Bjch;Y-#>HV|qNePh4dd+tuGHt0GTqRX@?Oa;z@*7Bl(MaDs z2UEO=OfckDOl%h8TGdQ=Ice!-Agylh?k0m?gt%;8LQ(#-_*Pjs@$?tc9nRt6!v zc^pyDH4Y6$epJ*s$3{j15)%_Ek=yD{i1GgFUM#)kPch8OA?;#)d5cRoxl>3^fM1#| z*)yRD$ILwRW-JIo4GL(NfJ^73SOm>DFd*|dY00Vmzpe{1uDaxF$u@(*;pNnzs3W_f zVjXSw)}5MzU(G?a&MEE4OLexW)-`Y+`kA`V3J>6*^1W$Pp@6T7_F)~i6tg(1~}Sk^f9_1izMp1Koe3hkemn+`atl%S%Ccfd}Cu{ zanQ9e4|yDu^~J8^FO1xOcJ0^QmjNx8_DnXCJfBl;3oVu9UWvMD>mHNeoqb_ zIbT@jdr<(4Sua{4`j=d@4Hc1;OOTlw70qE<$rRia+uYtxY{1C<@_4hS$_)1ZYb6mD zgYN8+eBP+BiwgmeyNi`_P|dVmtxV5?S#fc%v@|sEe!%ch+Aitbcx745UA~c57X39D zuIwzYk_zBB%Loq-m)D|g)=Xns0DEtH{|gLtCAD1?NO25^&ca z1I);pQ-4+}M4)%$j5LS|R6}t}%*I=KudfO300rp=aL|gkTZ~If<1PLE+148>+w;bECOroAMe$fl6DAI1w`{QE6x%^-`#W9BhUG`jQq-$8Uf zw;(qP9SoV13+LW@QB;^uSOHFly(xjl4E}AScN7bGGA+h4G^AQP)J%PN+4g5`b~RF? z-vWN;CN_}M(kg^26;73%P%d>xz9Y_KG+NG;7rC4r3>4GQM#zSbPeafDhxoS8CHV|! z`_xZt_OPZKbU6j>nGrK^zXvxmWF$HNRp1xg^T*SCX}7Yd`b;ujO_I@`r1u%y-78jI zIdFe+IjJ)~>bzaJxL+QPyDUQ^1*aO%<`BPkcygfq$P9&p9X?KMcpc;UyXS(Axy?jr z+(Y4QZ~jTBJhg{KR#YxW&s6!drlrBpa&wNHNP`PbK&!D~qE{zha@kq}mz%(y0NHIW z{f~HXk+OW%IO@lEt;9)QeJ(SnxdDECyJaQn6cgCm);FrJz_N6O!*JSB=_^q`O;l`c1)pSZ%~K`V$gI|< z$NR$*x%*Ha?J$siVyJ4QNZt-u|AF*Rdd*aapCHGk0QB3&1JG}<;f(lS(oSK@{_uGspUB_S@NKa+Olr?LlpSQgk|id+dS{Ev!ycmyMkM zwSNpgE+}+*XHxMMaySoK z?(L`k*bkCNZ>6<9Mk}9>uRnAV#{>?M7?r5Bs{WC2Qci61sdYa@a=0Y&wY5|`un-y} zDBPA5D%3{{674CwsAf*BPi1n_!xi)`+QP=gV)*>|b}05D>9zi$zb{x~8hIEv87I%$ zBE^G&sV(}{>vG`yQ#L?4@dqjW(Y$=+6re-;uP&rYzBXtKfKXd-wFw9on9qpnTL}?& zf>xwK6~g@j?iHfuZChxF+87~v>2ero^F05j9;lpz&0bxqxcsY>(T4d2Zx2#ov5t#L z&}ZV}#EJYUun>>8z`Rp`OUkIta`W-l;cJR_$W0X5ed43(d%9pl2p+x7Nfht7Z%Vu( zi3$W=BgHw#*^DNX7YkL#`T5?dN_Enx4XQd%m&?f= zq)$Vd|B~cEOUnIE6jM|rnoPC$8=D0tFt7uc2E7x1sm_8q-U?)Pg4dECY3O?D1ZmM0 z(IEG&P))2zQ?!T}WyN4p2MTOVe#uB`ne*=fwnP`UY6Y2dX>esEv~((~)DpgedKt~o zoA}xk)zW;aU2PiZ%vvb5E#z}1`&-~$&RIpeBfY%H5>aC1(k4o28GZ`g)bTAd$o;QW z@g4VHBTn>SBw2B!AA@je;$8}l;I^*O6uahM7_$gmMo8RxdHBNe-`B~sm3aFASCc%boCxdTOL2sT2&l57yw5aG=*N)I~lqb6LUAsTLDo7~Y z$MYXUBBHr3W(q`%>b$Ph7;LvqXcqgz*2D|2XFWbYCFT+ znR9gssIfFMlDrnwDpy%!|EIO3A3MZ|YrV*ZwcnEU7(Wg=SJM-J+v_SXv6esv_TS`Y zn5*CRsOmpN(b)$M5ynlb7xkzEZk2gNc8YFa_M{eYQaMbQEOsLJC@Gf2T-FK-@?xi0 z`uD2~c}f^5P>HpZ%Au74UgdxP-9}^by8j3T)ZL+5l*(16l78%A=~2>shuh@mRZ;oD zxceq$Qm5|tAQ9Yp_+IQZI3_i zM#I8_vbD7ZqUt45RsIWo{)zFU8!>&)suf^W@%ZRcn0y`yEtrqIlYCi<>SPjyYNtEx zZ-cETfVAo8o$+z%3gT&shz&A;!GpfS0aLqk#pd zN2v##=jRTRK?V4*HWpJ*J9_5Ot&59u#onL)nD|^Jz~E;GU*+WWZvf5hU{U1#%eRU( zEsQi<0Bly|rWgl#G!5tg4=^sQF_#t@^%LG!OK`Pk;vcC)JMfPkKWZwQyq-9#lhF^4 zPz6@}r5ci;43`=HcVmLKD`hJWrphXMI&}87fh~e4_wg;Q2SVBL=>|(A9Nj`G%-GV` z+Rjb_^kDvy&?M`}g8irbASagtSwOhKH}SKo8ShG%;GQs0=6dRx6`&GE7i?^HU`t zn~RFbE+5T7#d`@^X}}VAq9cu|fdjG7#ft_gvLIX*PDq#K^(AsqZ@*Q_%jkrwLB_A@ zkR2eXxY3p}Tgvq_V?AO|z3>sk-uQ11hy<+U<3h*pIR0ZzBs0FBX2mwyh`#`(V0Ag$ zXb>6ua=>tMj}sVE6IL?UDu zdU|?LD45 za#HLxEn=AQVtPCs4E7BQk+Sa$54jWGi59$b;RPVhL+0=23ZQc#M+5RU=1igoivOb%*%BEN4IO!qriR2-G12*LevPa!#`a1!vHwg>B9 zy0M2X1E+QV&TExAjR*8AJfvX!@pFJczkDKZ^u=5$Qy4zLJ3MHRzfe{eUU6M50Vvi3 zwh@^z(`TJx>uMj#$5vwf>@w zDy4`_AXpG3Nb?&%Wp>%qS+%`G;-}!D{G>4J*R3pccUslDUFH2&b?JZm(X*p~Pk`V4 zw(Vo#gG(VJClw~f<_z+=;*cg_qheU8nL{y%u31JO<9New>^R)lvxJ+L zu0md7I{W->(bei@gXQIdW3<`VAr!#N!Bt^~5Lxq3<(Ubh4u=Y|S_l_K`9%53$*IMP zBGnBvlnhmVq-#zI=PpQ_wZIfaY4l^+Z1j|v@W4}f4N?>gI2$;oEVFMj(A`$j=T(3TM>4^3~m z`Q!KvF%PmQxU|_AN+vwK@!h>K&D7v$T6s|bDV5p$YAZlhMPORF=>yBU8-4(|Lr!rp zi!34)77mM~xjCy4UJq$jfFTA}O3{L@tg_KR^)jsJcBQzw?AoH*dVYG$Z|p?uP6Dx7 z(C&ys-%MK&6>3>D@Y-8enW1TnPgk#+_=^+%7% zQHpoF=M#C5Ils5|wxyaZ%#0&_FN!4(^pt4mt{M{14#zconCCNV*D zP6QT}m4%hbXDGcmJ7(>}j!?>h))6f!S=O2iq)%3@hpl9;Et=fPn|F7~IM`y*4HZCj z5nqMe8?txTb>Te-H+s1U-BQ7>9$eB71~wJ+eJUI03klFYh$Z`Q411axH8APEAKI}@ z`U&|g$ynp_sacgCx=H_(IxA84761i-s{$nw|C&K$D3k`D zdoYD`{M_cIK<&iem&_SjDV1c^A{AQDmZpz@$$=>E2C%EBQ15(Dxw|kBd{BhDPa=H? zN-QV&IP+b*+}>z@IdfG8lsb0@#b_~$)R3d1P1MXEx%wL%=0^FC^D|spX1h&fg?UM? zY%|=Z-G7WYQrj9yuViPcA<#yZBY=lUJ*I*xXU zU9UdoejEiOLPah!tC8{KP4%xF$Fd^r{G=uq8KvNBJTw);s~kE!Phn=DA*Zvi8*)fL zv4>u^wWFfPik6fhLuda089}hGaT`({P$USjQ{AyEd02zq^^|ZwK{L!Ezr3=zJT8&sT#!xa zAMItN+sS4r+hCJ3BcP?9Hn@<88Pp@fy1 z0(O|q;CRzOtFZjvDpY8($*MYH1ucE}ep9?`1Kz;q9)B2H5>goY5T3#w3FsX05XbHij$fwL5gFO%JJ%kz zcgzTEV5-mLPc0$k4W4S1(STa`s?#z922%^%*=KLehEF7B1Rc%JF}+FKHR3yvO~>Tm zin)Xe?Z7LWOC{CZkqi+eJinl%`20B2xfUL$HW^>h8DbP)ae*=AQ!KQ=GZVcHEcoGb zHUl`g!KL~YjoSX`pI%gyX4rr%1PGUgJN6lg|9_8|uFvhx z7+EHHop@;zZqP24cQl>8hDV+e{vkSQp{2qPZ&K@u4V*018*7U}R5Sj}N={r;O>~tN zijO#rH-VzU13(!{Qi)+863wcX+e6s#T|sPL?GJh+}xOqi+C(>jb zd8+GLWb+}-izUrc79=GEYZsj_f_;(uYO5p?F%92yyhwU1^8xu8BkS-nv zDa?Rp<$Dt$41ZymGfN8oUrh5@hnCmx|6TMv`mB5-x!s?T%kMaIH}F5Nt86K5a4~qE zEa16rl?J!k`69n~Go12>lr_y_Gw{4tR`=Hpx8Lkn2Fk>x< zbXmo3rLo+n1}V<@=f8{;e)6VQD9BA{n-(H5wK53cNqJ-&Ug^?H6-kOF&_uqr?mMA&2)d3*mWMLIebhB|9N>w;8-Y| zJR<;g8ebiTD(1|)5p6V_=z5cH34h4W)Z?V3p`BmN`t0aQZlj$pY%sT{=3RB*51tO} zY)l4?enwB8nJ>+7JU^NbS`+q6$T5GO3(q$>2$pd*L%~2le|Ypxe?|}=)O`OWkpFHk zCHFj5<8l3aHXz(I0$Je#qvXFliD=`y4>Kh-lcSszj_#fC89tj9`~7nOd+(hk{3Ol3ss67kCv`C%A%Iq_)kem4dPKd1 zxtf~Jk}`##vguNRf&xEpvtQSIYGdA`APKF65;X@dB|Ak9S;_OXbJC4w^5|klTCN78 zgUk4++YRg=b9sRez6@XA`*~^gkN;3>?lF%Gr6tw?TUI5lR3_PYCT2`_9VXbGoAC-# z@r#_Ay@e&i6vw!gF80&c%6IKwuePgSV}@;Cx`rUPu!PoXh$8FU`wmynXPVZz+bQBH znb4}T$+nZluQBn~&8h7-e@Jwto@XXK&p}Jx=OG}XoBQ=*LO`VQ=8LZT)~9@a+lN*t zq`&`t5z2LxkN+rzaC?|#KmbX9P*AKh&n7YRCxAt@)dK11^AtS%J%sZ+*WHNg>>w8W z;HO_oPaTr2(tfdWK>UA!A?^Q4!8y3Qc_us%O$6ZhyOlTZF^yMu7E65-H}2N)gv zvGdBzzvIOf;r}hE?#8 zYCYD=-*fJamLeRvUa_oJ{>5qDBQtUCA1y!$RR$*UBRz2HB(r^52_w-xJ&@2oN31?k z1}A|v*FTTp-_7~m>`3&_)$(aj!@Bwcn?4V92_8b6S?($54N;G0#wtx=$9UVU#lIHKsS~;OcQDP$lm8S}5%OtGu^H_R^Tzh*_IPkyqY5f?M5Ae&32yj7Y!9q##`fOXzy!r7 zBt*}96>7gScnzIhU*%{$Kf#SHizS&IC#>B2_+O_==Es$i<6(b+zEhv*Dkdk1*v&O#QACXW&kpbt0}lbCbVs zu-=?}1e%D5KGBUgxMx4EspWj$tPJV}cE}LQ-G}7{KFOdLi?L1jSnDqRqyL%HnB89p z-P(+NAm2Y2^W>6(?1NRO_|mrJydmVA7_gxiw00$zzUjMREek7W=oua_X}wF1=miY8 zcDsLTDp@GQLWp$s&2T`EBP?V35=!w^PQcUW4XKBi}0&fd~@sGA{5sE|?odC8eo zhZLvcxgwWC9m+<-ACvmnN236eL^`}_nIoRkRM)QvS^N?#_pIn*mT&Sw!_ki3C@hnd z4Gxz=FfSvmyN2Hv-@90}UCinZ#WZCjscJ_}lYriWHf+@gkEdNTEY}%dUB>moD0e5F zQx%Ml$IfW;l-aB1R}(wNRR#zczK(7$`y?i+v&PyknR{^g#1r$p9`o4`Nwpff%y3zB zbO{!A1PO&x&4M}e#WcqI!7f$5y_B(B50kYsGpFokX-IxFm6|ZK>8*J?N_js-)OO~l zo$b5wSI0|y06uDD z0PNN6Hc|m`j!{kXK|fkbms{v$b4?rVf%k7Wsi}X)Sz*gA7By6(XyyTo^V_6UIg78H z@&w`o&>K?g+>$b-lqIuvWI=xd|A3>>gbJcMi>`h{`yPtkI(}HeuuXFgv1!!V?;b>G zIONiAV#G%N9`gj*z4=qgu!-fEd%pb-NyhMd*DMq{YJhKZydDmNEsr1{gQB;d^}L)O z?Gd^9ONZWh-A%hwmcjXKKh&5~Mm{$6byp@iahuT?gsA}tgm!(~Ra&sj-^r-+c7OH8 zKcg7@Q8S92S|Y8g1SrgnyT5F|b}vv$HgV~iPnMITw}`pF|F`pb**a8>YkzTpry38& zFV2RHA}|82IzV7I9*?J#2F?2Kc8s?d_k}tNYjn6c2{pDa6bk4zmu1?;5u^o6iHc6n z1)bDJq+knq&HQtq$ndJ130;(WouIWKxU(y`sHsP7U0d2M7k&ce_DX%DWS$NCw>fvVy-^-;3JhC zuVaj2xv8JVG|^DO?fgQ+5M^`sR=%ZtN((WXVy=O+fjA8x{uA1Rw4V;x?EF$J2D{+r1BndQIswY<0~ zt=`$8Q__sKTbK~G=@NTpk>O&Qd$5O-%B2pYr*2(c1uFZu_+;wK#GdbL*~)987nK0C z7zxlJL&0F+N)4Gu^tXB^@|1y^@R}kh5;YVV`D-WleUm1Nm_IsAPkB>EL`&;?U6*g< zFM?&~%^hiFLlmT6NE+2Y#YY7_D41*)aNfInyEAHVdc%k^dP6{@ZalnC<6p3;H|GP$UM#dDHbPbD>7t{K_U@pdFOB`}~>jw$Q< z@FP9MH8r;a)*mmom`5v323*b zKc|k{_ZbW=Pdss01Yco2eD_?>J>SxDUmqE)*8e1hBplaIwuG(y!uE@z~p^|8+at_4yGnT9s!x z_wkQG;IUWObhr}G=;jK3c#NJoPn+;@HQV;wSa7_+^2y-ge_D`grU82RykgsOi)&{H zvfNcy*9h6(HN@3|>Q4eJr7Jxq|FUXVMxhLPs(xZymxn- zPg-cEALLIu)0YqqTXNTAftsGoQcFPAP#BJru`aQ{TFlN(-CIn4DJ972pMbI@OkcA( zf=)ffQqNu#fcD}7xQ8`4ubG=^L(+DLU6sxZx%-?n_$^P|3SX%eh6BH!J%Z|An&AgD zh@gGH?y#i^khTDa%N)PAgvlJa_MS@0V$SPkvI#tmW%<2Bcoz|~Y&h2a=FhP)I40|* z$~*a6$;e}Ju~86n7y|f8D_lo|LESd`*3QBU`uX)>~wVgJb|3Y6D z3vEUf`puKiE(lo)fV5;e)?H~>Um$5Yf4moNlr(CAy&j^{tCpllrl8XGmSVx?_)$73 zJH|wNXP;B`_cBT)GE>h^jU9&`-^F=;b*}HRX5&9XU(H^2-1E=~MGN`C$r(rwrq>#P zb#WqJ=|2v^{_t?KVZ|D4zb^2e5dl!(RI2K56H-%+hqKNkI;?n+W8>H5pe!}nm%y-I z(y51BNgpVI9~HN@XUcd73O62qf4V(~?1e0R9KvGUafeUXdc3pd1%T#<&|1J{xibJ& ziM_tgB`_nCqu?d?rky(He$1-Kd%kJ6JmT_1kzyXbMwk1_L3rOGrVK$((73bX>ZNc!d(ow?GQ3x zxw6EoD_J1)C5f?m+#g6#&;aBVvN0mF734;TF`0NZIn8QiWT;4wSwQKo>!oz+-2N98kI2rTT?F!Ff4M+_m`LpLk z!&@i*&y$BM2ff07)G^SkxWTCh0b@A0)Ih<%16Pt*%4>Ef^*LjPyCwdlHO-#)X@|Py z=sdtx^UKcq1+$Z5qetwRZI^pm_i+bXEw@8-LIl|9!+h1L5|Aw2j0*xya zZjr&q)qQEM0^J#7fvPk7*o-jYci({Jc5nKr5mnU9y*@7cMbH*gd4>YV^h1u3HSmTzl9Ghyvt;_@4!_#M4jX*IeW&RE+xH; zCE?b;3K?mqNoi}zE>+(SU)H^#;BFH?oJ2p65I={X(aTa@%+K?@-uy%YNa|J$X8o2w z)Vcn$S!2e%Pu-Y)ng~w`=NOKy0V2tJ9NuBTw1&4ix{TQi1R*}RpK)`BshOj@c^z9P z?^|yiF6fyfd!kS&hL_E7o3(ZFdrU7pSC>UrY@x%H|^nov{V zTk5gXTjW2^xO47YOSD{RoNjGCAd2fYt4tJZnew)H<~kBc^99qs1A=!XhJ`9GpxA{8B@MCBbJA z*=9&to4({d5yGN-6B1w}>MM*i-JAk4`5zTmTORWic?>NZ^o1zMaWu#(5WKPAQ$$!4 zZLES6iS(7@(5eQIu475`u_x43OuO`*-+S)^=wq8dDb062&qhvn7d;7UQ?wgQbeo>fd z;_vtc9w?_eE>#}{uNp+BXpmHQ3*z-nN#Hzh8WcCA;wmgukQ;P`rf;g9%hVZc)=0Tk zs3%~@N$V!W2@_e=t*pw%UX2(BCi(0s(lmg5yF8^+UXgh=+776^L`j@azbh}IJwx1?x z)iPq_8K~k6I|w4V_(PB86Aci+bG7TyTNj6;|6y%D3|!C^k&eY4K;D-B0!+5ALJc2i zl)EUq`;SMJI$0u&`;xmb%a7GVnZ0XHL-G=VV4>+{8`R=_qD_trrYWE7e4F{?k!+L{ z6&?LV;hR`r>gKD22i*$nrT4j4vM*Ahpm3=u+HzS=RRuVJ4dBn( zsstJ_qcufn-$1d}qf5?g01dkbrZc&*6pBJaun00Yj^5c6@!j zORG0s@R4}C)UdDQ(Nw@zc+}^?7Hrl2;;5i$_71G~SnAD?JwBl1Ml%0T!S2%|i8h_) z^%vn+2nJ5wn7BriO;zPS_1PO}7pgWS1Tl3ypLx{ycmuQE_3`d}o*w6d_Xn92E-9-+ zD};vPq&%c3e>r-jYBc5AcyePRP zpP%`G1-y#FIa(JPbEup#X9L)Z{e^bKt(^RShtYpP37dy&m`h;i=DorXK1y3d zH7@!E6dkH}arEV}jZG^qm7mx`_-{M`4PS_THucfEgu(~%BXPd;WT`Im;wZ!d0y9A0 z)mPet(}ZjJH!a^mQ0pAYitvcH(mqqY$BiAi+7;ybTf0U82a%f!({J_B^$G6n!h%U` zKMZ4r0ccwairjf9b9M~~ZoR}D%kd$N_bsEVTqE?A06T+=?8@g*^Eq*(R~1wvs^cAVa6NVtRs953F~h7FdZ zex0{GUBlgxM4|x+FYI~_pP~QDJQ>q<7O}m0sjekJsqh2Tm7D@Qb7hns(xUjDkNzU<>r#5-(7A!&qkOe!^&SfZMF>vm3DSsByXi92Pj`(pLPvr}B<3v_?B(w;*Zi>dMi&<*wWR zMn7HwLZ$G-KqO^%`j|UQpkgkqF%h4TDI~40^G$?SpHvdAJoqP@; zw{L8@<-H*JNu3UU!+DCX8a(K7o%k&OPvEWEuiCl#h+=>6#?Acasz5SW-J-#0!MQL1 zilPtl5mK)T3CEzmo~}6Z>rYR*y2<+LCcWd~pOSYVe; zS4U`Xb%d!AV6bTWpmopuohdZ z1n$e`gF(N6!C*KGcBi4IpXzn68ud3jr72l~$Ef-Df`kvj0QnrlyTVQ7g7ZU4dkU7H zvt&s;&d!|=>K*2ma(emY-SIHz{Jf-wG73y|UPG@$S1XQ2osT-7c3a{Zc0h*uUQ1B? zV9}Jwx+b3{gEotd9!1`>6P%gH=(dVWPL;5O^ScZ{%+4jt~ID8*|{~d*{s+ z#fT=&zrY*65uyxz*!uV@9{(wJXL8Ab7)Tf;J-k`nP}V#%>;r4m>8>9EC>j5>5_oEr z(@E!em=o&Ns*f4s3+nB*@bz*wakC-CaXsx(Oh|{=YEq(aT|`J*YWs>#HMD%@su-Mk za@)3;L+9qWf-tEe=Fl`e=~?lSOvuHW`~sJ)zKa)$k`sme{ky#XXH#P(m3?j}f&bs2 zvan2C%cUmcq?lY3H5B=cmd54K`66u%GbpRdX!!U#v_@$c;G%XTM{Vgd2)cM9vO2VwlT?qS^AIB0;bU3m*4D`k~^R zu?Bp)Sdn&QteP_)0TltL-e@8!J^Pb!cm!Ii7u!Pmueqxp@$vM$yjPw(c21LGZf)Mo zTkO*<%$c(9@GHF^yX%YvWS-}y?vdxhio|}dAy==IF7n<}?&jz`=V{vSRmBDfkA~Nl z_!;;5yqw`D^&hQ zSh_dxEWIsPlH@mgz_a)-qmtDzlo}FeZDMMP$nQ3eyJ{ayc%$-CtQNVD2p;j45|p2Q zi|^DChkIyYGsxqR6pwf@lMlbWT0g=4?RRFjmhGXg)tPLb6F)1_fK8=od|L0yz}96J zuXTSriT-AP@5EKTs@??o2isLFuf&#kcTN<{Vfrg$(ib)d5hPPj2@Bodm_14cuz#5rm@P4teVb5k>x{>uEXyzFfJ z_j%DOf+}2GT%)B1u6x8^i(AVfPV1{`!S+C5VjSbW8Ikv%rlHZ&-r}NDKCY#uHXEd3 zQKU)p{h!uGD7dK^X=t}OxZ?Qc#jzMo@Ka=QV}+5z*n%HTt*t)%Q3>j=GL@|q`H~Aza05i<9cEX_tjZ0XkLd#%5q{B(n3laA_JQWg9cN# z&VH0K7o3u8<*qw^PmNx87Rxn4m8A0(lt2ivy59_Kb*V8l_pJxVSZv&sV#*R$3BrLBNkd;55$*`jJ36DrzN?24ncHD z_^`cf4hVrk0oVd=1V=r*=KK@i4k7XU-pm37l9?F18$|yC`}$Saq)7aqQ{azrEL-F#d=q`u_>TgytPo7F^k3v?uIkm zQM|m`S?hN$Ky9}=(QxL>cDE0>cIzvpL)#v-L+1szj;^lj_a1+9&Jw2!x@RYMe7QQxL#$$zDxDw|zVJgMxDj zatH4`r-8+gl0JsG@MT`ynHZf?j*Uztj1hEU0od|`CNw3G1d`Xl*3s^J8SGL!>`&_r zRN5V<+>)rdvcF#6Aoyn|hfOzR>HL&d7i>DmxE?8O zj2tbhgyw9Vl@F~?N6#zo!-TSiLXlLB{hO{N*7BfHTN@83%!sl`)!C-en<{-Cal;WB zKJs(@r>{zHzH&}MsU$JpowH0vVDhtTw(q7NrfZTv9X5RVUJ7xMvLhAf}*OvR4477W+FKOu_*2g{3c|Z15V~yug&i1^2@f~ax zQ?bi1>7e*)-3%2X3i1%SdHawUFa}vZsy`vo)!PwFHn5tq#S;rgms`8JyQ}Hy##}CI zum4FsvXG@Dq{jb)3;Tc;BL#OK1`8c>a`}uq5W+TLD`3TjqzG$A2Mln3uP4C8jl@X= zw@PtV_12hkediIfq{~zal^|)8MglAbIrxA^H%Wy48rVZUy1_*zlz1&! z4WFL)$3=+X#%hMN&vd(=@I309Zy7QkIW|veMh3yokL5#FZj3`tGX3FdC}6<5I{1${ zg`m4^H$g%7|L6ke59r#qefXZo=DNdk0A&g2UdL!M^c*e6j5{RoW;i)cjxQqbYn*-U z$~^k44l2leoB3L6b&YrD-f{KKc)NIunxL&)oEeZuTgf4THfrt80X9Ss#40z;Z%4wQ z=njtyFg>Y=3H)d_L}u*+JGMCvCTrX32*G8m{r(yMYn|_L?d=*C1rW7(lDu_ZFD-TO zIr7T%A8bzycAYw$oyUl3Dq_9Mr|PQyx$RN;Xo+Ja(Yx2VU;l6N+HH%ip!m;oCB4x zPnG%l4OsWhQ58+7&O;&~OB-8^v}{O0f~TdasSr-|Y`z4P4CnuJg|j;%^#tNXXu;4$ z4J(8O_5=M(Q!(*`?7oNkii&lkaRT!29ob*e@K)w4e?j>L5l2J(Xp=uz)MKnx8-h)c#YKr{cFY?nB?fc?h( z&qr3m&({r!*W;0=(Rxs4MkpZ@I=i}vSVyP=P9iHik`Mj21HI&gk?eN7hfJd3w%H$0 z^Ut>u#kgluNc{Z;+D#(P=tb*!C z)H4(#Pt?`PVPA4YSM}0^E&c5M=}{ZBtN7a9@7y~LWkEF|bH}5;W(cCxikgT^wH3t$ z2C*R}voV~yCzJa?cI4UV8@eNwby@QNz#b@Nvw54dfMR=J=R*f{ACr)_tn1Do$!wjY z2MRX@hdzs(^9fn_g5G(f7l=E3IEwI0d8FpHCJ6GZ&qNvej3>BPZqT;_GGBs-B<^)H z0iX{xVUZ;rcjZyzrK%=Ud8H9)7&Sxrn_U?H^i}Ie{Ybr zD^_)cS`BLu`F~n~{X6t+v#qI^TdLZHopGvHDz`CYA%Zu;rwx?Y$XkZchzsdwjdKpY z8pGkUrj?uA4?;su$AiTYz=^Upa__yXHt{%5Pn=@sc^~?qq$?xiWh04EL`z8TT0n{N z=NvOMWurW?!zih z506WRD{Jd2gVSQXN2?5rNhdn-w=4d%SWV2=U72kESVjoY5(lP0ht@LP*9RtVBJX6y zJkjM4YQ4*fXfo5LdCQd^ocat2j&J*~lIu5cfE}A+m4x~)(csln$&Zo579`a;Bi2aO zQntTn<)!PQ_NEvMM8k7PxdU+Lgk)r{5@Ois z-*{6XT$m?D^;8oU>4>FM{K2?>IGkUj&A>_V(4Zay&`>P-i-euPKHl%B-KL_7`Q6+i zWHuUIKVq1m0hrNjZ7Q9CTP`R>E|151YP1&7)bk)pP2=*XP-*>cOY;$G8 zBTq#(`))RgC|SRDQXSRM)MP8lVDq0{E+<%=io5RZXxV*pND3U#r8`%9W6~M41Bh$) zZue-hNP9Idf7}(8hSNs+4q4Lme zPuo!V)jtI*AZOsl8rNGnws%Ko!(}!uGiGLHrfY+b@78g0yRNo2KJM&0DluY$Ob&Od z%zt`{c2Usi%(|W`s1g&4tP``R{|PyLI2SlK#A#v0XB5Qr8;qtM+W7%vA)Kd~R-P;? zWPwa@Xzdw*{Z=?MxN8N_MA=EFoUsn3P&9N_;R(mL zdwZ#DqfiM-(+(pAX8EY8Xrn38`C4oIj#?V!P$)eYZQ@}GD0K<7GqS*i=LRnuK{T`> zR;seJLrjvB60J5`78V+-Z%*F7%u+~k1}U0sNVWfA$nQENR_@dKyK+XnW~MQUx%cM|oq>6#4xws%fP?y}r)> zy0eBA*1MwRxZ@>!bQBF)(V75&&or|Ffu3<;$!?J|Oe>dv`QmS8KIcmC!;G#PEz^&v zwao(KC5kADcrI4IB;%@?p+f&-`FZrZZ!?JO8_(9h^jGqL|ap1wLP%I}GH z>5iqFB}J4*x;v#qO1ee5yPKs1M7kH2?gnWUq#H!K1*Ge~et-Ag_u-Fyp5@uyIcH|h z%x6Al27K#Sc-+Pd7S!;sHc!;2`_jrIR&HV7?(LCwOWMG7&!jz&;U{#bSy_C|6zZwaWO`*O&ldE=CTw{_&n9~+ zWkM)lo0VmI^vt29xu^zQSpM^syS#KM{oVJ#KjLDYbRXIZZ#>S}1&b}hva&?URs3Iz zZ^S$!e4#qosruzCS@tc;{Xiw>ErVD@AD3w0vYkE^kE@EquSM?a`?Mr>x4*m3`mbAh zDL;tcxBl9DpQ!4sQb(O(TJ6mMdQ~X;kWaLfz`gX>+~_#UMuv6Ad?L5&A6?*Rr7d-C zZf@ow{@?9Ez`E*!E2?3omBP<5SG2QK`Wm%twTNf8)@-5|6K~la+LkAKOLj#ETh%qy zk~3%%YdSV@P{(bkS`!6JZA1tyI}4|lxLxYrMQ7^#*5*phj1eTq5p+BKb_UBZdc3Zu zw0z)u2@M>pjYnP>(B)&Asz+EG^Z+?3M33wefRpbDG}1v6FP2P3Vxv`Pr7!B!A2A+S-5dbQ#xBisAFZOc1<^_i}u!i!srSrbZr+S*2DW@uehSNn< z7a!D4>`G-NF+q5HG>Y$BL>>(Wu*2U)?j&C0AR{h}gM8~GU;mCOSCyfpx8JkW`yOHSRTrmoF(<&|t?_jhrISJ|FG1A5kDhT&5s`!kCf zB5e5P=t@S$_zpSZ-NgacdwRqvGLtfF*w?cFH-PC(e`^|Bcnj*6XKq~P3R^kHFMqSy z4>r{rP&9^guh{8Zd>a;tXCk~vKCPp=YP8ad z89e^t`TIT&j)>sx^Kd3UaP_*~lIE_W{6oyz>({HR^Mep1ZGP<#e!80>u3zpzmri!~0DYtd&7tWMa*~++$=K1c zsqq4H$K|)Hbjf_Q=2lh=Z-W%;e`8BwPkhRB$ixlWk%=S^kh|?kUh(qrM%z_)fsxrS zkV-bD6V}lq-=Xb`uOwL+rlo%Z#|$|i& z-)<$jb$m;AEL3bn5bLVD=sto!G46xo7XvDV59Gh_v{6~LE?^JDeIIC9N5=j(bk3XQ zaZ=AS87`;g%+&NGbcfn88Q$B>^m$*E$PSEgCNB~pc)Y?M#I?`%wv6ywb8S_tI|hx2 z!sA(ND=(F-NhztnqIm94Wa7G#G`tzhm3PSj`G0v&^|7NY(ro7j3`MMmoXH|&yT)E8 z?4oyY_M04)BZ)#>A|;myG8%}=($JOh_X*Qx=Cm}8)n4O=njn458^FaTb{~&{94tp= zG_-6l+oWCo-7bQEb-11KogURGX3jafrF%i~$WLOtGg4PN@hq_Rn`be-W?nw@%Pt6FRX;e}z8ou>!AvSP~>ni%DwN;H4}HccD91;7LO4U2x-&u?f* z74^HScX^D|<}FHzk4ppE!`|iTqytyEr7|mMf7I85U+oNBUH%xk-63?-DOX9$BI43W zO4WB`NM6!9kGC=tZN`*MX^-?>y7O3Y>377l(jCb~a?o`2J1)kn+j4$Vyfq`z$a;n2 z7(Y|%xGz9WP+t&W4pyE1kut=Tb`w|EwG*G`S2bK*Q=F8MZDQ`T>I8{eFzal~hARLlW|9ID}Gl8rnR7X+>hMC`XoPrIQ*8HnnwTA+BagMt>Pi zf~VXJPELriddVb(j{UV)!-0^EVhlfrYhB${L2x)VSA@&l?K1~2Lc@Z1Vcy7rfB>h0 zi=rY-&9Zms{2IRwm23a&`g+W_ZTjDrCG^~HG~~Qwp$Bi+eRHEX78fNU{%Ij8kL2VO zZLmlitUV)hq4&!&i5XpLp4)CXJB^E8s_Ee*+3aP$*Oq%r(YStvBFH@ss z*eZ-r>`L8eM&c29ePSo#b-kIjXcA4lnT`3@3^cO>SyZn72=;G(q@ghk`OTFfp{jv; z1ab>354Lu_sS@)$Q=N-M&)0S*N!0Wi2yZ<~w9H zR2Uh97pPK?1zf)4xRamF3z6vPle3=9^7UI6Xwd3c;#Rjl9~Z=%Dlv_S6uZPv94+Se z83;^_wwG_+g~$(`lxLE|hDTN_*F-#a$HtYvl-$Cs!{pf5=bBH~`Q#?DUQ|V}(6E+z zmwS(+_aj)q>YJg`a3rDj<__n zesbR#e{qY6S;k&Wq0c$ilP<}jd!$q99=+GF%51b?hA(42(QykTS!wQHxC=eZDv{`qQDBp zd}htgOO;eM$R>(iWZdNUwBXk=Vp0W&-0VctgPT1bE%kH+pLNd!ev84A$sD%O7c;-a z)vdB@HmZ}7@}K1Q9odX-7(2qR)B$%1ScH+=4?m#SWN}du&l|PhDh)OhCTq^)Z9u3% z$nc5mMkb5hrHuX+bMSN4B28aw=3de_&mu?7U7Z>>S@xaKqw+@H*utFfemAX9)^nbW z!SD9dg>zcp4nm|GMAJf{7V{PQ&fjkWa=#|I@Z!^SXoV1=M4{uoT|L{O{LIzGQ*w|v zSt**(6u@fBqonoi*!Sc#YCnKEHka5c>jCd@a%x~WwzRQXWrETr%9B-kP+CO%Pk$p- z5I4Z+T`e)DGFb$^nYa6jcQhkOiecPUHqlDCppJe5^TR|F+q!Q>3z@L}U=dOiezOxD zzDxqX*#~qsRqoPhX*5xccP#jw-={&|FX;v#pj=aO(fS;77)TKXN1OQx#MZN#L$UZ{td3b#4QRn)CtrRGM4~aG(bg&6W{yvxkri_Tm zfqCIp3_n?>2NSinOlESuyf{eIKmTfq+HNbdo$6?fNCF5LUb9f|M ztItsmCpKs~f7mv^@%FFlBrPM5VtsZKIYaj@#-yVqksgT}yhmjVu0p2`(F9e5ha|vg zvr&@P&qm+lDJ|$%{%9BS=8bx8uB_$Se<+!H>>M`t#G}?fO~Z;T5S_S0k6{vrW@^8&@2- z_AeU??d#%MfbMN2{>O1&EP|U%4+UFp&QRbu~ zANJ!&!7r=p8h1Tm@GI*K%W%`UW( z`fE$!YRwbux;1YB~Nu2;RR8y{Mf<1#x?^Pn3T>oxSG>dxE? ztGiQqGk?2Ipd3qwr`}2I-}$5=O&t8v!hlr1Vsb!9RccZ3m{-BQj1#)jkzGsUaPJm= zgLZgS6J3SPgwg_fj;}d6v{NL1;70%4lzsJEB&Xb?JB>Y2!XGPjha4TBRkPW*X5H3U zE>o!oDH^yq%MuxPfH9*qOV5ZwH*&mEpow*Pe~wQ^1VR^J5JCGTV5B6>x1&A3O($UI zPdoZkM5<^k6nlJ4gqo+KXub8< z&%&(77|<=YH^Q*MBb!5ymk$oY-mjn6Zyf4O_sTd)gVVK5~uC%Iqfq+vr3Sv_a&UKyuACNH+buN^QOc4 zc>QBTb^vam=$-B~zwMzfTDPz(Of9q>nQ_< zsXw^fCR{D6j%z#y+MAh~t#if2#d#!Yi1%FiH4MSMXHRcCO-{QlI&;VFMNHJbx_K5k zKbTKjoWJ;dTCuPv@?&lHiuI57bAUE-M%!RsixvPu1miP z&oITyp6S9!cWwW~QumQc&C99AUG}B6wD0x5sZz9YDdJiH%|nq4MuvQdqhoX= zdPTYoYnC6JbKEB1RLi1k<0g~#;TYfarYWOYm3*p*Q+Vf<{P2gaSSFv{woK6z~!_OH10PGPJi@qiMGGJk3%`5UhkTE9J3NOE2^I;a_u(IiT}|^A;3C( zHI_ihpa1N)vCxg?3r@p1_-LsZ=tgfq3c0)LF{9R9J(>2-3~TvXybO}z<&gOMQA)*= zl>6!s&B^$Hd{3OJQ#1{C2@>(@(G!2;$M5M02xhNq_IpE_c6oSLa&=&o_Ny(wLwE~C zZjn%?BZ>AL)=LCapHex84VBsMy$sfmdNqrii?mX@v|5Lo$OiYF8{@T4KLhAO`JUGh`Im<@v$k9oP`Q&l%R$G(-NnhM0vk#sbp zTetoF-&KUdvC9tp*}knFc0ElJT}Z<*{gICTqWygUf6es%wQ`3+MWDz?0PQjcO}dht zM?{gU_)ihXsuofP^>>2{i3h!45W7jIIwlo|N$1b$UXAC-Ch;&sAv&?Ue2(2&(IaDS ztiLun@b3K&-ihxYb@GQO_1{c-k(QnY;YCga;+FCUu3S10P%}q<u0BJMGm ze0OcydL<19`YOtZ{!|K{pUAII-{qVBmS3;)V~w!oF1Jl%uL3!1HpHsIw0>2cpqy5P zefYDUGHkiEpna{}z_pPxw9N=P!l-@QwEpv6hZa~)7cE(0*H8X{DPY>d7rs2!Z$h=M zx{}Oe4N2H?_Io6J{hD2Z6C`Bi>ZX(J_KF~x=$GcI232VNN1I~n4S?0oHfkG?H+b+! zL_|~MNh==uhnAV5}Ec@)VZ6=B{@D}>E6%nr+D&W2S9;32XsHu&KQd!)!3na4_M6r7{cv0cN|a;}WbL&V z-3%5z&x8%+JJwG%TBFKFgPPF7K(v&mTt5zH!sY=1l3at(pa9A_FaqJ#%b6T)y+c`@ z*#z7uB;kehQ{9}B!b=0eZf|4bzVhyB+=ZXBg1A>@nl_ zBsw8^s=a7@vvBxplHhhZ(yVAo$@rC{_Mr~31;ZmI)g?9-(0@HTI*}PQeO2qZbLN|A zeLCNXr}Svmc!GjZtOEDECZ!j=fWK*}<_v}X-Ozz?LV*9`2|rnu9@ zT!tBzq#x>}r`gdVxTW@L7+)^zxh*Mq6rcMSS;~6seO^#yhM-)!no8NNXe zl0?Qv;gKtg$4_NO7m~=}k^FushJL!;9hKnJaxMhdX5zzSx(DlD0c~C8SHqJM`sGT} z+jSSp=aN{5`^`|yw?WLAkvn{0zNz1^yfGwNXBW=1+k!DSy(sp`HyB|X{ zA8vgpPQi<(e~Q!j7XNOsr+lNcY}w7{-wNTPc8}ybiVS7h}lc8Y?f)J-F zh#VRCK)oXhT&gd1Ur_vQVgOk|mF-kDkCjFbYU|vU@eN?Mj!dT7wDZyRYcli*af6yJ zU-ZkOmQ_y(c1Y-}s0=NhNEbPkg;WGsNP@~d3_C9B-^3f05m)2I1qm~Y4?Y0r%t8%n~z z9$6`*Ec7YO@AE7DdZyl3CF2e#K?v*LUFX2r_0l8`H@$ zF!l#Juz*iYUeUpwVRl!mS`RHA1Wn}*Mm}PuKVL6{9cTuxyfyx5 zlT0|pxnrb&l})CqCduCwWiYdN(4C|RLaqoZFn_g#L3n=|kS|;5UejoJnYr#L>g~wy zD6$9W&di4?C96$`nt+-OH!^MlFz`(FTBx_ZzkEvh{a4Sd)t7jOVi)C~6Ga-;4ONiP zA$~{YsP!t^Kj_3FdKBFxdUZ(OvB6H3QC(1@V^x$M=ega#qgFE*$O<*8qGb{w^{LUt zdiU3Fe7ku+4~N;T_r(}am=5vA4Mz;4GhiC8p+rr`jG~FrT?do=KP~`~m=CDI4>>tC zH8U#*0klxX7oQkEMn@K$oU9>m@pb_j>vbXc`gHy4(h>#cEuxAwp|y>*5<<~Kzvi|{ z0_>icypFqEI}yeL^bhq>R!|I``Gs_>!;-a343$O=Mpk5z2-l~uEUHreP6?ri>+_yM z4U_IS5x|Hi7RN1+lQmDsuS*{rnsT!bbfutr@6nY9HhJ|PIBcI!=y1so?Q}28gOt`5 zd9Nk*6c=u;bA@lb5=W;j9v9;32!SBA_vi@Q+S(c*D@Q~Evl;*E-cMgx;5-wi)Ule# z5p?^_`*K##fo9#l$r6sS(iEz2$y6&IuN|sjcN746yCuDQh?*R$YuFGn7pgGng%({% zBy?cHfd<_sWdo67l}NJujzum|H1vGoH|=rP>iRsZ6%_Hl>$wMFBM?dLLaAXvMCc=2 zUx~HQfbcR3H_I7ud5v2C3v;|+4lv;1e%ukN!l}TVscJ1ih092&cyxSxoTqJEWnNW| zs7+l&D4WSd`8Ndv5&0;_O#h%!P#Fp(G0c`)C79*Rw%^xBi0FK{Zh3JcF{b$Q(EU6& zUda~I)PD(~%d$T*2y5;_$Z>gW{Z+|_7a_5H=b8(8hb7tJQ7JQ94icBld`2=y3dH~NCaw0m^ED1f+YsK6At+7;FV;R0e|{%{LkXVqvA+8 zOx@fXoR)e2^${*)aP)f-+@O|+;@3 zY-shM{fLQn0R|}LPPDV@=7UJkvobmw)(A%_n0NaZv?_W(o^vnQu{>BsD5R<_SV9Q1 zau#tplekm^>B~6RmU{5`Ybi|1Uq2J1Yo?{~QS{-ud+tKfgLE7OAPsy7CSv`W$dL7y zl3K2YjIRrgNQj{9AE?G_AjOnl_+|MVWXZ8srWEs%N?7=+gJ~*=*r6C%DyX3qRDYY) zG?NBUA!-@AQ5pLR2;_7jRcWE1+f88h;=k)6Ny_0g)(Ur2^$1Aci-fkQ!DMcq9y#7Ra%@+q?;YuWQcMHJKE_`U&2Iesh9>vqe9WNe^15{j95fDe)!QwDqU&Lb9Ceoc5k)T|HvJPbLe6;l3)zraQ!`(9n~d!-2%j=s*`geoC5# z6XolnKqHAU?#w}p-_+$m&cj#i{aC_eT|99y(UeoRh#iH&p_YBowzB#yQB;^v#$H=q zsT4*=dc~uYqm8p%(xTGg5$gs{$|`(_nd3)XEjI$sX|69KJ_KjpRD6}h1fYh|a2XNY zC@X9qW0FNjU0jN?IO2psk}X@4r+aYhbTtk;k}Cm-0V2hsD};zTiXFBVJ+tnQd^V^R z+=qNojxf5)GT;JkuL7q?CVIK)OxIXx%Kj-edZVi&Kje9(j(g6RKTq`-qBN zYx-Rf^(DQj-cm?)Z4~;LG;cd*WXa>Lscim2F>%M*#mug*p8lL)uDXaqMW-Xvk>hTi z{dK1~r97=_gn8?N;)4DH0;VvcD@V78vrc@h?h>&4xG&457at)1!aC{i$DUtLPan5r z>EW~4;qd9vf+fR`U9&Fg6?1X<+`r?0MS388lY8-r<1OgVDBjV{uS;KL;^YIUMxAa| zuy&`JsByQ6hvQ)FXNr4iT|KF0N{O*DxZ_uLl*Dpuh!zaU+_49HC%x;aL@4waGli(s z8{Rx2FX#CpPIR!h5@@lkyyu;suA;ffTT zh-9!z|1>y+>&%W|4lCt^C$#JJAW@^%gw`1}G}}eSOS2Hf*mfb)!|13mEWQgyIx|*X zYDP!nisns}T@pm28g%7r!bv5!M<$XW6bb!@mr}d4$9ON|bYhj7%uD=m-uDP)R^{eD z4sa&E`HK9hUby5!oGac!aM2fpk+xhr>nF*#ibk*<0KpnuUi=8V3e`qQR$8#tjDVIB zV|-%1m)bEwH>0FOpFpDPA^((5c((W^ek+I5F`>`A8Iti`lIZehjNDdoShuO1P`aF_ zngpL7=zB0E*7>dAuSS97aZ89k7Nct;v%7QHN31WquiOGQ9AQb=k5}lUN^vsvbyiuBy#FUo| zA3GAFNN_X+-r_;2x~G*Yo9<)LhoB?=O#wrL)7Vi#WK9Vm#9ANWxJI!=ptHqAWbVJ8F*^~Oy5eN8XI|Dp|pwp_dRvw&-O6u0s@7{U zn_t4JHvwTZ*5X-e6nG0icEeV+iKRZrnH9;tVOnmd?}Opet-fSj&HgEh#t4=qP^-o2 zC3dsm6~mPt3)N=FwQ(omOTy{c5a8Ctyw%2q{{4eCZ#ugSZ7Ip0_-x8YVYcShd%|hz zX=hOFl$J6QtyoO|jPgs)IfMO~zrjBg8mYlbTlSSsE z{T`%escT&?Vu>YtBZ$8gD@8T>)xNIxq}IaSk_Z5lUs#%QWz(U*(`O?g^U$^Q#2VSY z&=2y$>qr*3;s#emoc{j4SoW)4jh+IJF5??r&S)>RuK$F$SIlDQ$^bd^TX<#w&Zq)O z`RgwqvV~NRX2rhT&y?F%*=FnNNbO=f#jZYHn{&u)K_* zqN<7rb-p@!*SdP){TznpeD+)RCcwn;BO0gpY2?H%8iWpiA*6j*q_$yt`~X$6p|&m+ z>f$tq^L*#ak+E1W_hA}{+ih(Dx_W$v5qhM37XlOD4uw_#UJ5R+rDIg9u3t}c7_8iJ z=FT|j-w}TRA}Fs46~Pnqcbthd=H>~zB&mdixT0qPR%51vZujnGFANr{jRvLbprz~R zArgXb5~6dA%ww4_9PMZn`%7?U$w*=L0;3@o7RdgLVA45;bJ+~e3{VYVKz2tYiQ>uJ z5>0)5DGDK`W}3O9Iq&h+Ynj07igY<|Nh?o~ExF&3F)~c;H;QPN3e-`6@|RxJsXJP+ zZ(X48hAylvhrZ%Zm<+}7(TMV9$56~bLWVF$m&A%;1drN=zWW&FqXP7A0GYJ}51tWn z+6)0^q$2bpJS`Zk5j<%I~sWgC+^rBI(y7A!cp9b^f=TQ(P@hYXe(bj35X;v?q!A#dfimt2qGyW9zC@@$`B3 zXSpJTeRm4s!JjTRHfX}aQHQ(j24)sJ!%=P=-+ceuf&Z+goTGTqn)0Vd&2m0>&;ud~ z=@^~m(?G;$I!pN2sGJUTb0M@GkjR75ldS~bRi#@$uT?$pPk+P|SG)NQ%iT$D%@Or} zN0?=ft|O?nn#fd3M>4TWf$ZH&38N862!sQjfN2fga)|s1Z!x4@%v?F9%OV&ZnXj``0heLt&IG9q%64K zmLSUr_oXydp>pUCrd~(BuLZP{d>Xw#jvz_&>kHZ7-+ICwu&C!(Fc3gzmbpfsj(ymK z|1_uV&()PxA|}0`cy;vgOn0e{vh6kioE1a_fx#pPF)Dt0vMIId2N2Hd~huLEQ` zIy(CGo!sZ+Tw9yq7oh+OC}ZpH&ae0H<(*$d=j1;GP+;Rafhuq*@w5O0rt9BX1B~;O z*N5Qu&e$+FnV^EfI4|ug1SaQsTE!I(X;y=ulkJrbDAz-L(2%W4;c1#?=RTT z(plQ!<3R9=6j7Cj_psYFK^P#ONOf8C{c+jroS-)en&>fg7TajKPcK2@I$$Zp-XXcO zA{LOhT6cR}Tg=uv!su_V4ma11Z3QlX=8g&trUItkwU~}%)pZ_7x$~m*q8(nah<5LE zB)m{$z?1}IZ7Tm-D#L8 zTUx<`j*@gZM+VbS?3awwC}h78-BB?7vXG}L7~`3J?3)-iBy>|CR&3G7D9QX~rg<*C zTSTU=2b?bch$LTGz8Coxr@S2Sx~{#oMeEn5>90n~);i^dFA0y>5Bk>3jvso}i(7ce zT6Ddf3k6JrXlryNB6i&R7TraP)uhn9FpmF?!69~#s3R%|9b}EYuR-i}Eu)@?eqY8XPO^G3@8UklxBMyY3r}kl1jz;>k z<0*b0U7aU@sxT+7ee1U*M6f`RO9ca`ZfN+bC0R#@pul(CR!oc5!_JV@YOIAJ_~*RD z#4A=uX?X02!H0$8FJ+5vLV`g*HcQ5S)xCqen#r>OTy-mtUki3O<(}7TPi7jM?4*pK zY8TS(KM{F-n=g{Un34FH5%`#P!p;rZ|6w!LJziZ=mHR3lKw>w)b7UcCQS6GLfDv%WNxx>HH)>Qdw>q)XA6a)Ao z1VPYITThA)lg>j2$u1Zs3JHmQq(d-efBz(?Zv5sQSj7pXW`^sHIDnwC8S$7GOhM3) z{*{Gb&|Yy5A$|<3bv}qQK=(cfvI43X0?ypb)VG${e)#=-@lLPlX{QUI$?78t3T4>N zZxcZ&xW1F1m)R(c7+J;`XMbrhcd!XYk>%Wrpuc@Zx;s!)N3nU%$+*-Y6-nkV>cdR8 zKB&ZZfNO)o%Qqz-UycR*Jlx>CG%1?9v>x_!`+j^aTsfkpC%$xaK7aJLACaJq#WVc8 z8Eq9A+Gl=g&O+25c8>=Fsfl_Z+DzmQ4h_k<#HnN8(TW`$p$NI_FBezpw5ak}iuBXJ zeW8g9jEhc=M%5CaiUgoQfx_dDGXN5b*t4E=d+T%a7zodh;%!WOBtvV{Y0pdhQZbR+)hw$hMtxBkz;razL0vS;zNx}y%OmP)fY|MX}7~Tyo2F$>%EKDtPC*3VD;$k zAl@kUu&DmsdayjZ^5#VOM>WzWXb2&|kqAW(yL}a`kLkHpLWS8zHFe8aU-25*0zrxy zBNL$lV#ZG`E3+GAMxUg@jO1XAopQqND1@fsCa6#9s?gy?@1#Pd@anH*cnn-@t@6{M z$+48RFP8VsA37Cg z9;a29@y3$!YGnM0Apg@<$NI^neS48pwly##NSc8Rb7N*SwKweEfFmM0+Me^>4+SPI z1CFpgbuDHUKM@*uMrglg!L6ipl?E~6&rN*ICfZ_ORz7vXG`Wi4s@(X1RijF&X7Ba= z3(%F?kSA%F(zYl3>UeQ+>3DVLz?54I69g^NLINSh*Y@gnPTOb73Z;cEJ0doRxCD_Mkk3Ag8y+r;#p`&Z+S()uz_s+r1<6-VJcFfCyb0+BC?)ljtq1QoDs zZsyCT{m*=4WIi7>5>whzN%1Y=xvoH-3(IEl>)j1cWz3%9J0pK@8_W(j>~v^hQXxp} zb|9S%UE2p9ji)1iA;seS_+1jjsY@lt!^5KmcF&soW>yT6V2Mn%t|V9Z{s}K06v<4S z-n3;iuUw;-X}C^$q6mX(f`Wf@J;IC}FFTLJV~>wE7cjC{aY58*ac~%wh?cPbOrBk5 zn56&}dqnJT67AQqF&7UiA$&>O#1-~VhgVn^bMWzi3@@~(oA8WjXg(_`p)=(59 zf$sQNS^WfE+Gi~)=igVx)|pT?lFV!r5u7w>Uf%3YTKtpJ!s4yU#P?qd=UgJb53Pr7 zBuy}~mQIr|0$#Y&SXd?bbsE3+avj7u#nI8kj14eIs9_x39p54%2w!k+fATU{c##SU zZZQdZgk*T`{TQFH@C-CLw895Zf|jgX6=ZmM(>6H5ezL=lMitQ1Djy+~P3A~V(h64M zBXV@b`Z_4&e^(`MvbUGSkJN zbcQE#XGOFfW#O=4-@c+1ZtA|w>6ol6yLiFvn)zY1+{VXtzAowt5AY_|`K|&6K|1Tu zenf<(KqYeGWxw3>o#~0->O6GP4&# zB^^aay~1dxl9kmBCc$0Vo@-Z7==z+QdzCOgheuBho9IiumNjZsueSa|lhMNmO!$f1 zT~}rFs~uabn0JCV>Z9Sy-l!lCf6Cwz6~!qU4TriWZ%>L~01Hr$S1Sj^lzY)9qbE`eM-HpeICK#K0Mf+n1(#)U zK{0k9-GR0T;Nb28p&xW43-5K03;>|P{wr$mhjr?sav0=PI|7>e3Ppt&h^L7$rr-1r zzh!|>0avOHgw*33wTaUY?$ehMgR5AhwVy2ctiSD+yJfvb{bGNxd`8i??G(nz1M~fk z{p3^ zfpbGMwyS{_+qC6H@!W6q?GXMB1BOe9VCrO#`gFO5%X*NW8y>Gj$r~JN3I+knQQKie z+(+N!*V7g?@RL%(-li{;r0pgIZ1}yMaLDvku#@1M!1=O>LCS**>cx@i8vHH~p$s zk3sjU)bz8*zu%O*oTDq6F!g1zX2toY zjm?Kd+Yrkhx<^8|b_H;(&Oa4U+S{~ShWpSf2WpKa8t z$whVzO;_)8Zwv)SWGIZKftXHLjOU8p zcIMmm=AJYb6%h%Y|daX~s9O!Oiphi`?*1+(s#ZP%O-Xj~}Pi&7xyp z@Z(B(Cw$GX)}X5koiZX8j+}Uq-!SXOD_TSAY>JE2;uobFOd99zv?h{T$kpfjyzov!E45kG;(`Nl8%%PdIF7l|=$cY!v zAuANB|82@ltR&eDA}E4M&~_s*zSuKg2MPlL)EE3q*AMS2?=t0%sa+42rE z%}SS^Ml$)bB0VR#@4>BMWS=QK^nBiA$dG)%2{|Mx&wq;3R$J|JwddV;!IetbU;mrY zA5)is+8)hI?Q560@pbyxz#rbpDiTP<x)AB99>D)jUv~@S{z|LY^FFm z%S+DB7f?U|DTPa`BK&iV;1~Sc5Y4}E=6dIo$P6Q$Cc9|R4Wn< z8}}`+m?%?zWw!YPPkf-i9}$ovSBOasmD})jZ9*a+HZ^c!OpP)gv6Gq?sMln8?Y)H0 z#J;VhVwglvWMkVLHBift|4$1kF1$tb4Gg9lQ;jI}{( z|LSrd6km(LK10L?3wDV zs#w^M2Wxphnz_$>qJm3!L02Aq)csr8W2nQG=mQyK}$Zxw?ONsxHx9y*b_Pb-C2a>;L!Fm;X<5Twz$USgTaUCFfvX=G%{}83z!&r zoq9RdYcc=w$=Ls}sc2mB664R&?Rv&281AG}h^tMONa=+2AxpDRcsTUH^Jp1#(q+<( z0}3j$AJy$2;(Z`Yh^N|meN%lG10&&MPRLjIH(Rg&Be04|0FG+!&m4VwezF_>B9YCjiydZen?5j3%u)hGuEpYn)E0^n*VWBd|1-u84dR<{Yb@Aw`7LMX}#Pf30q&)v~ zjOON+vx}ZTSl*W%>mPhO{hShkg`I?8poWoowc%r<0QLk1UuJRNMA(wOJf5O@l9B<6 z!(FgY_nWIby7_XS_hnBLHi90Q$Na(;}1sd{^X}d9dm#5ufI?R-LHP6 z{W&J|^?y|b)X+t9IqgGPd}=xe2L}U=kZ9ZxPZ%U*=w1?$O;;L`_+E;27P^Z-2A2cD zqmrUTy*oXRDcFs>Eh94{ zX7wH@*|Rkn;#43*4=@!xE;nrmT@}ialR&_S`kz_t#Yt}FBPX_eTVZ#P}MdSHjeI6gDg0l{p+m`Oz zeK6Wc-_t}N40){wkd{q+>D%WibGaTj{tvqqr|Nla^>0ym8B3WL*j2v{?_O*GU7G-a zL4ilF#$@n+o*S$&(P(g~U$bg}K`Tz$8FfL@c4Il)9(h<=qPc)>Yq;utJx=Yvofm*o zVTq|lsP(6&hW3U+sPCVS*#epF@;}9j=Ispt$|7X$KzbQ@>24P!&*ZG#FXtiLq&u7N z@!~>`3A)-Y!rsNQ3B;Caa=}Ja&bfiuZZ1{+@+hlFMj!b~n zY%^9eN;MAaP{>Bs!@}%|S7v<`34=1M4>Ff4(%19w;~C@mJm~4TyT^os^FMk^A%imc zgA}lK$Z28nU-7yljwbx67diZ?gQ<9dk8|aYCLCo`IY1(Y&y2YrgxQxQo*r+Ur4EzP z(#ms^9UVGcB1#X@ktE9eau)zv+cg3eqB~pR&I|;%YW=9 zoDc~}aK(g*eHS*p>W#k`Q24lcjI!Wn(5P{FFIV{WqnVlHA=Aw4X%ibeyJrAy((v?_ zh~n+2d?VtoX>|Z6nfLU!tgg9vuEC8ay+^(V;II?m z9=R>X)mp1lr`O0IBsF)7)n6{BG>kg#yH2GbR1GE0H@3Ac{>|LY^})S9Sw{lJw;7>V zvXW=lEgl0YqH5Cef^B!AF4w<3p`iaCAmTxrmn+uV90!N5brq0nqut(8xx*X(78ATY zV&ewu$>@WgM6OKR&#|E}K*@!xr#OFlAJT0vjHFV8OoL`AjkLTnrz zv6)jbMz!tNUB3PaqXlzjBJ|d6TL4CI{m>cKY9lX>{d>Ja>aZuQEHSTlV21bVw;vnz z`;qPYPI{r(_S^QCTUY_N?G4Mv`uh643k&)a69H+|rPt>uV1V zy!Hyx6N2g$BE2~9_?eCEK}+kEAf3V(-hcn?gKSsz$3y!P#>~bd5A-R#S@GK3fIIS) z&H&}2SzfP$3a!@bUnUddUPNJqQr-EN1ol(sZmVOIm+9%mD;-{Vetz(Xco};%@{zxH zXcGX+D{}Fj=jQ3UXMOr&uAla^9W>yw^8Mg!rCt=fDHFZ@PDzFdA|&c_6XMjtPcEQ@ zSO5M-2y>X@_k7XE4P^S8wIe1#F8ly5)4R&&ro%UnaqBm14|zd1X!j@2QyD$+&wssw zT27xfZ6**w&7CF#7F;SEuT9%;>Hx3;jez%HHjiZx(kV#Mn6f5msMcX$@_a}_OF}~O z=g-<>;>7a!t}F(-anX3<`;QCMGQr8QL-$VNYe{Sj; z8p3jNs1tN&{KEb`E43u{5924u)d3|bJh2;z|KhKj`MBBHS%$L!6~F^^UC$YQ)G=az z{o2&btbj;}HHgThhE$E<`VUJ-G=Ei@3%v_Y<^CIg!}aXWucG{D&%VbY9^yWSZ2mh9 zd4uAeXL5s&O0@#NosTMQsaymObcL=`Oq&eejS3V4m7uq|A~6p0)plKJxk5)F&O8qY z75}HHuYjsL*uK7WcXtaST_Q-QAl=g4B_Z9NBHao~r*wA+NOy-wr(9|H2H*RC>#_vjMq8m0`s>b8G1r zU3)Tk7GMam(p2Q#QJSs1YpD_yhuPQDCl?s1IU;# zAcK~FfdA#VpXmtPICA{pGdi=Qb=LEE2NYpKeiz7y`PG}kZlNa6vf1>hocY%?GJ+<| zn2*Nhv7VF!yLOI_wrwF{Ah-AI*)y<{q7Vaux3ui+nWvk4t==aT1e^P;$APuy_Dd;a zzd2K*-Rr2fz7c8a3a|mV0~9dUo=uw%ZC16v&!iJkDvF=S%pVaX7J5Hnho^0Vr(No^ zPoA$SC24W$-{RpwBQ}uMx-%WyQA8cm+da<22X@|%{e&qJIsLY{n8}^$1Pz-P zsyC>_`G-pZ;{ook-v1or=-R%igOlXB+HP7~iA?j0C+j5hRe?tb7l^_W%8RS3l)ETXT}B^Sr>2PjJcHY@y`+e_!$w#(Dq-#_b1s1A$=`F{Zu&|^!T9j2zu zgX`{M=NSQ@t(K}3$i%&5iY-Q-)z}L;La#Nh=9ZSCs~1-UKXBylYex;3AkU=BRP8}G zdm2{vbsCF|o^ngiv60a)LiWJwsFw$Gj-p!-X$COgj28;9+&C^s!HO@*(n@soI~GC- zTFOe@pJ{IjH#|=vj_rR*g}n~SbHbugpD;r$qNkEHBrPp%{6C)@+nEC2zy-5Djr9)H z3%uu22G@!LPzA81_WV#QlxyHFR<~Z08oR%3{Ilxqi$X+zP72e3wNidR! z>mLgxgZ%%Sah?kOmVS3@T7vk2;BVg;o@#M;YT4SV7HeGkOgI6eiiwL$Irau0ngU(I zxH4ie9(TRZnO&_Ag2jL+Qx$A3tW7>%n!$H6o9>gDUk(5M4FWI?Z5~WjeSKJ8U!UqN z4-O8@vzp?q9k17vS+BiuL0X#cR(548r=u!J)CsBKc+J5hYr@R#y3P%ef~~zOC|=~c zam&Ru3YY}OH_`0py1_xfoFwnNP^KhrpR-O?ww^~l-6Pf&uLyec+9KMMdUgV1APo*; zR1;5~JvJ>gYF9`7ov2SXIG|cTT@P_VkI=M&vv=z(C%XZRVx(1(f}$d(&pN>LZQK7# z#E2?m1sL8j*j8M4n4s0A1Ud#X*QXlZXzo`VWMso$@$*BD2Q(Xo?3t?QNn#G&<4^L|b z$UI2Qm8A2G-HsM{_1b-Oz&K*yyYT`~1MR;`D?K(P$`Ojk64_H4M21}Zv^(xpgwxQ` z5Tkc*mpq0lxh7%UoDx0dNrE@eJhXqxN>0;V+ueVx%moTl(CIBSG_<{4`X5-WMf7Fw z|7X5xhE@6*VHDsgXWXIt8Z4}=)fov9MPqEQz1vSJag=%!-hML@>P&gkr0~?%H#Bg* zdQ}YNBF*?`w5}o5<{4q>TwsUB{Is!rqO3udib7{+><5ggi0(Inz)rs3D@d2o8euWL z8|;#B|25BUK0dx$1K5ND@R;gkNS)X?ZjOTE9)ngLy5DB#Ws&~A`$qwU;p-Myr&WJS zDB=UASXamU&&PIMyX@QwpGvVN$U;8Bm-cy4R}Oqk00tkXNsUc>)x}=MRp7UF}L=mMXH!hA_;l~$;2c$x~%+e6q zXNf@WLMZ=ON&=iOQpdRR(yBu%P30_j$NTS1O~t?m^L+T9sil9q0yIujBL?-&CnGLs z$9B$>!<+cHI6uGM9>a6d$WEu?TV_E|yHCLiwAy53WJr@-K-CCwx-H18^N=PVgi#hvm}3|`V;&>BQo~7f`~s;^J2Lo>xjJAA2!DF?{fhNM}L!qrzo>!2c_JJ0+Xl z0U4HgFH8Ke?;m^7WT`?-5!$sQHG3p|k$dk#&tBH)dWjjLS8>ri2Cg1QB@(ufuG9LE ze?oP&^EE?p+Sta1^o#Q2-}|}CqY>94rXEA_FCYIoFt}deZX~Bi0LVV8tMtYA=k)=h zK=9qg!ED9h(D!#u+RfVIOL|Rqnj3k;uKC)!M^ zvY+-@V5v)JdEPJ!%apV#nR|MY2!82WG+jIR(`|QbxFqyMhyaXi16GmE=++sB6@6aD z^oCIjLFDYg$zUMmuYJ*;W-7#vj-x-ah^E(JOex~>kU_x#xr34TxI7MlsNQ`BFqy`n ze{b+%H*APq{l&%dG`=zuwcD`{M6}B;j14z%Z&pE8+Vm{VI^s-7maxNQDF4E-}^Aa*yUMZM>WjfbLL*@of#0V_SR@C#PxM;+m?Gm*Ov z<*Hcf3+N+e^9r$@)}xqkH8u6kIXlfu-q16Vn+8b0y8oj{XH^{v4PE%B+1%F9!OA;k zRKgcvO4#LXn`^yLlyY7N+Aq%@PI-I=64+*|njPRzAx`UP7H%_~{Ut79tJ@dZ} zCumT(JnnWqap?0+)nwnuJ~&ywnmlW!%1xo2V0tT!H<|7_Hug^$ZZ!zVd=*ba>5dNP zZG?#`HD+QWA|fCY;-Q}QCgm%oE-R>IdNEfzws6=KOKD5WQ}Qk^`Ba(0olsilpn|j7 ztJoNOv23Mz;zoc%91a3BNNnW>-6xM-C#JmuL8e;+0>WAy#Ie%EvHk5KG0TYwasY!e zzMWDgz1Uy}RORw$z)cul0SG1fPm?{@{+Ac{WFGaAl=~imlJKugGydfvX0c(V#IwT$ z!B8GAjBhiZCx3D)=Sx-YWjrai<5iutGYH#`!}mtB!;U6@3XfXMr0sXA>NLD>n~@u} zacCeralKj&{$AY#14>I$U1~lhL|An`fiz)X(#zu&V05mM06U?RTc_!_xMQTU8}=JM zLJj{p>q1Ic7k~)LQzcxB-b6=Cty#10+l;)^Sku|dwTH~OF=r$CraaEX z9~T$3|MqG2j*eT03pG!B*a)6pz;-V7&~Qj5f9;b(w)bOag2}(}6o^N@XT@=e$@Wj?d#juxV^rUa)#s}X_O=AI)fZlYNN5z{TJ}eIP zTVBYtPqAI@Dr?*R#S$Spm90G6cC!_56(1J(D|NQw5ObhwEJ?1}r^lWL z-BJ%qYOT=c4Hygf=oV@{bLzIU6=jE(+P-=%M?*u-GpRkBs+@X4b~JPlNmCW=5kh*k zA352H$ua7Ix9vC>1pw&+$u(F>GQ?nCHU#iT8310G$)#GACV-QPw%4@BDX!Cn7AiAi zgDFm_cv-@wZcB(ynB!e>Y$_M}MHRHRDXA>YW%qbZV5?zZ*!Fi{S&c$A!v;R)Co@i_ zN(mKSX{uZx9fyyY@k>lofD#jbcG_`XUStUbcb!&xc}WY@e)>WG#3J2Zo;E+Sxdu2mr_+GJAcDoAR7^SWB`+n1t4%lTjAb+XaX0X;N^xjA8wS9VD$DROfN z5NvqlVtn{`q`Uz*8q!d0H;QM8wCYEv9TU~Q(Q)s!kjRY4krFHg04u@qB3a#OuPrQuE5$XC2w2#gtygO9f2M_*#`#<%2y@-KQ;=R#3@463#cy5a4x&(K+}s6toUPXGaM z>hbz&U#nwr>d)lH=T%TJ#Vj7G+Nb5)GBqSERjz3X^$VAq`OUCuX4u3wqH(`Vw+1bl4@7L42;fpcPG7iA%$A4J1`G$e?oWgqQBlKuXx zqur%lDSENdHW$BcH_^pIY;?m<1rDMuO6-E1FEhQxG;~HVflLOUgAKhZE1H_EpoWE6 z=kAWHjF2XeLrBZTt-DG_UysyAzW$yyF#Mi!Y*@!Nl3A~R)OEUuo21FU*`vrvG1L)K zyYXCl*5cE#@J;z>B%B&<1KUA(({2L;BN`TTj$7!_Jy;n^TAM-Tg*>^vI2mF~{pT~` zP`3E$vvNjB2U9UjKN?zCfc9X3oBMikdAS7=1pMBA%ND+kQ_|4XQC05yp+o9-3*JCF zX=zao0&vPqwH3GCsKnu|F`L{rmOUQ!eoZiR3~C~2%a)BeF^cq}^F zC7T;&{=`R4a`Y1?sihhK!iP%a!eVNw|owX_J6ulEK zkCJ`p6>HJ5HM5y(%gQ35%_7MSnm~7$0w@~64Ppc*m zPE%?kYx~gc?$EDuF^FIGb_LlqWQ$hE?0Oc<9h?igH|*T=N^8*89*!G+viT9U4E&!K zfWZ^G7{u5|g@+n8l2n^B-0H(y_)a1zxLKSoTG~ulP=VYT zRVWE34w0@3dn7|+ur=x$Ftrr_ow3L##Ki^6-qJid`QeXwi^eORojkuKhh~Uk$4~zB zUT!432G+t7H7fFgQW_1U{0UMGj);)UPOHI^4y-C1-0x@!s(br~;%k3=Em9NIHe}%s zx{OAT0X?zlbc#k$10oZ-h~M%dm+Iy^(W144gv9RdZfBFr&Ins56T8ze&-M@(?NxPF z)NRg<7Xi+lqyu?q-l$bs5Q4;e5;$#f1Qu;Ectd=Q-DK{fP=faPSJ6*yAbINQW05pG zE*0SnagzL1Qchl;LuUyHSKUg!`$gDBZzOz`eZ_G=Vl4HxXE+Kr)Ts0WPXi_?! zI=_)7;#8Nu-g`SWDl!p=%-Bfrx89epWU(nos*4iy;Nl!%cC1y}r$1X%z!im)JEc+Y zdIm4dz7L*4>1G})+NPBz6$i!%i}|!!Pn;N+QIf#m6U;?#f&3Z+Ge?Y7+I*lKPaeGk z+NGk3?za`h0%Rg)-ahS6^T@;)?s9}lEX6mB`i!6350n*j6z?Kx8wP~J{l0(Cs4c5E zW-L{)*BVuqc(yO}7FvhHY{!G^gKJ(2EN#@na(3z~<1t^pU__?VvE<6c0ppJACM$BeAwu&@pYM=E>}O4&lpY_`y1C z7G~sfK}Bfa?9kWdfoYnj%oKua>#!+S`qSdpLh)GAyFY@R`NMWO+WrnSQR}B%D7L78ksE2OAjRE^JDTJwLHCl;YY1X%Sk4AwssIn%oW=RJQHM#)()J?DKtc zzRfjg#tm@pg0x3R*bwknMB@r}V8CCYqtz0S%1fCKM~1H*yNP#&N-Zwck$!sf0RtjQ z{kaYE{y^o#nvZKnm*vy_;*00c#WWN&7Tvlm7-@Oyv<1Cb*yy?C${W~NjGAg*9C*WL zW@~$`Z!xu;E6yGS|5Pk@sN>7@E`mZh9(PT(n=TE?*1TQ}tu0*r(S28*cD+AWbxw3? zvb}n%eEk>uYhO^O;Uh+husiPeTJ+hbSA(B$-`+PoV&Y(axhNn4sY#Tq($e6Q`D`X= zT<7=ZsH%L*z%h})bupr$3IiAji|-Ykw$CYE)hLotc5F_iu7*bFl4A$Otg5Y;T}|BJ z5f+l^pll}jtM~9zQ&ZYHI-D)|dHNrA$7$XwD*mA_w3){*GI@0irQW$Yj?|nqoH?g$4g{rBm(Fu7Xa9f#) z&T=K`Ry)5Fa;*l-)ke$d^)nyiX`C8UP~mGd2Js$Bp!DPPT1x4&IH7-mC1f?b3!9Ip zVcGFPtV1OP>M}qV_K~j%@$pL$jo72MPJ$)Z^Xcm|IxHxXC&rrER`leG4Vw3N#MgC+jhc_P z9BQ3eOo#3gMs!v){up1eNHjVv^tA)*rz;U$z{HjzJ{+oUU~vE4w}LviRLpj$f@f!Z0xKKg@46s%S=?QQg5Y zuTpj|<0(mt_;0+Ke%y*T`V(h#))g-SKc~Va62I^7k1(9gsQlO9;$%WYLxbOEmm`QP z?UE)R8&>rh8AS?(Lu!G-JdIRe3|>L;d~9s&MrR>sX4xAj#z;BnKaQl^DZE z=$ePxqbb$s8|P za!0evB1$_pNJlI*dsix4xKvRlPJ7>`9^157(VESTJTv>N+<|CrDi_Y$RiNIl-0Ng| z+A9B2wqEm|oY<3M|12`t{=26mRJRo>(m@!^OW&>utxF&cQe{HQS#p{{OJzk|=b z=7ndT%1)=MTPoBMAv-v!s{Y8<{E#0Td&uu2tPyPzy^M+tdaa?qXz z8dd$^MIu88B&p4XWMkh(8_iBjng9DekbWV7GO&n z9{jTSox2aYB6yS{r~R=S0|;2CAN=tjrKB5mhmA!EWMON7|E+bZHe|D=TKj}|m68>KMj3nV@!F|L&pFr#H{7S_<6wkqJe~nN zZFzav7~=F4mLm%Ef}SD+R&)v14(d@W_I$tQFXzitE_ylgtWS0jxq{CMD}s0967R~t z6y}aHQ%@m%6TJ!KDxNKUH|=fYdKH`Je*)=Mh#Hj)&A6!(C&DK!7t&EkpDn!QwW6oz zJ+~Fo$6yv+igP{CcxlWWjrBUs-FJH(5=4SnWbX68bAV^qQJXAUgz_T++06R6UA0Sc zc?~yHhbv0lDmU`d0d{ebXw~-TdV{h`IKmgbizV)uTXhF>G~HwaZzAgIc1^|4WZueV zVj#XZ)|1JbWm?Q*COfRvN|GCW>>#M*qWI;c=9h~0T`jKLz z7y3l+939yebA@9Q5^y|B#n#=M8!v3};PTDHlG~RsA=n22Qy=I`ZlGUuxJpcALR~fE zWpp#=DN!fc6km!zk~U2KNR^%WR7}UY;zpO9 zAw6qZ!aa4Gt=EdR7i2+qFg!H;$)JIR_-zVX1kWTxqx*%`;z4>dMLF7^=Tvyb<$>nH z_wH5)-L11YP1e2&3d?m>ZJ5#ip18Bu5OIZ{Oz9p}Uvx34i@am`I;dugpO>vnAXc|m z%+#;G$NqAETkU?u=h{%Wf#ukNaj@y5_nCOH0n5Y}!&t`7DWwlKM7-+SH$q*jixin! zPb>V>S#@pYb3=7?4P)~k9x}~1=p@#7VbSU%{KgqfCB?-+grE{Lwi7(H_bbVoS=O)2 z6b1)4`|2QMN*p(^GlYRqN>e<;>BjB8%5wUQsp%RmaOYBX%Sn+Nqfj+#uMk^X-yIbD znN4HR{r3n-mVg_ozxVIAi*a>tyW+eI2rN)QAWpyu@$xc)dhj7c-rT-(+fXtoXJ~6% z)SPn-nTtM^!0LLx5k%;^CqlN@yM(XUf2=jRL`EcPQ9`#6A2`xueZkAv;#fbHd*zE( zPo!y*dBEL z$;a{EmzL<*E;M>-nLM(!u{Su9zdyPxSihz(CnxVbOe|F9yQ9=RagaIc5RP9cY>(Mr zyC+Qe{+`A6kY4T?W3}tK-?YdrTv;83)cAIgw!YNNwU&yPFR`1_z0BS3@|P29i>S9E zk1!uQ@BBTG&9znok;5R*Y04S21>YmhI<^tSaX-Qj5260f@xV=nt2DiCAKleFf>k!q zz<|8MAeAyV-~OxQ{#EE(dpo5}9J!dkf5*Z%?DWlFKN1^V_f%JNhCK!-K0qK925mO) z8EUmC_?;jW6cqd)jrOh9Is!=Kub~ARiS^Af$U_T0UzHeFK-*w-570+l*oW5Vy(-_wiPKEgU zckPa>Tf91Nk<<6D4KMeg<5NmKH=EHUV-{}@SEofz+y%~J^v38XS22e}(Vm}V7cYTB z@Q{cFTexOSFKFDD_v#&^MIj~*Z1;qYEff*ivFTTOpnX)B?Ab%nz<;-~bLRT`Lzi0K zaXcd7(&CDH@4JLWkXm}$_c9WWCij{NKA7ISfAjXE%T7x_#<0smSs*xwA|Kqa-M<#c zO6eZn^*6O#D=fEahjKuSE^eGgkAEnFojEMGkWehBg9Urvd=ECd2}FnV0&%d{7*P7f zqlw)moV1Rj68{{&8jG(r)*KmPNOXHf@d}2~PCK|a`aL18XoJ)Ghxe3V_f9K7rlm%D zd*h&Pgevy>Md4|h(|T#j{nc8I)~T=Ln2&2`l!z%or!=GC_kiv7uHZ)JEkw*!H=>7| zEh?G5%MPqLBoXBJz922%_Qs9p-`gl?e;5%#-ti|@Bq|oX`olK4nDPFm(zS`2O;1+P zL+Wu6w?Vd)cW;*Ll?$gn#F8G8g}QX;QT^zx`7g{J%;KddFf^6VEwrnSLmQ6gSj_5`B-- zW;A7c(wEA0qD-kD_74nrveBu)f>HHppknYK8`h3=qgJF1d8D&E)wc7#FpMId?uw%7 z6TlUrEjeSa4#0tolFrk%#UKk)Gjl$JJN@C-`WIRlaB}CnY>G+w8X5Ajy!>kTV2<;? z7Z03IG9kbPJJ%I_y4s2&Nqefza&_MqeWgkb8QbW&D&Cid--PX}@^!gPF`=)LBidw8 zNO$OHIZ$+&w|q*K=ymaDUbaTHIc|6#(ONY&^N-2cr{0`VoMqO z-j%n9eCFmn9G?D>W_@$+-tf+`0gp!wyKHSg=a{pY-eKoqeQQQL3nRb12_DW@-ucfG z)m;WbPw>RrT1|fEa$0ZUu@9atm4jqk)#loRa7;lyY_c1yemoirQa~WY>CwM_^ClCg zagp`(HIa0({`&kqEVuCIW*Cnxdy!+$5*T?ciw!Hp)dzFKne|4~Ua#p76L}x_LPEx3LXYG=&l|4?O7BQth1ENdpuAF*1T) zIH#(T31H3H*1%5yYZTL-(JuPh4DkSVq`f2nftxGqB7xGU_2=nH;v^XiIcDLdct);ToOcMC#t*2>4Sn?2K*kLMCkx z%4TCTz1psHD~Spz{fMdRmNwq(5~7LRaY!Ee$OsYi7P}DR2_E4Fm-kXD3Sw2Z=^unm zi^%9vdt9y*BX!X4Imi=!w@1DFPG0t@Bzknv-MqHG;OGLqWyQJ$GG+hrC9}Too`6v7 zs-XU$rE8VkchXqJhFL7M$x7avRcpNN6^Hquwf?>jmtyE}@jh+v?01#1&@SHfn@q9} zTm4I9y(>3(3?#DfeDHq`HOH0+?@>sV7J$^|W(=5mFXxto)9MEc%^ zde^J?YaRqz?R-H+jID6v6FkEy#Pc1ySJOLc+BZT+>ansa8vD`a9%cH-s{Lc)pH@Z^ zAp)e?in_F``SW z6e>i^5^VT>Gq#87_XEoQ(uYZy2c_szUXtVZU*9&-QEa=+I4F^rk-D*Z~v#q68 zl?i=k{Pl!O;_$|Ol%9u6->c=Ip@)m>yJ@gS3}*J5`c>rs(tLy9hqHyUxsLdo8WHYn ztztt*g-M)DdwyHrnc!=+aEN38nSr)Ex$~U;w&>0lq52$JE3^`49t%0fAdZ>?Q++xv z|2ROjF9fT8!ilF=&?K}DU)wOU!q5?gE3hwVw!pBY#AJ% zFLmP#H*P}<<@`I2`FpFEH#sN4{?k}XDY;Fj(*tf?zyEcJl(PYCnV?W;7LS5dFES)z}kexB&DX{h`nODiYV%*+U7bY;yoRrzSCB^xiTDvv_Jd1QI^%iOzWXKy%qi* z)xX^n?`7K@h@%b=ZE^Sy(Y~jT7ll^R1mxXO@0ubcm?W%q+6a5Kje-$0wJRM$vWy$Z z7(^aDhcciPc4PXD0qofVp*ycBmm#$upXo;woT$nZ?3yk1XYA?qxMsVjiwo!Lx;5ZU zenY*ktwF`8P@0WIGQ%`ZoGD#>nZLunzcyet)gD`>R3^AIt}Z0Ju#hXwph!HH0bjzB$#4brTQd@OTMW7pZ-hQjoolnRn$Rb zqv|Ltn23%61Hfm$L_|bdUz4tC()wjH?8+y@kBvhR`_zqSsbLHdkQo^nn<>_dDxe9D zm5ohzARN*Y2k8j7`kp-=_kO$t5Pek9QIfZXc?S+n`oL0S^drMQ zL6lpRsL7)Y-~!HVjLyBBzs9V@yY`6ekL}U#iGLA^=Uln0@3yH~XirZRoXAnt(TN-y zl5^)$oe*%{#eT-fSl!xc=l=Y8lOEf0tLM}qmlc*;upuE4(a$GpmxYC8eZJZ>EjM@I zA6%na;;y-T(ko$JX4C8bGEpCkItFVr{M6F>6}*XB%#pj~vV(So z0m7ksgebMkx@iL)z+lmH(W2Cl>UzY6rC7A;09Li}f{O4J2W?kfbATBp9Qf%DOzXl{ z9FQd$naN6o-eA!F%?Oz*oiTN7lOig6*J==Px%RTwpj;!D)u3`CfU6o4D)u{#1a0G& zTAfvMK7Qo`%gxS6GShnI`3R!e*+_Dhgn8P0ocb>C2o#bosXTkcv zCiUMlcrzsii`x?hZ6II^l+npj%O)DY5LVU|xi`TO!nM#poZ z;6yM3!9pfcMj%`eAtMg8_3!d37Dmm)%mMch@;D_ybN>rY0a?$4a+UZN;<_WEO&I7Iczy zza~eOlqAi)2kJ{2ItE^D?jA@m(-^1K*Z;5^7(f&#oEvY+tvcb{UEm8i4E>^RlqV%^XW0IBqMH%6KJ{(uXK!R0 zR0=U^V%J@*<$#+lPJ7bKOwZ4!x%1KCNI@?zU50s%o-59~im*vVM?AipP%8QRgL-sm zfuekP>#P&BF+Fm({X&OhUjWW&ilaTQ;d;$9+*qV&IiVP6=} zZ7OOe#e?f}-4P^YMvOU&$!aR9f9vQ5K_4^wnl$ZhooCVq#M>&bQxmMXLCi10MmKtM zdrDX2i;tT#A)6$)|5loSk2y}rb(sTB+U4KNKFKrkdJLzVVkB$D>=S=Oi1Su@J|{3W zfYn7l8r#KDo6)AhS%OJBl~ zUKYG%6a)v9G&N&$7``MSa=jaVKFUv?543oRRX{Iy?5KZJXa7#jKNF9b6WY$)q)P`+=X7M8Z7OT z#6-^jkd;i5Zg))Ae2TzUm(IgH37+%dMTOi5w>A{3t%+l9%DSbY^Sw~f^Ela>ZPU&) zN6nNJRli@T64G+f;MV6$AU{b;M)s2}_;2I?&%fl+&;OJ)qeP6A)a8E7017mwdH?*k;c7z1Y%aUMK((3j3_x&FQh7=iu7 zVNnR(4=PI=?3jF=&#nEf71EY9cq{SlrbbQyFs76ygR&&m@=;OxG(ZKkhyhwkfohB- z*cOt=rwd5|nk`s5&z_hv>G_zRD}P}12eakB)-pA+Hwm`PMu*<*SPv@xqbEvBAd88< z0dn7W-vEWWhyje8=@l;|3|Qdxmxcx+2%{37y^M*`t`%V#RDujWUud*xVz20N(0qJ; zW+Ajf zDtgQ@Xb$9PLM3gX+6${$h-@c9ePJ~HBIRu;P)n;IUbpMN1Le(v3faShV0?c7pOpXY zTOVL{Wo1M>GxTF6o3^b8i78`FY(^OF15$x+bN}_qU4kB;vn50y2&B0-L#%0k`7&++ zvCa7Wyp=nNIy}F51`}_`8dmPu0Jx^7v_g)1%L+Pa@p@8nYPx=qak!w=;%L8}tDC!X zr#uW8;4lJtZ+4ZuA3xqe1`iyh0qeiQ#lzFn(AE@SsKPR{cFM^7nAJ_L2k0d59=~VnwcX)DuVh>bt z{<4WcH7wyK($F&9B#BFR6`90)VdhJG>36~?4FPWryq25NeL9lcDc-$=~$iRPbQsnBZ*0&Ggn@Mqdi z@baL^W&+bAC~eyf=|2sM(r^F31=~42jX!4oRi6_WfTDCB zIzJ?==ybPGiQA5Th!w2NwX2(#r~M~BSI2AFD?CCO*)gHnOB}^%)rkpKJy%!! zf+Ue#r?>Z~*FMXj`pRg2M)vw^Yu@r9?t7q`zyrpU*-QjZw{A4%P@e}gXZ&yGR$_pQ z$Xnsyk#zX#EfP6o?Rry~-QFU?gh?IIO-t*=Y!XN+5ka zWb5aD;a~9dxwNOxxq@p@T!D+2WeIrWKyD0nr<#eNYK0meMZy7B75zQgur>LrncC&; zBCnaa5tGfpQCms8fMPO9J=x(h09CudlY?21GV<}s0$~Cj3R6_QlY<|7t}RXRyAw`?L!#eNlk8#*sU`QC z@X55`U%wtuVn0OMgU0NRhj;zRu7XZ#-4OGim?O4(@`O#I7tFC$;;Kp$nB+QmZ%Ta0;>n0_JsPBmQecMt1nw^>O&>y#0%}Y*1{3JOTbePuv2B6=4kjQV7yPqm09-|H zIdK?vKnIV_UX=e}U7YQR_R_P9y{W}H$tG1z0}FSQH?K0Y!4$zlE`%J*TqcTo*`$Cf z2q4Clc);_-G#aJroXxu3l404a(;Nl=B@dmR#-015|sAXclGv4ih)8b z5!7*qr#1v?YKdTW2;klL=ol67j`a6i`$2XoXHM2TNC30*0J`}kBTGK@86ul(Cd7-? z(_X@-rF2QP715lFYZ_Kt4R#Nkv8eH#I;1VCnx308H8)3i@#4i(K0c$Qgjrof!+NUV zkBX@&T|r^twRf_6AJ|n_H8w_oeswkSG|b2YaTGnIu4M7S$cV+RauiP_q|08jvd zdhtkBooU&j;jiuGQ+aV;G|>m>bt)VVPqW zMaAPqqf($P0Jr7n=Z1#4+5qs<-R5J=1+8C_EIA66NXzS$rj9|mqfTae`bLN~vsb7S z+ZNDkgQRr=SmCr=(+e?@>aU6URNIFOohF!kQ#Uz3cutBszwcd!;kvG%3;|znq!cA9#EpXfAL}guTL1t6 literal 0 HcmV?d00001 diff --git a/planning/behavior_path_dynamic_avoidance_module/image/image-20230808-152853.png b/planning/behavior_path_dynamic_avoidance_module/image/image-20230808-152853.png new file mode 100644 index 0000000000000000000000000000000000000000..ce8605cafd666d4fe9f77a938223f622ad97e21f GIT binary patch literal 67033 zcmYg&1yohv6YeFXyDupz-6cvRBHbX}(j_I`jewMbN_Tg6mvl>mgmgD=SG7^$c?Oe>M^qJ*!Y=91 zYAkF>NVKr%N}}ybaoOIoT&#bk$9vEab-QUR0`1qGVF|7dDhU#c&<;-_;B#5zbxxM3 z!0%Vy=qoR}%00Um7djam8)MTRe>wh1kRn>hQs(VjihdX7<~whnC4sp9c!=qylK>3F z*w`4QG_a~?(=k0a7cnz4^XS@Bnk^(WkMU?(UOBwms2x%GO7w08QCQ?TmZJO1EJupl z+1{f*>S+3AG-d3h!JzznhN0nMhGsnF(Uq0wugNk0Y;7gzp}hMlOXuX`(((5^@!b37 z=4R#c7CTCE&|P>lL&F`$a?43z_3}1B55Xexi0+e{+gH0UVWHvA10#ArlZh)RM2`(Bm5$npYK=R-T(1B1)|mISSKhDLD`_6-g7qG67$ftW<1NuK7kQ zhme3^^!IO_i(3Z7;K=vvCRx%rOLv?GG*pZ%sUsn)tA=1pN=0T_Vu50mUx&@WI#9H8 zkfja=`=lkE3sn0whlw}`o*qckv_nQlrshT~AyFLxp7=#^xGydC1Q{WKJ!M#$EkM;D zJeNj0=Y4;k9_hmu5^+i7i0+P}fs>@7qGdPFlExO3#PCbk;fDlw{rU4pvtJ6>6C6;* zf8UX2H^_2)<$gx*DMaz~m1i8_D~3GOo1HN1H24@H?}zgoekUn4^WV|(1xJzu68fM) z^S=`TPss1x-lh*}SDZsGWqCg=Rc{YL3mYCDPA@H0*fEXisAJ1?ces*qL4)!gu??x( zvL;1<&BPAa?{cfb7D5>)z&^_D`HO%9J_D|PX{t(z;nN>QNgXpE5~~)e%1U}7CXuBF zEcF}K5Ax&{E~F4~qu)ufQj1_QuYx0`f+M|K^?}<)83Av~@_xD$81?#TArAVII2WcS zgH<>7U=7Kb&>%+1Rkk6C?5-zgaR+vBG~%Jg_rK-*Vqj?*e#?oID_e*c(rVHh<3Mdf z!^i`|@#jx+gh&YqH3=kQ4|n%?J(Q{EU=^(Cib(ASF)R}j@f}{!sfbSf4GRGilQyYM zD)`9G&Q58zpwQ58ZUKRCN$R29_T2dN?=|jVPZqu(@fLN=`y`k%(KlzAQP`(QuIaX_K&DZaE#V zBK}<(94SFNJ~0shp1ZoyANN1_39WgDMEnvdSUPGdG9Fbs=Uq`|rZ@;p6c89-EpL9( ziAy3xs$!rKg@sy1k8A~uY;}%hz6H25g$1@NWc`iqc|DskKk1*ANaC$yH_iS$W#FS> zl+;SdPmTtF?%!8qjt*Zj5$DH)6PPPAP0j*;W(ko#P$_(*q=u7Ztj>HJ-LZA*Kp{z$ zLCh;4kUa02l!pgSwn&|+5c-Y)ER3Cpr(0SwYW;}teC;SnHW>|i@7+2+m`1$nSpQ@y zi>{+1_5evnhNn|_TGkxru(agb5ux+H%Tb=r*pPxWV;^hD z&<~tLztR7!2KF5V&LQp(z#?V)dL8idvul!znvmDt;Vm$u9TGn;>CsTu%4-Lh8ZXMSiHld0FAVg=DQ%~c)+=>4DaaA1BGcgGXSW5Ga z=S1_YV7I(rw=kEcG#EZgFED)G<%Y#z8{kvhP#`vAVaHB_Fnl4e^6u*XpyOgqYb0ZQI6#ULFx6qMj@dY?16%Oz<5Uztc zAXK32<1Wbfj8B)+rvMWI``Lg5a&&tS;0F#s;w-o|@c-S8Rkj@>PMl3j_{e`Np0i)$ zPI!uKk{VguHiikU-c`2U?p3ywT{MJF!UR2udH_)HurS~USXgaf)6vk-&`%A-SbP%j zIzKqXvX5Kx4~F42G{jLIM&)VQ*+HfH473Ch>4k-;5fKsipQvSaozHjG&d$$|T_c05 zYif)vERY8W2SL|FxC<{RO(aAX8D;ISq!Ch4F-{*H z*;`WRXA}dESdX_DXakYy#CYfoRJ3f^+e~WK^pA>Eb6m1CMG1+yBAHW2m*?sSmE- zP_>vxNg8~XI?@{x8yYHY>*Rz7{0!i-Ie>0QV7ULdL8yr;mAUHeQBpF>le4Km#b_KI zRYnCd8QJDTq$)Q^4Gd2%9?!1Nd*OikM>AMmw z)&Md+xteO&Dw}00yDk@H<`JQuI;S#6pl>WCH8yra%E%TR1f=(PKxNbpnNDo~&eY0Y!)a2gJb{7x^|jWa*}ggHvtXqcFlHp$^QNbrDn&2h>x zq$`GkbkVU|HZJr0nF9zLHKVJD@e_P7Zzq_dxaiHBU);F;H-vbW|BLm01$$&JzG>qrBsnx zmq%dOn|C)_hiwIu8{URW=g-`4jO0ne&~)05`aI z&C|xpbsNH8{*b@A_Xg;v)&}B%4IF`T0>A{)S1z(3^ClSl2dDrUsm{l4j*<#6ph3PI zSV;8Ecm=ReXa9sZYJoL70R9=DKI^d3Q|J29X3fj=6mcP~=7ivPiWV^6ZVWacEsUXq zo6^m()ZjU|z%m>lLli=hMI7~e4A}d;pkdsRASOaQIMq20dZmJlQUIdnLxGhQpR8PD zHpz?OLkUhZP95BFJ|-518b2J+4(xogTsf8WCk_P640xFX=|hGM_${9>n-sf0PTRwa z%@{bixuyq>L=_)U+_8y?&Kiq>2si^NER-OS^uRa7BrKH^fNy1lCq%|$7J{wiB?BBs z!A62NsMZ1;2m(AdtW*Er8uOJwzSnIC1i&vO*0z0m4G07_wvuSz@_S%v&pVLXWS%D= z1&RH~nnW%=C%`%wfz=D7pAP6LW3(G6g7n?Ne-{Mc zUC#1%Qn}vFGdw`9@Bv#?I^J{fnBT$($y`})*0bw5Cy#!ybuK}pkY~1W$T{%lHzyeq ze7qh8!;=p$WLFQbA8&Xq$|tDhyIAlPG{nTRWzkb44JIUyzmrJmN>A%tmGWZsR-(c{ z@cX^G($^<7f1UN)ws!C7zWYt%BVqLKhuuKN92y$3U%(s)XPKbEx-dlx5(9vY*S5+g zF+Vjvo>4HpQ-BIBR%iO@wubyvdGrimW(EK-yp=Rf$HMu^?_jiWsUa(6Ub`?M z_O^E6$BhmtKc^=R3+{vFAIEz3*RPAt9Hp`Y6D?YJbNc(=on2n8fBW!L$(eKeTQLZDtpM^=WVvRM^-~!$$J$J0osi@C4+bpWm57wbiyGy-H7^ydrt|yab-Z<$ zr7!tOQ{W6p%+=kNa5SKNz&n`%_F!X|y}UE^_SOTpedeIhW3z@zKhO)(eLEtBsykG| zlokVjikzN6hSe7jG5T`ZN7#3`cVINuaGS!o4k^{hjiUIRc>1e2VZIKr<_JwNjE(Qq;KavMm7{($Vae zsum+ROvhl!XIKRYS>J68oay|98YKw3VNz3PdHHF+}B zMoT2%)W9XN^L?i;jPNF*Xu)iZ&7q#(DUe!WGQ2TfJ-Bp>!LFu z@SXyk!}_hConXt_WYQ9Dde6jUs*k?os-doyPBu3;-+8@-0#hwr|8ngB`7%d0Jih$H z2>G^?KyW0nDd)E<53$U|q@;46$A?J~si%DePEDy5m6Rmz3lS3&kB*L}B`-g!sr2^= znn`^g+%&?cR>Q9^coVF<`NB5ErE#%rVZZM2;r9Kal$t3>cd3teTO3?moqRFzet?Hr z9}G&(cRhtcWmy@daH`;pQ@H@3eq5}$dBwd8CU&VwY!i#$0#?4q!#I!`NopYHjEq!ZC{TT z{u~yD{BWXyoc=@W^$%i5t5BAfP%5VD(x(@XZIV!se*Hn=&&}YGY;=9GCMhQESN{=48l>3vkx)ui&;-)z!z* zn~XRS-He=uT5@O7Y|kkG*CmvV7bUvr;M2_F1t%&lE}n1E^Fsc+L7V0qNlD40HaJYk z>~~qYEMBoe?%4QIPPuvBmoLNqQ!h}yrKE`K>!*$nK7WR^Kb|G{AKOuPheA~K`pwHV zA!SeeJ31kv`i;(9pCHLQ8&KkcQbYY8+Y0J7TK)ThD(YY6GN8>I&@5JujEZ6aQVi6P zO|qq&iU*64Fo-}~opqYP!F2upa(QGxQW^b;jqgFIz_EZ#Ggebm!<(HX!Z|?3Et#oQ zRaF&#E`*Z3`!68T;Utye3?GF`XCe^E-F#P#(2ZxMEU8P(XmE@H%@biK0_ABi;9Dtm zgqZ?rMo3A?^Vw=-oUj0~WQ&YwvXQ4EfK_^I&&JI0#>`cBvSY*u2nnBJMyJkR6#Nrb zmJZk5!{hqryMTtqMh;=&=*>-2;6Wt+(eL+6#8Hye0GdGEq)~HAA8*M74N7N|FnZci zsCH)kAr*{uI-N79b^8I^jjajlGz1nz0UT~u`H8>H$0=1$WdDD;qQf^f{`pU0ue&RU z;D~rp^CZF+jaeau1RB+Ru4;O zqHYgcQ=$v$P$ZQleZ%;xuMY`GA_t9!Et6Xko9Z%Ckqe)&^**nZklLZ3pnrI}Gbt-fKMXt2 z>u4x{DA(MQLb8!N3wRV89XC;&1jv{$05>sGg>nk~koP=ISq2#^iwe;G7YaY0{t5%U z0vtXC)0p{SlO7wn+X_tGqAeOax}k|lplJ0#!fEMX!p-1${l~2*Cn+>4g!0@~w|srh zwtOD+Q^rPgQo-j&1r&2lcPCG!7ak`F%ZG<2nuxNyy$!;tXJ};Pqk<$pP64#`RIA;r za#?~UE=7%a9eljH9`VteB=M^DvZGIr zDYd8;RM@-|YWBS5^xaVHpPQR&>b0vCU|z1TJ=L7LI@KvIQZEF|iz0N40VF)Bq6I04R-|ovXW;=4oWVvN|12oSixK&#augZ;DIO>Q|9O zN$S))zHvdHx-iSYvh-15%b7g&84(BzfZ&Dn&)`c7_Yj~w4(AcelT~H^VD6F z@Wre#5GdS^yFm?&k`L5l-{r%QZX?nEWMp4Odict@qBBk@%2j(JFE1~UbQwj6J)u#O zv-=m37M*kc&0_wQMsWF_y053EH!BxKN-8UH3kwUiF}zXhAOHL@1K1}kCug%GB%S@x z<_8zfDzZD8F79@JKJ&4qz4Q+soay zzJ;yucuT3tta0(Pwq0|={uqzQ@N$HL&^66(TfU{ohs*V@FkB#pTgH!UiQCzg0?$0L>R6Ntz%(I_pu;-8b z_3KxKQ0!!E+6H?HeOA9l-FZoDRQ@afh_(%r2*SlF;==rr)^*?kub z*Yt2ADD<6N>Yq!}gu$U9SvfS{^l_j71WfFJc;Fc};mm&UEt-a5GOPSXnThZuV?L>5 zrmD@>=|9g-995BRdGPR1YQl%zL#5O8T+c2NM|eex_ouT-PlQj{kp zHTA8wb_zIeWJ+`9t=7kmmdGNL-=JJ#x_}Lx9R9y$t0H>&!oIZ^iX;9YgkN-WdTMZ@|&lwI6 zXi*OI3#!3@Ydakg)<63cnr9Dq0saCVEy+}1B#`W~u6jbH-yjjav<{dI6{Sw-92!Cc z=?wo~cYbazzn=Y_^lt%FdX*`Sd@m^KwE*hKTV?_kX8S_C?0`267(V&(<7I66sO4ww zfGK|dj3KL_Ksd>Ywt;a=1g{?bA5jB{0yq@TSjR(m0rFE37gny8EFAetoL7DlRAEeMiV-0GxiFYT*3=(YzuL*8CMTe1;(1re>Ta z!;%C-jX?@?F!92ZLUq@}$lAInim_TpvU&68UFMM>~~T9P}3^g%bhqFi6!J<+?i7$AJ^yL8&tauuZ)aB_0O0*HAfR3`5%2?Ayx|>5gQe9-#5wMQ1VepUOU*MtSo5h_k5t&Z>5so8XtlYQ7oIcL zNXso32g9&i+OVb`(8B>cQ{2RLE)?; zwlGDyVqVrG0sTt|-9p5U7AApsy5g=?eok+%@U}{QaH|RG6$&!q$3;EaLKsSHrD~-& zeVTpxYSr^*v_Cs?gL>J>uN+s}VC2*rkrIToJSJFFU)sE|&jSyBj!p#G_Z%rSJSk8< z5xmesBi=N>_7GA0b)n3I<_lvftceF2Z25vWlM=uk^P5nRx2<_e=I7__7oBI)0sGi* zux?K+k!KU2I~8(rb_d>QT>J8NLuzBM4@E!tZexHRz%8&$?#d*dhF<^DiN7XS|PCbYwxJbBm}D zqLd$V)1Mgfo11k(oe2v(MN3=z<=vYAKr5>nUl^C)a-hIS)L(Ka7ixLK{X9gEN$gD0 zdT7{E>6=-!t(`HcPD<=FdwzPW$0U3RQP#iA$)N*1y~xN&19S7d-2x}n>_o4>19JU- zMAB%!V*{;fQ&d<;ZHJdh&iax(^i|G;vuHP2en0qs590qp-VhUPFWRn8M7{XZYaQ%* zKb!%>^1h?_p=OAZwd4Nma93WJ_tU3S7bXb8(m4kFF9hDt???FQw1+3OXs-3-Z0QQT zX=9sy8FgxkwA_qZ^ivF&RTeMU!Y3F71tyL!*zj!+T{Pi&-r6j+mc5|Hwg?!<&B4cn z);3a5cP7mvF9LKz^@gJ%Y*9TmW(z+1tM}J#pu1}U5h=P+9Zr&=*wZJ%BEMNVhQ*o$ z3iVsqFUe0+l4;NAT~|8eD98pKCrc)eYtzEBI8?aq)l{sGcL6PPZPr>-(hwnWv1xnPLAMFb4;_W?XI?KZM)H+j z9ZP*S4&M~?pgiQzDv*pv{ zI}8eftP~X+8=H(qR82qyH;+z$`e~^8)t}7T|2qqS#cg@L%tp%qwAo#t(uOZ3IWQ&o z!BSqu)!hF+gy0`*Bb)xej2Pc- z`pX7?UFfyvQ1KjXDpr)Q^YR>xyb>YYRgficz6Eq7Sic#2EVUW=-VMu2{C-p+u%;@< zy7oONvrIhjD9==1n=qRQ_lO-0yEzNnf}SI2HT)4QNhJTsQFT>^icB3G91IvI2hfN5 zvlF5S;D}g+%nbetPl%1u2mYOsDDGshk_bz*D2Nmb5GkAj;(G$`oiW({xbOareBs_E zWVAdUlEWolJSXy;>v!Yp2wf722)OnQe*u;Dv??zRt+5v+B+T@8D(q*4Sw}iVWcy^0 z9BG$d!DLaIEe)y_r%KmVwY7w=@7}PkFsW^8Ncl48s7tvqG^z(DLcVx#qKLn#me)Dg z2scm=CYKG0a-7*xzO=IwX&v*@ww6MMfK6*R=)Mf=)P5u0V{~a8KkitjDHB}}CL|yg z>Kc=4#;kz^6s{aLkG8dqX0Vbh-o-HVOJW7_`v^8250O(u++RT7pcq5D7=@V|sj6fq zSM9O5xWtyc5gV)F;-Z~+sK^!>-fWCQj-2b$%Ss~!Qlt{8c^|J2e4X9aEG-o?TPT;@ zICpBw{I6@VIloK?cJAiuv1s@*pi@+;=}9kiqb>%h5bIcSRH=s7xhpEliqNBP21ZBZ zTMoGtRV6DO@E~ZS`X?TP6u*NnvW=1x`c`o>{Bp zV0`WJQ~q~;2Uwt(0R4%lUJa5!uALK6xwuL>eJ(J|%Q`ct3V$#Soe7qPbDs)&d~ z1s1;zAgs;LS424#6cwv4hl#&heH`Cy_spU+*j@K4sfrGYQE+eeriw=y+xVPN@?zoU zY+aN&H7WxX7$290mPb0)3va^^>nb99T*-TPAJ65t;gq&vm9~2WG_Q9(lpg#3=HI@* z9^cOszDAf9c4OJ4@MeKt@$jt=m)6Bz{n((ub1n_WqTn{(pFvQ19Ie}1ACx@!6zhma zHG8Z9nlpg%2l4BKM!73 zg&Nr3-B_qMwDHvlP)^hy60|g|)7LKF?PC2z&CFa^f2w)E{>!p&+xN${Gp?{)Mo$KrBOT{iU9QVs6(@@&M8uouB` zOVmo;U|<)F=N+&D)5;?7^8MUw>rQeuVP?~ zQ@4*sEpzOvvp_+64BFZE#HFhBAOnRV+gf8jG>fF`ztbv)Y0t|zp3`VcAwf_z;bTbY z)>8Y6MrF{U`J(BHSoesx$3vAP;5d|}-g+Q{u8%A~spLNaZ4Dn7zoSFyi3z2y0U%jEkgoC8L zB7En=S^=N7R{c(x??;r_^4z!Y0(9S99eDO%@_1jo zxtm5*tgZPx6~upr*#wbDjEnZNKxguCMvS}^hHHA(_8VSj>9x@9Q;?PF z{V*R1k^z1{a)&T385ao>#A>G&jQ{w4pj!8=CPhe;VaF5G&~PX=Q++jA#YcgipTsYV zhZr^I&r{D{@z6yx9epNJTh{<3TAD_^AK_#Yn3#{|V}v=!rJPIrGsU+2S>Rh6rv^_( z-H9?L^_iyMV-j7t>nPI5m2~?^#8o+pT8Ja1wNU-%v1b|EH=?0!2=mpO3>c#6~KzxqxH=IA=-RfkK2@An}|Ek1l z^7~+vumJrxNjQp{On_dfbXb7FfL)=VUdzY6YB~H0nC7ZCn*5S3t!+_*J!T)$3MY)y zbIA~+A8^d>2vvGbQmF3MdV1Hw+Vj(?{+__-*Vxz-Ar!o&$Mdges;mewXCi*7+rS7^ zV2L1{j;=|ezyPx@#D*uQuu>xs6X`X8W1mDFx#GMqBL5kNU*t89e2>~v#n{ZVk($SB zvy*`Evw@0{Ve{7xRNs%heX{o;ognhNCjE_0N7in0XxnlXsxHNj=zW;RY2YWTIu`{d zC!2b>*1w;*bG%psKLrK*8lQ6njzB@ljw;~&DiB4=&?Y=6vKzxIeZEWGf-!JmKX}ph zLpFgD0Z_NwfRv00Dkj{7mY_g)kp}~X108Mji}4ansa~r-yAxK7dvE^QProKN3bY`cnnZN_V+RnTz)E-bdjC zFKaZoYRdP+vq6gVmu3g59$-eOrcyUq3Z$AplShPx3Oz;p0~ucMLDAhRKhD=hfvsZd za#(BxKHi7DBZ_v)^j_n9z0Q<}$c|3K1mCKceD9N;Zd?wNiRB+w2oYRove<9G)(Xn* z&6Sn43ACy_YF3=J$|GYcJZg%4#XLknCxBAaq@zjyntPGeP_W~))5Ss=O*57=@5*I=9@tv9{^XXFrxw(84z^a8y8|q)iB#?jD4;Ct(eI z>d_e23awP*AgH8BvmRuxK=fOy?)S2$FsG-lW2#ATYwW`J9|yXIa?_VFqjCdlYuWt9 z7a5Ek+}vFRipt+B8wuqj86W%~>G~+ZN&xODn&^CF)J6$)iDq>X#Gr@U_fYK`+Qa|bA zCF^3>ekG!@TfPv?tG_ir7E?}sD*{KH5>)+Gx`D!=WWB~+m$uu81I(Cq8I^zU4P%0z zs<;rNpJyHJAD;)E*Q1pHOh(WZ;W+4&vg9QA`U_g3Cg2w5eDe(G#qEuidgZAk^(Z3s zgM(0noM)aShAYu;f5z%2C3lKsIIaS9M!H638T7rRVE#!z%s=@x@oG^BCu+2%QYyaM z+d5P^?Hf6o*q5|1*!T{lL9rF!hf`liPNic^+7#*PsC_Mp8AO9whm#}{_Trju5&C@9 zCi!N)Yx0i+Zu_Lb#)Eb7g`%tuRCCBXQhIjaBTzlZ#>bUo1)AD z=F0Tv+sM+gtxd5R&te3pL?&uPPEAey)Vex37^zEOXV;G?(^O*VfONK@pbQ}xlxrI7 z)PO0MOkjBFY{R$44*^p6KvVcPoFh4m#R!uPlg^Ix#`F4{9%Q0EmqMm_eQ;(i_XPnb zLZXQk6EFFW4Ne+%?XYv4NL${5p$1)`0|O!t1{UJQ=SSnBDCr%uDARS!>-1e&ezK+Q zD%C0UreROK$SEfj@ysKv+)_8xZ9)TX!J3AT0k1L@1U`WQLw{>w_+5w^_T)CBcJP74 z#e;30+@IdZ!l|Ip%9<|?WSJGP+>2WcRLh)p7uQ&nt7+M!ze|tTyi6AlvA;esEh;Tt zuUW8V+N~KU7*b}?FrcwPXG#1bs!rKOsm?o|IO7j`i zGOl;+&--86b*F-d-QQ|+RvN!vBa#LCb%9|Z(?v)A^@=We#5Drk>A#%fJq>O7(##Q| zjQ`Cv(z6Pg2OGDA?%;CeM+@TasM)ODBX`3oWoqk*`3cmH_F1KMkh*?;z}HpI&J!?jUg(+4V zM{GpQAgr&ln9%bF70sJ$yY%BQeYPtdRo$ly(21ka;-WLZ9Nfc&&Ae|XLpI??r#xDp zNStV|v9;2yAFTy^@eyo$x3OQ=z;g`zHS;~r}p})3Xf5~$i3UGk$J8?yK;Musb;23ekO$&>d%zgy@7D{o1kDvRT(AYFOAST{^iJ^0_ z+i?(Z&mJil=dfsry_Nq)Y*yWTw1%wSyLO|=R>QT&G%o1_sz6RlIr7Z8Zpe%`M=+ne zZ;B^me#rOgkBynEB#Kq>5Mh(o!5`OE*HllM$1wR;#nF3w97zJ4-FE?fo~v0CMsOHp z?^=g@jM?a(Cs2E1Z2n5vfBCECk9G8;ND^6d?V?|G_Yg{f&Sg5n+Jz~{vFVzi{HB9V#=`4pJ2AsZACP7RfA zKRO=c@S}V^@}4b)nX02qBgOS+o#8;N5dyOLL(&;wAbG-nKNYSeaMQ&hN8hg;+oZlN zq?D~*u&L<~CTZK5$UUWyO?JHc(|M%Z1g0nRB;=c&Py{bMi3A&6J6(@6z*`9Tn$F$` ze-k_NP`~@za`^u2;x@a#eq>K#dL5^yAzNs}k*-NOF!e_}V!sm%ty(;gBWh8crya}E zK#xq3uQxh`9nzB6_TuzX8+34XH}9Ha25wMGjaC;MvAq;91zN5VA_)oDZ*%2I?{40E zZgG)mq69f?HVa-w_qbQRUhP)<@ItZl?ZgP2W?eI4R4H#emR5)5TR7rhYzDnM>^YCQ zBsoc9+gFk&(GM~jNmxT%B8)W+%HwI$Ea@}q8z>wq6@kTb{zKLyA-}!$m!`tZ2Gxq* zOo&U?L-3_Am_Jo&gf#m6Z2P9y24$zJsd?}B0zQr|0K0r@W0R?d>8s}sN=B{w*xl(6 z>r0ETpL%k{olIYT@TIrWPsBlV^w$wr&gu;d6Ym@v{7_i}BO-ZQg+;Tb)`t*&{>5TM z`B;?emz|EV@{;X`g6HYFTJOZziAZM%@wt-`*Yl&ZYjt%eVIaFqWRuR$&Z~Rcb{x+q z*}*FZf@xCIEPNDZRxgyoez@%-^|}AS{&=aONT}11J)#@E zwCshk>zOyUDJGwze2xVDuRo8+?L- zji+}{PUpjp#B|#P(1_R1Dv zY{H%o3-9lRo!GV-xr6K1eEx}Q#I53{teJ!;?pyfY?CfdTWLELK{|#6d1VHrg)`^gda4RZJ2fSadkcXu;2V(SBzfu zXTD^Xcj7_E#X8OYOV3loralzOj4!9UO`)Aq50T~4U%Ox{Vbl%>r3P>gCp5xpRvowP zxYlE%d=-dMSoiJV8vK%C(I^uyYjY5tN&Hf;PO3x{=#Jt96)>{h^iW^EUHr|dMIrY& zsO<3%mnOXZVJ*fAN$PBfTO7zskU78Ld@qX}2 zLL4S~buXqBlSup%$Bn7k>pFipwK1}wLj&@m7Cjd+>c}?Gdta1G-JQ?JJCdtE^`(Pa z4(ffIwVCM_*>uVm3hSW;B2?KAc7C-qOsr88uQ)8Ff_={Sz4B|!?%mik*EqHNm|jl< zvBH_{O1YL0DIv0(afZg6>bW2(9&C4spPQufnz~j#ehRDHyh*v{%E*MW==?{36JQ>M zF;j)@N5|WPYb0^W0W2i=FFufsLo+#)ApdRQ+2{{Hz3BE&Ht%iBrEK|flGBuGP85Rq zH?-#`g0qA7YH@{gHt&nyQ)JqIq8#xXABp>p|CVb_Qqb&SDXQl1XNau@S?O8Vs35dc zCyCtZM^v5XVfAS7i!^P$-p><;MYGyv#!dvNhqZ=VmxB2p4s} zV`SE;P4xN2xEVi`f_pvZJ@qI{D8%j{HHCPfcQt+-jeznq6P*xBNG8U_qH-Lti9KBDS<}3N@9(uhtyvpDiEKgoSv69yCSc-Jov|SGQ#%O@e<{18FTIZu~7JO zzwlRcn>>p1+!qepzer#pH@SMj-kEF4TAy~RW=}9E1}@w-g3s8iipa|~|Ey%|WZ4Xf zJUkzLP1Flo<$J&An2YTmbiywU<9~i=T+I-Pb=mn~>9kBZ03@?7@uPIZC`=hA0_Wol zzfWGJu3`~MsH(EiJja8oNB3 zk@Iti6s(xVg8fUecICgzQ@XRhc-HFHun9j{i|MpHnx?203~*kqC7Sq5uxb*rbpnB* zhnfKVE%RWKQ|r*8d&y_+N(+slH!$xty4{4d_SM3A1^40f;UpRLQAA1r2%|Q9+wz}JATg?8w>=k)SHCq?St&ag+{a>#zgIp z(EE9dujJCURZ~}2STUj0OJ2BVm287c@&)r3bVC|~^cYCF<>9V6cD>35r@Rfb#AuW< zJ;p3=OpUWmQ`WxAaoCJavA!k*1Kh7VGNgNoEoa9jH-u(HKM`t9akPAzG@%=G(QT-H{_JT3 z?QhmiR%q9H2MOaw+&tFI>tVTThA6qv*ip`H!@9Yc>OvZ;|yLg;9Yt4vM z+_2-Jba*QeT}5~H+q2sfmBG1nVlFaOz!B%5%2<^l*MEN+xnD;56VPs9LaU*f?decBbC!JPgf&C z*;(vi#__T+%6+y*ta%0G{1uknPPhArO}@0`;)$eUR%z$%ie37_8frelUSN8C8c!%( zqclQPy?=*T0n*1}CHEhOD~#43gR77yRvYz1*Kwb*CKiBhOUU1w8weh+Y27r^s!_Io zS!DVPl0CS7!G{h1t}9=tpPAt6^`$B=Y?zfhWDz#5mr%$V{eBzPy<6Fev`{vz_Rfv6 z$Gcy!k02)P1-!H>xfSCP;>NeMSt`^%zhkS7z@>vkMMV*jl7e}%5qDb$xWi}@f9m=) z%bRNogC|9LGx;^^G|M&Ihjf+|$6lK^zYOeBy7q_Xz&wyngA;?*-zxjh3$0Dz{S-5_ zY@Tug$TzFsFUMwP5L=g{&AGMi0%n85Yh^xGRJk|^OMY1^Bg`0h)om&H1*FsPn+sET z-*Z|K{g5kp#OeK7+|Q0^yBkk5#``2|I(PW@~@U1o|o^3 zoV6)6Ad0OIwh*6yYmYBeZ0H~U@F*?jJ_BK6RT0j2vX*GuYU{y=Q;ad$db5vHTI9Zg zg0|Tq=4UN)BKfL9ktHt`$p%61h1m)bw=H}|%3=DVI1AK+g1{2cEASetc7shllAj*s z)ECEEd`6t^Eh#lhm&-L9;ji69C$+C5O4;Z%hr7)x+fC~c2+PA|Bz1Q=87%0(?(@H# z>)>>tuQTq&0Mq{~L*KZbEw?C+Ye&ncE=*r%8D?=;HB~nAt=ARrnavzYBH^Vabsfh>WMZe%=OyuPaCXwAZ+6PmtS`?H4C!=XRLUhwVS`G|fd~wW=4()0 z8+r6nAHqSlskaO~4_dRyD%>XyGgs%>R(6|5jCzGzQLRFRf}9r`$M`+@Ai(&L-KLS1 z-O-V>#s+A{jyP^;?QB`EfbWlXeFM`Fs0eIN;kWemDRDA$eq0#l{=_c)x2O;UPMqIF zpOqUd#i}i4HTC~yj{lg+BbZF}faQAZjX0W_>102K*)|d_5)ckJU#z8Cdg&`LGBG-m z+PQn)im>Pi-_Q-g(tq1jNfE3;A@tBfs)AyA+jRTI_;TlfymVqcb1{`I z`?c_Kmze|Y5AF?|UpwTM?}}%HMt$c#R?oOIzJ9Q_`339X!4-psAGDBr?_*@O80Xlo z*TUGYQ~S&}#h_y_)bO!qD=5$(a&&h(GDu#VpjcL24c_t1ESmDjrb553A%Xpa%CdP; z5g(j5H?6cMlqlwAP9B-LNE+hpN?JZ^mPUW?Q?p?9N|J?f>7PE>1;&BEe80p1cw;y$ z-&w!Mio|721C#t$ooCg$ji$vy$a4L?o@Z71vqzWPW(ez=id^xPe(iDuyc3ayfUm2b zRre)q%KuLoNO1vBp9K! z^^s-hZeqHiZIT|q`OqrSL|F81Ua?Y6_k)fSAE@DvZ#)Icn`-zu+m-eSBAhafd+ceFZIQT9455 zIlC-xX!5V#A#~W#wOjcxi`uEj=WlPkY=h3;wa?D1Wib0!elcm4*tI8FeI#n5ne`3g za~LPx8|mrZuf_Q9>wp4+5H!#+xw(!DP0%u0D`Q{ibqvq{f?GhqG`FPtZron2K|f

}N4cvX_^_v*ur0 zHlRRhp!%_nUNKEKna!Xo6r>9xkS^k%ppDT?zeierY2R+}H=)&h74D(-9k$TH6&$w_ ze(UTf7F*4F-)NQxw8!!No;dW7qw79QtogBEk3{{BXe|V6yP^PF9*iGCez!xZy^j~( z_^D-&gm-p_8pj#=n6=FPdos0EpWTef&SZ9AOa@hUOW_$LK^yC_-5XMx&02^$`EY3d z*SoDjKSWU8;A#Z7?0`+qO#_2(DYKJ}T&|5P@vaHas`-XVxW{AZ%D8E6$q&pc921a4 z#x48Vn!;!tk^~u^4d$g1OJ=0whh5Z)5_)}6_=Ep0s`-i6JLncZpIy~Zx;{%dGY z+Ftp{54X*lQ$V2q$boe~d`W$={$hggXno_+L_7LTd%6y4MG42XU5sHV2~$$VA>7x$ zCte{WSl@Kt<~EZjHCg2kZeDQV)pCBQ;vQ6`kQQDlfjf{4d~KCK5_E2>20EJ_9Fn;juRkIzRlX#3J)h*pK!nV~XxE}AnSC(1#P$4Wh6fq{xnP-hwh;dB#fr_P9`T4Q zn}Hx4#00UU89P1kJZ(&Us_SNgyU%5=R9N4Cz<7W4Uf4OOC0+D^(_>{ffe$a$)A>)# z+~v(yJbrpt^C^bG3)1i2GtY@jI+SVd+H)*C1R+P@|1Iu`WbAxzOj3sOdhgom^|%X( z(O-n^r0L_O>UemAc5W~tcSy^MgO7b&A30m__&=-Uc+FPgbS=By z;Rp$&Hg`xM5p^48ayu2_h2W0<^*aqh?^ciRM0T2WGT(vxyjK@1cLwuR2&_$v9*Zlt z&Tc2|@ZQJfj?IZyaoG-*XvCcp$a~FD^ZjYcJ-O$^OWvcJkMqbye0h2(;!5cnoq_7uor@A6;mn>xmh^!v1!HXq7zNSVPY;Fgz zdplp44+*3N$TT| zMShlJ#lXI0Ki;|c8g9CptQ5F2dK&wdlhZYyZXU!l&HeanIR6-Baj@9mX2xWsvU`jl z`M3^&sRYiyT>7vv6bixI)m564ZSaf%p0Q-OsAPrUuf;mzy)Woh#*bdN`I>+=53+VT3x z5*qycif-WmM*9H+IH;p&EaZG@{dZ! zQ2y;QZ1(g}aq+-uG`)T(_4$CF7Jq=;ot|;uRkciuGT#3ZdiUDt%s9)`o^AqAoV>X4(cv>*U)LNS7m@Fgv`Ra z)V4l3Y7cDz`RUK;Q=7AgiQ?Pk3KY$Q@w^q1CX;D<4@9LZ7BVLHdg0I)EwXg0Z=WYp z&MgcXiByBtj8q6AG!%!2LSQI203}!DuE55cu-FS}%9(l%+L8HToRQs%2$OVc7yJ1}3 z_3Y8%#=*=0ZtqPxoPRlyasN8~=9-EL?y}ixxGKKSUAuv2{xOkpz3Zd8)cK29qxjgB zP#D+s^}&Azxb2;HqJ1_DH_Z4d^l-0Sk4y0ubnZ=7H-6vt0sQi%$KY&U!?&TspF8is z>kYj)5c?ti_MX4PU-%!z?-^Qf`+a|oH&(jPX0qe)-wI%DC4qgB4&3>l--YGH^mR&y zCdm2b=@$yxL#^&`H+Id2kq`}9(TxX@7&JpCgoE~a=*NRFN7ev)JrJ2oUEXOo;D8$d zt{^^W#wGji)a?O4H*zL)16LhW@_m z5k9_IJuI|O1Aw?rez)jy0Jz-Uf%u>q?XzJR{$zWZfe;!3z~a7s7|teVLRjy(AF=i9 zmFwA_Z#9NxTMa~8TU#+dpL=N8R!IZVQY+=a6CpT^M~pBJ#&OBJhTym!&QGsl?CbRz z_p{ae%oQ*?Ogp!9&T7DRX(~I5g+pH`NvL8x#gLIm6K-Z&(AZC zZ9Egns9F?0R{NCX8?K(m!`{Ef^QO1q?XfrT(60C3sg^@{*>nx8tC#T)?RVmp9eeT5 zZSTOnk>@aD=)mWCej9P<@#uvI%C@fk`{JpOS6g$xdD+nnTysUIvJ8A-vaM#!@`_=6=-)7&f-w+qs@x>&{oRR8*}egCom9 z9ejtHQX$s5F1ap!9nif`K5)Az3CFI?0=5AiE?-PQUxIfjMiUUekVt(jsH;!^T+nF; ze6J@z4o_#^u2>FdamUAH-kaZej}A)Brn^w zTmBdT*wqen?g1Ptz@C8>7|(AWw__*p`)$98-;F#0_u3hJ;mV`9L3aV4vi&xGBl=_f zx1LYn6Vd1J`Oe?MS3O_HI)Fq1XjxjopZI@-la||IYOOX8^UBmDS9blkN&)yBM|{vwt)!bQx6li`L}^1Dp( zxm*CU?{EYBZ?53%sg1oKN0NK0#RtvMKVF{SjW(MN(F^I9T_^j)WDLyle12xB31{Tse5{Z|mUu&U2WWlG%$^ zL_8TgV=u~wGlRfO0PsM1J-lPE0hhd)|8``29lW!^sab?`uBdRr`RjL?QXiYVYlv+G zklBK;Tmf0<7DMK>j#%opU6OD$pO9xQ<9@pw^@z>KQD~Ht3QrrN=yDifh!l3aQiX-3 zs1Oxb67~cDEJeCNg%oJVrU|H8^_^#ocaa;tl^RuIN&xRZePRL*SEFIG-_y* zjz*(sX=$nW{W4^vir~-}0vKcvsgdvEMOHJ`2)Q=p<^9QKvW7GBXgm|a^8Pj?8Um>E zWCn!uPrr^mk;a0Czf^005qAdK>=5^H%_Xxw>Zjy6t!IAHn|z0I+V- z;cs_+2u}pRgdaEdqd^odnc{J*??{F<{oTNwcO);D26@u(E}KDbH7z~pNQ2s<0Cz6lso_bHq+_xT*nz{(rqJq?rV zvJC*wpD1`KxO}m6dpLS7C*Zk|d3k&-c^}ggo0r{qj}GB!^;L&XPbBb>Kht6S$z~{rsQKjx7UdyS2urVURt){xc7em0Os_KI2gNt6##!1 z`v)xR>Y>{i$A4}66+ATkxA>dgAHnGc2QJsO;6tHP`1o~yg5L}OJ03Q;@Z;V=eDCTb zs9V#a&X7n|Gu9c>*RrBZzAasgt^zwY-lASzL$Gxhf=i33urK`hMPTD&(;d69erh%u zZWTcsdVJustvLJQ63(7lPWu?hzvp7czJ!vHFyHY~(iY;g<6#)vVpxfoFg-n;3X6o0 zN;qCTfW~ykHHba^aMt_K8Jo~BG65la7H%sZZX=M}f3ofOUPR_Ca$=4<;b$6s9)^1Lgreqak&+Z<4k3j~Js$9J2!!0)-R(cs#Wods~ zs$IAem3-O4L%ID8rR$M?-f$*@xU~<4EbGoT{H5_s1oQVe(E6w+_5W)0k27Dx*E`;a z=b8@SJKn!Rb9@QQ8#&<>{SN$}v;U3{_xvH&p~u_jHea_cLl11crk^|y{P2QsP3iVi zdaJof_VOe9by$g|4q@bkL6nvG1cz&^I)s!oPio8vp~o8;1I zuZPzQ1l;>k|6KZe>TF@CcrQxfV_kjn->k%*R+w)6Ys9|u2gze5E}`ztCFtsmh%a8k zu0MJWcwYjSztWH9|Md5We)qGf^VVAju{Jx2_CGy`OOG8!-J45j|C6%_4G-YjkN+AL zes&yyI@*l0wc3jVtzxSSD=k~lST4n$TO1Nz@~-8a*qrO!*{&0}HH(8p;rMvOxN-kL zJdz$v<_a$35hFV7$@7~B6G+S(0TlLcNU0RMC!_eesfGbStYoCJvsf$`JDqDQdD05* z#Ym(+zKa*(yXa%3agoF!Teblxxojsm%y!v!n3 z?jw0+HrcwXq-=wF#-B`J{K;fsr`B*$Fg*c8!wKx#4e0Ajx8Cqv7#$tA0s!I-b!k)7 zb7@;&#GMPL@dvwq9iP1X6TH;ahkt85g1@}QrXAG$~b;&<6l_xRaVm}uHL2;gy?J+%y*%?6=R zaNjMBX;p*g%`Ir&XF&6`4RxpdXncnSj`aoT>*9#7Z&o+OX4;d_%ihzekAY-ZDD3U% zop}|r%kwbz*`Obp&O6;$Ok8n@Z)8>><{|_N`iW3l8?z7~3RAI#a|+jqj{}mGjN$9` z*me6?5c{j6n`;~BL__p#*!ipfhVU27SbFgv(RlbbW!KVh<0r88{Xao;_%qPI9z+7b z>eP>*AD_j-uly}8J^WB%Pl$q~gI~%?u9~t?a#eoYS#MigTiNzx+}sOu1;KIsMlhHh z_*6`5v$P^H+2*{0*B;jch~tu1I9@n!@xi6|x=UW*wZ{QqIThX&Q*pV~O3ijl{@>%J z2oo0;7SP<>jA%5vt@HfE2dZY{m2TfM1gyiAWhtH(2T5_{q}A&CQ+ z1QG&C*uvv+xi@gRz~h{I;azwKIJsON7alj5oj}OO<|N<%i9;aC#BuD&*dEVJ>{&cB zy{mVr)!o{w-XEosN~J2Pq*iY;^*N`Hq^e*2s#LA@qwit`^*(NEY1+EnwMsTTkc0GC|klM}yNUKf-$_{+(U z0Px8A?#jN=c9K@RHt$xnouzkLFj`^qLgO*J0rgyN#W~H4g%PvG8o{WSj_U1BDTCy7 z@X>`oU;`KT7q4@C{M-Ce?8o`(#i#gY@eb}=y~=Vp!n+s0hEH;E-8(>9^zc`axA8y6 z|HSlI+-@Z*Np?FBaz*aWchS+=0i6&Wjv+nq4!X}M-zgXGeu(={{G#bxssJ2{124nG z#B%^#eqjRdT((NWsbjTKk=pBp{f9W1zlIkW1>{^79t5mAMx-MVghVAORG3&rjs+>` z(v;P)`eguehl``Hb8_i-$B|=7;|TSBh%e8>TNQSTt7KR_~ajw_|wM_ zU!EuQ;TuS)IRuBB^jCie!PPhD!Hg-aiYLIqkiT~q5oQ82-TgN)f$P7Qk#wHFB)}+ZuU6q zEpH{_ve|Wu**u+hE7#5BWV6CkyIx(_HQ=P+cHvEJZSFy!1>8bT+u`jaz$A#9yJz|S2BtKJm6g|Z?f1a(EHXi{>F8qg%&#%`GhZj)y`Rym zpJC=#rtx2Un(m$mQ-VOJFM#Ve5=erBJAd&dlHt1uC9d(v)Bn-ZacQIdtacP{c3zuW z)Fvvh`9>wGOk7HC03u>IM_(9R9db=)==qmL%iWvx4PUekTsF%+r@btU7l@2Hx4q8c zebEtCO4rTgpSBjG5muyTm#4tOY@W5X>ak|>vYxm!+YYLm6m5%Sj6@>L+fj_SCDEu| zkI}{!7dAF~f!nzOjGFGOk3`gVRaRwTb}VEl68CbQLM`!lT={{}e(%1mSg=2*Z#n(Z z{)S^3Nq#GH7%>}>iR!kUjmQiv2%PZkXW=^s@qN}wq{FMMER_e%J7ru>O?PVJvZ2Vx zAj9W9_c0>|amo_^CG!j)*?5Ys4v{y9-p9Ws{}@kc{0DRA=@32O^&op8rA&gWRF-jV zZ4KNGymEoTFFp&v!g1x?WOGik;Q~M5T_)~ylJBg1olOATdk1)xW&3X4r1-!Xj?_zh z^}Yef6nN&+5_lX)cXxB;ssm1yn!l99-@m_D|g=U`D@A*j{_l* z;k7R*azX&E|G6Ru9i?qwD{Ui8tWx+;AFF>piAY6EzIxy;#Z-F%-Q@Y`?sUi?y)zw8_1 z$NcZ*7xq1lOD^!6Z+|cUHQd8*zV<)Jyyg2?ocSw$ee8$%i2vKX*CF!Bg+Jv9`Efop z^Em+C9sYm#*xX;ivDY^|CO!AfO|?xj+Ehp+5{!bZSJG(ZkVsWSH8%o(6e!riMjSa)~M$)fc^%z?bm-W_bkIRl^w6U?-QicWx z?S?NlHhX|uu>p)K4fO(1ds{0It)wuUiNsq$Fshg}f7x!%%}($_bi#0*$LB3ye_^(@ zbMNtbOWPao!*n~%zHcSw7Z!+Un!nttn29;`cs`c3p5zo3rJ@WZV!Vit zFFQ~1%)%eCnBU;Cdw_$vS$@9%{d{8Sqo#8@-K9>`f{UdGjsh?YEFAPB&ZW3>Uf}C4 zr6J4U9VY?kk4DiRy_7G)5l97P!jGTgk<#)8FiKY~iSzi16 zydpGXid?)pN0l&?V?mZ)aB$~)`jBEl9A}g{uf~E1$t-st067#wd^uZghEtE_P=_&r#(0lpd{1?jG{Y~(V ziePj*AlJCAryjY}jnKk&HS?6@u6q7%MOmp$Io^zL({HbeLOqSrnbq6vlz+DiRvw>v z(b%kDTw7Zs5D08rO~%EE!uCi;rCXhyu5ddt&~G<=x!oBY9I{iTZEW@cd#wSCRe`8o zu4S`n%=&%aDl}^TvYmK+UOxQlGdq14wPYJd3)yUrW<+4UvC*OuJ#)XazPzX>_>9D! z(YEI=oNsv!BQghSYrLv>uO!Ory??9OZ|SPhBh>7hSaLMU(o~qS@DSO+IzYJ&qnLoa z$#zD3Zu~c^#^-@|u6zT*7od>Ob7y{nJn*MePms1SpX?I(+{%lHsXX2*3HYLNUc6Tl z6r;+IVwd99KV$Ys`^g>%lb&56{564p)2xg38%yS%;RqB#eB@rjs{#WH0@<-JFGe?b z@XHzQIeu?x?#lL3-uUsB2+D+41!jNYG|@OrOipq$CbKX6K;=HGa&x%)$B&NT71pP^ zNNzyL)yL%IB#(dJ2IoJcje6{3`tWJw*w^SDarwid~!Mjd9yq3ceWLq{rU$68cTXe2LN*=OX4L^dhZL`!a#U`%-|txmM~i%y+6 z+c~e*IptUodBa)v@urH!U`%G@v_x`TWOYIy7?aC$tB?QU>5=je5mp&FT_ia!5*n45 zJkwg#>Ec9zp3^<_lC&ckZMK$ZG)nyGosWjF**WZnFE%!Nhh`hVXuB#Wzh@NB=P#V+P)OP5rR1FHSXEkW7e?~Xs6kYt zV`}#?pA2*%W_FiA7xEJRa|`4L{pJ5ttM@x|Ak4Kv2d?C*naK+>D?ypJjUFPm(9hBT zQ(1R?puoNfffrmyIq{<(s-EmIjl7(kgfSTII!4!9-9-D8$74R1y^;6LeHp3KLs5n&Z~Qu!oJu$E{`?A_E+@Y>`&S&!+~j=l zE{??Cc}v1Ny5O&YXX;Eu1#sy z&YMZpz8K4~Akt_E$C*h>5-XFa$VGKtt-NhTgsF3ZBJGAh(8=nV)TX6i=Ld%2%w%~U z?fI>TUSw+@C#tm5&Z!=^o{q%==|yGRMvu385>VYv98Wg=xK-y|op6+ox0Ulcj~~ax zk}Vl+whpsj1Z{2~PMti(^vv{5ABK&MjYXzsW_Z`&kmd2(`h;q_uvR=8p)_D z-TdX&!>R}jcZE55@+3pCVV;jhdEl|P8IRop8EAEEv-GBA4u$&+=Sn_4O6aNavb1W4 zY%E6?mLd&JyUXkLvz?Mt&(hKoJ<&UMZ2wkp&1~SpxMrDEHX|st$I%K^k3aoWG4GvIRe*T@$>9+wa4@gAb+fjSI>XCZkm6zKg!I)EZrUl z>2+1`IS>(XclgSw-hN+6704jED=C`Kd5-dK=`}i>1qu`iXR>&mZaRccJ~sDfNNzVz z2Or?$-EZZ0XFf`sWzff6^~j0skyEdg$KU3NaoxslV5i*@^F#jaER$|D3VML zdl6rruMvyW_l4>TzP_UpnS{XVgn)RUlSh7HiLd>NtGr(A0N#wSS)UV#gp~W~@XB2I zmnrW2PzR|qsfP6qK@oqds8qz^IFTa~QY?fxp}d}W!!ntKP?C)1>B_}WxGeLMKsX$( z+RwrF6nORTmH+eVgit;odW4Bp9Hn!h3fx9AOchqDtco0!S^RveJVz@e36=Ld^~p8l zSO~!|cH0^wr;AK}atiGmn^n1{-iLDSR^2(#&Z9;hYWddPu<@1Z*A%03TKK6Gh%d$w zpPS*vu?G^lfV$uWW7|qEWlEv<-VA z?b61^rh?U!>C9NTrVgQ28X5^iZT&-axfWX>?hfqcFFS)(8E83ru)+5R{r^{Vi6Fw< z{2Xy{j=A}Y7}-h@xLZ)gppl5G7kyZjx~$o@9a3vM`PK7Z#t}bDcB6iW)f0oUx?@fZ zD76x^>B^Xg`}Xnm`J1|Nqg7+f=CP?}@&cBGYrW^@TzroEWP!Df4C$eMWS5ALmmm%G z{`+cY@waxKCsIgoLx_-ey7}jhL4I)kEZ;lypZVwYKSXpD7;@(L?fjFx8X4n&w20^` zAUF$1c?VM7Nj{fDmX$8zxqJ?Xrp(+({~#kHN@OImQrGhS59K-cdoDl`SCe0N(06o| zSWJm(ROO6T(%jcSj4)A={DnZGN$I-`;JIrUP6expNEU`v3>zDpCeWu$>pLz(b!wl!fr?QyqS0-eoxu@5i!^X+HTc` zzgV;EM0AvYn7>xFOnn(N8)*|ID`B`(3I}j!^1Lhkul#QCLEcq3%Qu`|4COZn=5l!D3_lS589tZ&eZDFl;1THx zqU6NmaU$eEL}ciV9sJO{P9qg6Y1H!l&+(RfPATc$B_<~(8U3zlruv4;l4x>Lsb$%B zRHpyl0w=D{koPGD(|z}Ka{1-*_Q4g2fg>Uu0a#{SSfTHSBnp#o*LPRsl61P0u8Haz znaT0eb4KY)#Qe)5PLjx8nTJ2L$WuS6)XE%=u5#fU61k(REI35cp^)LZ)e9+*aX((k zELodNa_=w66w*bqtDTHIROIHD9V}lFahsHHm198!&rCUnS8Xi7#n9Z=3m2m+&! z)*VAxK7~Ax%))4(dh(DPMgzz(<^HHrOucPH=ct5yCZ)NDusSXP=G$mlA%sZfwOJZf zwsVgL$t71U)!>wqUIfkSog9)`O$b%XrO^;8P0g~!D7zYUfu{2hA{wC``ehg`#6W5=;ME)mF;QF(d;A$M{ zMuFmEci=1*$R;57k8_YIkpH;{a6NI3RIZ40w~N`?91L_ab#;w=Z<_Qc*T|1%kLM!*w}0dLxY2W9m!~8vs*E%d-xg~ylZgCR2FKtX_OjmW3$t2 zS9D-A>A~^2xS8QYk#Rd8zksUpTc5^8?&z%n(Ama&FMI6e0r(yJ=(d}EErR8Pr zJk$*hoZoIk>OX}zXEzqy3A}Qik^B;WJMr6mBCPc7KD1tua6c0JSzH?eKfL%=0DfWL z&+|_=e}i|&evzMA{vvWwCJ`^P?w3ex6oDceWRYEp*t_x<3p^XV$m9hjJv_J2&+(wd z@~e~d_bac}lNTU7kY%`gKfaRzK&Jmllp8}5p=Fsw819|wC3G~w$s-R_C=`kN#^{R% zc<#w*1|N`cc%bWUB~tRfhr3w&`U=;tBMWMMN$Q0GV#B!yaA2> zxpJvZcdkJfiMIGMBv&_ZoKKNVDso7O$)rkxY2cK^>{+ptLaZF891{>GYK2q&myY22 z@HbE;QzhClWmtbujs+3VB+L6M(?pbH7s;wQ)%5M+88yDOf@$PwB7+?EA|#ZU-PLgc zPZ%~%kKlOfDnL!0MWeaI@nlUZy*5I$1Vh zC#W*NzJW}uDb(tHkYhnxGTLk%c4z6^8@sEtjm`FBl%i}Jl~X5ed3tP`J5&C;KN9Fg zV?8Npv$vQn)n(kSbm`p?8Mv2ZpiMRUI*59_R}y%~6XomL?QVC$s730pj&OD~(Y1M} z*bB$FTUkjah&M=$x57DJZ9UJF;3bY$9+-KH%)yBQ>+y=r)1sA?3DsBU_tr(7J4**{H#by6JZvN$>nrs zt0X+t{o+?AgtDldJu4E7$qbyTG#4?eN$LDVb;Pp17NODwxya-hM=2dyCOKZIpQsgg zRvPq3qal*xNu<*uMq?`^Cj>kpC0#dl##mC;lb70cp3wm5m*)wUq9pZ#&1@d^yy(x5 z91F5Kv09dO>Ul6a26-@myzW9qX{=)wJ*l4W)r7#l(HkUVB0T>Js|W};5{jJs(hX(a z@zwH2Ao1!lxvR?rPMlEY`Iz#=a{Z5QRL!rg8M)aSjoT8*7>Pufw^OBWOYF|lw>NgG zw9V~^R_e7=wlzvw)}oh(tsIBdF4Ou3F1BF2HHgRK+;{9a+MfxxQv`x718pi;k%&gu zRSq4!AE-^?)i!(q&uM3v5OO(8CG9ig~TY`z{ne_g{1bnDjQYSpG~n=uECfhbynow zA1tu)nn-9=V&-`Vp_oKRzhEdTRi?b7<;Xkc)@#;lBOzBO1fKsL7b6cB%N@McZqVX* zQb|z`d1{*MsHw}UBufIxaUiB#XIyE{qmC^fk44H&XC_veEJ?i-YNTaz^&+*=iNeGx ztK$NWiAh$ibT!k>qn%IR)mfEwX5F9x#BWX`^!8RY)@g*%e62Rp(Xv^&sAbC~)Ohp23K7h#+B5$TPv`L8S1*{np|Eb5%Ma}=W^eiqmHZG#<2*(10voT(b)$4Bmp4~aB4p9(W_1YWwK z2+GL|2JcUG9&_6F)V||6B4b5dH}0gTvq;~=IhayDSH0=6H`jj?{ zRxV=i9%tqm5hw8KS>;t)?cl7U7nJ}GCKdVE59zRnfl~o|$s)7QD`Pu{lnA!Y*9Q?M zlFU9Yl8;KrvC3Sk6m*n?qh9Rkm#eZQ@89(P zcN^Q1F1@f&zd*3ftw*%q?ks&fW2Z{n+)n805~^ZQ_B#5v^AgdfK1<6>^mM;&%jS2)&m#1_#V|UtQN-eAW3KCP(QvgT>iE$xGSo2bRFFR+?idCY~ z=GMlp$!KF^V`F2}fXrB!%)YSFJU|m+m>o0ji08eWAbnqNSrYEmNWa0sq1#$Awmn6- zNg1d`FZni;BAj{q`*`|`PuCrjN~Nmi+6pPQSs}KWIgREu+t%uRHxnkC-QMbPTG>`h z_COfVl|=bc>OY0-@>AIVow&~bf#rSJ67lvx?v)!4GQ%lvZhIZVV*AqiZg)QZit-xa z@hPdSFU(HV8*YlWD|yRv`095yZ-q*|w9ZCp zng4hPJ;h4;vD&CcdpkO@52%geRml(fnbLIVom!||&kuCqx^T5Jxa26u-tr_9UxA)@ z7jT7Wf3)2A!~xueyGl+zde8mk$VoMNb!AcMvOOU`i+oebK&z@b`Au-fwK46=_1Uu` zoLy6D0G?e#js+R)Z~VHx6>{esg@6BpySTChnjbhxZsC60lLQL{@%fP*! zA}mEuk$L-H7)mWwh)oPe>3+{6%+xlO1gr}&XrB~oWzJ>iMSoq6LE5nHA!bx=4r%RgLgQgN)c$r09()Z?06XXE||uG!kgDfyCUG@|&)Rr2Etv8q!RfdL!n2XO{J*j-AkP8z1(J1g{ioG`xW=G0nE89-EYCClgJ|HpkyhtHBULzr4YoZ}-wgy`=+H45}{dOed?TTHG@zy~a9&2ek z_c}fn($tyM7ZZ8NV8=GdR_n2N`1vv=P!TOT16^sO= znUpk=nC%pp`9Z(o?fgK8p)dsF$U-$;y4_e6iLoO}w547`YHx2PRrMwAY4Q`6d9VM^4_6Lguu%F^e6smtw?cnvnZ7_b&O#EgVDbe# z36!Lpk&xR?%;cY*dNMFJJi@X2j&b4J7Xe!a-cH2l;@o%aI4`}t(??>{h-T86J(rVh zk4&^8=XNsU?_RkNDcXLKvX?ka{r7{%0e~yf_%UMiyxr_`Sy&Xx$DmyX6>+E@o4P#Q--kT+8tw~<*vdyL z0?{n;&qLSgAGPc1MM7>Ts#yH?msSDg^M2LmKMP&Dt0E>R zdgwczLx_(c7bFfm7DdVzk?(z$gX=%0NXe)Y9XT;MiF|XA3F+C&_ESSOsoRs2lT~8T z7L4s<%Ozu9B*Iq~+Hd`Bb~n*zl=#!OWV}_WCokUorbqe9PkhX>;Lwvh`ADmWwP^;- z#L+e|xVAgnBn~!lPG-j?a9ycc{=!I+6RApvI#p&3+%R}EztQXwZXc&Je%8cEI5MjI zmDo#>Ud_tDp}|2;-G7SDJ@pS;eP}i|HYONJME!LY&+6?a-OCwmSW&aV|_vbXvNRlV3d-}6T1 zQJ=u!v}KKU$Hf`EUoW#CloaskhsKUK*+tLLE4hx_yKJIq1 zbM35ztcUtp)i`3ZlFHq4Bn_{Cb0J+`rq-E+G(8+Ie;<{PPw=MbTaXJ9^5hWmfFc~_ zlixu2?DqqToCL~|lM~;l{&C7kQno_zj^jvo+($9srI<=1jqIbCtFB|}xZb8(sXK%n z$+(TQDqVIHRwHu;2M0NJ{MZ&BP4n!9|3TZMpSH1NN+=lO&b#j9?eBPd>yxbSoNSwM z8rSoyOS{gms2+oHx8j{*#vNk3uObND%K>uTDRNz_xL1@N2%V@KA(AQnEu}(ATysGHa zZtIC_>$@s-@`@2~v4q?!Q@975C|`67_cVWe*=QI~Jb@II@Wd0SM{*5DaR{Twh|2Y2C-KKDmR7!kn=%EMX=q+a)pe zNX`e!U6@;qw)7CE@J4LA^?8c}O4(OWU6g16nhNrpzo&B79!U@CEOg^iulSX13efTXD1s~bh zy^mbCm+W$;mD7QE{l&(EfP%10zT29cu{vix5$bG31T`aS?mcvfx2@F{+uu%FmNvIe zJ=?ZnC1NMo86*%2&_B34h2CyY)iaAK+G(tuw^R3@;+xNYle6bqugRGH**|Z2+r5q= zuCm*pUaTgGs2|vTz@(;5B0%c(4g$|^Pe)0| z^kqDahc!+9!FS#g>FljCJu}VF;2_g8GmQt^+%m-H;(IDeSH*H?-4@e#o7snoULpc` z;)(KdPkgz0WkHEP^enBE_Se+zEa8bKsxEI;WbZ+)$$h++_m*XinfTL7KO^C%-)3{% zS+hhd_{u_0yDVp(o@pcp^%Bl(Ow_GJFrG-&mNC(D(d}rgs-%(KqCP?3R$<^C%12ymQE4zF1IK4=!rsgKs&%_;5r z_XfFFMnZ16T!WE#9A6Y*49=VbN*_%(Q`gc+1ZtP*Yd$tg$u^UpsvO-c6|uN^=Hhb{ zB59W5K8U-SX9ZZ{!26f^*N=7s*8q*!{Iaj=wsT=$c`ogbvR!YxOwZF}^hXbqeh%(A zF42GT0304JOUl9GRpg??aG^ktvxmh*CG+>DtEc8zr9$mv=%%X&qSl`4!QsOU4L5#$ zSN8ouOLNx4Sx*F+Nrkz2>rd|0)nrrSH-p)S;oT^0cDv}>4AK55>!~%Ke){R1J`|fh zi08@Q+VXvDR}`9BP+wnIe>?W8$Edrq`$GGR`xjTjxHM^e{(lD7E^i>v2yy7u+gdW( z+`d?iWZX(4A7k-7A% zir}*#{q!(Dv>%9&H>;=q98ko%Fx?? zlz~Nod8ZS{nvY_q=9vAD;#l)>5zRSBLZS0v1fP$7;DR#(z`p?m%%eojB0?+Uy@pYn zhvf&VZmWGk%*q2){a7IPBMH@MsC$Wa*R~WE1&Uq?DI!tqDOzgAGcj8$EbFCYPh6;N zPP3a?y5Qr$`Z_ky-pFdx@o}Nx~<$R_(it@{qtN91Nhc_QN1i(d) zkA2}zZo1Zh=1O-RDbxn?Nrl?Lj=@5b0V&IaQpJ@SMPve|u`aTiG^XGS;SNHyVx>hVUD;l*DG27pTXKuw% zBI@Vc3ldQ;=jQV8X!lWM?<`;}`zqVk&(q$TG+z_Rqsl;w(hus3zgDE5RpDnv2I?^v zH`?pwX}yh7b`z-{4u)i|-~2}N2dAM^3~{&X2(yI=*5o89_dwmpP%|`oyg}p2clyU< z(@}|3|NjC~o|I@VW?T7RH$wkdEp+N0+l3&7z$(r)AAOSk`QTuX3uvk%iVtT+T()9NBzol#_wb5<6Y@ncD(%jab$kK?rgU@a<7c+m61a-a(Z)R zF|^|Grsj5RSYTqRGOy4pFmeQ9Ln3mo#MHkFhS8Bb$(2uam%CwCr(rinJ66A)HnqFw zNV>d_nc;)XmdZQLIDG^!JI}E6WDGF zef!9a93{W3G~&pNLTj0|s zg|dJ9{$;##-4r_0IM?bwM?wF5&sD8El1+1j6@0Q1?Q~bZ5;o<_O0{Y7>zWA764zWx zVH`zVD%89-lma=+uLr)vrE#Yy@}crD{d3OhbJyx~wb^=_dkLe|a8QI}>^rJO<4s`r zUbvYm!aHkwJjNbU1f{T|Tu#1Jk(F9$xtX-^dMK&f?MuVf3QLu$+Xo;LDg7j}dWzok zzp%D(tvs&GbN^T~?`u!`fN?zhGp-|PJQx1i(lL2Q_u=t$Q`o3q?{o<$4mFmRsth#} zp#@g&1ve7WI+f}} z{aO`&>Cry?m%rBhLF_?R9=eCn&2_w!i{*wJuEcuVx(KVnaljd4wxCG3%?rn^MSI^X z=fdFe<=8-Q#!!ET8>E*tDM?C7R^3O*Yuts_tSO4;ropo2??yu$h5K+W-M}dum&TC1 z2l1C)2i*xcAh}4n1^~F|GVTn0Az=PGXZ3k)^g34W$BHA_G(K4(Er=Y+Rkrm>i#6i1 zy6&fvPOfeXr;K0QI^I~fQ~?;j{uDFI$k{YSPo*)C(QD35{=l$R#D*35rwYQaKW836 zH!)joJ*He7RK%qAQjv{Pm3%C3KUMwt&1&cHQLo6vw9LdT(5uMCsej+RwA4mM0#(;l z78VrojRz7}y)0d?tk*_B8r@b=BP6XxUW!wf5gSNGb)02%B2>kej5cj&AR6Vx^LxAP zx=r&a>6FtueHdHLrc##wmn{!%wvWw7Grhcn!A^SRZ)ntc#!-)5CLBj@Irnc_!pGRc4Jzzt;Gf&jcUTRL-;{O0KC7m zi!b-Vd^&Hq-YWH^pK`tVh`+7=GM*k)>dW~r@1ZaKo%L7eL!C^$@2zy7dzs)XO0-Na z90Cy%M-Gu5?q|*Q8W#p5+71G(c=Z}H-|-#DqDbKS zYb+l-#=a*%Q*{h-K}KFPe{GL4Qofw^mV~2s0@gNh|IOIMoUXO?s`Kh9tk<09yuX7D z*}=NA6gF3KDCtli!DKf<_LGydtVu~`ixY;zcB{H5H;dWx%As2>x{ffERnnt}pebo= z^m=dh`hHROqmAr6X!<(Ws<>F$WYf693C89twa6|UT;#~B)wRK_$h&3)ADDNNwIch>Xm^yKa=r59bzy!# z;@Uc5N=b;?N$I!Uq+@+_pSe`MY&3#z++z8sI>JxxG-%?`Et3uOnQS2-cS5Eof>Sn- zQG&A0A+H;+2Qu9eyvqy7J`s-PSUnbF)qfAcjaSHedhuqb@Gj1fylaDpIu3J*1k#-n zs{;oK$6o-}Kq7lGic8shPffi} zvxrNpH8-tF%lD<0cwb7hUysk?`$(iVdNOQ$%*}|)g4;nc*hPWGJtHlxU?eu{iAepj zdSbNI20Zh);h`c?XSJv+M*DGZ~&*w?5~XsRz+r6;Atxtm9BT6xWe+% z0RVd5p2p!&p3GuAh7_$l7bDr@q}JES<*G{sIP_9E(o7M}paxb3< z^FnkL_i_*b;d+cu2bz<6R>zppYArw5-g|g zo28N3ujN@WikCSyPM73!$u&vc66+85P!KxGGEeT*Z`)TT`oym4=S)$k{sQT!l7f<{ zBy`DZxG?_#*T*%}bpU?pH3-A9a2&tqIsggh5&WL(__@w%$062&2MFiSvLLP_I|QWT z5(&>?gux6Q#Z_>D?5LbqSy1FC>LoyTX-V>i=1dR3jAKtdbG?@k*7>#SDVqwGTOE{+LsR>g?cnQ}?@7L27kdwf3FdDI?`1 zq+Ip$!E6qBSw=1x+}~_fx10ECt3;#o~qhS|bJv~Le1JqeZqFXJyNkA=l4F9#n?usH1{-uZbJr!-yI zbzjx3*1gn@vm+U8Y;4+sS!Zc&`fxkCENjJ~zEHm&qoVxV)$LQ=Pw>3Hys?eV-eYQy z$i-Vh?A60c8ZOjN#WkD9C?z-M>cSQD^V;IH={P;=ml7P+?su%cP69b+!|R2qrCs(sxes1bZdg3*f5Gm?3&%#+?{ z7VT$FR_MbcHxukotd>Y6GGad-X%4r+7AhWeU;cJs(09^t6p<_vE~Y&1VIcdDtUB&N z#)T}n`8P)gMRH_?9zbHnd4i6jA|@AIZ=^S`)Tj*S&oSkBH=TL&x?QcxwN|hy54GaZ zDX-OtMD2W8u@8?lU%mtk9~(xrL#XNn=~itk2}LAXqFB?{xk6U#BO~+?DqdvcY7hQo zDH5uV>+(AT6ax}Pr(_tpsY=c&)^u{yL`GIcVm27tEc(}PQC4KqQ0cE+Z!^)Fv^4wd z(Q2e+JYHALD(gB|aVK zLCCzy!HqLqTdV(rk;?wkY43_=dEq(hm0JA;A9Ir~)^nBb!G-ZmNiHgav3I!gp=fc+ zTe&?C>2VU8$;l0C;9Y!7~Fe(@^Z~CaISmjX((NX|r2QJu$ag zu{Y^hr>CQv>2URr3pJ5kn&r)q6%=9EoB*^gdCKEyZaf&@$E?uT(pw)5B z&GNr5Uw=P``4ks%kgZzYoqxV+uAp?8VAfbLrUFT>jGb?bSZudEv`SI%QxH1wFpopt zVBK*CPI;{?8})3bP~C2lj>CkC7x9#O$$F%DmV*8CtY*nIXCPw=Ar*@}@w<0ZrZU-YB9xi2-pH1|i2dqR{LhWZC zqbN)3(sC4+ToK*zPDK(96so`94La|rx=rVID$5IvzX#4ZtG{Q;!1cvhaKdOr2?$B` zz04V1gBqjgL7);PsBwcY8hApZF4?1z>+JI`Ga5)DrZ3az?d9PI9p%P3H%gzwi$yQx zMma5_ibPc)>P4dVwq8J*EmN^2qm7NtmZ5EgqNSBC%f(31I7P$8W}A_`2Vsk3msQ!; zo_$%r4~0$-#oi$Keec@BBT{IG*fX1_Q3DO5F?#AX(lDCCYSh7IBK1`CUuf3D(*!OJ z0Vx!zw@Tg*o(4_2^5Ho=@fC^(?qRMFpvYBa{+#k<%Kz;^d0(!ZpiKmI-Q4{B*iESQ z_aVPZ69ci4^|cojwFp z8rABlqL~!i6uf1)16Qh2|E}J?tjIjGu|_m2_F(7g>nZEB*Eb)n*Jyu6WTRn1&s4w8 zI^&Q$bvF+0LQS~|^)`U_W}2?_4R>jY zRwUq7MgV%51Mv+w0Tp?uMZ0V} zEadQ)>oJ)^1Uyf3(oF5PR z`>#fP*83lrMTPDV{@I!td?eEmWTN&p;m>sH^i8l)@+rS;AVv! z8z$#gKc6ZXt(*(1=gUk+YPYvC#>zOW^8f@=A;Yoy^mwc1!zyO)i$==_XEg1GOPRz2 zGnLwdgR`3T_bTJP9uJ{Fh}UIaZ@8aSK>LHUk5s1;Wh~0@yl@6dOybRgCk+=niZ}`| zKF~+#nZ}>L0LZ*(xLB*Xt#%F9M_7XOT9#&=!yBcBTgjw>%4cfrc&nes>roZWs1c0% zby{M>0?~lLT&lL4cICF0*swrsc=J(`+Y-q*zpy)M*EB;hdW!t9|AZrc7ODSK%{o0= z5!q;cJ;b^C<80x%_sJXxm!tc(OTIOdhg#~TD;wQb85|g5dd9f>p}LLs{u)I$+Susv z6@8=~O+@BxF&_=}HXgLcXhx=uCHx4P>j;@_+hkrV$FbXJmnf?jjVH%sa$>jPI=8e; zHrfS%C%y>x~TIOJbS8=oMP)vnW zUc<=-f}F=ASL&-8NvviCOS2-Z)oofqZT51zu!33bTm@6<+D6(bEE|n$Mtr)&5KBQ% zIURg@XuSM7p_~^bic^hpZ6rm_M5iE$?3<}XA(~1;b=geqGA%QMwcp2P24>2a>qG1G zdHT4PxmGnkkP30&@-fqS9YqLadvWD@DFnvJyT&=0g8q3(o}c40_eSweD4#(#+lXhY zyM_Y%VmE!MkJ@2brB%_m z8F6T~Y^&Mr(Tv51ibxMz4{&d}o=S_`>C+&j5vgHnL@P8pKDX?~>2!iRtn_}gQMC5U zUNZy&oeT>@TwS-;ac!$`BtF-aFxyVHQ_ea1zZb{i^Efq~rt1o}p!q62+F7imzBZh1 z6XI{Xqw8{lA_(2`O8L5qc9~mVs@WElbLVDRxgM*X+pQ4<`rDhuikLBzfM#jGTbT~r zP6>FcNU3_<>i4lAbh0k)!y_;33el*S4>AHpp;GZQEA-)z*Kty*Uuaa%&`6}H%Q~o} zKda)d14TF<6!&qtSiL?Y_HVYgz@9@Z8rAc*7or%q0`**IADg$sx$sEyZdEKAN#Z31h2$~IeIODK$67>;r1iT;PHCM<#J?J(j+#Lh(QP9 zevv>&0GCI3i&zO3Hi#Ecmo}ADN#GKfTTUyr1!;17X5`deLf_iaTZ!R+#SP(kN zi2ZnEML6iA0aYnjPYxQLA2Z>%TcZJ!jw9v!c{?-$xm{2je6$1gi@cg%oE7@YLeL?v zSKS6E&{1{UA+Og6L+x`%D+t?7QSkFE(E~;0eyGh)c3Qmd6t{y&v&yY}E{udh;;d*}CJkynMg;@oTB~f6}h=kO5(&d|Q3p%8Gp~ z1w8;t_i!jja;^qf@MJ+C$w+*j?zKL=nIvnTK04N6JtvSYHDvKlERcyss`l@lSf~+? za;L%P*-nGy?G%=pu>r9<9bVfxyeu3ob`H+3_-IN2c!m+6>CENn0Pu*cXX#$zpo`Zo+x#FK}M{3_^ObYPsx-;Cu3I z0A%0%`?xOtx#9M*=)&{#k0XWe1i<^$yV>}_xA1@RB!)VM3A%lzqLbW^wwZXo?=)SVoGjLUCQmC-I04*L^(%J=)x<_Sr&-y zVtt`#6{{)2dLft*>ThQx6c&W5?3YDmW#vneUIMDOcdHz17phpi)$ix+g8s(=wf3M^ zmKTK%93|_$A&JST-LuZjH>g$_ETn>&3-HZ~2> zOG2$6gjz}1DAgG1ryILu_{e`a$G#bnn}bq0&AFZ=-0f7Nb$#@#`bY&5Tp3f!T4_6n zyMV5Q644k*%p(9J^Yergu$mM&CseeOp=2w`JwpMhF3;62H{51fS(lEL${59r_bW%u zg{8bEBNybVeX4Y1gLDui$_Q(6k~Jwwyf9fiuynuDBfWI#YEoum5fjX3yZt!yS@QS&49*LGg47X3T#q9r zUPCBm4L6rN1`tvch-=e;fYf!MGPY>&NVeHiv=VV>CJ*hVD7%Nf(12h&IF>j@ej>+r zKJpG`iwlH8VOCd@NRmX*9i$`dC(s=tlSv~W;+EWG$lytOkc%?uc$&%lB&k#iS+1N@ zK@bp2g0Z8cgWld=<|pRaD6T6K6F?nb5|U1r3%}n_m#+%}0Wl{c`UE9C)a619i{xB6 z<_q)q++G|G2eKdh1wZlzgoZ=-{XKY`T{u@{e&nUYeD?6)lXAAdlcmk>L=}F`2t6z5 z%c7iXN+32P1@+N@W)Xr`B8=K8HMG&2Ha5Er{c}t!2%!>HsFj9UNA+_{5rp#y$Td+x zyIBynlX}nZlbmd7u5V%guxC@BW+Mq(k%XIxA~eDc%nVj8Zxv<-$C({8ubE$t36w#Q zVYa7_aALl^Y~|s5YDAk6X5y`$kTYB7`}U%4NhNa8Oj@eKa>?N(>+sT>s`#A6VYl*+ z)!>rat;=r<6Tm5^H5-G&yMyO?Nyl-anonvANf z+iA&WBn_ecH4cr0VsE*dx+0-NE!TQ^>N6 zugi-p%Q$i2$T)CEJP3k-jEr0MAVnm|2}pf1(d7Xm{Snre*1@aHD`Y_O$VkN^0apO` zh6_Ou@QHp3jyz76a$67tJd&GGD1r-)RB0 z=D3s2;%imQw4%{0eOW&~Bla6c{bhvyvh+)eN2&xxv+2Ty;|xT`Zjl>mYB*FNhn{}yLiz6o$Y7IPn4+*c#9 zS8w|${d~9Zc-!QlEg3Dc$A9Cl7fsk~O~QIngaGI6KWAwhn=L?A6rTDwxHQjHUmsnG zdA>5*k8e^h{C1W`GPBnerBkd980)>BV@*ny8^NqeB@a;gm{{GaMS0I!dFUR)`<~g? zS0gL|FzDfz@CC^D9c0`M(xnZ)t7du>Y3g0l-QWM8y*m$YGsG;EL*Z8`5YazWz&|L>X!Ppx=D~|f^3q_0|W^IsMDUPk*vYyY7YU+<&V2vC5%@ZA!Sd{MaCx zt}ItIY^$`tVXo6E;kde#y6?Atbsw6?7dU0P1VUHW^&iuorp>sut-)c zP29%x&!&;E#u1Arun|n3cFB&O-9A87#VE-#RyS8Mzc7!e z97SY#9l_~oNRot5D3tm;d|`1BHk%EB^(l0@y3s9lBVmzX>9E4p?nWY!!0whkSh;)y z%@I2SOEc(d?Lkn!jpld<9zORFM)&;yaaTOYBSBiGL63leO}-hx{JqE!w<64L()RL;wFzoM4zJ-ExUgj~T|04w;a<);{tJctUr zFo$axkXv(JUNbby5fHtF>@Wm!j??qqeugjMO9d}e?)5*0$MJ&vVnw%4bx_{?z?`?$ zd$SiC@^;{mwdMF`@zsQdLc*EenXI6YAz@<>WTgMRlYxQRIY0*XPtIXhwCJ_8iYWaT zm2J_bQUb=zP_vY+(rw-*$ZLy05j`2Rj*lGSZbl&4-!5QrZ4(=to0#uz!a}nn>nh>a zB>>%+5d)BszC~R#%*+@z2mla)^`o5(87mbV`WI+=^?%Dcz3KbEmE3Cm+V25KRyoR! zHb{N{1BA2xH>CE%H3=AphKBIPFMbiL;V{-C5o~U5Vrh99FW%gPU;5`qu(G^@SS*It zRyS5x!w^Lgi9{Tmo12)Jm_%!<8{u#m5Cn*VfOF^0!R_9vzTDcv7!HRK3WXpD$=`A_ zGc&mtR0PjACUaI3D(Y2jSZm4}+P?B$flD@)zTQ53{TnaT_8?)Ts^X|NZg*+z>E`ApHY^)(%1*3# znqakB;p<5DuG$2!fiOhb0=p{QSwk3rfQ{7++`4ru)vHlW`I+PKcpw0{y>uH>a{<_` zHmo&mzc`g839>A~eP|Git*z*kWh^etVxMaOq0lnA+j?;1Cx`LQ2aPezrBPL58f&g? z#4*)2WohfJU;#1M<>cGR`L+ZDg#h5?>mDxGP+#g|Ain}l%d*GLoBjdFu8V}=0&MLq+t2YnxrbP6Jo2}&o%?@bz49FFKmKEgvu|PJ(Z7f7>=zOJ@L$7v{!3VY z;#+8b{v)YMM%nIxxNrf&N&v8XATGQMxyb_|TKSV(ZG3zj4?g%{*6FdkejDE^p^~w? zyL&ra1TZ^0ivtG^ARG?E?RG;D1ROYU5N@{{q1hSq_4dK%^TA8U!Wyx` z(b@#N&6abjbyV2;rPTyjU`c*$0}|@A2f(HfgH?_}{THNFwn9d-Un2lO5FpEPs*j_v zbsA(DZkG!X1bDq(?Ao;pPRWT5p=0~_N_8ZV>I>P{-j0sVRx~%;5Z{#0x$i+tBqp(H zS*`qm1Jb7MdJ^wcC4e)U4Y4~lX&Bhr!YF26PI(-F?d^>*p-uBK*%aI1j%WAqaZ8u8 zPE*Sl8fNxj)Y?K_3H5#0iQi|ck7Bpj=Bv_+3F#F_5+t0(*|gK%5QF$-`C<6wR!EQ` zib7Th_l6L}??@j@ejx*!h~gIJ;Eg$kgEfC~QtbhDv2yz1A;sr#0{Q|_faagZ>1=j1|sQLXV)!f`1=H}9?L}q8x z{{R~w9|y2iWq37t+WQ8M003sNjE#G|Xleo+S7UIw+>qOMp$UNNH-8QfPHo`*&OI3W z@sIJL4}A!iFJH!Vdkh1&?U?SEh9C%-n%bV?r2d?UYGapu7wmRBrYC}cEJG9o2%@+( z{n?Esp$Smldk~8Ivm*0SG61LSMCM;N5ix>h$(iiS2tbnMWaXkPC#$H14zV50Qug%eCV3X_ghp_f$Udo3nZsVH88BvIFwr>f5PvBZ zn&ney>n)HS5Nd66RbNJZe)8X4`i+kXm(qunh~2Qr5m@Cgeu$~9%UsUdZk%h2v6@Q) zzK8MD*IGZ9ToUjl)n&TnZX6emv!@a*6&C$W30v4?hVZ zwg%_l-igSmvv8h1f%RYce)2`LoPguyQ;7Ue<5<1-BHF(49+n>))U`)nzAel7Dhz?` zibAU+*-K#I{6*juK=Wz*t>nAxKiT?nY;3!~*N*|*fB*fdua6u#g7)?{Oid+Uv?|*r z{eC|Jfk5i($w0EqR{$_M$v%fWS#NJIZr;rPgGxEQ_>XlG4{)#Hdlxfmb zeI-}vscF2BE2c-D=Js2>iB~LfJe;s5f8Yq)J^g+tOlgLWsjati`t7Ix`~AA+deXP? zYhMN^BAnLvG24>=8YNk_98dksVl^&NIwb(CWXf@=15DVLumLo3psA?jKFHf2Qx%L1 z7aPX9RK?NM1#r4_jaa5fAuhZF`Vw0uvJx*u8r<0ATm-J$UuiSFmSK@}0a_ zUU>x{{NM*u$GCChM(X3p|0PbHI*Bu9zKoM6KZP@AzKlQllRw6hqepS+ z;w2nCdSvVRM{()WMI1eP6c;aQeLRMX7cXMhFLdL=+y(UZCjYR@6&}9teec7IFTRL- z@4Xi8kLIcJDjs8 zlBe~dAAPcA`!X`prVRt7S4C2Jik@Z*;0EUxXgyQ3y^^G8uvRYbfZa}(;P}7K;9Z;vi07G&+hxE= zW}*%UeK&n+;bCTQm@g>2>AQ)U-kE}zCn}3xFDLT+jUdX~m5e~f=e1rJHJqA;jB~ec zp{uhCx8{wzFTG}x<5D3+lP|_>nF4jlr3wA0j|E3RC= zk_r}Ic;SUq(0KXs_7=y>moKNjR)6g6_Tg(^`x*e?(xqgn_^DGT0RSgYek$#wa{i@D z7XbhlFBbRlo$sB8+$pE37;}Am@x|n1#1~#j4x)MU&E$*KpZ@fxnje$b4MP54_HXo} zLc^`3EZ1clrAkB;1<0#1tR5?xz0=6p`*MtaK zWM}g9WjmZP8`e4t2amE-Mhs2>$$pR!k}vm@x1X$VTy`}h>;_ubM8t&_%!%tb5cgn3 z04%BcY2{kUkFp?RO|-%yIS>^^tcxPLTl>m>p{))Ras>E}T}P=v z%nS~d(6AaBZQ5`t;hfq%f=0z%na3#<%9Ru3X$`;F5W8^}XYqj4k3SP%zzLj4Rqkos zUalZ7h-thfpT&$kQ?ovL*+GBq;6K;UA1z8nvDUwD<=<^11cSBE2)~zzN>NIH2yBOf zN^q!D7cwj))5`O*M@#^=7~ojn-YzZ3fFQA;k+KPghmO|ldGXN5L%4A1Lc@iOvAcd7 zwi1S<6ru!$((v~nj{O3pd%h0w+^<4zk|3A#UcC4ynT(g@HT|4@Jg=U3ppi7 zs>N1N|KGFG^C7gfb-+2?mbQi2v(^k-!j4VnCT`or zvz& z?LHZIO#^e5S=@W?y_m7cXqKDdkyI@#WF=xu2Eei`!=A9gop3`;h_J2LvD&_he{B0| zS&!E{qV~_IL&%6HvTxd-=TJ+J%G536X!gfvm| z?Ufqtl@r93bQ{G~)D^*~J?pdr?s5b5M=c-4TT(J)RNqb^rS|+}=w%$;Lb500_oeUa zy%egWk69ka3yBx?UWTSh14MPzAw$G%dxc~HMMZ;OsNvi%-j5$i**m!M=?enAH?#li z3j*Is$!F%}oUC_PmcpCUw9Fz|;Zb?I-sma-s`u&s|G> z-S*tibY7LdlwPGP5AKHhqCx)%%J}`5t8%82s>V&BEfqe6E&I|c)JpF4CvLs?SM?)H zz=3sZ0&&5O`P(;;5M9Y(Dl!mp#vr&|uv!wZVhxbDe@3i1*I-N75VOSK$mk=c1dg-4 z%~)7j#;R*I^;k8_$)9PFt!l@Ju!d&IiS@`jZpm|y0f_Q;Pe$ecE3M7w4n{B|0G6#i z%D#kv*KKncky=y7p0NVS64PWYqbvgs(E@h@n6kyOF0SIL^C~vQ^a?ukL_UWxYUJBu`Mf{tYqNHTX-w$__IO?e)#d0oIj8& zrAn?`g>J7=Du`>PNuJaExsY!nc&;#TLXZ&^cVR=`{s&&nV{4=eLFM^i_U8qW5oHF5 zz;+MBd;ubm3=yj}1ciulP^L-C+yA9183CLXEfD6@-Tzfh5H9i^<%`Q>{7DUS93@xKEA#KqUK@%Zy_y!Zq* zKJvG4eCwY904z6NE_hp+m5Z6d+`Gz0Uou#XtsH~%+-sVb`Qg@O9OK#Bl;2f`;rH%?^Q~L3Ut3Py27uJ< z0Kh*zoIMdu76de1U4nOM11lCw*7;hD5^66$Hi$%v4SoMd`a4TIA!wZc>=8J}x1XcM zZi$ba=tQhL8A916*AVUTqA66H?^oGXjCp9i$j=uD=BxaP3f+*lwlQ1fFrwlvM6oM1 zNw}n5e;Svy$aXYaEU*h~+}8R%*Tu)V1nax<1KG8U|BxY@c4K!zZw(vYoTFw5>JTCtv- zer*xaj~UEZWNgBYvzDzF7qSdrd}|u@R)wS_Nw7+8EXrInG)2-B}qm;g7x)#;0A%tLs)v(ojz;>9VJjab3DwQ(`Nb6^V){r6f zd1*xLfB*Rc!QFy@1!=abRoV5X+-IXc7l?MU%t0!}1c<#idvUY(Cf>Yf`}a*|55#=O zswD=QWHzaZ(nt>)v!+Z}<5(KuWVwMQkR3c~1(sTu%XJzR#}FZ-7RS{kEI&4ww?eQ` zPeS!=6?>lJ>JnmiCHogvo7Cb1n%dCx%Kw@?)@xtF#vQK$0HU^k1$+BpU^5K+*q>DW z*tMh%Jnud`kKM3f>HKz}q!m;;wt`9}WXycQZojq+uPRu37umcS!CPi^r($$uaO?a? z)_KBO4CuAt^#=!2r`?xvJC2M%Z0X7USBw2h zldsB0>pXR}kVBeHg+G#DhbV96Ttl-wt$F&U*p4Q74y%^K@Wjs}D(*s)G>c8K9iqI6 zO|c!DLhjpD-wvQX@FQT2VNa(B&#HiEuNUi6ZbT7|8`!?#Hi~>*rG_SZ3f` zC+c7k8bPCh6;)vg6dhUu#aCPAyL`UWYo(>BrLne4=L$fghdhYic4DL5n|2zIzP-5V z%Ccsl*mPyNYE^_rAg)dUtLf8{9q%Te(dy~SX43gzE^1clb^e!&CEr%AzLZLZX1=im z>cBF4Bua+=aH-HG@S(prm-qbpRwIa<=){|!`!h>5jPO&w=$5omru(INUhs)jY1`v|{6M8=|V)ly=F$ zsuj!o4nb;4wi0L#WZ%zqe;1l3GhXN`TW%KsaU(m76Xpdp|C)Bd2jmX_a-F9>O8{)3img!;#dE~oX=WHiDjt#h`!&vTGhI=J~CPV>2 zz~7AKu-z%a)o`FLDn5d z?||i^B`v@UOig88Ep>hb;j|%)nXck8rZlc!3a#rWM(Pv5srd)|72igw>y}2U7o_HL z5C^gDT*p)-_xEXVVld}<`RtzD4foIT&kPVX0^Z#dyHlUvh2yEuiwT3(L1|{dsSZPn z2|x1%oMsC*)xjb(f=06`y4q4vAi%WvEU@0T!n&~?&E*Ux^MslCtR09zhzk%_OPd8= zZV+nK3I>X;5LD9&{F-(x!y1afF~5}eavKM|Ss|OzdNWe(v_1E;)O2Z}@xo&*g$D8b z)YSsa0Fe{URNxkIM-aWI7j4h|EVU)wd3GMlbAv^1FIKKos?-{a3>qUtT?mhCzq>8J zzaO{yj%QbCia>b82j|=K$=jBYcD>Z`Gec29fEbCRN&Q^7nyh?neoOtcDfx-yQ@lyw~$fKJ_~Csfw0$w8Hp3W5+wYn`Nsv<-)O28W@&Eq z7rODD5HER~Z?&kmL2DAzFRMsxp*C0uSZm6C-pQdenNKO$| z+w0lY11*`?1JWz+cJ*XmFIVMSTHyDc@&do_Pvvh5q6B#lJ@gPRT)2Q+w~XBz-7;EU zbzmie2o}CjAz!ZiCbU!%UbeI+U#|og)9;`9HUpOJ=T#}e=WBSa@P*2x4kEP_3PyMT zEdBbKVdw6N-Kl`nNa1GccIq5*iW1VQ86hYCSP!{E%e-M`9+t)A^U!juHa|Zz z!$_-Epi}RV$8mKjEmW+>)=<)y(xWdj)P>H!yoC1uc1`ak>CSm}K2^E5anK9NZA0Yl z&gA1%LX}~5s8;$qO1;d0HH3jLjb^W9Yu(PX^QBc|p6JY~ZrwQOg=IBXa)?^&AeUPH+fZp4IAPvtZfZ^ks&~U3<);PAr5NlV--5)giXf6+ydl2 z3nJ~ESdwoeo=9Nb4%k}Uut+vUJAmyD&;^&CB_c?0%9($WC<9u6keI+?y90n% zm`!H*X_%gj>Y#BaRI(K-a-uU8w9S9^NLKHPSst#loIS|USA#d zDO)~sTt?A!bt(CrxTg!wv-4#=AM|)kgExcd>+MDGX8JEF=h^wP9!KSRVmJ-}sheN-`^5q=Alw&R1&%@_Dh@~qlxTC29H!d&0YPBI|0m9ekU_%VeixQfL zoLE~6qg85!+wBG*V{>y8iG+lNEdjgDhW3_ZpC9?kP0YqcB%JH$ZEMA5TL+rt>}t}e zumM??5nWsbZimsa7*1BS3PLI~6a)e7ZDF)8h9Lvk)7pt$aRFVeeXzu5u{$oL2E8N? zE<=U@S(ag!?C6NOvA!BbbZ!RyKB@7;my97E%J+KNa=a#6Wc!6aOy_AGpf`s!i)G94 zw2-yozsF>1l>~gnhI`_;m=(lzcXp$5cPDngxjXCf`2sz))NN+J&jlbyW#7^C%j6CG z@@(l0>g)4GqDr{xQ#irLy*s4rnL;a8>K z2d(>)d7HV8(a6t%Ov-&xs#lA>Z_4+`d3GN2pF0BQTg6{@r%`XcuBBU;M{ip%I+xqw z9`s({TU*AOJ~3K~zP=6~V^sD6DZ2x5PQj&Cj99(F7@x zz{W-t@`jAKHI6p#JOn|2*l9sxApxt$ib;6|LTDAu%}!XYRwQf*Kn4<#1RS0w*yScP zcR1kj?8fTqDpprkkdP!mk^mtY7RoYkV`2gVfUd4C3`Fesws#E&7S|94l3T5185_|k z>~=d^TU#N^GM1w&2(2ul#nyqPjwxJ?7VN%ic$Ew_*{Rrnkjho;Hr$?`p1hTNg>Fab zyH`%nKA><_U%o26Oj0ZX9LPT1)#5^LZ!cWVmh{`)qSdD_^Z13rJ+(rWeE@?#BGQ&C zysTBI2~@vgvz-2$g@Vj{mk}YR1)YULPx~gY?>eyi2C#b~`QIMZ=er}xHb?^l19@+! z(D@3#KiLDdMQl!;mKj3&Rkw9?-(k(mWXczImKt*A3pN>Q8YE;?!Zvl)R-=b)OT=HF}((6~7*0Id? z9IvD*v-7_;euZx()O{V5O08N1OY@F-+;C1{ZMq!?15Jp#<8T~vAikV{ZD9?Y%bSQt z#=FOXs zWjVPmIx4`~?nG;AD_{k@UN8E3dl8Grv9Ym%L?VIN*;#b2tm9UHH+t6-Snut|k6Z2N zNo=CU@$v26%T!kjos%1{ME%&x6n(Ue!dY^mxt5*a>8ZkRN>Dp`7PsQiq#b6`URI9avdiK`fTt zgTGpVWm{Vt78VvDSju~Yv()t%B4pH3i?B^msDiE7K(6B6cW=*Q{L2V7ORXc$QB!!m@nRUMszwNCK7w5ZVBiHh{|;fMe^w`$Y-f>|D$+Dh)j=2|M!zn96xmQ&Sii7(iE77uMF+ z5Q#)IFRuatrKQ{e4FF<(7uK7*5ShZg#VNE6~qF*rmg1PIt0*b7kvnk`N^oz7%6V?2R` zl)&t42wmQ8INF=xo^8dzK>yaQ$dCmR=O0I~paUO+4sht-;VPfP$XbM_|e2|Fx{7BqS7aM@fCMFELKGH7g(TF~rt!qMeM z$9g~3qz!mCU1(cv!r0_3d=ww8+G7M%_c1pbb&xgaPxkgX7C5HYa>`O{m<1%a7Ku6j zXfNe<0)YTlP5+}=}9J%wkVeYUFWAma;#^7ptRBBGs72{Jdf{!_b*`cHaq z6#4$%QlB?9H3h%lkNNreoFQX1Dm#@o4`*fyPcJW|m~HRYS_VC~mN1$x-GXyIf2fix zaMH8dEq2#$r+uC1xi{@=OX#OX-Hte$`*PB*PDD=pw549yw_ES{vy6Z0V z`g(EKU3cZb;G00?)5#XG&a?AC0>E8;Ra-~7VOcJvytpi+P>-Z)sz;>@upK_QTihjG zubPi5P+3(C{;u?^RD1o^pj7=7TV=fkR8-v?H#&rXlz_z0DM&~RDV+n-E!`j>ARwT0 zcR3&_h;+A7(k-3RB@H4V-FM^r|GsaenC=wbv$a2N<4mW2MK9SX-|k}fGN1&xH@X!=g7u(ow)TB_LWA2X<-9Y}{Y7+h>- zPbfkrZG#z5PTxO9RSSCJ&?a%^BfW~xrbmL`!MLVPO8g^WvXf;t&EDFL59OJk2?>o< z_g*JK;$~7Mm9FenGdo*}f&cd#%z#Q}hFO9z!R%boG@1J4xiXrxc@f=sb4^K#(rZe2 z$ouQ*RRP~W!i*kFJi{EW?UuAVMw09Ep|<6rVb)B$fBtj_W04#iq2c3`>TtaQ04kU( zK@)>g_&uaj8oSB+L6Ptxsw&M#maodA4#8hZIqLF$Ng_r2Lk^3#S5)CE>q>S^4K{O` zxZbL+DZkaHwpLcHXT`#bA1VG?CJ)4zaeHN$M>1zB(VHqPmb!XvkW&}*_>n_-uHK5A zRe^ap)z$HEbaI7_F@dB zJDoWxHWXjP*j@97-?l`|hAwKa?+YxcbV+pmtSjHaR^kO#bbzwyRr& znz@dSPOCo(*?2}+7>kJ(f2rn2b)1~vEkBErZ3*@qg$%^m&fIKV3yv=XTbH%*!#Go^ zke?~;-YJwPZ@;s=B43sV$w2PrA#C@dS7~qNxZ_;OE6KCZmFr)#j^4}mo!e!1eg4BymO_0fB-u0&Dbommg^&`r%>sKV(|2WW4x@!tMGS z(2g>^e`fAH_WlNJhT0KU?vKK_A=5Hpu?=7YPUib{5QxrdZN0hgk(a{K=9 zA0c_^=-7llX=$OCz{YKCY}~UQu`Nx954wVzlGL=cn@Gf^rKP)jA}o)#_xEKvq4&!L ziH7X$dqwW=i;?Wt6n*2 zEp7pUUYh$gg(>!LA;l0-eO+`%jl{wV!{JjVdfi;nZ5>4xCUdnArd+<$6jk**=Gj(L zPy}}OMz!*hASJ{vmrR@ca#lF3i;wFK#|jj&rt{00>Il?vLAM{247MT0PFGYWPSd(K zCN1<4h{x8`&82U{f2ZeM@V>v7e9b{sD#m;S}@GkgB>!RHU>zWk|cO@h?aXP zy*~&W%FRdYRAkw~u}H}Zv*4v8t99-rj}cNWY8hR>9itEEd^q`Hn+%P(6&(m0& zT(kwZ`KoUGa0Ol=_?t)^h@%D@g+;_v534AZ6r8Ro0+4D2Pg>tiy(`*xB(`(WJnW`D zf44Eq9*+GsiunDcIdT?0EDunQLV>r*H@^K|u z_sr3rc*K>KvF$gN4rldQNVy_cdQ=)r`FMT0@e$bE^d}3s8PxAcPUq(46$&A{UoTm1 zY9*C7DLHK?mo0{AXDeg88nsZhYRgEY`4{r3T#QR94}%_}TyE(K4T*9xdX1$F^Y1aH zwzilpbyZob5oEITK~#FMsU{OA($i+eX+g5Go$i9z+*zl0+>qt;Ez$Isarz#~CQ+?$ z1^NfP@0Q-7gFVq0?XV(oh<+BVV>-xvT3Ge>cEpQ0+B`ABoJ91mw=1S2!@qRXnm;8B zc*Dy3eGuOb)7E{5TS*Q`ZaB`QN za(x#@H>@T36hf6wl55H&0y=eyDxNobKF+2!4;FyqI$#EKE4k{) zKC$bGk-%6AIZ8-6zF);8=#2E~hyS3|HI+~j$cR8$^qph!7F9S^W3V{+@=P|(AA z1psgdt+OXaXnT%7^+IXv?d`Q5>P1ofTpN2T#aVPST~kwIW?}-lIwgJAFT<;-q_hpz z_yE~I)y~F9SJ%I1wQ#HEi9R}k=e{x)I7#RA$3!?z@6Iz{@$rKFzqxmwoX#>asp>No z#uV*u?=H%*Np>JYOw(K}ug5hiy!Xq&gYm%+FUD@Xim2{53We}{yo{^)&58!S_XahI za9n4|L@vMKbK9FbpUd%#?zh7tufo2mdM|jNExcci{#)D7ofi7R(JJIc^ymixWAVIq z;vJkJeJf{IwDX&*M?FE8mzSI(BBf`rumaqMh6YD)EMVvj9=@98yaPXIC(^E6)onQl z=9oB!#0vk#0EQfNB-?sWz!GzFpMaip6V8G&^@1T5%3HImMdOasCKir}us)c8K-lOg zu<{auTl@Q)`;K&3ltoQVhWk(OMsc6)G(l!lbZ+j=@Pv++C^Z&Jn4+1f|IKjt@z=+p z%@AzT@PaKfL!Hsz>)e0Cc)eUUFJ+g2vXHn;Q>~ zKo{^};8ViF3Xp&Qkh7oy$Klqw?j|nw(_{(i=;@7lKK$BI8Hcbn^Y9=8j_dvkJPcHI zZ}32;$_T{0B`FH!ZXv*W`;|eBv#0wV}7ZWEZwS7xGwdi^S_L8!)pC`$# z4@spm!6QFS93S%((<#Q>-vd2g{_(xyOj3EmwEgxYQpt-+2Lb6F`+3w*RFUDz34Hv` zT-HVu*JjFwhK9+XK8*typlNPYPSW4s52&o@Cjwr-ySw{5Aoza45}YPEx3@mH4)pgF zt(vg^&f^IfOadrFN`1u@7XSv#LT{jhk>k1HVQ%cTbJ30h229QCz zUU~!o=V6bK+adGEjo?_@= zIJhzR6CQS4sR0xO$hK>{E&LY*N@q?+O44$&-@#L=If&F7)mTmE_o6Rkfl!e1QOvys{caIz<_<#NyJ~~)vObjj?JNr%( zHeC@{Qh)H|{ws{tNAkmT*xc^s-VL)%xh$=YfZPX;;xc;<7 z(Fg>-@a0za{~kcTbk1M?=Z^zGc63=q#h$%T%wSF)9?kuZIRE3bv)v|C7>zbJ!Q>Fo z$>xi}H$Ws{Pl09Oa7bc=kpP+VJgpI}}A~M(<^--p<0?4|WE3-FL zw@WT%I`*IJ(Sr-ifoK5>F6~N)8@lVGXvjkP{5lv&gC6*!X-IJ@DP0e={b11d@jv6Z zOmcMiUihEwCjDy3^vD~@W#>ol3daW62)|n%K1PUv3M@F3hd}FLXp^ew?;dLh(TrHF zD8?>e&ZIAA3#E)9V3m}pff4}6DraYB1LDr}DQVI^DS6c^cTqu2kB@j>L7naH)W9Xdnz&J#&umL-X_RE*9&ubj!a(~PRw9))e05oav zAP}@@X-l(Kx!{9n(O*CY0MpD=;PL+xg(Cii`&aFnpGJwmeExO=yH@FOg8y7jAr!c- z5(^%#Q#cbH-B{@OwuMT!-tqy-Ta8OtRb0T|l^UC@F~?LMqCoxJADc%`uMpu*2a(S! znX;c(Qqxb8qqlr;0JIBsoaIrofpQY4Rn}>x{u8h73k{U|zzTF2Tie-1d6O2>SkCeU z!n3Y{KfNa!OkJYHg5eJ%jN^ZN0YU)U`^R;YR)acL8Yr0J%kJM2Sigu|yH8fWa5{V7 zUP{bzvN%l`{N{28qx5sb2ZBKxSGWl2Yd>J(mJ@AQlxgr4OV{Wc%Xm-?3`0S4^iX|Y53Q4VRr(+8w^xr4~}3m;3f)z-T^LlgV0A> zC<7qVot+}~o{eRaF``;U4d&?##8b*EPIYEL|N20`<)aIoE^D*@DZT~v$xctf<}yjK zgKYQdK~j>jkM6MLhoSR;Q2G1FB@H|boJ60XZ(%DxJ>-Xw$HzuHF+#rg7H!JgJpfvM zIU{gpakW>@fBfv(GwU~R%10yOaH)hbLOT#{dQBVTTVycj?>tCz`gs|?x9&|zk~n5A zE`<5Y>FwanNqOR!nFEbJyKjIPNfO86{d?%J=v4{uW9c|JI4ikHMq|J|2b%Z9I2H5Q zz?{S46|zfpW04Yp(kdw_33wb^|CqA>+B5YuFE8)!=l#R?c#&Nr^YaGzME1o~yH*RV z_bM}?pQmdo(WUw*00>jmVn1yWYpx{(y-AgMIx%RX&amMy;V}gG%hnagiD$yrogXA) zY2-?^V`o}hA;9Cf9an^VVLlM^DAqc!uCIUir7`2eU%d4omfYle-#%|>NEy<4eeE?E zv*KJ2sOz{l`z@7{p4w0fZt^`9;rlz89I&DAqXZ|D%4draxjYyQ)-J)JS#|Fsy$ZSL zAF$N_bOzn$03xDOz5g=AI-B<{OoN5q+n9B7VF3ps;B#F!#LDHv`DJQYY za6Op)5gq;><$EuE)?Xeh?1Ppi#~-~C9}q3&a0DyHeY#VC;^*E~aihevoX>d&^-fbz z-1_CM@89^0PS*0q_BIYi9x<`l+9e--VB6E(g{jb@&{kapU+Z-h0G9KL!Py%^qbP1A z0SwXrX?H&2>`)ZA;eEnp;oTC>i?|PR3A+i`5d1u36M0qoP6s z9-a{bjG#8aG!&O+>U(>8L~r8ry4OxT0BwP!O0X#BS8p__8L}reCq%*Db9o$ZsWo2x z`CeEaUBQ^m>5;5fV%D5rT3Y)4`mo1or9D`%BrGa#OnezU?fpR;x>FD3JI#}%!ckT) z!f4_Go>`9*9vCd(-I8}wLW3rsasngGb1e@qFN1x{56TVSzw35ctAn(V2Zw*yj-9Kk zR;{^ybjAA4a$Df}{HAFBg?RFMuyxr;dzdNwc|;TS*^;jq5PNm4Xse6cq=48L4#Og6 z6w054!%aAQ#Y5bJfct_hAEos12@4Nk0_+j5f1hxAsQHR27F|I>0U$Tc9knhD2K1IK zUR^RsiScXv*MFA4@yqIWFno0oD*;`wO?S%sf{XfHANEK*&Y?b^0A!qO5kvbWr$t!Oxgcfa~ z3Dh37)ejM73ovi^Kz>tGx_+)wga~PLzR`H@3AjS-AD%&VgkWoB5G-<9GteJi-3Wk_ z*g-S_sKlZT03x^)c#+8ahjpzx1HV94>+~T2#iW4vBc5y_8U0v1P_aUdd`>~ZK0icJ z1ke^s;92SDZYHv+v(=z1_h3HwiXts|1-$=7^ufa zxOxO$`JcT1^Fv1EFZZ9QqE#Q8qhb@o zLL_Mi1_l5O%e@C8-0DjAiv@Q`6IOD~wVQky0?Yt1;I(5B4}c?1Tag#gOlo?QiVtdS zws3Wj=6nmmp8QB~TA@NeNr2v{Dgp!rcz;V%qU?I7?_b@4C&AxtbEI88KNnynWex^3 zq?+(1)18!?%sVz-^CKzx1}rmL)W?wjOY_0Vdu~z9OcA*@mpbEp)JK=)0W;{u@be~RR^o(8gE*3xe$s#jPi{_haC=;n9aJ{* zGkgU1p37(|U_+V5M@H~K!Tl8VNrV(9k18RGJ*haa)|gEyBq~!C z0~8;D@?u;3CujV9r#8wNdCpN$Q6~4CRLR&lwJsvRN7KRjKxXEE%!CFSJDco7`*IZf z?ibR(we|Gg=|W6Kcd8N}NCmjOh7F>J}ZF2<9yWa2co_9UPCWo;A%m<5(js{^6HZ2}T z4$h@&&G6VzmR>q$?f3n1(3 zS(@CUch^S%(mf>-v^=%7fKE zo$IlW(6Te7;3tVTx0TYi;H1a*JB9fpQ&UN)f=W5H27#tfK0e}*NDCKvqSfkQ(c&}p zUK5Z=0!+Y9A*_{;$A|iS=V=AuRCE*RkAjH~(~qr)xq@gF5iSoGmyc40y(2nZa(V*C z!4QCag+SEHQ9jkr0uL;l(ze0%VMbbt&Nax(&ma9~XpAhiH({*EDO8y15lG}522x-9?cc_&;5>S?3a0I@n`CvtA$oY2 z!BAN0e5HAhg#cngo1r8v&|~FP85G zk3fYa3vv8puwMIU(H%gqwPn_lh8376nk$|$Ya#ed}-$xTCM@Kw> z?I<=RaU$n(n5i>{d-&HL0??AirX+2F2Y~m{(Gjmm2;!0pSqp=dTT14MwWeq}nsQ2> zmw-(wSxQ5k(|-nD{y}t!16xLe8NT?=p+%iswEROTDJ(8AGn4j|iwPnQvQS3eCtCNZ zNSilrdcM7$0?C%`)~E5g=xAu5&@*FOc?z~08WCM z+k>izoDhEYKGg-!Ma%ttZaQM^&=W%`1!_`K-IN8>BW<&rVKFExO3RAa z2{K>jl+99`q>vrN6%1X!GFAdJckKzRFI|LuL?l1S^X@E#1yjudX#@v{cKp7!3)++v zxgQ$^Y0-yz?*yJ}tma6Ui{Qaz0+JFh{rAbOTtU7u3!y&La zZh}u7HARbx$p@>x=^2(5{Hes?`9mEo9sK(vOE=tI;?0EX2BsSzjsbg8nLb1GW%3?s zZlh|;YK)NMYBvt3N>4h<%(=DiFTk-SolEPRnkdn6DVE9A8C^Hi-jPT7kW8OXjbhR$ELa)Y zB^MHnX@3XQ&C%qn;-}x!>}!Pv3%Yn+Zs(6n_M}%d=@}McScFChdBa@jo2=jDd_#`b z3g+hIgn+CdQ-&ApgjXwRR0?hVm3vvnHf|_N?VF{aC$E~F?XtxZQ^@R_g1zoTlcl?x zrQIg%v4>0wpU9aM;?*>t5ow}FeZy=&PJ@-YW?(K1t9K|qk^3#ko@>Z=+RoMeveR#81Ao4a$7d}^IrGw#)QCsH z*eklaEc($qDS+*?^BPpas@U?8W!AH&c9ld_{xlv9ece>F+A8oeDs6p&hhgIA$hpVU zvXp^Iln~o@m^J#;2hcR9G*|oYf^2pOHQbP7atLG=oBt-1JMNON^MIUJLdf5*++dFr zh5aWVVgz(&8$s=-_Qj`<|79N*`{m3hxiOw@PJ`*yu4eBm+nUXJ&dkC5MYP3cp$q6q zkl$xKpTe_0JJg#UPd*zBxO%{lmsM3K z@H?LjDi_uuk@?=}eavv(!Bc&1zrWa|oAgq$-|T5^{k#3eue%SBkpKjIl@6Dl0r?K# zdmHIJxYX_UI{6n1U4YT7167;*G`Xvb%YhOzT|6*fA*AP76)Yk?wz;z$L)oKG!TF~C zpzEY)(SdQn_#AE4|9gvn>!W@3^z)9!mopC~{_Z&%7Rz{NTmN%g z+Df&c=VhMyqTkGR6G8Y+Fb8qr2Vh!3Dd7KSTHD+27m*I;uH!I~3q;eDUk$!xrLXc? z!7?84#CbBF3TvWoLR?Z?KAoUHy4v&&VEViz3w)zlGHjscZ#tn_Q7FC>=jc%W6*-4A zBTQHr+mDuhogYME07%{2(N>?R&PmGD0d)}& zo?){?6++{kmE5nsnI{|NiNo+@igdA;Tj5ie`gJB=Z1Rt-1fhvQ$|a%;6Lq({W(M*k?$ ziV_d}hj>AiU&yVGM{5`)l0^^0RdQG)2MGPNipex~U7om1U{Zfm9wxD1*{qhe`dhgz z$iDJZ$ZUs;YtCHU!U`lxyZ&By0RRf7h3)aTDS9ip;sj;1Qk z-#lua_2mD>zZBxSEDGSnU1#5tmqG27?AON=*>R)m&XdQd{gV~tR`&%SMGZAjjsZtq zs^r*z%ImYn@hr5QG<@D>@qDVEMDJ&|v6WS8FQ@?=f$~mBlqQDfzo>;LKUj=Ze79UI z)_<;ib#`yfCh>GZ=c2ghLtT0r4+Tgrq>3GQ&b_P>RL^j`9u+3O{qmU7moqY0Z1w@< z13i|`#i!VgF>h#ieZT8>4oy+zM7}%^#Y8utVgUB>ID&8p2*-}IQlDk@|aD;liH0^ zz)w2zQ7bQl13E-k@@lhu<@C-KosYv8Yv|Dp5)B5PowAPLS#B9e=@2pm)l*^TYiGMB z1XB4eiPk)D*}`VkOr;wQl;1Qxqv_7 zi%pMOZ6{^j7>aZ)tb4*j;>)kb3}OJF8>5W`)nE+%`=1*D_ID!wF+FG%2R+`_KFhUE zS4&I58=<%Fq?^x}bT0a3X?f~tYh29sGDKUvQJg6tG^J09OG^SfDoz#xPxx=S397Nn z$U*UY6jUuTjiii0-n@OqaWGb+Cuh3Mp__AzPe+Vo6 zfLbH$ONqMwG34W8lDwesPeTRFv&0l#NC|105lNIOQWaN;*_r)VP3Qlo}%=5k%1C+Gnk0#4~66W%L zj7-q#(W9HLhr}ls@K1d`8aSGm%nWWHbY`y}XQtf?=Ke`J$u7YGEXDcG%a$ULB$B}X zziD3!8W1&z)`-v-4nLw0P^GZ|WrGzGUy{Y83&hUa+Wube*&VNN#?{Z$AJ5Vuw|A#Q zq79{gn^%nubziXkK-lR%RS<(` z5F<1((aJx)+KGlWs+E}d2$mR?$iQQ3tB9_=mV?)BmL`p;q;HuEf404NLurE zUwoCdv`O86CVD2?vN@XIlCgi&1mTulgqS-aLlpVN!hh6K;r+N|TaK6_lEC|w?SVjW zK%^F7pP;JkdOsNg<>+XvoTvL|j0TqQj!RdU+%)6u8>+xF7obxZ)1?kvvqc z6VV^#ScE^l96Y5ZL<#0&xE9M05E#C7EPs@UCjUyjSE_K+gi!xLkw2+^$f+j4g1tSL zaPwnao$O8U+a@W6i&Ub=%~jVXkFvurG$q?e8u$_dJ666FjWIj&$>MKK^xMNnD`xE8 zW>tsOmPE8r&0cqX?ZLhIZN}E{+l`Y^C~xtGw8ZyFUs_gqWgz6JOZqq_vP~&iy7m*z z*9dTM_8jWWXi%@*1CuZVQk@YIlaZ6-W3DqpV3s2Z&!pY^o08{G&is@^VVm-b zcSkL4jel$u8*fFnh;`ePaQ)I55NhE%Y{VcR)oYK2kmh1lKo6AoarFaTDJ%*?Rs)_ zh~QOD^OzU%p%AP*d@g1-7HuW6gOfJPk$omtm zUWdqviz8U$a|&EJ9Oyzs$QqTX+|>Ia>q84r?>~9Jhn4W2NOB324q8>`Y;q6|{>Rjf zo)uGC#n{=&$zaef-&m|P$A@cT{g$%sV5af+s1}?5qGq&Qiy&z3?wa%J!YnvYaKLyI z_wDPKxWKjDxS+~*ydmmA^FIeIyzN=$jZ;~wb_1^vh7mapXz7D*yE>=SLS*{YSkUT^ z*C#l-ZfkKjEHj|yg4bgPqpvGM+mNdTrfjP4ShV#aP7<2ob+hykzjbu~#F?Gu8&~l` zIn*0g7`5k%CL*TxKd; zu6fgoqWGY7zxGRr z?0FY_%Nyl`pT^Td;Z$p7EPD4p*6g_wyHkbGtc>p~&d@zJkmUchXx(0+VJfB`Mz=kr z`}@GUQjYgC5I%opE9J89IyyzlT)*tg7K2|dHWHLK9(oNKMVYM}IAXZ$5Y*JqW}mOQ zI$`d}-7I8w?lZ2u+rWni;d|;tiXo#=bG6E*#NKuDr%hL`Li~c`=8DiR1y6u&9G!}P zdP}*R!iq*UE~k_n@R!S~)x(&7NZ0@gGO~?>apr0^y1vwQppt|lNO_!KEbUT2(oOCY z5I)t+>TxH1s%mMot{&xR^MpRNw*WO$g7tyPc^aF1vW8L?N=&0>NMFR!C(I(gK{)5- z^-I&+oyQM9)mx+f)`4j3U!#2Cry)4*Q1zAR(~uUs!&oi%BHwUTF~44S1Lh3RV*<_4 z-SW?AFREciFk*+BJy$kfop{bHj$-F2c8a1yKA)+j=xCwN>Wf#hqFKq>(&cu|S77?Z z;H6IdrY=_8htO2m&9fqb7KQUmR5$mhaVsV1~RzGMPlbS+W6CF>Pb> zYf+JWYStr)P@B8rho6FEjHVBL6wlUHK1zf|OxotE+B{HaL#X|bF@}7J8b*)X&(ei% z(B~w7rVEce(9m&RkA@bznpj-AND6&>FKdzd-33{nkyi5AD*H#fx6erTSn)*vNY(K> zIh`5bihcR^jp$^3Px8-}I?Iri@)K(!9D>Y-S-F5ZOdmWj!`v_)2x63h&sZU$RD z@c>o3vD-3+;U^Dqf6-i*6uXLkN=;SO*Dnr3-_$FaE=B!&SOpvfC@h6a6Wau;A5?vt zv2$OKXTk{hkXj}Arg2P5BA(m*^np}{IhXcI>mUED85+imFie+@B+`}Zpx7&Q2XwPw zliAtXs-a=%>=p!~c;jL2HFq$~@xt2N=!|E`PA4j&#e;aoh&n6Nh|SfMY`O-BQh-N4{=3p27(;~GahDyRIViV}iDKq13k7Q; z)9+IlqAnpMMS^pi3RtUEAerrv*H94w57L4$`8#>j*FM)v`rFa$!h z$AJRrvo$d32`H#Ld6MRN=gy|*jSjez1~$1beuo5c!BR~AdqdB-s|z55W+2o3k5MIhw5*PTsG#M2AEU^rFI6!pee1_28Qs&2~ePFpc77QKs*Ck+hFa@;vnL z<$h3^9j%q92iD3kE{(?qlBmm)UBWqK*JmF zDb%yP{AHdI4>mqM9kx>KtS`|U4lIvX6lShYLaqXxfnFil;aA~gF)GOGU{XA{Zy3tt zj0R#LQFP8DpP&>8WEz zYk2Z?TsECmY*o!=n)j*tbTutoF;<#f=;`bqnjT)_28k_T&C%yqoY&m>+3c-CApM4K zvj6&vWqDLrWmrHU0^qQ3U?x8Q{Hfj7AxDV%FiM&Q%zg&TgM@cc5lfKdEOr9lM6D|B z8QT{}8%y<)ERHr4)iKdd@uOUmi}|SU@Aebt2xkr}KA*o9TTL1zIJB|)bog9JR5!LmjKxib+R_qg>X5I^su4T%=3TuCOSBdg+Ms$ zyl{5!{&<{2(ZoT?)R8)|(VbN=ofQJnXqgE*c!jP>3k&h|cK#%ehf2$ARL=hgNd@mh zl8zpM8QLL{Ife>pwW`i!A`Dm`x|ph2S#2&+mu3z=IGi~_e$HgkY5T2xf9j{65i5un z^>EhMU`0v=J76k~^4+|DYAPA%1If3~uW?$B2tDcSnWVA_{p4!yIpda6N`U@oH-((cx z9TJ32Cn)i`>G)#^ZhMc5nf&rP^zqq-M@DDu8OqR9`a#)Y`xL@!-pgXr8n;GPh5oAz z^K|&c3fKC}TRbTho}%`61W>hNust^TBxT7SK_I9DFQg?j?G_re95gTzq>TQPLz@q59^OlcU=h#V1>!xO@`#{CI$$mH6@llx)v*IM4m= zxPs^F+O-A8KU)m|#J8u5ESX9QNRZ8j&nOVZy(?x&r%X>K6B!aj+7Kuu+n4H z%;%t_;`V2rxt27jZv~4eu2+s>)lr~e84HOfF;)!+8ASpwS4o%A6wx!-Fgn1O9siu; z7mw_x(N^A0nPSZYWNkqhB`Zrl(v6MC&vKoNzZ-iETdvHHUdPsKPT+_wQsuo`tlUKQ zZMNHpB#{e#FQ9VW^x8DL!qG3*ohx(j;qAF@DF@?aZcFAxen7SR#^yp&jD>`Nxo9`? zamtgI(;cD4%SIHfv7FB@& zRg$WOo&PGh=af?<%R^$rxlGgk!v0n_wEeWVR;E@>`MuL554rNQ;MU#_k^tIFATL=i znUWkqIy}6*nT3T9=W6WZfm-+rP~hIT?ST|muVP7&i<|>D#sknN#Zvpwz0z(5R z;q|+uxHw)oYQd@+NgzX#o|44C(Lcw{LQ0p9&Zr8~b0?PhN!&9>i}t6qyK;f;g%6Z|cyl;q%q~_)o4K9q!9h7rgYGe+l0TgZ?rGo()W`2zm@j zdLYY?FZ;fdJiUH~z@Amu zT5*h>A&t;U*-GLguoZ02+8P5$J!1;Srgow~341=HKHzRxV@C?Q4tcf*pAy=AjGF&7 z2yun)D$Z)y=2oy0S(-T^5cb# zq`|(Ed^L8XagKTzE33gIG!Idcr|aJ`0fbpl^b}aOhs!R4g(C`71uvF+g9umawz49@ zPM<$Zbm@28CmALnv-R-K?mf3`uoZ(t?fd#g_m9mVlJrM@gn)(;!qRduc1s3qVE@(o z+?J)zYcL80y1)wg4D|X{Ew`nsh)IKKyBhhk$+rLeiFtXT5P~W|_wwA!psPrr)C${O z^OzAMi}PcJv0PeGAeJ2Cjb6&+bl_WdGFUz~ZhP;;e4-y!DVc3tR zLgV(|gVep--mJ{Z7-~^bkt6699rWf4o3GF-J-B*Nu1W^aR&z#-+VLrP_*7o_TKv&c U6p`+nhJc?JGRo3rk|qKF59K-5p8x;= literal 0 HcmV?d00001 From 031c8739547e36fd00d65caf33d600fd8b2e7cbb Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 29 Mar 2024 21:05:29 +0900 Subject: [PATCH 21/56] feat(crosswalk): ignore occlusions in the presence of traffic lights (#6604) Signed-off-by: Maxime CLEMENT --- planning/behavior_velocity_crosswalk_module/README.md | 4 ++-- .../config/crosswalk.param.yaml | 2 +- .../include/behavior_velocity_crosswalk_module/util.hpp | 1 + planning/behavior_velocity_crosswalk_module/src/debug.cpp | 1 + planning/behavior_velocity_crosswalk_module/src/manager.cpp | 4 ++-- .../src/scene_crosswalk.cpp | 5 ++++- .../src/scene_crosswalk.hpp | 2 +- 7 files changed, 12 insertions(+), 7 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/README.md b/planning/behavior_velocity_crosswalk_module/README.md index 7d6acbfc6aa9a..b82ea7887dc98 100644 --- a/planning/behavior_velocity_crosswalk_module/README.md +++ b/planning/behavior_velocity_crosswalk_module/README.md @@ -209,7 +209,7 @@ This range is meant to be large when ego is far from the crosswalk and small whe In order to avoid flickering decisions, a time buffer can be used such that the decision to add (or remove) the slow down is only taken after an occlusion is detected (or not detected) for a consecutive time defined by the `time_buffer` parameter. -To ignore occlusions when the pedestrian light is red, `ignore_with_red_traffic_light` should be set to true. +To ignore occlusions when the crosswalk has a traffic light, `ignore_with_traffic_light` should be set to true. To ignore temporary occlusions caused by moving objects, `ignore_behind_predicted_objects` should be set to true. @@ -230,7 +230,7 @@ To inflate the masking behind objects, their footprint can be made bigger using | `min_size` | [m] | double | minimum size of an occlusion (square side size) | | `free_space_max` | [-] | double | maximum value of a free space cell in the occupancy grid | | `occupied_min` | [-] | double | minimum value of an occupied cell in the occupancy grid | -| `ignore_with_red_traffic_light` | [-] | bool | if true, occlusions at crosswalks with traffic lights are ignored | +| `ignore_with_traffic_light` | [-] | bool | if true, occlusions at crosswalks with traffic lights are ignored | | `ignore_behind_predicted_objects` | [-] | bool | if true, occlusions behind predicted objects are ignored | | `ignore_velocity_thresholds.default` | [m/s] | double | occlusions are only ignored behind objects with a higher or equal velocity | | `ignore_velocity_thresholds.custom_labels` | [-] | string list | labels for which to define a non-default velocity threshold (see `autoware_auto_perception_msgs::msg::ObjectClassification` for all the labels) | diff --git a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml index 09ce64593ff46..f8b9e5dbf1327 100644 --- a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml +++ b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml @@ -78,7 +78,7 @@ min_size: 0.5 # [m] minimum size of an occlusion (square side size) free_space_max: 43 # [-] maximum value of a free space cell in the occupancy grid occupied_min: 58 # [-] minimum value of an occupied cell in the occupancy grid - ignore_with_red_traffic_light: true # [-] if true, occlusions at crosswalks with traffic lights are ignored + ignore_with_traffic_light: true # [-] if true, occlusions at crosswalks with traffic lights are ignored ignore_behind_predicted_objects: true # [-] if true, occlusions behind predicted objects are ignored ignore_velocity_thresholds: default: 0.5 # [m/s] occlusions are only ignored behind objects with a higher or equal velocity diff --git a/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp b/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp index 77de7d241c05c..d287d7e705542 100644 --- a/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp +++ b/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp @@ -67,6 +67,7 @@ struct DebugData bool ignore_crosswalk{false}; double base_link2front; double stop_judge_range{}; + std::string virtual_wall_suffix{}; geometry_msgs::msg::Pose first_stop_pose; geometry_msgs::msg::Point nearest_collision_point; diff --git a/planning/behavior_velocity_crosswalk_module/src/debug.cpp b/planning/behavior_velocity_crosswalk_module/src/debug.cpp index d6a2a3cb185a1..4bee98db2fa56 100644 --- a/planning/behavior_velocity_crosswalk_module/src/debug.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/debug.cpp @@ -190,6 +190,7 @@ motion_utils::VirtualWalls CrosswalkModule::createVirtualWalls() virtual_walls.push_back(wall); } wall.style = motion_utils::VirtualWallType::slowdown; + wall.text += debug_data_.virtual_wall_suffix; for (const auto & p : debug_data_.slow_poses) { wall.pose = calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); virtual_walls.push_back(wall); diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index 39f88d5389c2b..aeff5e27cea7b 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -135,8 +135,8 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) cp.occlusion_min_size = getOrDeclareParameter(node, ns + ".occlusion.min_size"); cp.occlusion_free_space_max = getOrDeclareParameter(node, ns + ".occlusion.free_space_max"); cp.occlusion_occupied_min = getOrDeclareParameter(node, ns + ".occlusion.occupied_min"); - cp.occlusion_ignore_with_red_traffic_light = - getOrDeclareParameter(node, ns + ".occlusion.ignore_with_red_traffic_light"); + cp.occlusion_ignore_with_traffic_light = + getOrDeclareParameter(node, ns + ".occlusion.ignore_with_traffic_light"); cp.occlusion_ignore_behind_predicted_objects = getOrDeclareParameter(node, ns + ".occlusion.ignore_behind_predicted_objects"); diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index e4b9f346f4f6d..7caf8651d8b33 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -240,8 +240,10 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto const auto cmp_with_time_buffer = [&](const auto & t, const auto cmp_fn) { return t && cmp_fn((now - *t).seconds(), planner_param_.occlusion_time_buffer); }; + const auto crosswalk_has_traffic_light = + !crosswalk_.regulatoryElementsAs().empty(); const auto is_crosswalk_ignored = - (planner_param_.occlusion_ignore_with_red_traffic_light && isRedSignalForPedestrians()) || + (planner_param_.occlusion_ignore_with_traffic_light && crosswalk_has_traffic_light) || crosswalk_.hasAttribute("skip_occluded_slowdown"); if (planner_param_.occlusion_enable && !path_intersects.empty() && !is_crosswalk_ignored) { const auto dist_ego_to_crosswalk = @@ -269,6 +271,7 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto applySafetySlowDownSpeed( *path, path_intersects, std::max(target_velocity, planner_param_.occlusion_slow_down_velocity)); + debug_data_.virtual_wall_suffix = " (occluded)"; } else { most_recent_occlusion_time_.reset(); } diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 5ce5d4020928a..d2468e7f31aa7 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -162,7 +162,7 @@ class CrosswalkModule : public SceneModuleInterface double occlusion_min_size; int occlusion_free_space_max; int occlusion_occupied_min; - bool occlusion_ignore_with_red_traffic_light; + bool occlusion_ignore_with_traffic_light; bool occlusion_ignore_behind_predicted_objects; std::vector occlusion_ignore_velocity_thresholds; double occlusion_extra_objects_size; From 1527f8a299d12b46b4f26ed515533270a32175e4 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 30 Mar 2024 07:07:34 +0900 Subject: [PATCH 22/56] fix(dynamic_obstacle_stop): fix run time error (#6714) Signed-off-by: Takayuki Murooka --- .../src/scene_dynamic_obstacle_stop.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp index 2e2a7bbae9bdf..82a6af3c3f518 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp @@ -18,6 +18,7 @@ #include "debug.hpp" #include "footprint.hpp" #include "object_filtering.hpp" +#include "object_stop_decision.hpp" #include "types.hpp" #include From b5c29fc36bde2fe4d4a482d05b5fd375cfd00b96 Mon Sep 17 00:00:00 2001 From: DSak <58344842+sak-0822@users.noreply.github.com> Date: Sun, 31 Mar 2024 19:13:46 +0900 Subject: [PATCH 23/56] docs(mpc_lateral_controller): modify mathjax visualization error (#6486) * docs: modified mathjacs error * test * fix * docs(mpc_lateral_controller): modify mathjax visualization error Signed-off-by: root --------- Signed-off-by: root Co-authored-by: Daiki Sakanoue --- .../model_predictive_control_algorithm.md | 88 +++++++++---------- 1 file changed, 44 insertions(+), 44 deletions(-) diff --git a/control/mpc_lateral_controller/model_predictive_control_algorithm.md b/control/mpc_lateral_controller/model_predictive_control_algorithm.md index fa214abc9a564..a1116d8a11c74 100644 --- a/control/mpc_lateral_controller/model_predictive_control_algorithm.md +++ b/control/mpc_lateral_controller/model_predictive_control_algorithm.md @@ -22,7 +22,7 @@ In the linear MPC formulation, all motion and constraint expressions are linear. $$ \begin{gather} -x_{k+1}=Ax_{k}+Bu_{k}+w_{k}, y_{k}=Cx_{k} \tag{1} \\ +x_{k+1}=Ax_{k}+Bu_{k}+w_{k}, y_{k}=Cx_{k} \tag{1} \\\ x_{k}\in R^{n},u_{k}\in R^{m},w_{k}\in R^{n}, y_{k}\in R^{l}, A\in R^{n\times n}, B\in R^{n\times m}, C\in R^{l \times n} \end{gather} $$ @@ -47,10 +47,10 @@ Then, when $k=2$, using also equation (2), we get $$ \begin{align} -x_{2} & = Ax_{1} + Bu_{1} + w_{1} \\ -& = A(Ax_{0} + Bu_{0} + w_{0}) + Bu_{1} + w_{1} \\ -& = A^{2}x_{0} + ABu_{0} + Aw_{0} + Bu_{1} + w_{1} \\ -& = A^{2}x_{0} + \begin{bmatrix}AB & B \end{bmatrix}\begin{bmatrix}u_{0}\\ u_{1} \end{bmatrix} + \begin{bmatrix}A & I \end{bmatrix}\begin{bmatrix}w_{0}\\ w_{1} \end{bmatrix} \tag{3} +x_{2} & = Ax_{1} + Bu_{1} + w_{1} \\\ +& = A(Ax_{0} + Bu_{0} + w_{0}) + Bu_{1} + w_{1} \\\ +& = A^{2}x_{0} + ABu_{0} + Aw_{0} + Bu_{1} + w_{1} \\\ +& = A^{2}x_{0} + \begin{bmatrix}AB & B \end{bmatrix}\begin{bmatrix}u_{0}\\\ u_{1} \end{bmatrix} + \begin{bmatrix}A & I \end{bmatrix}\begin{bmatrix}w_{0}\\\ w_{1} \end{bmatrix} \tag{3} \end{align} $$ @@ -58,10 +58,10 @@ When $k=3$ , from equation (3) $$ \begin{align} -x_{3} & = Ax_{2} + Bu_{2} + w_{2} \\ -& = A(A^{2}x_{0} + ABu_{0} + Bu_{1} + Aw_{0} + w_{1} ) + Bu_{2} + w_{2} \\ -& = A^{3}x_{0} + A^{2}Bu_{0} + ABu_{1} + A^{2}w_{0} + Aw_{1} + Bu_{2} + w_{2} \\ -& = A^{3}x_{0} + \begin{bmatrix}A^{2}B & AB & B \end{bmatrix}\begin{bmatrix}u_{0}\\ u_{1} \\ u_{2} \end{bmatrix} + \begin{bmatrix} A^{2} & A & I \end{bmatrix}\begin{bmatrix}w_{0}\\ w_{1} \\ w_{2} \end{bmatrix} \tag{4} +x_{3} & = Ax_{2} + Bu_{2} + w_{2} \\\ +& = A(A^{2}x_{0} + ABu_{0} + Bu_{1} + Aw_{0} + w_{1} ) + Bu_{2} + w_{2} \\\ +& = A^{3}x_{0} + A^{2}Bu_{0} + ABu_{1} + A^{2}w_{0} + Aw_{1} + Bu_{2} + w_{2} \\\ +& = A^{3}x_{0} + \begin{bmatrix}A^{2}B & AB & B \end{bmatrix}\begin{bmatrix}u_{0}\\\ u_{1} \\\ u_{2} \end{bmatrix} + \begin{bmatrix} A^{2} & A & I \end{bmatrix}\begin{bmatrix}w_{0}\\\ w_{1} \\\ w_{2} \end{bmatrix} \tag{4} \end{align} $$ @@ -69,7 +69,7 @@ If $k=n$ , then $$ \begin{align} -x_{n} = A^{n}x_{0} + \begin{bmatrix}A^{n-1}B & A^{n-2}B & \dots & B \end{bmatrix}\begin{bmatrix}u_{0}\\ u_{1} \\ \vdots \\ u_{n-1} \end{bmatrix} + \begin{bmatrix} A^{n-1} & A^{n-2} & \dots & I \end{bmatrix}\begin{bmatrix}w_{0}\\ w_{1} \\ \vdots \\ w_{n-1} \end{bmatrix} +x_{n} = A^{n}x_{0} + \begin{bmatrix}A^{n-1}B & A^{n-2}B & \dots & B \end{bmatrix}\begin{bmatrix}u_{0}\\\ u_{1} \\\ \vdots \\\ u_{n-1} \end{bmatrix} + \begin{bmatrix} A^{n-1} & A^{n-2} & \dots & I \end{bmatrix}\begin{bmatrix}w_{0}\\\ w_{1} \\\ \vdots \\\ w_{n-1} \end{bmatrix} \tag{5} \end{align} $$ @@ -78,8 +78,8 @@ Putting all of them together with (2) to (5) yields the following matrix equatio $$ \begin{align} -\begin{bmatrix}x_{1}\\ x_{2} \\ x_{3} \\ \vdots \\ x_{n} \end{bmatrix} = \begin{bmatrix}A^{1}\\ A^{2} \\ A^{3} \\ \vdots \\ A^{n} \end{bmatrix}x_{0} + \begin{bmatrix}B & 0 & \dots & & 0 \\ AB & B & 0 & \dots & 0 \\ A^{2}B & AB & B & \dots & 0 \\ \vdots & \vdots & & & 0 \\ A^{n-1}B & A^{n-2}B & \dots & AB & B \end{bmatrix}\begin{bmatrix}u_{0}\\ u_{1} \\ u_{2} \\ \vdots \\ u_{n-1} \end{bmatrix} \\ + -\begin{bmatrix}I & 0 & \dots & & 0 \\ A & I & 0 & \dots & 0 \\ A^{2} & A & I & \dots & 0 \\ \vdots & \vdots & & & 0 \\ A^{n-1} & A^{n-2} & \dots & A & I \end{bmatrix}\begin{bmatrix}w_{0}\\ w_{1} \\ w_{2} \\ \vdots \\ w_{n-1} \end{bmatrix} +\begin{bmatrix}x_{1}\\\ x_{2} \\\ x_{3} \\\ \vdots \\\ x_{n} \end{bmatrix} = \begin{bmatrix}A^{1}\\\ A^{2} \\\ A^{3} \\\ \vdots \\\ A^{n} \end{bmatrix}x_{0} + \begin{bmatrix}B & 0 & \dots & & 0 \\\ AB & B & 0 & \dots & 0 \\\ A^{2}B & AB & B & \dots & 0 \\\ \vdots & \vdots & & & 0 \\\ A^{n-1}B & A^{n-2}B & \dots & AB & B \end{bmatrix}\begin{bmatrix}u_{0}\\\ u_{1} \\\ u_{2} \\\ \vdots \\\ u_{n-1} \end{bmatrix} \\\ + +\begin{bmatrix}I & 0 & \dots & & 0 \\\ A & I & 0 & \dots & 0 \\\ A^{2} & A & I & \dots & 0 \\\ \vdots & \vdots & & & 0 \\\ A^{n-1} & A^{n-2} & \dots & A & I \end{bmatrix}\begin{bmatrix}w_{0}\\\ w_{1} \\\ w_{2} \\\ \vdots \\\ w_{n-1} \end{bmatrix} \tag{6} \end{align} $$ @@ -88,7 +88,7 @@ In this case, the measurements (outputs) become; $y_{k}=Cx_{k}$, so $$ \begin{align} -\begin{bmatrix}y_{1}\\ y_{2} \\ y_{3} \\ \vdots \\ y_{n} \end{bmatrix} = \begin{bmatrix}C & 0 & \dots & & 0 \\ 0 & C & 0 & \dots & 0 \\ 0 & 0 & C & \dots & 0 \\ \vdots & & & \ddots & 0 \\ 0 & \dots & 0 & 0 & C \end{bmatrix}\begin{bmatrix}x_{1}\\ x_{2} \\ x_{3} \\ \vdots \\ x_{n} \end{bmatrix} \tag{7} +\begin{bmatrix}y_{1}\\\ y_{2} \\\ y_{3} \\\ \vdots \\\ y_{n} \end{bmatrix} = \begin{bmatrix}C & 0 & \dots & & 0 \\\ 0 & C & 0 & \dots & 0 \\\ 0 & 0 & C & \dots & 0 \\\ \vdots & & & \ddots & 0 \\\ 0 & \dots & 0 & 0 & C \end{bmatrix}\begin{bmatrix}x_{1}\\\ x_{2} \\\ x_{3} \\\ \vdots \\\ x_{n} \end{bmatrix} \tag{7} \end{align} $$ @@ -124,8 +124,8 @@ Substituting equation (8) into equation (9) and tidying up the equation for $U$. $$ \begin{align} -J(U) &= (H(Fx_{0}+GU+SW)-Y_{ref})^{T}Q(H(Fx_{0}+GU+SW)-Y_{ref})+(U-U_{ref})^{T}R(U-U_{ref}) \\ -& =U^{T}(G^{T}H^{T}QHG+R)U+2\left\{(H(Fx_{0}+SW)-Y_{ref})^{T}QHG-U_{ref}^{T}R\right\}U +(\rm{constant}) \tag{10} +J(U) &= (H(Fx_{0}+GU+SW)-Y_{ref})^{T}Q(H(Fx_{0}+GU+SW)-Y_{ref})+(U-U_{ref})^{T}R(U-U_{ref}) \\\ +& =U^{T}(G^{T}H^{T}QHG+R)U+2\lbrace\{(H(Fx_{0}+SW)-Y_{ref})^{T}QHG-U_{ref}^{T}R\rbrace\}U +(\rm{constant}) \tag{10} \end{align} $$ @@ -141,9 +141,9 @@ For a nonlinear kinematic vehicle model, the discrete-time update equations are $$ \begin{align} -x_{k+1} &= x_{k} + v\cos\theta_{k} \text{d}t \\ -y_{k+1} &= y_{k} + v\sin\theta_{k} \text{d}t \\ -\theta_{k+1} &= \theta_{k} + \frac{v\tan\delta_{k}}{L} \text{d}t \tag{11} \\ +x_{k+1} &= x_{k} + v\cos\theta_{k} \text{d}t \\\ +y_{k+1} &= y_{k} + v\sin\theta_{k} \text{d}t \\\ +\theta_{k+1} &= \theta_{k} + \frac{v\tan\delta_{k}}{L} \text{d}t \tag{11} \\\ \delta_{k+1} &= \delta_{k} - \tau^{-1}\left(\delta_{k}-\delta_{des}\right)\text{d}t \end{align} $$ @@ -171,9 +171,9 @@ We make small angle assumptions for the following derivations of linear equation $$ \begin{align} -y_{k+1} &= y_{k} + v\sin\theta_{k} \text{d}t \\ +y_{k+1} &= y_{k} + v\sin\theta_{k} \text{d}t \\\ \theta_{k+1} &= \theta_{k} + \frac{v\tan\delta_{k}}{L} \text{d}t - \kappa_{r}v\cos\theta_{k}\text{d}t -\tag{12} \\ +\tag{12} \\\ \delta_{k+1} &= \delta_{k} - \tau^{-1}\left(\delta_{k}-\delta_{des}\right)\text{d}t \end{align} $$ @@ -202,9 +202,9 @@ Substituting this equation into equation (12), and approximate $\Delta\delta$ to $$ \begin{align} -\tan\delta &\simeq \tan\delta_{r} + \frac{\text{d}\tan\delta}{\text{d}\delta} \Biggm|_{\delta=\delta_{r}}\Delta\delta \\ -&= \tan \delta_{r} + \frac{1}{\cos^{2}\delta_{r}}\Delta\delta \\ -&= \tan \delta_{r} + \frac{1}{\cos^{2}\delta_{r}}\left(\delta-\delta_{r}\right) \\ +\tan\delta &\simeq \tan\delta_{r} + \frac{\text{d}\tan\delta}{\text{d}\delta} \Biggm|_{\delta=\delta_{r}}\Delta\delta \\\ +&= \tan \delta_{r} + \frac{1}{\cos^{2}\delta_{r}}\Delta\delta \\\ +&= \tan \delta_{r} + \frac{1}{\cos^{2}\delta_{r}}\left(\delta-\delta_{r}\right) \\\ &= \tan \delta_{r} - \frac{\delta_{r}}{\cos^{2}\delta_{r}} + \frac{1}{\cos^{2}\delta_{r}}\delta \end{align} $$ @@ -213,9 +213,9 @@ Using this, $\theta_{k+1}$ can be expressed $$ \begin{align} -\theta_{k+1} &= \theta_{k} + \frac{v\tan\delta_{k}}{L}\text{d}t - \kappa_{r}v\cos\delta_{k}\text{d}t \\ -&\simeq \theta_{k} + \frac{v}{L}\text{d}t\left(\tan\delta_{r} - \frac{\delta_{r}}{\cos^{2}\delta_{r}} + \frac{1}{\cos^{2}\delta_{r}}\delta_{k} \right) - \kappa_{r}v\text{d}t \\ -&= \theta_{k} + \frac{v}{L}\text{d}t\left(L\kappa_{r} - \frac{\delta_{r}}{\cos^{2}\delta_{r}} + \frac{1}{\cos^{2}\delta_{r}}\delta_{k} \right) - \kappa_{r}v\text{d}t \\ +\theta_{k+1} &= \theta_{k} + \frac{v\tan\delta_{k}}{L}\text{d}t - \kappa_{r}v\cos\delta_{k}\text{d}t \\\ +&\simeq \theta_{k} + \frac{v}{L}\text{d}t\left(\tan\delta_{r} - \frac{\delta_{r}}{\cos^{2}\delta_{r}} + \frac{1}{\cos^{2}\delta_{r}}\delta_{k} \right) - \kappa_{r}v\text{d}t \\\ +&= \theta_{k} + \frac{v}{L}\text{d}t\left(L\kappa_{r} - \frac{\delta_{r}}{\cos^{2}\delta_{r}} + \frac{1}{\cos^{2}\delta_{r}}\delta_{k} \right) - \kappa_{r}v\text{d}t \\\ &= \theta_{k} + \frac{v}{L}\frac{\text{d}t}{\cos^{2}\delta_{r}}\delta_{k} - \frac{v}{L}\frac{\delta_{r}\text{d}t}{\cos^{2}\delta_{r}} \end{align} $$ @@ -224,7 +224,7 @@ Finally, the linearized time-varying model equation becomes; $$ \begin{align} -\begin{bmatrix} y_{k+1} \\ \theta_{k+1} \\ \delta_{k+1} \end{bmatrix} = \begin{bmatrix} 1 & v\text{d}t & 0 \\ 0 & 1 & \frac{v}{L}\frac{\text{d}t}{\cos^{2}\delta_{r}} \\ 0 & 0 & 1 - \tau^{-1}\text{d}t \end{bmatrix} \begin{bmatrix} y_{k} \\ \theta_{k} \\ \delta_{k} \end{bmatrix} + \begin{bmatrix} 0 \\ 0 \\ \tau^{-1}\text{d}t \end{bmatrix}\delta_{des} + \begin{bmatrix} 0 \\ -\frac{v}{L}\frac{\delta_{r}\text{d}t}{\cos^{2}\delta_{r}} \\ 0 \end{bmatrix} +\begin{bmatrix} y_{k+1} \\\ \theta_{k+1} \\\ \delta_{k+1} \end{bmatrix} = \begin{bmatrix} 1 & v\text{d}t & 0 \\\ 0 & 1 & \frac{v}{L}\frac{\text{d}t}{\cos^{2}\delta_{r}} \\\ 0 & 0 & 1 - \tau^{-1}\text{d}t \end{bmatrix} \begin{bmatrix} y_{k} \\\ \theta_{k} \\\ \delta_{k} \end{bmatrix} + \begin{bmatrix} 0 \\\ 0 \\\ \tau^{-1}\text{d}t \end{bmatrix}\delta_{des} + \begin{bmatrix} 0 \\\ -\frac{v}{L}\frac{\delta_{r}\text{d}t}{\cos^{2}\delta_{r}} \\\ 0 \end{bmatrix} \end{align} $$ @@ -243,23 +243,23 @@ Using this equation, write down the update equation likewise (2) ~ (6) $$ \begin{align} \begin{bmatrix} - x_{1} \\ x_{2} \\ x_{3} \\ \vdots \\ x_{n} + x_{1} \\\ x_{2} \\\ x_{3} \\\ \vdots \\\ x_{n} \end{bmatrix} = \begin{bmatrix} - A_{1} \\ A_{1}A_{0} \\ A_{2}A_{1}A_{0} \\ \vdots \\ \prod_{i=0}^{n-1} A_{k} + A_{1} \\\ A_{1}A_{0} \\\ A_{2}A_{1}A_{0} \\\ \vdots \\\ \prod_{i=0}^{n-1} A_{k} \end{bmatrix} x_{0} + \begin{bmatrix} - B_{0} & 0 & \dots & & 0 \\ A_{1}B_{0} & B_{1} & 0 & \dots & 0 \\ A_{2}A_{1}B_{0} & A_{2}B_{1} & B_{2} & \dots & 0 \\ \vdots & \vdots & &\ddots & 0 \\ \prod_{i=1}^{n-1} A_{k}B_{0} & \prod_{i=2}^{n-1} A_{k}B_{1} & \dots & A_{n-1}B_{n-1} & B_{n-1} + B_{0} & 0 & \dots & & 0 \\\ A_{1}B_{0} & B_{1} & 0 & \dots & 0 \\\ A_{2}A_{1}B_{0} & A_{2}B_{1} & B_{2} & \dots & 0 \\\ \vdots & \vdots & &\ddots & 0 \\\ \prod_{i=1}^{n-1} A_{k}B_{0} & \prod_{i=2}^{n-1} A_{k}B_{1} & \dots & A_{n-1}B_{n-1} & B_{n-1} \end{bmatrix} \begin{bmatrix} - u_{0} \\ u_{1} \\ u_{2} \\ \vdots \\ u_{n-1} + u_{0} \\\ u_{1} \\\ u_{2} \\\ \vdots \\\ u_{n-1} \end{bmatrix} + \begin{bmatrix} -I & 0 & \dots & & 0 \\ A_{1} & I & 0 & \dots & 0 \\ A_{2}A_{1} & A_{2} & I & \dots & 0 \\ \vdots & \vdots & &\ddots & 0 \\ \prod_{i=1}^{n-1} A_{k} & \prod_{i=2}^{n-1} A_{k} & \dots & A_{n-1} & I +I & 0 & \dots & & 0 \\\ A_{1} & I & 0 & \dots & 0 \\\ A_{2}A_{1} & A_{2} & I & \dots & 0 \\\ \vdots & \vdots & &\ddots & 0 \\\ \prod_{i=1}^{n-1} A_{k} & \prod_{i=2}^{n-1} A_{k} & \dots & A_{n-1} & I \end{bmatrix} \begin{bmatrix} - w_{0} \\ w_{1} \\ w_{2} \\ \vdots \\ w_{n-1} + w_{0} \\\ w_{1} \\\ w_{2} \\\ \vdots \\\ w_{n-1} \end{bmatrix} \end{align} $$ @@ -280,7 +280,7 @@ As an example, let's determine the weight matrix $Q_{1}$ of the evaluation funct $$ \begin{align} -Q_{1} = \begin{bmatrix} q_{e} & 0 & 0 & 0 & 0& 0 \\ 0 & q_{\theta} & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & q_{e} & 0 & 0 \\ 0 & 0 & 0 & 0 & q_{\theta} & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 \end{bmatrix} +Q_{1} = \begin{bmatrix} q_{e} & 0 & 0 & 0 & 0& 0 \\\ 0 & q_{\theta} & 0 & 0 & 0 & 0 \\\ 0 & 0 & 0 & 0 & 0 & 0 \\\ 0 & 0 & 0 & q_{e} & 0 & 0 \\\ 0 & 0 & 0 & 0 & q_{\theta} & 0 \\\ 0 & 0 & 0 & 0 & 0 & 0 \end{bmatrix} \end{align} $$ @@ -302,7 +302,7 @@ For instance, write $Q_{2}$ as follows for the $n=2$ system. $$ \begin{align} -Q_{2} = \begin{bmatrix} 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & q_{d} & 0 & 0 & -q_{d} \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & 0 & 0 \\ 0 & 0 & -q_{d} & 0 & 0 & q_{d} \end{bmatrix} +Q_{2} = \begin{bmatrix} 0 & 0 & 0 & 0 & 0 & 0 \\\ 0 & 0 & 0 & 0 & 0 & 0 \\\ 0 & 0 & q_{d} & 0 & 0 & -q_{d} \\\ 0 & 0 & 0 & 0 & 0 & 0 \\\ 0 & 0 & 0 & 0 & 0 & 0 \\\ 0 & 0 & -q_{d} & 0 & 0 & q_{d} \end{bmatrix} \end{align} $$ @@ -340,7 +340,7 @@ We can also put constraints on the input deviations. As the derivative of steeri $$ \begin{align} -\dot{u}_{min} < \dot{u} < \dot{u}_{max} +\dot u_{min} < \dot u < \dot u_{max} \end{align} $$ @@ -348,7 +348,7 @@ We discretize $\dot{u}$ as $\left(u_{k} - u_{k-1}\right)/\text{d}t$ and multiply $$ \begin{align} -\dot{u}_{min}\text{d}t < u_{k} - u_{k-1} < \dot{u}_{max}\text{d}t +\dot u_{min}\text{d}t < u_{k} - u_{k-1} < \dot u_{max}\text{d}t \end{align} $$ @@ -356,8 +356,8 @@ Along the prediction or control horizon, i.e for setting $n=3$ $$ \begin{align} -\dot{u}_{min}\text{d}t < u_{1} - u_{0} < \dot{u}_{max}\text{d}t \\ -\dot{u}_{min}\text{d}t < u_{2} - u_{1} < \dot{u}_{max}\text{d}t +\dot u_{min}\text{d}t < u_{1} - u_{0} < \dot u_{max}\text{d}t \\\ +\dot u_{min}\text{d}t < u_{2} - u_{1} < \dot u_{max}\text{d}t \end{align} $$ @@ -365,10 +365,10 @@ and aligning the inequality signs $$ \begin{align} -u_{1} - u_{0} &< \dot{u}_{max}\text{d}t \\ + -u_{1} + u_{0} &< -\dot{u}_{min}\text{d}t \\ -u_{2} - u_{1} &< \dot{u}_{max}\text{d}t \\ + -u_{2} + u_{1} &< - \dot{u}_{min}\text{d}t +u_{1} - u_{0} &< \dot u_{max}\text{d}t \\\ + +u_{1} + u_{0} &< -\dot u_{min}\text{d}t \\\ +u_{2} - u_{1} &< \dot u_{max}\text{d}t \\\ + +u_{2} + u_{1} &< - \dot u_{min}\text{d}t \end{align} $$ @@ -384,6 +384,6 @@ Thus, putting this inequality to fit the form above, the constraints against $\d $$ \begin{align} -\begin{bmatrix} -1 & 1 & 0 \\ 1 & -1 & 0 \\ 0 & -1 & 1 \\ 0 & 1 & -1 \end{bmatrix}\begin{bmatrix} u_{0} \\ u_{1} \\ u_{2} \end{bmatrix} \leq \begin{bmatrix} \dot{u}_{max}\text{d}t \\ -\dot{u}_{min}\text{d}t \\ \dot{u}_{max}\text{d}t \\ -\dot{u}_{min}\text{d}t \end{bmatrix} +\begin{bmatrix} -1 & 1 & 0 \\\ 1 & -1 & 0 \\\ 0 & -1 & 1 \\\ 0 & 1 & -1 \end{bmatrix}\begin{bmatrix} u_{0} \\\ u_{1} \\\ u_{2} \end{bmatrix} \leq \begin{bmatrix} \dot u_{max}\text{d}t \\\ -\dot u_{min}\text{d}t \\\ \dot u_{max}\text{d}t \\\ -\dot u_{min}\text{d}t \end{bmatrix} \end{align} $$ From badd9496b011aa2480023776222e092f7a368123 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Mon, 1 Apr 2024 07:27:08 +0900 Subject: [PATCH 24/56] refactor(dynamic_obstacle_stop): change log level for processing time (#6716) change log level for processing time Signed-off-by: kyoichi-sugahara --- .../src/scene_dynamic_obstacle_stop.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp index 82a6af3c3f518..11ec540e3980f 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp @@ -121,7 +121,7 @@ bool DynamicObstacleStopModule::modifyPathVelocity(PathWithLaneId * path, StopRe } const auto total_time_us = stopwatch.toc(); - RCLCPP_INFO( + RCLCPP_DEBUG( logger_, "Total time = %2.2fus\n\tpreprocessing = %2.2fus\n\tfootprints = " "%2.2fus\n\tcollisions = %2.2fus\n", From 7869149a282cb01b041c043a352e2eb18a64d185 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 1 Apr 2024 11:24:51 +0900 Subject: [PATCH 25/56] feat(default_ad_api): add dynamic_obstacle_stop velocity factor topic (#6712) add dynamic_obstacle_stop velocity factor to default ad_api --- system/default_ad_api/src/planning.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/system/default_ad_api/src/planning.cpp b/system/default_ad_api/src/planning.cpp index ed2dcee92eb2b..887e1167a7c3e 100644 --- a/system/default_ad_api/src/planning.cpp +++ b/system/default_ad_api/src/planning.cpp @@ -74,6 +74,7 @@ PlanningNode::PlanningNode(const rclcpp::NodeOptions & options) : Node("planning "/planning/velocity_factors/blind_spot", "/planning/velocity_factors/crosswalk", "/planning/velocity_factors/detection_area", + "/planning/velocity_factors/dynamic_obstacle_stop", "/planning/velocity_factors/intersection", "/planning/velocity_factors/merge_from_private", "/planning/velocity_factors/no_stopping_area", From d49680db9da7fb7c207539b24e426d93a067995a Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Mon, 1 Apr 2024 13:07:28 +0900 Subject: [PATCH 26/56] feat(default_ad_api): release adapi v1.2.0 (#6694) Signed-off-by: Takagi, Isamu --- system/default_ad_api/src/interface.cpp | 2 +- system/default_ad_api/test/node/interface_version.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/system/default_ad_api/src/interface.cpp b/system/default_ad_api/src/interface.cpp index 0b90e1c4c79a7..506a4aa8bf5eb 100644 --- a/system/default_ad_api/src/interface.cpp +++ b/system/default_ad_api/src/interface.cpp @@ -21,7 +21,7 @@ InterfaceNode::InterfaceNode(const rclcpp::NodeOptions & options) : Node("interf { const auto on_interface_version = [](auto, auto res) { res->major = 1; - res->minor = 1; + res->minor = 2; res->patch = 0; }; diff --git a/system/default_ad_api/test/node/interface_version.py b/system/default_ad_api/test/node/interface_version.py index 4694f3af642ce..ccfa3e1101185 100644 --- a/system/default_ad_api/test/node/interface_version.py +++ b/system/default_ad_api/test/node/interface_version.py @@ -30,7 +30,7 @@ if response.major != 1: exit(1) -if response.minor != 1: +if response.minor != 2: exit(1) if response.patch != 0: exit(1) From 0836cfb53b5d4ce2c0300c0ec7e9400e18de83fb Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 1 Apr 2024 15:04:41 +0900 Subject: [PATCH 27/56] 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 28/56] 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 29/56] 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 30/56] 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 31/56] 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=-@5D
lec?}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 32/56] 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 33/56] 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 34/56] 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 35/56] 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 36/56] 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 37/56] 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 38/56] 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 39/56] 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 40/56] 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 41/56] 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 42/56] 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 43/56] 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 44/56] 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 45/56] 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 46/56] 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 47/56] 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 48/56] 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 49/56] 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 50/56] 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 51/56] 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 52/56] 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 53/56] 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 54/56] 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 55/56] 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 56/56] 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);