From a1f354d6f2d3c935ef0437c2067674e1f6251850 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 <129915538+TaikiYamada4@users.noreply.github.com> Date: Wed, 6 Dec 2023 15:25:57 +0900 Subject: [PATCH 01/87] fix(ekf_localizer): correct the calculation of delay_step in updateMeasurementPose/Twist (#5691) * Added X_delay_times_ to obtain the accumulated lap times of the timer callback. Added find_closest_index function to easily use the X_delay_times_. Signed-off-by: TaikiYamada4 * Added a concept/variable of accumulated_delay_time_ and store every lap time of timer callback. The delay_step will be calculated from it, and the bug of calculating delay_step should be gone. Besides, removed dt in measurementUpdatePose/Twist since it is not needed. Signed-off-by: TaikiYamada4 * Fixed dt to ekf_dt_ in predictUpdateFrequency() Signed-off-by: TaikiYamada4 * Removed temporary debug stuff Signed-off-by: TaikiYamada4 * style(pre-commit): autofix * Fixed code style pointed out from pre-commit.ci Signed-off-by: TaikiYamada4 * style(pre-commit): autofix * Fixed typo Signed-off-by: TaikiYamada4 * Removed variable ekf_rate_ which is currently unused. Added warnings when the ekf_dt_ is too large. Signed-off-by: TaikiYamada4 * style(pre-commit): autofix * Changed threshold of delay time so that to look the most last (or largest) value of accumulated_delay_times_ Signed-off-by: TaikiYamada4 * Correct the warning messages of diag_info to look up the last (or largest) value of accumulated_delay_times_ Signed-off-by: TaikiYamada4 * style(pre-commit): autofix --------- Signed-off-by: TaikiYamada4 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../include/ekf_localizer/ekf_localizer.hpp | 1 - .../include/ekf_localizer/ekf_module.hpp | 9 ++- .../include/ekf_localizer/warning_message.hpp | 5 +- .../ekf_localizer/src/ekf_localizer.cpp | 25 +++++--- localization/ekf_localizer/src/ekf_module.cpp | 63 ++++++++++++++++--- .../ekf_localizer/src/warning_message.cpp | 14 ++--- .../test/test_warning_message.cpp | 8 +-- 7 files changed, 91 insertions(+), 34 deletions(-) diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index e2ffff2195645..ba18b7dadd599 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -155,7 +155,6 @@ class EKFLocalizer : public rclcpp::Node const HyperParameters params_; - double ekf_rate_; double ekf_dt_; /* process noise variance for discrete model */ diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp index 873060c75fcfc..e88a59ffdfab9 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp @@ -30,6 +30,7 @@ #include #include +#include struct EKFDiagnosticInfo { @@ -76,12 +77,15 @@ class EKFModule std::array getCurrentPoseCovariance() const; std::array getCurrentTwistCovariance() const; + size_t find_closest_delay_time_index(double target_value) const; + void accumulate_delay_time(const double dt); + void predictWithDelay(const double dt); bool measurementUpdatePose( - const PoseWithCovariance & pose, const double dt, const rclcpp::Time & t_curr, + const PoseWithCovariance & pose, const rclcpp::Time & t_curr, EKFDiagnosticInfo & pose_diag_info); bool measurementUpdateTwist( - const TwistWithCovariance & twist, const double dt, const rclcpp::Time & t_curr, + const TwistWithCovariance & twist, const rclcpp::Time & t_curr, EKFDiagnosticInfo & twist_diag_info); geometry_msgs::msg::PoseWithCovarianceStamped compensatePoseWithZDelay( const PoseWithCovariance & pose, const double delay_time); @@ -91,6 +95,7 @@ class EKFModule std::shared_ptr warning_; const int dim_x_; + std::vector accumulated_delay_times_; const HyperParameters params_; }; diff --git a/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp b/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp index f6c664eb26451..e1eafdc6f7948 100644 --- a/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp @@ -17,10 +17,9 @@ #include -std::string poseDelayStepWarningMessage( - const double delay_time, const int extend_state_step, const double ekf_dt); +std::string poseDelayStepWarningMessage(const double delay_time, const double delay_time_threshold); std::string twistDelayStepWarningMessage( - const double delay_time, const int extend_state_step, const double ekf_dt); + const double delay_time, const double delay_time_threshold); std::string poseDelayTimeWarningMessage(const double delay_time); std::string twistDelayTimeWarningMessage(const double delay_time); std::string mahalanobisWarningMessage(const double distance, const double max_distance); diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 5dd78a00f2fbd..a3d2f52a4058c 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -44,7 +44,6 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti : rclcpp::Node(node_name, node_options), warning_(std::make_shared(this)), params_(this), - ekf_rate_(params_.ekf_rate), ekf_dt_(params_.ekf_dt), pose_queue_(params_.pose_smoothing_steps), twist_queue_(params_.twist_smoothing_steps) @@ -109,9 +108,22 @@ void EKFLocalizer::updatePredictFrequency() if (get_clock()->now() < *last_predict_time_) { warning_->warn("Detected jump back in time"); } else { - ekf_rate_ = 1.0 / (get_clock()->now() - *last_predict_time_).seconds(); - DEBUG_INFO(get_logger(), "[EKF] update ekf_rate_ to %f hz", ekf_rate_); - ekf_dt_ = 1.0 / std::max(ekf_rate_, 0.1); + /* Measure dt */ + ekf_dt_ = (get_clock()->now() - *last_predict_time_).seconds(); + DEBUG_INFO( + get_logger(), "[EKF] update ekf_dt_ to %f seconds (= %f hz)", ekf_dt_, 1 / ekf_dt_); + + if (ekf_dt_ > 10.0) { + ekf_dt_ = 10.0; + RCLCPP_WARN( + get_logger(), "Large ekf_dt_ detected!! (%f sec) Capped to 10.0 seconds", ekf_dt_); + } else if (ekf_dt_ > params_.pose_smoothing_steps / params_.ekf_rate) { + RCLCPP_WARN( + get_logger(), "EKF period may be too slow to finish pose smoothing!! (%f sec) ", ekf_dt_); + } + + /* Register dt and accumulate time delay */ + ekf_module_->accumulate_delay_time(ekf_dt_); /* Update discrete proc_cov*/ proc_cov_vx_d_ = std::pow(params_.proc_stddev_vx_c * ekf_dt_, 2.0); @@ -165,7 +177,7 @@ void EKFLocalizer::timerCallback() const size_t n = pose_queue_.size(); for (size_t i = 0; i < n; ++i) { const auto pose = pose_queue_.pop_increment_age(); - bool is_updated = ekf_module_->measurementUpdatePose(*pose, ekf_dt_, t_curr, pose_diag_info_); + bool is_updated = ekf_module_->measurementUpdatePose(*pose, t_curr, pose_diag_info_); if (is_updated) { pose_is_updated = true; @@ -200,8 +212,7 @@ void EKFLocalizer::timerCallback() const size_t n = twist_queue_.size(); for (size_t i = 0; i < n; ++i) { const auto twist = twist_queue_.pop_increment_age(); - bool is_updated = - ekf_module_->measurementUpdateTwist(*twist, ekf_dt_, t_curr, twist_diag_info_); + bool is_updated = ekf_module_->measurementUpdateTwist(*twist, t_curr, twist_diag_info_); if (is_updated) { twist_is_updated = true; } diff --git a/localization/ekf_localizer/src/ekf_module.cpp b/localization/ekf_localizer/src/ekf_module.cpp index 0a5e3c98c96c8..10926b04507a0 100644 --- a/localization/ekf_localizer/src/ekf_module.cpp +++ b/localization/ekf_localizer/src/ekf_module.cpp @@ -38,6 +38,7 @@ EKFModule::EKFModule(std::shared_ptr warning, const HyperParameters params) : warning_(std::move(warning)), dim_x_(6), // x, y, yaw, yaw_bias, vx, wz + accumulated_delay_times_(params.extend_state_step, 1.0E15), params_(params) { Eigen::MatrixXd X = Eigen::MatrixXd::Zero(dim_x_, 1); @@ -131,6 +132,48 @@ double EKFModule::getYawBias() const return kalman_filter_.getLatestX()(IDX::YAWB); } +size_t EKFModule::find_closest_delay_time_index(double target_value) const +{ + // If target_value is too large, return last index + 1 + if (target_value > accumulated_delay_times_.back()) { + return accumulated_delay_times_.size(); + } + + auto lower = std::lower_bound( + accumulated_delay_times_.begin(), accumulated_delay_times_.end(), target_value); + + // If the lower bound is the first element, return its index. + // If the lower bound is beyond the last element, return the last index. + // If else, take the closest element. + if (lower == accumulated_delay_times_.begin()) { + return 0; + } else if (lower == accumulated_delay_times_.end()) { + return accumulated_delay_times_.size() - 1; + } else { + // Compare the target with the lower bound and the previous element. + auto prev = lower - 1; + bool is_closer_to_prev = (target_value - *prev) < (*lower - target_value); + + // Return the index of the closer element. + return is_closer_to_prev ? std::distance(accumulated_delay_times_.begin(), prev) + : std::distance(accumulated_delay_times_.begin(), lower); + } +} + +void EKFModule::accumulate_delay_time(const double dt) +{ + // Shift the delay times to the right. + std::copy_backward( + accumulated_delay_times_.begin(), accumulated_delay_times_.end() - 1, + accumulated_delay_times_.end()); + + // Add the new delay time to all elements. + accumulated_delay_times_.front() = 0.0; + for (auto & delay_time : accumulated_delay_times_) { + delay_time += dt; + } +} + void EKFModule::predictWithDelay(const double dt) { const Eigen::MatrixXd X_curr = kalman_filter_.getLatestX(); @@ -147,8 +190,7 @@ void EKFModule::predictWithDelay(const double dt) } bool EKFModule::measurementUpdatePose( - const PoseWithCovariance & pose, const double dt, const rclcpp::Time & t_curr, - EKFDiagnosticInfo & pose_diag_info) + const PoseWithCovariance & pose, const rclcpp::Time & t_curr, EKFDiagnosticInfo & pose_diag_info) { if (pose.header.frame_id != params_.pose_frame_id) { warning_->warnThrottle( @@ -170,14 +212,15 @@ bool EKFModule::measurementUpdatePose( delay_time = std::max(delay_time, 0.0); - const int delay_step = std::roundf(delay_time / dt); + const int delay_step = static_cast(find_closest_delay_time_index(delay_time)); pose_diag_info.delay_time = std::max(delay_time, pose_diag_info.delay_time); - pose_diag_info.delay_time_threshold = params_.extend_state_step * dt; + pose_diag_info.delay_time_threshold = accumulated_delay_times_.back(); if (delay_step >= params_.extend_state_step) { pose_diag_info.is_passed_delay_gate = false; warning_->warnThrottle( - poseDelayStepWarningMessage(delay_time, params_.extend_state_step, dt), 2000); + poseDelayStepWarningMessage(pose_diag_info.delay_time, pose_diag_info.delay_time_threshold), + 2000); return false; } @@ -243,7 +286,7 @@ geometry_msgs::msg::PoseWithCovarianceStamped EKFModule::compensatePoseWithZDela } bool EKFModule::measurementUpdateTwist( - const TwistWithCovariance & twist, const double dt, const rclcpp::Time & t_curr, + const TwistWithCovariance & twist, const rclcpp::Time & t_curr, EKFDiagnosticInfo & twist_diag_info) { if (twist.header.frame_id != "base_link") { @@ -262,14 +305,16 @@ bool EKFModule::measurementUpdateTwist( } delay_time = std::max(delay_time, 0.0); - const int delay_step = std::roundf(delay_time / dt); + const int delay_step = static_cast(find_closest_delay_time_index(delay_time)); twist_diag_info.delay_time = std::max(delay_time, twist_diag_info.delay_time); - twist_diag_info.delay_time_threshold = params_.extend_state_step * dt; + twist_diag_info.delay_time_threshold = accumulated_delay_times_.back(); if (delay_step >= params_.extend_state_step) { twist_diag_info.is_passed_delay_gate = false; warning_->warnThrottle( - twistDelayStepWarningMessage(delay_time, params_.extend_state_step, dt), 2000); + twistDelayStepWarningMessage( + twist_diag_info.delay_time, twist_diag_info.delay_time_threshold), + 2000); return false; } diff --git a/localization/ekf_localizer/src/warning_message.cpp b/localization/ekf_localizer/src/warning_message.cpp index 9a7bbf47a94eb..c69f30b2d6601 100644 --- a/localization/ekf_localizer/src/warning_message.cpp +++ b/localization/ekf_localizer/src/warning_message.cpp @@ -18,22 +18,20 @@ #include -std::string poseDelayStepWarningMessage( - const double delay_time, const int extend_state_step, const double ekf_dt) +std::string poseDelayStepWarningMessage(const double delay_time, const double delay_time_threshold) { const std::string s = "Pose delay exceeds the compensation limit, ignored. " - "delay: {:.3f}[s], limit = extend_state_step * ekf_dt : {:.3f}[s]"; - return fmt::format(s, delay_time, extend_state_step * ekf_dt); + "delay: {:.3f}[s], limit: {:.3f}[s]"; + return fmt::format(s, delay_time, delay_time_threshold); } -std::string twistDelayStepWarningMessage( - const double delay_time, const int extend_state_step, const double ekf_dt) +std::string twistDelayStepWarningMessage(const double delay_time, const double delay_time_threshold) { const std::string s = "Twist delay exceeds the compensation limit, ignored. " - "delay: {:.3f}[s], limit = extend_state_step * ekf_dt : {:.3f}[s]"; - return fmt::format(s, delay_time, extend_state_step * ekf_dt); + "delay: {:.3f}[s], limit: {:.3f}[s]"; + return fmt::format(s, delay_time, delay_time_threshold); } std::string poseDelayTimeWarningMessage(const double delay_time) diff --git a/localization/ekf_localizer/test/test_warning_message.cpp b/localization/ekf_localizer/test/test_warning_message.cpp index b4a05afa844dc..2069969e0ae5e 100644 --- a/localization/ekf_localizer/test/test_warning_message.cpp +++ b/localization/ekf_localizer/test/test_warning_message.cpp @@ -21,17 +21,17 @@ TEST(PoseDelayStepWarningMessage, SmokeTest) { EXPECT_STREQ( - poseDelayStepWarningMessage(6.0, 2, 2.0).c_str(), + poseDelayStepWarningMessage(6.0, 4.0).c_str(), "Pose delay exceeds the compensation limit, ignored. " - "delay: 6.000[s], limit = extend_state_step * ekf_dt : 4.000[s]"); + "delay: 6.000[s], limit: 4.000[s]"); } TEST(TwistDelayStepWarningMessage, SmokeTest) { EXPECT_STREQ( - twistDelayStepWarningMessage(10.0, 3, 2.0).c_str(), + twistDelayStepWarningMessage(10.0, 6.0).c_str(), "Twist delay exceeds the compensation limit, ignored. " - "delay: 10.000[s], limit = extend_state_step * ekf_dt : 6.000[s]"); + "delay: 10.000[s], limit: 6.000[s]"); } TEST(PoseDelayTimeWarningMessage, SmokeTest) From ea958a2ebadff16c154fe92637cbd4275fd9ecca Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Wed, 6 Dec 2023 19:45:39 +0900 Subject: [PATCH 02/87] fix(start_planner): check safety only when waiting approval (#5792) 1. The `updateData()` function now sets `status_.is_safe_dynamic_objects` to true when `requiresDynamicObjectsCollisionDetection()` returns false. 2. The `isExecutionReady()` function now checks for dynamic object collisions only if `requiresDynamicObjectsCollisionDetection()` returns true and `isWaitingApproval()` also returns true. This change ensures that dynamic object collision detection is performed only when necessary and approval is pending. Signed-off-by: kyoichi-sugahara --- .../src/scene_module/start_planner/start_planner_module.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 7bbee7fe0a10c..23a981c4920b4 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -146,6 +146,8 @@ void StartPlannerModule::updateData() if (requiresDynamicObjectsCollisionDetection()) { status_.is_safe_dynamic_objects = !hasCollisionWithDynamicObjects(); + } else { + status_.is_safe_dynamic_objects = true; } } @@ -279,7 +281,7 @@ bool StartPlannerModule::isExecutionReady() const is_safe = false; } - if (requiresDynamicObjectsCollisionDetection()) { + if (requiresDynamicObjectsCollisionDetection() && isWaitingApproval()) { is_safe = !hasCollisionWithDynamicObjects(); } From ab4a3eb34b3df4bcc7d8dfac6ef489459dbb87a7 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 7 Dec 2023 01:04:35 +0900 Subject: [PATCH 03/87] feat(start_planner): add surround moving obstacle check (#5782) * feat(start_planner): add surround moving obstacle check This commit introduces a new feature in the start_planner module for checking surrounding moving obstacles. - It adds parameters to specify the search radius and threshold velocity for moving obstacles, along with flags to indicate which types of objects should be checked. - The `noMovingObjectsAround` function has been added to filter dynamic objects within a certain radius based on their velocity. - If no moving objects are detected, the function returns true; otherwise, it returns false. - This feature enhances the safety of the start_planner by ensuring that the path can't be approved while surrond moving obstacles exist. --------- Signed-off-by: kyoichi-sugahara --- .../start_planner/start_planner.param.yaml | 14 +++++++++ .../start_planner/start_planner_module.hpp | 11 +++++++ .../start_planner_parameters.hpp | 6 ++++ .../scene_module/start_planner/manager.cpp | 29 +++++++++++++++++ .../start_planner/start_planner_module.cpp | 31 +++++++++++++++---- .../path_safety_checker/objects_filtering.hpp | 13 ++++++++ .../path_safety_checker/objects_filtering.cpp | 21 +++++++++++++ 7 files changed, 119 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml b/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml index 4bcb847d1280c..514d61e225ecd 100644 --- a/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml +++ b/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml @@ -138,6 +138,20 @@ backward_path_length: 30.0 forward_path_length: 100.0 + surround_moving_obstacle_check: + search_radius: 10.0 + th_moving_obstacle_velocity: 1.0 + # ObjectTypesToCheck + object_types_to_check: + check_car: true + check_truck: true + check_bus: true + check_trailer: true + check_bicycle: true + check_motorcycle: true + check_pedestrian: true + check_unknown: false + # debug debug: print_debug_info: false diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index e3249d7ffd311..f70effb7cf186 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -137,6 +137,17 @@ class StartPlannerModule : public SceneModuleInterface void initializeSafetyCheckParameters(); bool requiresDynamicObjectsCollisionDetection() const; + + /** + * @brief Check if there are no moving objects around within a certain radius. + * + * This function filters the dynamic objects within a certain radius and then filters them by + * their velocity. If there are no moving objects around, it returns true. Otherwise, it returns + * false. + * + * @return True if there are no moving objects around. False otherwise. + */ + bool noMovingObjectsAround() const; bool receivedNewRoute() const; bool isModuleRunning() const; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp index 46b72cacac651..cbde2b514366d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp @@ -93,6 +93,12 @@ struct StartPlannerParameters utils::path_safety_checker::ObjectsFilteringParams objects_filtering_params{}; utils::path_safety_checker::SafetyCheckParams safety_check_params{}; + // surround moving obstacle check + double search_radius{0.0}; + double th_moving_obstacle_velocity{0.0}; + behavior_path_planner::utils::path_safety_checker::ObjectTypesToCheck + surround_moving_obstacles_type_to_check{}; + bool print_debug_info{false}; }; diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp index e379fcfa03a80..14660396062aa 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp @@ -273,6 +273,35 @@ void StartPlannerModuleManager::init(rclcpp::Node * node) node->declare_parameter(rss_ns + "longitudinal_velocity_delta_time"); } + // surround moving obstacle check + std::string surround_moving_obstacle_check_ns = ns + "surround_moving_obstacle_check."; + { + p.search_radius = + node->declare_parameter(surround_moving_obstacle_check_ns + "search_radius"); + p.th_moving_obstacle_velocity = node->declare_parameter( + surround_moving_obstacle_check_ns + "th_moving_obstacle_velocity"); + // ObjectTypesToCheck + std::string obj_types_ns = surround_moving_obstacle_check_ns + "object_types_to_check."; + { + p.surround_moving_obstacles_type_to_check.check_car = + node->declare_parameter(obj_types_ns + "check_car"); + p.surround_moving_obstacles_type_to_check.check_truck = + node->declare_parameter(obj_types_ns + "check_truck"); + p.surround_moving_obstacles_type_to_check.check_bus = + node->declare_parameter(obj_types_ns + "check_bus"); + p.surround_moving_obstacles_type_to_check.check_trailer = + node->declare_parameter(obj_types_ns + "check_trailer"); + p.surround_moving_obstacles_type_to_check.check_unknown = + node->declare_parameter(obj_types_ns + "check_unknown"); + p.surround_moving_obstacles_type_to_check.check_bicycle = + node->declare_parameter(obj_types_ns + "check_bicycle"); + p.surround_moving_obstacles_type_to_check.check_motorcycle = + node->declare_parameter(obj_types_ns + "check_motorcycle"); + p.surround_moving_obstacles_type_to_check.check_pedestrian = + node->declare_parameter(obj_types_ns + "check_pedestrian"); + } + } + // debug std::string debug_ns = ns + "debug."; { diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 23a981c4920b4..7bede9192d35f 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -181,6 +181,21 @@ bool StartPlannerModule::requiresDynamicObjectsCollisionDetection() const return parameters_->safety_check_params.enable_safety_check && status_.driving_forward; } +bool StartPlannerModule::noMovingObjectsAround() const +{ + auto dynamic_objects = *(planner_data_->dynamic_object); + utils::path_safety_checker::filterObjectsWithinRadius( + dynamic_objects, planner_data_->self_odometry->pose.pose.position, parameters_->search_radius); + utils::path_safety_checker::filterObjectsByClass( + dynamic_objects, parameters_->surround_moving_obstacles_type_to_check); + const auto filtered_objects = utils::path_safety_checker::filterObjectsByVelocity( + dynamic_objects, parameters_->th_moving_obstacle_velocity, false); + if (!filtered_objects.objects.empty()) { + DEBUG_PRINT("Moving objects exist in the safety check area"); + } + return filtered_objects.objects.empty(); +} + bool StartPlannerModule::hasCollisionWithDynamicObjects() const { // TODO(Sugahara): update path, params for predicted path and so on in this function to avoid @@ -273,20 +288,24 @@ bool StartPlannerModule::isStopped() bool StartPlannerModule::isExecutionReady() const { bool is_safe = true; - // Evaluate safety. The situation is not safe if any of the following conditions are met: // 1. pull out path has not been found - // 2. waiting for approval and there is a collision with dynamic objects + // 2. there is a moving objects around ego + // 3. waiting for approval and there is a collision with dynamic objects if (!status_.found_pull_out_path) { is_safe = false; + } else if (isWaitingApproval()) { + if (!noMovingObjectsAround()) { + is_safe = false; + } else if (requiresDynamicObjectsCollisionDetection() && hasCollisionWithDynamicObjects()) { + is_safe = false; + } } - if (requiresDynamicObjectsCollisionDetection() && isWaitingApproval()) { - is_safe = !hasCollisionWithDynamicObjects(); + if (!is_safe) { + stop_pose_ = planner_data_->self_odometry->pose.pose; } - if (!is_safe) stop_pose_ = planner_data_->self_odometry->pose.pose; - return is_safe; } diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp index 018e6bd2a3d6e..f66f425f1b7fa 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp @@ -134,6 +134,19 @@ void filterObjectsByPosition( const geometry_msgs::msg::Point & current_pose, const double forward_distance, const double backward_distance); +/** + * @brief Filter objects based on their distance from a reference point. + * + * This function filters out objects that are outside a specified radius from a reference point. + * + * @param objects The predicted objects to filter. + * @param reference_point The reference point (e.g., current pose of the ego vehicle). + * @param search_radius The radius within which to retain objects. + */ +void filterObjectsWithinRadius( + PredictedObjects & objects, const geometry_msgs::msg::Point & reference_point, + const double search_radius); + /** * @brief Filters the provided objects based on their classification. * diff --git a/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp b/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp index 84c02b3b325de..188c50993e4ae 100644 --- a/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp @@ -44,6 +44,15 @@ bool position_filter( return (backward_distance < dist_ego_to_obj && dist_ego_to_obj < forward_distance); } + +bool is_within_circle( + const geometry_msgs::msg::Point & object_pos, const geometry_msgs::msg::Point & reference_point, + const double search_radius) +{ + const double dist = + std::hypot(reference_point.x - object_pos.x, reference_point.y - object_pos.y); + return dist < search_radius; +} } // namespace behavior_path_planner::utils::path_safety_checker::filter namespace behavior_path_planner::utils::path_safety_checker @@ -128,6 +137,18 @@ void filterObjectsByPosition( filterObjects(objects, filter); } +void filterObjectsWithinRadius( + PredictedObjects & objects, const geometry_msgs::msg::Point & reference_point, + const double search_radius) +{ + const auto filter = [&](const auto & object) { + return filter::is_within_circle( + object.kinematics.initial_pose_with_covariance.pose.position, reference_point, search_radius); + }; + + filterObjects(objects, filter); +} + void filterObjectsByClass( PredictedObjects & objects, const ObjectTypesToCheck & target_object_types) { From 13d45ae3dd082fdb342b456dacd6abe23ffe1dff Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 7 Dec 2023 10:33:18 +0900 Subject: [PATCH 04/87] refactor(avoidance, avoidance_by_lane_change): separate package (#5790) * refactor(avoidance): separate package Signed-off-by: satoshi-ota * refactor(AbLC): separate package Signed-off-by: satoshi-ota * refactor(bpp): remove separate module Signed-off-by: satoshi-ota * fix(bpp): fix test error Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../CMakeLists.txt | 26 +++ .../config}/avoidance_by_lc.param.yaml | 0 .../data_structs.hpp | 33 ++++ .../interface.hpp | 48 +++++ .../manager.hpp | 52 ++++++ .../scene.hpp} | 10 +- .../package.xml | 36 ++++ .../plugins.xml | 3 + .../src/interface.cpp | 62 ++++++ .../src/manager.cpp | 176 ++++++++++++++++++ .../src/scene.cpp} | 7 +- ...t_behavior_path_planner_node_interface.cpp | 129 +++++++++++++ .../CMakeLists.txt | 29 +++ .../config}/avoidance.param.yaml | 0 .../data_structs.hpp} | 6 +- .../behavior_path_avoidance_module}/debug.hpp | 10 +- .../helper.hpp | 10 +- .../manager.hpp | 10 +- .../behavior_path_avoidance_module/scene.hpp} | 14 +- .../shift_line_generator.hpp | 10 +- .../behavior_path_avoidance_module}/utils.hpp | 10 +- .../package.xml | 53 ++++++ .../plugins.xml | 3 + .../src}/debug.cpp | 2 +- .../src}/manager.cpp | 2 +- .../src/scene.cpp} | 8 +- .../src}/shift_line_generator.cpp | 4 +- .../src}/utils.cpp | 6 +- ...t_behavior_path_planner_node_interface.cpp | 126 +++++++++++++ .../test/test_utils.cpp} | 5 +- planning/behavior_path_planner/CMakeLists.txt | 14 -- .../scene_module/lane_change/interface.hpp | 18 -- .../scene_module/lane_change/manager.hpp | 18 -- .../lane_change/lane_change_module_data.hpp | 11 +- planning/behavior_path_planner/plugins.xml | 2 - .../scene_module/lane_change/interface.cpp | 34 ---- .../src/scene_module/lane_change/manager.cpp | 145 --------------- ...t_behavior_path_planner_node_interface.cpp | 4 - 38 files changed, 832 insertions(+), 304 deletions(-) create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/CMakeLists.txt rename planning/{behavior_path_planner/config/avoidance_by_lc => behavior_path_avoidance_by_lane_change_module/config}/avoidance_by_lc.param.yaml (100%) create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp => behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp} (81%) create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/package.xml create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/plugins.xml create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp rename planning/{behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp => behavior_path_avoidance_by_lane_change_module/src/scene.cpp} (97%) create mode 100644 planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp create mode 100644 planning/behavior_path_avoidance_module/CMakeLists.txt rename planning/{behavior_path_planner/config/avoidance => behavior_path_avoidance_module/config}/avoidance.param.yaml (100%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp => behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp} (98%) rename planning/{behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance => behavior_path_avoidance_module/include/behavior_path_avoidance_module}/debug.hpp (90%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/avoidance => behavior_path_avoidance_module/include/behavior_path_avoidance_module}/helper.hpp (96%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/avoidance => behavior_path_avoidance_module/include/behavior_path_avoidance_module}/manager.hpp (80%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp => behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp} (96%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/avoidance => behavior_path_avoidance_module/include/behavior_path_avoidance_module}/shift_line_generator.hpp (95%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/avoidance => behavior_path_avoidance_module/include/behavior_path_avoidance_module}/utils.hpp (96%) create mode 100644 planning/behavior_path_avoidance_module/package.xml create mode 100644 planning/behavior_path_avoidance_module/plugins.xml rename planning/{behavior_path_planner/src/marker_utils/avoidance => behavior_path_avoidance_module/src}/debug.cpp (99%) rename planning/{behavior_path_planner/src/scene_module/avoidance => behavior_path_avoidance_module/src}/manager.cpp (99%) rename planning/{behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp => behavior_path_avoidance_module/src/scene.cpp} (99%) rename planning/{behavior_path_planner/src/utils/avoidance => behavior_path_avoidance_module/src}/shift_line_generator.cpp (99%) rename planning/{behavior_path_planner/src/utils/avoidance => behavior_path_avoidance_module/src}/utils.cpp (99%) create mode 100644 planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp rename planning/{behavior_path_planner/test/test_avoidance_utils.cpp => behavior_path_avoidance_module/test/test_utils.cpp} (92%) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/CMakeLists.txt b/planning/behavior_path_avoidance_by_lane_change_module/CMakeLists.txt new file mode 100644 index 0000000000000..bca909c7cef7e --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/CMakeLists.txt @@ -0,0 +1,26 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_path_avoidance_by_lane_change_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_path_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/scene.cpp + src/manager.cpp + src/interface.cpp +) + +if(BUILD_TESTING) + ament_add_ros_isolated_gmock(test_${PROJECT_NAME} + test/test_behavior_path_planner_node_interface.cpp + ) + + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) + + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/config/avoidance_by_lc/avoidance_by_lc.param.yaml b/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lc.param.yaml similarity index 100% rename from planning/behavior_path_planner/config/avoidance_by_lc/avoidance_by_lc.param.yaml rename to planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lc.param.yaml diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp new file mode 100644 index 0000000000000..e177244930da6 --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp @@ -0,0 +1,33 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__DATA_STRUCTS_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__DATA_STRUCTS_HPP_ + +#include "behavior_path_avoidance_module/data_structs.hpp" + +#include + +namespace behavior_path_planner +{ +struct AvoidanceByLCParameters : public AvoidanceParameters +{ + // execute only when the target object longitudinal distance is larger than this param. + double execute_object_longitudinal_margin{0.0}; + + // execute only when lane change end point is before the object. + bool execute_only_when_lane_change_finish_before_object{false}; +}; +} // namespace behavior_path_planner + +#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp new file mode 100644 index 0000000000000..0bc08ccd400ca --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp @@ -0,0 +1,48 @@ +// 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 BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__INTERFACE_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__INTERFACE_HPP_ + +#include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" +#include "behavior_path_avoidance_by_lane_change_module/scene.hpp" +#include "behavior_path_planner/scene_module/lane_change/interface.hpp" + +#include + +#include +#include +#include + +namespace behavior_path_planner +{ +class AvoidanceByLaneChangeInterface : public LaneChangeInterface +{ +public: + AvoidanceByLaneChangeInterface( + const std::string & name, rclcpp::Node & node, + const std::shared_ptr & parameters, + const std::shared_ptr & avoidance_by_lane_change_parameters, + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map); + + bool isExecutionRequested() const override; + +protected: + void updateRTCStatus(const double start_distance, const double finish_distance) override; +}; +} // namespace behavior_path_planner + +#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__INTERFACE_HPP_ diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp new file mode 100644 index 0000000000000..b1beae9c6fc03 --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp @@ -0,0 +1,52 @@ +// 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 BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__MANAGER_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__MANAGER_HPP_ + +#include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" +#include "behavior_path_avoidance_by_lane_change_module/interface.hpp" +#include "behavior_path_planner/scene_module/lane_change/manager.hpp" + +#include + +#include +#include +#include +#include + +namespace behavior_path_planner +{ +using route_handler::Direction; + +class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager +{ +public: + AvoidanceByLaneChangeModuleManager() + : LaneChangeModuleManager( + "avoidance_by_lc", route_handler::Direction::NONE, + LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE) + { + } + + void init(rclcpp::Node * node) override; + + std::unique_ptr createNewSceneModuleInstance() override; + +private: + std::shared_ptr avoidance_parameters_; +}; +} // namespace behavior_path_planner + +#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp similarity index 81% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp rename to planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp index 67fd2c1ba0c77..1e667c207c64f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp @@ -12,18 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__AVOIDANCE_BY_LANE_CHANGE_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__AVOIDANCE_BY_LANE_CHANGE_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_ +#include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" #include "behavior_path_planner/scene_module/lane_change/normal.hpp" #include namespace behavior_path_planner { -using autoware_auto_planning_msgs::msg::PathWithLaneId; -using geometry_msgs::msg::Pose; -using geometry_msgs::msg::Twist; using AvoidanceDebugData = DebugData; class AvoidanceByLaneChange : public NormalLaneChange @@ -56,4 +54,4 @@ class AvoidanceByLaneChange : public NormalLaneChange }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__AVOIDANCE_BY_LANE_CHANGE_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_ diff --git a/planning/behavior_path_avoidance_by_lane_change_module/package.xml b/planning/behavior_path_avoidance_by_lane_change_module/package.xml new file mode 100644 index 0000000000000..3bb32bdf76bf0 --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/package.xml @@ -0,0 +1,36 @@ + + + + behavior_path_avoidance_by_lane_change_module + 0.1.0 + The behavior_path_avoidance_by_lane_change_module package + + Satoshi Ota + Zulfaqar Azmi + Fumiya Watanabe + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + behavior_path_avoidance_module + behavior_path_planner + behavior_path_planner_common + motion_utils + pluginlib + rclcpp + rtc_interface + tier4_autoware_utils + tier4_planning_msgs + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_path_avoidance_by_lane_change_module/plugins.xml b/planning/behavior_path_avoidance_by_lane_change_module/plugins.xml new file mode 100644 index 0000000000000..092d54c096ae9 --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp new file mode 100644 index 0000000000000..2e451461abab7 --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp @@ -0,0 +1,62 @@ +// 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 "behavior_path_avoidance_by_lane_change_module/interface.hpp" + +#include "behavior_path_planner_common/interface/scene_module_interface.hpp" +#include "behavior_path_planner_common/interface/scene_module_visitor.hpp" +#include "behavior_path_planner_common/marker_utils/utils.hpp" + +#include +#include +#include +#include +#include + +namespace behavior_path_planner +{ +AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface( + const std::string & name, rclcpp::Node & node, + const std::shared_ptr & parameters, + const std::shared_ptr & avoidance_by_lane_change_parameters, + const std::unordered_map> & rtc_interface_ptr_map, + std::unordered_map> & + objects_of_interest_marker_interface_ptr_map) +: LaneChangeInterface{ + name, + node, + parameters, + rtc_interface_ptr_map, + objects_of_interest_marker_interface_ptr_map, + std::make_unique(parameters, avoidance_by_lane_change_parameters)} +{ +} + +bool AvoidanceByLaneChangeInterface::isExecutionRequested() const +{ + return module_type_->specialRequiredCheck() && module_type_->isLaneChangeRequired(); +} + +void AvoidanceByLaneChangeInterface::updateRTCStatus( + const double start_distance, const double finish_distance) +{ + const auto direction = std::invoke([&]() -> std::string { + const auto dir = module_type_->getDirection(); + return (dir == Direction::LEFT) ? "left" : "right"; + }); + + rtc_interface_ptr_map_.at(direction)->updateCooperateStatus( + uuid_map_.at(direction), isExecutionReady(), start_distance, finish_distance, clock_->now()); +} +} // namespace behavior_path_planner diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp new file mode 100644 index 0000000000000..61b0a36ae0fb0 --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp @@ -0,0 +1,176 @@ +// 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 "behavior_path_avoidance_by_lane_change_module/manager.hpp" + +#include "tier4_autoware_utils/ros/parameter.hpp" +#include "tier4_autoware_utils/ros/update_param.hpp" + +#include + +#include +#include +#include + +namespace behavior_path_planner +{ + +void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) +{ + using autoware_auto_perception_msgs::msg::ObjectClassification; + using tier4_autoware_utils::getOrDeclareParameter; + + // init manager interface + initInterface(node, {"left", "right"}); + + // init lane change manager + LaneChangeModuleManager::init(node); + + AvoidanceByLCParameters p{}; + // unique parameters + { + const std::string ns = "avoidance_by_lane_change."; + p.execute_object_longitudinal_margin = + getOrDeclareParameter(*node, ns + "execute_object_longitudinal_margin"); + p.execute_only_when_lane_change_finish_before_object = + getOrDeclareParameter(*node, ns + "execute_only_when_lane_change_finish_before_object"); + } + + // general params + { + const std::string ns = "avoidance."; + p.resample_interval_for_planning = + getOrDeclareParameter(*node, ns + "resample_interval_for_planning"); + p.resample_interval_for_output = + getOrDeclareParameter(*node, ns + "resample_interval_for_output"); + } + + // target object + { + const auto get_object_param = [&](std::string && ns) { + ObjectParameter param{}; + param.execute_num = getOrDeclareParameter(*node, ns + "execute_num"); + param.moving_speed_threshold = + getOrDeclareParameter(*node, ns + "moving_speed_threshold"); + param.moving_time_threshold = + getOrDeclareParameter(*node, ns + "moving_time_threshold"); + param.max_expand_ratio = getOrDeclareParameter(*node, ns + "max_expand_ratio"); + param.envelope_buffer_margin = + getOrDeclareParameter(*node, ns + "envelope_buffer_margin"); + param.avoid_margin_lateral = + getOrDeclareParameter(*node, ns + "avoid_margin_lateral"); + param.safety_buffer_lateral = + getOrDeclareParameter(*node, ns + "safety_buffer_lateral"); + return param; + }; + + const std::string ns = "avoidance_by_lane_change.target_object."; + p.object_parameters.emplace( + ObjectClassification::MOTORCYCLE, get_object_param(ns + "motorcycle.")); + p.object_parameters.emplace(ObjectClassification::CAR, get_object_param(ns + "car.")); + p.object_parameters.emplace(ObjectClassification::TRUCK, get_object_param(ns + "truck.")); + p.object_parameters.emplace(ObjectClassification::TRAILER, get_object_param(ns + "trailer.")); + p.object_parameters.emplace(ObjectClassification::BUS, get_object_param(ns + "bus.")); + p.object_parameters.emplace( + ObjectClassification::PEDESTRIAN, get_object_param(ns + "pedestrian.")); + p.object_parameters.emplace(ObjectClassification::BICYCLE, get_object_param(ns + "bicycle.")); + p.object_parameters.emplace(ObjectClassification::UNKNOWN, get_object_param(ns + "unknown.")); + + p.lower_distance_for_polygon_expansion = + getOrDeclareParameter(*node, ns + "lower_distance_for_polygon_expansion"); + p.upper_distance_for_polygon_expansion = + getOrDeclareParameter(*node, ns + "upper_distance_for_polygon_expansion"); + } + + // target filtering + { + const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) { + if (p.object_parameters.count(object_type) == 0) { + return; + } + p.object_parameters.at(object_type).is_avoidance_target = + getOrDeclareParameter(*node, ns); + }; + + const std::string ns = "avoidance.target_filtering."; + set_target_flag(ObjectClassification::CAR, ns + "target_type.car"); + set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck"); + set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer"); + set_target_flag(ObjectClassification::BUS, ns + "target_type.bus"); + set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian"); + set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle"); + set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle"); + set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown"); + + p.object_check_goal_distance = + getOrDeclareParameter(*node, ns + "object_check_goal_distance"); + p.threshold_distance_object_is_on_center = + getOrDeclareParameter(*node, ns + "threshold_distance_object_is_on_center"); + p.object_check_shiftable_ratio = + getOrDeclareParameter(*node, ns + "object_check_shiftable_ratio"); + p.object_check_min_road_shoulder_width = + getOrDeclareParameter(*node, ns + "object_check_min_road_shoulder_width"); + p.object_last_seen_threshold = + getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); + } + + { + const std::string ns = "avoidance.target_filtering.force_avoidance."; + p.enable_force_avoidance_for_stopped_vehicle = + getOrDeclareParameter(*node, ns + "enable"); + p.threshold_time_force_avoidance_for_stopped_vehicle = + getOrDeclareParameter(*node, ns + "time_threshold"); + p.object_ignore_section_traffic_light_in_front_distance = + getOrDeclareParameter(*node, ns + "ignore_area.traffic_light.front_distance"); + p.object_ignore_section_crosswalk_in_front_distance = + getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.front_distance"); + p.object_ignore_section_crosswalk_behind_distance = + getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.behind_distance"); + } + + { + const std::string ns = "avoidance.target_filtering.detection_area."; + p.use_static_detection_area = getOrDeclareParameter(*node, ns + "static"); + p.object_check_min_forward_distance = + getOrDeclareParameter(*node, ns + "min_forward_distance"); + p.object_check_max_forward_distance = + getOrDeclareParameter(*node, ns + "max_forward_distance"); + p.object_check_backward_distance = + getOrDeclareParameter(*node, ns + "backward_distance"); + } + + // safety check + { + const std::string ns = "avoidance.safety_check."; + p.hysteresis_factor_expand_rate = + getOrDeclareParameter(*node, ns + "hysteresis_factor_expand_rate"); + } + + avoidance_parameters_ = std::make_shared(p); +} + +std::unique_ptr +AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance() +{ + return std::make_unique( + name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_); +} + +} // namespace behavior_path_planner + +#include +PLUGINLIB_EXPORT_CLASS( + behavior_path_planner::AvoidanceByLaneChangeModuleManager, + behavior_path_planner::SceneModuleManagerInterface) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp similarity index 97% rename from planning/behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp rename to planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp index befd458153e6e..bfa873d9518ef 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/avoidance_by_lane_change.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -12,15 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp" +#include "behavior_path_avoidance_by_lane_change_module/scene.hpp" -#include "behavior_path_planner/utils/avoidance/utils.hpp" +#include "behavior_path_avoidance_module/utils.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" -#include -#include - #include #include diff --git a/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp new file mode 100644 index 0000000000000..2264669fdcdbe --- /dev/null +++ b/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -0,0 +1,129 @@ +// 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 "ament_index_cpp/get_package_share_directory.hpp" +#include "behavior_path_planner/behavior_path_planner_node.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include + +#include +#include + +using behavior_path_planner::BehaviorPathPlannerNode; +using planning_test_utils::PlanningInterfaceTestManager; + +std::shared_ptr generateTestManager() +{ + auto test_manager = std::make_shared(); + + // set subscriber with topic name: behavior_path_planner → test_node_ + test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); + + // set behavior_path_planner's input topic name(this topic is changed to test node) + test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); + + test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); + + return test_manager; +} + +std::shared_ptr generateNode() +{ + auto node_options = rclcpp::NodeOptions{}; + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto behavior_path_planner_dir = + ament_index_cpp::get_package_share_directory("behavior_path_planner"); + + std::vector module_names; + module_names.emplace_back("behavior_path_planner::AvoidanceByLaneChangeModuleManager"); + + std::vector params; + params.emplace_back("launch_modules", module_names); + node_options.parameter_overrides(params); + + test_utils::updateNodeOptions( + node_options, + {planning_test_utils_dir + "/config/test_common.param.yaml", + planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", + behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", + behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", + ament_index_cpp::get_package_share_directory("behavior_path_planner") + + "/config/lane_change/lane_change.param.yaml", + ament_index_cpp::get_package_share_directory("behavior_path_avoidance_module") + + "/config/avoidance.param.yaml", + ament_index_cpp::get_package_share_directory("behavior_path_avoidance_by_lane_change_module") + + "/config/avoidance_by_lc.param.yaml"}); + + return std::make_shared(node_options); +} + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ + // publish necessary topics from test_manager + test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); + test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); + test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); + test_manager->publishOccupancyGrid( + test_target_node, "behavior_path_planner/input/occupancy_grid_map"); + test_manager->publishLaneDrivingScenario( + test_target_node, "behavior_path_planner/input/scenario"); + test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); + test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); + test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); + test_manager->publishLateralOffset( + test_target_node, "behavior_path_planner/input/lateral_offset"); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) +{ + rclcpp::init(0, nullptr); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty route + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + + rclcpp::shutdown(); +} diff --git a/planning/behavior_path_avoidance_module/CMakeLists.txt b/planning/behavior_path_avoidance_module/CMakeLists.txt new file mode 100644 index 0000000000000..c94591f9bbd30 --- /dev/null +++ b/planning/behavior_path_avoidance_module/CMakeLists.txt @@ -0,0 +1,29 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_path_avoidance_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_path_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/scene.cpp + src/debug.cpp + src/utils.cpp + src/manager.cpp + src/shift_line_generator.cpp +) + +if(BUILD_TESTING) + ament_add_ros_isolated_gmock(test_${PROJECT_NAME} + test/test_utils.cpp + test/test_behavior_path_planner_node_interface.cpp + ) + + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) + + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml similarity index 100% rename from planning/behavior_path_planner/config/avoidance/avoidance.param.yaml rename to planning/behavior_path_avoidance_module/config/avoidance.param.yaml diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp similarity index 98% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp rename to planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp index 68c64ff9b7112..8c45230959c6c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__AVOIDANCE_MODULE_DATA_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__AVOIDANCE_MODULE_DATA_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__DATA_STRUCTS_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__DATA_STRUCTS_HPP_ #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" @@ -622,4 +622,4 @@ struct DebugData } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__AVOIDANCE_MODULE_DATA_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance/debug.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/debug.hpp similarity index 90% rename from planning/behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance/debug.hpp rename to planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/debug.hpp index 12b54a5031041..2bf3158da9ab6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/avoidance/debug.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/debug.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// 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. @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__MARKER_UTILS__AVOIDANCE__DEBUG_HPP_ -#define BEHAVIOR_PATH_PLANNER__MARKER_UTILS__AVOIDANCE__DEBUG_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__DEBUG_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__DEBUG_HPP_ -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" +#include "behavior_path_avoidance_module/data_structs.hpp" #include "behavior_path_planner_common/marker_utils/utils.hpp" #include @@ -78,4 +78,4 @@ std::string toStrInfo(const behavior_path_planner::ShiftLine & sp); std::string toStrInfo(const behavior_path_planner::AvoidLine & ap); -#endif // BEHAVIOR_PATH_PLANNER__MARKER_UTILS__AVOIDANCE__DEBUG_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__DEBUG_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp similarity index 96% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp rename to planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp index 54a38b828e987..6717cefefc9f6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__HELPER_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__HELPER_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__HELPER_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__HELPER_HPP_ -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" -#include "behavior_path_planner/utils/avoidance/utils.hpp" +#include "behavior_path_avoidance_module/data_structs.hpp" +#include "behavior_path_avoidance_module/utils.hpp" #include @@ -331,4 +331,4 @@ class AvoidanceHelper }; } // namespace behavior_path_planner::helper::avoidance -#endif // BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__HELPER_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__HELPER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/manager.hpp similarity index 80% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp rename to planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/manager.hpp index 0fe8bd7efa17b..72cfbe6f0a1ed 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/manager.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/manager.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__AVOIDANCE__MANAGER_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__AVOIDANCE__MANAGER_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__MANAGER_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__MANAGER_HPP_ -#include "behavior_path_planner/scene_module/avoidance/avoidance_module.hpp" -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" +#include "behavior_path_avoidance_module/data_structs.hpp" +#include "behavior_path_avoidance_module/scene.hpp" #include "behavior_path_planner_common/interface/scene_module_manager_interface.hpp" #include @@ -51,4 +51,4 @@ class AvoidanceModuleManager : public SceneModuleManagerInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__AVOIDANCE__MANAGER_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp similarity index 96% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp rename to planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp index b01cb62f22372..6a66b485d1c59 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// 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. @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__AVOIDANCE__AVOIDANCE_MODULE_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__AVOIDANCE__AVOIDANCE_MODULE_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__SCENE_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__SCENE_HPP_ -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" -#include "behavior_path_planner/utils/avoidance/helper.hpp" -#include "behavior_path_planner/utils/avoidance/shift_line_generator.hpp" +#include "behavior_path_avoidance_module/data_structs.hpp" +#include "behavior_path_avoidance_module/helper.hpp" +#include "behavior_path_avoidance_module/shift_line_generator.hpp" #include "behavior_path_planner_common/interface/scene_module_interface.hpp" #include "behavior_path_planner_common/interface/scene_module_visitor.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" @@ -450,4 +450,4 @@ class AvoidanceModule : public SceneModuleInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__AVOIDANCE__AVOIDANCE_MODULE_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__SCENE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/shift_line_generator.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/shift_line_generator.hpp similarity index 95% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/shift_line_generator.hpp rename to planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/shift_line_generator.hpp index 054a6e15ef6bf..edfe9ab9663ce 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/shift_line_generator.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/shift_line_generator.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__SHIFT_LINE_GENERATOR_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__SHIFT_LINE_GENERATOR_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__SHIFT_LINE_GENERATOR_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__SHIFT_LINE_GENERATOR_HPP_ -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" -#include "behavior_path_planner/utils/avoidance/helper.hpp" +#include "behavior_path_avoidance_module/data_structs.hpp" +#include "behavior_path_avoidance_module/helper.hpp" #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -248,4 +248,4 @@ class ShiftLineGenerator } // namespace behavior_path_planner::utils::avoidance -#endif // BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__SHIFT_LINE_GENERATOR_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__SHIFT_LINE_GENERATOR_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp similarity index 96% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp rename to planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp index e7611208962f0..c954ab9022853 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/utils.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// 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. @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__UTILS_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__UTILS_HPP_ +#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__UTILS_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__UTILS_HPP_ -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" +#include "behavior_path_avoidance_module/data_structs.hpp" #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" @@ -180,4 +180,4 @@ double calcDistanceToAvoidStartLine( const std::shared_ptr & parameters); } // namespace behavior_path_planner::utils::avoidance -#endif // BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__UTILS_HPP_ +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__UTILS_HPP_ diff --git a/planning/behavior_path_avoidance_module/package.xml b/planning/behavior_path_avoidance_module/package.xml new file mode 100644 index 0000000000000..68cc911e9373d --- /dev/null +++ b/planning/behavior_path_avoidance_module/package.xml @@ -0,0 +1,53 @@ + + + + behavior_path_avoidance_module + 0.1.0 + The behavior_path_avoidance_module package + + Takamasa Horibe + Satoshi Ota + Fumiya Watanabe + Kyoichi Sugahara + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + autoware_auto_perception_msgs + autoware_auto_planning_msgs + autoware_auto_tf2 + autoware_perception_msgs + behavior_path_planner + behavior_path_planner_common + geometry_msgs + lanelet2_extension + libboost-dev + magic_enum + motion_utils + objects_of_interest_marker_interface + pluginlib + rclcpp + route_handler + rtc_interface + sensor_msgs + signal_processing + tf2 + tf2_eigen + tf2_geometry_msgs + tf2_ros + tier4_autoware_utils + tier4_planning_msgs + vehicle_info_util + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_path_avoidance_module/plugins.xml b/planning/behavior_path_avoidance_module/plugins.xml new file mode 100644 index 0000000000000..f25677dad1e9a --- /dev/null +++ b/planning/behavior_path_avoidance_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp b/planning/behavior_path_avoidance_module/src/debug.cpp similarity index 99% rename from planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp rename to planning/behavior_path_avoidance_module/src/debug.cpp index 7587c3bb3663e..3ae210e0b1d78 100644 --- a/planning/behavior_path_planner/src/marker_utils/avoidance/debug.cpp +++ b/planning/behavior_path_avoidance_module/src/debug.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/marker_utils/avoidance/debug.hpp" +#include "behavior_path_avoidance_module/debug.hpp" #include "behavior_path_planner_common/utils/utils.hpp" diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_avoidance_module/src/manager.cpp similarity index 99% rename from planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp rename to planning/behavior_path_avoidance_module/src/manager.cpp index e17804f10deaa..f4997d2af12f1 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_avoidance_module/src/manager.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/avoidance/manager.hpp" +#include "behavior_path_avoidance_module/manager.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp similarity index 99% rename from planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp rename to planning/behavior_path_avoidance_module/src/scene.cpp index df93df75410e1..9b0c85f60ba29 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// 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. @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/avoidance/avoidance_module.hpp" +#include "behavior_path_avoidance_module/scene.hpp" -#include "behavior_path_planner/marker_utils/avoidance/debug.hpp" -#include "behavior_path_planner/utils/avoidance/utils.hpp" +#include "behavior_path_avoidance_module/debug.hpp" +#include "behavior_path_avoidance_module/utils.hpp" #include "behavior_path_planner_common/interface/scene_module_visitor.hpp" #include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" diff --git a/planning/behavior_path_planner/src/utils/avoidance/shift_line_generator.cpp b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp similarity index 99% rename from planning/behavior_path_planner/src/utils/avoidance/shift_line_generator.cpp rename to planning/behavior_path_avoidance_module/src/shift_line_generator.cpp index c7fbaa931737c..48d7e3a4baf8b 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/shift_line_generator.cpp +++ b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/avoidance/shift_line_generator.hpp" +#include "behavior_path_avoidance_module/shift_line_generator.hpp" -#include "behavior_path_planner/utils/avoidance/utils.hpp" +#include "behavior_path_avoidance_module/utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" #include diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp similarity index 99% rename from planning/behavior_path_planner/src/utils/avoidance/utils.cpp rename to planning/behavior_path_avoidance_module/src/utils.cpp index 6fd1943369cb9..b469e9070baad 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// 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. @@ -14,8 +14,8 @@ #include "behavior_path_planner_common/utils/utils.hpp" -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" -#include "behavior_path_planner/utils/avoidance/utils.hpp" +#include "behavior_path_avoidance_module/data_structs.hpp" +#include "behavior_path_avoidance_module/utils.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/traffic_light_utils.hpp" diff --git a/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp new file mode 100644 index 0000000000000..83514127b0a8e --- /dev/null +++ b/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -0,0 +1,126 @@ +// 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 "ament_index_cpp/get_package_share_directory.hpp" +#include "behavior_path_planner/behavior_path_planner_node.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include + +#include +#include + +using behavior_path_planner::BehaviorPathPlannerNode; +using planning_test_utils::PlanningInterfaceTestManager; + +std::shared_ptr generateTestManager() +{ + auto test_manager = std::make_shared(); + + // set subscriber with topic name: behavior_path_planner → test_node_ + test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); + + // set behavior_path_planner's input topic name(this topic is changed to test node) + test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); + + test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); + + return test_manager; +} + +std::shared_ptr generateNode() +{ + auto node_options = rclcpp::NodeOptions{}; + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto behavior_path_planner_dir = + ament_index_cpp::get_package_share_directory("behavior_path_planner"); + + std::vector module_names; + module_names.emplace_back("behavior_path_planner::AvoidanceModuleManager"); + + std::vector params; + params.emplace_back("launch_modules", module_names); + node_options.parameter_overrides(params); + + test_utils::updateNodeOptions( + node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", + planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", + behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", + behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", + ament_index_cpp::get_package_share_directory("behavior_path_planner") + + "/config/lane_change/lane_change.param.yaml", + ament_index_cpp::get_package_share_directory("behavior_path_avoidance_module") + + "/config/avoidance.param.yaml"}); + + return std::make_shared(node_options); +} + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ + // publish necessary topics from test_manager + test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); + test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); + test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); + test_manager->publishOccupancyGrid( + test_target_node, "behavior_path_planner/input/occupancy_grid_map"); + test_manager->publishLaneDrivingScenario( + test_target_node, "behavior_path_planner/input/scenario"); + test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); + test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); + test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); + test_manager->publishLateralOffset( + test_target_node, "behavior_path_planner/input/lateral_offset"); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) +{ + rclcpp::init(0, nullptr); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty route + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + + rclcpp::shutdown(); +} diff --git a/planning/behavior_path_planner/test/test_avoidance_utils.cpp b/planning/behavior_path_avoidance_module/test/test_utils.cpp similarity index 92% rename from planning/behavior_path_planner/test/test_avoidance_utils.cpp rename to planning/behavior_path_avoidance_module/test/test_utils.cpp index fc2bea1a5b288..e5c6fd2e72092 100644 --- a/planning/behavior_path_planner/test/test_avoidance_utils.cpp +++ b/planning/behavior_path_avoidance_module/test/test_utils.cpp @@ -11,8 +11,9 @@ // 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 "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" -#include "behavior_path_planner/utils/avoidance/utils.hpp" + +#include "behavior_path_avoidance_module/data_structs.hpp" +#include "behavior_path_avoidance_module/utils.hpp" #include #include diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index 2ea43bf5a4ef1..b99bc2a4eb2e4 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -12,8 +12,6 @@ pluginlib_export_plugin_description_file(${PROJECT_NAME} plugins.xml) ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/planner_manager.cpp src/behavior_path_planner_node.cpp - src/scene_module/avoidance/avoidance_module.cpp - src/scene_module/avoidance/manager.cpp src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp src/scene_module/dynamic_avoidance/manager.cpp src/scene_module/start_planner/start_planner_module.cpp @@ -25,11 +23,8 @@ ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/scene_module/lane_change/interface.cpp src/scene_module/lane_change/normal.cpp src/scene_module/lane_change/external_request.cpp - src/scene_module/lane_change/avoidance_by_lane_change.cpp src/scene_module/lane_change/manager.cpp src/utils/start_goal_planner_common/utils.cpp - src/utils/avoidance/shift_line_generator.cpp - src/utils/avoidance/utils.cpp src/utils/lane_change/utils.cpp src/utils/side_shift/util.cpp src/utils/goal_planner/util.cpp @@ -44,7 +39,6 @@ ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/utils/start_planner/freespace_pull_out.cpp src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp - src/marker_utils/avoidance/debug.cpp src/marker_utils/lane_change/debug.cpp ) @@ -71,14 +65,6 @@ if(BUILD_TESTING) ${PROJECT_NAME}_lib ) - ament_add_ros_isolated_gmock(test_${CMAKE_PROJECT_NAME}_avoidance_module - test/test_avoidance_utils.cpp - ) - - target_link_libraries(test_${CMAKE_PROJECT_NAME}_avoidance_module - ${PROJECT_NAME}_lib - ) - ament_add_ros_isolated_gmock(test_${CMAKE_PROJECT_NAME}_lane_change_module test/test_lane_change_utils.cpp ) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp index 2e3cbd992e27f..b7cef007d6d9f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp @@ -15,7 +15,6 @@ #ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__INTERFACE_HPP_ #define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__INTERFACE_HPP_ -#include "behavior_path_planner/scene_module/lane_change/avoidance_by_lane_change.hpp" #include "behavior_path_planner/scene_module/lane_change/base_class.hpp" #include "behavior_path_planner/scene_module/lane_change/external_request.hpp" #include "behavior_path_planner/scene_module/lane_change/normal.hpp" @@ -145,23 +144,6 @@ class LaneChangeInterface : public SceneModuleInterface bool is_abort_approval_requested_{false}; }; - -class AvoidanceByLaneChangeInterface : public LaneChangeInterface -{ -public: - AvoidanceByLaneChangeInterface( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters, - const std::shared_ptr & avoidance_by_lane_change_parameters, - const std::unordered_map> & rtc_interface_ptr_map, - std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); - - bool isExecutionRequested() const override; - -protected: - void updateRTCStatus(const double start_distance, const double finish_distance) override; -}; } // namespace behavior_path_planner #endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__INTERFACE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp index ed476adcbd834..024c6685b28c4 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp @@ -94,24 +94,6 @@ class ExternalRequestLaneChangeLeftModuleManager : public LaneChangeModuleManage { } }; - -class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager -{ -public: - AvoidanceByLaneChangeModuleManager() - : LaneChangeModuleManager( - "avoidance_by_lc", route_handler::Direction::NONE, - LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE) - { - } - - void init(rclcpp::Node * node) override; - - std::unique_ptr createNewSceneModuleInstance() override; - -private: - std::shared_ptr avoidance_parameters_; -}; } // namespace behavior_path_planner #endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp index f11d48a24c79c..6f34bc79fe5f1 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp @@ -14,8 +14,8 @@ #ifndef BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_MODULE_DATA_HPP_ #define BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_MODULE_DATA_HPP_ -#include "behavior_path_planner/utils/avoidance/avoidance_module_data.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" +#include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" #include @@ -147,15 +147,6 @@ enum class LaneChangeModuleType { EXTERNAL_REQUEST, AVOIDANCE_BY_LANE_CHANGE, }; - -struct AvoidanceByLCParameters : public AvoidanceParameters -{ - // execute only when the target object longitudinal distance is larger than this param. - double execute_object_longitudinal_margin{0.0}; - - // execute only when lane change end point is before the object. - bool execute_only_when_lane_change_finish_before_object{false}; -}; } // namespace behavior_path_planner namespace behavior_path_planner::data::lane_change diff --git a/planning/behavior_path_planner/plugins.xml b/planning/behavior_path_planner/plugins.xml index 561246fcf75e4..5196b20dc5abd 100644 --- a/planning/behavior_path_planner/plugins.xml +++ b/planning/behavior_path_planner/plugins.xml @@ -1,5 +1,4 @@ - @@ -8,5 +7,4 @@ - diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp index 413350e3eb23b..26fc423fce02f 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp @@ -474,38 +474,4 @@ TurnSignalInfo LaneChangeInterface::getCurrentTurnSignalInfo( // not in the vicinity of the end of the path. return original return original_turn_signal_info; } - -AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface( - const std::string & name, rclcpp::Node & node, - const std::shared_ptr & parameters, - const std::shared_ptr & avoidance_by_lane_change_parameters, - const std::unordered_map> & rtc_interface_ptr_map, - std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: LaneChangeInterface{ - name, - node, - parameters, - rtc_interface_ptr_map, - objects_of_interest_marker_interface_ptr_map, - std::make_unique(parameters, avoidance_by_lane_change_parameters)} -{ -} - -bool AvoidanceByLaneChangeInterface::isExecutionRequested() const -{ - return module_type_->specialRequiredCheck() && module_type_->isLaneChangeRequired(); -} - -void AvoidanceByLaneChangeInterface::updateRTCStatus( - const double start_distance, const double finish_distance) -{ - const auto direction = std::invoke([&]() -> std::string { - const auto dir = module_type_->getDirection(); - return (dir == Direction::LEFT) ? "left" : "right"; - }); - - rtc_interface_ptr_map_.at(direction)->updateCooperateStatus( - uuid_map_.at(direction), isExecutionReady(), start_distance, finish_distance, clock_->now()); -} } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp index 29b7cad533a66..ed40476723dba 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp @@ -246,148 +246,6 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector(*node, ns + "execute_object_longitudinal_margin"); - p.execute_only_when_lane_change_finish_before_object = - getOrDeclareParameter(*node, ns + "execute_only_when_lane_change_finish_before_object"); - } - - // general params - { - const std::string ns = "avoidance."; - p.resample_interval_for_planning = - getOrDeclareParameter(*node, ns + "resample_interval_for_planning"); - p.resample_interval_for_output = - getOrDeclareParameter(*node, ns + "resample_interval_for_output"); - } - - // target object - { - const auto get_object_param = [&](std::string && ns) { - ObjectParameter param{}; - param.execute_num = getOrDeclareParameter(*node, ns + "execute_num"); - param.moving_speed_threshold = - getOrDeclareParameter(*node, ns + "moving_speed_threshold"); - param.moving_time_threshold = - getOrDeclareParameter(*node, ns + "moving_time_threshold"); - param.max_expand_ratio = getOrDeclareParameter(*node, ns + "max_expand_ratio"); - param.envelope_buffer_margin = - getOrDeclareParameter(*node, ns + "envelope_buffer_margin"); - param.avoid_margin_lateral = - getOrDeclareParameter(*node, ns + "avoid_margin_lateral"); - param.safety_buffer_lateral = - getOrDeclareParameter(*node, ns + "safety_buffer_lateral"); - return param; - }; - - const std::string ns = "avoidance_by_lane_change.target_object."; - p.object_parameters.emplace( - ObjectClassification::MOTORCYCLE, get_object_param(ns + "motorcycle.")); - p.object_parameters.emplace(ObjectClassification::CAR, get_object_param(ns + "car.")); - p.object_parameters.emplace(ObjectClassification::TRUCK, get_object_param(ns + "truck.")); - p.object_parameters.emplace(ObjectClassification::TRAILER, get_object_param(ns + "trailer.")); - p.object_parameters.emplace(ObjectClassification::BUS, get_object_param(ns + "bus.")); - p.object_parameters.emplace( - ObjectClassification::PEDESTRIAN, get_object_param(ns + "pedestrian.")); - p.object_parameters.emplace(ObjectClassification::BICYCLE, get_object_param(ns + "bicycle.")); - p.object_parameters.emplace(ObjectClassification::UNKNOWN, get_object_param(ns + "unknown.")); - - p.lower_distance_for_polygon_expansion = - getOrDeclareParameter(*node, ns + "lower_distance_for_polygon_expansion"); - p.upper_distance_for_polygon_expansion = - getOrDeclareParameter(*node, ns + "upper_distance_for_polygon_expansion"); - } - - // target filtering - { - const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) { - if (p.object_parameters.count(object_type) == 0) { - return; - } - p.object_parameters.at(object_type).is_avoidance_target = - getOrDeclareParameter(*node, ns); - }; - - const std::string ns = "avoidance.target_filtering."; - set_target_flag(ObjectClassification::CAR, ns + "target_type.car"); - set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck"); - set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer"); - set_target_flag(ObjectClassification::BUS, ns + "target_type.bus"); - set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian"); - set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle"); - set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle"); - set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown"); - - p.object_check_goal_distance = - getOrDeclareParameter(*node, ns + "object_check_goal_distance"); - p.threshold_distance_object_is_on_center = - getOrDeclareParameter(*node, ns + "threshold_distance_object_is_on_center"); - p.object_check_shiftable_ratio = - getOrDeclareParameter(*node, ns + "object_check_shiftable_ratio"); - p.object_check_min_road_shoulder_width = - getOrDeclareParameter(*node, ns + "object_check_min_road_shoulder_width"); - p.object_last_seen_threshold = - getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); - } - - { - const std::string ns = "avoidance.target_filtering.force_avoidance."; - p.enable_force_avoidance_for_stopped_vehicle = - getOrDeclareParameter(*node, ns + "enable"); - p.threshold_time_force_avoidance_for_stopped_vehicle = - getOrDeclareParameter(*node, ns + "time_threshold"); - p.object_ignore_section_traffic_light_in_front_distance = - getOrDeclareParameter(*node, ns + "ignore_area.traffic_light.front_distance"); - p.object_ignore_section_crosswalk_in_front_distance = - getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.front_distance"); - p.object_ignore_section_crosswalk_behind_distance = - getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.behind_distance"); - } - - { - const std::string ns = "avoidance.target_filtering.detection_area."; - p.use_static_detection_area = getOrDeclareParameter(*node, ns + "static"); - p.object_check_min_forward_distance = - getOrDeclareParameter(*node, ns + "min_forward_distance"); - p.object_check_max_forward_distance = - getOrDeclareParameter(*node, ns + "max_forward_distance"); - p.object_check_backward_distance = - getOrDeclareParameter(*node, ns + "backward_distance"); - } - - // safety check - { - const std::string ns = "avoidance.safety_check."; - p.hysteresis_factor_expand_rate = - getOrDeclareParameter(*node, ns + "hysteresis_factor_expand_rate"); - } - - avoidance_parameters_ = std::make_shared(p); -} - -std::unique_ptr -AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance() -{ - return std::make_unique( - name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); -} - } // namespace behavior_path_planner #include @@ -403,6 +261,3 @@ PLUGINLIB_EXPORT_CLASS( PLUGINLIB_EXPORT_CLASS( behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager, behavior_path_planner::SceneModuleManagerInterface) -PLUGINLIB_EXPORT_CLASS( - behavior_path_planner::AvoidanceByLaneChangeModuleManager, - behavior_path_planner::SceneModuleManagerInterface) diff --git a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp index 9235e8e8e3de6..c2b115ae98afe 100644 --- a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp @@ -49,7 +49,6 @@ std::shared_ptr generateNode() ament_index_cpp::get_package_share_directory("behavior_path_planner"); std::vector module_names; - module_names.emplace_back("behavior_path_planner::AvoidanceModuleManager"); module_names.emplace_back("behavior_path_planner::DynamicAvoidanceModuleManager"); module_names.emplace_back("behavior_path_planner::SideShiftModuleManager"); module_names.emplace_back("behavior_path_planner::StartPlannerModuleManager"); @@ -58,7 +57,6 @@ std::shared_ptr generateNode() module_names.emplace_back("behavior_path_planner::LaneChangeLeftModuleManager"); module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeRightModuleManager"); module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager"); - module_names.emplace_back("behavior_path_planner::AvoidanceByLaneChangeModuleManager"); std::vector params; params.emplace_back("launch_modules", module_names); @@ -72,12 +70,10 @@ std::shared_ptr generateNode() behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - behavior_path_planner_dir + "/config/avoidance/avoidance.param.yaml", behavior_path_planner_dir + "/config/dynamic_avoidance/dynamic_avoidance.param.yaml", behavior_path_planner_dir + "/config/lane_change/lane_change.param.yaml", behavior_path_planner_dir + "/config/start_planner/start_planner.param.yaml", behavior_path_planner_dir + "/config/goal_planner/goal_planner.param.yaml", - behavior_path_planner_dir + "/config/avoidance_by_lc/avoidance_by_lc.param.yaml", behavior_path_planner_dir + "/config/side_shift/side_shift.param.yaml"}); return std::make_shared(node_options); From c95b9976eb690aead39e6aef57da7a9787ac25ca Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 7 Dec 2023 01:42:16 +0000 Subject: [PATCH 05/87] chore: update CODEOWNERS (#5800) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/CODEOWNERS | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 01ccc632b0133..ea86022e7134d 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -154,6 +154,8 @@ perception/traffic_light_multi_camera_fusion/** shunsuke.miura@tier4.jp tao.zhon perception/traffic_light_occlusion_predictor/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/traffic_light_ssd_fine_detector/** daisuke.nishimatsu@tier4.jp perception/traffic_light_visualization/** yukihiro.saito@tier4.jp +planning/behavior_path_avoidance_by_lane_change_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp zulfaqar.azmi@tier4.jp +planning/behavior_path_avoidance_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp takamasa.horibe@tier4.jp planning/behavior_path_planner/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_planner_common/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_velocity_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp From dd0d6eb4127f7ba3660e4b796997a377b6ed62a2 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 7 Dec 2023 11:30:28 +0900 Subject: [PATCH 06/87] refactor(motion_velocity_smoother): boost::optional to std::optional (#5758) * refactor(motion_velocity_smoother): boost::optional to std::optional 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> --- .../trajectory_utils.hpp | 22 +++++++------------ planning/motion_velocity_smoother/package.xml | 1 - .../src/trajectory_utils.cpp | 10 ++++----- 3 files changed, 12 insertions(+), 21 deletions(-) diff --git a/planning/motion_velocity_smoother/include/motion_velocity_smoother/trajectory_utils.hpp b/planning/motion_velocity_smoother/include/motion_velocity_smoother/trajectory_utils.hpp index ec8a89c5a3e9c..35e8ab53dd75d 100644 --- a/planning/motion_velocity_smoother/include/motion_velocity_smoother/trajectory_utils.hpp +++ b/planning/motion_velocity_smoother/include/motion_velocity_smoother/trajectory_utils.hpp @@ -15,20 +15,15 @@ #ifndef MOTION_VELOCITY_SMOOTHER__TRAJECTORY_UTILS_HPP_ #define MOTION_VELOCITY_SMOOTHER__TRAJECTORY_UTILS_HPP_ -#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" -#include "geometry_msgs/msg/pose.hpp" +#include "autoware_auto_planning_msgs/msg/detail/trajectory_point__struct.hpp" +#include "geometry_msgs/msg/detail/pose__struct.hpp" -#include "boost/optional.hpp" - -#include #include -#include +#include #include #include -namespace motion_velocity_smoother -{ -namespace trajectory_utils +namespace motion_velocity_smoother::trajectory_utils { using autoware_auto_planning_msgs::msg::TrajectoryPoint; using TrajectoryPoints = std::vector; @@ -57,7 +52,7 @@ double getMaxAbsVelocity(const TrajectoryPoints & trajectory); void applyMaximumVelocityLimit( const size_t from, const size_t to, const double max_vel, TrajectoryPoints & trajectory); -boost::optional searchZeroVelocityIdx(const TrajectoryPoints & trajectory); +std::optional searchZeroVelocityIdx(const TrajectoryPoints & trajectory); bool calcStopDistWithJerkConstraints( const double v0, const double a0, const double jerk_acc, const double jerk_dec, @@ -68,12 +63,12 @@ bool isValidStopDist( const double v_end, const double a_end, const double v_target, const double a_target, const double v_margin, const double a_margin); -boost::optional applyDecelFilterWithJerkConstraint( +std::optional applyDecelFilterWithJerkConstraint( const TrajectoryPoints & input, const size_t start_index, const double v0, const double a0, const double min_acc, const double decel_target_vel, const std::map & jerk_profile); -boost::optional> updateStateWithJerkConstraint( +std::optional> updateStateWithJerkConstraint( const double v0, const double a0, const std::map & jerk_profile, const double t); std::vector calcVelocityProfileWithConstantJerkAndAccelerationLimit( @@ -82,7 +77,6 @@ std::vector calcVelocityProfileWithConstantJerkAndAccelerationLimit( double calcStopDistance(const TrajectoryPoints & trajectory, const size_t closest); -} // namespace trajectory_utils -} // namespace motion_velocity_smoother +} // namespace motion_velocity_smoother::trajectory_utils #endif // MOTION_VELOCITY_SMOOTHER__TRAJECTORY_UTILS_HPP_ diff --git a/planning/motion_velocity_smoother/package.xml b/planning/motion_velocity_smoother/package.xml index 54c60c938970a..4bb0d8a2883dd 100644 --- a/planning/motion_velocity_smoother/package.xml +++ b/planning/motion_velocity_smoother/package.xml @@ -22,7 +22,6 @@ autoware_auto_planning_msgs geometry_msgs interpolation - libboost-dev motion_utils nav_msgs osqp_interface diff --git a/planning/motion_velocity_smoother/src/trajectory_utils.cpp b/planning/motion_velocity_smoother/src/trajectory_utils.cpp index dd361696a5dad..acc3673d66925 100644 --- a/planning/motion_velocity_smoother/src/trajectory_utils.cpp +++ b/planning/motion_velocity_smoother/src/trajectory_utils.cpp @@ -15,7 +15,6 @@ #include "motion_velocity_smoother/trajectory_utils.hpp" #include "interpolation/linear_interpolation.hpp" -#include "interpolation/spline_interpolation.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" @@ -430,7 +429,7 @@ bool isValidStopDist( return true; } -boost::optional applyDecelFilterWithJerkConstraint( +std::optional applyDecelFilterWithJerkConstraint( const TrajectoryPoints & input, const size_t start_index, const double v0, const double a0, const double min_acc, const double decel_target_vel, const std::map & jerk_profile) @@ -536,7 +535,7 @@ boost::optional applyDecelFilterWithJerkConstraint( return output_trajectory; } -boost::optional> updateStateWithJerkConstraint( +std::optional> updateStateWithJerkConstraint( const double v0, const double a0, const std::map & jerk_profile, const double t) { // constexpr double eps = 1.0E-05; @@ -558,15 +557,14 @@ boost::optional> updateStateWithJerkC x = integ_x(x, v, a, j, dt); v = integ_v(v, a, j, dt); a = integ_a(a, j, dt); - const auto state = std::make_tuple(x, v, a, j); - return boost::optional>(state); + return std::make_tuple(x, v, a, j); } } RCLCPP_WARN_STREAM( rclcpp::get_logger("motion_velocity_smoother").get_child("trajectory_utils"), "Invalid jerk profile"); - return {}; + return std::nullopt; } std::vector calcVelocityProfileWithConstantJerkAndAccelerationLimit( From 49c95d143eceebf8fa71f6a00d4f95cf43d18297 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 7 Dec 2023 18:05:27 +0900 Subject: [PATCH 07/87] refactor(start_planner, goal_planner): separate package (#5802) * separate packages Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../CMakeLists.txt | 19 +++++ .../config}/goal_planner.param.yaml | 0 .../default_fixed_goal_planner.hpp | 8 +- .../fixed_goal_planner_base.hpp | 6 +- .../freespace_pull_over.hpp | 8 +- .../geometric_pull_over.hpp | 10 +-- .../goal_planner_module.hpp | 39 ++++++--- .../goal_planner_parameters.hpp | 8 +- .../goal_searcher.hpp | 8 +- .../goal_searcher_base.hpp | 8 +- .../manager.hpp | 8 +- .../pull_over_planner_base.hpp | 8 +- .../shift_pull_over.hpp | 8 +- .../util.hpp | 8 +- .../package.xml | 35 ++++++++ .../plugins.xml | 3 + .../src}/default_fixed_goal_planner.cpp | 4 +- .../src}/freespace_pull_over.cpp | 8 +- .../src}/geometric_pull_over.cpp | 4 +- .../src}/goal_planner_module.cpp | 56 ++++++++----- .../src}/goal_searcher.cpp | 4 +- .../src}/manager.cpp | 4 +- .../src}/shift_pull_over.cpp | 4 +- .../src}/util.cpp | 2 +- planning/behavior_path_planner/CMakeLists.txt | 16 ---- planning/behavior_path_planner/plugins.xml | 2 - ...t_behavior_path_planner_node_interface.cpp | 4 - .../CMakeLists.txt | 2 + .../parking_departure}/common_module_data.hpp | 6 +- .../geometric_parallel_parking.hpp | 6 +- .../utils/parking_departure}/utils.hpp | 48 ++++------- .../geometric_parallel_parking.cpp | 6 +- .../src/utils/parking_departure}/utils.cpp | 80 +++++++------------ .../CMakeLists.txt | 17 ++++ .../config}/start_planner.param.yaml | 0 .../freespace_pull_out.hpp | 8 +- .../geometric_pull_out.hpp | 12 +-- .../manager.hpp | 8 +- .../pull_out_path.hpp | 6 +- .../pull_out_planner_base.hpp | 10 +-- .../shift_pull_out.hpp | 10 +-- .../start_planner_module.hpp | 34 +++++--- .../start_planner_parameters.hpp | 8 +- .../util.hpp | 13 +-- .../package.xml | 35 ++++++++ .../plugins.xml | 3 + .../src}/freespace_pull_out.cpp | 9 ++- .../src}/geometric_pull_out.cpp | 4 +- .../src}/manager.cpp | 2 +- .../src}/shift_pull_out.cpp | 10 +-- .../src}/start_planner_module.cpp | 48 ++++++++--- .../src}/util.cpp | 23 +----- 52 files changed, 395 insertions(+), 305 deletions(-) create mode 100644 planning/behavior_path_goal_planner_module/CMakeLists.txt rename planning/{behavior_path_planner/config/goal_planner => behavior_path_goal_planner_module/config}/goal_planner.param.yaml (100%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/default_fixed_goal_planner.hpp (80%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/fixed_goal_planner_base.hpp (86%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/freespace_pull_over.hpp (83%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/geometric_pull_over.hpp (86%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/goal_planner_module.hpp (92%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/goal_planner_parameters.hpp (92%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/goal_searcher.hpp (88%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/goal_searcher_base.hpp (86%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/manager.hpp (84%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/pull_over_planner_base.hpp (92%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/shift_pull_over.hpp (88%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/goal_planner => behavior_path_goal_planner_module/include/behavior_path_goal_planner_module}/util.hpp (91%) create mode 100644 planning/behavior_path_goal_planner_module/package.xml create mode 100644 planning/behavior_path_goal_planner_module/plugins.xml rename planning/{behavior_path_planner/src/utils/goal_planner => behavior_path_goal_planner_module/src}/default_fixed_goal_planner.cpp (96%) rename planning/{behavior_path_planner/src/utils/goal_planner => behavior_path_goal_planner_module/src}/freespace_pull_over.cpp (94%) rename planning/{behavior_path_planner/src/utils/goal_planner => behavior_path_goal_planner_module/src}/geometric_pull_over.cpp (95%) rename planning/{behavior_path_planner/src/scene_module/goal_planner => behavior_path_goal_planner_module/src}/goal_planner_module.cpp (97%) rename planning/{behavior_path_planner/src/utils/goal_planner => behavior_path_goal_planner_module/src}/goal_searcher.cpp (99%) rename planning/{behavior_path_planner/src/scene_module/goal_planner => behavior_path_goal_planner_module/src}/manager.cpp (99%) rename planning/{behavior_path_planner/src/utils/goal_planner => behavior_path_goal_planner_module/src}/shift_pull_over.cpp (98%) rename planning/{behavior_path_planner/src/utils/goal_planner => behavior_path_goal_planner_module/src}/util.cpp (99%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common => behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure}/common_module_data.hpp (84%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/geometric_parallel_parking => behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure}/geometric_parallel_parking.hpp (95%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common => behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure}/utils.hpp (63%) rename planning/{behavior_path_planner/src/utils/geometric_parallel_parking => behavior_path_planner_common/src/utils/parking_departure}/geometric_parallel_parking.cpp (98%) rename planning/{behavior_path_planner/src/utils/start_goal_planner_common => behavior_path_planner_common/src/utils/parking_departure}/utils.cpp (72%) create mode 100644 planning/behavior_path_start_planner_module/CMakeLists.txt rename planning/{behavior_path_planner/config/start_planner => behavior_path_start_planner_module/config}/start_planner.param.yaml (100%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/freespace_pull_out.hpp (83%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/geometric_pull_out.hpp (70%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/manager.hpp (83%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/pull_out_path.hpp (84%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/pull_out_planner_base.hpp (83%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/shift_pull_out.hpp (84%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/start_planner_module.hpp (88%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/start_planner_parameters.hpp (91%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/start_planner => behavior_path_start_planner_module/include/behavior_path_start_planner_module}/util.hpp (81%) create mode 100644 planning/behavior_path_start_planner_module/package.xml create mode 100644 planning/behavior_path_start_planner_module/plugins.xml rename planning/{behavior_path_planner/src/utils/start_planner => behavior_path_start_planner_module/src}/freespace_pull_out.cpp (93%) rename planning/{behavior_path_planner/src/utils/start_planner => behavior_path_start_planner_module/src}/geometric_pull_out.cpp (97%) rename planning/{behavior_path_planner/src/scene_module/start_planner => behavior_path_start_planner_module/src}/manager.cpp (99%) rename planning/{behavior_path_planner/src/utils/start_planner => behavior_path_start_planner_module/src}/shift_pull_out.cpp (97%) rename planning/{behavior_path_planner/src/scene_module/start_planner => behavior_path_start_planner_module/src}/start_planner_module.cpp (96%) rename planning/{behavior_path_planner/src/utils/start_planner => behavior_path_start_planner_module/src}/util.cpp (83%) diff --git a/planning/behavior_path_goal_planner_module/CMakeLists.txt b/planning/behavior_path_goal_planner_module/CMakeLists.txt new file mode 100644 index 0000000000000..c91289bf29e2c --- /dev/null +++ b/planning/behavior_path_goal_planner_module/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_path_goal_planner_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_path_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/default_fixed_goal_planner.cpp + src/freespace_pull_over.cpp + src/geometric_pull_over.cpp + src/goal_searcher.cpp + src/shift_pull_over.cpp + src/util.cpp + src/goal_planner_module.cpp + src/manager.cpp +) + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml b/planning/behavior_path_goal_planner_module/config/goal_planner.param.yaml similarity index 100% rename from planning/behavior_path_planner/config/goal_planner/goal_planner.param.yaml rename to planning/behavior_path_goal_planner_module/config/goal_planner.param.yaml diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/default_fixed_goal_planner.hpp similarity index 80% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/default_fixed_goal_planner.hpp index 1595503a225f8..4da625a7a9087 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/default_fixed_goal_planner.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__DEFAULT_FIXED_GOAL_PLANNER_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__DEFAULT_FIXED_GOAL_PLANNER_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__DEFAULT_FIXED_GOAL_PLANNER_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__DEFAULT_FIXED_GOAL_PLANNER_HPP_ -#include "behavior_path_planner/utils/goal_planner/fixed_goal_planner_base.hpp" +#include "behavior_path_goal_planner_module/fixed_goal_planner_base.hpp" #include @@ -42,4 +42,4 @@ class DefaultFixedGoalPlanner : public FixedGoalPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__DEFAULT_FIXED_GOAL_PLANNER_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__DEFAULT_FIXED_GOAL_PLANNER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/fixed_goal_planner_base.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp similarity index 86% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/fixed_goal_planner_base.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp index 5fe3427749844..0926d1010b5c3 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/fixed_goal_planner_base.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__FIXED_GOAL_PLANNER_BASE_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__FIXED_GOAL_PLANNER_BASE_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__FIXED_GOAL_PLANNER_BASE_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__FIXED_GOAL_PLANNER_BASE_HPP_ #include "behavior_path_planner_common/data_manager.hpp" @@ -50,4 +50,4 @@ class FixedGoalPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__FIXED_GOAL_PLANNER_BASE_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__FIXED_GOAL_PLANNER_BASE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/freespace_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/freespace_pull_over.hpp similarity index 83% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/freespace_pull_over.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/freespace_pull_over.hpp index bb5d7b7555cfc..5ce6d83795069 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/freespace_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/freespace_pull_over.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__FREESPACE_PULL_OVER_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__FREESPACE_PULL_OVER_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__FREESPACE_PULL_OVER_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__FREESPACE_PULL_OVER_HPP_ -#include "behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp" +#include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" #include #include @@ -51,4 +51,4 @@ class FreespacePullOver : public PullOverPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__FREESPACE_PULL_OVER_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__FREESPACE_PULL_OVER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/geometric_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp similarity index 86% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/geometric_pull_over.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp index d96b01582a2d1..c5ba04ba7f52e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/geometric_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GEOMETRIC_PULL_OVER_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GEOMETRIC_PULL_OVER_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GEOMETRIC_PULL_OVER_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GEOMETRIC_PULL_OVER_HPP_ -#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" -#include "behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp" +#include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" #include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" +#include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include @@ -69,4 +69,4 @@ class GeometricPullOver : public PullOverPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GEOMETRIC_PULL_OVER_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GEOMETRIC_PULL_OVER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp similarity index 92% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp index a9bc31983ac6c..7b5b9b1a68102 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -12,19 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__GOAL_PLANNER__GOAL_PLANNER_MODULE_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__GOAL_PLANNER__GOAL_PLANNER_MODULE_HPP_ - -#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" -#include "behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp" -#include "behavior_path_planner/utils/goal_planner/freespace_pull_over.hpp" -#include "behavior_path_planner/utils/goal_planner/geometric_pull_over.hpp" -#include "behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp" -#include "behavior_path_planner/utils/goal_planner/goal_searcher.hpp" -#include "behavior_path_planner/utils/goal_planner/shift_pull_over.hpp" +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_PLANNER_MODULE_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_PLANNER_MODULE_HPP_ + +#include "behavior_path_goal_planner_module/default_fixed_goal_planner.hpp" +#include "behavior_path_goal_planner_module/freespace_pull_over.hpp" +#include "behavior_path_goal_planner_module/geometric_pull_over.hpp" +#include "behavior_path_goal_planner_module/goal_planner_parameters.hpp" +#include "behavior_path_goal_planner_module/goal_searcher.hpp" +#include "behavior_path_goal_planner_module/shift_pull_over.hpp" #include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" -#include "behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp" #include "behavior_path_planner_common/interface/scene_module_interface.hpp" +#include "behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" +#include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/utils.hpp" @@ -282,6 +282,19 @@ class GoalPlannerModule : public SceneModuleInterface bool isExecutionReady() const override; void processOnExit() override; void updateData() override; + + void updateEgoPredictedPathParams( + std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & goal_planner_params); + + void updateSafetyCheckParams( + std::shared_ptr & safety_check_params, + const std::shared_ptr & goal_planner_params); + + void updateObjectsFilteringParams( + std::shared_ptr & objects_filtering_params, + const std::shared_ptr & goal_planner_params); + void postProcess() override; void setParameters(const std::shared_ptr & parameters); void acceptVisitor( @@ -291,7 +304,7 @@ class GoalPlannerModule : public SceneModuleInterface CandidateOutput planCandidate() const override { return CandidateOutput{}; } private: - /*  + /* * state transitions and plan function used in each state * * +--------------------------+ @@ -494,4 +507,4 @@ class GoalPlannerModule : public SceneModuleInterface }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__GOAL_PLANNER__GOAL_PLANNER_MODULE_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_PLANNER_MODULE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_parameters.hpp similarity index 92% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_parameters.hpp index c5adf3a2ad652..21eb22046bff6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_parameters.hpp @@ -13,10 +13,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_PLANNER_PARAMETERS_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_PLANNER_PARAMETERS_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_PLANNER_PARAMETERS_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_PLANNER_PARAMETERS_HPP_ -#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" +#include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include @@ -124,4 +124,4 @@ struct GoalPlannerParameters }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_PLANNER_PARAMETERS_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_PLANNER_PARAMETERS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp similarity index 88% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp index 2fc0acf1c5086..2d9e2c6cf3700 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_SEARCHER_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_SEARCHER_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_HPP_ -#include "behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp" +#include "behavior_path_goal_planner_module/goal_searcher_base.hpp" #include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include @@ -55,4 +55,4 @@ class GoalSearcher : public GoalSearcherBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_SEARCHER_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp similarity index 86% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp index 7d1c99a69b1d5..93472ab6c0703 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_SEARCHER_BASE_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_SEARCHER_BASE_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_BASE_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_BASE_HPP_ -#include "behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp" +#include "behavior_path_goal_planner_module/goal_planner_parameters.hpp" #include "behavior_path_planner_common/data_manager.hpp" #include @@ -69,4 +69,4 @@ class GoalSearcherBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__GOAL_SEARCHER_BASE_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_BASE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/manager.hpp similarity index 84% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/manager.hpp index a166a677c7388..aefd4cac3ee35 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/manager.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/manager.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__GOAL_PLANNER__MANAGER_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__GOAL_PLANNER__MANAGER_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__MANAGER_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__MANAGER_HPP_ -#include "behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp" +#include "behavior_path_goal_planner_module/goal_planner_module.hpp" #include "behavior_path_planner_common/interface/scene_module_manager_interface.hpp" #include @@ -55,4 +55,4 @@ class GoalPlannerModuleManager : public SceneModuleManagerInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__GOAL_PLANNER__MANAGER_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp similarity index 92% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp index a0bfd8e883d80..ddd7c93998654 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__PULL_OVER_PLANNER_BASE_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__PULL_OVER_PLANNER_BASE_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER_BASE_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER_BASE_HPP_ -#include "behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp" +#include "behavior_path_goal_planner_module/goal_planner_parameters.hpp" #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" @@ -135,4 +135,4 @@ class PullOverPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__PULL_OVER_PLANNER_BASE_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER_BASE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/shift_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp similarity index 88% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/shift_pull_over.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp index 9247ec566fbd8..cc8686f4a9fef 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/shift_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__SHIFT_PULL_OVER_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__SHIFT_PULL_OVER_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__SHIFT_PULL_OVER_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__SHIFT_PULL_OVER_HPP_ -#include "behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp" +#include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" #include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include @@ -61,4 +61,4 @@ class ShiftPullOver : public PullOverPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__SHIFT_PULL_OVER_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__SHIFT_PULL_OVER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp similarity index 91% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp rename to planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp index 25c0551d896b3..791c35f3afca6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/util.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__UTIL_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__UTIL_HPP_ +#ifndef BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_ +#define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_ -#include "behavior_path_planner/utils/goal_planner/goal_searcher_base.hpp" +#include "behavior_path_goal_planner_module/goal_searcher_base.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/utils.hpp" @@ -71,4 +71,4 @@ MarkerArray createNumObjectsToAvoidTextsMarkerArray( } // namespace goal_planner_utils } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GOAL_PLANNER__UTIL_HPP_ +#endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_ diff --git a/planning/behavior_path_goal_planner_module/package.xml b/planning/behavior_path_goal_planner_module/package.xml new file mode 100644 index 0000000000000..d29f6c6124750 --- /dev/null +++ b/planning/behavior_path_goal_planner_module/package.xml @@ -0,0 +1,35 @@ + + + + behavior_path_goal_planner_module + 0.1.0 + The behavior_path_goal_planner_module package + + Kosuke Takeuchi + Kyoichi Sugahara + Satoshi OTA + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + behavior_path_planner + behavior_path_planner_common + motion_utils + pluginlib + rclcpp + rtc_interface + tier4_autoware_utils + tier4_planning_msgs + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_path_goal_planner_module/plugins.xml b/planning/behavior_path_goal_planner_module/plugins.xml new file mode 100644 index 0000000000000..6c3b557e35e7a --- /dev/null +++ b/planning/behavior_path_goal_planner_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_path_planner/src/utils/goal_planner/default_fixed_goal_planner.cpp b/planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp similarity index 96% rename from planning/behavior_path_planner/src/utils/goal_planner/default_fixed_goal_planner.cpp rename to planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp index 9ae50def1d358..f028b8aff8b98 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/default_fixed_goal_planner.cpp +++ b/planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/goal_planner/default_fixed_goal_planner.hpp" +#include "behavior_path_goal_planner_module/default_fixed_goal_planner.hpp" -#include "behavior_path_planner/utils/goal_planner/util.hpp" +#include "behavior_path_goal_planner_module/util.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" diff --git a/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp similarity index 94% rename from planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp rename to planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp index d5252028f880b..c9af9ee369bd5 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/freespace_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/goal_planner/freespace_pull_over.hpp" +#include "behavior_path_goal_planner_module/freespace_pull_over.hpp" -#include "behavior_path_planner/utils/goal_planner/util.hpp" -#include "behavior_path_planner/utils/start_goal_planner_common/utils.hpp" +#include "behavior_path_goal_planner_module/util.hpp" +#include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include @@ -116,7 +116,7 @@ std::optional FreespacePullOver::plan(const Pose & goal_pose) std::vector> pairs_terminal_velocity_and_accel{}; pairs_terminal_velocity_and_accel.resize(partial_paths.size()); - utils::start_goal_planner_common::modifyVelocityByDirection( + utils::parking_departure::modifyVelocityByDirection( partial_paths, pairs_terminal_velocity_and_accel, velocity_, 0); // Check if driving forward for each path, return empty if not diff --git a/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp similarity index 95% rename from planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp rename to planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp index 55d8bc6cfda3f..31c1d3ef77b0e 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/geometric_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/goal_planner/geometric_pull_over.hpp" +#include "behavior_path_goal_planner_module/geometric_pull_over.hpp" -#include "behavior_path_planner/utils/goal_planner/util.hpp" +#include "behavior_path_goal_planner_module/util.hpp" #include #include diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp similarity index 97% rename from planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp rename to planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index e8905f64e9617..19c60d77b3d67 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp" +#include "behavior_path_goal_planner_module/goal_planner_module.hpp" -#include "behavior_path_planner/utils/goal_planner/util.hpp" -#include "behavior_path_planner/utils/start_goal_planner_common/utils.hpp" +#include "behavior_path_goal_planner_module/util.hpp" #include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" +#include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -39,7 +39,7 @@ #include #include -using behavior_path_planner::utils::start_goal_planner_common::calcFeasibleDecelDistance; +using behavior_path_planner::utils::parking_departure::calcFeasibleDecelDistance; using motion_utils::calcLongitudinalOffsetPose; using motion_utils::calcSignedArcLength; using motion_utils::findFirstNearestSegmentIndexWithSoftConstraints; @@ -120,8 +120,7 @@ GoalPlannerModule::GoalPlannerModule( // Initialize safety checker if (parameters_->safety_check_params.enable_safety_check) { initializeSafetyCheckParameters(); - utils::start_goal_planner_common::initializeCollisionCheckDebugMap( - goal_planner_data_.collision_check); + utils::parking_departure::initializeCollisionCheckDebugMap(goal_planner_data_.collision_check); } prev_data_.reset(); @@ -242,6 +241,30 @@ void GoalPlannerModule::onFreespaceParkingTimer() } } +void GoalPlannerModule::updateEgoPredictedPathParams( + std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & goal_planner_params) +{ + ego_predicted_path_params = + std::make_shared(goal_planner_params->ego_predicted_path_params); +} + +void GoalPlannerModule::updateSafetyCheckParams( + std::shared_ptr & safety_check_params, + const std::shared_ptr & goal_planner_params) +{ + safety_check_params = + std::make_shared(goal_planner_params->safety_check_params); +} + +void GoalPlannerModule::updateObjectsFilteringParams( + std::shared_ptr & objects_filtering_params, + const std::shared_ptr & goal_planner_params) +{ + objects_filtering_params = + std::make_shared(goal_planner_params->objects_filtering_params); +} + void GoalPlannerModule::updateData() { if (getCurrentStatus() == ModuleStatus::IDLE && !isExecutionRequested()) { @@ -303,11 +326,9 @@ void GoalPlannerModule::initializeOccupancyGridMap() void GoalPlannerModule::initializeSafetyCheckParameters() { - utils::start_goal_planner_common::updateEgoPredictedPathParams( - ego_predicted_path_params_, parameters_); - utils::start_goal_planner_common::updateSafetyCheckParams(safety_check_params_, parameters_); - utils::start_goal_planner_common::updateObjectsFilteringParams( - objects_filtering_params_, parameters_); + updateEgoPredictedPathParams(ego_predicted_path_params_, parameters_); + updateSafetyCheckParams(safety_check_params_, parameters_); + updateObjectsFilteringParams(objects_filtering_params_, parameters_); } void GoalPlannerModule::processOnExit() @@ -775,7 +796,7 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output if (prev_data_.safety_status.is_safe || !prev_data_.stop_path_after_approval) { auto current_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); const auto stop_path = - behavior_path_planner::utils::start_goal_planner_common::generateFeasibleStopPath( + 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) { @@ -1761,13 +1782,13 @@ std::pair GoalPlannerModule::isSafePath() const parameters_->forward_goal_search_length); const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(pull_over_path.points); const std::pair terminal_velocity_and_accel = - utils::start_goal_planner_common::getPairsTerminalVelocityAndAccel( + utils::parking_departure::getPairsTerminalVelocityAndAccel( thread_safe_data_.get_pull_over_path()->pairs_terminal_velocity_and_accel, thread_safe_data_.get_pull_over_path()->path_idx); RCLCPP_DEBUG( getLogger(), "pairs_terminal_velocity_and_accel for goal_planner: %f, %f", terminal_velocity_and_accel.first, terminal_velocity_and_accel.second); - utils::start_goal_planner_common::updatePathProperty( + utils::parking_departure::updatePathProperty( ego_predicted_path_params_, terminal_velocity_and_accel); // TODO(Sugahara): shoule judge is_object_front properly const bool is_object_front = true; @@ -1786,7 +1807,7 @@ std::pair GoalPlannerModule::isSafePath() const const auto target_objects_on_lane = utils::path_safety_checker::createTargetObjectsOnLane( pull_over_lanes, route_handler, filtered_objects, objects_filtering_params_); - utils::start_goal_planner_common::updateSafetyCheckTargetObjectsData( + utils::parking_departure::updateSafetyCheckTargetObjectsData( goal_planner_data_, filtered_objects, target_objects_on_lane, ego_predicted_path); const double hysteresis_factor = @@ -1812,7 +1833,7 @@ std::pair GoalPlannerModule::isSafePath() const throw std::domain_error("[pull_over] invalid safety check method"); }); - /*   + /* *   ==== is_safe *   ---- current_is_safe *   is_safe @@ -1937,8 +1958,7 @@ void GoalPlannerModule::setDebugData() } add(showPredictedPath(goal_planner_data_.collision_check, "ego_predicted_path")); add(showPolygon(goal_planner_data_.collision_check, "ego_and_target_polygon_relation")); - utils::start_goal_planner_common::initializeCollisionCheckDebugMap( - goal_planner_data_.collision_check); + utils::parking_departure::initializeCollisionCheckDebugMap(goal_planner_data_.collision_check); // visualize safety status maker { diff --git a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp similarity index 99% rename from planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp rename to planning/behavior_path_goal_planner_module/src/goal_searcher.cpp index ee8dae231f587..b087827a9c539 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/goal_searcher.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/goal_planner/goal_searcher.hpp" +#include "behavior_path_goal_planner_module/goal_searcher.hpp" -#include "behavior_path_planner/utils/goal_planner/util.hpp" +#include "behavior_path_goal_planner_module/util.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "lanelet2_extension/regulatory_elements/no_parking_area.hpp" diff --git a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp b/planning/behavior_path_goal_planner_module/src/manager.cpp similarity index 99% rename from planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp rename to planning/behavior_path_goal_planner_module/src/manager.cpp index 0916b5e8ebaef..3079361253c31 100644 --- a/planning/behavior_path_planner/src/scene_module/goal_planner/manager.cpp +++ b/planning/behavior_path_goal_planner_module/src/manager.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/goal_planner/manager.hpp" +#include "behavior_path_goal_planner_module/manager.hpp" -#include "behavior_path_planner/utils/goal_planner/util.hpp" +#include "behavior_path_goal_planner_module/util.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" #include diff --git a/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp similarity index 98% rename from planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp rename to planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp index 9ff452b131efa..712da5aa03a4e 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/shift_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/goal_planner/shift_pull_over.hpp" +#include "behavior_path_goal_planner_module/shift_pull_over.hpp" -#include "behavior_path_planner/utils/goal_planner/util.hpp" +#include "behavior_path_goal_planner_module/util.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" diff --git a/planning/behavior_path_planner/src/utils/goal_planner/util.cpp b/planning/behavior_path_goal_planner_module/src/util.cpp similarity index 99% rename from planning/behavior_path_planner/src/utils/goal_planner/util.cpp rename to planning/behavior_path_goal_planner_module/src/util.cpp index 1cd985d566f73..a01f5680dcc13 100644 --- a/planning/behavior_path_planner/src/utils/goal_planner/util.cpp +++ b/planning/behavior_path_goal_planner_module/src/util.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/goal_planner/util.hpp" +#include "behavior_path_goal_planner_module/util.hpp" #include #include diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index b99bc2a4eb2e4..75f9e7f7af187 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -14,30 +14,14 @@ ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/behavior_path_planner_node.cpp src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp src/scene_module/dynamic_avoidance/manager.cpp - src/scene_module/start_planner/start_planner_module.cpp - src/scene_module/start_planner/manager.cpp - src/scene_module/goal_planner/goal_planner_module.cpp - src/scene_module/goal_planner/manager.cpp src/scene_module/side_shift/side_shift_module.cpp src/scene_module/side_shift/manager.cpp src/scene_module/lane_change/interface.cpp src/scene_module/lane_change/normal.cpp src/scene_module/lane_change/external_request.cpp src/scene_module/lane_change/manager.cpp - src/utils/start_goal_planner_common/utils.cpp src/utils/lane_change/utils.cpp src/utils/side_shift/util.cpp - src/utils/goal_planner/util.cpp - src/utils/goal_planner/shift_pull_over.cpp - src/utils/goal_planner/geometric_pull_over.cpp - src/utils/goal_planner/freespace_pull_over.cpp - src/utils/goal_planner/goal_searcher.cpp - src/utils/goal_planner/default_fixed_goal_planner.cpp - src/utils/start_planner/util.cpp - src/utils/start_planner/shift_pull_out.cpp - src/utils/start_planner/geometric_pull_out.cpp - src/utils/start_planner/freespace_pull_out.cpp - src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp src/marker_utils/lane_change/debug.cpp ) diff --git a/planning/behavior_path_planner/plugins.xml b/planning/behavior_path_planner/plugins.xml index 5196b20dc5abd..fed2e1c9af3c3 100644 --- a/planning/behavior_path_planner/plugins.xml +++ b/planning/behavior_path_planner/plugins.xml @@ -1,6 +1,4 @@ - - diff --git a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp index c2b115ae98afe..0e253c0c73985 100644 --- a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp @@ -51,8 +51,6 @@ std::shared_ptr generateNode() std::vector module_names; module_names.emplace_back("behavior_path_planner::DynamicAvoidanceModuleManager"); module_names.emplace_back("behavior_path_planner::SideShiftModuleManager"); - module_names.emplace_back("behavior_path_planner::StartPlannerModuleManager"); - module_names.emplace_back("behavior_path_planner::GoalPlannerModuleManager"); module_names.emplace_back("behavior_path_planner::LaneChangeRightModuleManager"); module_names.emplace_back("behavior_path_planner::LaneChangeLeftModuleManager"); module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeRightModuleManager"); @@ -72,8 +70,6 @@ std::shared_ptr generateNode() behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", behavior_path_planner_dir + "/config/dynamic_avoidance/dynamic_avoidance.param.yaml", behavior_path_planner_dir + "/config/lane_change/lane_change.param.yaml", - behavior_path_planner_dir + "/config/start_planner/start_planner.param.yaml", - behavior_path_planner_dir + "/config/goal_planner/goal_planner.param.yaml", behavior_path_planner_dir + "/config/side_shift/side_shift.param.yaml"}); return std::make_shared(node_options); diff --git a/planning/behavior_path_planner_common/CMakeLists.txt b/planning/behavior_path_planner_common/CMakeLists.txt index 5567f04d5726b..5dbf81280f9b1 100644 --- a/planning/behavior_path_planner_common/CMakeLists.txt +++ b/planning/behavior_path_planner_common/CMakeLists.txt @@ -21,6 +21,8 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/utils/drivable_area_expansion/drivable_area_expansion.cpp src/utils/drivable_area_expansion/map_utils.cpp src/utils/drivable_area_expansion/footprints.cpp + src/utils/parking_departure/geometric_parallel_parking.cpp + src/utils/parking_departure/utils.cpp src/marker_utils/utils.cpp ) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp similarity index 84% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp rename to planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp index 84d84e0628cad..c270a1500431c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_GOAL_PLANNER_COMMON__COMMON_MODULE_DATA_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_GOAL_PLANNER_COMMON__COMMON_MODULE_DATA_HPP_ +#ifndef BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__COMMON_MODULE_DATA_HPP_ +#define BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__COMMON_MODULE_DATA_HPP_ #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" @@ -44,4 +44,4 @@ struct StartGoalPlannerData } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_GOAL_PLANNER_COMMON__COMMON_MODULE_DATA_HPP_ +#endif // BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__COMMON_MODULE_DATA_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp similarity index 95% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp rename to planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp index 7f5eee7a12aaa..4d1f1fdb959c0 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__GEOMETRIC_PARALLEL_PARKING__GEOMETRIC_PARALLEL_PARKING_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__GEOMETRIC_PARALLEL_PARKING__GEOMETRIC_PARALLEL_PARKING_HPP_ +#ifndef BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__GEOMETRIC_PARALLEL_PARKING_HPP_ +#define BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__GEOMETRIC_PARALLEL_PARKING_HPP_ #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/parameters.hpp" @@ -150,4 +150,4 @@ class GeometricParallelParking }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__GEOMETRIC_PARALLEL_PARKING__GEOMETRIC_PARALLEL_PARKING_HPP_ +#endif // BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__GEOMETRIC_PARALLEL_PARKING_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/utils.hpp similarity index 63% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/utils.hpp rename to planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/utils.hpp index 16be48b5acc6d..1d4245bfec0e4 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_goal_planner_common/utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/utils.hpp @@ -12,14 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_GOAL_PLANNER_COMMON__UTILS_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_GOAL_PLANNER_COMMON__UTILS_HPP_ +#ifndef BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__UTILS_HPP_ +#define BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__UTILS_HPP_ -#include "behavior_path_planner/utils/goal_planner/goal_planner_parameters.hpp" -#include "behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp" -#include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" -#include "behavior_path_planner/utils/start_planner/start_planner_parameters.hpp" #include "behavior_path_planner_common/data_manager.hpp" +#include "behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include @@ -28,10 +25,9 @@ #include #include -namespace behavior_path_planner::utils::start_goal_planner_common +namespace behavior_path_planner::utils::parking_departure { -using behavior_path_planner::StartPlannerParameters; using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebugMap; using behavior_path_planner::utils::path_safety_checker::EgoPredictedPathParams; using behavior_path_planner::utils::path_safety_checker::ObjectsFilteringParams; @@ -59,30 +55,6 @@ void modifyVelocityByDirection( std::vector> & terminal_vel_acc_pairs, const double target_velocity, const double acceleration); -void updateEgoPredictedPathParams( - std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & start_planner_params); - -void updateEgoPredictedPathParams( - std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & goal_planner_params); - -void updateSafetyCheckParams( - std::shared_ptr & safety_check_params, - const std::shared_ptr & start_planner_params); - -void updateSafetyCheckParams( - std::shared_ptr & safety_check_params, - const std::shared_ptr & goal_planner_params); - -void updateObjectsFilteringParams( - std::shared_ptr & objects_filtering_params, - const std::shared_ptr & start_planner_params); - -void updateObjectsFilteringParams( - std::shared_ptr & objects_filtering_params, - const std::shared_ptr & goal_planner_params); - void updatePathProperty( std::shared_ptr & ego_predicted_path_params, const std::pair & pairs_terminal_velocity_and_accel); @@ -103,6 +75,14 @@ std::optional generateFeasibleStopPath( geometry_msgs::msg::Pose & stop_pose, const double maximum_deceleration, const double maximum_jerk); -} // namespace behavior_path_planner::utils::start_goal_planner_common +/** + * @brief calculate end arc length to generate reference path considering the goal position + * @return a pair of s_end and terminal_is_goal + */ +std::pair calcEndArcLength( + const double s_start, const double forward_path_length, const lanelet::ConstLanelets & road_lanes, + const Pose & goal_pose); + +} // namespace behavior_path_planner::utils::parking_departure -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_GOAL_PLANNER_COMMON__UTILS_HPP_ +#endif // BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PARKING_DEPARTURE__UTILS_HPP_ diff --git a/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp b/planning/behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp similarity index 98% rename from planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp rename to planning/behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp index e6dbd2679db3c..7ba4f114328a7 100644 --- a/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp +++ b/planning/behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" +#include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" -#include "behavior_path_planner/utils/start_planner/util.hpp" +#include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" @@ -281,7 +281,7 @@ bool GeometricParallelParking::planPullOut( // get road center line path from pull_out end to goal, and combine after the second arc path const double s_start = getArcCoordinates(road_lanes, *end_pose).length; - const auto path_end_info = start_planner_utils::calcEndArcLength( + const auto path_end_info = utils::parking_departure::calcEndArcLength( s_start, planner_data_->parameters.forward_path_length, road_lanes, goal_pose); const double s_end = path_end_info.first; const bool path_terminal_is_goal = path_end_info.second; diff --git a/planning/behavior_path_planner/src/utils/start_goal_planner_common/utils.cpp b/planning/behavior_path_planner_common/src/utils/parking_departure/utils.cpp similarity index 72% rename from planning/behavior_path_planner/src/utils/start_goal_planner_common/utils.cpp rename to planning/behavior_path_planner_common/src/utils/parking_departure/utils.cpp index cbc6d6a4a0b8d..58fd392988ad9 100644 --- a/planning/behavior_path_planner/src/utils/start_goal_planner_common/utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/parking_departure/utils.cpp @@ -12,9 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/start_goal_planner_common/utils.hpp" +#include "behavior_path_planner_common/utils/parking_departure/utils.hpp" -namespace behavior_path_planner::utils::start_goal_planner_common +#include "behavior_path_planner_common/utils/utils.hpp" + +#include + +namespace behavior_path_planner::utils::parking_departure { using motion_utils::calcDecelDistWithJerkAndAccConstraints; @@ -80,53 +84,6 @@ void modifyVelocityByDirection( } } -void updateEgoPredictedPathParams( - std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & start_planner_params) -{ - ego_predicted_path_params = - std::make_shared(start_planner_params->ego_predicted_path_params); -} -void updateEgoPredictedPathParams( - std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & goal_planner_params) -{ - ego_predicted_path_params = - std::make_shared(goal_planner_params->ego_predicted_path_params); -} - -void updateSafetyCheckParams( - std::shared_ptr & safety_check_params, - const std::shared_ptr & start_planner_params) -{ - safety_check_params = - std::make_shared(start_planner_params->safety_check_params); -} - -void updateSafetyCheckParams( - std::shared_ptr & safety_check_params, - const std::shared_ptr & goal_planner_params) -{ - safety_check_params = - std::make_shared(goal_planner_params->safety_check_params); -} - -void updateObjectsFilteringParams( - std::shared_ptr & objects_filtering_params, - const std::shared_ptr & start_planner_params) -{ - objects_filtering_params = - std::make_shared(start_planner_params->objects_filtering_params); -} - -void updateObjectsFilteringParams( - std::shared_ptr & objects_filtering_params, - const std::shared_ptr & goal_planner_params) -{ - objects_filtering_params = - std::make_shared(goal_planner_params->objects_filtering_params); -} - void updatePathProperty( std::shared_ptr & ego_predicted_path_params, const std::pair & pairs_terminal_velocity_and_accel) @@ -178,7 +135,7 @@ std::optional generateFeasibleStopPath( // try to insert stop point in current_path after approval // but if can't stop with constraints(maximum deceleration, maximum jerk), don't insert stop point const auto min_stop_distance = - behavior_path_planner::utils::start_goal_planner_common::calcFeasibleDecelDistance( + behavior_path_planner::utils::parking_departure::calcFeasibleDecelDistance( planner_data, maximum_deceleration, maximum_jerk, 0.0); if (!min_stop_distance) { @@ -198,4 +155,25 @@ std::optional generateFeasibleStopPath( return current_path; } -} // namespace behavior_path_planner::utils::start_goal_planner_common +std::pair calcEndArcLength( + const double s_start, const double forward_path_length, const lanelet::ConstLanelets & road_lanes, + const Pose & goal_pose) +{ + const double s_forward_length = s_start + forward_path_length; + // use forward length if the goal pose is not in the lanelets + if (!utils::isInLanelets(goal_pose, road_lanes)) { + return {s_forward_length, false}; + } + + const double s_goal = lanelet::utils::getArcCoordinates(road_lanes, goal_pose).length; + + // If the goal is behind the start or beyond the forward length, use forward length. + if (s_goal < s_start || s_goal >= s_forward_length) { + return {s_forward_length, false}; + } + + // path end is goal + return {s_goal, true}; +} + +} // namespace behavior_path_planner::utils::parking_departure diff --git a/planning/behavior_path_start_planner_module/CMakeLists.txt b/planning/behavior_path_start_planner_module/CMakeLists.txt new file mode 100644 index 0000000000000..6bb2f76cb9842 --- /dev/null +++ b/planning/behavior_path_start_planner_module/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_path_start_planner_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_path_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/start_planner_module.cpp + src/manager.cpp + src/freespace_pull_out.cpp + src/geometric_pull_out.cpp + src/shift_pull_out.cpp + src/util.cpp +) + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/config/start_planner/start_planner.param.yaml b/planning/behavior_path_start_planner_module/config/start_planner.param.yaml similarity index 100% rename from planning/behavior_path_planner/config/start_planner/start_planner.param.yaml rename to planning/behavior_path_start_planner_module/config/start_planner.param.yaml diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/freespace_pull_out.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/freespace_pull_out.hpp similarity index 83% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/freespace_pull_out.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/freespace_pull_out.hpp index 3a154dfd83353..f38279d172009 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/freespace_pull_out.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/freespace_pull_out.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__FREESPACE_PULL_OUT_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__FREESPACE_PULL_OUT_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__FREESPACE_PULL_OUT_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__FREESPACE_PULL_OUT_HPP_ -#include "behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp" +#include "behavior_path_start_planner_module/pull_out_planner_base.hpp" #include #include @@ -49,4 +49,4 @@ class FreespacePullOut : public PullOutPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__FREESPACE_PULL_OUT_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__FREESPACE_PULL_OUT_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/geometric_pull_out.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/geometric_pull_out.hpp similarity index 70% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/geometric_pull_out.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/geometric_pull_out.hpp index 4f46350d6c2b1..164868b47535e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/geometric_pull_out.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/geometric_pull_out.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__GEOMETRIC_PULL_OUT_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__GEOMETRIC_PULL_OUT_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__GEOMETRIC_PULL_OUT_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__GEOMETRIC_PULL_OUT_HPP_ -#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" -#include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" -#include "behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp" +#include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" +#include "behavior_path_start_planner_module/pull_out_path.hpp" +#include "behavior_path_start_planner_module/pull_out_planner_base.hpp" #include @@ -36,4 +36,4 @@ class GeometricPullOut : public PullOutPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__GEOMETRIC_PULL_OUT_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__GEOMETRIC_PULL_OUT_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/manager.hpp similarity index 83% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/manager.hpp index 10fcbf81f8d45..3fb64baaa2bba 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/manager.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/manager.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__START_PLANNER__MANAGER_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__START_PLANNER__MANAGER_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__MANAGER_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__MANAGER_HPP_ -#include "behavior_path_planner/scene_module/start_planner/start_planner_module.hpp" #include "behavior_path_planner_common/interface/scene_module_manager_interface.hpp" +#include "behavior_path_start_planner_module/start_planner_module.hpp" #include @@ -53,4 +53,4 @@ class StartPlannerModuleManager : public SceneModuleManagerInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__START_PLANNER__MANAGER_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_path.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_path.hpp similarity index 84% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_path.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_path.hpp index 9c9c6fe83e288..68fcb25cac88e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_path.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_path.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__PULL_OUT_PATH_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__PULL_OUT_PATH_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PATH_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PATH_HPP_ #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -34,4 +34,4 @@ struct PullOutPath Pose end_pose{}; }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__PULL_OUT_PATH_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PATH_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp similarity index 83% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp index 60cd2731eb92f..de3d376fa4b3d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__PULL_OUT_PLANNER_BASE_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__PULL_OUT_PLANNER_BASE_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_ -#include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" -#include "behavior_path_planner/utils/start_planner/start_planner_parameters.hpp" #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" +#include "behavior_path_start_planner_module/pull_out_path.hpp" +#include "behavior_path_start_planner_module/start_planner_parameters.hpp" #include #include @@ -66,4 +66,4 @@ class PullOutPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__PULL_OUT_PLANNER_BASE_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/shift_pull_out.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/shift_pull_out.hpp similarity index 84% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/shift_pull_out.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/shift_pull_out.hpp index 7a868e6c2a234..9012504ed2e7a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/shift_pull_out.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/shift_pull_out.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__SHIFT_PULL_OUT_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__SHIFT_PULL_OUT_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__SHIFT_PULL_OUT_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__SHIFT_PULL_OUT_HPP_ -#include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" -#include "behavior_path_planner/utils/start_planner/pull_out_planner_base.hpp" +#include "behavior_path_start_planner_module/pull_out_path.hpp" +#include "behavior_path_start_planner_module/pull_out_planner_base.hpp" #include @@ -57,4 +57,4 @@ class ShiftPullOut : public PullOutPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__SHIFT_PULL_OUT_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__SHIFT_PULL_OUT_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp similarity index 88% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp index f70effb7cf186..a143f34ead649 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp @@ -12,20 +12,20 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__START_PLANNER__START_PLANNER_MODULE_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__START_PLANNER__START_PLANNER_MODULE_HPP_ - -#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" -#include "behavior_path_planner/utils/start_goal_planner_common/common_module_data.hpp" -#include "behavior_path_planner/utils/start_planner/freespace_pull_out.hpp" -#include "behavior_path_planner/utils/start_planner/geometric_pull_out.hpp" -#include "behavior_path_planner/utils/start_planner/pull_out_path.hpp" -#include "behavior_path_planner/utils/start_planner/shift_pull_out.hpp" -#include "behavior_path_planner/utils/start_planner/start_planner_parameters.hpp" +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_MODULE_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_MODULE_HPP_ + #include "behavior_path_planner_common/interface/scene_module_interface.hpp" +#include "behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" +#include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" #include "behavior_path_planner_common/utils/utils.hpp" +#include "behavior_path_start_planner_module/freespace_pull_out.hpp" +#include "behavior_path_start_planner_module/geometric_pull_out.hpp" +#include "behavior_path_start_planner_module/pull_out_path.hpp" +#include "behavior_path_start_planner_module/shift_pull_out.hpp" +#include "behavior_path_start_planner_module/start_planner_parameters.hpp" #include #include @@ -100,6 +100,18 @@ class StartPlannerModule : public SceneModuleInterface void processOnExit() override; void updateData() override; + void updateEgoPredictedPathParams( + std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & start_planner_params); + + void updateSafetyCheckParams( + std::shared_ptr & safety_check_params, + const std::shared_ptr & start_planner_params); + + void updateObjectsFilteringParams( + std::shared_ptr & objects_filtering_params, + const std::shared_ptr & start_planner_params); + void setParameters(const std::shared_ptr & parameters) { parameters_ = parameters; @@ -244,4 +256,4 @@ class StartPlannerModule : public SceneModuleInterface }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__START_PLANNER__START_PLANNER_MODULE_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_MODULE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp similarity index 91% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp index cbde2b514366d..783aace0983ca 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/start_planner_parameters.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_parameters.hpp @@ -13,10 +13,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__START_PLANNER_PARAMETERS_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__START_PLANNER_PARAMETERS_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_PARAMETERS_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_PARAMETERS_HPP_ -#include "behavior_path_planner/utils/geometric_parallel_parking/geometric_parallel_parking.hpp" +#include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include @@ -104,4 +104,4 @@ struct StartPlannerParameters } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__START_PLANNER_PARAMETERS_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_PARAMETERS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/util.hpp similarity index 81% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp rename to planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/util.hpp index 5fcb5fd5668b1..147632329d926 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/util.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/util.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__UTIL_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__UTIL_HPP_ +#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__UTIL_HPP_ +#define BEHAVIOR_PATH_START_PLANNER_MODULE__UTIL_HPP_ #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" @@ -50,13 +50,6 @@ lanelet::ConstLanelets getPullOutLanes( const std::shared_ptr & planner_data, const double backward_length); Pose getBackedPose( const Pose & current_pose, const double & yaw_shoulder_lane, const double & back_distance); -/** - * @brief calculate end arc length to generate reference path considering the goal position - * @return a pair of s_end and terminal_is_goal - */ -std::pair calcEndArcLength( - const double s_start, const double forward_path_length, const lanelet::ConstLanelets & road_lanes, - const Pose & goal_pose); } // namespace behavior_path_planner::start_planner_utils -#endif // BEHAVIOR_PATH_PLANNER__UTILS__START_PLANNER__UTIL_HPP_ +#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__UTIL_HPP_ diff --git a/planning/behavior_path_start_planner_module/package.xml b/planning/behavior_path_start_planner_module/package.xml new file mode 100644 index 0000000000000..393c1d46fa789 --- /dev/null +++ b/planning/behavior_path_start_planner_module/package.xml @@ -0,0 +1,35 @@ + + + + behavior_path_start_planner_module + 0.1.0 + The behavior_path_start_planner_module package + + Kyoichi Sugahara + Kosuke Takeuchi + Satoshi OTA + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + behavior_path_planner + behavior_path_planner_common + motion_utils + pluginlib + rclcpp + rtc_interface + tier4_autoware_utils + tier4_planning_msgs + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_path_start_planner_module/plugins.xml b/planning/behavior_path_start_planner_module/plugins.xml new file mode 100644 index 0000000000000..fde8b673be5bc --- /dev/null +++ b/planning/behavior_path_start_planner_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_path_planner/src/utils/start_planner/freespace_pull_out.cpp b/planning/behavior_path_start_planner_module/src/freespace_pull_out.cpp similarity index 93% rename from planning/behavior_path_planner/src/utils/start_planner/freespace_pull_out.cpp rename to planning/behavior_path_start_planner_module/src/freespace_pull_out.cpp index 32a36e1d70509..dd068c3c26cf8 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/freespace_pull_out.cpp +++ b/planning/behavior_path_start_planner_module/src/freespace_pull_out.cpp @@ -12,11 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/start_planner/freespace_pull_out.hpp" +#include "behavior_path_start_planner_module/freespace_pull_out.hpp" -#include "behavior_path_planner/utils/start_planner/util.hpp" +#include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" +#include "behavior_path_start_planner_module/util.hpp" #include @@ -90,8 +91,8 @@ std::optional FreespacePullOut::plan(const Pose & start_pose, const constexpr double offset_from_end_pose = 1.0; const auto arc_position_end = lanelet::utils::getArcCoordinates(road_lanes, end_pose); const double s_start = std::max(arc_position_end.length + offset_from_end_pose, 0.0); - const auto path_end_info = - start_planner_utils::calcEndArcLength(s_start, forward_path_length, road_lanes, goal_pose); + const auto path_end_info = behavior_path_planner::utils::parking_departure::calcEndArcLength( + s_start, forward_path_length, road_lanes, goal_pose); const double s_end = path_end_info.first; const bool path_terminal_is_goal = path_end_info.second; diff --git a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp b/planning/behavior_path_start_planner_module/src/geometric_pull_out.cpp similarity index 97% rename from planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp rename to planning/behavior_path_start_planner_module/src/geometric_pull_out.cpp index fefa6b440c096..7d6dd60398e8e 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/geometric_pull_out.cpp +++ b/planning/behavior_path_start_planner_module/src/geometric_pull_out.cpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/start_planner/geometric_pull_out.hpp" +#include "behavior_path_start_planner_module/geometric_pull_out.hpp" -#include "behavior_path_planner/utils/start_planner/util.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" +#include "behavior_path_start_planner_module/util.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp b/planning/behavior_path_start_planner_module/src/manager.cpp similarity index 99% rename from planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp rename to planning/behavior_path_start_planner_module/src/manager.cpp index 14660396062aa..58d0fbee7921b 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp +++ b/planning/behavior_path_start_planner_module/src/manager.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/start_planner/manager.hpp" +#include "behavior_path_start_planner_module/manager.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" diff --git a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp similarity index 97% rename from planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp rename to planning/behavior_path_start_planner_module/src/shift_pull_out.cpp index dd1d3d3c4cca4..73952ca02f558 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp +++ b/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/start_planner/shift_pull_out.hpp" +#include "behavior_path_start_planner_module/shift_pull_out.hpp" -#include "behavior_path_planner/utils/start_goal_planner_common/utils.hpp" -#include "behavior_path_planner/utils/start_planner/util.hpp" +#include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" +#include "behavior_path_start_planner_module/util.hpp" #include "motion_utils/trajectory/path_with_lane_id.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" @@ -187,8 +187,8 @@ std::vector ShiftPullOut::calcPullOutPaths( // generate road lane reference path const auto arc_position_start = getArcCoordinates(road_lanes, start_pose); const double s_start = std::max(arc_position_start.length - backward_path_length, 0.0); - const auto path_end_info = - start_planner_utils::calcEndArcLength(s_start, forward_path_length, road_lanes, goal_pose); + const auto path_end_info = behavior_path_planner::utils::parking_departure::calcEndArcLength( + s_start, forward_path_length, road_lanes, goal_pose); const double s_end = path_end_info.first; const bool path_terminal_is_goal = path_end_info.second; diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp similarity index 96% rename from planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp rename to planning/behavior_path_start_planner_module/src/start_planner_module.cpp index 7bede9192d35f..ca84795cb77b3 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/start_planner/start_planner_module.hpp" +#include "behavior_path_start_planner_module/start_planner_module.hpp" -#include "behavior_path_planner/utils/start_goal_planner_common/utils.hpp" -#include "behavior_path_planner/utils/start_planner/util.hpp" #include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" +#include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" +#include "behavior_path_start_planner_module/util.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include @@ -36,7 +36,7 @@ #include #include -using behavior_path_planner::utils::start_goal_planner_common::initializeCollisionCheckDebugMap; +using behavior_path_planner::utils::parking_departure::initializeCollisionCheckDebugMap; using motion_utils::calcLongitudinalOffsetPose; using tier4_autoware_utils::calcOffsetPose; @@ -130,6 +130,30 @@ void StartPlannerModule::initVariables() initializeCollisionCheckDebugMap(start_planner_data_.collision_check); } +void StartPlannerModule::updateEgoPredictedPathParams( + std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & start_planner_params) +{ + ego_predicted_path_params = + std::make_shared(start_planner_params->ego_predicted_path_params); +} + +void StartPlannerModule::updateSafetyCheckParams( + std::shared_ptr & safety_check_params, + const std::shared_ptr & start_planner_params) +{ + safety_check_params = + std::make_shared(start_planner_params->safety_check_params); +} + +void StartPlannerModule::updateObjectsFilteringParams( + std::shared_ptr & objects_filtering_params, + const std::shared_ptr & start_planner_params) +{ + objects_filtering_params = + std::make_shared(start_planner_params->objects_filtering_params); +} + void StartPlannerModule::updateData() { if (receivedNewRoute()) { @@ -350,7 +374,7 @@ BehaviorModuleOutput StartPlannerModule::plan() if (!status_.is_safe_dynamic_objects && !isWaitingApproval() && !status_.has_stop_point) { auto current_path = getCurrentPath(); const auto stop_path = - behavior_path_planner::utils::start_goal_planner_common::generateFeasibleStopPath( + behavior_path_planner::utils::parking_departure::generateFeasibleStopPath( current_path, planner_data_, *stop_pose_, parameters_->maximum_deceleration_for_stop, parameters_->maximum_jerk_for_stop); @@ -431,11 +455,9 @@ CandidateOutput StartPlannerModule::planCandidate() const void StartPlannerModule::initializeSafetyCheckParameters() { - utils::start_goal_planner_common::updateEgoPredictedPathParams( - ego_predicted_path_params_, parameters_); - utils::start_goal_planner_common::updateSafetyCheckParams(safety_check_params_, parameters_); - utils::start_goal_planner_common::updateObjectsFilteringParams( - objects_filtering_params_, parameters_); + updateEgoPredictedPathParams(ego_predicted_path_params_, parameters_); + updateSafetyCheckParams(safety_check_params_, parameters_); + updateObjectsFilteringParams(objects_filtering_params_, parameters_); } PathWithLaneId StartPlannerModule::getFullPath() const @@ -1095,13 +1117,13 @@ bool StartPlannerModule::isSafePath() const // for ego predicted path const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(pull_out_path.points); const std::pair terminal_velocity_and_accel = - utils::start_goal_planner_common::getPairsTerminalVelocityAndAccel( + utils::parking_departure::getPairsTerminalVelocityAndAccel( status_.pull_out_path.pairs_terminal_velocity_and_accel, status_.current_path_idx); RCLCPP_DEBUG( getLogger(), "pairs_terminal_velocity_and_accel for start_planner: %f, %f", terminal_velocity_and_accel.first, terminal_velocity_and_accel.second); RCLCPP_DEBUG(getLogger(), "current_path_idx %ld", status_.current_path_idx); - utils::start_goal_planner_common::updatePathProperty( + utils::parking_departure::updatePathProperty( ego_predicted_path_params_, terminal_velocity_and_accel); // TODO(Sugahara): shoule judge is_object_front properly const bool is_object_front = true; @@ -1122,7 +1144,7 @@ bool StartPlannerModule::isSafePath() const const double hysteresis_factor = status_.is_safe_dynamic_objects ? 1.0 : safety_check_params_->hysteresis_factor_expand_rate; - utils::start_goal_planner_common::updateSafetyCheckTargetObjectsData( + utils::parking_departure::updateSafetyCheckTargetObjectsData( start_planner_data_, filtered_objects, target_objects_on_lane, ego_predicted_path); return behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS( diff --git a/planning/behavior_path_planner/src/utils/start_planner/util.cpp b/planning/behavior_path_start_planner_module/src/util.cpp similarity index 83% rename from planning/behavior_path_planner/src/utils/start_planner/util.cpp rename to planning/behavior_path_start_planner_module/src/util.cpp index 0b26c793155f7..9a9466936c422 100644 --- a/planning/behavior_path_planner/src/utils/start_planner/util.cpp +++ b/planning/behavior_path_start_planner_module/src/util.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/start_planner/util.hpp" +#include "behavior_path_start_planner_module/util.hpp" #include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -106,25 +106,4 @@ lanelet::ConstLanelets getPullOutLanes( /*forward_only_in_route*/ true); } -std::pair calcEndArcLength( - const double s_start, const double forward_path_length, const lanelet::ConstLanelets & road_lanes, - const Pose & goal_pose) -{ - const double s_forward_length = s_start + forward_path_length; - // use forward length if the goal pose is not in the lanelets - if (!utils::isInLanelets(goal_pose, road_lanes)) { - return {s_forward_length, false}; - } - - const double s_goal = lanelet::utils::getArcCoordinates(road_lanes, goal_pose).length; - - // If the goal is behind the start or beyond the forward length, use forward length. - if (s_goal < s_start || s_goal >= s_forward_length) { - return {s_forward_length, false}; - } - - // path end is goal - return {s_goal, true}; -} - } // namespace behavior_path_planner::start_planner_utils From 3ec620148cc8dc77a035652dd7412f6cc902e206 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 7 Dec 2023 18:26:14 +0900 Subject: [PATCH 08/87] fix(avoidance): fix invalid optional access (#5804) Signed-off-by: satoshi-ota --- .../src/shift_line_generator.cpp | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp index 48d7e3a4baf8b..108412876d47f 100644 --- a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp @@ -966,6 +966,7 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( AvoidLineArray ret = shift_lines; constexpr double ep = 1.0e-3; + constexpr double RETURN_SHIFT_THRESHOLD = 0.1; const bool has_candidate_point = !ret.empty(); const bool has_registered_point = last_.has_value(); @@ -977,14 +978,15 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( return ret; } - // If the return-to-center shift points are already registered, do nothing. - if (!has_registered_point && std::fabs(base_offset_) < ep) { - return ret; - } - - constexpr double RETURN_SHIFT_THRESHOLD = 0.1; - if (std::abs(last_.value().end_shift_length) < RETURN_SHIFT_THRESHOLD) { - return ret; + if (last_.has_value()) { + if (std::abs(last_.value().end_shift_length) < RETURN_SHIFT_THRESHOLD) { + return ret; + } + } else { + // If the return-to-center shift points are already registered, do nothing. + if (std::abs(base_offset_) < ep) { + return ret; + } } // From here, the return-to-center is not registered. But perhaps the candidate is From 566c57f671c4aa01cd0a52b214ffbbda16ef47f9 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 7 Dec 2023 21:47:20 +0900 Subject: [PATCH 09/87] refactor(behavior_path_planner): delete unnecessary TODO (#5806) delete unnecessary TODO Signed-off-by: kyoichi-sugahara --- .../src/goal_planner_module.cpp | 1 - .../src/scene_module/lane_change/interface.cpp | 1 - .../src/start_planner_module.cpp | 2 -- 3 files changed, 4 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 19c60d77b3d67..98f5664153bfd 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 @@ -873,7 +873,6 @@ void GoalPlannerModule::updateSteeringFactor( return SteeringFactor::STRAIGHT; }); - // TODO(tkhmy) add handle status TRYING steering_factor_interface_ptr_->updateSteeringFactor( pose, distance, PlanningBehavior::GOAL_PLANNER, steering_factor_direction, type, ""); } diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp index 26fc423fce02f..cec9d5013d929 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp @@ -372,7 +372,6 @@ void LaneChangeInterface::updateSteeringFactorPtr(const BehaviorModuleOutput & o const auto finish_distance = motion_utils::calcSignedArcLength( output.path->points, current_position, status.lane_change_path.info.shift_line.end.position); - // TODO(tkhmy) add handle status TRYING steering_factor_interface_ptr_->updateSteeringFactor( {status.lane_change_path.info.shift_line.start, status.lane_change_path.info.shift_line.end}, {start_distance, finish_distance}, PlanningBehavior::LANE_CHANGE, steering_factor_direction, 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 ca84795cb77b3..0d3892cde8023 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 @@ -427,7 +427,6 @@ BehaviorModuleOutput StartPlannerModule::plan() path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.end_pose.position); updateRTCStatus(start_distance, finish_distance); - // TODO(tkhmy) add handle status TRYING steering_factor_interface_ptr_->updateSteeringFactor( {status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, {start_distance, finish_distance}, PlanningBehavior::START_PLANNER, steering_factor_direction, @@ -437,7 +436,6 @@ BehaviorModuleOutput StartPlannerModule::plan() path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); updateRTCStatus(0.0, distance); - // TODO(tkhmy) add handle status TRYING steering_factor_interface_ptr_->updateSteeringFactor( {status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, {0.0, distance}, PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::TURNING, ""); From 089e8f27c9fb4493137854e54c2e155b93d1900b Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 8 Dec 2023 09:35:08 +0900 Subject: [PATCH 10/87] chore(bpp): update maintainer (#5809) Signed-off-by: satoshi-ota --- .../package.xml | 3 +++ .../package.xml | 3 +++ .../package.xml | 3 +++ planning/behavior_path_planner/package.xml | 21 ++++++------------- .../package.xml | 5 ++++- 5 files changed, 19 insertions(+), 16 deletions(-) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/package.xml b/planning/behavior_path_avoidance_by_lane_change_module/package.xml index 3bb32bdf76bf0..da51dd9f235dc 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/package.xml +++ b/planning/behavior_path_avoidance_by_lane_change_module/package.xml @@ -8,6 +8,9 @@ Satoshi Ota Zulfaqar Azmi Fumiya Watanabe + Tomoya Kimura + Shumpei Wakabayashi + Tomohito Ando Apache License 2.0 diff --git a/planning/behavior_path_avoidance_module/package.xml b/planning/behavior_path_avoidance_module/package.xml index 68cc911e9373d..642f83497acfb 100644 --- a/planning/behavior_path_avoidance_module/package.xml +++ b/planning/behavior_path_avoidance_module/package.xml @@ -9,6 +9,9 @@ Satoshi Ota Fumiya Watanabe Kyoichi Sugahara + Tomoya Kimura + Shumpei Wakabayashi + Tomohito Ando Apache License 2.0 diff --git a/planning/behavior_path_goal_planner_module/package.xml b/planning/behavior_path_goal_planner_module/package.xml index d29f6c6124750..213c0093b08d9 100644 --- a/planning/behavior_path_goal_planner_module/package.xml +++ b/planning/behavior_path_goal_planner_module/package.xml @@ -8,6 +8,9 @@ Kosuke Takeuchi Kyoichi Sugahara Satoshi OTA + Tomoya Kimura + Shumpei Wakabayashi + Tomohito Ando Apache License 2.0 diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index 5ca86ee5a47b6..0ca7badd0b3f4 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -7,28 +7,19 @@ Zulfaqar Azmi - - Kosuke Takeuchi - - Kosuke Takeuchi Fumiya Watanabe Kyoichi Sugahara - - Takamasa Horibe - Satoshi Ota - - Zulfaqar Azmi - Satoshi Ota - Mamoru Sobue - - - Takayuki Murooka - Taiki Tanaka Tomoya Kimura Shumpei Wakabayashi + Tomohito Ando + Takamasa Horibe + Satoshi Ota + Kosuke Takeuchi + Kyoichi Sugahara + Takayuki Murooka Apache License 2.0 diff --git a/planning/behavior_path_start_planner_module/package.xml b/planning/behavior_path_start_planner_module/package.xml index 393c1d46fa789..cbfdba0d07a57 100644 --- a/planning/behavior_path_start_planner_module/package.xml +++ b/planning/behavior_path_start_planner_module/package.xml @@ -5,9 +5,12 @@ 0.1.0 The behavior_path_start_planner_module package - Kyoichi Sugahara Kosuke Takeuchi + Kyoichi Sugahara Satoshi OTA + Tomoya Kimura + Shumpei Wakabayashi + Tomohito Ando Apache License 2.0 From 795d7871b7b0fa385c10c47dae6d7711944e06d1 Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Fri, 8 Dec 2023 10:20:39 +0900 Subject: [PATCH 11/87] fix(crosswalk_traffic_light_estimator): add operation to remove traffic signals with duplicated ids (#5653) * fix: add operation to remove traffic signals with duplicated ids Signed-off-by: ktro2828 * feat: move operation into `crosswalk_traffic_light_estimator` Signed-off-by: ktro2828 --------- Signed-off-by: ktro2828 --- .../crosswalk_traffic_light_estimator/node.hpp | 2 ++ .../src/node.cpp | 17 +++++++++++++++++ 2 files changed, 19 insertions(+) diff --git a/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp b/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp index e38b747a6ce67..848293f6334bb 100644 --- a/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp +++ b/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp @@ -92,6 +92,8 @@ class CrosswalkTrafficLightEstimatorNode : public rclcpp::Node boost::optional getHighestConfidenceTrafficSignal( const lanelet::Id & id, const TrafficLightIdMap & traffic_light_id_map) const; + void removeDuplicateIds(TrafficSignalArray & signal_array) const; + // Node param bool use_last_detect_color_; double last_detect_color_hold_time_; diff --git a/perception/crosswalk_traffic_light_estimator/src/node.cpp b/perception/crosswalk_traffic_light_estimator/src/node.cpp index 870b8bc7c13f5..6527f0662bcbf 100644 --- a/perception/crosswalk_traffic_light_estimator/src/node.cpp +++ b/perception/crosswalk_traffic_light_estimator/src/node.cpp @@ -174,6 +174,8 @@ void CrosswalkTrafficLightEstimatorNode::onTrafficLightArray( setCrosswalkTrafficSignal(crosswalk, crosswalk_tl_color, output); } + removeDuplicateIds(output); + updateLastDetectedSignal(traffic_light_id_map); pub_traffic_light_array_->publish(output); @@ -383,6 +385,21 @@ boost::optional CrosswalkTrafficLightEstimatorNode::getHighestConfidenc return ret; } + +void CrosswalkTrafficLightEstimatorNode::removeDuplicateIds(TrafficSignalArray & signal_array) const +{ + auto & signals = signal_array.signals; + std::sort(signals.begin(), signals.end(), [](const auto & s1, const auto & s2) { + return s1.traffic_signal_id < s2.traffic_signal_id; + }); + + signals.erase( + std::unique( + signals.begin(), signals.end(), + [](const auto & s1, const auto s2) { return s1.traffic_signal_id == s2.traffic_signal_id; }), + signals.end()); +} + } // namespace traffic_light #include From aeb461a01779483c1ee665da7a40eb440cf0d900 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 8 Dec 2023 10:24:27 +0900 Subject: [PATCH 12/87] refactor(multi_object_tracker): put node parameters to yaml file (#5769) * rework multi object tracker parameters Signed-off-by: yoshiri * update README Signed-off-by: yoshiri * rework radar tracker parameter too Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- .../tracking/tracking.launch.xml | 10 ++----- .../launch/perception.launch.xml | 1 + perception/multi_object_tracker/README.md | 30 ++++++++++++------- ...l => multi_object_tracker_node.param.yaml} | 6 ++++ .../launch/multi_object_tracker.launch.xml | 8 +---- .../src/multi_object_tracker_core.cpp | 6 ++-- .../launch/radar_object_tracker.launch.xml | 6 ---- 7 files changed, 33 insertions(+), 34 deletions(-) rename perception/multi_object_tracker/config/{default_tracker.param.yaml => multi_object_tracker_node.param.yaml} (68%) diff --git a/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml index 07b53fb671732..85c6e87c0fd19 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml @@ -1,8 +1,6 @@ - - @@ -19,8 +17,7 @@ - - + @@ -29,15 +26,12 @@ - - + - - diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 96ad80131e4e7..da393b1efff59 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -14,6 +14,7 @@ + diff --git a/perception/multi_object_tracker/README.md b/perception/multi_object_tracker/README.md index 0cc8f1708e334..311fe7b6da716 100644 --- a/perception/multi_object_tracker/README.md +++ b/perception/multi_object_tracker/README.md @@ -70,16 +70,26 @@ Example: ### Core Parameters -| Name | Type | Description | -| --------------------------- | ------ | -------------------------------------------------------------- | -| `can_assign_matrix` | double | Assignment table for data association | -| `max_dist_matrix` | double | Maximum distance table for data association | -| `max_area_matrix` | double | Maximum area table for data association | -| `min_area_matrix` | double | Minimum area table for data association | -| `max_rad_matrix` | double | Maximum angle table for data association | -| `world_frame_id` | double | tracking frame | -| `enable_delay_compensation` | bool | Estimate obstacles at current time considering detection delay | -| `publish_rate` | double | if enable_delay_compensation is true, how many hertz to output | +Node parameters are defined in [multi_object_tracker.param.yaml](config/multi_object_tracker.param.yaml) and association parameters are defined in [data_association.param.yaml](config/data_association.param.yaml). + +#### Node parameters + +| Name | Type | Description | +| --------------------------- | ------ | --------------------------------------------------------------------------------------------------------------------------- | +| `***_tracker` | string | EKF tracker name for each class | +| `world_frame_id` | double | object kinematics definition frame | +| `enable_delay_compensation` | bool | if True, tracker use timers to schedule publishers and use prediction step to extrapolate object state at desired timestamp | +| `publish_rate` | double | Timer frequency to output with delay compensation | + +#### Association parameters + +| Name | Type | Description | +| ------------------- | ------ | ------------------------------------------- | +| `can_assign_matrix` | double | Assignment table for data association | +| `max_dist_matrix` | double | Maximum distance table for data association | +| `max_area_matrix` | double | Maximum area table for data association | +| `min_area_matrix` | double | Minimum area table for data association | +| `max_rad_matrix` | double | Maximum angle table for data association | ## Assumptions / Known limits diff --git a/perception/multi_object_tracker/config/default_tracker.param.yaml b/perception/multi_object_tracker/config/multi_object_tracker_node.param.yaml similarity index 68% rename from perception/multi_object_tracker/config/default_tracker.param.yaml rename to perception/multi_object_tracker/config/multi_object_tracker_node.param.yaml index 23e88d8274172..9552b35b65bed 100644 --- a/perception/multi_object_tracker/config/default_tracker.param.yaml +++ b/perception/multi_object_tracker/config/multi_object_tracker_node.param.yaml @@ -1,5 +1,6 @@ /**: ros__parameters: + # default tracker models for each class car_tracker: "multi_vehicle_tracker" truck_tracker: "multi_vehicle_tracker" bus_tracker: "multi_vehicle_tracker" @@ -7,3 +8,8 @@ pedestrian_tracker: "pedestrian_and_bicycle_tracker" bicycle_tracker: "pedestrian_and_bicycle_tracker" motorcycle_tracker: "pedestrian_and_bicycle_tracker" + + # default tracker node parameters + publish_rate: 10.0 + world_frame_id: map + enable_delay_compensation: false diff --git a/perception/multi_object_tracker/launch/multi_object_tracker.launch.xml b/perception/multi_object_tracker/launch/multi_object_tracker.launch.xml index 21a2ce67d552d..dcd080b851c20 100644 --- a/perception/multi_object_tracker/launch/multi_object_tracker.launch.xml +++ b/perception/multi_object_tracker/launch/multi_object_tracker.launch.xml @@ -2,18 +2,12 @@ - - - - + - - - 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 d302b04d733cd..e42ff748c503e 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -78,9 +78,9 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) create_publisher("output", rclcpp::QoS{1}); // Parameters - double publish_rate = declare_parameter("publish_rate", 30.0); - world_frame_id_ = declare_parameter("world_frame_id", "world"); - bool enable_delay_compensation{declare_parameter("enable_delay_compensation", false)}; + double publish_rate = declare_parameter("publish_rate"); + world_frame_id_ = declare_parameter("world_frame_id"); + bool enable_delay_compensation{declare_parameter("enable_delay_compensation")}; auto cti = std::make_shared( this->get_node_base_interface(), this->get_node_timers_interface()); diff --git a/perception/radar_object_tracker/launch/radar_object_tracker.launch.xml b/perception/radar_object_tracker/launch/radar_object_tracker.launch.xml index 6e6813d3e40ff..60ed2efb5767b 100644 --- a/perception/radar_object_tracker/launch/radar_object_tracker.launch.xml +++ b/perception/radar_object_tracker/launch/radar_object_tracker.launch.xml @@ -2,9 +2,6 @@ - - - @@ -19,8 +16,5 @@ - - - From 0e9d1f04eba87a313fe8cd550dd61d093b3ea189 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 8 Dec 2023 14:26:53 +0900 Subject: [PATCH 13/87] chore(crosswalk): update comments (#5813) * fix typo * update comments Signed-off-by: Yuki Takagi --- .../config/crosswalk.param.yaml | 36 +++++++++---------- .../src/manager.cpp | 8 ++--- 2 files changed, 22 insertions(+), 22 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml index 762639950b2c5..6559f39278fdc 100644 --- a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml +++ b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml @@ -9,7 +9,7 @@ # param for stop position stop_position: - stop_position_threshold: 1.0 # [m] threshold to check whether the vehicle stops in front of crosswalk for yielding + stop_position_threshold: 1.0 # [m] If the ego vehicle has stopped near the stop line than this value, this module assumes itself to have achieved yielding. # For the Lanelet2 map with no explicit stop lines stop_distance_from_crosswalk: 3.5 # [m] make stop line away from crosswalk @@ -18,24 +18,24 @@ # For the case where the stop position is determined according to the object position. stop_distance_from_object: 2.0 # [m] the vehicle decelerates to be able to stop in front of object with margin - # param for ego's slow down velocity + # params for ego's slow down velocity. These params are not used for the case of "enable_rtc: false". slow_down: min_slow_down_velocity: 2.78 # [m/s] target vehicle velocity when module receive slow down command from FOA (2.78 m/s = 10.0 kmph) max_slow_down_jerk: -1.5 # [m/sss] minimum jerk deceleration for safe brake max_slow_down_accel: -2.5 # [m/ss] minimum accel deceleration for safe brake no_relax_velocity: 2.78 # [m/s] if the current velocity is less than X m/s, ego always stops at the stop position(not relax deceleration constraints 2.78 m/s = 10 kmph) - # param for stuck vehicles + # params to prevent stopping on crosswalks due to another vehicle ahead stuck_vehicle: enable_stuck_check_in_intersection: false # [-] flag to enable stuck vehicle checking for crosswalk which is in intersection - stuck_vehicle_velocity: 1.0 # [m/s] maximum velocity threshold whether the vehicle is stuck - max_stuck_vehicle_lateral_offset: 2.0 # [m] maximum lateral offset for stuck vehicle position should be looked - stuck_vehicle_attention_range: 10.0 # [m] the detection area is defined as X meters behind the crosswalk - min_acc: -1.0 # min acceleration [m/ss] - min_jerk: -1.0 # min jerk [m/sss] - max_jerk: 1.0 # max jerk [m/sss] + stuck_vehicle_velocity: 1.0 # [m/s] threshold velocity whether other vehicles are assumed to be stuck or not. + max_stuck_vehicle_lateral_offset: 2.0 # [m] The feature does not handle the vehicles farther than this value to the ego's path. + stuck_vehicle_attention_range: 10.0 # [m] Ego does not enter the crosswalk area if a stuck vehicle exists within this distance from the end of the crosswalk on the ego's path. + min_acc: -1.0 # min acceleration [m/ss] + min_jerk: -1.0 # min jerk [m/sss] + max_jerk: 1.0 # max jerk [m/sss] - # param for pass judge logic + # params for the pass judge logic against the crosswalk users such as pedestrians or bicycles pass_judge: ego_pass_first_margin_x: [0.0] # [[s]] time to collision margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) ego_pass_first_margin_y: [6.0] # [[s]] time to vehicle margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) @@ -44,21 +44,21 @@ ego_pass_later_margin_y: [10.0] # [[s]] time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) ego_pass_later_additional_margin: 0.5 # [s] additional time margin for object pass first situation to suppress chattering - no_stop_decision: + no_stop_decision: # parameters to determine if it is safe to attempt stopping before the crosswalk max_offset_to_crosswalk_for_yield: 0.0 # [m] maximum offset from ego's front to crosswalk for yield. Positive value means in front of the crosswalk. - min_acc: -1.0 # min acceleration [m/ss] - min_jerk: -1.0 # min jerk [m/sss] - max_jerk: 1.0 # max jerk [m/sss] + min_acc: -1.0 # min acceleration [m/ss] + min_jerk: -1.0 # min jerk [m/sss] + max_jerk: 1.0 # max jerk [m/sss] stop_object_velocity_threshold: 0.28 # [m/s] velocity threshold for the module to judge whether the objects is stopped (0.28 m/s = 1.0 kmph) min_object_velocity: 1.39 # [m/s] minimum object velocity (compare the estimated velocity by perception module with this parameter and adopt the larger one to calculate TTV. 1.39 m/s = 5.0 kmph) ## param for yielding - disable_stop_for_yield_cancel: true # for the crosswalk where there is a traffic signal - disable_yield_for_new_stopped_object: true # for the crosswalk where there is a traffic signal - # if the pedestrian does not move for X seconds after stopping before the crosswalk, the module judge that ego is able to pass first. + disable_stop_for_yield_cancel: true # for the crosswalks with traffic signal + disable_yield_for_new_stopped_object: true # for the crosswalks with traffic signal + # If the pedestrian does not move for X seconds after the ego has stopped in front the crosswalk, the module judge that the pedestrian has no intention to walk and allows the ego to proceed. distance_map_for_no_intention_to_walk: [1.0, 5.0] # [m] ascending order timeout_map_for_no_intention_to_walk: [3.0, 0.0] # [s] - timeout_ego_stop_for_yield: 3.0 # [s] the amount of time which ego should be stopping to query whether it yields or not + timeout_ego_stop_for_yield: 3.0 # [s] If the ego maintains the stop for this amount of time, then the ego proceeds, assuming it has stopped long time enough. # param for target object filtering object_filtering: diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index c743d440bee85..cb0311ffe8ebb 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -152,10 +152,10 @@ void CrosswalkModuleManager::launchNewModules(const PathWithLaneId & path) path.header.stamp); }; - const auto crosswalk_leg_elem_map = planning_utils::getRegElemMapOnPath( + const auto crosswalk_reg_elem_map = planning_utils::getRegElemMapOnPath( path, rh->getLaneletMapPtr(), planner_data_->current_odometry->pose); - for (const auto & crosswalk : crosswalk_leg_elem_map) { + for (const auto & crosswalk : crosswalk_reg_elem_map) { // NOTE: The former id is a lane id, and the latter one is a regulatory element's id. launch(crosswalk.second.id(), crosswalk.first->crosswalkLanelet().id(), crosswalk.first->id()); } @@ -178,10 +178,10 @@ CrosswalkModuleManager::getModuleExpiredFunction(const PathWithLaneId & path) crosswalk_id_set = getCrosswalkIdSetOnPath( planner_data_->current_odometry->pose, path, rh->getLaneletMapPtr(), rh->getOverallGraphPtr()); - const auto crosswalk_leg_elem_map = planning_utils::getRegElemMapOnPath( + const auto crosswalk_reg_elem_map = planning_utils::getRegElemMapOnPath( path, rh->getLaneletMapPtr(), planner_data_->current_odometry->pose); - for (const auto & crosswalk : crosswalk_leg_elem_map) { + for (const auto & crosswalk : crosswalk_reg_elem_map) { crosswalk_id_set.insert(crosswalk.first->crosswalkLanelet().id()); } From f582b5a17f594e12fcc3f682c66b5aacc9efa818 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 8 Dec 2023 15:00:57 +0900 Subject: [PATCH 14/87] refactor(motion_utils): stop using CAPACITY from Trajectory message (#5755) Signed-off-by: Maxime CLEMENT --- common/motion_utils/src/trajectory/tmp_conversion.cpp | 7 +------ .../test/src/trajectory/test_trajectory.cpp | 11 ----------- 2 files changed, 1 insertion(+), 17 deletions(-) diff --git a/common/motion_utils/src/trajectory/tmp_conversion.cpp b/common/motion_utils/src/trajectory/tmp_conversion.cpp index 5c907a5926046..18705637a8387 100644 --- a/common/motion_utils/src/trajectory/tmp_conversion.cpp +++ b/common/motion_utils/src/trajectory/tmp_conversion.cpp @@ -36,12 +36,7 @@ autoware_auto_planning_msgs::msg::Trajectory convertToTrajectory( const std::vector & trajectory) { autoware_auto_planning_msgs::msg::Trajectory output{}; - for (const auto & pt : trajectory) { - output.points.push_back(pt); - if (output.points.size() >= output.CAPACITY) { - break; - } - } + for (const auto & pt : trajectory) output.points.push_back(pt); return output; } diff --git a/common/motion_utils/test/src/trajectory/test_trajectory.cpp b/common/motion_utils/test/src/trajectory/test_trajectory.cpp index 1786586ec39a8..22567b569d0ad 100644 --- a/common/motion_utils/test/src/trajectory/test_trajectory.cpp +++ b/common/motion_utils/test/src/trajectory/test_trajectory.cpp @@ -803,17 +803,6 @@ TEST(trajectory, convertToTrajectory) const auto traj = convertToTrajectory(traj_input); EXPECT_EQ(traj.points.size(), traj_input.size()); } - - // Clipping check - { - const auto traj_input = generateTestTrajectoryPointArray(10000, 1.0); - const auto traj = convertToTrajectory(traj_input); - EXPECT_EQ(traj.points.size(), traj.CAPACITY); - // Value check - for (size_t i = 0; i < traj.points.size(); ++i) { - EXPECT_EQ(traj.points.at(i), traj_input.at(i)); - } - } } TEST(trajectory, convertToTrajectoryPointArray) From 1bac0bf948bfbfd5888a3fb13af75e023d79961a Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Fri, 8 Dec 2023 15:18:53 +0900 Subject: [PATCH 15/87] fix: add missing param on perception launch: (#5812) detection_by_tracker_param_path was missing Signed-off-by: Taekjin LEE --- .../launch/object_recognition/detection/detection.launch.xml | 2 ++ launch/tier4_perception_launch/launch/perception.launch.xml | 1 + 2 files changed, 3 insertions(+) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml index 0d03e3c8cdcd9..0649d8c5d5116 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -104,6 +104,7 @@ + @@ -132,6 +133,7 @@ + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index da393b1efff59..7f5f9d61c4bf0 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -178,6 +178,7 @@ + From 1f7ad1709947848a0bc7833685480457f6dc2726 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 8 Dec 2023 17:18:51 +0900 Subject: [PATCH 16/87] refactor(lane_change): move lane change param (#5807) * refactor(lane_change): move lane change params Signed-off-by: satoshi-ota * fix(avoidance): remove unnecessary param path Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- ...t_behavior_path_planner_node_interface.cpp | 2 - .../lane_change/lane_change_module_data.hpp | 53 ++++++++++ .../utils/lane_change/utils.hpp | 15 ++- .../src/behavior_path_planner_node.cpp | 37 ------- .../scene_module/lane_change/interface.cpp | 7 +- .../src/scene_module/lane_change/manager.cpp | 43 +++++++++ .../src/scene_module/lane_change/normal.cpp | 96 +++++++++---------- .../src/utils/lane_change/utils.cpp | 65 +++++++++---- .../test/test_lane_change_utils.cpp | 3 +- .../parameters.hpp | 51 ---------- .../utils/utils.hpp | 4 - .../src/utils/utils.cpp | 25 ----- 12 files changed, 205 insertions(+), 196 deletions(-) diff --git a/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp index 83514127b0a8e..58bf36d978cea 100644 --- a/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -62,8 +62,6 @@ std::shared_ptr generateNode() behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - ament_index_cpp::get_package_share_directory("behavior_path_planner") + - "/config/lane_change/lane_change.param.yaml", ament_index_cpp::get_package_share_directory("behavior_path_avoidance_module") + "/config/avoidance.param.yaml"}); diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp index 6f34bc79fe5f1..debeef5ec573f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp @@ -17,12 +17,55 @@ #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" +#include + #include +#include #include namespace behavior_path_planner { +struct LateralAccelerationMap +{ + std::vector base_vel; + std::vector base_min_acc; + std::vector base_max_acc; + + void add(const double velocity, const double min_acc, const double max_acc) + { + if (base_vel.size() != base_min_acc.size() || base_vel.size() != base_max_acc.size()) { + return; + } + + size_t idx = 0; + for (size_t i = 0; i < base_vel.size(); ++i) { + if (velocity < base_vel.at(i)) { + break; + } + idx = i + 1; + } + + base_vel.insert(base_vel.begin() + idx, velocity); + base_min_acc.insert(base_min_acc.begin() + idx, min_acc); + base_max_acc.insert(base_max_acc.begin() + idx, max_acc); + } + + std::pair find(const double velocity) const + { + if (!base_vel.empty() && velocity < base_vel.front()) { + return std::make_pair(base_min_acc.front(), base_max_acc.front()); + } + if (!base_vel.empty() && velocity > base_vel.back()) { + return std::make_pair(base_min_acc.back(), base_max_acc.back()); + } + + const double min_acc = interpolation::lerp(base_vel, base_min_acc, velocity); + const double max_acc = interpolation::lerp(base_vel, base_max_acc, velocity); + + return std::make_pair(min_acc, max_acc); + } +}; struct LaneChangeCancelParameters { @@ -33,6 +76,7 @@ struct LaneChangeCancelParameters double max_lateral_jerk{10.0}; double overhang_tolerance{0.0}; }; + struct LaneChangeParameters { // trajectory generation @@ -41,6 +85,15 @@ struct LaneChangeParameters int longitudinal_acc_sampling_num{10}; int lateral_acc_sampling_num{10}; + // lane change parameters + double backward_length_buffer_for_end_of_lane; + double backward_length_buffer_for_blocking_object; + double lane_changing_lateral_jerk{0.5}; + double minimum_lane_changing_velocity{5.6}; + double lane_change_prepare_duration{4.0}; + double lane_change_finish_judge_buffer{3.0}; + LateralAccelerationMap lane_change_lat_acc_map; + // parked vehicle double object_check_min_road_shoulder_width{0.5}; double object_shiftable_ratio_threshold{0.6}; diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp index 12e6da00b2f36..f99ed043eb5dd 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp @@ -54,17 +54,21 @@ using tier4_autoware_utils::Polygon2d; double calcLaneChangeResampleInterval( const double lane_changing_length, const double lane_changing_velocity); +double calcMinimumLaneChangeLength( + const LaneChangeParameters & lane_change_parameters, const std::vector & shift_intervals, + const double length_to_intersection = 0.0); + double calcMaximumLaneChangeLength( - const double current_velocity, const BehaviorPathPlannerParameters & common_param, + const double current_velocity, const LaneChangeParameters & lane_change_parameters, const std::vector & shift_intervals, const double max_acc); double calcMinimumAcceleration( const double current_velocity, const double min_longitudinal_acc, - const BehaviorPathPlannerParameters & params); + const LaneChangeParameters & lane_change_parameters); double calcMaximumAcceleration( const double current_velocity, const double current_max_velocity, - const double max_longitudinal_acc, const BehaviorPathPlannerParameters & params); + const double max_longitudinal_acc, const LaneChangeParameters & lane_change_parameters); double calcLaneChangingAcceleration( const double initial_lane_changing_velocity, const double max_path_velocity, @@ -130,7 +134,7 @@ double getLateralShift(const LaneChangePath & path); bool hasEnoughLengthToLaneChangeAfterAbort( const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, const Pose & curent_pose, const double abort_return_dist, - const BehaviorPathPlannerParameters & common_param, const Direction direction); + const LaneChangeParameters & lane_change_parameters, const Direction direction); lanelet::ConstLanelets getBackwardLanelets( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, @@ -150,7 +154,8 @@ std::optional getLaneChangeTargetLane( std::vector convertToPredictedPath( const LaneChangePath & lane_change_path, const Twist & vehicle_twist, const Pose & pose, - const BehaviorPathPlannerParameters & common_parameters, const double resolution); + const BehaviorPathPlannerParameters & common_parameters, + const LaneChangeParameters & lane_change_parameters, const double resolution); bool isParkedObject( const PathWithLaneId & path, const RouteHandler & route_handler, diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 907c5226c3908..46057031afd8a 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -238,39 +238,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() p.min_acc = declare_parameter("normal.min_acc"); p.max_acc = declare_parameter("normal.max_acc"); - // lane change parameters - p.backward_length_buffer_for_end_of_lane = - declare_parameter("lane_change.backward_length_buffer_for_end_of_lane"); - p.backward_length_buffer_for_blocking_object = - declare_parameter("lane_change.backward_length_buffer_for_blocking_object"); - p.lane_changing_lateral_jerk = - declare_parameter("lane_change.lane_changing_lateral_jerk"); - p.lane_change_prepare_duration = declare_parameter("lane_change.prepare_duration"); - p.minimum_lane_changing_velocity = - declare_parameter("lane_change.minimum_lane_changing_velocity"); - p.minimum_lane_changing_velocity = - std::min(p.minimum_lane_changing_velocity, p.max_acc * p.lane_change_prepare_duration); - p.lane_change_finish_judge_buffer = - declare_parameter("lane_change.lane_change_finish_judge_buffer"); - - // lateral acceleration map for lane change - const auto lateral_acc_velocity = - declare_parameter>("lane_change.lateral_acceleration.velocity"); - const auto min_lateral_acc = - declare_parameter>("lane_change.lateral_acceleration.min_values"); - const auto max_lateral_acc = - declare_parameter>("lane_change.lateral_acceleration.max_values"); - if ( - lateral_acc_velocity.size() != min_lateral_acc.size() || - lateral_acc_velocity.size() != max_lateral_acc.size()) { - RCLCPP_ERROR(get_logger(), "Lane change lateral acceleration map has invalid size."); - exit(EXIT_FAILURE); - } - for (size_t i = 0; i < lateral_acc_velocity.size(); ++i) { - p.lane_change_lat_acc_map.add( - lateral_acc_velocity.at(i), min_lateral_acc.at(i), max_lateral_acc.at(i)); - } - p.backward_length_buffer_for_end_of_pull_over = declare_parameter("backward_length_buffer_for_end_of_pull_over"); p.backward_length_buffer_for_end_of_pull_out = @@ -297,10 +264,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() p.ego_nearest_dist_threshold = declare_parameter("ego_nearest_dist_threshold"); p.ego_nearest_yaw_threshold = declare_parameter("ego_nearest_yaw_threshold"); - if (p.backward_length_buffer_for_end_of_lane < 1.0) { - RCLCPP_WARN_STREAM( - get_logger(), "Lane change buffer must be more than 1 meter. Modifying the buffer."); - } return p; } diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp index cec9d5013d929..101dd43919361 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp @@ -148,8 +148,7 @@ ModuleStatus LaneChangeInterface::updateState() return ModuleStatus::RUNNING; } - const auto & common_parameters = module_type_->getCommonParam(); - const auto threshold = common_parameters.backward_length_buffer_for_end_of_lane; + const auto threshold = module_type_->getLaneChangeParam().backward_length_buffer_for_end_of_lane; const auto status = module_type_->getLaneChangeStatus(); if (module_type_->isNearEndOfCurrentLanes(status.current_lanes, status.target_lanes, threshold)) { log_warn_throttled("Lane change path is unsafe but near end of lane. Continue lane change."); @@ -432,8 +431,8 @@ TurnSignalInfo LaneChangeInterface::getCurrentTurnSignalInfo( const auto & common_parameter = module_type_->getCommonParam(); const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); - const double next_lane_change_buffer = utils::calcMinimumLaneChangeLength( - common_parameter, shift_intervals, common_parameter.backward_length_buffer_for_end_of_lane); + const double next_lane_change_buffer = + utils::lane_change::calcMinimumLaneChangeLength(lane_change_param, shift_intervals); const double & nearest_dist_threshold = common_parameter.ego_nearest_dist_threshold; const double & nearest_yaw_threshold = common_parameter.ego_nearest_yaw_threshold; const double & base_to_front = common_parameter.base_link2front; diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp index ed40476723dba..658ffb06c25fe 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp @@ -141,6 +141,49 @@ void LaneChangeModuleManager::init(rclcpp::Node * node) p.rss_params_for_stuck.lateral_distance_max_threshold = getOrDeclareParameter( *node, parameter("safety_check.stuck.lateral_distance_max_threshold")); + // lane change parameters + const auto max_acc = getOrDeclareParameter(*node, "normal.max_acc"); + p.backward_length_buffer_for_end_of_lane = + getOrDeclareParameter(*node, parameter("backward_length_buffer_for_end_of_lane")); + p.backward_length_buffer_for_blocking_object = + getOrDeclareParameter(*node, parameter("backward_length_buffer_for_blocking_object")); + p.lane_changing_lateral_jerk = + getOrDeclareParameter(*node, parameter("lane_changing_lateral_jerk")); + p.lane_change_prepare_duration = + getOrDeclareParameter(*node, parameter("prepare_duration")); + p.minimum_lane_changing_velocity = + getOrDeclareParameter(*node, parameter("minimum_lane_changing_velocity")); + p.minimum_lane_changing_velocity = + std::min(p.minimum_lane_changing_velocity, max_acc * p.lane_change_prepare_duration); + p.lane_change_finish_judge_buffer = + getOrDeclareParameter(*node, parameter("lane_change_finish_judge_buffer")); + + if (p.backward_length_buffer_for_end_of_lane < 1.0) { + RCLCPP_WARN_STREAM( + node->get_logger().get_child(name()), + "Lane change buffer must be more than 1 meter. Modifying the buffer."); + } + + // lateral acceleration map for lane change + const auto lateral_acc_velocity = + getOrDeclareParameter>(*node, parameter("lateral_acceleration.velocity")); + const auto min_lateral_acc = + getOrDeclareParameter>(*node, parameter("lateral_acceleration.min_values")); + const auto max_lateral_acc = + getOrDeclareParameter>(*node, parameter("lateral_acceleration.max_values")); + if ( + lateral_acc_velocity.size() != min_lateral_acc.size() || + lateral_acc_velocity.size() != max_lateral_acc.size()) { + RCLCPP_ERROR( + node->get_logger().get_child(name()), + "Lane change lateral acceleration map has invalid size."); + exit(EXIT_FAILURE); + } + for (size_t i = 0; i < lateral_acc_velocity.size(); ++i) { + p.lane_change_lat_acc_map.add( + lateral_acc_velocity.at(i), min_lateral_acc.at(i), max_lateral_acc.at(i)); + } + // target object { const std::string ns = "lane_change.target_object."; diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index 423ffc48dd6cd..ebb41ae63dcbe 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -215,9 +215,8 @@ void NormalLaneChange::insertStopPoint( } const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(lanelets.back()); - const double lane_change_buffer = utils::calcMinimumLaneChangeLength( - getCommonParam(), shift_intervals, getCommonParam().backward_length_buffer_for_end_of_lane, - 0.0); + const double lane_change_buffer = + utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals, 0.0); const auto getDistanceAlongLanelet = [&](const geometry_msgs::msg::Pose & target) { return utils::getSignedDistance(path.points.front().point.pose, target, lanelets); @@ -233,7 +232,7 @@ void NormalLaneChange::insertStopPoint( distance_to_terminal = utils::getDistanceToEndOfLane(path.points.front().point.pose, lanelets); } - const double stop_point_buffer = getCommonParam().backward_length_buffer_for_end_of_lane; + const double stop_point_buffer = lane_change_parameters_->backward_length_buffer_for_end_of_lane; const auto target_objects = getTargetObjects(status_.current_lanes, status_.target_lanes); double stopping_distance = distance_to_terminal - lane_change_buffer - stop_point_buffer; @@ -294,15 +293,14 @@ void NormalLaneChange::insertStopPoint( if (distance_to_ego_lane_obj < distance_to_terminal) { // consider rss distance when the LC need to avoid obstacles const auto rss_dist = calcRssDistance( - 0.0, planner_data_->parameters.minimum_lane_changing_velocity, + 0.0, lane_change_parameters_->minimum_lane_changing_velocity, lane_change_parameters_->rss_params); - const double lane_change_buffer_for_blocking_object = utils::calcMinimumLaneChangeLength( - getCommonParam(), shift_intervals, - getCommonParam().backward_length_buffer_for_blocking_object, 0.0); + const double lane_change_buffer_for_blocking_object = + utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals); const auto stopping_distance_for_obj = distance_to_ego_lane_obj - lane_change_buffer_for_blocking_object - - getCommonParam().backward_length_buffer_for_blocking_object - rss_dist - + lane_change_parameters_->backward_length_buffer_for_blocking_object - rss_dist - getCommonParam().base_link2front; // If the target lane in the lane change section is blocked by a stationary obstacle, there @@ -498,9 +496,8 @@ bool NormalLaneChange::isNearEndOfCurrentLanes( const auto & current_pose = getEgoPose(); const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); - const auto lane_change_buffer = utils::calcMinimumLaneChangeLength( - planner_data_->parameters, shift_intervals, - getCommonParam().backward_length_buffer_for_end_of_lane); + const auto lane_change_buffer = + utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals); auto distance_to_end = utils::getDistanceToEndOfLane(current_pose, current_lanes); @@ -519,7 +516,7 @@ bool NormalLaneChange::hasFinishedLaneChange() const const auto & lane_change_end = status_.lane_change_path.info.shift_line.end; const double dist_to_lane_change_end = utils::getSignedDistance( current_pose, lane_change_end, status_.lane_change_path.info.target_lanes); - double finish_judge_buffer = planner_data_->parameters.lane_change_finish_judge_buffer; + double finish_judge_buffer = lane_change_parameters_->lane_change_finish_judge_buffer; // If ego velocity is low, relax finish judge buffer const double ego_velocity = getEgoVelocity(); @@ -560,7 +557,7 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const planner_data_->parameters.ego_nearest_yaw_threshold); const double ego_velocity = - std::max(getEgoVelocity(), planner_data_->parameters.minimum_lane_changing_velocity); + std::max(getEgoVelocity(), lane_change_parameters_->minimum_lane_changing_velocity); const double estimated_travel_dist = ego_velocity * lane_change_parameters_->cancel.delta_time; double dist = 0.0; @@ -664,10 +661,10 @@ std::pair NormalLaneChange::calcCurrentMinMaxAcceleration() cons prev_module_path_.points.at(ego_seg_idx).point.longitudinal_velocity_mps; // calculate minimum and maximum acceleration - const auto min_acc = - utils::lane_change::calcMinimumAcceleration(getEgoVelocity(), vehicle_min_acc, p); + const auto min_acc = utils::lane_change::calcMinimumAcceleration( + getEgoVelocity(), vehicle_min_acc, *lane_change_parameters_); const auto max_acc = utils::lane_change::calcMaximumAcceleration( - getEgoVelocity(), max_path_velocity, vehicle_max_acc, p); + getEgoVelocity(), max_path_velocity, vehicle_max_acc, *lane_change_parameters_); return {min_acc, max_acc}; } @@ -678,8 +675,8 @@ double NormalLaneChange::calcMaximumLaneChangeLength( const auto shift_intervals = getRouteHandler()->getLateralIntervalsToPreferredLane(current_terminal_lanelet); return utils::lane_change::calcMaximumLaneChangeLength( - std::max(getCommonParam().minimum_lane_changing_velocity, getEgoVelocity()), getCommonParam(), - shift_intervals, max_acc); + std::max(lane_change_parameters_->minimum_lane_changing_velocity, getEgoVelocity()), + *lane_change_parameters_, shift_intervals, max_acc); } std::vector NormalLaneChange::sampleLongitudinalAccValues( @@ -746,7 +743,6 @@ std::vector NormalLaneChange::sampleLongitudinalAccValues( std::vector NormalLaneChange::calcPrepareDuration( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const { - const auto & common_parameters = planner_data_->parameters; const auto base_link2front = planner_data_->parameters.base_link2front; const auto threshold = lane_change_parameters_->min_length_for_turn_signal_activation + base_link2front; @@ -754,7 +750,7 @@ std::vector NormalLaneChange::calcPrepareDuration( std::vector prepare_durations; constexpr double step = 0.5; - for (double duration = common_parameters.lane_change_prepare_duration; duration >= 0.0; + for (double duration = lane_change_parameters_->lane_change_prepare_duration; duration >= 0.0; duration -= step) { prepare_durations.push_back(duration); if (!isNearEndOfCurrentLanes(current_lanes, target_lanes, threshold)) { @@ -1024,12 +1020,11 @@ bool NormalLaneChange::hasEnoughLength( const auto current_pose = getEgoPose(); const auto & route_handler = *getRouteHandler(); const auto overall_graphs_ptr = route_handler.getOverallGraphPtr(); - const auto & common_parameters = planner_data_->parameters; const double lane_change_length = path.info.length.sum(); const auto shift_intervals = route_handler.getLateralIntervalsToPreferredLane(target_lanes.back(), direction); - double minimum_lane_change_length_to_preferred_lane = utils::calcMinimumLaneChangeLength( - common_parameters, shift_intervals, common_parameters.backward_length_buffer_for_end_of_lane); + double minimum_lane_change_length_to_preferred_lane = + utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals); if (lane_change_length > utils::getDistanceToEndOfLane(current_pose, current_lanes)) { return false; @@ -1125,7 +1120,8 @@ bool NormalLaneChange::getLaneChangePaths( const auto backward_path_length = common_parameters.backward_path_length; const auto forward_path_length = common_parameters.forward_path_length; - const auto minimum_lane_changing_velocity = common_parameters.minimum_lane_changing_velocity; + const auto minimum_lane_changing_velocity = + lane_change_parameters_->minimum_lane_changing_velocity; const auto lateral_acc_sampling_num = lane_change_parameters_->lateral_acc_sampling_num; // get velocity @@ -1137,12 +1133,12 @@ bool NormalLaneChange::getLaneChangePaths( const auto is_goal_in_route = route_handler.isInGoalRouteSection(target_lanes.back()); - const double lane_change_buffer = utils::calcMinimumLaneChangeLength( - common_parameters, route_handler.getLateralIntervalsToPreferredLane(current_lanes.back()), - common_parameters.backward_length_buffer_for_end_of_lane); - const double next_lane_change_buffer = utils::calcMinimumLaneChangeLength( - common_parameters, route_handler.getLateralIntervalsToPreferredLane(target_lanes.back()), - common_parameters.backward_length_buffer_for_end_of_lane); + const double lane_change_buffer = utils::lane_change::calcMinimumLaneChangeLength( + *lane_change_parameters_, + route_handler.getLateralIntervalsToPreferredLane(current_lanes.back())); + const double next_lane_change_buffer = utils::lane_change::calcMinimumLaneChangeLength( + *lane_change_parameters_, + route_handler.getLateralIntervalsToPreferredLane(target_lanes.back())); const auto dist_to_end_of_current_lanes = utils::getDistanceToEndOfLane(getEgoPose(), current_lanes); @@ -1219,7 +1215,7 @@ bool NormalLaneChange::getLaneChangePaths( // get lateral acceleration range const auto [min_lateral_acc, max_lateral_acc] = - common_parameters.lane_change_lat_acc_map.find(initial_lane_changing_velocity); + lane_change_parameters_->lane_change_lat_acc_map.find(initial_lane_changing_velocity); const auto lateral_acc_resolution = std::abs(max_lateral_acc - min_lateral_acc) / lateral_acc_sampling_num; @@ -1238,7 +1234,7 @@ bool NormalLaneChange::getLaneChangePaths( }; const auto lane_changing_time = PathShifter::calcShiftTimeFromJerk( - shift_length, common_parameters.lane_changing_lateral_jerk, lateral_acc); + shift_length, lane_change_parameters_->lane_changing_lateral_jerk, lateral_acc); const double longitudinal_acc_on_lane_changing = utils::lane_change::calcLaneChangingAcceleration( initial_lane_changing_velocity, max_path_velocity, lane_changing_time, @@ -1264,8 +1260,9 @@ bool NormalLaneChange::getLaneChangePaths( const auto num = std::abs(route_handler.getNumLaneToPreferredLane(target_lanes.back(), direction)); const double backward_buffer = - num == 0 ? 0.0 : common_parameters.backward_length_buffer_for_end_of_lane; - const double finish_judge_buffer = common_parameters.lane_change_finish_judge_buffer; + num == 0 ? 0.0 : lane_change_parameters_->backward_length_buffer_for_end_of_lane; + const double finish_judge_buffer = + lane_change_parameters_->lane_change_finish_judge_buffer; if ( s_start + lane_changing_length + finish_judge_buffer + backward_buffer + next_lane_change_buffer > @@ -1536,7 +1533,7 @@ bool NormalLaneChange::isValidPath(const PathWithLaneId & path) const bool NormalLaneChange::isRequiredStop(const bool is_object_coming_from_rear) const { - const auto threshold = planner_data_->parameters.backward_length_buffer_for_end_of_lane; + const auto threshold = lane_change_parameters_->backward_length_buffer_for_end_of_lane; return isNearEndOfCurrentLanes(status_.current_lanes, status_.target_lanes, threshold) && isAbleToStopSafely() && is_object_coming_from_rear; } @@ -1546,7 +1543,7 @@ bool NormalLaneChange::calcAbortPath() const auto & route_handler = getRouteHandler(); const auto & common_param = getCommonParam(); const auto current_velocity = - std::max(common_param.minimum_lane_changing_velocity, getEgoVelocity()); + std::max(lane_change_parameters_->minimum_lane_changing_velocity, getEgoVelocity()); const auto current_pose = getEgoPose(); const auto & selected_path = status_.lane_change_path; const auto reference_lanelets = selected_path.info.current_lanes; @@ -1557,8 +1554,8 @@ bool NormalLaneChange::calcAbortPath() const auto direction = getDirection(); const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane( selected_path.info.current_lanes.back(), direction); - const double minimum_lane_change_length = utils::calcMinimumLaneChangeLength( - common_param, shift_intervals, common_param.backward_length_buffer_for_end_of_lane); + const double minimum_lane_change_length = + utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals); const auto & lane_changing_path = selected_path.path; const auto lane_changing_end_pose_idx = std::invoke([&]() { @@ -1605,8 +1602,8 @@ bool NormalLaneChange::calcAbortPath() } if (!utils::lane_change::hasEnoughLengthToLaneChangeAfterAbort( - *route_handler, reference_lanelets, current_pose, abort_return_dist, common_param, - direction)) { + *route_handler, reference_lanelets, current_pose, abort_return_dist, + *lane_change_parameters_, direction)) { RCLCPP_ERROR(logger_, "insufficient distance to abort."); return false; } @@ -1629,7 +1626,8 @@ bool NormalLaneChange::calcAbortPath() const auto lateral_jerk = behavior_path_planner::PathShifter::calcJerkFromLatLonDistance( shift_line.end_shift_length, abort_start_dist, current_velocity); path_shifter.setVelocity(current_velocity); - const auto lateral_acc_range = common_param.lane_change_lat_acc_map.find(current_velocity); + const auto lateral_acc_range = + lane_change_parameters_->lane_change_lat_acc_map.find(current_velocity); const double & max_lateral_acc = lateral_acc_range.second; path_shifter.setLateralAccelerationLimit(max_lateral_acc); @@ -1662,7 +1660,7 @@ bool NormalLaneChange::calcAbortPath() PathWithLaneId ref = route_handler->getCenterLinePath(reference_lanelets, s_start, s_end, true); ref.points.back().point.longitudinal_velocity_mps = std::min( ref.points.back().point.longitudinal_velocity_mps, - static_cast(common_param.minimum_lane_changing_velocity)); + static_cast(lane_change_parameters_->minimum_lane_changing_velocity)); return ref; }); @@ -1707,7 +1705,8 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( const double & time_resolution = lane_change_parameters_->prediction_time_resolution; const auto ego_predicted_path = utils::lane_change::convertToPredictedPath( - lane_change_path, current_twist, current_pose, common_parameters, time_resolution); + lane_change_path, current_twist, current_pose, common_parameters, *lane_change_parameters_, + time_resolution); const auto debug_predicted_path = utils::path_safety_checker::convertToPredictedPath(ego_predicted_path, time_resolution); @@ -1818,10 +1817,9 @@ bool NormalLaneChange::isVehicleStuck( : utils::getDistanceToEndOfLane(getEgoPose(), current_lanes); const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); - const double lane_change_buffer = utils::calcMinimumLaneChangeLength( - getCommonParam(), shift_intervals, getCommonParam().backward_length_buffer_for_end_of_lane, - 0.0); - const double stop_point_buffer = getCommonParam().backward_length_buffer_for_end_of_lane; + const double lane_change_buffer = + utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals, 0.0); + const double stop_point_buffer = lane_change_parameters_->backward_length_buffer_for_end_of_lane; const double terminal_judge_buffer = lane_change_buffer + stop_point_buffer + 1.0; if (distance_to_terminal < terminal_judge_buffer) { return true; @@ -1844,7 +1842,7 @@ bool NormalLaneChange::isVehicleStuck(const lanelet::ConstLanelets & current_lan const auto [min_acc, max_acc] = calcCurrentMinMaxAcceleration(); const auto max_lane_change_length = calcMaximumLaneChangeLength(current_lanes.back(), max_acc); const auto rss_dist = calcRssDistance( - 0.0, planner_data_->parameters.minimum_lane_changing_velocity, + 0.0, lane_change_parameters_->minimum_lane_changing_velocity, lane_change_parameters_->rss_params); // It is difficult to define the detection range. If it is too short, the stuck will not be diff --git a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp index 66182454ecf85..8ba820231d7cc 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -67,17 +67,43 @@ double calcLaneChangeResampleInterval( lane_changing_length / min_resampling_points, lane_changing_velocity * resampling_dt); } +double calcMinimumLaneChangeLength( + const LaneChangeParameters & lane_change_parameters, const std::vector & shift_intervals, + const double length_to_intersection) +{ + if (shift_intervals.empty()) { + return 0.0; + } + + const double & vel = lane_change_parameters.minimum_lane_changing_velocity; + const auto lat_acc = lane_change_parameters.lane_change_lat_acc_map.find(vel); + const double & max_lateral_acc = lat_acc.second; + const double & lateral_jerk = lane_change_parameters.lane_changing_lateral_jerk; + const double & finish_judge_buffer = lane_change_parameters.lane_change_finish_judge_buffer; + const double & backward_buffer = lane_change_parameters.backward_length_buffer_for_end_of_lane; + + double accumulated_length = length_to_intersection; + for (const auto & shift_interval : shift_intervals) { + const double t = + PathShifter::calcShiftTimeFromJerk(shift_interval, lateral_jerk, max_lateral_acc); + accumulated_length += vel * t + finish_judge_buffer; + } + accumulated_length += backward_buffer * (shift_intervals.size() - 1.0); + + return accumulated_length; +} + double calcMaximumLaneChangeLength( - const double current_velocity, const BehaviorPathPlannerParameters & common_param, + const double current_velocity, const LaneChangeParameters & lane_change_parameters, const std::vector & shift_intervals, const double max_acc) { if (shift_intervals.empty()) { return 0.0; } - const double & finish_judge_buffer = common_param.lane_change_finish_judge_buffer; - const double & lateral_jerk = common_param.lane_changing_lateral_jerk; - const double & t_prepare = common_param.lane_change_prepare_duration; + const double & finish_judge_buffer = lane_change_parameters.lane_change_finish_judge_buffer; + const double & lateral_jerk = lane_change_parameters.lane_changing_lateral_jerk; + const double & t_prepare = lane_change_parameters.lane_change_prepare_duration; double vel = current_velocity; double accumulated_length = 0.0; @@ -87,7 +113,7 @@ double calcMaximumLaneChangeLength( vel = vel + max_acc * t_prepare; // lane changing section - const auto lat_acc = common_param.lane_change_lat_acc_map.find(vel); + const auto lat_acc = lane_change_parameters.lane_change_lat_acc_map.find(vel); const double t_lane_changing = PathShifter::calcShiftTimeFromJerk(shift_interval, lateral_jerk, lat_acc.second); const double lane_changing_length = @@ -97,26 +123,26 @@ double calcMaximumLaneChangeLength( vel = vel + max_acc * t_lane_changing; } accumulated_length += - common_param.backward_length_buffer_for_end_of_lane * (shift_intervals.size() - 1.0); + lane_change_parameters.backward_length_buffer_for_end_of_lane * (shift_intervals.size() - 1.0); return accumulated_length; } double calcMinimumAcceleration( const double current_velocity, const double min_longitudinal_acc, - const BehaviorPathPlannerParameters & params) + const LaneChangeParameters & lane_change_parameters) { - const double min_lane_changing_velocity = params.minimum_lane_changing_velocity; - const double prepare_duration = params.lane_change_prepare_duration; + const double min_lane_changing_velocity = lane_change_parameters.minimum_lane_changing_velocity; + const double prepare_duration = lane_change_parameters.lane_change_prepare_duration; const double acc = (min_lane_changing_velocity - current_velocity) / prepare_duration; return std::clamp(acc, -std::abs(min_longitudinal_acc), -std::numeric_limits::epsilon()); } double calcMaximumAcceleration( const double current_velocity, const double current_max_velocity, - const double max_longitudinal_acc, const BehaviorPathPlannerParameters & params) + const double max_longitudinal_acc, const LaneChangeParameters & lane_change_parameters) { - const double prepare_duration = params.lane_change_prepare_duration; + const double prepare_duration = lane_change_parameters.lane_change_prepare_duration; const double acc = (current_max_velocity - current_velocity) / prepare_duration; return std::clamp(acc, 0.0, max_longitudinal_acc); } @@ -601,12 +627,12 @@ double getLateralShift(const LaneChangePath & path) bool hasEnoughLengthToLaneChangeAfterAbort( const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, const Pose & current_pose, const double abort_return_dist, - const BehaviorPathPlannerParameters & common_param, const Direction direction) + const LaneChangeParameters & lane_change_parameters, const Direction direction) { const auto shift_intervals = route_handler.getLateralIntervalsToPreferredLane(current_lanes.back(), direction); - const double minimum_lane_change_length = utils::calcMinimumLaneChangeLength( - common_param, shift_intervals, common_param.backward_length_buffer_for_end_of_lane); + const double minimum_lane_change_length = + calcMinimumLaneChangeLength(lane_change_parameters, shift_intervals); const auto abort_plus_lane_change_length = abort_return_dist + minimum_lane_change_length; if (abort_plus_lane_change_length > utils::getDistanceToEndOfLane(current_pose, current_lanes)) { return false; @@ -765,7 +791,8 @@ std::optional getLaneChangeTargetLane( std::vector convertToPredictedPath( const LaneChangePath & lane_change_path, const Twist & vehicle_twist, const Pose & vehicle_pose, - const BehaviorPathPlannerParameters & common_parameters, const double resolution) + const BehaviorPathPlannerParameters & common_parameters, + const LaneChangeParameters & lane_change_parameters, const double resolution) { if (lane_change_path.path.points.empty()) { return {}; @@ -776,7 +803,8 @@ std::vector convertToPredictedPath( const auto lane_changing_acc = lane_change_path.info.longitudinal_acceleration.lane_changing; const auto duration = lane_change_path.info.duration.sum(); const auto prepare_time = lane_change_path.info.duration.prepare; - const auto & minimum_lane_changing_velocity = common_parameters.minimum_lane_changing_velocity; + const auto & minimum_lane_changing_velocity = + lane_change_parameters.minimum_lane_changing_velocity; const auto nearest_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, vehicle_pose, common_parameters.ego_nearest_dist_threshold, @@ -1065,7 +1093,8 @@ std::optional createPolygon( } ExtendedPredictedObject transform( - const PredictedObject & object, const BehaviorPathPlannerParameters & common_parameters, + const PredictedObject & object, + [[maybe_unused]] const BehaviorPathPlannerParameters & common_parameters, const LaneChangeParameters & lane_change_parameters) { ExtendedPredictedObject extended_object; @@ -1078,7 +1107,7 @@ ExtendedPredictedObject transform( 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 = common_parameters.lane_change_prepare_duration; + const auto & prepare_duration = lane_change_parameters.lane_change_prepare_duration; const auto & velocity_threshold = lane_change_parameters.prepare_segment_ignore_object_velocity_thresh; const auto start_time = check_at_prepare_phase ? 0.0 : prepare_duration; diff --git a/planning/behavior_path_planner/test/test_lane_change_utils.cpp b/planning/behavior_path_planner/test/test_lane_change_utils.cpp index 3268bd7ec468e..477af32893b0b 100644 --- a/planning/behavior_path_planner/test/test_lane_change_utils.cpp +++ b/planning/behavior_path_planner/test/test_lane_change_utils.cpp @@ -11,6 +11,7 @@ // 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 "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" #include @@ -41,7 +42,7 @@ TEST(BehaviorPathPlanningLaneChangeUtilsTest, projectCurrentPoseToTarget) TEST(BehaviorPathPlanningLaneChangeUtilsTest, TESTLateralAccelerationMap) { - LateralAccelerationMap lat_acc_map; + behavior_path_planner::LateralAccelerationMap lat_acc_map; lat_acc_map.add(0.0, 0.2, 0.315); lat_acc_map.add(3.0, 0.2, 0.315); lat_acc_map.add(5.0, 0.2, 0.315); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp index 7832dd4e53cfc..5bdd0a2f3f88d 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp @@ -15,7 +15,6 @@ #ifndef BEHAVIOR_PATH_PLANNER_COMMON__PARAMETERS_HPP_ #define BEHAVIOR_PATH_PLANNER_COMMON__PARAMETERS_HPP_ -#include #include #include @@ -32,47 +31,6 @@ struct ModuleConfigParameters uint8_t max_module_size{0}; }; -struct LateralAccelerationMap -{ - std::vector base_vel; - std::vector base_min_acc; - std::vector base_max_acc; - - void add(const double velocity, const double min_acc, const double max_acc) - { - if (base_vel.size() != base_min_acc.size() || base_vel.size() != base_max_acc.size()) { - return; - } - - size_t idx = 0; - for (size_t i = 0; i < base_vel.size(); ++i) { - if (velocity < base_vel.at(i)) { - break; - } - idx = i + 1; - } - - base_vel.insert(base_vel.begin() + idx, velocity); - base_min_acc.insert(base_min_acc.begin() + idx, min_acc); - base_max_acc.insert(base_max_acc.begin() + idx, max_acc); - } - - std::pair find(const double velocity) const - { - if (!base_vel.empty() && velocity < base_vel.front()) { - return std::make_pair(base_min_acc.front(), base_max_acc.front()); - } - if (!base_vel.empty() && velocity > base_vel.back()) { - return std::make_pair(base_min_acc.back(), base_max_acc.back()); - } - - const double min_acc = interpolation::lerp(base_vel, base_min_acc, velocity); - const double max_acc = interpolation::lerp(base_vel, base_max_acc, velocity); - - return std::make_pair(min_acc, max_acc); - } -}; - struct BehaviorPathPlannerParameters { bool verbose; @@ -81,8 +39,6 @@ struct BehaviorPathPlannerParameters double backward_path_length; double forward_path_length; - double backward_length_buffer_for_end_of_lane; - double backward_length_buffer_for_blocking_object; double backward_length_buffer_for_end_of_pull_over; double backward_length_buffer_for_end_of_pull_out; @@ -90,13 +46,6 @@ struct BehaviorPathPlannerParameters double min_acc; double max_acc; - // lane change parameters - double lane_changing_lateral_jerk{0.5}; - double minimum_lane_changing_velocity{5.6}; - double lane_change_prepare_duration{4.0}; - double lane_change_finish_judge_buffer{3.0}; - LateralAccelerationMap lane_change_lat_acc_map; - double minimum_pull_over_length; double minimum_pull_out_length; double drivable_area_resolution; diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp index 3a7d346849e16..e2c9fd1e332a2 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp @@ -333,10 +333,6 @@ lanelet::ConstLanelets calcLaneAroundPose( bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_threshold); -double calcMinimumLaneChangeLength( - const BehaviorPathPlannerParameters & common_param, const std::vector & shift_intervals, - const double backward_buffer, const double length_to_intersection = 0.0); - lanelet::ConstLanelets getLaneletsFromPath( const PathWithLaneId & path, const std::shared_ptr & route_handler); diff --git a/planning/behavior_path_planner_common/src/utils/utils.cpp b/planning/behavior_path_planner_common/src/utils/utils.cpp index 88c7532b0ad72..7c3a5883989fb 100644 --- a/planning/behavior_path_planner_common/src/utils/utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/utils.cpp @@ -1515,31 +1515,6 @@ bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_thre return true; } -double calcMinimumLaneChangeLength( - const BehaviorPathPlannerParameters & common_param, const std::vector & shift_intervals, - const double backward_buffer, const double length_to_intersection) -{ - if (shift_intervals.empty()) { - return 0.0; - } - - const double & vel = common_param.minimum_lane_changing_velocity; - const auto lat_acc = common_param.lane_change_lat_acc_map.find(vel); - const double & max_lateral_acc = lat_acc.second; - const double & lateral_jerk = common_param.lane_changing_lateral_jerk; - const double & finish_judge_buffer = common_param.lane_change_finish_judge_buffer; - - double accumulated_length = length_to_intersection; - for (const auto & shift_interval : shift_intervals) { - const double t = - PathShifter::calcShiftTimeFromJerk(shift_interval, lateral_jerk, max_lateral_acc); - accumulated_length += vel * t + finish_judge_buffer; - } - accumulated_length += backward_buffer * (shift_intervals.size() - 1.0); - - return accumulated_length; -} - lanelet::ConstLanelets getLaneletsFromPath( const PathWithLaneId & path, const std::shared_ptr & route_handler) { From 055bc9da0d32a3d9729cef190aaa80b30874b7c2 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 <129915538+TaikiYamada4@users.noreply.github.com> Date: Fri, 8 Dec 2023 19:16:52 +0900 Subject: [PATCH 17/87] fix(ekf_localizer): correct the initialization of accumulated_delay_times to obtain accurate computation of delay_time (#5821) Correct accumulated_delay_times in ekf_localizer so that the delay_step is computed accurately. Signed-off-by: TaikiYamada4 --- localization/ekf_localizer/src/ekf_module.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/localization/ekf_localizer/src/ekf_module.cpp b/localization/ekf_localizer/src/ekf_module.cpp index 10926b04507a0..573472fe2dabf 100644 --- a/localization/ekf_localizer/src/ekf_module.cpp +++ b/localization/ekf_localizer/src/ekf_module.cpp @@ -167,10 +167,10 @@ void EKFModule::accumulate_delay_time(const double dt) accumulated_delay_times_.begin(), accumulated_delay_times_.end() - 1, accumulated_delay_times_.end()); - // Add the new delay time to all elements. + // Add a new element (=0) and, and add delay time to the previous elements. accumulated_delay_times_.front() = 0.0; - for (auto & delay_time : accumulated_delay_times_) { - delay_time += dt; + for (size_t i = 1; i < accumulated_delay_times_.size(); ++i) { + accumulated_delay_times_[i] += dt; } } From 9b4cd9cc09bfd9bdc1c72d96898fe9546afede72 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Fri, 8 Dec 2023 21:25:04 +0900 Subject: [PATCH 18/87] feat(system_diagnostic_graph): support config override and add tests (#5816) Signed-off-by: Takagi, Isamu --- system/system_diagnostic_graph/CMakeLists.txt | 11 +- .../config/default.param.yaml | 4 +- .../example/example_0.yaml | 6 +- .../src/core/config.cpp | 125 +++++++++++---- .../src/core/config.hpp | 19 +++ .../src/core/debug.cpp | 27 +++- .../src/core/debug.hpp | 2 +- .../src/core/error.hpp | 5 + .../src/core/graph.cpp | 36 +++-- .../src/core/graph.hpp | 7 +- .../src/core/modes.cpp | 6 +- .../src/core/units.cpp | 33 +++- .../src/core/units.hpp | 17 +++ system/system_diagnostic_graph/src/main.cpp | 13 +- system/system_diagnostic_graph/src/main.hpp | 2 + .../system_diagnostic_graph/src/tool/main.cpp | 140 +++++++++++++++++ .../files/{ => test1}/field-not-found.yaml | 0 .../files/{ => test1}/file-not-found.yaml | 0 .../files/{ => test1}/graph-circulation.yaml | 0 .../files/{ => test1}/invalid-dict-type.yaml | 0 .../files/{ => test1}/invalid-list-type.yaml | 0 .../test/files/{ => test1}/path-conflict.yaml | 0 .../files/{ => test1}/path-not-found.yaml | 0 .../files/{ => test1}/unknown-node-type.yaml | 0 .../{ => test1}/unknown-substitution.yaml | 0 .../test/files/test2/and.yaml | 10 ++ .../test/files/test2/or.yaml | 10 ++ .../test/files/test2/warn-to-error.yaml | 7 + .../test/files/test2/warn-to-ok.yaml | 7 + .../test/src/{test.cpp => test1.cpp} | 29 ++-- .../test/src/test2.cpp | 143 ++++++++++++++++++ .../test/src/utils.cpp | 20 +++ .../test/src/utils.hpp | 23 +++ 33 files changed, 605 insertions(+), 97 deletions(-) create mode 100644 system/system_diagnostic_graph/src/tool/main.cpp rename system/system_diagnostic_graph/test/files/{ => test1}/field-not-found.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/file-not-found.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/graph-circulation.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/invalid-dict-type.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/invalid-list-type.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/path-conflict.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/path-not-found.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/unknown-node-type.yaml (100%) rename system/system_diagnostic_graph/test/files/{ => test1}/unknown-substitution.yaml (100%) create mode 100644 system/system_diagnostic_graph/test/files/test2/and.yaml create mode 100644 system/system_diagnostic_graph/test/files/test2/or.yaml create mode 100644 system/system_diagnostic_graph/test/files/test2/warn-to-error.yaml create mode 100644 system/system_diagnostic_graph/test/files/test2/warn-to-ok.yaml rename system/system_diagnostic_graph/test/src/{test.cpp => test1.cpp} (57%) create mode 100644 system/system_diagnostic_graph/test/src/test2.cpp create mode 100644 system/system_diagnostic_graph/test/src/utils.cpp create mode 100644 system/system_diagnostic_graph/test/src/utils.hpp diff --git a/system/system_diagnostic_graph/CMakeLists.txt b/system/system_diagnostic_graph/CMakeLists.txt index 142aa94eeef69..be0fc19188a0b 100644 --- a/system/system_diagnostic_graph/CMakeLists.txt +++ b/system/system_diagnostic_graph/CMakeLists.txt @@ -20,9 +20,18 @@ ament_auto_add_executable(converter src/tool.cpp ) +ament_auto_add_executable(tool + src/tool/main.cpp +) +target_include_directories(tool PRIVATE src/core) + if(BUILD_TESTING) get_filename_component(RESOURCE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/test/files ABSOLUTE) - ament_auto_add_gtest(gtest_${PROJECT_NAME} test/src/test.cpp) + ament_auto_add_gtest(gtest_${PROJECT_NAME} + test/src/test1.cpp + test/src/test2.cpp + test/src/utils.cpp + ) target_compile_definitions(gtest_${PROJECT_NAME} PRIVATE TEST_RESOURCE_PATH="${RESOURCE_PATH}") target_include_directories(gtest_${PROJECT_NAME} PRIVATE src) endif() diff --git a/system/system_diagnostic_graph/config/default.param.yaml b/system/system_diagnostic_graph/config/default.param.yaml index 9fd572c7926fa..e91664c5b82d8 100644 --- a/system/system_diagnostic_graph/config/default.param.yaml +++ b/system/system_diagnostic_graph/config/default.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: - mode_availability: true - mode: psim + use_operation_mode_availability: true + use_debug_mode: false rate: 1.0 input_qos_depth: 1000 graph_qos_depth: 1 diff --git a/system/system_diagnostic_graph/example/example_0.yaml b/system/system_diagnostic_graph/example/example_0.yaml index fc4436bba1595..ed92259b50721 100644 --- a/system/system_diagnostic_graph/example/example_0.yaml +++ b/system/system_diagnostic_graph/example/example_0.yaml @@ -22,15 +22,15 @@ nodes: list: - { type: link, link: /external/remote_command } - - path: /autoware/modes/emergency-stop + - path: /autoware/modes/emergency_stop type: ok - - path: /autoware/modes/comfortable-stop + - path: /autoware/modes/comfortable_stop type: and list: - { type: link, link: /functions/obstacle_detection } - - path: /autoware/modes/pull-over + - path: /autoware/modes/pull_over type: and list: - { type: link, link: /functions/pose_estimation } diff --git a/system/system_diagnostic_graph/src/core/config.cpp b/system/system_diagnostic_graph/src/core/config.cpp index 2339e96f3951f..4a32398a1b08f 100644 --- a/system/system_diagnostic_graph/src/core/config.cpp +++ b/system/system_diagnostic_graph/src/core/config.cpp @@ -22,6 +22,8 @@ #include #include #include +#include +#include #include #include @@ -66,15 +68,24 @@ ConfigData ConfigData::load(YAML::Node yaml) ConfigData ConfigData::type(const std::string & name) const { ConfigData data(file); - data.mark = name; + data.mark = mark.empty() ? name : mark + "-" + name; return data; } ConfigData ConfigData::node(const size_t index) const { - ConfigData data(file); - data.mark = mark + "-" + std::to_string(index); - return data; + return type(std::to_string(index)); +} + +std::optional ConfigData::take_yaml(const std::string & name) +{ + if (!object.count(name)) { + return std::nullopt; + } + + const auto yaml = object.at(name); + object.erase(name); + return yaml; } std::string ConfigData::take_text(const std::string & name) @@ -114,50 +125,82 @@ std::vector ConfigData::take_list(const std::string & name) return std::vector(yaml.begin(), yaml.end()); } -void check_config_nodes(const std::vector & nodes) +void resolve_link_nodes(RootConfig & root) { - std::unordered_map path_count; - for (const auto & node : nodes) { - path_count[node->path] += 1; + std::unordered_map paths; + for (const auto & node : root.nodes) { + if (node->path.empty()) { + continue; + } + if (paths.count(node->path)) { + throw error("object path is not unique", node->path); + } + paths[node->path] = node; } - path_count.erase(""); - for (const auto & [path, count] : path_count) { - if (1 < count) { - throw error("object path is not unique", path); + std::vector nodes; + std::vector links; + for (const auto & node : root.nodes) { + if (node->type == "link") { + links.push_back(node); + } else { + nodes.push_back(node); } } + + std::unordered_map targets; + for (const auto & node : nodes) { + targets[node] = node; + } + for (const auto & node : links) { + const auto path = node->data.take_text("link"); + if (!paths.count(path)) { + throw error("link path is not found", path, node->data); + } + const auto link = paths.at(path); + if (link->type == "link") { + throw error("link target is link type", path, node->data); + } + targets[node] = link; + } + for (const auto & node : nodes) { + for (auto & child : node->children) { + child = targets.at(child); + } + } + root.nodes = nodes; } -void resolve_link_nodes(std::vector & nodes) +void resolve_remove_edits(RootConfig & root) { - std::vector filtered; - std::unordered_map links; std::unordered_map paths; - - for (const auto & node : nodes) { - links[node] = node; + for (const auto & node : root.nodes) { paths[node->path] = node; } - for (const auto & node : nodes) { - if (node->type == "link" && node->path == "") { - const auto link = node->data.take_text("link"); - if (!paths.count(link)) { - throw error("link path is not found", link, node->data); + std::unordered_set removes; + for (const auto & edit : root.edits) { + if (edit->type == "remove") { + if (!paths.count(edit->path)) { + throw error("remove path is not found", edit->path, edit->data); } - links[node] = paths.at(link); - } else { - filtered.push_back(node); + removes.insert(paths.at(edit->path)); } } - nodes = filtered; - for (const auto & node : nodes) { - for (auto & child : node->children) { - child = links.at(child); + const auto filter = [removes](const std::vector & nodes) { + std::vector result; + for (const auto & node : nodes) { + if (!removes.count(node)) { + result.push_back(node); + } } + return result; + }; + for (const auto & node : root.nodes) { + node->children = filter(node->children); } + root.nodes = filter(root.nodes); } std::string complement_node_type(ConfigData & data) @@ -224,13 +267,23 @@ UnitConfig::SharedPtr parse_node_config(const ConfigData & data) return node; } +EditConfig::SharedPtr parse_edit_config(const ConfigData & data) +{ + const auto edit = std::make_shared(data); + edit->path = edit->data.take_text("path", ""); + edit->type = edit->data.take_text("type", ""); + return edit; +} + FileConfig::SharedPtr parse_file_config(const ConfigData & data) { const auto file = std::make_shared(data); const auto path_data = data.type("file"); const auto node_data = data.type("node"); + const auto edit_data = data.type("edit"); const auto paths = file->data.take_list("files"); const auto nodes = file->data.take_list("nodes"); + const auto edits = file->data.take_list("edits"); for (const auto & [index, yaml] : enumerate(paths)) { const auto path = path_data.node(index).load(yaml); @@ -240,6 +293,10 @@ FileConfig::SharedPtr parse_file_config(const ConfigData & data) const auto node = node_data.node(index).load(yaml); file->nodes.push_back(parse_node_config(node)); } + for (const auto & [index, yaml] : enumerate(edits)) { + const auto edit = edit_data.node(index).load(yaml); + file->edits.push_back(parse_edit_config(edit)); + } return file; } @@ -267,20 +324,22 @@ RootConfig load_root_config(const PathConfig::SharedPtr root) } std::vector nodes; + std::vector edits; for (const auto & file : files) { extend(nodes, file->nodes); + extend(edits, file->edits); } for (size_t i = 0; i < nodes.size(); ++i) { const auto node = nodes[i]; extend(nodes, node->children); } - check_config_nodes(nodes); - resolve_link_nodes(nodes); - RootConfig config; config.files = files; config.nodes = nodes; + config.edits = edits; + resolve_link_nodes(config); + resolve_remove_edits(config); return config; } diff --git a/system/system_diagnostic_graph/src/core/config.hpp b/system/system_diagnostic_graph/src/core/config.hpp index d959f5b6be8aa..d7cdd0ec3c5f7 100644 --- a/system/system_diagnostic_graph/src/core/config.hpp +++ b/system/system_diagnostic_graph/src/core/config.hpp @@ -18,6 +18,7 @@ #include #include +#include #include #include #include @@ -32,6 +33,14 @@ struct ConfigData ConfigData type(const std::string & name) const; ConfigData node(const size_t index) const; + template + T take(const std::string & name, const T & fail) + { + const auto yaml = take_yaml(name); + return yaml ? yaml.value().as() : fail; + } + + std::optional take_yaml(const std::string & name); std::string take_text(const std::string & name); std::string take_text(const std::string & name, const std::string & fail); std::vector take_list(const std::string & name); @@ -64,18 +73,28 @@ struct UnitConfig : public BaseConfig std::vector children; }; +struct EditConfig : public BaseConfig +{ + using SharedPtr = std::shared_ptr; + using BaseConfig::BaseConfig; + std::string type; + std::string path; +}; + struct FileConfig : public BaseConfig { using SharedPtr = std::shared_ptr; using BaseConfig::BaseConfig; std::vector paths; std::vector nodes; + std::vector edits; }; struct RootConfig { std::vector files; std::vector nodes; + std::vector edits; }; template diff --git a/system/system_diagnostic_graph/src/core/debug.cpp b/system/system_diagnostic_graph/src/core/debug.cpp index f14177f4571ad..e2771f08f9f1e 100644 --- a/system/system_diagnostic_graph/src/core/debug.cpp +++ b/system/system_diagnostic_graph/src/core/debug.cpp @@ -26,19 +26,32 @@ namespace system_diagnostic_graph { -const std::unordered_map level_names = { - {DiagnosticStatus::OK, "OK"}, - {DiagnosticStatus::WARN, "WARN"}, - {DiagnosticStatus::ERROR, "ERROR"}, - {DiagnosticStatus::STALE, "STALE"}}; +std::string get_level_text(DiagnosticLevel level) +{ + switch (level) { + case DiagnosticStatus::OK: + return "OK"; + case DiagnosticStatus::WARN: + return "WARN"; + case DiagnosticStatus::ERROR: + return "ERROR"; + case DiagnosticStatus::STALE: + return "STALE"; + } + return "UNKNOWN"; +} void Graph::debug() { std::vector lines; for (const auto & node : nodes_) { - const auto level_name = level_names.at(node->level()); + const auto level_name = get_level_text(node->level()); const auto index_name = std::to_string(node->index()); - lines.push_back({"unit", index_name, level_name, node->path(), "-----"}); + lines.push_back({index_name, level_name, node->path(), node->type()}); + } + for (const auto & [name, level] : unknowns_) { + const auto level_name = get_level_text(level); + lines.push_back({"*", level_name, name, "unknown"}); } std::array widths = {}; diff --git a/system/system_diagnostic_graph/src/core/debug.hpp b/system/system_diagnostic_graph/src/core/debug.hpp index bb1bbc6f14230..297356cd36bab 100644 --- a/system/system_diagnostic_graph/src/core/debug.hpp +++ b/system/system_diagnostic_graph/src/core/debug.hpp @@ -21,7 +21,7 @@ namespace system_diagnostic_graph { -constexpr size_t diag_debug_size = 5; +constexpr size_t diag_debug_size = 4; using DiagDebugData = std::array; } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/error.hpp b/system/system_diagnostic_graph/src/core/error.hpp index 2c10d659f2df4..7e110654bf475 100644 --- a/system/system_diagnostic_graph/src/core/error.hpp +++ b/system/system_diagnostic_graph/src/core/error.hpp @@ -40,6 +40,11 @@ class InvalidType : public Exception using Exception::Exception; }; +class InvalidValue : public Exception +{ + using Exception::Exception; +}; + class FieldNotFound : public Exception { using Exception::Exception; diff --git a/system/system_diagnostic_graph/src/core/graph.cpp b/system/system_diagnostic_graph/src/core/graph.cpp index 96e9bcff5bfd9..5ad7df09de1d1 100644 --- a/system/system_diagnostic_graph/src/core/graph.cpp +++ b/system/system_diagnostic_graph/src/core/graph.cpp @@ -103,6 +103,12 @@ BaseUnit::UniquePtr make_node(const UnitConfig::SharedPtr & config) if (config->type == "or") { return std::make_unique(config->path); } + if (config->type == "warn-to-ok") { + return std::make_unique(config->path, DiagnosticStatus::OK); + } + if (config->type == "warn-to-error") { + return std::make_unique(config->path, DiagnosticStatus::ERROR); + } if (config->type == "ok") { return std::make_unique(config->path, DiagnosticStatus::OK); } @@ -128,10 +134,8 @@ Graph::~Graph() // for unique_ptr } -void Graph::init(const std::string & file, const std::string & mode) +void Graph::init(const std::string & file) { - (void)mode; // TODO(Takagi, Isamu) - BaseUnit::UniquePtrList nodes; BaseUnit::NodeDict dict; @@ -149,17 +153,26 @@ void Graph::init(const std::string & file, const std::string & mode) // Sort units in topological order for update dependencies. nodes = topological_sort(std::move(nodes)); - for (size_t index = 0; index < nodes.size(); ++index) { - nodes[index]->set_index(index); - } - + // List diag nodes that have diag name. for (const auto & node : nodes) { const auto diag = dynamic_cast(node.get()); if (diag) { diags_[diag->name()] = diag; - std::cout << diag->name() << std::endl; } } + + // List unit nodes that have path name. + for (const auto & node : nodes) { + if (!node->path().empty()) { + units_.push_back(node.get()); + } + } + + // Set unit index. + for (size_t index = 0; index < units_.size(); ++index) { + units_[index]->set_index(index); + } + nodes_ = std::move(nodes); } @@ -170,8 +183,7 @@ void Graph::callback(const rclcpp::Time & stamp, const DiagnosticArray & array) if (iter != diags_.end()) { iter->second->callback(stamp, status); } else { - // TODO(Takagi, Isamu) - std::cout << "unknown diag: " << status.name << std::endl; + unknowns_[status.name] = status.level; } } } @@ -184,8 +196,8 @@ DiagnosticGraph Graph::report(const rclcpp::Time & stamp) DiagnosticGraph message; message.stamp = stamp; - message.nodes.reserve(nodes_.size()); - for (const auto & node : nodes_) { + message.nodes.reserve(units_.size()); + for (const auto & node : units_) { const auto report = node->report(); DiagnosticNode temp; temp.status.name = node->path(); diff --git a/system/system_diagnostic_graph/src/core/graph.hpp b/system/system_diagnostic_graph/src/core/graph.hpp index 366f6b457e272..7b0a5bf563106 100644 --- a/system/system_diagnostic_graph/src/core/graph.hpp +++ b/system/system_diagnostic_graph/src/core/graph.hpp @@ -34,16 +34,17 @@ class Graph final Graph(); ~Graph(); - void init(const std::string & file, const std::string & mode = ""); + void init(const std::string & file); void callback(const rclcpp::Time & stamp, const DiagnosticArray & array); + void debug(); DiagnosticGraph report(const rclcpp::Time & stamp); std::vector nodes() const; - void debug(); - private: std::vector> nodes_; + std::vector units_; std::unordered_map diags_; + std::unordered_map unknowns_; }; } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/core/modes.cpp b/system/system_diagnostic_graph/src/core/modes.cpp index 96944bd50f81a..1488387811d67 100644 --- a/system/system_diagnostic_graph/src/core/modes.cpp +++ b/system/system_diagnostic_graph/src/core/modes.cpp @@ -48,9 +48,9 @@ OperationModes::OperationModes(rclcpp::Node & node, const std::vector #include #include @@ -40,13 +42,6 @@ auto resolve(const BaseUnit::NodeDict & dict, const std::vector result; - result.push_back(dict.paths.at(path)); - return result; -} - BaseUnit::BaseUnit(const std::string & path) : path_(path) { index_ = 0; @@ -69,8 +64,8 @@ BaseUnit::NodeData BaseUnit::report() const void DiagUnit::init(const UnitConfig::SharedPtr & config, const NodeDict &) { - timeout_ = 3.0; // TODO(Takagi, Isamu): parameterize name_ = config->data.take_text("diag"); + timeout_ = config->data.take("timeout", 1.0); } void DiagUnit::update(const rclcpp::Time & stamp) @@ -148,6 +143,28 @@ void OrUnit::update(const rclcpp::Time &) level_ = std::min(level_, DiagnosticStatus::ERROR); } +RemapUnit::RemapUnit(const std::string & path, DiagnosticLevel remap_warn) : BaseUnit(path) +{ + remap_warn_ = remap_warn; +} + +void RemapUnit::init(const UnitConfig::SharedPtr & config, const NodeDict & dict) +{ + if (config->children.size() != 1) { + throw error("list size must be 1", config->data); + } + children_ = resolve(dict, config->children); +} + +void RemapUnit::update(const rclcpp::Time &) +{ + const auto status = children_.front()->status(); + level_ = status.level; + links_ = status.links; + + if (level_ == DiagnosticStatus::WARN) level_ = remap_warn_; +} + DebugUnit::DebugUnit(const std::string & path, DiagnosticLevel level) : BaseUnit(path) { level_ = level; // overwrite diff --git a/system/system_diagnostic_graph/src/core/units.hpp b/system/system_diagnostic_graph/src/core/units.hpp index ad5fa4c4bc090..2b94b5f83a216 100644 --- a/system/system_diagnostic_graph/src/core/units.hpp +++ b/system/system_diagnostic_graph/src/core/units.hpp @@ -50,6 +50,7 @@ class BaseUnit virtual ~BaseUnit() = default; virtual void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) = 0; virtual void update(const rclcpp::Time & stamp) = 0; + virtual std::string type() const = 0; NodeData status() const; NodeData report() const; @@ -77,6 +78,7 @@ class DiagUnit : public BaseUnit using BaseUnit::BaseUnit; void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; void update(const rclcpp::Time & stamp) override; + std::string type() const override { return "diag"; } std::string name() const { return name_; } void callback(const rclcpp::Time & stamp, const DiagnosticStatus & status); @@ -93,6 +95,7 @@ class AndUnit : public BaseUnit AndUnit(const std::string & path, bool short_circuit); void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; void update(const rclcpp::Time & stamp) override; + std::string type() const override { return short_circuit_ ? "short-circuit-and" : "and"; } private: bool short_circuit_; @@ -104,6 +107,19 @@ class OrUnit : public BaseUnit using BaseUnit::BaseUnit; void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; void update(const rclcpp::Time & stamp) override; + std::string type() const override { return "or"; } +}; + +class RemapUnit : public BaseUnit +{ +public: + RemapUnit(const std::string & path, DiagnosticLevel remap_warn); + void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; + void update(const rclcpp::Time & stamp) override; + std::string type() const override { return "remap"; } + +private: + DiagnosticLevel remap_warn_; }; class DebugUnit : public BaseUnit @@ -112,6 +128,7 @@ class DebugUnit : public BaseUnit DebugUnit(const std::string & path, DiagnosticLevel level); void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; void update(const rclcpp::Time & stamp) override; + std::string type() const override { return "const"; } }; } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/main.cpp b/system/system_diagnostic_graph/src/main.cpp index 7db35d1fd2551..7393d9fb086f6 100644 --- a/system/system_diagnostic_graph/src/main.cpp +++ b/system/system_diagnostic_graph/src/main.cpp @@ -25,13 +25,11 @@ MainNode::MainNode() : Node("system_diagnostic_graph_aggregator") // Init diagnostics graph. { const auto file = declare_parameter("graph_file"); - const auto mode = declare_parameter("mode"); - graph_.init(file, mode); - graph_.debug(); + graph_.init(file); } - // Init plugins - if (declare_parameter("mode_availability")) { + // Init plugins. + if (declare_parameter("use_operation_mode_availability")) { modes_ = std::make_unique(*this, graph_.nodes()); } @@ -48,6 +46,9 @@ MainNode::MainNode() : Node("system_diagnostic_graph_aggregator") const auto rate = rclcpp::Rate(declare_parameter("rate")); timer_ = rclcpp::create_timer(this, get_clock(), rate.period(), [this]() { on_timer(); }); } + + // Init debug mode. + debug_ = declare_parameter("use_debug_mode"); } MainNode::~MainNode() @@ -59,7 +60,7 @@ void MainNode::on_timer() { const auto stamp = now(); pub_graph_->publish(graph_.report(stamp)); - graph_.debug(); + if (debug_) graph_.debug(); if (modes_) modes_->update(stamp); } diff --git a/system/system_diagnostic_graph/src/main.hpp b/system/system_diagnostic_graph/src/main.hpp index 6deb0518cd9d0..495c51218cabc 100644 --- a/system/system_diagnostic_graph/src/main.hpp +++ b/system/system_diagnostic_graph/src/main.hpp @@ -40,6 +40,8 @@ class MainNode : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_graph_; void on_timer(); void on_diag(const DiagnosticArray::ConstSharedPtr msg); + + bool debug_; }; } // namespace system_diagnostic_graph diff --git a/system/system_diagnostic_graph/src/tool/main.cpp b/system/system_diagnostic_graph/src/tool/main.cpp new file mode 100644 index 0000000000000..6efb911d8e2d3 --- /dev/null +++ b/system/system_diagnostic_graph/src/tool/main.cpp @@ -0,0 +1,140 @@ +// 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 "graph.hpp" +#include "types.hpp" +#include "units.hpp" + +#include +#include +#include + +namespace system_diagnostic_graph +{ + +struct GraphNode +{ + using UniquePtr = std::unique_ptr; + std::string type; + std::string path; + std::vector children; + std::vector parents; +}; + +struct GraphRoot +{ + std::vector owner; + std::vector nodes; +}; + +GraphRoot load_graph_nodes(const std::string & path) +{ + GraphRoot result; + { + std::unordered_map mapping; + Graph graph; + graph.init(path); + + for (const auto & node : graph.nodes()) { + auto data = std::make_unique(); + data->path = node->path(); + data->type = node->type(); + mapping[node] = std::move(data); + } + + for (const auto & [node, data] : mapping) { + for (const auto & link : node->children()) { + const auto parent = data.get(); + const auto child = mapping.at(link).get(); + child->parents.push_back(parent); + parent->children.push_back(child); + } + } + + for (auto & [node, data] : mapping) { + result.owner.push_back(std::move(data)); + } + for (const auto & node : result.owner) { + result.nodes.push_back(node.get()); + } + } + return result; +} + +void dump_plantuml_path(const std::string & path) +{ + const auto graph = load_graph_nodes(path); + const auto color = "#FFFFFF"; + + for (const auto & node : graph.nodes) { + std::cout << "card " << node << " " << color << " [" << std::endl; + std::cout << node->path << std::endl; + std::cout << "]" << std::endl; + } + + for (const auto & node : graph.nodes) { + for (const auto & child : node->children) { + std::cout << node << " --> " << child << std::endl; + } + } +} + +void dump_tree_node(const GraphNode * node, const std::string & indent = "", bool root = true) +{ + const auto path = node->path.empty() ? "" : node->path + " "; + const auto type = "(" + node->type + ")"; + std::cout << indent << "- " << path << type << std::endl; + + if (root || node->parents.size() == 1) { + for (const auto child : node->children) { + dump_tree_node(child, indent + " ", false); + } + } +} + +void dump_tree_path(const std::string & path) +{ + const auto graph = load_graph_nodes(path); + + std::cout << "===== root nodes =================================" << std::endl; + for (const auto & node : graph.nodes) { + if (node->parents.size() == 0 && node->children.size() != 0) { + dump_tree_node(node); + } + } + std::cout << "===== intermediate nodes =========================" << std::endl; + for (const auto & node : graph.nodes) { + if (node->parents.size() >= 2) { + dump_tree_node(node); + } + } + + std::cout << "===== isolated nodes =============================" << std::endl; + for (const auto & node : graph.nodes) { + if (node->parents.size() == 0 && node->children.size() == 0) { + dump_tree_node(node); + } + } +} + +} // namespace system_diagnostic_graph + +int main(int argc, char ** argv) +{ + if (argc != 2) { + std::cerr << "usage: " << argv[0] << " " << std::endl; + return 1; + } + system_diagnostic_graph::dump_tree_path(argv[1]); +} diff --git a/system/system_diagnostic_graph/test/files/field-not-found.yaml b/system/system_diagnostic_graph/test/files/test1/field-not-found.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/field-not-found.yaml rename to system/system_diagnostic_graph/test/files/test1/field-not-found.yaml diff --git a/system/system_diagnostic_graph/test/files/file-not-found.yaml b/system/system_diagnostic_graph/test/files/test1/file-not-found.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/file-not-found.yaml rename to system/system_diagnostic_graph/test/files/test1/file-not-found.yaml diff --git a/system/system_diagnostic_graph/test/files/graph-circulation.yaml b/system/system_diagnostic_graph/test/files/test1/graph-circulation.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/graph-circulation.yaml rename to system/system_diagnostic_graph/test/files/test1/graph-circulation.yaml diff --git a/system/system_diagnostic_graph/test/files/invalid-dict-type.yaml b/system/system_diagnostic_graph/test/files/test1/invalid-dict-type.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/invalid-dict-type.yaml rename to system/system_diagnostic_graph/test/files/test1/invalid-dict-type.yaml diff --git a/system/system_diagnostic_graph/test/files/invalid-list-type.yaml b/system/system_diagnostic_graph/test/files/test1/invalid-list-type.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/invalid-list-type.yaml rename to system/system_diagnostic_graph/test/files/test1/invalid-list-type.yaml diff --git a/system/system_diagnostic_graph/test/files/path-conflict.yaml b/system/system_diagnostic_graph/test/files/test1/path-conflict.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/path-conflict.yaml rename to system/system_diagnostic_graph/test/files/test1/path-conflict.yaml diff --git a/system/system_diagnostic_graph/test/files/path-not-found.yaml b/system/system_diagnostic_graph/test/files/test1/path-not-found.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/path-not-found.yaml rename to system/system_diagnostic_graph/test/files/test1/path-not-found.yaml diff --git a/system/system_diagnostic_graph/test/files/unknown-node-type.yaml b/system/system_diagnostic_graph/test/files/test1/unknown-node-type.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/unknown-node-type.yaml rename to system/system_diagnostic_graph/test/files/test1/unknown-node-type.yaml diff --git a/system/system_diagnostic_graph/test/files/unknown-substitution.yaml b/system/system_diagnostic_graph/test/files/test1/unknown-substitution.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/unknown-substitution.yaml rename to system/system_diagnostic_graph/test/files/test1/unknown-substitution.yaml diff --git a/system/system_diagnostic_graph/test/files/test2/and.yaml b/system/system_diagnostic_graph/test/files/test2/and.yaml new file mode 100644 index 0000000000000..0c9b651f89b2e --- /dev/null +++ b/system/system_diagnostic_graph/test/files/test2/and.yaml @@ -0,0 +1,10 @@ +nodes: + - path: output + type: and + list: + - path: input-0 + type: diag + diag: "test: input-0" + - path: input-1 + type: diag + diag: "test: input-1" diff --git a/system/system_diagnostic_graph/test/files/test2/or.yaml b/system/system_diagnostic_graph/test/files/test2/or.yaml new file mode 100644 index 0000000000000..c7f37a6c32064 --- /dev/null +++ b/system/system_diagnostic_graph/test/files/test2/or.yaml @@ -0,0 +1,10 @@ +nodes: + - path: output + type: or + list: + - path: input-0 + type: diag + diag: "test: input-0" + - path: input-1 + type: diag + diag: "test: input-1" diff --git a/system/system_diagnostic_graph/test/files/test2/warn-to-error.yaml b/system/system_diagnostic_graph/test/files/test2/warn-to-error.yaml new file mode 100644 index 0000000000000..816bf4fd6e1bf --- /dev/null +++ b/system/system_diagnostic_graph/test/files/test2/warn-to-error.yaml @@ -0,0 +1,7 @@ +nodes: + - path: output + type: warn-to-error + list: + - path: input-0 + type: diag + diag: "test: input-0" diff --git a/system/system_diagnostic_graph/test/files/test2/warn-to-ok.yaml b/system/system_diagnostic_graph/test/files/test2/warn-to-ok.yaml new file mode 100644 index 0000000000000..1f5cf18978e3c --- /dev/null +++ b/system/system_diagnostic_graph/test/files/test2/warn-to-ok.yaml @@ -0,0 +1,7 @@ +nodes: + - path: output + type: warn-to-ok + list: + - path: input-0 + type: diag + diag: "test: input-0" diff --git a/system/system_diagnostic_graph/test/src/test.cpp b/system/system_diagnostic_graph/test/src/test1.cpp similarity index 57% rename from system/system_diagnostic_graph/test/src/test.cpp rename to system/system_diagnostic_graph/test/src/test1.cpp index b763179be0791..d01822e93c2eb 100644 --- a/system/system_diagnostic_graph/test/src/test.cpp +++ b/system/system_diagnostic_graph/test/src/test1.cpp @@ -14,75 +14,68 @@ #include "core/error.hpp" #include "core/graph.hpp" +#include "utils.hpp" #include -#include -#include - using namespace system_diagnostic_graph; // NOLINT(build/namespaces) -std::filesystem::path resource(const std::string & path) -{ - return std::filesystem::path(TEST_RESOURCE_PATH) / path; -} - TEST(ConfigFile, RootNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("fake-file-name.yaml")), FileNotFound); + EXPECT_THROW(graph.init(resource("test1/fake-file-name.yaml")), FileNotFound); } TEST(ConfigFile, FileNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("file-not-found.yaml")), FileNotFound); + EXPECT_THROW(graph.init(resource("test1/file-not-found.yaml")), FileNotFound); } TEST(ConfigFile, UnknownSubstitution) { Graph graph; - EXPECT_THROW(graph.init(resource("unknown-substitution.yaml")), UnknownType); + EXPECT_THROW(graph.init(resource("test1/unknown-substitution.yaml")), UnknownType); } TEST(ConfigFile, UnknownNodeType) { Graph graph; - EXPECT_THROW(graph.init(resource("unknown-node-type.yaml")), UnknownType); + EXPECT_THROW(graph.init(resource("test1/unknown-node-type.yaml")), UnknownType); } TEST(ConfigFile, InvalidDictType) { Graph graph; - EXPECT_THROW(graph.init(resource("invalid-dict-type.yaml")), InvalidType); + EXPECT_THROW(graph.init(resource("test1/invalid-dict-type.yaml")), InvalidType); } TEST(ConfigFile, InvalidListType) { Graph graph; - EXPECT_THROW(graph.init(resource("invalid-list-type.yaml")), InvalidType); + EXPECT_THROW(graph.init(resource("test1/invalid-list-type.yaml")), InvalidType); } TEST(ConfigFile, FieldNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("field-not-found.yaml")), FieldNotFound); + EXPECT_THROW(graph.init(resource("test1/field-not-found.yaml")), FieldNotFound); } TEST(ConfigFile, PathConflict) { Graph graph; - EXPECT_THROW(graph.init(resource("path-conflict.yaml")), PathConflict); + EXPECT_THROW(graph.init(resource("test1/path-conflict.yaml")), PathConflict); } TEST(ConfigFile, PathNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("path-not-found.yaml")), PathNotFound); + EXPECT_THROW(graph.init(resource("test1/path-not-found.yaml")), PathNotFound); } TEST(ConfigFile, GraphCirculation) { Graph graph; - EXPECT_THROW(graph.init(resource("graph-circulation.yaml")), GraphStructure); + EXPECT_THROW(graph.init(resource("test1/graph-circulation.yaml")), GraphStructure); } diff --git a/system/system_diagnostic_graph/test/src/test2.cpp b/system/system_diagnostic_graph/test/src/test2.cpp new file mode 100644 index 0000000000000..3e4c946f73fb7 --- /dev/null +++ b/system/system_diagnostic_graph/test/src/test2.cpp @@ -0,0 +1,143 @@ +// 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 "core/error.hpp" +#include "core/graph.hpp" +#include "utils.hpp" + +#include +#include +#include + +#include + +using namespace system_diagnostic_graph; // NOLINT(build/namespaces) + +using diagnostic_msgs::msg::DiagnosticArray; +using diagnostic_msgs::msg::DiagnosticStatus; +using tier4_system_msgs::msg::DiagnosticGraph; + +constexpr auto OK = DiagnosticStatus::OK; +constexpr auto WARN = DiagnosticStatus::WARN; +constexpr auto ERROR = DiagnosticStatus::ERROR; +constexpr auto STALE = DiagnosticStatus::STALE; + +struct GraphTestParam +{ + std::string config; + std::vector inputs; + uint8_t result; +}; + +class GraphTest : public testing::TestWithParam +{ +}; + +DiagnosticArray create_input(const std::vector & levels) +{ + DiagnosticArray array; + for (size_t i = 0; i < levels.size(); ++i) { + DiagnosticStatus status; + status.level = levels[i]; + status.name = "test: input-" + std::to_string(i); + array.status.push_back(status); + } + return array; +}; + +uint8_t get_output(const DiagnosticGraph & graph) +{ + for (const auto & node : graph.nodes) { + if (node.status.name == "output") { + return node.status.level; + } + } + throw std::runtime_error("output node is not found"); +} + +TEST_P(GraphTest, Aggregation) +{ + const auto param = GetParam(); + const auto stamp = rclcpp::Clock().now(); + Graph graph; + graph.init(resource(param.config)); + graph.callback(stamp, create_input(param.inputs)); + + const auto output = get_output(graph.report(stamp)); + EXPECT_EQ(output, param.result); +} + +// clang-format off + +INSTANTIATE_TEST_SUITE_P(And, GraphTest, + testing::Values( + GraphTestParam{"test2/and.yaml", {OK, OK }, OK }, + GraphTestParam{"test2/and.yaml", {OK, WARN }, WARN }, + GraphTestParam{"test2/and.yaml", {OK, ERROR}, ERROR}, + GraphTestParam{"test2/and.yaml", {OK, STALE}, ERROR}, + GraphTestParam{"test2/and.yaml", {WARN, OK }, WARN }, + GraphTestParam{"test2/and.yaml", {WARN, WARN }, WARN }, + GraphTestParam{"test2/and.yaml", {WARN, ERROR}, ERROR}, + GraphTestParam{"test2/and.yaml", {WARN, STALE}, ERROR}, + GraphTestParam{"test2/and.yaml", {ERROR, OK }, ERROR}, + GraphTestParam{"test2/and.yaml", {ERROR, WARN }, ERROR}, + GraphTestParam{"test2/and.yaml", {ERROR, ERROR}, ERROR}, + GraphTestParam{"test2/and.yaml", {ERROR, STALE}, ERROR}, + GraphTestParam{"test2/and.yaml", {STALE, OK }, ERROR}, + GraphTestParam{"test2/and.yaml", {STALE, WARN }, ERROR}, + GraphTestParam{"test2/and.yaml", {STALE, ERROR}, ERROR}, + GraphTestParam{"test2/and.yaml", {STALE, STALE}, ERROR} + ) +); + +INSTANTIATE_TEST_SUITE_P(Or, GraphTest, + testing::Values( + GraphTestParam{"test2/or.yaml", {OK, OK }, OK }, + GraphTestParam{"test2/or.yaml", {OK, WARN }, OK }, + GraphTestParam{"test2/or.yaml", {OK, ERROR}, OK }, + GraphTestParam{"test2/or.yaml", {OK, STALE}, OK }, + GraphTestParam{"test2/or.yaml", {WARN, OK }, OK }, + GraphTestParam{"test2/or.yaml", {WARN, WARN }, WARN }, + GraphTestParam{"test2/or.yaml", {WARN, ERROR}, WARN }, + GraphTestParam{"test2/or.yaml", {WARN, STALE}, WARN }, + GraphTestParam{"test2/or.yaml", {ERROR, OK }, OK }, + GraphTestParam{"test2/or.yaml", {ERROR, WARN }, WARN }, + GraphTestParam{"test2/or.yaml", {ERROR, ERROR}, ERROR}, + GraphTestParam{"test2/or.yaml", {ERROR, STALE}, ERROR}, + GraphTestParam{"test2/or.yaml", {STALE, OK }, OK }, + GraphTestParam{"test2/or.yaml", {STALE, WARN }, WARN }, + GraphTestParam{"test2/or.yaml", {STALE, ERROR}, ERROR}, + GraphTestParam{"test2/or.yaml", {STALE, STALE}, ERROR} + ) +); + +INSTANTIATE_TEST_SUITE_P(WarnToOk, GraphTest, + testing::Values( + GraphTestParam{"test2/warn-to-ok.yaml", {OK }, OK }, + GraphTestParam{"test2/warn-to-ok.yaml", {WARN }, OK}, + GraphTestParam{"test2/warn-to-ok.yaml", {ERROR}, ERROR}, + GraphTestParam{"test2/warn-to-ok.yaml", {STALE}, STALE} + ) +); + +INSTANTIATE_TEST_SUITE_P(WarnToError, GraphTest, + testing::Values( + GraphTestParam{"test2/warn-to-error.yaml", {OK }, OK }, + GraphTestParam{"test2/warn-to-error.yaml", {WARN }, ERROR}, + GraphTestParam{"test2/warn-to-error.yaml", {ERROR}, ERROR}, + GraphTestParam{"test2/warn-to-error.yaml", {STALE}, STALE} + ) +); + +// clang-format on diff --git a/system/system_diagnostic_graph/test/src/utils.cpp b/system/system_diagnostic_graph/test/src/utils.cpp new file mode 100644 index 0000000000000..c64812afa649a --- /dev/null +++ b/system/system_diagnostic_graph/test/src/utils.cpp @@ -0,0 +1,20 @@ +// 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 "utils.hpp" + +std::filesystem::path resource(const std::string & path) +{ + return std::filesystem::path(TEST_RESOURCE_PATH) / path; +} diff --git a/system/system_diagnostic_graph/test/src/utils.hpp b/system/system_diagnostic_graph/test/src/utils.hpp new file mode 100644 index 0000000000000..27f0b293d72dc --- /dev/null +++ b/system/system_diagnostic_graph/test/src/utils.hpp @@ -0,0 +1,23 @@ +// 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 UTILS_HPP_ +#define UTILS_HPP_ + +#include +#include + +std::filesystem::path resource(const std::string & path); + +#endif // UTILS_HPP_ From 64d12e66f4b4bbae38efa9df5973e7d80d2fde04 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Sat, 9 Dec 2023 00:51:12 +0900 Subject: [PATCH 19/87] fix(autoware_auto_msgs_adapter): fix predicted path test (#5744) Signed-off-by: Takagi, Isamu --- .../test/test_msg_predicted_objects.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/system/autoware_auto_msgs_adapter/test/test_msg_predicted_objects.cpp b/system/autoware_auto_msgs_adapter/test/test_msg_predicted_objects.cpp index 9f7f0ce8056f5..a84985770059d 100644 --- a/system/autoware_auto_msgs_adapter/test/test_msg_predicted_objects.cpp +++ b/system/autoware_auto_msgs_adapter/test/test_msg_predicted_objects.cpp @@ -65,7 +65,10 @@ autoware_perception_msgs::msg::PredictedObjects generate_perception_msg() kin.initial_acceleration_with_covariance.accel.angular.y = 0; kin.initial_acceleration_with_covariance.accel.angular.z = 0; - for (size_t i = 0; i < 10; i++) { + constexpr size_t path_size = 10; + kin.predicted_paths.resize(1); + kin.predicted_paths[0].path.resize(path_size); + for (size_t i = 0; i < path_size; i++) { kin.predicted_paths[0].path[i].position.x = i; kin.predicted_paths[0].path[i].position.y = 0; kin.predicted_paths[0].path[i].position.z = 0; From 41e59039a002c7a7d0bb0e1d9c93b2f2fc207f54 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Sat, 9 Dec 2023 17:55:35 +0900 Subject: [PATCH 20/87] refactor(side_shift): separate side shift module (#5820) * refactor(side_shift): separate side shift module Signed-off-by: satoshi-ota * refactor(bpp): remove side shift module Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- planning/behavior_path_planner/CMakeLists.txt | 3 - planning/behavior_path_planner/plugins.xml | 1 - ...t_behavior_path_planner_node_interface.cpp | 4 +- .../CMakeLists.txt | 26 ++++ .../config}/side_shift.param.yaml | 0 .../data_structs.hpp} | 6 +- .../manager.hpp | 8 +- .../scene.hpp} | 10 +- .../utils.hpp} | 8 +- .../package.xml | 38 ++++++ .../plugins.xml | 3 + .../src}/manager.cpp | 2 +- .../src/scene.cpp} | 6 +- .../src/utils.cpp} | 4 +- ...t_behavior_path_planner_node_interface.cpp | 124 ++++++++++++++++++ 15 files changed, 214 insertions(+), 29 deletions(-) create mode 100644 planning/behavior_path_side_shift_module/CMakeLists.txt rename planning/{behavior_path_planner/config/side_shift => behavior_path_side_shift_module/config}/side_shift.param.yaml (100%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/side_shift/side_shift_parameters.hpp => behavior_path_side_shift_module/include/behavior_path_side_shift_module/data_structs.hpp} (86%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/side_shift => behavior_path_side_shift_module/include/behavior_path_side_shift_module}/manager.hpp (83%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp => behavior_path_side_shift_module/include/behavior_path_side_shift_module/scene.hpp} (92%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/side_shift/util.hpp => behavior_path_side_shift_module/include/behavior_path_side_shift_module/utils.hpp} (86%) create mode 100644 planning/behavior_path_side_shift_module/package.xml create mode 100644 planning/behavior_path_side_shift_module/plugins.xml rename planning/{behavior_path_planner/src/scene_module/side_shift => behavior_path_side_shift_module/src}/manager.cpp (97%) rename planning/{behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp => behavior_path_side_shift_module/src/scene.cpp} (99%) rename planning/{behavior_path_planner/src/utils/side_shift/util.cpp => behavior_path_side_shift_module/src/utils.cpp} (97%) create mode 100644 planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index 75f9e7f7af187..56456b08aac1e 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -14,14 +14,11 @@ ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/behavior_path_planner_node.cpp src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp src/scene_module/dynamic_avoidance/manager.cpp - src/scene_module/side_shift/side_shift_module.cpp - src/scene_module/side_shift/manager.cpp src/scene_module/lane_change/interface.cpp src/scene_module/lane_change/normal.cpp src/scene_module/lane_change/external_request.cpp src/scene_module/lane_change/manager.cpp src/utils/lane_change/utils.cpp - src/utils/side_shift/util.cpp src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp src/marker_utils/lane_change/debug.cpp ) diff --git a/planning/behavior_path_planner/plugins.xml b/planning/behavior_path_planner/plugins.xml index fed2e1c9af3c3..2028b0d571e68 100644 --- a/planning/behavior_path_planner/plugins.xml +++ b/planning/behavior_path_planner/plugins.xml @@ -1,5 +1,4 @@ - diff --git a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp index 0e253c0c73985..bab77f9141a00 100644 --- a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp @@ -50,7 +50,6 @@ std::shared_ptr generateNode() std::vector module_names; module_names.emplace_back("behavior_path_planner::DynamicAvoidanceModuleManager"); - module_names.emplace_back("behavior_path_planner::SideShiftModuleManager"); module_names.emplace_back("behavior_path_planner::LaneChangeRightModuleManager"); module_names.emplace_back("behavior_path_planner::LaneChangeLeftModuleManager"); module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeRightModuleManager"); @@ -69,8 +68,7 @@ std::shared_ptr generateNode() behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", behavior_path_planner_dir + "/config/dynamic_avoidance/dynamic_avoidance.param.yaml", - behavior_path_planner_dir + "/config/lane_change/lane_change.param.yaml", - behavior_path_planner_dir + "/config/side_shift/side_shift.param.yaml"}); + behavior_path_planner_dir + "/config/lane_change/lane_change.param.yaml"}); return std::make_shared(node_options); } diff --git a/planning/behavior_path_side_shift_module/CMakeLists.txt b/planning/behavior_path_side_shift_module/CMakeLists.txt new file mode 100644 index 0000000000000..28009e48a4cc4 --- /dev/null +++ b/planning/behavior_path_side_shift_module/CMakeLists.txt @@ -0,0 +1,26 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_path_side_shift_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_path_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/scene.cpp + src/utils.cpp + src/manager.cpp +) + +if(BUILD_TESTING) + ament_add_ros_isolated_gmock(test_${PROJECT_NAME} + test/test_behavior_path_planner_node_interface.cpp + ) + + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) + + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/config/side_shift/side_shift.param.yaml b/planning/behavior_path_side_shift_module/config/side_shift.param.yaml similarity index 100% rename from planning/behavior_path_planner/config/side_shift/side_shift.param.yaml rename to planning/behavior_path_side_shift_module/config/side_shift.param.yaml diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/side_shift_parameters.hpp b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/data_structs.hpp similarity index 86% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/side_shift_parameters.hpp rename to planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/data_structs.hpp index 6475661f72ac4..c9edd3d6bf6a6 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/side_shift_parameters.hpp +++ b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/data_structs.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__SIDE_SHIFT__SIDE_SHIFT_PARAMETERS_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__SIDE_SHIFT__SIDE_SHIFT_PARAMETERS_HPP_ +#ifndef BEHAVIOR_PATH_SIDE_SHIFT_MODULE__DATA_STRUCTS_HPP_ +#define BEHAVIOR_PATH_SIDE_SHIFT_MODULE__DATA_STRUCTS_HPP_ #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -51,4 +51,4 @@ struct SideShiftDebugData }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__SIDE_SHIFT__SIDE_SHIFT_PARAMETERS_HPP_ +#endif // BEHAVIOR_PATH_SIDE_SHIFT_MODULE__DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/manager.hpp similarity index 83% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp rename to planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/manager.hpp index 53bac3914ce86..ef8a48bc29760 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/manager.hpp +++ b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/manager.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SIDE_SHIFT__MANAGER_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SIDE_SHIFT__MANAGER_HPP_ +#ifndef BEHAVIOR_PATH_SIDE_SHIFT_MODULE__MANAGER_HPP_ +#define BEHAVIOR_PATH_SIDE_SHIFT_MODULE__MANAGER_HPP_ -#include "behavior_path_planner/scene_module/side_shift/side_shift_module.hpp" #include "behavior_path_planner_common/interface/scene_module_manager_interface.hpp" +#include "behavior_path_side_shift_module/scene.hpp" #include @@ -50,4 +50,4 @@ class SideShiftModuleManager : public SceneModuleManagerInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SIDE_SHIFT__MANAGER_HPP_ +#endif // BEHAVIOR_PATH_SIDE_SHIFT_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/scene.hpp similarity index 92% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp rename to planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/scene.hpp index 014a0f403f9ec..7d72afebfb359 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/side_shift/side_shift_module.hpp +++ b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/scene.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2021 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SIDE_SHIFT__SIDE_SHIFT_MODULE_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SIDE_SHIFT__SIDE_SHIFT_MODULE_HPP_ +#ifndef BEHAVIOR_PATH_SIDE_SHIFT_MODULE__SCENE_HPP_ +#define BEHAVIOR_PATH_SIDE_SHIFT_MODULE__SCENE_HPP_ -#include "behavior_path_planner/utils/side_shift/side_shift_parameters.hpp" #include "behavior_path_planner_common/interface/scene_module_interface.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" +#include "behavior_path_side_shift_module/data_structs.hpp" #include @@ -134,4 +134,4 @@ class SideShiftModule : public SceneModuleInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__SIDE_SHIFT__SIDE_SHIFT_MODULE_HPP_ +#endif // BEHAVIOR_PATH_SIDE_SHIFT_MODULE__SCENE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/util.hpp b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/utils.hpp similarity index 86% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/util.hpp rename to planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/utils.hpp index 6cdfd84d79075..210dd4e8a8d2a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/side_shift/util.hpp +++ b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/utils.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2021 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__SIDE_SHIFT__UTIL_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__SIDE_SHIFT__UTIL_HPP_ +#ifndef BEHAVIOR_PATH_SIDE_SHIFT_MODULE__UTILS_HPP_ +#define BEHAVIOR_PATH_SIDE_SHIFT_MODULE__UTILS_HPP_ #include #include @@ -41,4 +41,4 @@ Point transformToGrid( } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__SIDE_SHIFT__UTIL_HPP_ +#endif // BEHAVIOR_PATH_SIDE_SHIFT_MODULE__UTILS_HPP_ diff --git a/planning/behavior_path_side_shift_module/package.xml b/planning/behavior_path_side_shift_module/package.xml new file mode 100644 index 0000000000000..5c421b04c0e39 --- /dev/null +++ b/planning/behavior_path_side_shift_module/package.xml @@ -0,0 +1,38 @@ + + + + behavior_path_side_shift_module + 0.1.0 + The behavior_path_side_shift_module package + + Satoshi Ota + Fumiya Watanabe + Kyoichi Sugahara + Tomoya Kimura + Shumpei Wakabayashi + Tomohito Ando + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + autoware_auto_planning_msgs + behavior_path_planner + behavior_path_planner_common + geometry_msgs + motion_utils + pluginlib + rclcpp + tier4_autoware_utils + tier4_planning_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_path_side_shift_module/plugins.xml b/planning/behavior_path_side_shift_module/plugins.xml new file mode 100644 index 0000000000000..2688e3a17c2b6 --- /dev/null +++ b/planning/behavior_path_side_shift_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_path_planner/src/scene_module/side_shift/manager.cpp b/planning/behavior_path_side_shift_module/src/manager.cpp similarity index 97% rename from planning/behavior_path_planner/src/scene_module/side_shift/manager.cpp rename to planning/behavior_path_side_shift_module/src/manager.cpp index b20712ef19179..fa8d579da3d09 100644 --- a/planning/behavior_path_planner/src/scene_module/side_shift/manager.cpp +++ b/planning/behavior_path_side_shift_module/src/manager.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/side_shift/manager.hpp" +#include "behavior_path_side_shift_module/manager.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" diff --git a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp b/planning/behavior_path_side_shift_module/src/scene.cpp similarity index 99% rename from planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp rename to planning/behavior_path_side_shift_module/src/scene.cpp index 9f77288e608cf..69df77672cd96 100644 --- a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp +++ b/planning/behavior_path_side_shift_module/src/scene.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2021 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/side_shift/side_shift_module.hpp" +#include "behavior_path_side_shift_module/scene.hpp" -#include "behavior_path_planner/utils/side_shift/util.hpp" #include "behavior_path_planner_common/marker_utils/utils.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" +#include "behavior_path_side_shift_module/utils.hpp" #include diff --git a/planning/behavior_path_planner/src/utils/side_shift/util.cpp b/planning/behavior_path_side_shift_module/src/utils.cpp similarity index 97% rename from planning/behavior_path_planner/src/utils/side_shift/util.cpp rename to planning/behavior_path_side_shift_module/src/utils.cpp index af733722562f8..a674d57597bc7 100644 --- a/planning/behavior_path_planner/src/utils/side_shift/util.cpp +++ b/planning/behavior_path_side_shift_module/src/utils.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2021 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/side_shift/util.hpp" +#include "behavior_path_side_shift_module/utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" diff --git a/planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp new file mode 100644 index 0000000000000..94be083bdebcd --- /dev/null +++ b/planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp @@ -0,0 +1,124 @@ +// 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 "ament_index_cpp/get_package_share_directory.hpp" +#include "behavior_path_planner/behavior_path_planner_node.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include + +#include +#include + +using behavior_path_planner::BehaviorPathPlannerNode; +using planning_test_utils::PlanningInterfaceTestManager; + +std::shared_ptr generateTestManager() +{ + auto test_manager = std::make_shared(); + + // set subscriber with topic name: behavior_path_planner → test_node_ + test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); + + // set behavior_path_planner's input topic name(this topic is changed to test node) + test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); + + test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); + + return test_manager; +} + +std::shared_ptr generateNode() +{ + auto node_options = rclcpp::NodeOptions{}; + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto behavior_path_planner_dir = + ament_index_cpp::get_package_share_directory("behavior_path_planner"); + + std::vector module_names; + module_names.emplace_back("behavior_path_planner::SideShiftModuleManager"); + + std::vector params; + params.emplace_back("launch_modules", module_names); + node_options.parameter_overrides(params); + + test_utils::updateNodeOptions( + node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", + planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", + behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", + behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", + ament_index_cpp::get_package_share_directory("behavior_path_side_shift_module") + + "/config/side_shift.param.yaml"}); + + return std::make_shared(node_options); +} + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ + // publish necessary topics from test_manager + test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); + test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); + test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); + test_manager->publishOccupancyGrid( + test_target_node, "behavior_path_planner/input/occupancy_grid_map"); + test_manager->publishLaneDrivingScenario( + test_target_node, "behavior_path_planner/input/scenario"); + test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); + test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); + test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); + test_manager->publishLateralOffset( + test_target_node, "behavior_path_planner/input/lateral_offset"); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) +{ + rclcpp::init(0, nullptr); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty route + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + + rclcpp::shutdown(); +} From 851de09583f1abf9321be678f704948a644efebc Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Sun, 10 Dec 2023 17:02:30 +0900 Subject: [PATCH 21/87] fix(avoidance): output invalid avoidance path with unsafe state (#5689) fix(avoidance): output invalid avoidance path Signed-off-by: satoshi-ota --- .../src/scene.cpp | 18 +++--------------- 1 file changed, 3 insertions(+), 15 deletions(-) diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index 9b0c85f60ba29..67316dbc763f2 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -137,7 +137,7 @@ bool AvoidanceModule::isExecutionRequested() const bool AvoidanceModule::isExecutionReady() const { DEBUG_PRINT("AVOIDANCE isExecutionReady"); - return avoid_data_.safe && avoid_data_.comfortable; + return avoid_data_.safe && avoid_data_.comfortable && avoid_data_.valid; } bool AvoidanceModule::canTransitSuccessState() @@ -450,15 +450,14 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de * STEP1: Create candidate shift lines. * Merge rough shift lines, and extract new shift lines. */ - const auto processed_shift_lines = generator_.generate(data, debug); + data.new_shift_line = generator_.generate(data, debug); /** * Step2: Validate new shift lines. * Output new shift lines only when the avoidance path which is generated from them doesn't have * huge offset from ego. */ - data.valid = isValidShiftLine(processed_shift_lines, path_shifter); - data.new_shift_line = data.valid ? processed_shift_lines : AvoidLineArray{}; + data.valid = isValidShiftLine(data.new_shift_line, path_shifter); const auto found_new_sl = data.new_shift_line.size() > 0; const auto registered = path_shifter.getShiftLines().size() > 0; data.found_avoidance_path = found_new_sl || registered; @@ -494,17 +493,6 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de void AvoidanceModule::fillEgoStatus( AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug) const { - /** - * TODO(someone): prevent meaningless stop point insertion in other way. - * If the candidate shift line is invalid, manage all objects as unavoidable. - */ - if (!data.valid) { - std::for_each(data.target_objects.begin(), data.target_objects.end(), [](auto & o) { - o.is_avoidable = false; - o.reason = "InvalidShiftLine"; - }); - } - /** * Find the nearest object that should be avoid. When the ego follows reference path, * if the both of following two conditions are satisfied, the module surely avoid the object. From 281f1ec0fb9b3758eaadfe885bdd995ce1c64a65 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Sun, 10 Dec 2023 08:05:57 +0000 Subject: [PATCH 22/87] chore: update CODEOWNERS (#5811) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/CODEOWNERS | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index ea86022e7134d..3045b3746ea8e 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -154,10 +154,13 @@ perception/traffic_light_multi_camera_fusion/** shunsuke.miura@tier4.jp tao.zhon perception/traffic_light_occlusion_predictor/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/traffic_light_ssd_fine_detector/** daisuke.nishimatsu@tier4.jp perception/traffic_light_visualization/** yukihiro.saito@tier4.jp -planning/behavior_path_avoidance_by_lane_change_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp zulfaqar.azmi@tier4.jp -planning/behavior_path_avoidance_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp takamasa.horibe@tier4.jp -planning/behavior_path_planner/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +planning/behavior_path_avoidance_by_lane_change_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +planning/behavior_path_avoidance_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_path_goal_planner_module/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_path_planner/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_planner_common/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +planning/behavior_path_side_shift_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_path_start_planner_module/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_crosswalk_module/** kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_detection_area_module/** kyoichi.sugahara@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp From 89d4462f45e3af4773f6b930d680cd7ff07f92ea Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Mon, 11 Dec 2023 09:38:16 +0900 Subject: [PATCH 23/87] fix(localization_util): fixed rejection criteria of SmartPoseBuffer::interpolate (#5818) Fixed rejection criteria of SmartPoseBuffer::interpolate Signed-off-by: Shintaro Sakoda --- localization/localization_util/src/smart_pose_buffer.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/localization/localization_util/src/smart_pose_buffer.cpp b/localization/localization_util/src/smart_pose_buffer.cpp index ba293109dcc4d..bc62bfa690946 100644 --- a/localization/localization_util/src/smart_pose_buffer.cpp +++ b/localization/localization_util/src/smart_pose_buffer.cpp @@ -39,10 +39,16 @@ std::optional SmartPoseBuffer::interpolate( const rclcpp::Time time_first = pose_buffer_.front()->header.stamp; const rclcpp::Time time_last = pose_buffer_.back()->header.stamp; - if (target_ros_time < time_first || time_last < target_ros_time) { + if (target_ros_time < time_first) { return std::nullopt; } + // [time_last < target_ros_time] is acceptable here. + // It is possible that the target_ros_time (often sensor timestamp) is newer than the latest + // timestamp of buffered pose (often EKF). + // However, if the timestamp difference is too large, + // it will later be rejected by validate_time_stamp_difference. + // get the nearest poses result.old_pose = *pose_buffer_.front(); for (const PoseWithCovarianceStamped::ConstSharedPtr & pose_cov_msg_ptr : pose_buffer_) { From 32712ab0ce06d551cd4413be5d99742c56c6297a Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Mon, 11 Dec 2023 10:16:28 +0900 Subject: [PATCH 24/87] fix(lidar_centerpoint,image_projection_based_fusion): add guard to avoid exceeding max voxel size (#5824) --- .../pointpainting_fusion/preprocess_kernel.hpp | 5 +++-- .../src/pointpainting_fusion/pointpainting_trt.cpp | 4 ++-- .../src/pointpainting_fusion/preprocess_kernel.cu | 13 ++++++++----- .../preprocess/preprocess_kernel.hpp | 5 +++-- .../lidar_centerpoint/lib/centerpoint_trt.cpp | 4 ++-- .../lib/preprocess/preprocess_kernel.cu | 13 ++++++++----- 6 files changed, 26 insertions(+), 18 deletions(-) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/preprocess_kernel.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/preprocess_kernel.hpp index c913ac33d5e84..897609fa3d86d 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/preprocess_kernel.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/preprocess_kernel.hpp @@ -27,8 +27,9 @@ cudaError_t generateVoxels_random_launch( cudaStream_t stream); cudaError_t generateBaseFeatures_launch( - unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, unsigned int * pillar_num, - float * voxel_features, float * voxel_num, int * voxel_idxs, cudaStream_t stream); + unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, int max_voxel_size, + unsigned int * pillar_num, float * voxel_features, float * voxel_num, int * voxel_idxs, + cudaStream_t stream); cudaError_t generateFeatures_launch( const float * voxel_features, const float * voxel_num_points, const int * coords, diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp index 8911442f4c75d..d44620995c61b 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp @@ -69,8 +69,8 @@ bool PointPaintingTRT::preprocess( CHECK_CUDA_ERROR(image_projection_based_fusion::generateBaseFeatures_launch( mask_d_.get(), voxels_buffer_d_.get(), config_.grid_size_y_, config_.grid_size_x_, - num_voxels_d_.get(), voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), - stream_)); + config_.max_voxel_size_, num_voxels_d_.get(), voxels_d_.get(), num_points_per_voxel_d_.get(), + coordinates_d_.get(), stream_)); CHECK_CUDA_ERROR(image_projection_based_fusion::generateFeatures_launch( voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), num_voxels_d_.get(), diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu b/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu index d06b60633acf8..68e08ac61a569 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu @@ -105,8 +105,8 @@ cudaError_t generateVoxels_random_launch( } __global__ void generateBaseFeatures_kernel( - unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, unsigned int * pillar_num, - float * voxel_features, float * voxel_num, int * voxel_idxs) + unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, int max_voxel_size, + unsigned int * pillar_num, float * voxel_features, float * voxel_num, int * voxel_idxs) { unsigned int voxel_idx = blockIdx.x * blockDim.x + threadIdx.x; unsigned int voxel_idy = blockIdx.y * blockDim.y + threadIdx.y; @@ -120,6 +120,7 @@ __global__ void generateBaseFeatures_kernel( unsigned int current_pillarId = 0; current_pillarId = atomicAdd(pillar_num, 1); + if (current_pillarId > max_voxel_size - 1) return; voxel_num[current_pillarId] = count; @@ -140,15 +141,17 @@ __global__ void generateBaseFeatures_kernel( // create 4 channels cudaError_t generateBaseFeatures_launch( - unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, unsigned int * pillar_num, - float * voxel_features, float * voxel_num, int * voxel_idxs, cudaStream_t stream) + unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, int max_voxel_size, + unsigned int * pillar_num, float * voxel_features, float * voxel_num, int * voxel_idxs, + cudaStream_t stream) { dim3 threads = {32, 32}; dim3 blocks = { (grid_x_size + threads.x - 1) / threads.x, (grid_y_size + threads.y - 1) / threads.y}; generateBaseFeatures_kernel<<>>( - mask, voxels, grid_y_size, grid_x_size, pillar_num, voxel_features, voxel_num, voxel_idxs); + mask, voxels, grid_y_size, grid_x_size, max_voxel_size, pillar_num, voxel_features, voxel_num, + voxel_idxs); cudaError_t err = cudaGetLastError(); return err; } diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/preprocess_kernel.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/preprocess_kernel.hpp index 824144fe3b22b..9488b67475509 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/preprocess_kernel.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/preprocess_kernel.hpp @@ -27,8 +27,9 @@ cudaError_t generateVoxels_random_launch( cudaStream_t stream); cudaError_t generateBaseFeatures_launch( - unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, unsigned int * pillar_num, - float * voxel_features, float * voxel_num, int * voxel_idxs, cudaStream_t stream); + unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, int max_voxel_size, + unsigned int * pillar_num, float * voxel_features, float * voxel_num, int * voxel_idxs, + cudaStream_t stream); cudaError_t generateFeatures_launch( const float * voxel_features, const float * voxel_num_points, const int * coords, diff --git a/perception/lidar_centerpoint/lib/centerpoint_trt.cpp b/perception/lidar_centerpoint/lib/centerpoint_trt.cpp index 67271985d3b5e..2804e172b73fa 100644 --- a/perception/lidar_centerpoint/lib/centerpoint_trt.cpp +++ b/perception/lidar_centerpoint/lib/centerpoint_trt.cpp @@ -156,8 +156,8 @@ bool CenterPointTRT::preprocess( CHECK_CUDA_ERROR(generateBaseFeatures_launch( mask_d_.get(), voxels_buffer_d_.get(), config_.grid_size_y_, config_.grid_size_x_, - num_voxels_d_.get(), voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), - stream_)); + config_.max_voxel_size_, num_voxels_d_.get(), voxels_d_.get(), num_points_per_voxel_d_.get(), + coordinates_d_.get(), stream_)); CHECK_CUDA_ERROR(generateFeatures_launch( voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), num_voxels_d_.get(), diff --git a/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu b/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu index 6f77ff84c2cea..118e31f892d72 100644 --- a/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu +++ b/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu @@ -87,8 +87,8 @@ cudaError_t generateVoxels_random_launch( } __global__ void generateBaseFeatures_kernel( - unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, unsigned int * pillar_num, - float * voxel_features, float * voxel_num, int * voxel_idxs) + unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, int max_voxel_size, + unsigned int * pillar_num, float * voxel_features, float * voxel_num, int * voxel_idxs) { unsigned int voxel_idx = blockIdx.x * blockDim.x + threadIdx.x; unsigned int voxel_idy = blockIdx.y * blockDim.y + threadIdx.y; @@ -102,6 +102,7 @@ __global__ void generateBaseFeatures_kernel( unsigned int current_pillarId = 0; current_pillarId = atomicAdd(pillar_num, 1); + if (current_pillarId > max_voxel_size - 1) return; voxel_num[current_pillarId] = count; @@ -120,15 +121,17 @@ __global__ void generateBaseFeatures_kernel( // create 4 channels cudaError_t generateBaseFeatures_launch( - unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, unsigned int * pillar_num, - float * voxel_features, float * voxel_num, int * voxel_idxs, cudaStream_t stream) + unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, int max_voxel_size, + unsigned int * pillar_num, float * voxel_features, float * voxel_num, int * voxel_idxs, + cudaStream_t stream) { dim3 threads = {32, 32}; dim3 blocks = { (grid_x_size + threads.x - 1) / threads.x, (grid_y_size + threads.y - 1) / threads.y}; generateBaseFeatures_kernel<<>>( - mask, voxels, grid_y_size, grid_x_size, pillar_num, voxel_features, voxel_num, voxel_idxs); + mask, voxels, grid_y_size, grid_x_size, max_voxel_size, pillar_num, voxel_features, voxel_num, + voxel_idxs); cudaError_t err = cudaGetLastError(); return err; } From f41d3faa54f8c1584f5399dcfaa0d851884eb7a0 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 11 Dec 2023 10:55:20 +0900 Subject: [PATCH 25/87] feat(obstacle_cruise_planner): add jerk and acc limits for slow-down (#5810) Add jerk and acc limits for slow-down Signed-off-by: Daniel Sanchez --- .../config/default_common.param.yaml | 4 ++++ .../include/obstacle_cruise_planner/common_structs.hpp | 7 +++++++ planning/obstacle_cruise_planner/src/planner_interface.cpp | 4 ++-- 3 files changed, 13 insertions(+), 2 deletions(-) diff --git a/planning/obstacle_cruise_planner/config/default_common.param.yaml b/planning/obstacle_cruise_planner/config/default_common.param.yaml index 6bb130e8052b0..f900d309123cf 100644 --- a/planning/obstacle_cruise_planner/config/default_common.param.yaml +++ b/planning/obstacle_cruise_planner/config/default_common.param.yaml @@ -7,6 +7,10 @@ min_jerk: -1.0 # min jerk [m/sss] max_jerk: 1.0 # max jerk [m/sss] + slow_down: + min_acc: -1.0 # min slowdown deceleration [m/ss] + min_jerk: -1.0 # min slowdown jerk [m/sss] + # constraints to be observed limit: min_acc: -2.5 # min deceleration limit [m/ss] diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp index 27b2945f614d2..6c44c4744e96c 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp @@ -172,6 +172,8 @@ struct LongitudinalInfo limit_min_accel = node.declare_parameter("limit.min_acc"); limit_max_jerk = node.declare_parameter("limit.max_jerk"); limit_min_jerk = node.declare_parameter("limit.min_jerk"); + slow_down_min_accel = node.declare_parameter("slow_down.min_acc"); + slow_down_min_jerk = node.declare_parameter("slow_down.min_jerk"); idling_time = node.declare_parameter("common.idling_time"); min_ego_accel_for_rss = node.declare_parameter("common.min_ego_accel_for_rss"); @@ -197,6 +199,9 @@ struct LongitudinalInfo tier4_autoware_utils::updateParam(parameters, "limit.min_accel", limit_min_accel); tier4_autoware_utils::updateParam(parameters, "limit.max_jerk", limit_max_jerk); tier4_autoware_utils::updateParam(parameters, "limit.min_jerk", limit_min_jerk); + tier4_autoware_utils::updateParam( + parameters, "slow_down.min_accel", slow_down_min_accel); + tier4_autoware_utils::updateParam(parameters, "slow_down.min_jerk", slow_down_min_jerk); tier4_autoware_utils::updateParam(parameters, "common.idling_time", idling_time); tier4_autoware_utils::updateParam( @@ -220,6 +225,8 @@ struct LongitudinalInfo double min_accel; double max_jerk; double min_jerk; + double slow_down_min_jerk; + double slow_down_min_accel; double limit_max_accel; double limit_min_accel; double limit_max_jerk; diff --git a/planning/obstacle_cruise_planner/src/planner_interface.cpp b/planning/obstacle_cruise_planner/src/planner_interface.cpp index 2dc1247630eaf..a7dac94e1c38a 100644 --- a/planning/obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/obstacle_cruise_planner/src/planner_interface.cpp @@ -763,8 +763,8 @@ PlannerInterface::calculateDistanceToSlowDownWithConstraints( } // TODO(murooka) Calculate more precisely. Final acceleration should be zero. const double min_feasible_slow_down_vel = calcDecelerationVelocityFromDistanceToTarget( - longitudinal_info_.min_jerk, longitudinal_info_.min_accel, planner_data.ego_acc, - planner_data.ego_vel, deceleration_dist); + longitudinal_info_.slow_down_min_jerk, longitudinal_info_.slow_down_min_accel, + planner_data.ego_acc, planner_data.ego_vel, deceleration_dist); return min_feasible_slow_down_vel; }(); if (prev_output) { From 5d6cfeffbef2658f73e875f01c2c8b7d57b65b9d Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Mon, 11 Dec 2023 11:28:34 +0900 Subject: [PATCH 26/87] fix(traffic_light): stop if the traffic light signal timed out (#5819) * fix(traffic_light): stop if the traffic light signal timed out Signed-off-by: Fumiya Watanabe * fix(traffic_light): fix README format Signed-off-by: Fumiya Watanabe --------- Signed-off-by: Fumiya Watanabe --- .../README.md | 23 ++++-- .../config/traffic_light.param.yaml | 1 + .../src/manager.cpp | 2 + .../src/scene.cpp | 74 ++++++++++++++----- .../src/scene.hpp | 15 +++- 5 files changed, 84 insertions(+), 31 deletions(-) diff --git a/planning/behavior_velocity_traffic_light_module/README.md b/planning/behavior_velocity_traffic_light_module/README.md index 866ab87070369..e85a171495e38 100644 --- a/planning/behavior_velocity_traffic_light_module/README.md +++ b/planning/behavior_velocity_traffic_light_module/README.md @@ -19,7 +19,13 @@ This module is activated when there is traffic light in ego lane. 1. Obtains a traffic light mapped to the route and a stop line correspond to the traffic light from a map information. -2. Uses the highest reliability one of the traffic light recognition result and if the color of that was red, generates a stop point. + - If a corresponding traffic light signal have never been found, it treats as a signal to pass. + + - If a corresponding traffic light signal is found but timed out, it treats as a signal to stop. + +2. Uses the highest reliability one of the traffic light recognition result and if the color of that was not green or corresponding arrow signal, generates a stop point. + + - If an elapsed time to receive stop signal is less than `stop_time_hysteresis`, it treats as a signal to pass. This feature is to prevent chattering. 3. When vehicle current velocity is @@ -63,12 +69,13 @@ This module is activated when there is traffic light in ego lane. #### Module Parameters -| Parameter | Type | Description | -| -------------------- | ------ | ----------------------------------------------- | -| `stop_margin` | double | [m] margin before stop point | -| `tl_state_timeout` | double | [s] time out for detected traffic light result. | -| `yellow_lamp_period` | double | [s] time for yellow lamp | -| `enable_pass_judge` | bool | [-] whether to use pass judge | +| Parameter | Type | Description | +| ---------------------- | ------ | -------------------------------------------------------------------- | +| `stop_margin` | double | [m] margin before stop point | +| `tl_state_timeout` | double | [s] time out for detected traffic light result. | +| `stop_time_hysteresis` | double | [s] time threshold to decide stop planning for chattering prevention | +| `yellow_lamp_period` | double | [s] time for yellow lamp | +| `enable_pass_judge` | bool | [-] whether to use pass judge | #### Flowchart @@ -91,7 +98,7 @@ if (state is APPROACH) then (yes) :change state to GO_OUT; stop elseif (no stop signal) then (yes) - :change previous state to STOP; + :change previous state to PASS; stop elseif (not pass through) then (yes) :insert stop pose; diff --git a/planning/behavior_velocity_traffic_light_module/config/traffic_light.param.yaml b/planning/behavior_velocity_traffic_light_module/config/traffic_light.param.yaml index a837ae1b46b9b..23746a61b6043 100644 --- a/planning/behavior_velocity_traffic_light_module/config/traffic_light.param.yaml +++ b/planning/behavior_velocity_traffic_light_module/config/traffic_light.param.yaml @@ -3,6 +3,7 @@ traffic_light: stop_margin: 0.0 tl_state_timeout: 1.0 + stop_time_hysteresis: 0.1 yellow_lamp_period: 2.75 enable_pass_judge: true enable_rtc: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval diff --git a/planning/behavior_velocity_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_traffic_light_module/src/manager.cpp index a23edefff52ab..908627540bdcc 100644 --- a/planning/behavior_velocity_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/manager.cpp @@ -38,6 +38,8 @@ TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node) const std::string ns(getModuleName()); planner_param_.stop_margin = getOrDeclareParameter(node, ns + ".stop_margin"); planner_param_.tl_state_timeout = getOrDeclareParameter(node, ns + ".tl_state_timeout"); + planner_param_.stop_time_hysteresis = + getOrDeclareParameter(node, ns + ".stop_time_hysteresis"); planner_param_.enable_pass_judge = getOrDeclareParameter(node, ns + ".enable_pass_judge"); planner_param_.yellow_lamp_period = getOrDeclareParameter(node, ns + ".yellow_lamp_period"); diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_traffic_light_module/src/scene.cpp index 90a547adeb930..a74ff8c0cb5e8 100644 --- a/planning/behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/scene.cpp @@ -222,13 +222,33 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason * if (signed_arc_length_to_stop_point < signed_deadline_length) { RCLCPP_INFO(logger_, "APPROACH -> GO_OUT"); state_ = State::GO_OUT; + stop_signal_received_time_ptr_.reset(); return true; } first_ref_stop_path_point_index_ = stop_line_point_idx; // Check if stop is coming. - setSafe(!isStopSignal()); + const bool is_stop_signal = isStopSignal(); + + // Update stop signal received time + if (is_stop_signal) { + if (!stop_signal_received_time_ptr_) { + stop_signal_received_time_ptr_ = std::make_unique diff --git a/system/autoware_auto_msgs_adapter/package.xml b/system/autoware_auto_msgs_adapter/package.xml index 99a94fa043565..2941820550ba0 100644 --- a/system/autoware_auto_msgs_adapter/package.xml +++ b/system/autoware_auto_msgs_adapter/package.xml @@ -22,9 +22,11 @@ autoware_auto_control_msgs autoware_auto_mapping_msgs autoware_auto_perception_msgs + autoware_auto_planning_msgs autoware_control_msgs autoware_map_msgs autoware_perception_msgs + autoware_planning_msgs rclcpp rclcpp_components diff --git a/system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json b/system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json index f6aa87f774528..a5d6c93029d09 100644 --- a/system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json +++ b/system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json @@ -12,7 +12,8 @@ "enum": [ "autoware_auto_control_msgs/msg/AckermannControlCommand", "autoware_auto_mapping_msgs/msg/HADMapBin", - "autoware_auto_perception_msgs/msg/PredictedObjects" + "autoware_auto_perception_msgs/msg/PredictedObjects", + "autoware_auto_planning_msgs/msg/Trajectory" ], "default": "autoware_auto_control_msgs/msg/AckermannControlCommand" }, diff --git a/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp b/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp index 15e3c90d227dd..6a23970246866 100644 --- a/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp +++ b/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp @@ -67,6 +67,11 @@ MapStringAdapter AutowareAutoMsgsAdapterNode::create_adapter_map( return std::static_pointer_cast( std::make_shared(*this, topic_name_source, topic_name_target)); }}, + {"autoware_auto_planning_msgs/msg/Trajectory", + [&] { + return std::static_pointer_cast( + std::make_shared(*this, topic_name_source, topic_name_target)); + }}, }; } diff --git a/system/autoware_auto_msgs_adapter/src/include/adapter_planning.hpp b/system/autoware_auto_msgs_adapter/src/include/adapter_planning.hpp new file mode 100644 index 0000000000000..79d73bdda0575 --- /dev/null +++ b/system/autoware_auto_msgs_adapter/src/include/adapter_planning.hpp @@ -0,0 +1,70 @@ +// 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. +#ifndef ADAPTER_PLANNING_HPP_ +#define ADAPTER_PLANNING_HPP_ + +#include "adapter_base.hpp" + +#include + +#include +#include + +#include + +namespace autoware_auto_msgs_adapter +{ +using TrajectoryAuto = autoware_auto_planning_msgs::msg::Trajectory; +using PointAuto = autoware_auto_planning_msgs::msg::TrajectoryPoint; +using Trajectory = autoware_planning_msgs::msg::Trajectory; + +class AdapterPlanning : public autoware_auto_msgs_adapter::AdapterBase +{ +public: + AdapterPlanning( + rclcpp::Node & node, const std::string & topic_name_source, + const std::string & topic_name_target, const rclcpp::QoS & qos = rclcpp::QoS{1}) + : AdapterBase(node, topic_name_source, topic_name_target, qos) + { + RCLCPP_DEBUG( + node.get_logger(), "AdapterPlanning is initialized to convert: %s -> %s", + topic_name_source.c_str(), topic_name_target.c_str()); + } + +protected: + TrajectoryAuto convert(const Trajectory & msg_source) override + { + TrajectoryAuto msg_auto; + msg_auto.header = msg_source.header; + PointAuto trajectory_point_auto; + msg_auto.points.reserve(msg_source.points.size()); + for (size_t i = 0; i < msg_source.points.size(); i++) { + trajectory_point_auto.time_from_start = msg_source.points.at(i).time_from_start; + trajectory_point_auto.pose = msg_source.points.at(i).pose; + trajectory_point_auto.longitudinal_velocity_mps = + msg_source.points.at(i).longitudinal_velocity_mps; + trajectory_point_auto.lateral_velocity_mps = msg_source.points.at(i).lateral_velocity_mps; + trajectory_point_auto.acceleration_mps2 = msg_source.points.at(i).acceleration_mps2; + trajectory_point_auto.heading_rate_rps = msg_source.points.at(i).heading_rate_rps; + trajectory_point_auto.front_wheel_angle_rad = msg_source.points.at(i).front_wheel_angle_rad; + trajectory_point_auto.rear_wheel_angle_rad = msg_source.points.at(i).rear_wheel_angle_rad; + msg_auto.points.push_back(trajectory_point_auto); + } + + return msg_auto; + } +}; +} // namespace autoware_auto_msgs_adapter + +#endif // ADAPTER_PLANNING_HPP_ diff --git a/system/autoware_auto_msgs_adapter/src/include/autoware_auto_msgs_adapter_core.hpp b/system/autoware_auto_msgs_adapter/src/include/autoware_auto_msgs_adapter_core.hpp index f0e28f48aacd8..258bf01244499 100644 --- a/system/autoware_auto_msgs_adapter/src/include/autoware_auto_msgs_adapter_core.hpp +++ b/system/autoware_auto_msgs_adapter/src/include/autoware_auto_msgs_adapter_core.hpp @@ -17,6 +17,7 @@ #include "adapter_control.hpp" #include "adapter_map.hpp" #include "adapter_perception.hpp" +#include "adapter_planning.hpp" #include diff --git a/system/autoware_auto_msgs_adapter/test/test_msg_planning_trajectory.cpp b/system/autoware_auto_msgs_adapter/test/test_msg_planning_trajectory.cpp new file mode 100644 index 0000000000000..e2d44d6085c8a --- /dev/null +++ b/system/autoware_auto_msgs_adapter/test/test_msg_planning_trajectory.cpp @@ -0,0 +1,149 @@ +// 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 + +autoware_planning_msgs::msg::Trajectory generate_planning_msg() +{ + using TrajectoryPoint = autoware_planning_msgs::msg::TrajectoryPoint; + // generate deterministic random int + std::mt19937 gen(0); + std::uniform_int_distribution<> dis_int(0, 1000000); + auto rand_int = [&dis_int, &gen]() { return dis_int(gen); }; + + autoware_planning_msgs::msg::Trajectory msg_planning; + msg_planning.header.stamp = rclcpp::Time(rand_int()); + msg_planning.header.frame_id = "test_frame"; + + TrajectoryPoint point; + geometry_msgs::msg::Pose pose; + pose.position.x = 0.0; + pose.position.y = 0.0; + pose.position.z = 0.0; + pose.orientation.x = 0.0; + pose.orientation.y = 0.0; + pose.orientation.z = 0.0; + pose.orientation.w = 1.0; + + for (size_t i = 0; i < 100; i++) { + point.longitudinal_velocity_mps = 1.0; + point.time_from_start = rclcpp::Duration::from_seconds(0.0); + point.pose = pose; + point.longitudinal_velocity_mps = 20.0; + point.lateral_velocity_mps = 0.0; + point.acceleration_mps2 = 1.0; + point.heading_rate_rps = 2.0; + point.front_wheel_angle_rad = 8.0; + point.rear_wheel_angle_rad = 10.0; + + msg_planning.points.push_back(point); + } + + return msg_planning; +} + +TEST(AutowareAutoMsgsAdapter, TestTrajectory) // NOLINT for gtest +{ + const std::string msg_type_target = "autoware_auto_planning_msgs/msg/Trajectory"; + const std::string topic_name_source = "topic_name_source"; + const std::string topic_name_target = "topic_name_target"; + + std::cout << "Creating the adapter node..." << std::endl; + + rclcpp::NodeOptions node_options; + node_options.append_parameter_override("msg_type_target", msg_type_target); + node_options.append_parameter_override("topic_name_source", topic_name_source); + node_options.append_parameter_override("topic_name_target", topic_name_target); + + using autoware_auto_msgs_adapter::AutowareAutoMsgsAdapterNode; + AutowareAutoMsgsAdapterNode::SharedPtr node_adapter; + node_adapter = std::make_shared(node_options); + + std::cout << "Creating the subscriber node..." << std::endl; + + auto node_subscriber = std::make_shared("node_subscriber", rclcpp::NodeOptions{}); + + bool test_completed = false; + + const auto msg_planning = generate_planning_msg(); + auto sub = node_subscriber->create_subscription( + topic_name_target, rclcpp::QoS{1}, + [&msg_planning, + &test_completed](const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr msg) { + EXPECT_EQ(msg->header.stamp, msg_planning.header.stamp); + EXPECT_EQ(msg->header.frame_id, msg_planning.header.frame_id); + for (size_t i = 0; i < msg_planning.points.size(); i++) { + EXPECT_FLOAT_EQ( + msg->points.at(i).pose.position.x, msg_planning.points.at(i).pose.position.x); + EXPECT_FLOAT_EQ( + msg->points.at(i).pose.position.y, msg_planning.points.at(i).pose.position.y); + EXPECT_FLOAT_EQ( + msg->points.at(i).pose.position.z, msg_planning.points.at(i).pose.position.z); + EXPECT_FLOAT_EQ( + msg->points.at(i).pose.orientation.x, msg_planning.points.at(i).pose.orientation.x); + EXPECT_FLOAT_EQ( + msg->points.at(i).pose.orientation.y, msg_planning.points.at(i).pose.orientation.y); + EXPECT_FLOAT_EQ( + msg->points.at(i).pose.orientation.z, msg_planning.points.at(i).pose.orientation.z); + EXPECT_FLOAT_EQ( + msg->points.at(i).pose.orientation.w, msg_planning.points.at(i).pose.orientation.w); + EXPECT_FLOAT_EQ( + msg->points.at(i).longitudinal_velocity_mps, + msg_planning.points.at(i).longitudinal_velocity_mps); + EXPECT_FLOAT_EQ( + msg->points.at(i).lateral_velocity_mps, msg_planning.points.at(i).lateral_velocity_mps); + EXPECT_FLOAT_EQ( + msg->points.at(i).acceleration_mps2, msg_planning.points.at(i).acceleration_mps2); + EXPECT_FLOAT_EQ( + msg->points.at(i).heading_rate_rps, msg_planning.points.at(i).heading_rate_rps); + EXPECT_FLOAT_EQ( + msg->points.at(i).front_wheel_angle_rad, msg_planning.points.at(i).front_wheel_angle_rad); + EXPECT_FLOAT_EQ( + msg->points.at(i).rear_wheel_angle_rad, msg_planning.points.at(i).rear_wheel_angle_rad); + } + + test_completed = true; + }); + + std::cout << "Creating the publisher node..." << std::endl; + + auto node_publisher = std::make_shared("node_publisher", rclcpp::NodeOptions{}); + auto pub = node_publisher->create_publisher( + topic_name_source, rclcpp::QoS{1}); + pub->publish(msg_planning); + + auto start_time = std::chrono::system_clock::now(); + auto max_test_dur = std::chrono::seconds(5); + auto timed_out = false; + + while (rclcpp::ok() && !test_completed) { + rclcpp::spin_some(node_subscriber); + rclcpp::spin_some(node_adapter); + rclcpp::spin_some(node_publisher); + rclcpp::sleep_for(std::chrono::milliseconds(50)); + if (std::chrono::system_clock::now() - start_time > max_test_dur) { + timed_out = true; + break; + } + } + + EXPECT_TRUE(test_completed); + EXPECT_FALSE(timed_out); + + // rclcpp::shutdown(); +} From 7477e9a5126cd6db5f382499ff8a0ac2fdc60161 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Wed, 13 Dec 2023 22:02:36 +0900 Subject: [PATCH 49/87] chore: add glog_component for pointcloud_container (#5716) Signed-off-by: badai-nguyen --- .../ground_segmentation/ground_segmentation.launch.py | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 32a3fa102897d..fecdd29bcb7e9 100644 --- a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -474,7 +474,13 @@ def get_single_frame_obstacle_segmentation_concatenated_component(input_topics, def launch_setup(context, *args, **kwargs): pipeline = GroundSegmentationPipeline(context) - components = [] + glog_component = ComposableNode( + package="glog_component", + plugin="GlogComponent", + name="glog_component", + ) + + components = [glog_component] components.extend( pipeline.create_single_frame_obstacle_segmentation_components( input_topic=LaunchConfiguration("input/pointcloud"), From dff91ba964ba51b3db7023044f1057dd8ea775ed Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 14 Dec 2023 09:13:57 +0900 Subject: [PATCH 50/87] refactor(ar_tag_based_localizer): refactor pub/sub and so on (#5854) * Fixed ar_tag_based_localizer pub/sub Signed-off-by: Shintaro SAKODA * Remove dependency on image_transport Signed-off-by: Shintaro SAKODA --------- Signed-off-by: Shintaro SAKODA --- .../ar_tag_based_localizer.launch.xml | 20 ++--- .../launch/ar_tag_based_localizer.launch.xml | 10 ++- .../ar_tag_based_localizer/package.xml | 1 - .../src/ar_tag_based_localizer.cpp | 79 +++++++------------ .../src/ar_tag_based_localizer.hpp | 13 ++- .../ar_tag_based_localizer/src/main.cpp | 1 - .../ar_tag_based_localizer/test/test.cpp | 3 +- 7 files changed, 50 insertions(+), 77 deletions(-) diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml index 181f470a00800..ac7589ea2273b 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml @@ -1,17 +1,13 @@ - - - - - - - - - - - - + + + + + + + + diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml b/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml index 6437455875cc2..272338905c3f0 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml @@ -8,18 +8,24 @@ - + + + + - + + + + diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml index 7e83220dadf2a..857ec4f16f051 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml @@ -17,7 +17,6 @@ aruco cv_bridge diagnostic_msgs - image_transport landmark_manager lanelet2_extension localization_util diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp index e569a71bbb5b0..a1e2f3ec31dd3 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp @@ -66,10 +66,6 @@ ArTagBasedLocalizer::ArTagBasedLocalizer(const rclcpp::NodeOptions & options) : Node("ar_tag_based_localizer", options), cam_info_received_(false) -{ -} - -bool ArTagBasedLocalizer::setup() { /* Declare node parameters @@ -92,7 +88,7 @@ bool ArTagBasedLocalizer::setup() } else { // Error RCLCPP_ERROR_STREAM(this->get_logger(), "Invalid detection_mode: " << detection_mode); - return false; + return; } ekf_pose_buffer_ = std::make_unique( this->get_logger(), ekf_time_tolerance_, ekf_position_tolerance_); @@ -111,59 +107,50 @@ bool ArTagBasedLocalizer::setup() tf_buffer_ = std::make_unique(this->get_clock()); tf_listener_ = std::make_unique(*tf_buffer_); - /* - Initialize image transport - */ - it_ = std::make_unique(shared_from_this()); - /* Subscribers */ + using std::placeholders::_1; map_bin_sub_ = this->create_subscription( "~/input/lanelet2_map", rclcpp::QoS(10).durability(rclcpp::DurabilityPolicy::TransientLocal), - std::bind(&ArTagBasedLocalizer::map_bin_callback, this, std::placeholders::_1)); + std::bind(&ArTagBasedLocalizer::map_bin_callback, this, _1)); rclcpp::QoS qos_sub(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); qos_sub.best_effort(); - pose_array_pub_ = this->create_publisher("~/debug/detected_landmarks", qos_sub); image_sub_ = this->create_subscription( - "~/input/image", qos_sub, - std::bind(&ArTagBasedLocalizer::image_callback, this, std::placeholders::_1)); + "~/input/image", qos_sub, std::bind(&ArTagBasedLocalizer::image_callback, this, _1)); cam_info_sub_ = this->create_subscription( - "~/input/camera_info", qos_sub, - std::bind(&ArTagBasedLocalizer::cam_info_callback, this, std::placeholders::_1)); + "~/input/camera_info", qos_sub, std::bind(&ArTagBasedLocalizer::cam_info_callback, this, _1)); ekf_pose_sub_ = this->create_subscription( - "~/input/ekf_pose", qos_sub, - std::bind(&ArTagBasedLocalizer::ekf_pose_callback, this, std::placeholders::_1)); + "~/input/ekf_pose", qos_sub, std::bind(&ArTagBasedLocalizer::ekf_pose_callback, this, _1)); /* Publishers */ - rclcpp::QoS qos_marker = rclcpp::QoS(rclcpp::KeepLast(10)); - qos_marker.transient_local(); - qos_marker.reliable(); - marker_pub_ = this->create_publisher("~/debug/marker", qos_marker); - rclcpp::QoS qos_pub(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); - image_pub_ = it_->advertise("~/debug/result", 1); - pose_pub_ = - this->create_publisher("~/output/pose_with_covariance", qos_pub); - diag_pub_ = this->create_publisher("/diagnostics", qos_pub); + const rclcpp::QoS qos_pub_once = rclcpp::QoS(rclcpp::KeepLast(10)).transient_local().reliable(); + const rclcpp::QoS qos_pub_periodic(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); + pose_pub_ = this->create_publisher( + "~/output/pose_with_covariance", qos_pub_periodic); + image_pub_ = this->create_publisher("~/debug/image", qos_pub_periodic); + mapped_tag_pose_pub_ = this->create_publisher("~/debug/mapped_tag", qos_pub_once); + detected_tag_pose_pub_ = + this->create_publisher("~/debug/detected_tag", qos_pub_periodic); + diag_pub_ = this->create_publisher("/diagnostics", qos_pub_periodic); RCLCPP_INFO(this->get_logger(), "Setup of ar_tag_based_localizer node is successful!"); - return true; } void ArTagBasedLocalizer::map_bin_callback(const HADMapBin::ConstSharedPtr & msg) { landmark_manager_.parse_landmarks(msg, "apriltag_16h5", this->get_logger()); const MarkerArray marker_msg = landmark_manager_.get_landmarks_as_marker_array_msg(); - marker_pub_->publish(marker_msg); + mapped_tag_pose_pub_->publish(marker_msg); } void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg) { // check subscribers - if ((image_pub_.getNumSubscribers() == 0) && (pose_pub_->get_subscription_count() == 0)) { + if ((image_pub_->get_subscription_count() == 0) && (pose_pub_->get_subscription_count() == 0)) { RCLCPP_DEBUG(this->get_logger(), "No subscribers, not looking for ArUco markers"); return; } @@ -192,7 +179,7 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg) } // for debug - if (pose_array_pub_->get_subscription_count() > 0) { + if (detected_tag_pose_pub_->get_subscription_count() > 0) { PoseArray pose_array_msg; pose_array_msg.header.stamp = sensor_stamp; pose_array_msg.header.frame_id = "map"; @@ -201,7 +188,7 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg) tier4_autoware_utils::transformPose(landmark.pose, self_pose); pose_array_msg.poses.push_back(detected_marker_on_map); } - pose_array_pub_->publish(pose_array_msg); + detected_tag_pose_pub_->publish(pose_array_msg); } // calc new_self_pose @@ -267,24 +254,12 @@ void ArTagBasedLocalizer::cam_info_callback(const CameraInfo::ConstSharedPtr & m return; } - cv::Mat camera_matrix(3, 4, CV_64FC1, 0.0); - camera_matrix.at(0, 0) = msg->p[0]; - camera_matrix.at(0, 1) = msg->p[1]; - camera_matrix.at(0, 2) = msg->p[2]; - camera_matrix.at(0, 3) = msg->p[3]; - camera_matrix.at(1, 0) = msg->p[4]; - camera_matrix.at(1, 1) = msg->p[5]; - camera_matrix.at(1, 2) = msg->p[6]; - camera_matrix.at(1, 3) = msg->p[7]; - camera_matrix.at(2, 0) = msg->p[8]; - camera_matrix.at(2, 1) = msg->p[9]; - camera_matrix.at(2, 2) = msg->p[10]; - camera_matrix.at(2, 3) = msg->p[11]; - - cv::Mat distortion_coeff(4, 1, CV_64FC1); - for (int i = 0; i < 4; ++i) { - distortion_coeff.at(i, 0) = 0; - } + // copy camera matrix + cv::Mat camera_matrix(3, 4, CV_64FC1); + std::copy(msg->p.begin(), msg->p.end(), camera_matrix.begin()); + + // all 0 + cv::Mat distortion_coeff(4, 1, CV_64FC1, 0.0); const cv::Size size(static_cast(msg->width), static_cast(msg->height)); @@ -361,12 +336,12 @@ std::vector ArTagBasedLocalizer::detect_landmarks( } // for debug - if (image_pub_.getNumSubscribers() > 0) { + if (image_pub_->get_subscription_count() > 0) { cv_bridge::CvImage out_msg; out_msg.header.stamp = sensor_stamp; out_msg.encoding = sensor_msgs::image_encodings::RGB8; out_msg.image = in_image; - image_pub_.publish(out_msg.toImageMsg()); + image_pub_->publish(*out_msg.toImageMsg()); } return landmarks; diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp index b7dfb45a26ce3..eb7406f8c77f8 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp @@ -48,11 +48,12 @@ #include "landmark_manager/landmark_manager.hpp" #include "localization_util/smart_pose_buffer.hpp" -#include #include #include #include +#include +#include #include #include @@ -82,7 +83,6 @@ class ArTagBasedLocalizer : public rclcpp::Node public: explicit ArTagBasedLocalizer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); - bool setup(); private: void map_bin_callback(const HADMapBin::ConstSharedPtr & msg); @@ -104,9 +104,6 @@ class ArTagBasedLocalizer : public rclcpp::Node std::unique_ptr tf_buffer_; std::unique_ptr tf_listener_; - // image transport - std::unique_ptr it_; - // Subscribers rclcpp::Subscription::SharedPtr map_bin_sub_; rclcpp::Subscription::SharedPtr image_sub_; @@ -114,10 +111,10 @@ class ArTagBasedLocalizer : public rclcpp::Node rclcpp::Subscription::SharedPtr ekf_pose_sub_; // Publishers - rclcpp::Publisher::SharedPtr marker_pub_; - rclcpp::Publisher::SharedPtr pose_array_pub_; - image_transport::Publisher image_pub_; rclcpp::Publisher::SharedPtr pose_pub_; + rclcpp::Publisher::SharedPtr image_pub_; + rclcpp::Publisher::SharedPtr detected_tag_pose_pub_; + rclcpp::Publisher::SharedPtr mapped_tag_pose_pub_; rclcpp::Publisher::SharedPtr diag_pub_; // Others diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/main.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/main.cpp index cbcd57b4b222a..8ef1dd6195580 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/main.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/main.cpp @@ -48,7 +48,6 @@ int main(int argc, char ** argv) { rclcpp::init(argc, argv); std::shared_ptr ptr = std::make_shared(); - ptr->setup(); rclcpp::spin(ptr); rclcpp::shutdown(); } diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp index 1b44327fd9e8b..5d05dd7e3755a 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/test/test.cpp @@ -55,7 +55,8 @@ class TestArTagBasedLocalizer : public ::testing::Test TEST_F(TestArTagBasedLocalizer, test_setup) // NOLINT { - EXPECT_TRUE(node_->setup()); + // Check if the constructor finishes successfully + EXPECT_TRUE(true); } int main(int argc, char ** argv) From 3d40702b39fe12b64576393bae71e00753290eae Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Kaan=20=C3=87olak?= Date: Thu, 14 Dec 2023 04:07:00 +0300 Subject: [PATCH 51/87] feat(shape_estimation): add bicycle shape corrector (#5860) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * feat(shape_estimation): add bicycle shape corrector Signed-off-by: Kaan Çolak * style(pre-commit): autofix * feat(shape_estimation): add bicycle shape corrector Signed-off-by: Kaan Çolak --------- Signed-off-by: Kaan Çolak Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../corrector/bicycle_corrector.hpp | 40 +++++++++++++++++++ .../shape_estimation/corrector/corrector.hpp | 1 + .../shape_estimation/lib/shape_estimator.cpp | 2 + 3 files changed, 43 insertions(+) create mode 100644 perception/shape_estimation/include/shape_estimation/corrector/bicycle_corrector.hpp diff --git a/perception/shape_estimation/include/shape_estimation/corrector/bicycle_corrector.hpp b/perception/shape_estimation/include/shape_estimation/corrector/bicycle_corrector.hpp new file mode 100644 index 0000000000000..ec1a2b8a42973 --- /dev/null +++ b/perception/shape_estimation/include/shape_estimation/corrector/bicycle_corrector.hpp @@ -0,0 +1,40 @@ +// Copyright 2018 Autoware Foundation. 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. +// 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 SHAPE_ESTIMATION__CORRECTOR__BICYCLE_CORRECTOR_HPP_ +#define SHAPE_ESTIMATION__CORRECTOR__BICYCLE_CORRECTOR_HPP_ + +#include "shape_estimation/corrector/vehicle_corrector.hpp" +#include "utils.hpp" + +class BicycleCorrector : public VehicleCorrector +{ +public: + explicit BicycleCorrector(const bool use_reference_yaw = false) + : VehicleCorrector(use_reference_yaw) + { + corrector_utils::CorrectionBBParameters params; + params.min_width = 0.3; + params.max_width = 1.2; + params.default_width = (params.min_width + params.max_width) * 0.5; + params.min_length = 1.0; + params.max_length = 2.8; + params.default_length = (params.min_length + params.max_length) * 0.5; + setParams(params); + } + + ~BicycleCorrector() = default; +}; + +#endif // SHAPE_ESTIMATION__CORRECTOR__BICYCLE_CORRECTOR_HPP_ diff --git a/perception/shape_estimation/include/shape_estimation/corrector/corrector.hpp b/perception/shape_estimation/include/shape_estimation/corrector/corrector.hpp index d52bdc21f916f..e4efc17181e52 100644 --- a/perception/shape_estimation/include/shape_estimation/corrector/corrector.hpp +++ b/perception/shape_estimation/include/shape_estimation/corrector/corrector.hpp @@ -15,6 +15,7 @@ #ifndef SHAPE_ESTIMATION__CORRECTOR__CORRECTOR_HPP_ #define SHAPE_ESTIMATION__CORRECTOR__CORRECTOR_HPP_ +#include "shape_estimation/corrector/bicycle_corrector.hpp" #include "shape_estimation/corrector/bus_corrector.hpp" #include "shape_estimation/corrector/car_corrector.hpp" #include "shape_estimation/corrector/corrector_interface.hpp" diff --git a/perception/shape_estimation/lib/shape_estimator.cpp b/perception/shape_estimation/lib/shape_estimator.cpp index 9577b1e2d3197..e89eaac0a6db0 100644 --- a/perception/shape_estimation/lib/shape_estimator.cpp +++ b/perception/shape_estimation/lib/shape_estimator.cpp @@ -120,6 +120,8 @@ bool ShapeEstimator::applyCorrector( corrector_ptr.reset(new TruckCorrector(use_reference_yaw)); } else if (label == Label::TRAILER) { corrector_ptr.reset(new TrailerCorrector(use_reference_yaw)); + } else if (label == Label::MOTORCYCLE || label == Label::BICYCLE) { + corrector_ptr.reset(new BicycleCorrector(use_reference_yaw)); } else { corrector_ptr.reset(new NoCorrector); } From d4d632a26dfbc9912d21c8142494e0611d971199 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 14 Dec 2023 14:05:50 +0900 Subject: [PATCH 52/87] feat(simple_planning_simulator): add mesurent_steer_bias (#5868) * feat(simple_planning_simulator): add mesurent_steer_bias Signed-off-by: kosuke55 * style(pre-commit): autofix --------- Signed-off-by: kosuke55 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- simulator/simple_planning_simulator/README.md | 23 ++++++++++--------- .../simple_planning_simulator_core.hpp | 3 +++ .../simple_planning_simulator_core.cpp | 4 ++++ 3 files changed, 19 insertions(+), 11 deletions(-) diff --git a/simulator/simple_planning_simulator/README.md b/simulator/simple_planning_simulator/README.md index b441f9f903d0d..ed2b06ee1f44d 100644 --- a/simulator/simple_planning_simulator/README.md +++ b/simulator/simple_planning_simulator/README.md @@ -40,17 +40,18 @@ The purpose of this simulator is for the integration test of planning and contro ### Common Parameters -| Name | Type | Description | Default value | -| :-------------------- | :----- | :----------------------------------------------------------------------------------------------------------------------------------------- | :------------------- | -| simulated_frame_id | string | set to the child_frame_id in output tf | "base_link" | -| origin_frame_id | string | set to the frame_id in output tf | "odom" | -| initialize_source | string | If "ORIGIN", the initial pose is set at (0,0,0). If "INITIAL_POSE_TOPIC", node will wait until the `input/initialpose` topic is published. | "INITIAL_POSE_TOPIC" | -| add_measurement_noise | bool | If true, the Gaussian noise is added to the simulated results. | true | -| pos_noise_stddev | double | Standard deviation for position noise | 0.01 | -| rpy_noise_stddev | double | Standard deviation for Euler angle noise | 0.0001 | -| vel_noise_stddev | double | Standard deviation for longitudinal velocity noise | 0.0 | -| angvel_noise_stddev | double | Standard deviation for angular velocity noise | 0.0 | -| steer_noise_stddev | double | Standard deviation for steering angle noise | 0.0001 | +| Name | Type | Description | Default value | +| :--------------------- | :----- | :----------------------------------------------------------------------------------------------------------------------------------------- | :------------------- | +| simulated_frame_id | string | set to the child_frame_id in output tf | "base_link" | +| origin_frame_id | string | set to the frame_id in output tf | "odom" | +| initialize_source | string | If "ORIGIN", the initial pose is set at (0,0,0). If "INITIAL_POSE_TOPIC", node will wait until the `input/initialpose` topic is published. | "INITIAL_POSE_TOPIC" | +| add_measurement_noise | bool | If true, the Gaussian noise is added to the simulated results. | true | +| pos_noise_stddev | double | Standard deviation for position noise | 0.01 | +| rpy_noise_stddev | double | Standard deviation for Euler angle noise | 0.0001 | +| vel_noise_stddev | double | Standard deviation for longitudinal velocity noise | 0.0 | +| angvel_noise_stddev | double | Standard deviation for angular velocity noise | 0.0 | +| steer_noise_stddev | double | Standard deviation for steering angle noise | 0.0001 | +| measurement_steer_bias | double | Measurement bias for steering angle | 0.0 | ### Vehicle Model Parameters diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp index 38f689c124439..d096130e65f05 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp @@ -195,6 +195,9 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node bool is_initialized_ = false; //!< @brief flag to check the initial position is set bool add_measurement_noise_ = false; //!< @brief flag to add measurement noise + /* measurement bias */ + double measurement_steer_bias_ = 0.0; //!< @brief measurement bias for steering measurement + DeltaTime delta_time_{}; //!< @brief to calculate delta time MeasurementNoiseGenerator measurement_noise_{}; //!< @brief for measurement noise diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index 9a0ea6a6c3659..8de5be9d71503 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -102,6 +102,7 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt simulated_frame_id_ = declare_parameter("simulated_frame_id", "base_link"); origin_frame_id_ = declare_parameter("origin_frame_id", "odom"); add_measurement_noise_ = declare_parameter("add_measurement_noise", false); + measurement_steer_bias_ = declare_parameter("measurement_steer_bias", 0.0); simulate_motion_ = declare_parameter("initial_engage_state"); enable_road_slope_simulation_ = declare_parameter("enable_road_slope_simulation", false); @@ -381,6 +382,9 @@ void SimplePlanningSimulator::on_timer() add_measurement_noise(current_odometry_, current_velocity_, current_steer_); } + // add measurement bias + current_steer_.steering_tire_angle += measurement_steer_bias_; + // add estimate covariance { using COV_IDX = tier4_autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; From 4fc8a4e75dbc21bf5381edfffb028a69db7c0fc3 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 14 Dec 2023 16:00:11 +0900 Subject: [PATCH 53/87] feat(diagnostic_graph_aggregator): rename system_diagnostic_graph package (#5827) Signed-off-by: Takagi, Isamu --- .../CMakeLists.txt | 24 +- .../README.md | 49 +- .../config/default.param.yaml | 0 .../doc/format/and.md | 0 .../doc/format/diag.md | 10 + .../doc/format/graph-file.md | 0 .../doc/format/node.md | 0 .../doc/format/or.md | 0 .../doc/format/path.md | 0 .../doc/format/unit.md | 0 .../doc/message.drawio.svg | 677 ++++++++++++++++++ .../doc/overview.drawio.svg | 0 .../example/example.launch.xml | 7 + .../example/example_0.yaml | 4 +- .../example/example_1.yaml | 0 .../example/example_2.yaml | 0 .../example/example_diags.py | 0 .../diagnostic_graph_aggregator.launch.xml | 8 + .../package.xml | 4 +- .../src/common/graph}/config.cpp | 4 +- .../src/common/graph}/config.hpp | 10 +- .../src/common/graph}/debug.cpp | 4 +- .../src/common/graph}/debug.hpp | 10 +- .../src/common/graph}/error.hpp | 10 +- .../src/common/graph}/graph.cpp | 4 +- .../src/common/graph}/graph.hpp | 10 +- .../src/common/graph}/types.hpp | 10 +- .../src/common/graph}/units.cpp | 4 +- .../src/common/graph}/units.hpp | 10 +- .../src/node/aggregator.cpp} | 10 +- .../src/node/aggregator.hpp} | 16 +- .../src/node/converter.cpp} | 10 +- .../src/node/converter.hpp} | 12 +- .../src/node/plugin}/modes.cpp | 10 +- .../src/node/plugin}/modes.hpp | 12 +- .../src/tool/tool.cpp} | 12 +- .../test/files/test1/field-not-found.yaml | 0 .../test/files/test1/file-not-found.yaml | 0 .../test/files/test1/graph-circulation.yaml | 0 .../test/files/test1/invalid-dict-type.yaml | 0 .../test/files/test1/invalid-list-type.yaml | 0 .../test/files/test1/path-conflict.yaml | 0 .../test/files/test1/path-not-found.yaml | 0 .../test/files/test1/unknown-node-type.yaml | 0 .../files/test1/unknown-substitution.yaml | 0 .../test/files/test2/and.yaml | 0 .../test/files/test2/or.yaml | 0 .../test/files/test2/warn-to-error.yaml | 0 .../test/files/test2/warn-to-ok.yaml | 0 .../test/src/test1.cpp | 6 +- .../test/src/test2.cpp | 6 +- .../test/src/utils.cpp | 0 .../test/src/utils.hpp | 0 .../doc/format/diag.md | 11 - .../example/example.launch.xml | 6 - .../launch/system_diagnostic_graph.launch.xml | 9 - 56 files changed, 835 insertions(+), 144 deletions(-) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/CMakeLists.txt (56%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/README.md (51%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/config/default.param.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/doc/format/and.md (100%) create mode 100644 system/diagnostic_graph_aggregator/doc/format/diag.md rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/doc/format/graph-file.md (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/doc/format/node.md (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/doc/format/or.md (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/doc/format/path.md (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/doc/format/unit.md (100%) create mode 100644 system/diagnostic_graph_aggregator/doc/message.drawio.svg rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/doc/overview.drawio.svg (100%) create mode 100644 system/diagnostic_graph_aggregator/example/example.launch.xml rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/example/example_0.yaml (83%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/example/example_1.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/example/example_2.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/example/example_diags.py (100%) create mode 100644 system/diagnostic_graph_aggregator/launch/diagnostic_graph_aggregator.launch.xml rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/package.xml (87%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/config.cpp (99%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/config.hpp (94%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/debug.cpp (96%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/debug.hpp (79%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/error.hpp (87%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/graph.cpp (98%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/graph.hpp (86%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/types.hpp (86%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/units.cpp (98%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/common/graph}/units.hpp (95%) rename system/{system_diagnostic_graph/src/main.cpp => diagnostic_graph_aggregator/src/node/aggregator.cpp} (90%) rename system/{system_diagnostic_graph/src/main.hpp => diagnostic_graph_aggregator/src/node/aggregator.hpp} (80%) rename system/{system_diagnostic_graph/src/tool.cpp => diagnostic_graph_aggregator/src/node/converter.cpp} (90%) rename system/{system_diagnostic_graph/src/tool.hpp => diagnostic_graph_aggregator/src/node/converter.hpp} (81%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/node/plugin}/modes.cpp (93%) rename system/{system_diagnostic_graph/src/core => diagnostic_graph_aggregator/src/node/plugin}/modes.hpp (85%) rename system/{system_diagnostic_graph/src/tool/main.cpp => diagnostic_graph_aggregator/src/tool/tool.cpp} (94%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/field-not-found.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/file-not-found.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/graph-circulation.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/invalid-dict-type.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/invalid-list-type.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/path-conflict.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/path-not-found.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/unknown-node-type.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test1/unknown-substitution.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test2/and.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test2/or.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test2/warn-to-error.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/files/test2/warn-to-ok.yaml (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/src/test1.cpp (94%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/src/test2.cpp (97%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/src/utils.cpp (100%) rename system/{system_diagnostic_graph => diagnostic_graph_aggregator}/test/src/utils.hpp (100%) delete mode 100644 system/system_diagnostic_graph/doc/format/diag.md delete mode 100644 system/system_diagnostic_graph/example/example.launch.xml delete mode 100644 system/system_diagnostic_graph/launch/system_diagnostic_graph.launch.xml diff --git a/system/system_diagnostic_graph/CMakeLists.txt b/system/diagnostic_graph_aggregator/CMakeLists.txt similarity index 56% rename from system/system_diagnostic_graph/CMakeLists.txt rename to system/diagnostic_graph_aggregator/CMakeLists.txt index be0fc19188a0b..188b1509dfca0 100644 --- a/system/system_diagnostic_graph/CMakeLists.txt +++ b/system/diagnostic_graph_aggregator/CMakeLists.txt @@ -1,29 +1,31 @@ cmake_minimum_required(VERSION 3.14) -project(system_diagnostic_graph) +project(diagnostic_graph_aggregator) find_package(autoware_cmake REQUIRED) autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED - src/core/config.cpp - src/core/debug.cpp - src/core/graph.cpp - src/core/units.cpp - src/core/modes.cpp + src/common/graph/config.cpp + src/common/graph/debug.cpp + src/common/graph/graph.cpp + src/common/graph/units.cpp ) ament_auto_add_executable(aggregator - src/main.cpp + src/node/aggregator.cpp + src/node/plugin/modes.cpp ) +target_include_directories(aggregator PRIVATE src/common) ament_auto_add_executable(converter - src/tool.cpp + src/node/converter.cpp ) +target_include_directories(converter PRIVATE src/common) ament_auto_add_executable(tool - src/tool/main.cpp + src/tool/tool.cpp ) -target_include_directories(tool PRIVATE src/core) +target_include_directories(tool PRIVATE src/common) if(BUILD_TESTING) get_filename_component(RESOURCE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/test/files ABSOLUTE) @@ -33,7 +35,7 @@ if(BUILD_TESTING) test/src/utils.cpp ) target_compile_definitions(gtest_${PROJECT_NAME} PRIVATE TEST_RESOURCE_PATH="${RESOURCE_PATH}") - target_include_directories(gtest_${PROJECT_NAME} PRIVATE src) + target_include_directories(gtest_${PROJECT_NAME} PRIVATE src/common) endif() ament_auto_package(INSTALL_TO_SHARE config example launch) diff --git a/system/system_diagnostic_graph/README.md b/system/diagnostic_graph_aggregator/README.md similarity index 51% rename from system/system_diagnostic_graph/README.md rename to system/diagnostic_graph_aggregator/README.md index df22121a778fb..4dc44feaafc33 100644 --- a/system/system_diagnostic_graph/README.md +++ b/system/diagnostic_graph_aggregator/README.md @@ -1,13 +1,23 @@ -# System diagnostic graph +# diagnostic_graph_aggregator ## Overview -The system diagnostic graph node subscribes to diagnostic array and publishes aggregated diagnostic graph. +The diagnostic graph aggregator node subscribes to diagnostic array and publishes aggregated diagnostic graph. As shown in the diagram below, this node introduces extra diagnostic status for intermediate functional unit. Diagnostic status dependencies will be directed acyclic graph (DAG). ![overview](./doc/overview.drawio.svg) +## Diagnostics graph message + +The diagnostics graph that this node outputs is a combination of diagnostic status and connections between them. +This graph consists of an array of diagnostic nodes, and each node has a status and links. +This link contains an index indicating the position of the node in the graph. +Therefore, the graph can be reconstructed from the array of nodes using links. +The following is an example of a message representing the graph in the overview section. + +![message](./doc/message.drawio.svg) + ## Operation mode availability For MRM, this node publishes the status of the top-level functional units in the dedicated message. @@ -22,7 +32,7 @@ This feature breaks the generality of the graph and may be changed to a plugin o - /autoware/operation/comfortable-stop - /autoware/operation/pull-over -## Interface +## Interfaces | Interface Type | Interface Name | Data Type | Description | | -------------- | ------------------------------------- | ------------------------------------------------- | ------------------ | @@ -32,12 +42,24 @@ This feature breaks the generality of the graph and may be changed to a plugin o ## Parameters -| Parameter Name | Data Type | Description | -| ----------------- | --------- | ------------------------------------------ | -| `graph_file` | `string` | Path of the config file. | -| `rate` | `double` | Rate of aggregation and topic publication. | -| `input_qos_depth` | `uint` | QoS depth of input array topic. | -| `graph_qos_depth` | `uint` | QoS depth of output graph topic. | +| Parameter Name | Data Type | Description | +| --------------------------------- | --------- | ------------------------------------------ | +| `graph_file` | `string` | Path of the config file. | +| `rate` | `double` | Rate of aggregation and topic publication. | +| `input_qos_depth` | `uint` | QoS depth of input array topic. | +| `graph_qos_depth` | `uint` | QoS depth of output graph topic. | +| `use_operation_mode_availability` | `bool` | Use operation mode availability publisher. | +| `use_debug_mode` | `bool` | Use debug output to stdout. | + +## Examples + +- [example_0.yaml](./example/example_0.yaml) +- [example_1.yaml](./example/example_1.yaml) +- [example_2.yaml](./example/example_2.yaml) + +```bash +ros2 launch diagnostic_graph_aggregator example.launch.xml +``` ## Graph file format @@ -48,12 +70,3 @@ This feature breaks the generality of the graph and may be changed to a plugin o - [Unit](./doc/format/unit.md) - [And](./doc/format/and.md) - [Or](./doc/format/or.md) - -## Example - -- [example1.yaml](./example/example1.yaml) -- [example2.yaml](./example/example2.yaml) - -```bash -ros2 launch system_diagnostic_graph example.launch.xml -``` diff --git a/system/system_diagnostic_graph/config/default.param.yaml b/system/diagnostic_graph_aggregator/config/default.param.yaml similarity index 100% rename from system/system_diagnostic_graph/config/default.param.yaml rename to system/diagnostic_graph_aggregator/config/default.param.yaml diff --git a/system/system_diagnostic_graph/doc/format/and.md b/system/diagnostic_graph_aggregator/doc/format/and.md similarity index 100% rename from system/system_diagnostic_graph/doc/format/and.md rename to system/diagnostic_graph_aggregator/doc/format/and.md diff --git a/system/diagnostic_graph_aggregator/doc/format/diag.md b/system/diagnostic_graph_aggregator/doc/format/diag.md new file mode 100644 index 0000000000000..04e850129cbbf --- /dev/null +++ b/system/diagnostic_graph_aggregator/doc/format/diag.md @@ -0,0 +1,10 @@ +# Diag + +Diag is a node that refers to a source diagnostics. + +## Format + +| Name | Type | Required | Description | +| ---- | ------ | -------- | -------------------------------------- | +| type | string | yes | Specify `diag` when using this object. | +| diag | string | yes | Name of diagnostic status. | diff --git a/system/system_diagnostic_graph/doc/format/graph-file.md b/system/diagnostic_graph_aggregator/doc/format/graph-file.md similarity index 100% rename from system/system_diagnostic_graph/doc/format/graph-file.md rename to system/diagnostic_graph_aggregator/doc/format/graph-file.md diff --git a/system/system_diagnostic_graph/doc/format/node.md b/system/diagnostic_graph_aggregator/doc/format/node.md similarity index 100% rename from system/system_diagnostic_graph/doc/format/node.md rename to system/diagnostic_graph_aggregator/doc/format/node.md diff --git a/system/system_diagnostic_graph/doc/format/or.md b/system/diagnostic_graph_aggregator/doc/format/or.md similarity index 100% rename from system/system_diagnostic_graph/doc/format/or.md rename to system/diagnostic_graph_aggregator/doc/format/or.md diff --git a/system/system_diagnostic_graph/doc/format/path.md b/system/diagnostic_graph_aggregator/doc/format/path.md similarity index 100% rename from system/system_diagnostic_graph/doc/format/path.md rename to system/diagnostic_graph_aggregator/doc/format/path.md diff --git a/system/system_diagnostic_graph/doc/format/unit.md b/system/diagnostic_graph_aggregator/doc/format/unit.md similarity index 100% rename from system/system_diagnostic_graph/doc/format/unit.md rename to system/diagnostic_graph_aggregator/doc/format/unit.md diff --git a/system/diagnostic_graph_aggregator/doc/message.drawio.svg b/system/diagnostic_graph_aggregator/doc/message.drawio.svg new file mode 100644 index 0000000000000..aef836dccf235 --- /dev/null +++ b/system/diagnostic_graph_aggregator/doc/message.drawio.svg @@ -0,0 +1,677 @@ + + + + + + + +
+
+
+ Top LiDAR +
+
+
+
+ Top LiDAR +
+
+ + + + +
+
+
+ Front LiDAR +
+
+
+
+ Front LiDAR +
+
+ + + + +
+
+
+ obstacle detection +
+
+
+
+ obstacle detection +
+
+ + + + +
+
+
+ pose estimation +
+
+
+
+ pose estimation +
+
+ + + + +
+
+
+ autonomous +
+
+
+
+ autonomous +
+
+ + + + +
+
+
+ remote +
+
+
+
+ remote +
+
+ + + + +
+
+
+ remote command +
+
+
+
+ remote command +
+
+ + + + +
+
+
+ local +
+
+
+
+ local +
+
+ + + + +
+
+
+ joystick command +
+
+
+
+ joystick command +
+
+ + + + +
+
+
+ stop +
+
+
+
+ stop +
+
+ + + + +
+
+
+ Front radar +
+
+
+
+ Front radar +
+
+ + + + +
+
+
+ MRM +
+
+
+
+ MRM +
+
+ + + + +
+
+
+ index +
+
+
+
+ index +
+
+ + + + +
+
+
+ status +
+
+
+
+ status +
+
+ + + + +
+
+
+ 0 +
+
+
+
+ 0 +
+
+ + + + +
+
+
+ 1 +
+
+
+
+ 1 +
+
+ + + + +
+
+
+ 2 +
+
+
+
+ 2 +
+
+ + + + +
+
+
+ 3 +
+
+
+
+ 3 +
+
+ + + + +
+
+
+ 4 +
+
+
+
+ 4 +
+
+ + + + +
+
+
+ 5 +
+
+
+
+ 5 +
+
+ + + + +
+
+
+ 6 +
+
+
+
+ 6 +
+
+ + + + +
+
+
+ 7 +
+
+
+
+ 7 +
+
+ + + + +
+
+
+ 8 +
+
+
+
+ 8 +
+
+ + + + +
+
+
+ 9 +
+
+
+
+ 9 +
+
+ + + + +
+
+
+ 10 +
+
+
+
+ 10 +
+
+ + + + +
+
+
+ 11 +
+
+
+
+ 11 +
+
+ + + + +
+
+
+ links +
+
+
+
+ links +
+
+ + + + +
+
+
+ - +
+
+
+
+ - +
+
+ + + + +
+
+
+ - +
+
+
+
+ - +
+
+ + + + +
+
+
+ 10, 11 +
+
+
+
+ 10, 11 +
+
+ + + + +
+
+
+ 9 +
+
+
+
+ 9 +
+
+ + + + +
+
+
+ 5, 6 +
+
+
+
+ 5, 6 +
+
+ + + + +
+
+
+ 8 +
+
+
+
+ 8 +
+
+ + + + +
+
+
+ - +
+
+
+
+ - +
+
+ + + + +
+
+
+ 7 +
+
+
+
+ 7 +
+
+ + + + +
+
+
+ - +
+
+
+
+ - +
+
+ + + + +
+
+
+ - +
+
+
+
+ - +
+
+ + + + +
+
+
+ - +
+
+
+
+ - +
+
+ + + + +
+
+
+ - +
+
+
+
+ - +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/system/system_diagnostic_graph/doc/overview.drawio.svg b/system/diagnostic_graph_aggregator/doc/overview.drawio.svg similarity index 100% rename from system/system_diagnostic_graph/doc/overview.drawio.svg rename to system/diagnostic_graph_aggregator/doc/overview.drawio.svg diff --git a/system/diagnostic_graph_aggregator/example/example.launch.xml b/system/diagnostic_graph_aggregator/example/example.launch.xml new file mode 100644 index 0000000000000..71e59a1833d6e --- /dev/null +++ b/system/diagnostic_graph_aggregator/example/example.launch.xml @@ -0,0 +1,7 @@ + + + + + + + diff --git a/system/system_diagnostic_graph/example/example_0.yaml b/system/diagnostic_graph_aggregator/example/example_0.yaml similarity index 83% rename from system/system_diagnostic_graph/example/example_0.yaml rename to system/diagnostic_graph_aggregator/example/example_0.yaml index ed92259b50721..7b01883723c76 100644 --- a/system/system_diagnostic_graph/example/example_0.yaml +++ b/system/diagnostic_graph_aggregator/example/example_0.yaml @@ -1,6 +1,6 @@ files: - - { path: $(find-pkg-share system_diagnostic_graph)/example/example_1.yaml } - - { path: $(find-pkg-share system_diagnostic_graph)/example/example_2.yaml } + - { path: $(find-pkg-share diagnostic_graph_aggregator)/example/example_1.yaml } + - { path: $(find-pkg-share diagnostic_graph_aggregator)/example/example_2.yaml } nodes: - path: /autoware/modes/stop diff --git a/system/system_diagnostic_graph/example/example_1.yaml b/system/diagnostic_graph_aggregator/example/example_1.yaml similarity index 100% rename from system/system_diagnostic_graph/example/example_1.yaml rename to system/diagnostic_graph_aggregator/example/example_1.yaml diff --git a/system/system_diagnostic_graph/example/example_2.yaml b/system/diagnostic_graph_aggregator/example/example_2.yaml similarity index 100% rename from system/system_diagnostic_graph/example/example_2.yaml rename to system/diagnostic_graph_aggregator/example/example_2.yaml diff --git a/system/system_diagnostic_graph/example/example_diags.py b/system/diagnostic_graph_aggregator/example/example_diags.py similarity index 100% rename from system/system_diagnostic_graph/example/example_diags.py rename to system/diagnostic_graph_aggregator/example/example_diags.py diff --git a/system/diagnostic_graph_aggregator/launch/diagnostic_graph_aggregator.launch.xml b/system/diagnostic_graph_aggregator/launch/diagnostic_graph_aggregator.launch.xml new file mode 100644 index 0000000000000..272901a3f8045 --- /dev/null +++ b/system/diagnostic_graph_aggregator/launch/diagnostic_graph_aggregator.launch.xml @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/system/system_diagnostic_graph/package.xml b/system/diagnostic_graph_aggregator/package.xml similarity index 87% rename from system/system_diagnostic_graph/package.xml rename to system/diagnostic_graph_aggregator/package.xml index 7855edcde9c62..2a9efad2c0d6e 100644 --- a/system/system_diagnostic_graph/package.xml +++ b/system/diagnostic_graph_aggregator/package.xml @@ -1,9 +1,9 @@ - system_diagnostic_graph + diagnostic_graph_aggregator 0.1.0 - The system_diagnostic_graph package + The diagnostic_graph_aggregator package Takagi, Isamu Apache License 2.0 diff --git a/system/system_diagnostic_graph/src/core/config.cpp b/system/diagnostic_graph_aggregator/src/common/graph/config.cpp similarity index 99% rename from system/system_diagnostic_graph/src/core/config.cpp rename to system/diagnostic_graph_aggregator/src/common/graph/config.cpp index 4a32398a1b08f..39044d1c82bf9 100644 --- a/system/system_diagnostic_graph/src/core/config.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/config.cpp @@ -30,7 +30,7 @@ // DEBUG #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { template @@ -351,4 +351,4 @@ RootConfig load_root_config(const std::string & path) return load_root_config(root); } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator diff --git a/system/system_diagnostic_graph/src/core/config.hpp b/system/diagnostic_graph_aggregator/src/common/graph/config.hpp similarity index 94% rename from system/system_diagnostic_graph/src/core/config.hpp rename to system/diagnostic_graph_aggregator/src/common/graph/config.hpp index d7cdd0ec3c5f7..40f16235ed5d6 100644 --- a/system/system_diagnostic_graph/src/core/config.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/config.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__CONFIG_HPP_ -#define CORE__CONFIG_HPP_ +#ifndef COMMON__GRAPH__CONFIG_HPP_ +#define COMMON__GRAPH__CONFIG_HPP_ #include @@ -23,7 +23,7 @@ #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { struct ConfigData @@ -124,6 +124,6 @@ T error(const std::string & text, const std::string & value) RootConfig load_root_config(const std::string & path); -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // CORE__CONFIG_HPP_ +#endif // COMMON__GRAPH__CONFIG_HPP_ diff --git a/system/system_diagnostic_graph/src/core/debug.cpp b/system/diagnostic_graph_aggregator/src/common/graph/debug.cpp similarity index 96% rename from system/system_diagnostic_graph/src/core/debug.cpp rename to system/diagnostic_graph_aggregator/src/common/graph/debug.cpp index e2771f08f9f1e..8f2b741edd805 100644 --- a/system/system_diagnostic_graph/src/core/debug.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/debug.cpp @@ -23,7 +23,7 @@ #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { std::string get_level_text(DiagnosticLevel level) @@ -72,4 +72,4 @@ void Graph::debug() } } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator diff --git a/system/system_diagnostic_graph/src/core/debug.hpp b/system/diagnostic_graph_aggregator/src/common/graph/debug.hpp similarity index 79% rename from system/system_diagnostic_graph/src/core/debug.hpp rename to system/diagnostic_graph_aggregator/src/common/graph/debug.hpp index 297356cd36bab..69a0eeb2c8023 100644 --- a/system/system_diagnostic_graph/src/core/debug.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/debug.hpp @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__DEBUG_HPP_ -#define CORE__DEBUG_HPP_ +#ifndef COMMON__GRAPH__DEBUG_HPP_ +#define COMMON__GRAPH__DEBUG_HPP_ #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { constexpr size_t diag_debug_size = 4; using DiagDebugData = std::array; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // CORE__DEBUG_HPP_ +#endif // COMMON__GRAPH__DEBUG_HPP_ diff --git a/system/system_diagnostic_graph/src/core/error.hpp b/system/diagnostic_graph_aggregator/src/common/graph/error.hpp similarity index 87% rename from system/system_diagnostic_graph/src/core/error.hpp rename to system/diagnostic_graph_aggregator/src/common/graph/error.hpp index 7e110654bf475..dadfab450c783 100644 --- a/system/system_diagnostic_graph/src/core/error.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/error.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__ERROR_HPP_ -#define CORE__ERROR_HPP_ +#ifndef COMMON__GRAPH__ERROR_HPP_ +#define COMMON__GRAPH__ERROR_HPP_ #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { struct Exception : public std::runtime_error @@ -65,6 +65,6 @@ class GraphStructure : public Exception using Exception::Exception; }; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // CORE__ERROR_HPP_ +#endif // COMMON__GRAPH__ERROR_HPP_ diff --git a/system/system_diagnostic_graph/src/core/graph.cpp b/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp similarity index 98% rename from system/system_diagnostic_graph/src/core/graph.cpp rename to system/diagnostic_graph_aggregator/src/common/graph/graph.cpp index 5ad7df09de1d1..5d7c11879a9cc 100644 --- a/system/system_diagnostic_graph/src/core/graph.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp @@ -28,7 +28,7 @@ // DEBUG #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { BaseUnit::UniquePtrList topological_sort(BaseUnit::UniquePtrList && input) @@ -223,4 +223,4 @@ std::vector Graph::nodes() const return result; } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator diff --git a/system/system_diagnostic_graph/src/core/graph.hpp b/system/diagnostic_graph_aggregator/src/common/graph/graph.hpp similarity index 86% rename from system/system_diagnostic_graph/src/core/graph.hpp rename to system/diagnostic_graph_aggregator/src/common/graph/graph.hpp index 7b0a5bf563106..8c29a303814b8 100644 --- a/system/system_diagnostic_graph/src/core/graph.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/graph.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__GRAPH_HPP_ -#define CORE__GRAPH_HPP_ +#ifndef COMMON__GRAPH__GRAPH_HPP_ +#define COMMON__GRAPH__GRAPH_HPP_ #include "types.hpp" @@ -25,7 +25,7 @@ #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { class Graph final @@ -47,6 +47,6 @@ class Graph final std::unordered_map unknowns_; }; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // CORE__GRAPH_HPP_ +#endif // COMMON__GRAPH__GRAPH_HPP_ diff --git a/system/system_diagnostic_graph/src/core/types.hpp b/system/diagnostic_graph_aggregator/src/common/graph/types.hpp similarity index 86% rename from system/system_diagnostic_graph/src/core/types.hpp rename to system/diagnostic_graph_aggregator/src/common/graph/types.hpp index c0b901d1e4511..693094914db1d 100644 --- a/system/system_diagnostic_graph/src/core/types.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/types.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__TYPES_HPP_ -#define CORE__TYPES_HPP_ +#ifndef COMMON__GRAPH__TYPES_HPP_ +#define COMMON__GRAPH__TYPES_HPP_ #include #include @@ -21,7 +21,7 @@ #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { using diagnostic_msgs::msg::DiagnosticArray; @@ -34,6 +34,6 @@ using DiagnosticLevel = DiagnosticStatus::_level_type; class BaseUnit; class DiagUnit; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // CORE__TYPES_HPP_ +#endif // COMMON__GRAPH__TYPES_HPP_ diff --git a/system/system_diagnostic_graph/src/core/units.cpp b/system/diagnostic_graph_aggregator/src/common/graph/units.cpp similarity index 98% rename from system/system_diagnostic_graph/src/core/units.cpp rename to system/diagnostic_graph_aggregator/src/common/graph/units.cpp index cb830c8d1df51..6048cae85e633 100644 --- a/system/system_diagnostic_graph/src/core/units.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/units.cpp @@ -21,7 +21,7 @@ #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { using LinkList = std::vector>; @@ -178,4 +178,4 @@ void DebugUnit::update(const rclcpp::Time &) { } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator diff --git a/system/system_diagnostic_graph/src/core/units.hpp b/system/diagnostic_graph_aggregator/src/common/graph/units.hpp similarity index 95% rename from system/system_diagnostic_graph/src/core/units.hpp rename to system/diagnostic_graph_aggregator/src/common/graph/units.hpp index 2b94b5f83a216..dce223b30f728 100644 --- a/system/system_diagnostic_graph/src/core/units.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/units.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__UNITS_HPP_ -#define CORE__UNITS_HPP_ +#ifndef COMMON__GRAPH__UNITS_HPP_ +#define COMMON__GRAPH__UNITS_HPP_ #include "config.hpp" #include "types.hpp" @@ -27,7 +27,7 @@ #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { class BaseUnit @@ -131,6 +131,6 @@ class DebugUnit : public BaseUnit std::string type() const override { return "const"; } }; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // CORE__UNITS_HPP_ +#endif // COMMON__GRAPH__UNITS_HPP_ diff --git a/system/system_diagnostic_graph/src/main.cpp b/system/diagnostic_graph_aggregator/src/node/aggregator.cpp similarity index 90% rename from system/system_diagnostic_graph/src/main.cpp rename to system/diagnostic_graph_aggregator/src/node/aggregator.cpp index 7393d9fb086f6..48f489c186bdb 100644 --- a/system/system_diagnostic_graph/src/main.cpp +++ b/system/diagnostic_graph_aggregator/src/node/aggregator.cpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "main.hpp" +#include "aggregator.hpp" #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { -MainNode::MainNode() : Node("system_diagnostic_graph_aggregator") +MainNode::MainNode() : Node("diagnostic_graph_aggregator_aggregator") { // Init diagnostics graph. { @@ -69,11 +69,11 @@ void MainNode::on_diag(const DiagnosticArray::ConstSharedPtr msg) graph_.callback(now(), *msg); } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator int main(int argc, char ** argv) { - using system_diagnostic_graph::MainNode; + using diagnostic_graph_aggregator::MainNode; rclcpp::init(argc, argv); rclcpp::executors::SingleThreadedExecutor executor; auto node = std::make_shared(); diff --git a/system/system_diagnostic_graph/src/main.hpp b/system/diagnostic_graph_aggregator/src/node/aggregator.hpp similarity index 80% rename from system/system_diagnostic_graph/src/main.hpp rename to system/diagnostic_graph_aggregator/src/node/aggregator.hpp index 495c51218cabc..dd64809e939cc 100644 --- a/system/system_diagnostic_graph/src/main.hpp +++ b/system/diagnostic_graph_aggregator/src/node/aggregator.hpp @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MAIN_HPP_ -#define MAIN_HPP_ +#ifndef NODE__AGGREGATOR_HPP_ +#define NODE__AGGREGATOR_HPP_ -#include "core/graph.hpp" -#include "core/modes.hpp" -#include "core/types.hpp" +#include "graph/graph.hpp" +#include "graph/types.hpp" +#include "plugin/modes.hpp" #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { class MainNode : public rclcpp::Node @@ -44,6 +44,6 @@ class MainNode : public rclcpp::Node bool debug_; }; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // MAIN_HPP_ +#endif // NODE__AGGREGATOR_HPP_ diff --git a/system/system_diagnostic_graph/src/tool.cpp b/system/diagnostic_graph_aggregator/src/node/converter.cpp similarity index 90% rename from system/system_diagnostic_graph/src/tool.cpp rename to system/diagnostic_graph_aggregator/src/node/converter.cpp index fda2c88a691a2..89acfce31a5ab 100644 --- a/system/system_diagnostic_graph/src/tool.cpp +++ b/system/diagnostic_graph_aggregator/src/node/converter.cpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "tool.hpp" +#include "converter.hpp" #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { std::string level_to_string(DiagnosticLevel level) @@ -35,7 +35,7 @@ std::string level_to_string(DiagnosticLevel level) return "UNKNOWN"; } -ToolNode::ToolNode() : Node("system_diagnostic_graph_converter") +ToolNode::ToolNode() : Node("diagnostic_graph_aggregator_converter") { using std::placeholders::_1; const auto qos_graph = rclcpp::QoS(1); @@ -66,11 +66,11 @@ void ToolNode::on_graph(const DiagnosticGraph::ConstSharedPtr msg) pub_array_->publish(message); } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator int main(int argc, char ** argv) { - using system_diagnostic_graph::ToolNode; + using diagnostic_graph_aggregator::ToolNode; rclcpp::init(argc, argv); rclcpp::executors::SingleThreadedExecutor executor; auto node = std::make_shared(); diff --git a/system/system_diagnostic_graph/src/tool.hpp b/system/diagnostic_graph_aggregator/src/node/converter.hpp similarity index 81% rename from system/system_diagnostic_graph/src/tool.hpp rename to system/diagnostic_graph_aggregator/src/node/converter.hpp index 5ad19b8460c4b..7a3e8e4e58033 100644 --- a/system/system_diagnostic_graph/src/tool.hpp +++ b/system/diagnostic_graph_aggregator/src/node/converter.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef TOOL_HPP_ -#define TOOL_HPP_ +#ifndef NODE__CONVERTER_HPP_ +#define NODE__CONVERTER_HPP_ -#include "core/types.hpp" +#include "graph/types.hpp" #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { class ToolNode : public rclcpp::Node @@ -33,6 +33,6 @@ class ToolNode : public rclcpp::Node void on_graph(const DiagnosticGraph::ConstSharedPtr msg); }; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // TOOL_HPP_ +#endif // NODE__CONVERTER_HPP_ diff --git a/system/system_diagnostic_graph/src/core/modes.cpp b/system/diagnostic_graph_aggregator/src/node/plugin/modes.cpp similarity index 93% rename from system/system_diagnostic_graph/src/core/modes.cpp rename to system/diagnostic_graph_aggregator/src/node/plugin/modes.cpp index 1488387811d67..c73de86cba439 100644 --- a/system/system_diagnostic_graph/src/core/modes.cpp +++ b/system/diagnostic_graph_aggregator/src/node/plugin/modes.cpp @@ -14,15 +14,15 @@ #include "modes.hpp" -#include "config.hpp" -#include "error.hpp" -#include "units.hpp" +#include "graph/config.hpp" +#include "graph/error.hpp" +#include "graph/units.hpp" #include #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { OperationModes::OperationModes(rclcpp::Node & node, const std::vector & graph) @@ -73,4 +73,4 @@ void OperationModes::update(const rclcpp::Time & stamp) const pub_->publish(message); } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator diff --git a/system/system_diagnostic_graph/src/core/modes.hpp b/system/diagnostic_graph_aggregator/src/node/plugin/modes.hpp similarity index 85% rename from system/system_diagnostic_graph/src/core/modes.hpp rename to system/diagnostic_graph_aggregator/src/node/plugin/modes.hpp index 47a31b8d2a152..1ed22c7d9d058 100644 --- a/system/system_diagnostic_graph/src/core/modes.hpp +++ b/system/diagnostic_graph_aggregator/src/node/plugin/modes.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CORE__MODES_HPP_ -#define CORE__MODES_HPP_ +#ifndef NODE__PLUGIN__MODES_HPP_ +#define NODE__PLUGIN__MODES_HPP_ -#include "types.hpp" +#include "graph/types.hpp" #include @@ -23,7 +23,7 @@ #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { class OperationModes @@ -46,6 +46,6 @@ class OperationModes BaseUnit * pull_over_mrm_; }; -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator -#endif // CORE__MODES_HPP_ +#endif // NODE__PLUGIN__MODES_HPP_ diff --git a/system/system_diagnostic_graph/src/tool/main.cpp b/system/diagnostic_graph_aggregator/src/tool/tool.cpp similarity index 94% rename from system/system_diagnostic_graph/src/tool/main.cpp rename to system/diagnostic_graph_aggregator/src/tool/tool.cpp index 6efb911d8e2d3..657f76c2d91b7 100644 --- a/system/system_diagnostic_graph/src/tool/main.cpp +++ b/system/diagnostic_graph_aggregator/src/tool/tool.cpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "graph.hpp" -#include "types.hpp" -#include "units.hpp" +#include "graph/graph.hpp" +#include "graph/types.hpp" +#include "graph/units.hpp" #include #include #include -namespace system_diagnostic_graph +namespace diagnostic_graph_aggregator { struct GraphNode @@ -128,7 +128,7 @@ void dump_tree_path(const std::string & path) } } -} // namespace system_diagnostic_graph +} // namespace diagnostic_graph_aggregator int main(int argc, char ** argv) { @@ -136,5 +136,5 @@ int main(int argc, char ** argv) std::cerr << "usage: " << argv[0] << " " << std::endl; return 1; } - system_diagnostic_graph::dump_tree_path(argv[1]); + diagnostic_graph_aggregator::dump_tree_path(argv[1]); } diff --git a/system/system_diagnostic_graph/test/files/test1/field-not-found.yaml b/system/diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/field-not-found.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/file-not-found.yaml b/system/diagnostic_graph_aggregator/test/files/test1/file-not-found.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/file-not-found.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/file-not-found.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/graph-circulation.yaml b/system/diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/graph-circulation.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/invalid-dict-type.yaml b/system/diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/invalid-dict-type.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/invalid-list-type.yaml b/system/diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/invalid-list-type.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/path-conflict.yaml b/system/diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/path-conflict.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/path-not-found.yaml b/system/diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/path-not-found.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/unknown-node-type.yaml b/system/diagnostic_graph_aggregator/test/files/test1/unknown-node-type.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/unknown-node-type.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/unknown-node-type.yaml diff --git a/system/system_diagnostic_graph/test/files/test1/unknown-substitution.yaml b/system/diagnostic_graph_aggregator/test/files/test1/unknown-substitution.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test1/unknown-substitution.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/unknown-substitution.yaml diff --git a/system/system_diagnostic_graph/test/files/test2/and.yaml b/system/diagnostic_graph_aggregator/test/files/test2/and.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test2/and.yaml rename to system/diagnostic_graph_aggregator/test/files/test2/and.yaml diff --git a/system/system_diagnostic_graph/test/files/test2/or.yaml b/system/diagnostic_graph_aggregator/test/files/test2/or.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test2/or.yaml rename to system/diagnostic_graph_aggregator/test/files/test2/or.yaml diff --git a/system/system_diagnostic_graph/test/files/test2/warn-to-error.yaml b/system/diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test2/warn-to-error.yaml rename to system/diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml diff --git a/system/system_diagnostic_graph/test/files/test2/warn-to-ok.yaml b/system/diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml similarity index 100% rename from system/system_diagnostic_graph/test/files/test2/warn-to-ok.yaml rename to system/diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml diff --git a/system/system_diagnostic_graph/test/src/test1.cpp b/system/diagnostic_graph_aggregator/test/src/test1.cpp similarity index 94% rename from system/system_diagnostic_graph/test/src/test1.cpp rename to system/diagnostic_graph_aggregator/test/src/test1.cpp index d01822e93c2eb..48a0e1f45ce07 100644 --- a/system/system_diagnostic_graph/test/src/test1.cpp +++ b/system/diagnostic_graph_aggregator/test/src/test1.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "core/error.hpp" -#include "core/graph.hpp" +#include "graph/error.hpp" +#include "graph/graph.hpp" #include "utils.hpp" #include -using namespace system_diagnostic_graph; // NOLINT(build/namespaces) +using namespace diagnostic_graph_aggregator; // NOLINT(build/namespaces) TEST(ConfigFile, RootNotFound) { diff --git a/system/system_diagnostic_graph/test/src/test2.cpp b/system/diagnostic_graph_aggregator/test/src/test2.cpp similarity index 97% rename from system/system_diagnostic_graph/test/src/test2.cpp rename to system/diagnostic_graph_aggregator/test/src/test2.cpp index 3e4c946f73fb7..1098ff9efb0db 100644 --- a/system/system_diagnostic_graph/test/src/test2.cpp +++ b/system/diagnostic_graph_aggregator/test/src/test2.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "core/error.hpp" -#include "core/graph.hpp" +#include "graph/error.hpp" +#include "graph/graph.hpp" #include "utils.hpp" #include @@ -22,7 +22,7 @@ #include -using namespace system_diagnostic_graph; // NOLINT(build/namespaces) +using namespace diagnostic_graph_aggregator; // NOLINT(build/namespaces) using diagnostic_msgs::msg::DiagnosticArray; using diagnostic_msgs::msg::DiagnosticStatus; diff --git a/system/system_diagnostic_graph/test/src/utils.cpp b/system/diagnostic_graph_aggregator/test/src/utils.cpp similarity index 100% rename from system/system_diagnostic_graph/test/src/utils.cpp rename to system/diagnostic_graph_aggregator/test/src/utils.cpp diff --git a/system/system_diagnostic_graph/test/src/utils.hpp b/system/diagnostic_graph_aggregator/test/src/utils.hpp similarity index 100% rename from system/system_diagnostic_graph/test/src/utils.hpp rename to system/diagnostic_graph_aggregator/test/src/utils.hpp diff --git a/system/system_diagnostic_graph/doc/format/diag.md b/system/system_diagnostic_graph/doc/format/diag.md deleted file mode 100644 index 9835924f08996..0000000000000 --- a/system/system_diagnostic_graph/doc/format/diag.md +++ /dev/null @@ -1,11 +0,0 @@ -# Diag - -Diag is a node that refers to a source diagnostics. - -## Format - -| Name | Type | Required | Description | -| -------- | ------ | -------- | -------------------------------------- | -| type | string | yes | Specify `diag` when using this object. | -| name | string | yes | Name of diagnostic status. | -| hardware | string | yes | Hardware ID of diagnostic status. | diff --git a/system/system_diagnostic_graph/example/example.launch.xml b/system/system_diagnostic_graph/example/example.launch.xml deleted file mode 100644 index 1456bfd5c6593..0000000000000 --- a/system/system_diagnostic_graph/example/example.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - diff --git a/system/system_diagnostic_graph/launch/system_diagnostic_graph.launch.xml b/system/system_diagnostic_graph/launch/system_diagnostic_graph.launch.xml deleted file mode 100644 index 5b9a84947d179..0000000000000 --- a/system/system_diagnostic_graph/launch/system_diagnostic_graph.launch.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - From 1b6cc51fefefae23491d31071a968f86c16ef9d8 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 14 Dec 2023 16:03:09 +0900 Subject: [PATCH 54/87] refactor(lane_change): separate lane change and external request (#5850) * refactor(lane_change): separate lane change and external request Signed-off-by: Muhammad Zulfaqar Azmi * refactored external request lane change Signed-off-by: Muhammad Zulfaqar Azmi * separate on external request Signed-off-by: Muhammad Zulfaqar Azmi * style(pre-commit): autofix * delete external request Signed-off-by: Muhammad Zulfaqar Azmi * fix interface Signed-off-by: Muhammad Zulfaqar Azmi * fix external lane change couldn't be initialize Signed-off-by: Muhammad Zulfaqar Azmi * fix documents Signed-off-by: Muhammad Zulfaqar Azmi * fix link in README Signed-off-by: Muhammad Zulfaqar Azmi * fix based on comments Signed-off-by: Zulfaqar Azmi * add ament auto package Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> * Update planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> * fix test Signed-off-by: Muhammad Zulfaqar Azmi * fix AbLC test Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Zulfaqar Azmi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --- planning/.pages | 2 +- .../interface.hpp | 2 +- .../manager.hpp | 2 +- .../scene.hpp | 2 +- .../package.xml | 1 + ...t_behavior_path_planner_node_interface.cpp | 5 +- .../CMakeLists.txt | 25 ++++ .../manager.hpp | 54 ++++++++ .../scene.hpp} | 8 +- .../package.xml | 39 ++++++ .../plugins.xml | 4 + .../src/manager.cpp | 49 +++++++ .../src/scene.cpp} | 2 +- ...t_behavior_path_planner_node_interface.cpp | 128 ++++++++++++++++++ .../CMakeLists.txt | 29 ++++ .../README.md} | 36 ++--- .../config}/lane_change.param.yaml | 0 .../images}/lane_change-abort.png | Bin .../images}/lane_change-cancel.png | Bin .../lane_change-candidate_path_samples.png | Bin .../lane_change-cant_cancel_no_abort.png | Bin .../images}/lane_change-debug-1.png | Bin .../images}/lane_change-debug-2.png | Bin .../images}/lane_change-debug-3.png | Bin ...nable_collision_check_at_prepare_phase.png | Bin .../images}/lane_change-intersection_case.png | Bin .../lane_change-lane_change_phases.png | Bin .../lane_change-stop_at_terminal.drawio.svg | 0 ...hange-stop_at_terminal_no_block.drawio.svg | 0 ...hange-stop_far_from_target_lane.drawio.svg | 0 ...ane_change-stop_not_at_terminal.drawio.svg | 0 ..._at_terminal_no_blocking_object.drawio.svg | 0 .../lane_change-when_cannot_change_lanes.png | Bin .../images}/lane_change.drawio.svg | 0 .../images}/lane_objects.drawio.svg | 0 .../interface.hpp | 17 ++- .../manager.hpp | 31 +---- .../scene.hpp} | 8 +- .../utils}/base_class.hpp | 12 +- .../utils/data_structs.hpp} | 6 +- .../utils/markers.hpp} | 12 +- .../utils/path.hpp} | 10 +- .../utils}/utils.hpp | 12 +- .../package.xml | 38 ++++++ .../plugins.xml | 6 + .../src}/interface.cpp | 7 +- .../src}/manager.cpp | 17 +-- .../src/scene.cpp} | 4 +- .../src/utils/markers.cpp} | 2 +- .../src/utils}/utils.cpp | 6 +- ...t_behavior_path_planner_node_interface.cpp | 126 +++++++++++++++++ .../test/test_lane_change_utils.cpp | 3 +- planning/behavior_path_planner/CMakeLists.txt | 14 -- planning/behavior_path_planner/plugins.xml | 4 - ...t_behavior_path_planner_node_interface.cpp | 7 +- 55 files changed, 585 insertions(+), 145 deletions(-) create mode 100644 planning/behavior_path_external_request_lane_change_module/CMakeLists.txt create mode 100644 planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/manager.hpp rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request.hpp => behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/scene.hpp} (79%) create mode 100644 planning/behavior_path_external_request_lane_change_module/package.xml create mode 100644 planning/behavior_path_external_request_lane_change_module/plugins.xml create mode 100644 planning/behavior_path_external_request_lane_change_module/src/manager.cpp rename planning/{behavior_path_planner/src/scene_module/lane_change/external_request.cpp => behavior_path_external_request_lane_change_module/src/scene.cpp} (92%) create mode 100644 planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp create mode 100644 planning/behavior_path_lane_change_module/CMakeLists.txt rename planning/{behavior_path_planner/docs/behavior_path_planner_lane_change_design.md => behavior_path_lane_change_module/README.md} (96%) rename planning/{behavior_path_planner/config/lane_change => behavior_path_lane_change_module/config}/lane_change.param.yaml (100%) rename planning/{behavior_path_planner/image/lane_change/cancel_and_abort => behavior_path_lane_change_module/images}/lane_change-abort.png (100%) rename planning/{behavior_path_planner/image/lane_change/cancel_and_abort => behavior_path_lane_change_module/images}/lane_change-cancel.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-candidate_path_samples.png (100%) rename planning/{behavior_path_planner/image/lane_change/cancel_and_abort => behavior_path_lane_change_module/images}/lane_change-cant_cancel_no_abort.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-debug-1.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-debug-2.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-debug-3.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-enable_collision_check_at_prepare_phase.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-intersection_case.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-lane_change_phases.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-stop_at_terminal.drawio.svg (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-stop_at_terminal_no_block.drawio.svg (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-stop_far_from_target_lane.drawio.svg (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-stop_not_at_terminal.drawio.svg (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change-when_cannot_change_lanes.png (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_change.drawio.svg (100%) rename planning/{behavior_path_planner/image/lane_change => behavior_path_lane_change_module/images}/lane_objects.drawio.svg (100%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/lane_change => behavior_path_lane_change_module/include/behavior_path_lane_change_module}/interface.hpp (87%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/lane_change => behavior_path_lane_change_module/include/behavior_path_lane_change_module}/manager.hpp (68%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp => behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp} (96%) rename planning/{behavior_path_planner/include/behavior_path_planner/scene_module/lane_change => behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils}/base_class.hpp (95%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp => behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp} (96%) rename planning/{behavior_path_planner/include/behavior_path_planner/marker_utils/lane_change/debug.hpp => behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/markers.hpp} (80%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp => behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/path.hpp} (82%) rename planning/{behavior_path_planner/include/behavior_path_planner/utils/lane_change => behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils}/utils.hpp (96%) create mode 100644 planning/behavior_path_lane_change_module/package.xml create mode 100644 planning/behavior_path_lane_change_module/plugins.xml rename planning/{behavior_path_planner/src/scene_module/lane_change => behavior_path_lane_change_module/src}/interface.cpp (98%) rename planning/{behavior_path_planner/src/scene_module/lane_change => behavior_path_lane_change_module/src}/manager.cpp (95%) rename planning/{behavior_path_planner/src/scene_module/lane_change/normal.cpp => behavior_path_lane_change_module/src/scene.cpp} (99%) rename planning/{behavior_path_planner/src/marker_utils/lane_change/debug.cpp => behavior_path_lane_change_module/src/utils/markers.cpp} (98%) rename planning/{behavior_path_planner/src/utils/lane_change => behavior_path_lane_change_module/src/utils}/utils.cpp (99%) create mode 100644 planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp rename planning/{behavior_path_planner => behavior_path_lane_change_module}/test/test_lane_change_utils.cpp (95%) diff --git a/planning/.pages b/planning/.pages index 7cbd36d2ca2d0..6ae8abe240d9b 100644 --- a/planning/.pages +++ b/planning/.pages @@ -14,7 +14,7 @@ nav: - 'Avoidance by Lane Change': planning/behavior_path_planner/docs/behavior_path_planner_avoidance_by_lane_change_design - 'Dynamic Avoidance': planning/behavior_path_planner/docs/behavior_path_planner_dynamic_avoidance_design - 'Goal Planner': planning/behavior_path_planner/docs/behavior_path_planner_goal_planner_design - - 'Lane Change': planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design + - 'Lane Change': planning/behavior_path_lane_change_module - 'Side Shift': planning/behavior_path_planner/docs/behavior_path_planner_side_shift_design - 'Start Planner': planning/behavior_path_planner/docs/behavior_path_planner_start_planner_design - 'Behavior Velocity Planner': diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp index 0bc08ccd400ca..016a6b2977701 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp @@ -17,7 +17,7 @@ #include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" #include "behavior_path_avoidance_by_lane_change_module/scene.hpp" -#include "behavior_path_planner/scene_module/lane_change/interface.hpp" +#include "behavior_path_lane_change_module/interface.hpp" #include diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp index b1beae9c6fc03..d996555365166 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp @@ -17,7 +17,7 @@ #include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" #include "behavior_path_avoidance_by_lane_change_module/interface.hpp" -#include "behavior_path_planner/scene_module/lane_change/manager.hpp" +#include "behavior_path_lane_change_module/manager.hpp" #include 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 1e667c207c64f..f22291c99b8e7 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 @@ -16,7 +16,7 @@ #define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_ #include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" -#include "behavior_path_planner/scene_module/lane_change/normal.hpp" +#include "behavior_path_lane_change_module/scene.hpp" #include diff --git a/planning/behavior_path_avoidance_by_lane_change_module/package.xml b/planning/behavior_path_avoidance_by_lane_change_module/package.xml index da51dd9f235dc..3a4f42f2d2a6c 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/package.xml +++ b/planning/behavior_path_avoidance_by_lane_change_module/package.xml @@ -19,6 +19,7 @@ eigen3_cmake_module behavior_path_avoidance_module + behavior_path_lane_change_module behavior_path_planner behavior_path_planner_common motion_utils diff --git a/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 2264669fdcdbe..3041ae7e1112e 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -47,6 +47,8 @@ std::shared_ptr generateNode() ament_index_cpp::get_package_share_directory("planning_test_utils"); const auto behavior_path_planner_dir = ament_index_cpp::get_package_share_directory("behavior_path_planner"); + const auto behavior_path_lane_change_module_dir = + ament_index_cpp::get_package_share_directory("behavior_path_lane_change_module"); std::vector module_names; module_names.emplace_back("behavior_path_planner::AvoidanceByLaneChangeModuleManager"); @@ -63,8 +65,7 @@ std::shared_ptr generateNode() behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - ament_index_cpp::get_package_share_directory("behavior_path_planner") + - "/config/lane_change/lane_change.param.yaml", + behavior_path_lane_change_module_dir + "/config/lane_change.param.yaml", ament_index_cpp::get_package_share_directory("behavior_path_avoidance_module") + "/config/avoidance.param.yaml", ament_index_cpp::get_package_share_directory("behavior_path_avoidance_by_lane_change_module") + diff --git a/planning/behavior_path_external_request_lane_change_module/CMakeLists.txt b/planning/behavior_path_external_request_lane_change_module/CMakeLists.txt new file mode 100644 index 0000000000000..86dc0ccb61330 --- /dev/null +++ b/planning/behavior_path_external_request_lane_change_module/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_path_external_request_lane_change_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_path_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/manager.cpp + src/scene.cpp +) + +if(BUILD_TESTING) + ament_add_ros_isolated_gmock(test_${PROJECT_NAME} + test/test_behavior_path_planner_node_interface.cpp + ) + + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) + + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() + +ament_auto_package() diff --git a/planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/manager.hpp b/planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/manager.hpp new file mode 100644 index 0000000000000..dfcc4f61d8241 --- /dev/null +++ b/planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/manager.hpp @@ -0,0 +1,54 @@ +// 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 BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__MANAGER_HPP_ +#define BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__MANAGER_HPP_ + +#include "behavior_path_lane_change_module/manager.hpp" +#include "route_handler/route_handler.hpp" + +#include + +#include +#include + +namespace behavior_path_planner +{ +class ExternalRequestLaneChangeRightModuleManager : public LaneChangeModuleManager +{ +public: + ExternalRequestLaneChangeRightModuleManager() + : LaneChangeModuleManager( + "external_request_lane_change_right", route_handler::Direction::RIGHT, + LaneChangeModuleType::EXTERNAL_REQUEST) + { + } + std::unique_ptr createNewSceneModuleInstance() override; +}; + +class ExternalRequestLaneChangeLeftModuleManager : public LaneChangeModuleManager +{ +public: + ExternalRequestLaneChangeLeftModuleManager() + + : LaneChangeModuleManager( + "external_request_lane_change_left", route_handler::Direction::LEFT, + LaneChangeModuleType::EXTERNAL_REQUEST) + { + } + std::unique_ptr createNewSceneModuleInstance() override; +}; +} // namespace behavior_path_planner + +#endif // BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request.hpp b/planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/scene.hpp similarity index 79% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request.hpp rename to planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/scene.hpp index d9c77d6db337e..c23d6f2f3996c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/external_request.hpp +++ b/planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/scene.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__EXTERNAL_REQUEST_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__EXTERNAL_REQUEST_HPP_ +#ifndef BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__SCENE_HPP_ +#define BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__SCENE_HPP_ -#include "behavior_path_planner/scene_module/lane_change/normal.hpp" +#include "behavior_path_lane_change_module/scene.hpp" #include @@ -35,4 +35,4 @@ class ExternalRequestLaneChange : public NormalLaneChange }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__EXTERNAL_REQUEST_HPP_ +#endif // BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__SCENE_HPP_ diff --git a/planning/behavior_path_external_request_lane_change_module/package.xml b/planning/behavior_path_external_request_lane_change_module/package.xml new file mode 100644 index 0000000000000..16216aa1f71e9 --- /dev/null +++ b/planning/behavior_path_external_request_lane_change_module/package.xml @@ -0,0 +1,39 @@ + + + + behavior_path_external_request_lane_change_module + 0.1.0 + The behavior_path_external_request_lane_change_module package + + Fumiya Watanabe + Zulfaqar Azmi + Kosuke Takeuchi + Tomoya Kimura + Shumpei Wakabayashi + Tomohito Ando + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + behavior_path_lane_change_module + behavior_path_planner + behavior_path_planner_common + motion_utils + pluginlib + rclcpp + rtc_interface + tier4_autoware_utils + tier4_planning_msgs + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_path_external_request_lane_change_module/plugins.xml b/planning/behavior_path_external_request_lane_change_module/plugins.xml new file mode 100644 index 0000000000000..f3cc686837c38 --- /dev/null +++ b/planning/behavior_path_external_request_lane_change_module/plugins.xml @@ -0,0 +1,4 @@ + + + + diff --git a/planning/behavior_path_external_request_lane_change_module/src/manager.cpp b/planning/behavior_path_external_request_lane_change_module/src/manager.cpp new file mode 100644 index 0000000000000..3cfe7aa51f0f1 --- /dev/null +++ b/planning/behavior_path_external_request_lane_change_module/src/manager.cpp @@ -0,0 +1,49 @@ +// 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 "behavior_path_external_request_lane_change_module/manager.hpp" + +#include "behavior_path_external_request_lane_change_module/scene.hpp" +#include "behavior_path_lane_change_module/interface.hpp" + +namespace behavior_path_planner +{ + +std::unique_ptr +ExternalRequestLaneChangeRightModuleManager::createNewSceneModuleInstance() +{ + return std::make_unique( + name_, *node_, parameters_, rtc_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, + std::make_unique(parameters_, direction_)); +} + +std::unique_ptr +ExternalRequestLaneChangeLeftModuleManager::createNewSceneModuleInstance() +{ + return std::make_unique( + name_, *node_, parameters_, rtc_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, + std::make_unique(parameters_, direction_)); +} + +} // namespace behavior_path_planner + +#include +PLUGINLIB_EXPORT_CLASS( + behavior_path_planner::ExternalRequestLaneChangeRightModuleManager, + behavior_path_planner::SceneModuleManagerInterface) +PLUGINLIB_EXPORT_CLASS( + behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager, + behavior_path_planner::SceneModuleManagerInterface) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/external_request.cpp b/planning/behavior_path_external_request_lane_change_module/src/scene.cpp similarity index 92% rename from planning/behavior_path_planner/src/scene_module/lane_change/external_request.cpp rename to planning/behavior_path_external_request_lane_change_module/src/scene.cpp index 3a304a9b5bb53..913266bf79fa3 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/external_request.cpp +++ b/planning/behavior_path_external_request_lane_change_module/src/scene.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/lane_change/external_request.hpp" +#include "behavior_path_external_request_lane_change_module/scene.hpp" #include diff --git a/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp new file mode 100644 index 0000000000000..ff5be388704da --- /dev/null +++ b/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -0,0 +1,128 @@ +// 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 "ament_index_cpp/get_package_share_directory.hpp" +#include "behavior_path_planner/behavior_path_planner_node.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include + +#include +#include + +using behavior_path_planner::BehaviorPathPlannerNode; +using planning_test_utils::PlanningInterfaceTestManager; + +std::shared_ptr generateTestManager() +{ + auto test_manager = std::make_shared(); + + // set subscriber with topic name: behavior_path_planner → test_node_ + test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); + + // set behavior_path_planner's input topic name(this topic is changed to test node) + test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); + + test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); + + return test_manager; +} + +std::shared_ptr generateNode() +{ + auto node_options = rclcpp::NodeOptions{}; + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto behavior_path_planner_dir = + ament_index_cpp::get_package_share_directory("behavior_path_planner"); + const auto behavior_path_lane_change_module_dir = + ament_index_cpp::get_package_share_directory("behavior_path_lane_change_module"); + + std::vector module_names; + module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeRightModuleManager"); + module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager"); + + std::vector params; + params.emplace_back("launch_modules", module_names); + node_options.parameter_overrides(params); + + test_utils::updateNodeOptions( + node_options, { + planning_test_utils_dir + "/config/test_common.param.yaml", + planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", + behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", + behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", + behavior_path_lane_change_module_dir + "/config/lane_change.param.yaml", + }); + + return std::make_shared(node_options); +} + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ + // publish necessary topics from test_manager + test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); + test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); + test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); + test_manager->publishOccupancyGrid( + test_target_node, "behavior_path_planner/input/occupancy_grid_map"); + test_manager->publishLaneDrivingScenario( + test_target_node, "behavior_path_planner/input/scenario"); + test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); + test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); + test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); + test_manager->publishLateralOffset( + test_target_node, "behavior_path_planner/input/lateral_offset"); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) +{ + rclcpp::init(0, nullptr); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty route + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + + rclcpp::shutdown(); +} diff --git a/planning/behavior_path_lane_change_module/CMakeLists.txt b/planning/behavior_path_lane_change_module/CMakeLists.txt new file mode 100644 index 0000000000000..e5bce68ebfa44 --- /dev/null +++ b/planning/behavior_path_lane_change_module/CMakeLists.txt @@ -0,0 +1,29 @@ +cmake_minimum_required(VERSION 3.14) +project(behavior_path_lane_change_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(behavior_path_planner plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/interface.cpp + src/manager.cpp + src/scene.cpp + src/utils/markers.cpp + src/utils/utils.cpp +) + +if(BUILD_TESTING) + ament_add_ros_isolated_gmock(test_${PROJECT_NAME} + test/test_behavior_path_planner_node_interface.cpp + test/test_lane_change_utils.cpp + ) + + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) + + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md b/planning/behavior_path_lane_change_module/README.md similarity index 96% rename from planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md rename to planning/behavior_path_lane_change_module/README.md index ee74f700c4d42..a1fa2068b9ab5 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_lane_change_design.md +++ b/planning/behavior_path_lane_change_module/README.md @@ -15,7 +15,7 @@ The Lane Change module is activated when lane change is needed and can be safely The lane change candidate path is divided into two phases: preparation and lane-changing. The following figure illustrates each phase of the lane change candidate path. -![lane-change-phases](../image/lane_change/lane_change-lane_change_phases.png) +![lane-change-phases](./images/lane_change-lane_change_phases.png) ### Preparation phase @@ -62,7 +62,7 @@ Note that when the `current_velocity` is lower than `minimum_lane_changing_veloc 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](../image/lane_change/lane_change-candidate_path_samples.png) +![path_samples](./images/lane_change-candidate_path_samples.png) Which path will be chosen will depend on validity and collision check. @@ -155,21 +155,21 @@ stop #### Candidate Path's Safety check -See [safety check utils explanation](../docs/behavior_path_planner_safety_check.md) +See [safety check utils explanation](../behavior_path_planner/docs/behavior_path_planner_safety_check.md) #### Objects selection and classification First, we divide the target objects into obstacles in the target lane, obstacles in the current lane, and obstacles in other lanes. Target lane indicates the lane that the ego vehicle is going to reach after the lane change and current lane mean the current lane where the ego vehicle is following before the lane change. Other lanes are lanes that do not belong to the target and current lanes. The following picture describes objects on each lane. Note that users can remove objects either on current and other lanes from safety check by changing the flag, which are `check_objects_on_current_lanes` and `check_objects_on_other_lanes`. -![object lanes](../image/lane_change/lane_objects.drawio.svg) +![object lanes](./images/lane_objects.drawio.svg) -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](../docs/behavior_path_planner_avoidance_design.md). +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_planner/docs/behavior_path_planner_avoidance_design.md). ##### 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. -![enable collision check at prepare phase](../image/lane_change/lane_change-enable_collision_check_at_prepare_phase.png) +![enable collision check at prepare phase](./images/lane_change-enable_collision_check_at_prepare_phase.png) The parameter `prepare_phase_ignore_target_speed_thresh` can be configured to ignore the prepare phase collision check for targets whose speeds are less than a specific threshold, such as stationary or very slow-moving objects. @@ -184,7 +184,7 @@ minimum_lane_change_distance = minimum_prepare_length + minimum_lane_changing_ve The following figure illustrates when the lane is blocked in multiple lane changes cases. -![multiple-lane-changes](../image/lane_change/lane_change-when_cannot_change_lanes.png) +![multiple-lane-changes](./images/lane_change-when_cannot_change_lanes.png) #### Stopping position when an object exists ahead @@ -195,25 +195,25 @@ The position to be stopped depends on the situation, such as when the lane chang Regardless of the presence or absence of objects in the lane change target lane, stop by keeping the distance necessary for lane change to the object ahead. -![stop_at_terminal_no_block](../image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg) +![stop_at_terminal_no_block](./images/lane_change-stop_at_terminal_no_block.drawio.svg) -![stop_at_terminal](../image/lane_change/lane_change-stop_at_terminal.drawio.svg) +![stop_at_terminal](./images/lane_change-stop_at_terminal.drawio.svg) ##### When the ego vehicle is not near the end of the lane change If there are NO objects in the lane change section of the target lane, stop by keeping the distance necessary for lane change to the object ahead. -![stop_not_at_terminal_no_blocking_object](../image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg) +![stop_not_at_terminal_no_blocking_object](./images/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg) If there are objects in the lane change section of the target lane, stop WITHOUT keeping the distance necessary for lane change to the object ahead. -![stop_not_at_terminal](../image/lane_change/lane_change-stop_not_at_terminal.drawio.svg) +![stop_not_at_terminal](./images/lane_change-stop_not_at_terminal.drawio.svg) ##### When the target lane is far away When the target lane for lane change is far away and not next to the current lane, do not keep the distance necessary for lane change to the object ahead. -![stop_far_from_target_lane](../image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg) +![stop_far_from_target_lane](./images/lane_change-stop_far_from_target_lane.drawio.svg) ### Lane Change When Stuck @@ -292,19 +292,19 @@ The function can be enabled by setting `enable_on_prepare_phase` to `true`. The following image illustrates the cancel process. -![cancel](../image/lane_change/cancel_and_abort/lane_change-cancel.png) +![cancel](./images/lane_change-cancel.png) #### Abort Assume the ego vehicle has already departed from the current lane. In that case, it is dangerous to cancel the path, and it will cause the ego vehicle to change the heading direction abruptly. In this case, planning a trajectory that allows the ego vehicle to return to the current path while minimizing the heading changes is necessary. In this case, the lane change module will generate an abort path. The following images show an example of the abort path. Do note that the function DOESN'T GUARANTEE a safe abort process, as it didn't check the presence of the surrounding objects and/or their reactions. The function can be enable manually by setting both `enable_on_prepare_phase` and `enable_on_lane_changing_phase` to `true`. The parameter `max_lateral_jerk` need to be set to a high value in order for it to work. -![abort](../image/lane_change/cancel_and_abort/lane_change-abort.png) +![abort](./images/lane_change-abort.png) #### Stop/Cruise The last behavior will also occur if the ego vehicle has departed from the current lane. If the abort function is disabled or the abort is no longer possible, the ego vehicle will attempt to stop or transition to the obstacle cruise mode. Do note that the module DOESN'T GUARANTEE safe maneuver due to the unexpected behavior that might've occurred during these critical scenarios. The following images illustrate the situation. -![stop](../image/lane_change/cancel_and_abort/lane_change-cant_cancel_no_abort.png) +![stop](./images/lane_change-cant_cancel_no_abort.png) ## Parameters @@ -451,11 +451,11 @@ Then add the marker in `rviz2`. -![debug](../image/lane_change/lane_change-debug-1.png) +![debug](./images/lane_change-debug-1.png) -![debug2](../image/lane_change/lane_change-debug-2.png) +![debug2](./images/lane_change-debug-2.png) -![debug3](../image/lane_change/lane_change-debug-3.png) +![debug3](./images/lane_change-debug-3.png) Available information diff --git a/planning/behavior_path_planner/config/lane_change/lane_change.param.yaml b/planning/behavior_path_lane_change_module/config/lane_change.param.yaml similarity index 100% rename from planning/behavior_path_planner/config/lane_change/lane_change.param.yaml rename to planning/behavior_path_lane_change_module/config/lane_change.param.yaml diff --git a/planning/behavior_path_planner/image/lane_change/cancel_and_abort/lane_change-abort.png b/planning/behavior_path_lane_change_module/images/lane_change-abort.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/cancel_and_abort/lane_change-abort.png rename to planning/behavior_path_lane_change_module/images/lane_change-abort.png diff --git a/planning/behavior_path_planner/image/lane_change/cancel_and_abort/lane_change-cancel.png b/planning/behavior_path_lane_change_module/images/lane_change-cancel.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/cancel_and_abort/lane_change-cancel.png rename to planning/behavior_path_lane_change_module/images/lane_change-cancel.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-candidate_path_samples.png b/planning/behavior_path_lane_change_module/images/lane_change-candidate_path_samples.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-candidate_path_samples.png rename to planning/behavior_path_lane_change_module/images/lane_change-candidate_path_samples.png diff --git a/planning/behavior_path_planner/image/lane_change/cancel_and_abort/lane_change-cant_cancel_no_abort.png b/planning/behavior_path_lane_change_module/images/lane_change-cant_cancel_no_abort.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/cancel_and_abort/lane_change-cant_cancel_no_abort.png rename to planning/behavior_path_lane_change_module/images/lane_change-cant_cancel_no_abort.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-debug-1.png b/planning/behavior_path_lane_change_module/images/lane_change-debug-1.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-debug-1.png rename to planning/behavior_path_lane_change_module/images/lane_change-debug-1.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-debug-2.png b/planning/behavior_path_lane_change_module/images/lane_change-debug-2.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-debug-2.png rename to planning/behavior_path_lane_change_module/images/lane_change-debug-2.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-debug-3.png b/planning/behavior_path_lane_change_module/images/lane_change-debug-3.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-debug-3.png rename to planning/behavior_path_lane_change_module/images/lane_change-debug-3.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-enable_collision_check_at_prepare_phase.png b/planning/behavior_path_lane_change_module/images/lane_change-enable_collision_check_at_prepare_phase.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-enable_collision_check_at_prepare_phase.png rename to planning/behavior_path_lane_change_module/images/lane_change-enable_collision_check_at_prepare_phase.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-intersection_case.png b/planning/behavior_path_lane_change_module/images/lane_change-intersection_case.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-intersection_case.png rename to planning/behavior_path_lane_change_module/images/lane_change-intersection_case.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-lane_change_phases.png b/planning/behavior_path_lane_change_module/images/lane_change-lane_change_phases.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-lane_change_phases.png rename to planning/behavior_path_lane_change_module/images/lane_change-lane_change_phases.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal.drawio.svg b/planning/behavior_path_lane_change_module/images/lane_change-stop_at_terminal.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal.drawio.svg rename to planning/behavior_path_lane_change_module/images/lane_change-stop_at_terminal.drawio.svg diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg b/planning/behavior_path_lane_change_module/images/lane_change-stop_at_terminal_no_block.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-stop_at_terminal_no_block.drawio.svg rename to planning/behavior_path_lane_change_module/images/lane_change-stop_at_terminal_no_block.drawio.svg diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg b/planning/behavior_path_lane_change_module/images/lane_change-stop_far_from_target_lane.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-stop_far_from_target_lane.drawio.svg rename to planning/behavior_path_lane_change_module/images/lane_change-stop_far_from_target_lane.drawio.svg diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal.drawio.svg b/planning/behavior_path_lane_change_module/images/lane_change-stop_not_at_terminal.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal.drawio.svg rename to planning/behavior_path_lane_change_module/images/lane_change-stop_not_at_terminal.drawio.svg diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg b/planning/behavior_path_lane_change_module/images/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg rename to planning/behavior_path_lane_change_module/images/lane_change-stop_not_at_terminal_no_blocking_object.drawio.svg diff --git a/planning/behavior_path_planner/image/lane_change/lane_change-when_cannot_change_lanes.png b/planning/behavior_path_lane_change_module/images/lane_change-when_cannot_change_lanes.png similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change-when_cannot_change_lanes.png rename to planning/behavior_path_lane_change_module/images/lane_change-when_cannot_change_lanes.png diff --git a/planning/behavior_path_planner/image/lane_change/lane_change.drawio.svg b/planning/behavior_path_lane_change_module/images/lane_change.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_change.drawio.svg rename to planning/behavior_path_lane_change_module/images/lane_change.drawio.svg diff --git a/planning/behavior_path_planner/image/lane_change/lane_objects.drawio.svg b/planning/behavior_path_lane_change_module/images/lane_objects.drawio.svg similarity index 100% rename from planning/behavior_path_planner/image/lane_change/lane_objects.drawio.svg rename to planning/behavior_path_lane_change_module/images/lane_objects.drawio.svg diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp similarity index 87% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp index b7cef007d6d9f..fd9a979ee0f76 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/interface.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// 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. @@ -12,14 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__INTERFACE_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__INTERFACE_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__INTERFACE_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__INTERFACE_HPP_ -#include "behavior_path_planner/scene_module/lane_change/base_class.hpp" -#include "behavior_path_planner/scene_module/lane_change/external_request.hpp" -#include "behavior_path_planner/scene_module/lane_change/normal.hpp" -#include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" -#include "behavior_path_planner/utils/lane_change/lane_change_path.hpp" +#include "behavior_path_lane_change_module/scene.hpp" +#include "behavior_path_lane_change_module/utils/base_class.hpp" +#include "behavior_path_lane_change_module/utils/data_structs.hpp" +#include "behavior_path_lane_change_module/utils/path.hpp" #include "behavior_path_planner_common/interface/scene_module_interface.hpp" #include "behavior_path_planner_common/turn_signal_decider.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -146,4 +145,4 @@ class LaneChangeInterface : public SceneModuleInterface }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__INTERFACE_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__INTERFACE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/manager.hpp similarity index 68% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/manager.hpp index 024c6685b28c4..b34f691bd2b0d 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/manager.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/manager.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__MANAGER_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__MANAGER_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__MANAGER_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__MANAGER_HPP_ -#include "behavior_path_planner/scene_module/lane_change/interface.hpp" +#include "behavior_path_lane_change_module/utils/data_structs.hpp" #include "behavior_path_planner_common/interface/scene_module_manager_interface.hpp" #include "route_handler/route_handler.hpp" @@ -23,7 +23,6 @@ #include #include -#include #include namespace behavior_path_planner @@ -72,28 +71,6 @@ class LaneChangeLeftModuleManager : public LaneChangeModuleManager { } }; - -class ExternalRequestLaneChangeRightModuleManager : public LaneChangeModuleManager -{ -public: - ExternalRequestLaneChangeRightModuleManager() - : LaneChangeModuleManager( - "external_request_lane_change_right", route_handler::Direction::RIGHT, - LaneChangeModuleType::EXTERNAL_REQUEST) - { - } -}; - -class ExternalRequestLaneChangeLeftModuleManager : public LaneChangeModuleManager -{ -public: - ExternalRequestLaneChangeLeftModuleManager() - : LaneChangeModuleManager( - "external_request_lane_change_left", route_handler::Direction::LEFT, - LaneChangeModuleType::EXTERNAL_REQUEST) - { - } -}; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__MANAGER_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp similarity index 96% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp index 61caf7b2b393f..50766621b2f44 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp @@ -11,10 +11,10 @@ // 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 BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__NORMAL_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__NORMAL_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__SCENE_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__SCENE_HPP_ -#include "behavior_path_planner/scene_module/lane_change/base_class.hpp" +#include "behavior_path_lane_change_module/utils/base_class.hpp" #include #include @@ -180,4 +180,4 @@ class NormalLaneChange : public LaneChangeBase double stop_time_{0.0}; }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__NORMAL_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__SCENE_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp similarity index 95% rename from planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp index be49ec5b2e740..a7a35f07e5f30 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/base_class.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp @@ -11,12 +11,12 @@ // 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 BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__BASE_CLASS_HPP_ -#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__BASE_CLASS_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__BASE_CLASS_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__BASE_CLASS_HPP_ -#include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" -#include "behavior_path_planner/utils/lane_change/lane_change_path.hpp" -#include "behavior_path_planner/utils/lane_change/utils.hpp" +#include "behavior_path_lane_change_module/utils/data_structs.hpp" +#include "behavior_path_lane_change_module/utils/path.hpp" +#include "behavior_path_lane_change_module/utils/utils.hpp" #include "behavior_path_planner_common/interface/scene_module_interface.hpp" #include "behavior_path_planner_common/turn_signal_decider.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -269,4 +269,4 @@ class LaneChangeBase mutable rclcpp::Clock clock_{RCL_ROS_TIME}; }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__LANE_CHANGE__BASE_CLASS_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__BASE_CLASS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp similarity index 96% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp index debeef5ec573f..dd7760d31eaa7 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_module_data.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp @@ -11,8 +11,8 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_MODULE_DATA_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_MODULE_DATA_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_ #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -211,4 +211,4 @@ struct PathSafetyStatus }; } // namespace behavior_path_planner::data::lane_change -#endif // BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_MODULE_DATA_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/lane_change/debug.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/markers.hpp similarity index 80% rename from planning/behavior_path_planner/include/behavior_path_planner/marker_utils/lane_change/debug.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/markers.hpp index 96f0851ed33c0..d6deecd4f46fa 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/marker_utils/lane_change/debug.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/markers.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__MARKER_UTILS__LANE_CHANGE__DEBUG_HPP_ -#define BEHAVIOR_PATH_PLANNER__MARKER_UTILS__LANE_CHANGE__DEBUG_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__MARKERS_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__MARKERS_HPP_ -#include "behavior_path_planner/utils/lane_change/lane_change_path.hpp" -#include "behavior_path_planner_common/marker_utils/utils.hpp" +#include "behavior_path_lane_change_module/utils/path.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" +#include + #include -#include #include namespace marker_utils::lane_change_markers @@ -38,4 +38,4 @@ MarkerArray showFilteredObjects( const ExtendedPredictedObjects & target_lane_objects, const ExtendedPredictedObjects & other_lane_objects, const std::string & ns); } // namespace marker_utils::lane_change_markers -#endif // BEHAVIOR_PATH_PLANNER__MARKER_UTILS__LANE_CHANGE__DEBUG_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__MARKERS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/path.hpp similarity index 82% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/path.hpp index c98f62c47860c..9e42b49635b82 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/lane_change_path.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/path.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2021 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_PATH_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_PATH_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ -#include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" +#include "behavior_path_lane_change_module/utils/data_structs.hpp" #include "behavior_path_planner_common/turn_signal_decider.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -50,4 +50,4 @@ struct LaneChangeStatus }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__LANE_CHANGE_PATH_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp similarity index 96% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp rename to planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp index f99ed043eb5dd..de4db37571122 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2021 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__UTILS_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__UTILS_HPP_ +#ifndef BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ +#define BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ -#include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" -#include "behavior_path_planner/utils/lane_change/lane_change_path.hpp" +#include "behavior_path_lane_change_module/utils/data_structs.hpp" +#include "behavior_path_lane_change_module/utils/path.hpp" #include "behavior_path_planner_common/parameters.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/utils.hpp" @@ -208,4 +208,4 @@ lanelet::ConstLanelets generateExpandedLanelets( const double right_offset); } // namespace behavior_path_planner::utils::lane_change -#endif // BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__UTILS_HPP_ +#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ diff --git a/planning/behavior_path_lane_change_module/package.xml b/planning/behavior_path_lane_change_module/package.xml new file mode 100644 index 0000000000000..fb4bef9535a48 --- /dev/null +++ b/planning/behavior_path_lane_change_module/package.xml @@ -0,0 +1,38 @@ + + + + behavior_path_lane_change_module + 0.1.0 + The behavior_path_lane_change_module package + + Fumiya Watanabe + Zulfaqar Azmi + Kosuke Takeuchi + Tomoya Kimura + Shumpei Wakabayashi + Tomohito Ando + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + behavior_path_planner + behavior_path_planner_common + motion_utils + pluginlib + rclcpp + rtc_interface + tier4_autoware_utils + tier4_planning_msgs + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_path_lane_change_module/plugins.xml b/planning/behavior_path_lane_change_module/plugins.xml new file mode 100644 index 0000000000000..a598bc8176938 --- /dev/null +++ b/planning/behavior_path_lane_change_module/plugins.xml @@ -0,0 +1,6 @@ + + + + + + diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp similarity index 98% rename from planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp rename to planning/behavior_path_lane_change_module/src/interface.cpp index 101dd43919361..1e80067842152 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/lane_change/interface.hpp" +#include "behavior_path_lane_change_module/interface.hpp" -#include "behavior_path_planner/marker_utils/lane_change/debug.hpp" -#include "behavior_path_planner/utils/lane_change/utils.hpp" +#include "behavior_path_lane_change_module/utils/markers.hpp" +#include "behavior_path_lane_change_module/utils/utils.hpp" #include "behavior_path_planner_common/interface/scene_module_interface.hpp" #include "behavior_path_planner_common/interface/scene_module_visitor.hpp" #include "behavior_path_planner_common/marker_utils/utils.hpp" @@ -26,7 +26,6 @@ #include #include #include -#include namespace behavior_path_planner { diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp b/planning/behavior_path_lane_change_module/src/manager.cpp similarity index 95% rename from planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp rename to planning/behavior_path_lane_change_module/src/manager.cpp index 658ffb06c25fe..e4405a31a360d 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/manager.cpp +++ b/planning/behavior_path_lane_change_module/src/manager.cpp @@ -12,8 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/lane_change/manager.hpp" +#include "behavior_path_lane_change_module/manager.hpp" +#include "behavior_path_lane_change_module/interface.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" @@ -262,16 +263,10 @@ void LaneChangeModuleManager::init(rclcpp::Node * node) std::unique_ptr LaneChangeModuleManager::createNewSceneModuleInstance() { - if (type_ == LaneChangeModuleType::NORMAL) { - return std::make_unique( - name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, - std::make_unique(parameters_, LaneChangeModuleType::NORMAL, direction_)); - } return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, objects_of_interest_marker_interface_ptr_map_, - std::make_unique(parameters_, direction_)); + std::make_unique(parameters_, LaneChangeModuleType::NORMAL, direction_)); } void LaneChangeModuleManager::updateModuleParams(const std::vector & parameters) @@ -298,9 +293,3 @@ PLUGINLIB_EXPORT_CLASS( PLUGINLIB_EXPORT_CLASS( behavior_path_planner::LaneChangeLeftModuleManager, behavior_path_planner::SceneModuleManagerInterface) -PLUGINLIB_EXPORT_CLASS( - behavior_path_planner::ExternalRequestLaneChangeRightModuleManager, - behavior_path_planner::SceneModuleManagerInterface) -PLUGINLIB_EXPORT_CLASS( - behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager, - behavior_path_planner::SceneModuleManagerInterface) diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp similarity index 99% rename from planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp rename to planning/behavior_path_lane_change_module/src/scene.cpp index ebb41ae63dcbe..21a600d11d83d 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/scene_module/lane_change/normal.hpp" +#include "behavior_path_lane_change_module/scene.hpp" -#include "behavior_path_planner/utils/lane_change/utils.hpp" +#include "behavior_path_lane_change_module/utils/utils.hpp" #include "behavior_path_planner_common/marker_utils/utils.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" diff --git a/planning/behavior_path_planner/src/marker_utils/lane_change/debug.cpp b/planning/behavior_path_lane_change_module/src/utils/markers.cpp similarity index 98% rename from planning/behavior_path_planner/src/marker_utils/lane_change/debug.cpp rename to planning/behavior_path_lane_change_module/src/utils/markers.cpp index c2a640f989b50..719acba405a68 100644 --- a/planning/behavior_path_planner/src/marker_utils/lane_change/debug.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/markers.cpp @@ -16,7 +16,7 @@ #include "behavior_path_planner_common/marker_utils/utils.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" -#include +#include #include #include diff --git a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp similarity index 99% rename from planning/behavior_path_planner/src/utils/lane_change/utils.cpp rename to planning/behavior_path_lane_change_module/src/utils/utils.cpp index 8ba820231d7cc..b5a4fd15b4c6b 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/lane_change/utils.hpp" +#include "behavior_path_lane_change_module/utils/utils.hpp" -#include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" -#include "behavior_path_planner/utils/lane_change/lane_change_path.hpp" +#include "behavior_path_lane_change_module/utils/data_structs.hpp" +#include "behavior_path_lane_change_module/utils/path.hpp" #include "behavior_path_planner_common/marker_utils/utils.hpp" #include "behavior_path_planner_common/parameters.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" diff --git a/planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp new file mode 100644 index 0000000000000..7a606b5d126ce --- /dev/null +++ b/planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -0,0 +1,126 @@ +// 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 "ament_index_cpp/get_package_share_directory.hpp" +#include "behavior_path_planner/behavior_path_planner_node.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager.hpp" +#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp" + +#include + +#include +#include + +using behavior_path_planner::BehaviorPathPlannerNode; +using planning_test_utils::PlanningInterfaceTestManager; + +std::shared_ptr generateTestManager() +{ + auto test_manager = std::make_shared(); + + // set subscriber with topic name: behavior_path_planner → test_node_ + test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); + + // set behavior_path_planner's input topic name(this topic is changed to test node) + test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); + + test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); + + return test_manager; +} + +std::shared_ptr generateNode() +{ + auto node_options = rclcpp::NodeOptions{}; + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto behavior_path_planner_dir = + ament_index_cpp::get_package_share_directory("behavior_path_planner"); + const auto behavior_path_lane_change_module_dir = + ament_index_cpp::get_package_share_directory("behavior_path_lane_change_module"); + + std::vector module_names; + module_names.emplace_back("behavior_path_planner::LaneChangeRightModuleManager"); + module_names.emplace_back("behavior_path_planner::LaneChangeLeftModuleManager"); + + std::vector params; + params.emplace_back("launch_modules", module_names); + node_options.parameter_overrides(params); + + test_utils::updateNodeOptions( + node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", + planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", + behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", + behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", + behavior_path_lane_change_module_dir + "/config/lane_change.param.yaml"}); + + return std::make_shared(node_options); +} + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ + // publish necessary topics from test_manager + test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); + test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); + test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); + test_manager->publishOccupancyGrid( + test_target_node, "behavior_path_planner/input/occupancy_grid_map"); + test_manager->publishLaneDrivingScenario( + test_target_node, "behavior_path_planner/input/scenario"); + test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); + test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); + test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); + test_manager->publishLateralOffset( + test_target_node, "behavior_path_planner/input/lateral_offset"); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) +{ + rclcpp::init(0, nullptr); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty route + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + + rclcpp::shutdown(); +} diff --git a/planning/behavior_path_planner/test/test_lane_change_utils.cpp b/planning/behavior_path_lane_change_module/test/test_lane_change_utils.cpp similarity index 95% rename from planning/behavior_path_planner/test/test_lane_change_utils.cpp rename to planning/behavior_path_lane_change_module/test/test_lane_change_utils.cpp index 477af32893b0b..1f90114df8045 100644 --- a/planning/behavior_path_planner/test/test_lane_change_utils.cpp +++ b/planning/behavior_path_lane_change_module/test/test_lane_change_utils.cpp @@ -11,8 +11,7 @@ // 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 "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp" -#include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" +#include "behavior_path_lane_change_module/utils/data_structs.hpp" #include #include diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index 56456b08aac1e..3e7a46f4899c3 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -14,13 +14,7 @@ ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/behavior_path_planner_node.cpp src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp src/scene_module/dynamic_avoidance/manager.cpp - src/scene_module/lane_change/interface.cpp - src/scene_module/lane_change/normal.cpp - src/scene_module/lane_change/external_request.cpp - src/scene_module/lane_change/manager.cpp - src/utils/lane_change/utils.cpp src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp - src/marker_utils/lane_change/debug.cpp ) target_include_directories(${PROJECT_NAME}_lib SYSTEM PUBLIC @@ -46,14 +40,6 @@ if(BUILD_TESTING) ${PROJECT_NAME}_lib ) - ament_add_ros_isolated_gmock(test_${CMAKE_PROJECT_NAME}_lane_change_module - test/test_lane_change_utils.cpp - ) - - target_link_libraries(test_${CMAKE_PROJECT_NAME}_lane_change_module - ${PROJECT_NAME}_lib - ) - ament_add_ros_isolated_gtest(test_${PROJECT_NAME}_node_interface test/test_${PROJECT_NAME}_node_interface.cpp ) diff --git a/planning/behavior_path_planner/plugins.xml b/planning/behavior_path_planner/plugins.xml index 2028b0d571e68..a16f3dd7bddee 100644 --- a/planning/behavior_path_planner/plugins.xml +++ b/planning/behavior_path_planner/plugins.xml @@ -1,7 +1,3 @@ - - - - diff --git a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp index bab77f9141a00..f2c22f774fc77 100644 --- a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp @@ -50,10 +50,6 @@ std::shared_ptr generateNode() std::vector module_names; module_names.emplace_back("behavior_path_planner::DynamicAvoidanceModuleManager"); - module_names.emplace_back("behavior_path_planner::LaneChangeRightModuleManager"); - module_names.emplace_back("behavior_path_planner::LaneChangeLeftModuleManager"); - module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeRightModuleManager"); - module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager"); std::vector params; params.emplace_back("launch_modules", module_names); @@ -67,8 +63,7 @@ std::shared_ptr generateNode() behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - behavior_path_planner_dir + "/config/dynamic_avoidance/dynamic_avoidance.param.yaml", - behavior_path_planner_dir + "/config/lane_change/lane_change.param.yaml"}); + behavior_path_planner_dir + "/config/dynamic_avoidance/dynamic_avoidance.param.yaml"}); return std::make_shared(node_options); } From 22522261d381cf445ab9cf119cdbc8e79c1f14f1 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 14 Dec 2023 16:31:00 +0900 Subject: [PATCH 55/87] feat(diagnostic_graph_aggregator): change default publish rate (#5872) Signed-off-by: Takagi, Isamu --- system/diagnostic_graph_aggregator/config/default.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/diagnostic_graph_aggregator/config/default.param.yaml b/system/diagnostic_graph_aggregator/config/default.param.yaml index e91664c5b82d8..2660396bd86df 100644 --- a/system/diagnostic_graph_aggregator/config/default.param.yaml +++ b/system/diagnostic_graph_aggregator/config/default.param.yaml @@ -2,6 +2,6 @@ ros__parameters: use_operation_mode_availability: true use_debug_mode: false - rate: 1.0 + rate: 10.0 input_qos_depth: 1000 graph_qos_depth: 1 From 4cd46880f879ec85046cba55db83e018b62ba5b5 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Thu, 14 Dec 2023 15:08:52 +0100 Subject: [PATCH 56/87] build(detected_object_validation): move header files to a separate directory to avoid conflicts (#5851) * build(detected_object_validation): move header files to a separate directory to avoid conflicts Signed-off-by: Esteve Fernandez * style(pre-commit): autofix --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../detected_object_filter/object_lanelet_filter.hpp | 8 ++++---- .../detected_object_filter/object_position_filter.hpp | 8 ++++---- .../obstacle_pointcloud_based_validator/debugger.hpp | 6 +++--- .../obstacle_pointcloud_based_validator.hpp | 11 +++++++---- .../occupancy_grid_based_validator.hpp | 6 +++--- .../{ => detected_object_validation}/utils/utils.hpp | 6 +++--- .../src/object_lanelet_filter.cpp | 2 +- .../src/object_position_filter.cpp | 2 +- .../src/obstacle_pointcloud_based_validator.cpp | 2 +- .../src/occupancy_grid_based_validator.cpp | 2 +- perception/detected_object_validation/src/utils.cpp | 2 +- 11 files changed, 29 insertions(+), 26 deletions(-) rename perception/detected_object_validation/include/{ => detected_object_validation}/detected_object_filter/object_lanelet_filter.hpp (88%) rename perception/detected_object_validation/include/{ => detected_object_validation}/detected_object_filter/object_position_filter.hpp (84%) rename perception/detected_object_validation/include/{ => detected_object_validation}/obstacle_pointcloud_based_validator/debugger.hpp (93%) rename perception/detected_object_validation/include/{ => detected_object_validation}/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp (90%) rename perception/detected_object_validation/include/{ => detected_object_validation}/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp (89%) rename perception/detected_object_validation/include/{ => detected_object_validation}/utils/utils.hpp (84%) diff --git a/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp similarity index 88% rename from perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp rename to perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp index ae6162542a1c3..4331b5c19d3f1 100644 --- a/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_ -#define DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_ +#ifndef DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_ +#define DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_ -#include "utils/utils.hpp" +#include "detected_object_validation/utils/utils.hpp" #include #include @@ -69,4 +69,4 @@ class ObjectLaneletFilterNode : public rclcpp::Node } // namespace object_lanelet_filter -#endif // DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_ +#endif // DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_ diff --git a/perception/detected_object_validation/include/detected_object_filter/object_position_filter.hpp b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_position_filter.hpp similarity index 84% rename from perception/detected_object_validation/include/detected_object_filter/object_position_filter.hpp rename to perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_position_filter.hpp index b9384e0f70379..be25eb6a353e6 100644 --- a/perception/detected_object_validation/include/detected_object_filter/object_position_filter.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_position_filter.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef DETECTED_OBJECT_FILTER__OBJECT_POSITION_FILTER_HPP_ -#define DETECTED_OBJECT_FILTER__OBJECT_POSITION_FILTER_HPP_ +#ifndef DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_POSITION_FILTER_HPP_ +#define DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_POSITION_FILTER_HPP_ -#include "utils/utils.hpp" +#include "detected_object_validation/utils/utils.hpp" #include #include @@ -55,4 +55,4 @@ class ObjectPositionFilterNode : public rclcpp::Node } // namespace object_position_filter -#endif // DETECTED_OBJECT_FILTER__OBJECT_POSITION_FILTER_HPP_ +#endif // DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_POSITION_FILTER_HPP_ diff --git a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp b/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp similarity index 93% rename from perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp rename to perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp index 6597475ae297e..8f5fa054090f5 100644 --- a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/debugger.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_ -#define OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_ +#ifndef DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_ +#define DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_ #include @@ -113,4 +113,4 @@ class Debugger }; } // namespace obstacle_pointcloud_based_validator -#endif // OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_ +#endif // DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_ diff --git a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp b/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp similarity index 90% rename from perception/detected_object_validation/include/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp rename to perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp index e7df2c409b18f..2d70247445043 100644 --- a/perception/detected_object_validation/include/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp @@ -12,10 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_ -#define OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_ +// NOLINTNEXTLINE(whitespace/line_length) +#ifndef DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_ +// NOLINTNEXTLINE(whitespace/line_length) +#define DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_ -#include "obstacle_pointcloud_based_validator/debugger.hpp" +#include "detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp" #include @@ -152,4 +154,5 @@ class ObstaclePointCloudBasedValidator : public rclcpp::Node }; } // namespace obstacle_pointcloud_based_validator -#endif // OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_ +// NOLINTNEXTLINE(whitespace/line_length) +#endif // DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_ diff --git a/perception/detected_object_validation/include/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp b/perception/detected_object_validation/include/detected_object_validation/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp similarity index 89% rename from perception/detected_object_validation/include/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp rename to perception/detected_object_validation/include/detected_object_validation/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp index f62b0d866dc3a..5fd866d09e725 100644 --- a/perception/detected_object_validation/include/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef OCCUPANCY_GRID_BASED_VALIDATOR__OCCUPANCY_GRID_BASED_VALIDATOR_HPP_ -#define OCCUPANCY_GRID_BASED_VALIDATOR__OCCUPANCY_GRID_BASED_VALIDATOR_HPP_ +#ifndef DETECTED_OBJECT_VALIDATION__OCCUPANCY_GRID_BASED_VALIDATOR__OCCUPANCY_GRID_BASED_VALIDATOR_HPP_ +#define DETECTED_OBJECT_VALIDATION__OCCUPANCY_GRID_BASED_VALIDATOR__OCCUPANCY_GRID_BASED_VALIDATOR_HPP_ #include #include @@ -68,4 +68,4 @@ class OccupancyGridBasedValidator : public rclcpp::Node }; } // namespace occupancy_grid_based_validator -#endif // OCCUPANCY_GRID_BASED_VALIDATOR__OCCUPANCY_GRID_BASED_VALIDATOR_HPP_ +#endif // DETECTED_OBJECT_VALIDATION__OCCUPANCY_GRID_BASED_VALIDATOR__OCCUPANCY_GRID_BASED_VALIDATOR_HPP_ diff --git a/perception/detected_object_validation/include/utils/utils.hpp b/perception/detected_object_validation/include/detected_object_validation/utils/utils.hpp similarity index 84% rename from perception/detected_object_validation/include/utils/utils.hpp rename to perception/detected_object_validation/include/detected_object_validation/utils/utils.hpp index 21df77825176b..2c46e1b9dd110 100644 --- a/perception/detected_object_validation/include/utils/utils.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/utils/utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef UTILS__UTILS_HPP_ -#define UTILS__UTILS_HPP_ +#ifndef DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_ +#define DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_ #include @@ -33,4 +33,4 @@ struct FilterTargetLabel }; // struct FilterTargetLabel } // namespace utils -#endif // UTILS__UTILS_HPP_ +#endif // DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_ diff --git a/perception/detected_object_validation/src/object_lanelet_filter.cpp b/perception/detected_object_validation/src/object_lanelet_filter.cpp index fe8de37c778ac..cd16d414425cb 100644 --- a/perception/detected_object_validation/src/object_lanelet_filter.cpp +++ b/perception/detected_object_validation/src/object_lanelet_filter.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "detected_object_filter/object_lanelet_filter.hpp" +#include "detected_object_validation/detected_object_filter/object_lanelet_filter.hpp" #include #include diff --git a/perception/detected_object_validation/src/object_position_filter.cpp b/perception/detected_object_validation/src/object_position_filter.cpp index 0f59e60d57d55..a509fc7571dd5 100644 --- a/perception/detected_object_validation/src/object_position_filter.cpp +++ b/perception/detected_object_validation/src/object_position_filter.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "detected_object_filter/object_position_filter.hpp" +#include "detected_object_validation/detected_object_filter/object_position_filter.hpp" namespace object_position_filter { 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 3249581513dd9..d903a9ca3bb41 100644 --- a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp +++ b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp" +#include "detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp" #include #include diff --git a/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp b/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp index 948f040d7ebde..80e4dc66d35c2 100644 --- a/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp +++ b/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "occupancy_grid_based_validator/occupancy_grid_based_validator.hpp" +#include "detected_object_validation/occupancy_grid_based_validator/occupancy_grid_based_validator.hpp" #include #include diff --git a/perception/detected_object_validation/src/utils.cpp b/perception/detected_object_validation/src/utils.cpp index d8f438e265c3a..53b21ee7ff5b6 100644 --- a/perception/detected_object_validation/src/utils.cpp +++ b/perception/detected_object_validation/src/utils.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "utils/utils.hpp" +#include "detected_object_validation/utils/utils.hpp" #include From 0ae2685b60d76034af66aef523bf916fd1de7385 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Thu, 14 Dec 2023 15:35:40 +0100 Subject: [PATCH 57/87] fix(traffic_light_visualization): move header directory to match package name (#5864) * fix(traffic_light_visualization): move header directory to match package name Signed-off-by: Esteve Fernandez * style(pre-commit): autofix * fix: fix include Signed-off-by: Esteve Fernandez --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../traffic_light_map_visualizer/node.hpp | 6 +++--- .../traffic_light_roi_visualizer/nodelet.hpp | 6 +++--- .../src/traffic_light_map_visualizer/main.cpp | 3 ++- .../src/traffic_light_map_visualizer/node.cpp | 3 ++- .../src/traffic_light_roi_visualizer/nodelet.cpp | 3 ++- 5 files changed, 12 insertions(+), 9 deletions(-) rename perception/traffic_light_visualization/include/{ => traffic_light_visualization}/traffic_light_map_visualizer/node.hpp (88%) rename perception/traffic_light_visualization/include/{ => traffic_light_visualization}/traffic_light_roi_visualizer/nodelet.hpp (95%) diff --git a/perception/traffic_light_visualization/include/traffic_light_map_visualizer/node.hpp b/perception/traffic_light_visualization/include/traffic_light_visualization/traffic_light_map_visualizer/node.hpp similarity index 88% rename from perception/traffic_light_visualization/include/traffic_light_map_visualizer/node.hpp rename to perception/traffic_light_visualization/include/traffic_light_visualization/traffic_light_map_visualizer/node.hpp index 3f83cf6e926ad..5e981bbeafda1 100644 --- a/perception/traffic_light_visualization/include/traffic_light_map_visualizer/node.hpp +++ b/perception/traffic_light_visualization/include/traffic_light_visualization/traffic_light_map_visualizer/node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef TRAFFIC_LIGHT_MAP_VISUALIZER__NODE_HPP_ -#define TRAFFIC_LIGHT_MAP_VISUALIZER__NODE_HPP_ +#ifndef TRAFFIC_LIGHT_VISUALIZATION__TRAFFIC_LIGHT_MAP_VISUALIZER__NODE_HPP_ +#define TRAFFIC_LIGHT_VISUALIZATION__TRAFFIC_LIGHT_MAP_VISUALIZER__NODE_HPP_ #include #include @@ -49,4 +49,4 @@ class TrafficLightMapVisualizerNode : public rclcpp::Node } // namespace traffic_light -#endif // TRAFFIC_LIGHT_MAP_VISUALIZER__NODE_HPP_ +#endif // TRAFFIC_LIGHT_VISUALIZATION__TRAFFIC_LIGHT_MAP_VISUALIZER__NODE_HPP_ diff --git a/perception/traffic_light_visualization/include/traffic_light_roi_visualizer/nodelet.hpp b/perception/traffic_light_visualization/include/traffic_light_visualization/traffic_light_roi_visualizer/nodelet.hpp similarity index 95% rename from perception/traffic_light_visualization/include/traffic_light_roi_visualizer/nodelet.hpp rename to perception/traffic_light_visualization/include/traffic_light_visualization/traffic_light_roi_visualizer/nodelet.hpp index 1c64eb2f9e82b..13d9045e89e98 100644 --- a/perception/traffic_light_visualization/include/traffic_light_roi_visualizer/nodelet.hpp +++ b/perception/traffic_light_visualization/include/traffic_light_visualization/traffic_light_roi_visualizer/nodelet.hpp @@ -11,8 +11,8 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#ifndef TRAFFIC_LIGHT_ROI_VISUALIZER__NODELET_HPP_ -#define TRAFFIC_LIGHT_ROI_VISUALIZER__NODELET_HPP_ +#ifndef TRAFFIC_LIGHT_VISUALIZATION__TRAFFIC_LIGHT_ROI_VISUALIZER__NODELET_HPP_ +#define TRAFFIC_LIGHT_VISUALIZATION__TRAFFIC_LIGHT_ROI_VISUALIZER__NODELET_HPP_ #include #include @@ -123,4 +123,4 @@ class TrafficLightRoiVisualizerNodelet : public rclcpp::Node } // namespace traffic_light -#endif // TRAFFIC_LIGHT_ROI_VISUALIZER__NODELET_HPP_ +#endif // TRAFFIC_LIGHT_VISUALIZATION__TRAFFIC_LIGHT_ROI_VISUALIZER__NODELET_HPP_ diff --git a/perception/traffic_light_visualization/src/traffic_light_map_visualizer/main.cpp b/perception/traffic_light_visualization/src/traffic_light_map_visualizer/main.cpp index 02f7a67302945..62d416457c6f0 100644 --- a/perception/traffic_light_visualization/src/traffic_light_map_visualizer/main.cpp +++ b/perception/traffic_light_visualization/src/traffic_light_map_visualizer/main.cpp @@ -12,8 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "traffic_light_visualization/traffic_light_map_visualizer/node.hpp" + #include -#include #include diff --git a/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp b/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp index 53e06e47a1873..e621a20450bbf 100644 --- a/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp +++ b/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "traffic_light_visualization/traffic_light_map_visualizer/node.hpp" + #include #include #include -#include #include diff --git a/perception/traffic_light_visualization/src/traffic_light_roi_visualizer/nodelet.cpp b/perception/traffic_light_visualization/src/traffic_light_roi_visualizer/nodelet.cpp index 2f2d80ba43233..4ff9729695be2 100644 --- a/perception/traffic_light_visualization/src/traffic_light_roi_visualizer/nodelet.cpp +++ b/perception/traffic_light_visualization/src/traffic_light_roi_visualizer/nodelet.cpp @@ -12,9 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "traffic_light_visualization/traffic_light_roi_visualizer/nodelet.hpp" // NOLINT(whitespace/line_length) + #include #include -#include #include #include From 34241d6d11abd729b45d8ff41bb2c7ec0fa94a51 Mon Sep 17 00:00:00 2001 From: Yuntianyi Chen Date: Thu, 14 Dec 2023 16:07:43 -0800 Subject: [PATCH 58/87] refactor(compare_map_segmentation): rework parameters (#5005) * refactor the configuration files of the node compare_map_segmentation according to the new ROS node config guideline. Signed-off-by: yuntianyi-chen * style(pre-commit): autofix * Add three parameters Signed-off-by: yuntianyi-chen * style(pre-commit): autofix * Update perception/compare_map_segmentation/config/distance_based_compare_map_filter.param.yaml Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> * Update perception/compare_map_segmentation/config/voxel_based_approximate_compare_map_filter.param.yaml Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> * Update perception/compare_map_segmentation/config/voxel_based_compare_map_filter.param.yaml Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> * Update perception/compare_map_segmentation/config/voxel_distance_based_compare_map_filter.param.yaml Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> * Update perception/compare_map_segmentation/schema/voxel_based_approximate_compare_map_filter.schema.json Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> --------- Signed-off-by: yuntianyi-chen Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> --- .../compare_map_segmentation/CMakeLists.txt | 4 +- .../compare_elevation_map_filter.param.yaml | 5 ++ ...stance_based_compare_map_filter.param.yaml | 8 +++ ..._approximate_compare_map_filter.param.yaml | 9 +++ .../voxel_based_compare_map_filter.param.yaml | 9 +++ ...stance_based_compare_map_filter.param.yaml | 9 +++ .../compare_elevation_map_filter.launch.xml | 4 +- ...stance_based_compare_map_filter.launch.xml | 4 +- ..._approximate_compare_map_filter.launch.xml | 4 +- .../voxel_based_compare_map_filter.launch.xml | 15 +---- ...stance_based_compare_map_filter.launch.xml | 4 +- .../compare_elevation_map_filter.schema.json | 43 ++++++++++++ ...tance_based_compare_map_filter.schema.json | 38 +++++++++++ ...approximate_compare_map_filter.schema.json | 43 ++++++++++++ ...voxel_based_compare_map_filter.schema.json | 65 +++++++++++++++++++ ...tance_based_compare_map_filter.schema.json | 43 ++++++++++++ .../src/compare_elevation_map_filter_node.cpp | 6 +- 17 files changed, 293 insertions(+), 20 deletions(-) create mode 100644 perception/compare_map_segmentation/config/compare_elevation_map_filter.param.yaml create mode 100644 perception/compare_map_segmentation/config/distance_based_compare_map_filter.param.yaml create mode 100644 perception/compare_map_segmentation/config/voxel_based_approximate_compare_map_filter.param.yaml create mode 100644 perception/compare_map_segmentation/config/voxel_based_compare_map_filter.param.yaml create mode 100644 perception/compare_map_segmentation/config/voxel_distance_based_compare_map_filter.param.yaml create mode 100644 perception/compare_map_segmentation/schema/compare_elevation_map_filter.schema.json create mode 100644 perception/compare_map_segmentation/schema/distance_based_compare_map_filter.schema.json create mode 100644 perception/compare_map_segmentation/schema/voxel_based_approximate_compare_map_filter.schema.json create mode 100644 perception/compare_map_segmentation/schema/voxel_based_compare_map_filter.schema.json create mode 100644 perception/compare_map_segmentation/schema/voxel_distance_based_compare_map_filter.schema.json diff --git a/perception/compare_map_segmentation/CMakeLists.txt b/perception/compare_map_segmentation/CMakeLists.txt index 4655cf4c2f73a..d56cb3fb31584 100644 --- a/perception/compare_map_segmentation/CMakeLists.txt +++ b/perception/compare_map_segmentation/CMakeLists.txt @@ -89,6 +89,8 @@ install( RUNTIME DESTINATION bin ) -ament_auto_package(INSTALL_TO_SHARE +ament_auto_package( + INSTALL_TO_SHARE launch + config ) diff --git a/perception/compare_map_segmentation/config/compare_elevation_map_filter.param.yaml b/perception/compare_map_segmentation/config/compare_elevation_map_filter.param.yaml new file mode 100644 index 0000000000000..3d5270d17479e --- /dev/null +++ b/perception/compare_map_segmentation/config/compare_elevation_map_filter.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + map_layer_name: "elevation" + height_diff_thresh: 0.15 + map_frame: "map" diff --git a/perception/compare_map_segmentation/config/distance_based_compare_map_filter.param.yaml b/perception/compare_map_segmentation/config/distance_based_compare_map_filter.param.yaml new file mode 100644 index 0000000000000..f95c0b0c94b92 --- /dev/null +++ b/perception/compare_map_segmentation/config/distance_based_compare_map_filter.param.yaml @@ -0,0 +1,8 @@ +/**: + ros__parameters: + distance_threshold: 0.5 + use_dynamic_map_loading: true + timer_interval_ms: 100 + map_update_distance_threshold: 10.0 + map_loader_radius: 150.0 + publish_debug_pcd: False diff --git a/perception/compare_map_segmentation/config/voxel_based_approximate_compare_map_filter.param.yaml b/perception/compare_map_segmentation/config/voxel_based_approximate_compare_map_filter.param.yaml new file mode 100644 index 0000000000000..d54f7a96ecda0 --- /dev/null +++ b/perception/compare_map_segmentation/config/voxel_based_approximate_compare_map_filter.param.yaml @@ -0,0 +1,9 @@ +/**: + ros__parameters: + distance_threshold: 0.5 + use_dynamic_map_loading: true + downsize_ratio_z_axis: 0.5 + timer_interval_ms: 100 + map_update_distance_threshold: 10.0 + map_loader_radius: 150.0 + publish_debug_pcd: False diff --git a/perception/compare_map_segmentation/config/voxel_based_compare_map_filter.param.yaml b/perception/compare_map_segmentation/config/voxel_based_compare_map_filter.param.yaml new file mode 100644 index 0000000000000..d54f7a96ecda0 --- /dev/null +++ b/perception/compare_map_segmentation/config/voxel_based_compare_map_filter.param.yaml @@ -0,0 +1,9 @@ +/**: + ros__parameters: + distance_threshold: 0.5 + use_dynamic_map_loading: true + downsize_ratio_z_axis: 0.5 + timer_interval_ms: 100 + map_update_distance_threshold: 10.0 + map_loader_radius: 150.0 + publish_debug_pcd: False diff --git a/perception/compare_map_segmentation/config/voxel_distance_based_compare_map_filter.param.yaml b/perception/compare_map_segmentation/config/voxel_distance_based_compare_map_filter.param.yaml new file mode 100644 index 0000000000000..d54f7a96ecda0 --- /dev/null +++ b/perception/compare_map_segmentation/config/voxel_distance_based_compare_map_filter.param.yaml @@ -0,0 +1,9 @@ +/**: + ros__parameters: + distance_threshold: 0.5 + use_dynamic_map_loading: true + downsize_ratio_z_axis: 0.5 + timer_interval_ms: 100 + map_update_distance_threshold: 10.0 + map_loader_radius: 150.0 + publish_debug_pcd: False diff --git a/perception/compare_map_segmentation/launch/compare_elevation_map_filter.launch.xml b/perception/compare_map_segmentation/launch/compare_elevation_map_filter.launch.xml index 42478c514b788..9cb41c8780f13 100644 --- a/perception/compare_map_segmentation/launch/compare_elevation_map_filter.launch.xml +++ b/perception/compare_map_segmentation/launch/compare_elevation_map_filter.launch.xml @@ -1,11 +1,13 @@ + + - + diff --git a/perception/compare_map_segmentation/launch/distance_based_compare_map_filter.launch.xml b/perception/compare_map_segmentation/launch/distance_based_compare_map_filter.launch.xml index 4a272646503f1..cdf17ebfeda9f 100644 --- a/perception/compare_map_segmentation/launch/distance_based_compare_map_filter.launch.xml +++ b/perception/compare_map_segmentation/launch/distance_based_compare_map_filter.launch.xml @@ -1,11 +1,13 @@ + + - + diff --git a/perception/compare_map_segmentation/launch/voxel_based_approximate_compare_map_filter.launch.xml b/perception/compare_map_segmentation/launch/voxel_based_approximate_compare_map_filter.launch.xml index 2942781ce8123..e3f4594729c2b 100644 --- a/perception/compare_map_segmentation/launch/voxel_based_approximate_compare_map_filter.launch.xml +++ b/perception/compare_map_segmentation/launch/voxel_based_approximate_compare_map_filter.launch.xml @@ -1,11 +1,13 @@ + + - + diff --git a/perception/compare_map_segmentation/launch/voxel_based_compare_map_filter.launch.xml b/perception/compare_map_segmentation/launch/voxel_based_compare_map_filter.launch.xml index 2fc2884fd5df9..01ad5cd9b1792 100644 --- a/perception/compare_map_segmentation/launch/voxel_based_compare_map_filter.launch.xml +++ b/perception/compare_map_segmentation/launch/voxel_based_compare_map_filter.launch.xml @@ -1,25 +1,16 @@ + + - - - - - - - - - - - - + diff --git a/perception/compare_map_segmentation/launch/voxel_distance_based_compare_map_filter.launch.xml b/perception/compare_map_segmentation/launch/voxel_distance_based_compare_map_filter.launch.xml index 09ea9022b97e5..13023a8c1c2c9 100644 --- a/perception/compare_map_segmentation/launch/voxel_distance_based_compare_map_filter.launch.xml +++ b/perception/compare_map_segmentation/launch/voxel_distance_based_compare_map_filter.launch.xml @@ -1,11 +1,13 @@ + + - + diff --git a/perception/compare_map_segmentation/schema/compare_elevation_map_filter.schema.json b/perception/compare_map_segmentation/schema/compare_elevation_map_filter.schema.json new file mode 100644 index 0000000000000..24ac2481a4e4a --- /dev/null +++ b/perception/compare_map_segmentation/schema/compare_elevation_map_filter.schema.json @@ -0,0 +1,43 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Compare Elevation Map Filter", + "type": "object", + "definitions": { + "compare_elevation_map_filter": { + "type": "object", + "properties": { + "map_layer_name": { + "type": "string", + "default": "elevation", + "description": "elevation map layer name" + }, + "height_diff_thresh": { + "type": "number", + "default": "0.15", + "description": "Remove points whose height difference is below this value [m]" + }, + "map_frame": { + "type": "string", + "default": "map", + "description": "frame_id of the map that is temporarily used before elevation_map is subscribed" + } + }, + "required": ["map_layer_name", "height_diff_thresh", "map_frame"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/compare_elevation_map_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/compare_map_segmentation/schema/distance_based_compare_map_filter.schema.json b/perception/compare_map_segmentation/schema/distance_based_compare_map_filter.schema.json new file mode 100644 index 0000000000000..10454b48d3d80 --- /dev/null +++ b/perception/compare_map_segmentation/schema/distance_based_compare_map_filter.schema.json @@ -0,0 +1,38 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Distance Based Compare Map Filter", + "type": "object", + "definitions": { + "distance_based_compare_map_filter": { + "type": "object", + "properties": { + "distance_threshold": { + "type": "number", + "default": "0.5", + "description": "Threshold distance to compare input points with map points [m]" + }, + "use_dynamic_map_loading": { + "type": "boolean", + "default": "true", + "description": "map loading mode selection, true for dynamic map loading, false for static map loading, recommended for no-split map pointcloud" + } + }, + "required": ["distance_threshold", "use_dynamic_map_loading"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/distance_based_compare_map_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/compare_map_segmentation/schema/voxel_based_approximate_compare_map_filter.schema.json b/perception/compare_map_segmentation/schema/voxel_based_approximate_compare_map_filter.schema.json new file mode 100644 index 0000000000000..3c301d5ad9fbb --- /dev/null +++ b/perception/compare_map_segmentation/schema/voxel_based_approximate_compare_map_filter.schema.json @@ -0,0 +1,43 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Voxel Based Approximate Compare Map Filter", + "type": "object", + "definitions": { + "voxel_based_approximate_compare_map_filter": { + "type": "object", + "properties": { + "distance_threshold": { + "type": "number", + "default": "0.5", + "description": "Threshold distance to compare input points with map points [m]" + }, + "use_dynamic_map_loading": { + "type": "boolean", + "default": "true", + "description": "map loading mode selection, true for dynamic map loading, false for static map loading, recommended for no-split map pointcloud" + }, + "downsize_ratio_z_axis": { + "type": "number", + "default": "0.5", + "description": "Positive ratio to reduce voxel_leaf_size and neighbor point distance threshold in z axis" + } + }, + "required": ["distance_threshold", "use_dynamic_map_loading", "downsize_ratio_z_axis"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/voxel_based_approximate_compare_map_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/compare_map_segmentation/schema/voxel_based_compare_map_filter.schema.json b/perception/compare_map_segmentation/schema/voxel_based_compare_map_filter.schema.json new file mode 100644 index 0000000000000..2e541662a1743 --- /dev/null +++ b/perception/compare_map_segmentation/schema/voxel_based_compare_map_filter.schema.json @@ -0,0 +1,65 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Voxel Based Compare Map Filter", + "type": "object", + "definitions": { + "voxel_based_compare_map_filter": { + "type": "object", + "properties": { + "distance_threshold": { + "type": "number", + "default": "0.5", + "description": "Threshold distance to compare input points with map points [m]" + }, + "use_dynamic_map_loading": { + "type": "boolean", + "default": "true", + "description": "map loading mode selection, true for dynamic map loading, false for static map loading, recommended for no-split map pointcloud" + }, + "downsize_ratio_z_axis": { + "type": "number", + "default": "0.5", + "description": "Positive ratio to reduce voxel_leaf_size and neighbor point distance threshold in z axis" + }, + "map_update_distance_threshold": { + "type": "number", + "default": "10.0", + "description": "Threshold distance to update map points with input points [m]" + }, + "map_loader_radius": { + "type": "number", + "default": "150.0", + "description": "Radius to load map points [m]" + }, + "timer_interval_ms": { + "type": "number", + "default": "100", + "description": "Timer interval to load map points [ms]" + } + }, + "required": [ + "distance_threshold", + "use_dynamic_map_loading", + "downsize_ratio_z_axis", + "map_update_distance_threshold", + "map_loader_radius", + "timer_interval_ms" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/voxel_based_compare_map_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/compare_map_segmentation/schema/voxel_distance_based_compare_map_filter.schema.json b/perception/compare_map_segmentation/schema/voxel_distance_based_compare_map_filter.schema.json new file mode 100644 index 0000000000000..4663dbe806223 --- /dev/null +++ b/perception/compare_map_segmentation/schema/voxel_distance_based_compare_map_filter.schema.json @@ -0,0 +1,43 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Voxel Distance Based Compare Map Filter", + "type": "object", + "definitions": { + "voxel_distance_based_compare_map_filter": { + "type": "object", + "properties": { + "distance_threshold": { + "type": "number", + "default": "0.5", + "description": "Threshold distance to compare input points with map points [m]" + }, + "use_dynamic_map_loading": { + "type": "boolean", + "default": "true", + "description": "map loading mode selection, true for dynamic map loading, false for static map loading, recommended for no-split map pointcloud" + }, + "downsize_ratio_z_axis": { + "type": "number", + "default": "0.5", + "description": "Positive ratio to reduce voxel_leaf_size and neighbor point distance threshold in z axis" + } + }, + "required": ["distance_threshold", "use_dynamic_map_loading", "downsize_ratio_z_axis"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/voxel_distance_based_compare_map_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/compare_map_segmentation/src/compare_elevation_map_filter_node.cpp b/perception/compare_map_segmentation/src/compare_elevation_map_filter_node.cpp index 7c8f2e8d4bd76..1eadeeb3bec05 100644 --- a/perception/compare_map_segmentation/src/compare_elevation_map_filter_node.cpp +++ b/perception/compare_map_segmentation/src/compare_elevation_map_filter_node.cpp @@ -40,9 +40,9 @@ CompareElevationMapFilterComponent::CompareElevationMapFilterComponent( : Filter("CompareElevationMapFilter", options) { unsubscribe(); - layer_name_ = this->declare_parameter("map_layer_name", std::string("elevation")); - height_diff_thresh_ = this->declare_parameter("height_diff_thresh", 0.15); - map_frame_ = this->declare_parameter("map_frame", "map"); + layer_name_ = declare_parameter("map_layer_name"); + height_diff_thresh_ = declare_parameter("height_diff_thresh"); + map_frame_ = declare_parameter("map_frame"); rclcpp::QoS durable_qos{1}; durable_qos.transient_local(); From 1f8285476004136b9cef7ccc6648cd4fb2db9b37 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Fri, 15 Dec 2023 09:42:32 +0900 Subject: [PATCH 59/87] feat(behavior_velocity_planner_common): add objects_of_interest_marker_intereface to behavior_velocity_planner (#5875) * feat(behavior_velocity_planner_common): add objects_of_interest_marker_intereface to behavior_velocity_planner Signed-off-by: Fumiya Watanabe * fix(behavior_velocity_planner_common): add functions to publish objects of interest marker Signed-off-by: Fumiya Watanabe * feat(no_stopping_area): insert object data Signed-off-by: Fumiya Watanabe * refactor(behavior_velocity_planner_common): rename function Signed-off-by: Fumiya Watanabe --------- Signed-off-by: Fumiya Watanabe --- .../src/scene_no_stopping_area.cpp | 4 +++ .../scene_module_interface.hpp | 30 +++++++++++++++++++ .../package.xml | 1 + .../src/scene_module_interface.cpp | 18 ++++++++++- 4 files changed, 52 insertions(+), 1 deletion(-) diff --git a/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp b/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp index 47d4985ae643e..e049d02ffe9b5 100644 --- a/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp +++ b/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp @@ -230,6 +230,8 @@ bool NoStoppingAreaModule::checkStuckVehiclesInNoStoppingArea( } const auto obj_v = std::fabs(object.kinematics.initial_twist_with_covariance.twist.linear.x); if (obj_v > planner_param_.stuck_vehicle_vel_thr) { + setObjectsOfInterestData( + object.kinematics.initial_pose_with_covariance.pose, object.shape, ColorName::GREEN); continue; // not stop vehicle } // check if the footprint is in the stuck detect area @@ -237,6 +239,8 @@ bool NoStoppingAreaModule::checkStuckVehiclesInNoStoppingArea( const bool is_in_stuck_area = !bg::disjoint(obj_footprint, poly); if (is_in_stuck_area) { RCLCPP_DEBUG(logger_, "stuck vehicle found."); + setObjectsOfInterestData( + object.kinematics.initial_pose_with_covariance.pose, object.shape, ColorName::RED); for (const auto & p : obj_footprint.outer()) { geometry_msgs::msg::Point point; point.x = p.x(); diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp index ced2e267cc025..fcde16d8a871c 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include @@ -47,6 +48,8 @@ namespace behavior_velocity_planner using autoware_auto_planning_msgs::msg::PathWithLaneId; using builtin_interfaces::msg::Time; +using objects_of_interest_marker_interface::ColorName; +using objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; using rtc_interface::RTCInterface; using tier4_autoware_utils::DebugPublisher; using tier4_debug_msgs::msg::Float64Stamped; @@ -55,6 +58,19 @@ using tier4_planning_msgs::msg::StopReason; using tier4_rtc_msgs::msg::Module; using unique_identifier_msgs::msg::UUID; +struct ObjectOfInterest +{ + geometry_msgs::msg::Pose pose; + autoware_auto_perception_msgs::msg::Shape shape; + ColorName color; + ObjectOfInterest( + const geometry_msgs::msg::Pose & pose, const autoware_auto_perception_msgs::msg::Shape & shape, + const ColorName & color_name) + : pose(pose), shape(shape), color(color_name) + { + } +}; + class SceneModuleInterface { public: @@ -94,6 +110,8 @@ class SceneModuleInterface void resetVelocityFactor() { velocity_factor_.reset(); } VelocityFactor getVelocityFactor() const { return velocity_factor_.get(); } + std::vector getObjectsOfInterestData() const { return objects_of_interest_; } + void clearObjectsOfInterestData() { objects_of_interest_.clear(); } protected: const int64_t module_id_; @@ -107,6 +125,7 @@ class SceneModuleInterface std::optional infrastructure_command_; std::optional first_stop_path_point_index_; VelocityFactorInterface velocity_factor_; + std::vector objects_of_interest_; void setSafe(const bool safe) { @@ -118,6 +137,13 @@ class SceneModuleInterface void setDistance(const double distance) { distance_ = distance; } void syncActivation() { setActivation(isSafe()); } + void setObjectsOfInterestData( + const geometry_msgs::msg::Pose & pose, const autoware_auto_perception_msgs::msg::Shape & shape, + const ColorName & color_name) + { + objects_of_interest_.emplace_back(pose, shape, color_name); + } + size_t findEgoSegmentIndex( const std::vector & points) const; }; @@ -200,6 +226,8 @@ class SceneModuleManagerInterfaceWithRTC : public SceneModuleManagerInterface RTCInterface rtc_interface_; std::unordered_map map_uuid_; + ObjectsOfInterestMarkerInterface objects_of_interest_marker_interface_; + virtual void sendRTC(const Time & stamp); virtual void setActivation(); @@ -220,6 +248,8 @@ class SceneModuleManagerInterfaceWithRTC : public SceneModuleManagerInterface void removeUUID(const int64_t & module_id); + void publishObjectsOfInterestMarker(); + void deleteExpiredModules(const autoware_auto_planning_msgs::msg::PathWithLaneId & path) override; }; diff --git a/planning/behavior_velocity_planner_common/package.xml b/planning/behavior_velocity_planner_common/package.xml index 187720ff92a15..784b7cabfe9ad 100644 --- a/planning/behavior_velocity_planner_common/package.xml +++ b/planning/behavior_velocity_planner_common/package.xml @@ -32,6 +32,7 @@ motion_utils motion_velocity_smoother nav_msgs + objects_of_interest_marker_interface pcl_conversions rclcpp rclcpp_components diff --git a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp b/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp index 49a52fcd60df2..6f596be92ec8b 100644 --- a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -192,7 +192,9 @@ void SceneModuleManagerInterface::unregisterModule( SceneModuleManagerInterfaceWithRTC::SceneModuleManagerInterfaceWithRTC( rclcpp::Node & node, const char * module_name, const bool enable_rtc) -: SceneModuleManagerInterface(node, module_name), rtc_interface_(&node, module_name, enable_rtc) +: SceneModuleManagerInterface(node, module_name), + rtc_interface_(&node, module_name, enable_rtc), + objects_of_interest_marker_interface_(&node, module_name) { } @@ -202,6 +204,7 @@ void SceneModuleManagerInterfaceWithRTC::plan( setActivation(); modifyPathVelocity(path); sendRTC(path->header.stamp); + publishObjectsOfInterestMarker(); } void SceneModuleManagerInterfaceWithRTC::sendRTC(const Time & stamp) @@ -244,6 +247,19 @@ void SceneModuleManagerInterfaceWithRTC::removeUUID(const int64_t & module_id) } } +void SceneModuleManagerInterfaceWithRTC::publishObjectsOfInterestMarker() +{ + for (const auto & scene_module : scene_modules_) { + const auto objects = scene_module->getObjectsOfInterestData(); + for (const auto & obj : objects) { + objects_of_interest_marker_interface_.insertObjectData(obj.pose, obj.shape, obj.color); + } + scene_module->clearObjectsOfInterestData(); + } + + objects_of_interest_marker_interface_.publishMarkerArray(); +} + void SceneModuleManagerInterfaceWithRTC::deleteExpiredModules( const autoware_auto_planning_msgs::msg::PathWithLaneId & path) { From 57278db59c8836eefc617bbe114ca5289e113943 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 15 Dec 2023 13:15:27 +0900 Subject: [PATCH 60/87] refactor(behavior_path_planner): move utils function to `behavior_path_planner_common` package (#5877) * refactor(bpp): remove unused header file Signed-off-by: satoshi-ota * refactor(bpp, bpp-common): move occ grid based collision detector Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../geometric_pull_over.hpp | 2 +- .../goal_planner_module.hpp | 2 +- .../goal_searcher.hpp | 2 +- .../shift_pull_over.hpp | 2 +- planning/behavior_path_planner/CMakeLists.txt | 1 - .../utils/lane_following/module_data.hpp | 32 ------------------- .../CMakeLists.txt | 1 + ...ccupancy_grid_based_collision_detector.hpp | 6 ++-- ...ccupancy_grid_based_collision_detector.cpp | 2 +- 9 files changed, 9 insertions(+), 41 deletions(-) delete mode 100644 planning/behavior_path_planner/include/behavior_path_planner/utils/lane_following/module_data.hpp rename planning/{behavior_path_planner/include/behavior_path_planner => behavior_path_planner_common/include/behavior_path_planner_common}/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp (91%) rename planning/{behavior_path_planner => behavior_path_planner_common}/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp (98%) diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp index c5ba04ba7f52e..6de1a726d4d4e 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp @@ -16,7 +16,7 @@ #define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GEOMETRIC_PULL_OVER_HPP_ #include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" -#include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" +#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include 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 8100ed7c66128..e90162c958be5 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 @@ -21,8 +21,8 @@ #include "behavior_path_goal_planner_module/goal_planner_parameters.hpp" #include "behavior_path_goal_planner_module/goal_searcher.hpp" #include "behavior_path_goal_planner_module/shift_pull_over.hpp" -#include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include "behavior_path_planner_common/interface/scene_module_interface.hpp" +#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include "behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" #include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp index 2d9e2c6cf3700..94cf7bc7ff5dd 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp @@ -16,7 +16,7 @@ #define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_HPP_ #include "behavior_path_goal_planner_module/goal_searcher_base.hpp" -#include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" +#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include #include diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp index cc8686f4a9fef..bd19dc2e87de0 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp @@ -16,7 +16,7 @@ #define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__SHIFT_PULL_OVER_HPP_ #include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" -#include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" +#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include diff --git a/planning/behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/CMakeLists.txt index 3e7a46f4899c3..f3727f35a492f 100644 --- a/planning/behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/CMakeLists.txt @@ -14,7 +14,6 @@ ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/behavior_path_planner_node.cpp src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp src/scene_module/dynamic_avoidance/manager.cpp - src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp ) target_include_directories(${PROJECT_NAME}_lib SYSTEM PUBLIC diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_following/module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_following/module_data.hpp deleted file mode 100644 index 98d52b79e2edf..0000000000000 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_following/module_data.hpp +++ /dev/null @@ -1,32 +0,0 @@ -// Copyright 2021-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 BEHAVIOR_PATH_PLANNER__UTILS__LANE_FOLLOWING__MODULE_DATA_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__LANE_FOLLOWING__MODULE_DATA_HPP_ - -namespace behavior_path_planner -{ - -struct LaneFollowingParameters -{ - double lane_change_prepare_duration{0.0}; - - // finding closest lanelet - double distance_threshold{0.0}; - double yaw_threshold{0.0}; -}; - -} // namespace behavior_path_planner - -#endif // BEHAVIOR_PATH_PLANNER__UTILS__LANE_FOLLOWING__MODULE_DATA_HPP_ diff --git a/planning/behavior_path_planner_common/CMakeLists.txt b/planning/behavior_path_planner_common/CMakeLists.txt index 5dbf81280f9b1..d1996bf72037f 100644 --- a/planning/behavior_path_planner_common/CMakeLists.txt +++ b/planning/behavior_path_planner_common/CMakeLists.txt @@ -23,6 +23,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/utils/drivable_area_expansion/footprints.cpp src/utils/parking_departure/geometric_parallel_parking.cpp src/utils/parking_departure/utils.cpp + src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp src/marker_utils/utils.cpp ) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp similarity index 91% rename from planning/behavior_path_planner/include/behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp rename to planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp index 91d99fcd4a0d6..c24aa021cf57c 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_PLANNER__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_ -#define BEHAVIOR_PATH_PLANNER__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_ +#ifndef BEHAVIOR_PATH_PLANNER_COMMON__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_ +#define BEHAVIOR_PATH_PLANNER_COMMON__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_ #include @@ -149,4 +149,4 @@ class OccupancyGridBasedCollisionDetector } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_PLANNER__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_ +#endif // BEHAVIOR_PATH_PLANNER_COMMON__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_ diff --git a/planning/behavior_path_planner/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp b/planning/behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp similarity index 98% rename from planning/behavior_path_planner/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp rename to planning/behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp index 0f87c68e38289..1aab58ac2ff6e 100644 --- a/planning/behavior_path_planner/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp +++ b/planning/behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_planner/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" +#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include #include From f2cc50cf4b5a6b3835fa1e3a390e7cdbe9b1d3b0 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Fri, 15 Dec 2023 04:50:31 +0000 Subject: [PATCH 61/87] chore: sync files (#5600) Signed-off-by: GitHub Co-authored-by: github-actions --- .github/workflows/cancel-previous-workflows.yaml | 2 +- .github/workflows/github-release.yaml | 2 +- .github/workflows/pre-commit-optional.yaml | 2 +- .github/workflows/pre-commit.yaml | 2 +- .github/workflows/spell-check-differential.yaml | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/.github/workflows/cancel-previous-workflows.yaml b/.github/workflows/cancel-previous-workflows.yaml index f9c29b81b6e6c..1da4d24966de9 100644 --- a/.github/workflows/cancel-previous-workflows.yaml +++ b/.github/workflows/cancel-previous-workflows.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Cancel previous runs - uses: styfle/cancel-workflow-action@0.11.0 + uses: styfle/cancel-workflow-action@0.12.0 with: workflow_id: all all_but_latest: true diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml index 95ebb8725f62b..b426d0cba6614 100644 --- a/.github/workflows/github-release.yaml +++ b/.github/workflows/github-release.yaml @@ -30,7 +30,7 @@ jobs: echo "tag-name=${REF_NAME#beta/}" >> $GITHUB_OUTPUT - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: fetch-depth: 0 ref: ${{ steps.set-tag-name.outputs.ref-name }} diff --git a/.github/workflows/pre-commit-optional.yaml b/.github/workflows/pre-commit-optional.yaml index e754ecab24f85..38738196a0bd3 100644 --- a/.github/workflows/pre-commit-optional.yaml +++ b/.github/workflows/pre-commit-optional.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: fetch-depth: 0 diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml index b231dbda87938..33c00ee1066ae 100644 --- a/.github/workflows/pre-commit.yaml +++ b/.github/workflows/pre-commit.yaml @@ -16,7 +16,7 @@ jobs: private_key: ${{ secrets.PRIVATE_KEY }} - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: ref: ${{ github.event.pull_request.head.ref }} diff --git a/.github/workflows/spell-check-differential.yaml b/.github/workflows/spell-check-differential.yaml index eb18ccdba38d0..1fbf2ff46925c 100644 --- a/.github/workflows/spell-check-differential.yaml +++ b/.github/workflows/spell-check-differential.yaml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Run spell-check uses: autowarefoundation/autoware-github-actions/spell-check@v1 From 7ce87a42d35dbf1b3793bf35bd04fb2a75d1f704 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 15 Dec 2023 16:38:27 +0900 Subject: [PATCH 62/87] feat(crosswalk): ignore predicted path going across the crosswalk (#5849) Signed-off-by: Mamoru Sobue --- .../config/crosswalk.param.yaml | 1 + .../util.hpp | 2 + .../src/manager.cpp | 2 + .../src/scene_crosswalk.cpp | 111 ++++++++++++++++-- .../src/scene_crosswalk.hpp | 15 ++- 5 files changed, 118 insertions(+), 13 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml index 6559f39278fdc..240963309e9a2 100644 --- a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml +++ b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml @@ -63,6 +63,7 @@ # param for target object filtering object_filtering: crosswalk_attention_range: 1.0 # [m] the detection area is defined as -X meters before the crosswalk to +X meters behind the crosswalk + vehicle_object_cross_angle_threshold: 0.5 # [rad] threshold judging object is crossing walkway as a pedestrian or passing over as a vehicle target_object: unknown: true # [-] whether to look and stop by UNKNOWN objects bicycle: true # [-] whether to look and stop by BICYCLE objects 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 3f4af4a5a1138..77de7d241c05c 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 @@ -50,6 +50,8 @@ enum class CollisionState { YIELD, EGO_PASS_FIRST, EGO_PASS_LATER, IGNORE }; struct CollisionPoint { geometry_msgs::msg::Point collision_point{}; + std::optional crosswalk_passage_direction{ + std::nullopt}; // denote obj is passing the crosswalk along the vehicle lane double time_to_collision{}; double time_to_vehicle{}; }; diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index cb0311ffe8ebb..b8190cb6124e7 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -116,6 +116,8 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) // param for target area & object cp.crosswalk_attention_range = getOrDeclareParameter(node, ns + ".object_filtering.crosswalk_attention_range"); + cp.vehicle_object_cross_angle_threshold = getOrDeclareParameter( + node, ns + ".object_filtering.vehicle_object_cross_angle_threshold"); cp.look_unknown = getOrDeclareParameter(node, ns + ".object_filtering.target_object.unknown"); cp.look_bicycle = diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 239eddca1fed9..69440aaddc2d0 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -25,6 +25,7 @@ #include #include +#include #include #include @@ -316,6 +317,8 @@ std::optional CrosswalkModule::checkStopForCrosswalkUsers( const double ego_vel = planner_data_->current_velocity->twist.linear.x; const double ego_acc = planner_data_->current_acceleration->accel.accel.linear.x; + const std::optional ego_crosswalk_passage_direction = + findEgoPassageDirectionAlongPath(sparse_resample_path); const auto base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; const auto dist_ego_to_stop = calcSignedArcLength(ego_path.points, ego_pos, p_stop_line->first) + p_stop_line->second; @@ -349,25 +352,44 @@ std::optional CrosswalkModule::checkStopForCrosswalkUsers( // Check pedestrian for stop // NOTE: first stop point and its minimum distance from ego to stop + auto isVehicleType = [](const uint8_t label) { + return label == ObjectClassification::MOTORCYCLE || label == ObjectClassification::BICYCLE; + }; std::optional> nearest_stop_info; std::vector stop_factor_points; for (const auto & object : object_info_manager_.getObject()) { - const auto & collision_point = object.collision_point; - if (collision_point) { + const auto & collision_point_opt = object.collision_point; + if (collision_point_opt) { + const auto & collision_point = collision_point_opt.value(); const auto & collision_state = object.collision_state; if (collision_state != CollisionState::YIELD) { continue; } + if ( + isVehicleType(object.classification) && ego_crosswalk_passage_direction && + collision_point.crosswalk_passage_direction) { + const double direction_diff = tier4_autoware_utils::normalizeRadian( + collision_point.crosswalk_passage_direction.value() - + ego_crosswalk_passage_direction.value()); + RCLCPP_INFO( + rclcpp::get_logger("temp"), + "collision_point.crosswalk_passage_direction = %f, ego_crosswalk_passage_direction = %f, " + "direction_diff = %f", + collision_point.crosswalk_passage_direction.value(), + ego_crosswalk_passage_direction.value(), direction_diff); + if (std::fabs(direction_diff) < planner_param_.vehicle_object_cross_angle_threshold) { + continue; + } + } stop_factor_points.push_back(object.position); const auto dist_ego2cp = - calcSignedArcLength( - sparse_resample_path.points, ego_pos, collision_point->collision_point) - + calcSignedArcLength(sparse_resample_path.points, ego_pos, collision_point.collision_point) - planner_param_.stop_distance_from_object; if (!nearest_stop_info || dist_ego2cp - base_link2front < nearest_stop_info->second) { nearest_stop_info = - std::make_pair(collision_point->collision_point, dist_ego2cp - base_link2front); + std::make_pair(collision_point.collision_point, dist_ego2cp - base_link2front); } } } @@ -580,6 +602,70 @@ std::pair CrosswalkModule::clampAttentionRangeByNeighborCrosswal return std::make_pair(clamped_near_attention_range, clamped_far_attention_range); } +std::optional CrosswalkModule::findEgoPassageDirectionAlongPath( + const PathWithLaneId & path) const +{ + auto findIntersectPoint = [&](const lanelet::ConstLineString3d line) + -> std::optional> { + const auto line_start = + tier4_autoware_utils::createPoint(line.front().x(), line.front().y(), line.front().z()); + const auto line_end = + tier4_autoware_utils::createPoint(line.back().x(), line.back().y(), line.back().z()); + for (unsigned i = 0; i < path.points.size() - 1; ++i) { + const auto & start = path.points.at(i).point.pose.position; + const auto & end = path.points.at(i + 1).point.pose.position; + if (const auto intersect = tier4_autoware_utils::intersect(line_start, line_end, start, end); + intersect.has_value()) { + return std::make_optional(std::make_pair(i, intersect.value())); + } + } + return std::nullopt; + }; + const auto intersect_pt1 = findIntersectPoint(crosswalk_.leftBound()); + const auto intersect_pt2 = findIntersectPoint(crosswalk_.rightBound()); + + if (!intersect_pt1 || !intersect_pt2) { + return std::nullopt; + } + const auto idx1 = intersect_pt1.value().first, idx2 = intersect_pt2.value().first; + const auto & front = idx1 > idx2 ? intersect_pt2.value().second : intersect_pt1.value().second; + const auto & back = idx1 > idx2 ? intersect_pt1.value().second : intersect_pt2.value().second; + return std::atan2(back.y - front.y, back.x - front.x); +} + +std::optional CrosswalkModule::findObjectPassageDirectionAlongVehicleLane( + const autoware_auto_perception_msgs::msg::PredictedPath & path) const +{ + using tier4_autoware_utils::Segment2d; + + auto findIntersectPoint = [&](const lanelet::ConstLineString3d line) + -> std::optional> { + const auto line_start = + tier4_autoware_utils::createPoint(line.front().x(), line.front().y(), line.front().z()); + const auto line_end = + tier4_autoware_utils::createPoint(line.back().x(), line.back().y(), line.back().z()); + for (unsigned i = 0; i < path.path.size() - 1; ++i) { + const auto & start = path.path.at(i).position; + const auto & end = path.path.at(i + 1).position; + if (const auto intersect = tier4_autoware_utils::intersect(line_start, line_end, start, end); + intersect.has_value()) { + return std::make_optional(std::make_pair(i, intersect.value())); + } + } + return std::nullopt; + }; + const auto intersect_pt1 = findIntersectPoint(crosswalk_.leftBound()); + const auto intersect_pt2 = findIntersectPoint(crosswalk_.rightBound()); + + if (!intersect_pt1 || !intersect_pt2) { + return std::nullopt; + } + const auto idx1 = intersect_pt1.value().first, idx2 = intersect_pt2.value().first; + const auto & front = idx1 > idx2 ? intersect_pt2.value().second : intersect_pt1.value().second; + const auto & back = idx1 > idx2 ? intersect_pt1.value().second : intersect_pt2.value().second; + return std::atan2(back.y - front.y, back.x - front.x); +} + std::optional CrosswalkModule::getCollisionPoint( const PathWithLaneId & ego_path, const PredictedObject & object, const std::pair & crosswalk_attention_range, const Polygon2d & attention_area) @@ -625,6 +711,8 @@ std::optional CrosswalkModule::getCollisionPoint( // Calculate multi-step object polygon, and reset start_idx const size_t start_idx_with_margin = std::max(static_cast(start_idx) - 1, 0); const size_t end_idx_with_margin = std::min(i + 1, obj_path.path.size() - 1); + const auto object_crosswalk_passage_direction = + findObjectPassageDirectionAlongVehicleLane(obj_path); const auto obj_multi_step_polygon = createMultiStepPolygon( obj_path.path, obj_polygon, start_idx_with_margin, end_idx_with_margin); is_start_idx_initialized = false; @@ -660,7 +748,8 @@ std::optional CrosswalkModule::getCollisionPoint( if (dist_ego2cp < minimum_stop_dist) { minimum_stop_dist = dist_ego2cp; nearest_collision_point = createCollisionPoint( - intersection_center_point, dist_ego2cp, dist_obj2cp, ego_vel, obj_vel); + intersection_center_point, dist_ego2cp, dist_obj2cp, ego_vel, obj_vel, + object_crosswalk_passage_direction); debug_data_.obj_polygons.push_back( toGeometryPointVector(obj_multi_step_polygon, ego_pos.z)); } @@ -679,17 +768,18 @@ std::optional CrosswalkModule::getCollisionPoint( CollisionPoint CrosswalkModule::createCollisionPoint( const geometry_msgs::msg::Point & nearest_collision_point, const double dist_ego2cp, const double dist_obj2cp, const geometry_msgs::msg::Vector3 & ego_vel, - const geometry_msgs::msg::Vector3 & obj_vel) const + const geometry_msgs::msg::Vector3 & obj_vel, + const std::optional object_crosswalk_passage_direction) const { constexpr double min_ego_velocity = 1.38; // [m/s] - - const auto & base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; + const auto base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y); const auto velocity = std::max(planner_param_.min_object_velocity, estimated_velocity); CollisionPoint collision_point{}; collision_point.collision_point = nearest_collision_point; + collision_point.crosswalk_passage_direction = object_crosswalk_passage_direction; collision_point.time_to_collision = std::max(0.0, dist_ego2cp - planner_param_.stop_distance_from_object - base_link2front) / std::max(ego_vel.x, min_ego_velocity); @@ -931,7 +1021,8 @@ void CrosswalkModule::updateObjectState( getCollisionPoint(sparse_resample_path, object, crosswalk_attention_range, attention_area); object_info_manager_.update( obj_uuid, obj_pos, std::hypot(obj_vel.x, obj_vel.y), clock_->now(), is_ego_yielding, - has_traffic_light, collision_point, planner_param_, crosswalk_.polygon2d().basicPolygon()); + has_traffic_light, collision_point, object.classification.front().label, planner_param_, + crosswalk_.polygon2d().basicPolygon()); if (collision_point) { const auto collision_state = object_info_manager_.getCollisionState(obj_uuid); diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index ef6d01fc43c23..7f020fbe5422c 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -150,6 +150,7 @@ class CrosswalkModule : public SceneModuleInterface double traffic_light_state_timeout; // param for target area & object double crosswalk_attention_range; + double vehicle_object_cross_angle_threshold; bool look_unknown; bool look_bicycle; bool look_motorcycle; @@ -160,6 +161,7 @@ class CrosswalkModule : public SceneModuleInterface { CollisionState collision_state{}; std::optional time_to_start_stopped{std::nullopt}; + uint8_t classification{ObjectClassification::UNKNOWN}; geometry_msgs::msg::Point position{}; std::optional collision_point{}; @@ -242,8 +244,8 @@ class CrosswalkModule : public SceneModuleInterface void update( const std::string & uuid, const geometry_msgs::msg::Point & position, const double vel, const rclcpp::Time & now, const bool is_ego_yielding, const bool has_traffic_light, - const std::optional & collision_point, const PlannerParam & planner_param, - const lanelet::BasicPolygon2d & crosswalk_polygon) + const std::optional & collision_point, const uint8_t classification, + const PlannerParam & planner_param, const lanelet::BasicPolygon2d & crosswalk_polygon) { // update current uuids current_uuids_.push_back(uuid); @@ -265,6 +267,7 @@ class CrosswalkModule : public SceneModuleInterface crosswalk_polygon); objects.at(uuid).collision_point = collision_point; objects.at(uuid).position = position; + objects.at(uuid).classification = classification; } void finalize() { @@ -330,6 +333,11 @@ class CrosswalkModule : public SceneModuleInterface const std::vector & path_intersects, const std::optional & stop_pose) const; + std::optional findEgoPassageDirectionAlongPath( + const PathWithLaneId & sparse_resample_path) const; + std::optional findObjectPassageDirectionAlongVehicleLane( + const autoware_auto_perception_msgs::msg::PredictedPath & path) const; + std::optional getCollisionPoint( const PathWithLaneId & ego_path, const PredictedObject & object, const std::pair & crosswalk_attention_range, const Polygon2d & attention_area); @@ -366,7 +374,8 @@ class CrosswalkModule : public SceneModuleInterface CollisionPoint createCollisionPoint( const geometry_msgs::msg::Point & nearest_collision_point, const double dist_ego2cp, const double dist_obj2cp, const geometry_msgs::msg::Vector3 & ego_vel, - const geometry_msgs::msg::Vector3 & obj_vel) const; + const geometry_msgs::msg::Vector3 & obj_vel, + const std::optional object_crosswalk_passage_direction) const; float calcTargetVelocity( const geometry_msgs::msg::Point & stop_point, const PathWithLaneId & ego_path) const; From cc0b1081a74a265a3dac05d5830610242aa0ecd3 Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Fri, 15 Dec 2023 16:41:48 +0900 Subject: [PATCH 63/87] refactor(image_projection_based_fusion): add JSON Schema and remove default value spefications (#4902) * refactor: add JSON Schema and remove default values in `declare_parameter()` Signed-off-by: ktro2828 * refactor: update configuration file Signed-off-by: ktro2828 * refactor: add configuration file and update launcher to load this Signed-off-by: ktro2828 * refactor: update funsion node configuration Signed-off-by: ktro2828 * docs: update the document for roi cluster fusion Signed-off-by: ktro2828 * docs: update documents Signed-off-by: ktro2828 * refactor: move `debug_mode` into `roi_sync.param.yaml` Signed-off-by: ktro2828 * refactor: rework parameters for `roi_pointcloud_fusion` Signed-off-by: ktro2828 * chore: update maintainers Signed-off-by: ktro2828 * refactor: remove debug_mode Signed-off-by: ktro2828 * refactor: rename parameter to avoid failure of spell-check Signed-off-by: ktro2828 * fix: fix typo and parameters for initialization Signed-off-by: ktro2828 --------- Signed-off-by: ktro2828 --- .../config/pointpainting.param.yaml | 40 +- .../config/roi_cluster_fusion.param.yaml | 12 + .../config/roi_pointcloud_fusion.param.yaml | 5 + .../config/roi_sync.param.yaml | 8 + .../images/roi_cluster_fusion_pipeline.svg | 966 ++++++++++++++++++ .../docs/roi-cluster-fusion.md | 5 + .../launch/pointpainting_fusion.launch.xml | 7 - .../launch/roi_cluster_fusion.launch.xml | 36 +- .../roi_detected_object_fusion.launch.xml | 6 - .../launch/roi_pointcloud_fusion.launch.xml | 8 +- .../image_projection_based_fusion/package.xml | 2 + .../schema/pointpainting.schema.json | 152 +++ .../schema/roi_cluster_fusion.schema.json | 96 ++ .../roi_detected_object_fusion.schema.json | 70 ++ .../schema/roi_pointcloud_fusion.schema.json | 41 + .../schema/roi_sync.schema.json | 84 ++ .../src/fusion_node.cpp | 19 +- .../src/pointpainting_fusion/node.cpp | 60 +- 18 files changed, 1510 insertions(+), 107 deletions(-) create mode 100644 perception/image_projection_based_fusion/config/roi_cluster_fusion.param.yaml create mode 100644 perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml create mode 100644 perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_pipeline.svg create mode 100644 perception/image_projection_based_fusion/schema/pointpainting.schema.json create mode 100644 perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json create mode 100644 perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json create mode 100644 perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json create mode 100644 perception/image_projection_based_fusion/schema/roi_sync.schema.json diff --git a/perception/image_projection_based_fusion/config/pointpainting.param.yaml b/perception/image_projection_based_fusion/config/pointpainting.param.yaml index e1be5426cba4b..21d31f216373b 100755 --- a/perception/image_projection_based_fusion/config/pointpainting.param.yaml +++ b/perception/image_projection_based_fusion/config/pointpainting.param.yaml @@ -1,18 +1,26 @@ /**: ros__parameters: - class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] - paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"] - point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle - max_voxel_size: 40000 - point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] - voxel_size: [0.32, 0.32, 8.0] - downsample_factor: 1 - encoder_in_feature_size: 12 - yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] - # post-process params - circle_nms_dist_threshold: 0.3 - iou_nms_target_class_names: ["CAR"] - iou_nms_search_distance_2d: 10.0 - iou_nms_threshold: 0.1 - # omp params - omp_num_threads: 1 + model_params: + class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] + paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"] + point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle + max_voxel_size: 40000 + point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] + voxel_size: [0.32, 0.32, 8.0] + downsample_factor: 1 + encoder_in_feature_size: 12 + yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] + has_twist: false + densification_params: + world_frame_id: "map" + num_past_frames: 0 + post_process_params: + # post-process params + circle_nms_dist_threshold: 0.3 + iou_nms_target_class_names: ["CAR"] + iou_nms_search_distance_2d: 10.0 + iou_nms_threshold: 0.1 + score_threshold: 0.4 + omp_params: + # omp params + num_threads: 1 diff --git a/perception/image_projection_based_fusion/config/roi_cluster_fusion.param.yaml b/perception/image_projection_based_fusion/config/roi_cluster_fusion.param.yaml new file mode 100644 index 0000000000000..90ba841d53b2d --- /dev/null +++ b/perception/image_projection_based_fusion/config/roi_cluster_fusion.param.yaml @@ -0,0 +1,12 @@ +/**: + ros__parameters: + fusion_distance: 100.0 + trust_object_distance: 100.0 + trust_object_iou_mode: "iou" + non_trust_object_iou_mode: "iou_x" + use_cluster_semantic_type: false + only_allow_inside_cluster: true + roi_scale_factor: 1.1 + iou_threshold: 0.65 + unknown_iou_threshold: 0.1 + remove_unknown: true diff --git a/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml b/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml new file mode 100644 index 0000000000000..5b86b8e81d1aa --- /dev/null +++ b/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + fuse_unknown_only: true + min_cluster_size: 2 + cluster_2d_tolerance: 0.5 diff --git a/perception/image_projection_based_fusion/config/roi_sync.param.yaml b/perception/image_projection_based_fusion/config/roi_sync.param.yaml index 21ba13787f1c0..99d85089befb8 100644 --- a/perception/image_projection_based_fusion/config/roi_sync.param.yaml +++ b/perception/image_projection_based_fusion/config/roi_sync.param.yaml @@ -3,3 +3,11 @@ input_offset_ms: [61.67, 111.67, 45.0, 28.33, 78.33, 95.0] timeout_ms: 70.0 match_threshold_ms: 50.0 + image_buffer_size: 15 + debug_mode: false + filter_scope_min_x: -100.0 + filter_scope_min_y: -100.0 + filter_scope_min_z: -100.0 + filter_scope_max_x: 100.0 + filter_scope_max_y: 100.0 + filter_scope_max_z: 100.0 diff --git a/perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_pipeline.svg b/perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_pipeline.svg new file mode 100644 index 0000000000000..aaadfaf186dd2 --- /dev/null +++ b/perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_pipeline.svg @@ -0,0 +1,966 @@ + + + + + + + + + + +
+
+
+ + Check whether + the cluster RoI (inner) + is fully contained within + the scaled detected RoI (outer) + . +
+
+ *NOTE* +
+ Because the cluster RoI is calculated with the points projected on the image, our recommended scale factor is [1.1, 1.5] . +
+ Otherwise, set + only_allow_inside_cluster + to + False + . +
+
+
+
+
+
+ Check whether the cluster RoI (inner) is fully contained within the scaled... +
+
+ + + + +
+
+
+ use_iou +
+
+
+
+ use_iou +
+
+ + + + +
+
+
+ unknown_iou_threshold +
+
+
+
+ unknown_iou_threshold +
+
+ + + + +
+
+
+ + use_iou_x /  y +
+
+
+
+
+
+ use_iou_x /  y +
+
+ + + + + + +
+
+
+ only_allow_inside_cluster +
+
+
+
+ only_allow_inside_cluster +
+
+ + + + +
+
+
+ iou_threshold +
+
+
+
+ iou_threshold +
+
+ + + + + + + + +
+
+
+ Is UNKNOWN object? +
+
+
+
+ Is UNKNOWN object? +
+
+ + + + + + +
+
+
+ + IoU threshold < IoU score? + +
+
+
+
+ IoU threshold < IoU score? +
+
+ + + + + + + + + + + + +
+
+
+ IoU Score +
+
+
+
+ IoU Score +
+
+ + + + + + + + + + + + + + + + + + + + + +
+
+
+ Is Cluster RoI inside Detected RoI? +
+
+
+
+ Is Cluster RoI inside Detected RoI? +
+
+ + + + + + +
+
+
+ Fused Cluster +
+
+
+
+ Fused Cluster +
+
+ + + + + + +
+
+
+ Unfused Cluster +
+
+
+
+ Unfused Cluster +
+
+ + + + + + + + +
+
+
+ Fusion Target Cluster
&
Detected RoI
+
+
+
+
+ Fusion Target Cluster... +
+
+ + + + +
+
+
+ Unfused Cluster +
+
+
+
+ Unfused Cluster +
+
+ + + + + + + + + + + +
+
+
+ + + roi_scale_factor
(>=1.0)
+
+
+
+
+
+
+ roi_scale_factor... +
+
+ + + + +
+
+
+ + Check whether the IoU score between + the cluster RoI + and + the detected RoI + is greater than the threshold. +
+
+ **NOTE** +
+ Our default threshold is 0.65 with + only_allow_inside_cluster + is + True + . +
+ Also, please try the bigger score threshold and set + only_allow_inside_cluster + to + False + depending on your 2D RoI detector performance. +
+
+
+
+
+
+ Check whether the IoU score between the cluster RoI and the detected RoI is greater than the thr... +
+
+ + + + + + +
+
+
+
    +
  • + IoU = Intersection Area / Union Area +
  • +
  • + IoU X = Intersection Width / Union Width +
  • +
  • + IoU Y = Intersection Height / Union Height +
  • +
+
+
+
+
+ IoU = Intersection Area / Union AreaIoU X = Intersectio... +
+
+ + + + +
+
+
+ + Nodes overview + +
+
+
+
+ Nodes overview +
+
+ + + + +
+
+
+ Numeric Parameter +
+
+
+
+ Numeric Parameter +
+
+ + + + +
+
+
+ Result +
+
+
+
+ Result +
+
+ + + + + + + + +
+
+
+ Boolean Parameter +
+
+
+
+ Boolean Parameter +
+
+ + + + +
+
+
+ + true + +
+
+
+
+ true +
+
+ + + + +
+
+
+ + false + +
+
+
+
+ false +
+
+ + + + + + + + +
+
+
+ Condition +
+
+
+
+ Condition +
+
+ + + + +
+
+
+ + true + +
+
+
+
+ true +
+
+ + + + +
+
+
+ + false + +
+
+
+
+ false +
+
+ + + + +
+
+
+ use_cluster_semantic_type +
+
+
+
+ use_cluster_semantic_type +
+
+ + + + +
+
+
+ + Objects +
+ w/ Semantic Label +
+
+
+
+
+ Objects... +
+
+ + + + + + +
+
+
+ + All objects are set to +
+ UNKOWN Label +
+
+
+
+
+
+ All objects are set to... +
+
+ + + + + + + + +
+
+
+ Fusion Target Cluster +
+
+
+
+ Fusion Target Cluster +
+
+ + + + +
+
+
+ trust_distance +
+
+
+
+ trust_distance +
+
+ + + + + + +
+
+
+ + Is Cluster closer than + trust_distance + ? + +
+
+
+
+ Is Cluster closer than trust_... +
+
+ + + + + + + + + + + + +
+
+
+ + Input Cluster + +
+
+
+
+ Input Cluster +
+
+ + + + +
+
+
+ roi_scale_factor +
+
+
+
+ roi_scale_factor +
+
+ + + + +
+
+
+ Pre-Process +
+
+
+
+ Pre-Process +
+
+ + + + +
+
+
+ Fusion Process +
+
+
+
+ Fusion Process +
+
+ + + + +
+
+
+ Post-Process +
+
+
+
+ Post-Process +
+
+ + + + + + +
+
+
+ remove_unknown +
+
+
+
+ remove_unknown +
+
+ + + + + + +
+
+
+ Fused Cluster +
+
+
+
+ Fused Cluster +
+
+ + + + +
+
+
+ Is KNOWN object?
&&
0.1 <= RoI probability?
+
+
+
+
+ Is KNOWN object?... +
+
+ + + + + + +
+
+
+ Remove noise clusters, which are undetected by RoI detector, such as fog and exhaust gas. +
+
+
+
+ Remove noise clusters, which are undet... +
+
+ + + + +
+
+
+ + Output Fused Cluster + +
+
+
+
+ Output Fused Cluster +
+
+ + + + + + + + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md b/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md index 03eaab2a3c6ca..86d3a2fa070b2 100644 --- a/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md +++ b/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md @@ -30,6 +30,11 @@ The clusters are projected onto image planes, and then if the ROIs of clusters a ## Parameters +The following figure is an inner pipeline overview of RoI cluster fusion node. +Please refer to it for your parameter settings. + +![roi_cluster_fusion_pipeline](./images/roi_cluster_fusion_pipeline.svg) + ### Core Parameters | Name | Type | Description | diff --git a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml index e15737f5ed222..33781461fa1cc 100644 --- a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml @@ -30,7 +30,6 @@ - @@ -43,9 +42,6 @@ - - - @@ -82,9 +78,6 @@ - - - diff --git a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml index 60f6f943b8cda..52dd71e9579c1 100644 --- a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml @@ -18,24 +18,11 @@ + - - - - - - - - - - - - - - @@ -46,17 +33,8 @@ - - - - - - - - - - + @@ -86,16 +64,6 @@ - - - - - - - - - - diff --git a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml index b6165fc7c87d2..c9da81af9ddb0 100644 --- a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml @@ -25,8 +25,6 @@ - - @@ -69,10 +67,6 @@ - - - - diff --git a/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml index 181f4ccb88320..046d88d06e2a1 100644 --- a/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml @@ -1,8 +1,5 @@ - - - @@ -23,6 +20,7 @@ + @@ -38,9 +36,7 @@ - - - + diff --git a/perception/image_projection_based_fusion/package.xml b/perception/image_projection_based_fusion/package.xml index 1648de210ec2c..49ff4dafc7900 100644 --- a/perception/image_projection_based_fusion/package.xml +++ b/perception/image_projection_based_fusion/package.xml @@ -9,6 +9,8 @@ Shunsuke Miura Yoshi Ri badai nguyen + Kotaro Uetake + Tao Zhong Apache License 2.0 ament_cmake_auto diff --git a/perception/image_projection_based_fusion/schema/pointpainting.schema.json b/perception/image_projection_based_fusion/schema/pointpainting.schema.json new file mode 100644 index 0000000000000..036628d72e70a --- /dev/null +++ b/perception/image_projection_based_fusion/schema/pointpainting.schema.json @@ -0,0 +1,152 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Point Painting Fusion Node", + "type": "object", + "definitions": { + "pointpainting": { + "type": "object", + "properties": { + "model_params": { + "type": "object", + "description": "Parameters for model configuration.", + "properties": { + "class_names": { + "type": "array", + "description": "An array of class names will be predicted.", + "default": ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"], + "uniqueItems": true + }, + "paint_class_names": { + "type": "array", + "description": "An array of class names will be painted by PointPainting", + "default": ["CAR", "BICYCLE", "PEDESTRIAN"], + "uniqueItems": true + }, + "point_feature_size": { + "type": "integer", + "description": "A number of channels of point feature layer.", + "default": 7 + }, + "max_voxel_size": { + "type": "integer", + "description": "A maximum size of voxel grid.", + "default": 40000 + }, + "point_cloud_range": { + "type": "array", + "description": "An array of distance ranges of each class, this must have same length with `class_names`.", + "default": [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] + }, + "voxel_size": { + "type": "array", + "description": "An array of voxel grid sizes for PointPainting, this must have same length with `paint_class_names`.", + "default": [0.32, 0.32, 8.0] + }, + "down_sample_factor": { + "type": "integer", + "description": "A scale factor of downsampling points", + "default": 1, + "minimum": 1 + }, + "encoder_in_feature_size": { + "type": "integer", + "description": "A size of encoder input feature channels.", + "default": 12 + }, + "yaw_norm_thresholds": { + "type": "array", + "description": "An array of distance threshold values of norm of yaw [rad].", + "default": [0.3, 0.3, 0.3, 0.3, 0.0], + "minimum": 0.0, + "maximum": 1.0 + }, + "has_twist": { + "type": "boolean", + "description": "Indicates whether the model outputs twist value.", + "default": false + } + } + }, + "densification_params": { + "type": "object", + "description": "Parameters for pointcloud densification.", + "properties": { + "world_frame_id": { + "type": "string", + "description": "A name of frame id where world coordinates system is defined with respect to.", + "default": "map" + }, + "num_past_frames": { + "type": "integer", + "description": "A number of past frames to be considered as same input frame.", + "default": 0, + "minimum": 0 + } + } + }, + "post_process_params": { + "type": "object", + "properties": { + "score_threshold": { + "type": "number", + "description": "A threshold value of existence probability score, all of objects with score less than this threshold are ignored.", + "default": 0.4, + "minimum": 0.0, + "maximum": 1.0 + }, + "circle_nms_dist_threshold": { + "type": "number", + "description": "", + "default": 0.3, + "minimum": 0.0, + "maximum": 1.0 + }, + "iou_nms_target_class_names": { + "type": "array", + "description": "An array of class names to be target in NMS.", + "default": ["CAR"], + "uniqueItems": true + }, + "iou_search_distance_2d": { + "type": "number", + "description": "A maximum distance value to search the nearest objects.", + "default": 10.0, + "minimum": 0.0 + }, + "iou_nms_threshold": { + "type": "number", + "description": "A threshold value of NMS using IoU score.", + "default": 0.1, + "minimum": 0.0, + "maximum": 1.0 + } + } + }, + "omp_params": { + "type": "object", + "properties": { + "num_threads": { + "type": "integer", + "description": "The number of threads that is set to the environment variable OMP_NUM_THREADS.", + "default": 1, + "minimum": 1 + } + } + } + }, + "required": ["model_params", "densification_params", "post_process_params", "omp_params"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/pointpainting" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json b/perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json new file mode 100644 index 0000000000000..fc32e9d6d3d8b --- /dev/null +++ b/perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json @@ -0,0 +1,96 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for RoI Cluster Fusion Node", + "type": "object", + "definitions": { + "roi_cluster_fusion": { + "type": "object", + "properties": { + "fusion_distance": { + "type": "number", + "description": "If the detected object's distance is less than its value, the fusion will be processed.", + "default": 100.0, + "minimum": 0.0 + }, + "trust_object_distance": { + "type": "number", + "description": "If the detected object's distance is less than its value, IoU method specified in `trust_object_iou_mode` is used, otherwise `non_trust_object_iou_mode` is used.", + "default": 100.0, + "minimum": 0.0 + }, + "trust_object_iou_mode": { + "type": "string", + "description": "Name of IoU method applied to the objects in range of [0.0, `trust_distance`].", + "default": "iou", + "enum": ["iou", "iou_x", "iou_y"] + }, + "non_trust_object_iou_mode": { + "type": "string", + "description": "Name of IoU method applied to the objects in range of [`trust_distance`, `fusion_distance`], if `trust_distance` < `fusion_distance`.", + "default": "iou_x", + "enum": ["iou", "iou_x", "iou_y"] + }, + "use_cluster_semantic_type": { + "type": "boolean", + "description": "If this parameter is false, label of cluster objects will be reset to UNKNOWN.", + "default": false + }, + "only_allow_inside_cluster": { + "type": "boolean", + "description": "If this parameter is true, only clusters in which all their points are inside the RoI can be assigned to the RoI.", + "default": true + }, + "roi_scale_factor": { + "type": "number", + "description": "A scale factor for resizing RoI while checking if cluster points are inside the RoI.", + "default": 1.1, + "minimum": 1.0, + "maximum": 2.0 + }, + "iou_threshold": { + "type": "number", + "description": "An IoU score threshold. Note that the total IoU score is the sum of the IoU scores that are set to true in use_iou, use_iou_x and use_iou_y.", + "default": 0.65, + "minimum": 0.0, + "maximum": 1.0 + }, + "unknown_iou_threshold": { + "type": "number", + "description": "A threshold value of IoU score for objects labeled UNKNOWN.", + "default": 0.1, + "minimum": 0.0, + "maximum": 1.0 + }, + "remove_unknown": { + "type": "boolean", + "description": "If this parameter is true, all of objects labeled UNKNOWN will be removed in post-process.", + "default": false + } + }, + "required": [ + "fusion_distance", + "trust_object_distance", + "trust_object_iou_mode", + "non_trust_object_iou_mode", + "use_cluster_semantic_type", + "only_allow_inside_cluster", + "roi_scale_factor", + "iou_threshold", + "unknown_iou_threshold", + "remove_unknown" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/roi_cluster_fusion" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json b/perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json new file mode 100644 index 0000000000000..3030be1305d56 --- /dev/null +++ b/perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json @@ -0,0 +1,70 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for RoI Detected Object Fusion Node", + "type": "object", + "definitions": { + "roi_detected_object_fusion": { + "type": "object", + "properties": { + "passthrough_lower_bound_probability_thresholds": { + "type": "array", + "description": "An array of object probability thresholds. The objects that have higher probability than their respective thresholds are kept.", + "default": [0.35, 0.35, 0.35, 0.35, 0.35, 0.35, 0.35, 0.5] + }, + "trust_distances": { + "type": "array", + "description": "An array of object distances thresholds. Any objects that is farther than this value will be skipped in the clustering process, but will still be published.", + "default": [50.0, 100.0, 100.0, 100.0, 100.0, 50.0, 50.0, 50.0] + }, + "min_iou_threshold": { + "type": "number", + "description": "An Iou score threshold.", + "default": 0.5, + "minimum": 0.0, + "maximum": 1.0 + }, + "roi_probability_threshold": { + "type": "number", + "description": "A object probability threshold.", + "default": 0.5, + "minimum": 0.0, + "maximum": 1.0 + }, + "use_roi_probability": { + "type": "boolean", + "description": "If this parameter is true, the objects are filtered out with their RoI probabilities.", + "default": false + }, + "can_assign_matrix": { + "type": "array", + "description": "An NxN matrix, where N represents the number of classes. A value 1 indicates that it is assignable, while a value of 0 indicates not.", + "default": [ + 1, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1, + 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 0, 0, 0, 0, 0, 1, 1, 1, 0, 0, + 0, 0, 0, 1, 1, 1 + ] + } + }, + "required": [ + "passthrough_lower_bound_probability_thresholds", + "trust_distances", + "min_iou_threshold", + "roi_probability_threshold", + "use_roi_probability", + "can_assign_matrix" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/roi_detected_object_fusion" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json b/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json new file mode 100644 index 0000000000000..f39ef257ea789 --- /dev/null +++ b/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json @@ -0,0 +1,41 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for RoI PointCloud Fusion Node", + "type": "object", + "definitions": { + "roi_pointcloud_fusion": { + "type": "object", + "properties": { + "fuse_unknown_only": { + "type": "boolean", + "description": "Whether to fuse only UNKNOWN clusters.", + "default": true + }, + "min_cluster_size": { + "type": "integer", + "description": "The minimum number of points that a cluster must contain to be considered as valid.", + "default": 2 + }, + "cluster_2d_tolerance": { + "type": "number", + "description": "A cluster tolerance measured in radial direction [m]", + "default": 0.5, + "exclusiveMinimum": 0.0 + } + }, + "required": ["fuse_unknown_only", "min_cluster_size", "cluster_2d_tolerance"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/roi_pointcloud_fusion" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/image_projection_based_fusion/schema/roi_sync.schema.json b/perception/image_projection_based_fusion/schema/roi_sync.schema.json new file mode 100644 index 0000000000000..411fb678a49a7 --- /dev/null +++ b/perception/image_projection_based_fusion/schema/roi_sync.schema.json @@ -0,0 +1,84 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Synchronization of RoI Fusion Nodes", + "type": "object", + "definitions": { + "roi_sync": { + "type": "object", + "properties": { + "input_offset_ms": { + "type": "array", + "description": "An array of timestamp offsets for each camera [ms].", + "default": [61.67, 111.67, 45.0, 28.33, 78.33, 95.0] + }, + "timeout_ms": { + "type": "number", + "description": "A timeout value can be assigned within a single frame [ms].", + "default": 70.0, + "minimum": 1.0, + "maximum": 100.0 + }, + "match_threshold_ms": { + "type": "number", + "description": "A maximum threshold value to synchronize RoIs from multiple cameras [ms].", + "default": 50.0, + "minimum": 0.0, + "maximum": 100.0 + }, + "image_buffer_size": { + "type": "integer", + "description": "The number of image buffer size for debug.", + "default": 15, + "minimum": 1 + }, + "debug_mode": { + "type": "boolean", + "description": "Whether to debug or not.", + "default": false + }, + "filter_scope_min_x": { + "type": "number", + "description": "Minimum x position to be considered for debug [m].", + "default": -100.0 + }, + "filter_scope_min_y": { + "type": "number", + "description": "Minimum y position to be considered for debug [m].", + "default": -100.0 + }, + "filter_scope_min_z": { + "type": "number", + "description": "Minimum z position to be considered for debug [m].", + "default": -100.0 + }, + "filter_scope_max_x": { + "type": "number", + "description": "Maximum x position to be considered for debug [m].", + "default": 100.0 + }, + "filter_scope_max_y": { + "type": "number", + "description": "Maximum y position to be considered for debug [m].", + "default": 100.0 + }, + "filter_scope_max_z": { + "type": "number", + "description": "Maximum z position [m].", + "default": 100.0 + } + } + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/roi_sync" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index b01a910aaded1..4abd92d7fb063 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -46,7 +46,7 @@ FusionNode::FusionNode( : Node(node_name, options), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { // set rois_number - rois_number_ = static_cast(declare_parameter("rois_number", 1)); + rois_number_ = static_cast(declare_parameter("rois_number")); if (rois_number_ < 1) { RCLCPP_WARN( this->get_logger(), "minimum rois_number is 1. current rois_number is %zu", rois_number_); @@ -80,7 +80,7 @@ FusionNode::FusionNode( "/sensing/camera/camera" + std::to_string(roi_i) + "/image_rect_color"); } - input_offset_ms_ = declare_parameter("input_offset_ms", std::vector{}); + input_offset_ms_ = declare_parameter>("input_offset_ms"); if (!input_offset_ms_.empty() && rois_number_ != input_offset_ms_.size()) { throw std::runtime_error("The number of offsets does not match the number of topics."); } @@ -122,7 +122,7 @@ FusionNode::FusionNode( // debugger if (declare_parameter("debug_mode", false)) { std::size_t image_buffer_size = - static_cast(declare_parameter("image_buffer_size", 15)); + static_cast(declare_parameter("image_buffer_size")); debugger_ = std::make_shared(this, rois_number_, image_buffer_size, input_camera_topics_); } @@ -136,14 +136,15 @@ FusionNode::FusionNode( stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); } + // cspell: ignore minx, maxx, miny, maxy, minz, maxz // FIXME: use min_x instead of minx - filter_scope_minx_ = declare_parameter("filter_scope_minx", -100); - filter_scope_maxx_ = declare_parameter("filter_scope_maxx", 100); - filter_scope_miny_ = declare_parameter("filter_scope_miny", -100); - filter_scope_maxy_ = declare_parameter("filter_scope_maxy", 100); - filter_scope_minz_ = declare_parameter("filter_scope_minz", -100); - filter_scope_maxz_ = declare_parameter("filter_scope_maxz", 100); + filter_scope_minx_ = declare_parameter("filter_scope_min_x"); + filter_scope_maxx_ = declare_parameter("filter_scope_max_x"); + filter_scope_miny_ = declare_parameter("filter_scope_min_y"); + filter_scope_maxy_ = declare_parameter("filter_scope_max_y"); + filter_scope_minz_ = declare_parameter("filter_scope_min_z"); + filter_scope_maxz_ = declare_parameter("filter_scope_max_z"); } template diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 48ef3d26806c8..76b561f677c0f 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -95,28 +95,29 @@ inline bool isUnknown(int label2d) PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & options) : FusionNode("pointpainting_fusion", options) { - omp_num_threads_ = this->declare_parameter("omp_num_threads", 1); + omp_num_threads_ = this->declare_parameter("omp_params.num_threads"); const float score_threshold = - static_cast(this->declare_parameter("score_threshold", 0.4)); - const float circle_nms_dist_threshold = - static_cast(this->declare_parameter("circle_nms_dist_threshold", 1.5)); + static_cast(this->declare_parameter("post_process_params.score_threshold")); + const float circle_nms_dist_threshold = static_cast( + this->declare_parameter("post_process_params.circle_nms_dist_threshold")); const auto yaw_norm_thresholds = - this->declare_parameter>("yaw_norm_thresholds"); + this->declare_parameter>("model_params.yaw_norm_thresholds"); // densification param const std::string densification_world_frame_id = - this->declare_parameter("densification_world_frame_id", "map"); + this->declare_parameter("densification_params.world_frame_id"); const int densification_num_past_frames = - this->declare_parameter("densification_num_past_frames", 0); + this->declare_parameter("densification_params.num_past_frames"); // network param - const std::string trt_precision = this->declare_parameter("trt_precision", "fp16"); - const std::string encoder_onnx_path = this->declare_parameter("encoder_onnx_path", ""); - const std::string encoder_engine_path = this->declare_parameter("encoder_engine_path", ""); - const std::string head_onnx_path = this->declare_parameter("head_onnx_path", ""); - const std::string head_engine_path = this->declare_parameter("head_engine_path", ""); - - class_names_ = this->declare_parameter>("class_names"); + const std::string trt_precision = this->declare_parameter("trt_precision"); + const std::string encoder_onnx_path = this->declare_parameter("encoder_onnx_path"); + const std::string encoder_engine_path = + this->declare_parameter("encoder_engine_path"); + const std::string head_onnx_path = this->declare_parameter("head_onnx_path"); + const std::string head_engine_path = this->declare_parameter("head_engine_path"); + + class_names_ = this->declare_parameter>("model_params.class_names"); const auto paint_class_names = - this->declare_parameter>("paint_class_names"); + this->declare_parameter>("model_params.paint_class_names"); std::vector classes_{"CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"}; if ( std::find(paint_class_names.begin(), paint_class_names.end(), "TRUCK") != @@ -138,17 +139,17 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt isClassTable_.erase(cls); } } - has_twist_ = this->declare_parameter("has_twist", false); - const std::size_t point_feature_size = - static_cast(this->declare_parameter("point_feature_size")); + has_twist_ = this->declare_parameter("model_params.has_twist"); + const std::size_t point_feature_size = static_cast( + this->declare_parameter("model_params.point_feature_size")); const std::size_t max_voxel_size = - static_cast(this->declare_parameter("max_voxel_size")); - pointcloud_range = this->declare_parameter>("point_cloud_range"); - const auto voxel_size = this->declare_parameter>("voxel_size"); - const std::size_t downsample_factor = - static_cast(this->declare_parameter("downsample_factor")); - const std::size_t encoder_in_feature_size = - static_cast(this->declare_parameter("encoder_in_feature_size")); + static_cast(this->declare_parameter("model_params.max_voxel_size")); + pointcloud_range = this->declare_parameter>("model_params.point_cloud_range"); + const auto voxel_size = this->declare_parameter>("model_params.voxel_size"); + const std::size_t downsample_factor = static_cast( + this->declare_parameter("model_params.downsample_factor")); + const std::size_t encoder_in_feature_size = static_cast( + this->declare_parameter("model_params.encoder_in_feature_size")); const auto allow_remapping_by_area_matrix = this->declare_parameter>("allow_remapping_by_area_matrix"); const auto min_area_matrix = this->declare_parameter>("min_area_matrix"); @@ -172,10 +173,11 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt { centerpoint::NMSParams p; p.nms_type_ = centerpoint::NMS_TYPE::IoU_BEV; - p.target_class_names_ = - this->declare_parameter>("iou_nms_target_class_names"); - p.search_distance_2d_ = this->declare_parameter("iou_nms_search_distance_2d"); - p.iou_threshold_ = this->declare_parameter("iou_nms_threshold"); + p.target_class_names_ = this->declare_parameter>( + "post_process_params.iou_nms_target_class_names"); + p.search_distance_2d_ = + this->declare_parameter("post_process_params.iou_nms_search_distance_2d"); + p.iou_threshold_ = this->declare_parameter("post_process_params.iou_nms_threshold"); iou_bev_nms_.setParameters(p); } From 88dae03152a734d7478797fde8c96c4800adace5 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 15 Dec 2023 18:44:07 +0900 Subject: [PATCH 64/87] fix(avoidance): fix unexpected sudden deceleration for avoidance maneuver (#5805) fix(avoidance): fix sudden deceleration Signed-off-by: satoshi-ota --- planning/behavior_path_avoidance_module/src/scene.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index 46c3bbe55d69d..783877e9c753d 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -1700,7 +1700,7 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const // insert slow down speed. const double current_target_velocity = PathShifter::calcFeasibleVelocityFromJerk( shift_length, helper_->getLateralMinJerkLimit(), distance_to_object); - if (current_target_velocity < getEgoSpeed() && decel_distance < remaining_distance) { + if (current_target_velocity < getEgoSpeed() + parameters_->buf_slow_down_speed) { utils::avoidance::insertDecelPoint( getEgoPosition(), decel_distance, parameters_->velocity_map.front(), shifted_path.path, slow_pose_); From a6615856d9498525988085333ee5178b9d2fdd26 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 15 Dec 2023 19:02:40 +0900 Subject: [PATCH 65/87] fix(goal_planner): set rederence path for candidate path (#5886) Signed-off-by: kosuke55 --- .../src/goal_planner_module.cpp | 1 + 1 file changed, 1 insertion(+) 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 6f1b1e7f41571..b50387b3f6b0e 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 @@ -943,6 +943,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate() const BehaviorModuleOutput pull_over_output = planPullOverAsOutput(); output.modified_goal = pull_over_output.modified_goal; output.path = std::make_shared(generateStopPath()); + output.reference_path = getPreviousModuleOutput().reference_path; const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( *output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); From a5d547926045a6d0cd18bc670c33697effcc5341 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 15 Dec 2023 19:37:11 +0900 Subject: [PATCH 66/87] fix(avoidance): check far objects during shifting (#5857) * fix(avoidance): check far objects during shifting Signed-off-by: satoshi-ota * fix(avoidance): update impl Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../behavior_path_avoidance_module/helper.hpp | 16 ++++++++++++++-- 1 file changed, 14 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp index 6717cefefc9f6..df9640fa75626 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp @@ -58,6 +58,8 @@ class AvoidanceHelper double getEgoSpeed() const { return std::abs(data_->self_odometry->twist.twist.linear.x); } + geometry_msgs::msg::Pose getEgoPose() const { return data_->self_odometry->pose.pose; } + size_t getConstraintsMapIndex(const double velocity, const std::vector & values) const { const auto itr = std::find_if( @@ -185,10 +187,20 @@ class AvoidanceHelper return parameters_->object_check_max_forward_distance; } + const auto & route_handler = data_->route_handler; + + lanelet::ConstLanelet closest_lane; + if (!route_handler->getClosestLaneletWithinRoute(getEgoPose(), &closest_lane)) { + return parameters_->object_check_max_forward_distance; + } + + const auto limit = route_handler->getTrafficRulesPtr()->speedLimit(closest_lane); + const auto speed = isShifted() ? limit.speedLimit.value() : getEgoSpeed(); + const auto max_shift_length = std::max( std::abs(parameters_->max_right_shift_length), std::abs(parameters_->max_left_shift_length)); - const auto dynamic_distance = PathShifter::calcLongitudinalDistFromJerk( - max_shift_length, getLateralMinJerkLimit(), getEgoSpeed()); + const auto dynamic_distance = + PathShifter::calcLongitudinalDistFromJerk(max_shift_length, getLateralMinJerkLimit(), speed); return std::clamp( 1.5 * dynamic_distance + getNominalPrepareDistance(), From ad9778e9cc0bb68594fa93477238c671fa5cf64e Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 15 Dec 2023 23:45:24 +0900 Subject: [PATCH 67/87] perf(run_out): improve calculation cost of smoothPath (#5885) * perf(run_out): improve calculation cost of smoothPath Signed-off-by: Takayuki Murooka * re-index enum elements Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../src/debug.hpp | 19 +++--- .../src/scene.cpp | 68 ++++++++++++------- 2 files changed, 54 insertions(+), 33 deletions(-) diff --git a/planning/behavior_velocity_run_out_module/src/debug.hpp b/planning/behavior_velocity_run_out_module/src/debug.hpp index 91656d542ea8e..b28725a92628e 100644 --- a/planning/behavior_velocity_run_out_module/src/debug.hpp +++ b/planning/behavior_velocity_run_out_module/src/debug.hpp @@ -35,14 +35,17 @@ class DebugValues public: enum class TYPE { CALCULATION_TIME = 0, - CALCULATION_TIME_COLLISION_CHECK = 1, - LATERAL_DIST = 2, - LONGITUDINAL_DIST_OBSTACLE = 3, - LONGITUDINAL_DIST_COLLISION = 4, - COLLISION_POS_FROM_EGO_FRONT = 5, - STOP_DISTANCE = 6, - NUM_OBSTACLES = 7, - LATERAL_PASS_DIST = 8, + CALCULATION_TIME_PATH_PROCESSING = 1, + CALCULATION_TIME_OBSTACLE_CREATION = 2, + CALCULATION_TIME_COLLISION_CHECK = 3, + CALCULATION_TIME_PATH_PLANNING = 4, + LATERAL_DIST = 5, + LONGITUDINAL_DIST_OBSTACLE = 6, + LONGITUDINAL_DIST_COLLISION = 7, + COLLISION_POS_FROM_EGO_FRONT = 8, + STOP_DISTANCE = 9, + NUM_OBSTACLES = 10, + LATERAL_PASS_DIST = 11, SIZE, // this is the number of enum elements }; diff --git a/planning/behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_run_out_module/src/scene.cpp index 2fa8cf241ee74..7a13c0c4f1052 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_run_out_module/src/scene.cpp @@ -60,7 +60,7 @@ bool RunOutModule::modifyPathVelocity( PathWithLaneId * path, [[maybe_unused]] StopReason * stop_reason) { // timer starts - const auto t1_modify_path = std::chrono::system_clock::now(); + const auto t_start = std::chrono::system_clock::now(); // set planner data const auto current_vel = planner_data_->current_velocity->twist.linear.x; @@ -70,20 +70,27 @@ bool RunOutModule::modifyPathVelocity( // set height of debug data debug_ptr_->setHeight(current_pose.position.z); - // smooth velocity of the path to calculate time to collision accurately - PathWithLaneId smoothed_path; - if (!smoothPath(*path, smoothed_path, planner_data_)) { - return true; - } - // extend path to consider obstacles after the goal - const auto extended_smoothed_path = - run_out_utils::extendPath(smoothed_path, planner_param_.vehicle_param.base_to_front); + const auto extended_path = + run_out_utils::extendPath(*path, planner_param_.vehicle_param.base_to_front); // trim path ahead of the base_link to make calculation easier const double trim_distance = planner_param_.run_out.detection_distance; - const auto trim_smoothed_path = - run_out_utils::trimPathFromSelfPose(extended_smoothed_path, current_pose, trim_distance); + const auto trim_path = + run_out_utils::trimPathFromSelfPose(extended_path, current_pose, trim_distance); + + // smooth velocity of the path to calculate time to collision accurately + PathWithLaneId extended_smoothed_path; + if (!smoothPath(trim_path, extended_smoothed_path, planner_data_)) { + return true; + } + + // record time for path processing + const auto t_path_processing = std::chrono::system_clock::now(); + const auto elapsed_path_processing = + std::chrono::duration_cast(t_path_processing - t_start); + debug_ptr_->setDebugValues( + DebugValues::TYPE::CALCULATION_TIME_PATH_PROCESSING, elapsed_path_processing.count() / 1000.0); // create abstracted dynamic obstacles from objects or points dynamic_obstacle_creator_->setData(*planner_data_, planner_param_, *path, extended_smoothed_path); @@ -92,18 +99,24 @@ bool RunOutModule::modifyPathVelocity( // extract obstacles using lanelet information const auto partition_excluded_obstacles = - excludeObstaclesOutSideOfPartition(dynamic_obstacles, trim_smoothed_path, current_pose); + excludeObstaclesOutSideOfPartition(dynamic_obstacles, extended_smoothed_path, current_pose); - // timer starts - const auto t1_collision_check = std::chrono::system_clock::now(); + // record time for obstacle creation + const auto t_obstacle_creation = std::chrono::system_clock::now(); + const auto elapsed_obstacle_creation = + std::chrono::duration_cast(t_obstacle_creation - t_path_processing); + debug_ptr_->setDebugValues( + DebugValues::TYPE::CALCULATION_TIME_OBSTACLE_CREATION, + elapsed_obstacle_creation.count() / 1000.0); // detect collision with dynamic obstacles using velocity planning of ego - const auto dynamic_obstacle = detectCollision(partition_excluded_obstacles, trim_smoothed_path); + const auto dynamic_obstacle = + detectCollision(partition_excluded_obstacles, extended_smoothed_path); - // timer ends - const auto t2_collision_check = std::chrono::system_clock::now(); + // record time for collision check + const auto t_collision_check = std::chrono::system_clock::now(); const auto elapsed_collision_check = - std::chrono::duration_cast(t2_collision_check - t1_collision_check); + std::chrono::duration_cast(t_collision_check - t_obstacle_creation); debug_ptr_->setDebugValues( DebugValues::TYPE::CALCULATION_TIME_COLLISION_CHECK, elapsed_collision_check.count() / 1000.0); @@ -112,7 +125,7 @@ bool RunOutModule::modifyPathVelocity( // after a certain amount of time has elapsed since the ego stopped, // approach the obstacle with slow velocity insertVelocityForState( - dynamic_obstacle, *planner_data_, planner_param_, trim_smoothed_path, *path); + 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); @@ -124,14 +137,19 @@ bool RunOutModule::modifyPathVelocity( } publishDebugValue( - trim_smoothed_path, partition_excluded_obstacles, dynamic_obstacle, current_pose); + extended_smoothed_path, partition_excluded_obstacles, dynamic_obstacle, current_pose); - // timer ends - const auto t2_modify_path = std::chrono::system_clock::now(); - const auto elapsed_modify_path = - std::chrono::duration_cast(t2_modify_path - t1_modify_path); + // record time for collision check + const auto t_path_planning = std::chrono::system_clock::now(); + const auto elapsed_path_planning = + std::chrono::duration_cast(t_path_planning - t_collision_check); debug_ptr_->setDebugValues( - DebugValues::TYPE::CALCULATION_TIME, elapsed_modify_path.count() / 1000.0); + DebugValues::TYPE::CALCULATION_TIME_PATH_PLANNING, elapsed_path_planning.count() / 1000.0); + + // record time for the function + const auto t_end = std::chrono::system_clock::now(); + const auto elapsed_all = std::chrono::duration_cast(t_end - t_start); + debug_ptr_->setDebugValues(DebugValues::TYPE::CALCULATION_TIME, elapsed_all.count() / 1000.0); return true; } From 90d5b94e91eee5fd437976196a9e6dbf465ec9cb Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 16 Dec 2023 15:31:04 +0900 Subject: [PATCH 68/87] feat(planning_debug_utils): add update_logger_level.sh (#5888) * feat(planning_debug_utils): update_logger_level.sh Signed-off-by: Takayuki Murooka * add error handling Signed-off-by: Takayuki Murooka * update README Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- planning/planning_debug_tools/CMakeLists.txt | 1 + planning/planning_debug_tools/README.md | 17 ++++++++ .../image/logging_level_updater.png | Bin 0 -> 53603 bytes .../image/logging_level_updater_typo.png | Bin 0 -> 58134 bytes .../scripts/update_logger_level.sh | 41 ++++++++++++++++++ 5 files changed, 59 insertions(+) create mode 100644 planning/planning_debug_tools/image/logging_level_updater.png create mode 100644 planning/planning_debug_tools/image/logging_level_updater_typo.png create mode 100755 planning/planning_debug_tools/scripts/update_logger_level.sh diff --git a/planning/planning_debug_tools/CMakeLists.txt b/planning/planning_debug_tools/CMakeLists.txt index 58f73ca3836c2..389bfdaa848d4 100644 --- a/planning/planning_debug_tools/CMakeLists.txt +++ b/planning/planning_debug_tools/CMakeLists.txt @@ -53,5 +53,6 @@ install(PROGRAMS scripts/closest_velocity_checker.py scripts/perception_replayer/perception_reproducer.py scripts/perception_replayer/perception_replayer.py + scripts/update_logger_level.sh DESTINATION lib/${PROJECT_NAME} ) diff --git a/planning/planning_debug_tools/README.md b/planning/planning_debug_tools/README.md index aa46c0e2fc7ef..a89cec2864857 100644 --- a/planning/planning_debug_tools/README.md +++ b/planning/planning_debug_tools/README.md @@ -6,6 +6,7 @@ This package contains several planning-related debug tools. - **Closest velocity checker**: prints the velocity information indicated by each modules - **Perception reproducer**: generates detected objects from rosbag data in planning simulator environment - **processing time checker**: displays processing_time of modules on the terminal +- **logging level updater**: updates the logging level of the planning modules. ## Trajectory analyzer @@ -264,3 +265,19 @@ The program allows users to customize two parameters via command-line arguments: - --display_frequency (or -f): This sets the frequency at which the terminal UI updates. The default value is 5Hz. By adjusting these parameters, users can tailor the display to their specific monitoring needs. + +## Logging Level Updater + +The purpose of the Logging Level Updater is to update the logging level of the planning modules via ROS 2 service. Users can easily update the logging level for debugging. + +```bash +ros2 run planning_debug_tools update_logger_level.sh +``` + +`` will be `DEBUG`, `INFO`, `WARN`, or `ERROR`. + +![logging_level_updater](image/logging_level_updater.png) + +When you have a typo of the planning module, the script will show the available modules. + +![logging_level_updater_typo](image/logging_level_updater_typo.png) diff --git a/planning/planning_debug_tools/image/logging_level_updater.png b/planning/planning_debug_tools/image/logging_level_updater.png new file mode 100644 index 0000000000000000000000000000000000000000..ae91140060b0f2a485d15aa6e814d89a69bbfbba GIT binary patch literal 53603 zcmaI7Wl$Z#7BxyBXmEG8KyY_=4-kU8yE_DT3-0a~+&RJB-QC^cz&YpTe)qnr_vd@7 zreGCLL?|CC=@wa$?s55@Ip{fpO6sX{F&{;v@Vik+36mdSIQszWz!} zTMOf}!Jin|K4|%y9$18+#O>sb>C7Fnmv9a86WYR8q5PAv2T^v24}^ zlixIAnB7S~|9?QNOb@RM_2vJLn0O;tA*OHtSD@O~6qJYkUom7Hhx6F{=l=@c8nxma zj2G??Iz><749AwWM1nbdf2=umkRw--)~s) zP*UcKjSx?TQWbsGYnr$}`EMWpxx-^z{S7P?jVDtCbvOq>nDwLV<)(u0sLaIE4J|we zeC0f25zxl9s+~W+Z-u$&d>Bf_6GpxVW0y#f<1&vt`P_-6NRyAC^!s~Y&Lf&!v+LcY zT=#g1<6ir|8#O;FN(-$Y0E~BB@axH~_)=o?By-_LDNS$#l{MghNXCx#r92VDZ~TaH zeODR0VGwKnc1SF_SK;iX0~Y&%(XlUKQe6Y}7&J6p!h`#8dM4m~b(-w$k=cT5-@p?5 z?2=Z!w)#8`q*E^o5Ir+KM3vg)t$V*!n?6$?p3JU42CI0uwEO1&!MfQ^U7;O_-N@iF z#VWK5TnIND!ZI|FoDV-~-)$;QA-$I8tN3spR||Oe&pgZ4#uMBpQmHeUDweZVw^VTC^KFx{egiS@a~5 z($9e7t+)^-)|x{LeHW0JSH+OkrSAQM|B-_6!<*OMB51%6ECJ8u%&K136S|;Gq_A^| z&*?}Lc9G8Zl55=!T*s8J{pl#cM!(Y>d-OnzAUf!7se02M!lWVF9?zHmFhaYBEtli= zXR~Pf1m`143t`3`@o%I{Kl}UGW=BBq##?Ya#b&qlJT94fp zjwhD>s5lus7yjppjGp`>@_|14|aDt0DX5oiSsQD7bWw130nAd}@(!Yl~I+9_J z_W9rHrA6&=s_x{49JIBrGbHwK+>)fnZwnz?r$^4)q?Ep`2CT--k89u@?mE2EmKRxe zBu2;6*NN+Q!)#odgqDXqW!u;PF^-)Y<`G7u8i-mH)mSRDV-U~nAh912i!&e*Jg=Iw zaFjt3Z75EV>q8I;g>I)f_?w%7vAJez#JCn-E5T;8Mj8H1H~;?gZ8~}y05bwA^o!?r zR0CbDQ}taHfz03>PU-?||AgwsGW$$axlV%s-({<^k0b1|*oKg-X+)K7$>-xMJA>w5 zYx$FArfX!z>c7ZcHd_SWws#2fDuMxNjk!{hp=RvT%E#RpSOg-kI?Nql%W(+8)RoJ} zH~(D|W?%AKk@v4EtnVQ8KO}mE;{8qDSOVQ6a}y4#trY3e5&?ZP{n)L>Igm>LZy$Gh zAmEjP(FS!G3UUyeE`eGd2>C^P4HVowLd#_i%p=7-0HF_;1fb5mC5YeOQW4DWM0FW4 zZg}9g@2ijIIbrtDD(}_U2JTlrI2?n_TWZ@l6>{(67+1H4edE-!WLhvPM67oad|sSX zyWCN#J$%*l*r+Wm*-uMIk@MJ7u?$~{w6?e-qER#RLoQ=Tk2C4Y6ZbwBw}yTwb&RfZ z`Y2||Pp{h9;N=YvW!F^vH?|LvCHdz+YV5M=vH^;Q0xX_vTpy3^}j2`5B-ry1>EgmB`IFBmVjMj!U$~p{8*^#B-n&g zYF;ph69s7wc#V&iW_Smq9*p*RO{>`bP%axRQi+lxBaS;bL#gm>gtx_~LmhIpu_Mn| zCRgzh1V8dV_USqcHo=xMrvN3a>YWM6pXPYwF+Z_?F$|G+l>pN*0ixgoDS0x!Zd@a?Au#9Qyhf&eph)Bub3J;=A+W<0vGIe9_s!de=LtGl1s2FwI4p9$(0mjhNCY ztEHQeW(Njw?zGYa9eS+^e%mzKIe-Xzn;5N~oirtnedw$itPFby%Xx()1FnQr<=Kf!!H-d!8anI04FR#6nnMR((GT(q~ zI|h6Oblc&-%6DQK%kWFTOFb({s%Z4##zQXcnp=p}YP?^`f`3%n3pk})!W4N3-A$}` zwv)!xNlB{gmz}T_c>ZL%FzC&X$O9%ly>a1BTYU#2TO1DlN?%dQ9IHL>W%W}eHgUg$+=Z?{R%R>pKpY}9!mBR-rCG$&KW7#OVnpNv z&omr?QCcjkibE0kE+=<%P9S@-`wOLq)fM3YS3|YFb*<~;K$(OCfcgS~vl;F9$L8#{ zC<@Wg5t=fM($k;kK7h*sOm)`iS-Hs(Pj`D`)91GT@+e+xYm!IB(SCnNvRK@}BpKw= z>qrZL*rZ;ltq%D~O4~+629$xwTFRwA@^+FN!JPims>id3Z^0OB71Xx zI6K$s7o6C4pot{)KADY7?nT%mwjUNI8#^T{Ch;gMiUz^#OqRaY&ZQ`mBfI{j?2xA$ zrL+&PbP7{}%8+QvQb7&FUv5`Ad2^zPxhxn{4LGnG;wgdgC<2ZfiJDqOW5egGh}w#< zfW?^~rV3XfdhMheALpXGYOAv>ywEdAb)rVifyDP+grOR9Go(?Lo7*>mR`J2k8nodg ziI_*}=Dfn+zWB+=)8=ge3nCB?ZxtVBV&)h$9}%tb8OTvmSnv)$nDPBC*S^dst>I^h zk|qU#%?WIB*ML*4T7CE_=m>x1Mb0C>I87qvt-22%fKFIH?x0PIS&Kf)!@G)(3-h%@ zIH0JM!?Ju*++kOH*W-2O%@i{lAQ_T=BV{IT2}mV(OURM|Z0jy8!?V<}obZdw1pxrm z4HiwN@4R2kUcL#oJ@(0ZQfP`$)?;72Gp+vcd~}y1Z&JS_%Z>+lQqRK{RSEBs_0C9a zZ9V_h{7!cV5%&AF@V?lz3%+OEruOW7*T$-4W%u07>yQHdtQ?x#{gahYm~nf3A5wsbEyiJ z^2#q`r2-JURIb%Ysm{DSsJXDvnIK=jyMB?7B{dpJcBW2^LKFk7vV{iiSN=6fQaFs) zY(FOgYV~b^zIj*fZkTd0{bLKZNpKCTwg3gW<62begq-DiT&2`bua zf9^V3b3RG|iGamsaUBZECj5ZQ&(bQy1Aq3mgWt<>|GcvIxB;*m2J9_Ohyn)a=~U!MS|&AOmR%KGH{!=@XsXBLLAMd9_b@pXH?tA8|}1XJcl_unsz6AoQYR!7_!xAza6jxqr()@?=ZFf0Q6`0EUBjt-M| zN-M_D5k*d5EdbmE7MsI|O~S>5s`JCHeNW}=cCutX$7YEc=s{Z*#eVNTxc<+$^@49C zx&nXJWaUUkVB2zrGLrny=BQHJ>FK-}==Hin4R?HVd3N*^o#D~ms$pi1wj-vERr3{p z?^8Kd2v>O?H3B1Myf5ZFe`f5o+iu(WPNlYSoW%_Z`urpR?Jxf$|JFos=viQ#qKKUF zp|+d}Hkl_HrftM)!f{V~I?o}Sw7_TDdjC9y3QO3(a>FST?LgoHKF7CQdNql@D%g)+ z4j9;Vy;#?0!7NvY&d9GLsD-*kB#vVq%ab2DZKMG)-rltWKP6H2C(Fy&UfcJ~=xi2m zw)^i{wog)J%9_f?zB)BMZ?*u{WWg8NeouoLv|niw_VetCI?Cm~7TfXjJa*@H_-5J9 zLo%2hG1b9S#AP5AS#V#Df9sA&=sMu|3Si4-D`GJc^LA%0EpnWHqp#w7sMW~4pL*oU zp{G3rk?nTdE$QoBo$yMxf-n&Z`rSHh+G+R&tzIO}a}uJ)oS6 z7&H#FBhaaS#8X0u8S(Vcxpm7WJIdA!`c=LL^v9_n0=>#?h&mfRqDG+fWoFE>HimSt zm&P}i6{%+dRNk-@my0Ef65^mK)Q;^?;RH3!Zm1vgjAe&D@f%^`Yh#G=HEQwqMmaMv zUAqg2sz0u&|{M8D(I+L23kRvEq-x_179&oWUDRX|J>-ovNz@i&ME(qDSpwIOY35t4`C;2sbC~Z9*^84vC?h4 zeOCKR5Rz9~;J~R3`Mzc5`zf99BO-|2@&5kkiJZ{lFr2JA*9nz@w#d1Uk%9Oil31{Z z%1N-9u%-6zGgwx6P=unxJ8Sn+!*5M#e6{#CUkD%Rm}|`momwb}cA{<6pz_sc*toj~ zVWeBtPzF0TD&#IFH&TNrknwN?#ot&E8_VY}FFUu)^w`%8A?B&>wHroCW!6%JS|-PdnpDJSK|8* z5oz-@)`MY>SIk;?5L_5ltbD8eHzfNN57{fOi1`Ej>8@ww@0w9+hEmpj%7U#wfBPov z4{pdf9VR8X3@uvQA+yaEJ?0F0Yvn3dQQj@3sOD%vt3{Q>@yCCWR@x7(OmGHuEd1OE z3S+=nj_Wh+!ZJ`5-Cn=Kf99R{c{2UL0pYvq1%jO)MKUz4LKh8Ok5I;WzFCYB!$YGZ z3K6XH1ndCWY6DYao5+sB@Kk6AKKUqp4cm}MSCgYYLZ+=;F$#}hI_XIa$umZ7Hz%Cg z5{R~v+OPdL3ggQ2r&zpNh{)%-3Y~*Wy}6b6^n92Qs($ zSak;vQ&T7!V;O%l)8+j%rLb>WF|vh!MFm38OjYowbLqCmYS2R*^sC9DJXd_urqyO8 zzio{iqtjKbwmQL-DlsH$c5o{5OajT8j;7}2z_rP&H)NCR-~Q96}=(%>`cFz*hFU~xnd*#pRY+0gyT&)x7<3o?1L0g<1%rXt`{ zG+nOGeT}awWAoBL>Zdn->c0x*Ubjci5e%1=D!;v`*LLwb!fyR9-#n#m{!z~KzeGGy zd+hc7GmI##lvVXbcFl(T>gn2pBMku4JXI$oysKqt>8Y+K%Dbo<*b4$ z1u!j8^1oUC&d9l^39-*_gwLmGn(*hsmY?&YFqm+sVA;FlGTb$}&OJPL!7~OJLFB4> zNZVrqPX6n|LcvF=715IDIOM4NF*ZF@#MkE6M$}l3LHc>D)Wp!2{eSTp;XN*y+`V6l2z3w5^#g`UW#eg-Z zcW3_4LLOP!hcG>S#+6#q+YW@f!jN+k%1t6_*RG#uczt6++e$a#-)gynyMZmi* z$x#LrtE&k9{w?%Lh@{1X$0H$_g@FK2MxHA~e`6R{8zv|%sbXUSoh>i9#Z5V0l_kWI z65WY@5CGSjMQLXYJ*6LU{tzVe$y1L#0Csl1V)9)26V07yOGVsgCc zO!6WOh-C+ed+n&VKjlJLpGJvZZ~Pf~UygTR@}u~}W5B|ZtTQ&-IX-+d(@eH{zf`GY zi4tW&0V*YoB{}{=mM>bfZGOX#`2v;zci(j)1|TrK-Rtt8<_@|-GNCtErfg^O^ls&L zr83{;BEpYUmv?CM|YA^Jj-8S>x(Au7vhi5q$hlj~;_$O*L?TCbxZLB<3 z<$H`5AL{)DfIZm>T9I%?ys#jCk31f}(D_kahvvQh4&sqI$m4?dHrGAA)M`G$9FAZC zwC>(4dBEQ!wrCF0fDB!g39BClW4s~027u7sz0!|>8>P+nN9gDta>{p?M8f}Q_x?yIi`iJhxf&s*6S-3AY5TP(oq8U=x z-`tZ)%u+VtDf*uvY0FY}xbl$k4zd7qH=@BL5Gg!PV1P{GACmQ5ug+L+{rEB7FD5opzIPw`(AKioTLQNKoj{L682k-FHaY zQNzp8zGvP(OR@f|OWtYj*#{^RVLV!4Tk;wPF$R+FL+9*W-yC{n+Gu7LIBL z{9l=aH%CoJN%eeuPIxQQ9!P7)NJvLW>4^7yM$~ZiwiaryIk3zYmC=HHBB9`{s2c(T zJ*^t*ggzYQBEUeGe=*I@?YEIMioK5TtoafuX}21BaMh1%%{H~fvYcMPX=i_pn?OqN z;c3Dtt>Hu<0HF4|Zz#T$0Sf^)Bkg^*!6E!-NkI!m*9F4!mrHr&Y#-G3t~NDG~Bil;o6 z93wYLgpg>qW3b7+Mubxo7u_Yqg(JP>(f7tS2dO1AGSX-4_Xo;z`vk*92gf2wNb{&g zGfb{HcJ^T2z0=xd2QS=AA`3zUF<;yVZuN2rPK$qw+mYQkq!QwqvxvM$Qb(2AIt#aA zk1TvyH%GgY2C7=rjev(eutWZi9ZF?409r|FslAGLx7YSzWhsyA`=53(iCLHi-u}ur zHyTCVe*TbH&)#phhRJ;`H~TySTT4rmuP)D4jZ&mMl1R9VQ~Ff*{^3!v z*KKUkw%JIdPo0P|6v+bRa5zZ zMV`VPu+DA~)#?gYInhhuyrnW|pQo_7J|m~yMapC~BduXWZeOcCIqvvF)U}}GuSrI=T&_8C7P40WDBj)hUabQ8uwsY#@;=|)RXl-D+V8v;%jyQ8N|4atP}JeRRFH#z1@7Z=}Uwpe|MS>rVLvZfHVx z7DSjk3STH;#=$=*H8;i726A-;6&@d`(&fg0*E`PPXeWb*5u3qTqW>lCy>3TzhpIhc zzhj~O;oft#&elxN3wET`!-yjU(5o#9^Vg6!!CGaqOsC2$fl##iqG_tNZQ^Mm4``3v zv5y%pBhLWvj}(AxpgSS>4Xf|WaYiyr8wTJCUBZRke8jvPXe*VHiSCaXj;0&dmA^HQ z4DSN;C)AvO_j}$P#*g4$%1JR)uRM%Bsj!w4Qqt!3hYlW-kb6#94#!Suz~gCcb%@+A z;>y-H_wpr2M%hBoZh^bd&K(`=Sjku-8?YbIaN5hF3R(zP3nBF;FTH zg=prTzE1B{ZeUu{J{gM*uzFy06c^l4?5&BLsY&e4#|v=NxOr1bt2rH}9+E8GpD=hl zUi2pTXd?T54v6?t)p~`9Wa`?2;dBixK9^8qa;G1-cYm>Mu9ioHv5+0LvNgb=5NHk@ z;o+!Ezkos@mAsh3kfAHaPyGPT)i+N%UFpB!?9?w~>`~zhFq5Y@_zDARYh(s<2LTqs zW2u3plHJ8|oiD+zw?l%!F%;yO8uOz-$NeZW#;)!7uFoRb=`}-CIC^JaB|U?BmZsiA z9arA|^+mu_*8*SdM|d7;&cv+=wulJZ0r-ykYOh_hyz0cLvSL z6*B*b6tdN7oJvQAe*v;E7g3eK`a2^G_}ZmWCZ-iFbrqPIlx$rI;1f-@~PRP3+0FGYT`s5qTL8k*2&DsB6A&NW5mHXDEVIY`b24Ag^U z<)tZSNhrSgWJ~f>5`{$Mv0qNDn;KPDOQMH;E}?QVw4>9W7goI+K`CUfMte$9!$-Lv zqXiqffx)@02-+fzzgrwPCp2#a<))p>o!4nBUGMLDM)O=y5@JPy(^UXD>3EB7{;aA> zv@}Ye{P6@@TN(spX6PKV$@nIfU8E_ITJXVf-QL$b2-(ku%voOSE4}WRTB#?Ew+m;A zfp=5^2D%+9`nS&kCl9xlZ5*_H1H&ivCuK5Pb8-=aXh=TpC{LJ0#M8U}8o3}?Z@Z0s z8B~|V-vo<*Gx?my&U3^(A1ik2_|~3E75c0DrvI)rO+c2kP8l><|Ipz)SfP4R@^>=M ztY;HPJ;@41MP-ROeLy#;0Z<|y z%>76me^qN@m)*w$=#r=hRG&#gc55q248%hjku9|*$rR`JPM(5JSvY_^j0u<$HWs`{ z{2h!uBp-9Q{SOX?Zf|~?p%?_k6s#4M6%J}W*>8}}L;--!j88&-%gpwuyCZkmt|nH5 z({Zwj^M&=w?W^rjj^}yTVRq_FMM+~n6o#^5ck=QxofA!2QWmVUF}y!s@PA!0Qh0NS z|2!DPLg+6vW3?*rS3IYmuzwUvN}05CJ}yM;GZ}>Xn=iQXz$oEv~`^hENh zAu87T(}7c3A@I!pZksS!cE}S&Xjh^F&uN7)zvMLq|95?Rz18uNHXrfm0R@2wm>+SF ziA{i@xTtB8-AcT%j#{Q({UEN&HOR|`ty)#3RuvqW;C{__$5=&3+YUE=Q|(;08ZAtY zN;UQ=0F9Cz_J*y`mxpme4T+k*aM7`-r#~L@Nc@QK32b9mU(?q*@XN5(6^I3B|i73v7>Wc@75?ykVIiIT zLpu%}X3k{WdUO5|^v8pGvxit7Z@b}*ZuU#TYrhNT_$#*9iTvK!{DcoOBL1_iv*}^_ zi~(0Vl8JJe+`+{!%15v2@kW+A4F;X+vwNiM1|ZD^Xi-8H=S%_W3XJNV(OI(P*R?X| z?_-qKT(vGv62$1iwOejw5bGnd$qmbLU_|Sw#=FRD1_=vAZ2f?aNGLgA`dI~FJVgRS z;5Rv@DEkr35@UxfY>A|uHJz5wYvlf*1(r}2$vq}>6S@^9mrS1`SDYi5xqz89EPHg6 z&l?U<#Wn^$JtUS_pP1^P`5admr8H8txpK6h4l%youEP`fEpjOG-6O|Oz5QC@d7pDf ztgy1bHeL<}ycA#jQk#5c;=(^D8YP&=x*9mLFZcal4f<80_{#P73bicxQjcO*3hT!R zH7xY+`Gk9r&80|cvBt%&{GjiS(Z~CEauQMb9AZ50hdKxy%c}OL0luOq;ow5zyrgK!m@n)LT_6WCp`~8Y)nPx1n2gltah}1Y z9730!6&??0=uG_X2+XL8d${@3G&xyp@=JWay+00tGwO z%kJe*!HmjdCTBvWav>VeyAZ>93}5K}E`#07tFECN)A@(n>7Id`;HDPEoM!w(zd~3P zu`~eds%5C)1rcs1CR)vtdo@bZZfXFmPx*v57=#(VErPtUY~-`tJ;htUwQ2m+A}4dX zV;J{*M2n3xD9v)rZt*2{F&tY6Q*F<|J>9X%ugRVuuv8$?Ki$3LVOrDmCg*dk~zZvm-+nS}`|2@%cm4WUhjSQp}>P4y}7bpP*tRv6kGs`UV{O zXf~)n&sgmEzl;xmGxQIz^iJOItZ$m3O66_S*XDu$5C>U)H}4iQ`<3y_LEKr z0B1ETtYlidT_i|MQawBGpP9qQ`7%Rka~hg6pKQ?~C5}H$M|a`oH^LT~UN<^Ex8=rD z>yzeHB7h2L9WQp&=-F|yPWlKrrep`knwtTe>{hpjETbRAJ#N^^>2hnXJ$|nAmn|wb zcG)7Fm9hfbhlD@zz`B+_?B|?ydzrFJ%ydK(U3dMWSP>dZUOKr=hhOFt-p&DaTu#07 zal=Fl1F|n1K9Y(;Quq{?mk!dWvv;&1N#Q|SasO;Ubj~nMw0VTL15N`pHOz$QT?=lOd>SfQQ<29 zc3g&>CXw7~HJf&G4uuACh?N8L)4+vdB3CUlsBaO^kB)R35b&xYB&&sos&CVaO`sRG zIbgEU&_A3Okn~QI4|(*2BNGY#T2A}$1nQ>BW}*kGSxyx8UdZ#OmaX*uwp`9l>rpA z*hJbxQeI7M^5#R_WCOi}LmKfCP5c=CQ+D);sKV6~_L>zNX&B>c(7PZC&-wf~?Gbg+ zVo!N4JKd)(4I2n(bf=~QZ_bIV{Ew*_&)1T*L{xP5KDkbH33)Vmxm$PEueelYU&Qm2 zs$&)Zij+{u78l#qB9~tQ-_-ZuZAA3rt`9Bky8qc!^Ykg(x?Yt~ zM&FK8+AkRuojW#`RxAsqk#|SzeZ^MI(qZ6vi@RAbnMKH&;8liuHJi-bKgOu@k-~;( zI0mLz7pqI1t0Z?As}t(^^M_@rNpr00S3>rptG4eLTq$36ULzBZd&cZ7&06J`7zANM zPo^lGpS~0O;=<6#Pr;dJ`HK#3YK{H87n(b&T|g#i*m@~xEp;HO<4-2BxsX=!laSXH zc|LDE{=(Nt+F~5`J#;V5&V{bZ$*9>b){SSI=Ue}+G$)fI+N+GG@H8A>Dst6A^0Oec z*-w$G--J00@Rr)fSl-m)j+=EX1If4CF_E3K_J!Sf0&_&cS&g_dW2klpEaHR+TPwq7 zo>AuxmtUwlbxp}GlRd`C8Uxmc+x&f5@hb|5BbUBFq;Ws=A`2ziu5&~%HpE5WXVv)} zenr>l_jm8SH2k_|Hhar{d3YfLl*;p;dSCL+zpQ4Dr?R+iEaf*nkk?(E zzX_~f!I!?1!wr&Po-jT~XSouOAb(HFTl%KGx?Vn-MR-n4e|I-{J!D{qN(6nYsp(o# zdxNjJv`AP$ON+5V;N1Yq{@GH4S~oz;v`T7;K2dwx}2n z@S`NjZRC^5nMQ=kPLNT5-u#yXMypA9GCJV|ihX9e)0<~rLT$n_SfOi5w3Vwyq%$}pxBYCKT!~gvGsIDpg_CUO@ zDxxpco&&Bg^nxoW1Fi>F=VZc|GirNA?P~Ib%5>oeT`s)a96q}O6hu3BmH56L9AyOm zw(cVxySKjd{KaqGmbBN1lwtoWwaU$D0**0X=5$Jsak3R)%0Hm?=kGST2xnUU39~87 zUV(ZQ_dJXz5@RT&5?DyXi)!ulWYH(UU&1{DoRZqCP&g;z3;`)ieZD02Y_D}h!7noe z_;u61O^Hk66FdDf1r~m zZKmN9-1z2)=&dwDETV+-4jb~!5>+Lj7SHGBZS2Z#k_r?yP8wo}x5Vuxe;RNkzTe-O z=P_efLEfF9HJzv6THBD@5K#H-!>HB9EPHA*W6A^MI!Jb^-^4{y%v?C|}L z0PO3C_ZKscQF-XnA&kuB#+gUY3Bjz^jB=bRg;Ap=1=__(s0nFF7WYicsHjCW48~9ZRiqHe zfwcVy0h1)CRT4!w+1H>aB`>RQ+Oz!5U!oOyMOC@$>RbFN&XQkx3ZcRc##(#mpy3Z` z_mJ0VwH)6mRXu6a{LN=*MqAzrd~X1oV=-BO{NX$#N3rczno1Q_wxq*e63DB}-+?yA z4JG!o{-EQj#TNfGF=fUp;bw#Psrtl$VunubJ@@Zd(;{dw_dQB$Sr$xes9ch2ZdFDc zlXAV$Gnjs~I8Gn2M?RQht!b;>6+y$&Jv?s{mhwQh z_Xf$GxOFgA8jh2feCd0Xw=Zs}3SYjp-J>?&#}RxTrg>ETZ}2+;S_cO*>T&~XiQ z0tSi+^)S_BP0cd-h2w@C4=@&XTz^n{GvKeYW!oFFZ_1~Niq^W@O@Y=cUXI_jx{e|G zmt_3ni@~IOFka(-ke(CF+4dv{T{w)<*lc;mtDx~e69@f#oTE`yqZ^W zecmx7@!ck&zqF>}dq2|ZI4I$z&lze$14&!b{)GNh8h>1*b+fD+rV@3*ClmIG>P7|t&o%pN=W{f#mH%X`-!8p4*rKhoC&pQsEjc+!s3wb?C{9` z#9X3v)a!!cc#8-&k+ib-!w!MNq6#+;9Q1{JgGd{0-F1wJ6w0c&IJQqyf}E^p|GH1? z(OFj$o{!pAbELz+-~3=cA*W>JT4nqHVMKeUYw((u z6JzwO$1@hVP!9}pbT~jUf$S?Fs+Fx2c+Dr6xs`jdLsx7fHxErv4OL=JkqInruk_bUP#VpnC8Kce`%p!WKSvU^S(L#1G( zn8xb|Q`v)jvZ3|{@fMg~_2Z6~iueX2BGi9p#s-CxW{NEc4fXe=u0BoZz&qRWV5;#Y z-s209v+8|q&nBMM>@P}6$wuy9#7t`oKdzje1?{=X1jO!&A(oqLr1q zcT9)}c|Yt##pKf8@!`t;C}m|mN;&o~Ei%K2@Ki1&OD5!f1&(B<)YDLGS?EPwD?C?}ns(2U;)tCFy{@*O8d7Revz@Nkgc-PMWrZHp*g^99?I2;BPk{)Cs(% z)cxF~n2w}0U$2q|2P4`V$xIgnHr>6sA-+$3Kz$F9dIKMpr=wDh_J{Qzr zpov(M8LCZwwU_INHa6ahxErNhgEF?;__5$v?h9wU%s+eT5^yc#o5k}5$J@mmUGiNz zl*-y^+5XO^1!L} zgta@9){mgY1nu?G8Py|CmV;vJ3BGp#m8|StV9X z1y3^<>%YRa2hj^ai}(XD{5L!A;BCR?w%S;du5_-}kzb9QRsQ&)|Ea!-?^X4l$tOz2 zKp>p1{&GtD1~MA;wy~;dPSqeo%f=k^4H#y5{T9x?cGzXmp0vSkus3%B=R6tW$Z=PP z>2XCrK$a&iT?T{NkwgDKt7~o);Zbb67J8(6=oynToSflqN#Q_HY$L@L(yP0qxzPCX z_h$2<3W1);dGCj4-j-D|a3ej7>OAW75D8f+m z9Y|m=6*$mKXSWf#cL_LM^~k+RExZ+U!P&c$42Dq@+ZD)5nv;xYLEAkjsCxJ$QO&az z5$`gK>FUOHHh(VUPipWekw6?xHH>ey;yFh(Ov@};DoIbf7(Axg4$#YwOKE4cV{C88WP_KZ#E*DqER@#_Rj=z zRiV^If+R5f%89%b(O8Y?E+^cYuwnw~MJTPSMeN7~;yhf{)=BFA3{Pa3FAb7_rNCHv zqQ5};rTi|jZyb@iF2Q-D$>Kko3V&*fBQwQyh4W+dH`6|t7mllyBISGxCYSYzA@*bVpE-~zNcEM}apL9oxZhEwc5%||R25zh$M`G)G z_}l`RBuo0iwl608Jk0$^*3|$(-f<+=B`3FR7zs^``H1t%;U7IAe|`(*v^9l)d z8vKB*f{|#V(&S21(tRoNscz7`8P;sY(el<-9f8x4VrH%nzjiXV;-OWMt+-XuZWQD;F)A=4d)KIg{Zrpx+JF9U^^e0n<4TdBZq=RW@OtmmRY^pj#S< z))Fz-l(MSjUNN{moZcJhzzMZ1OUlVoG;#U1mz7ZUp|=cvW^57$1-;qI&wZk?r99DR z4ZWS0@&lgx$!BMDu7mKwF59BS0w?!-8xs{sVjn_JH(3KGhBy70dD7pzQD&~EzWKZm zT=$#@PO@yqh@^1Y<+OyZA6}c8(_)aF3>xN4L_1pEFVvJ?R>3~9|L}hnx~L-gXH3A# z&Qi8`(I^`D+}=AAS12Tey!4qNh? z2;3o$At0NC191Ez7`EDMhWQ&S%DwaJPv94kZ>f)GL=g=ZaP@(mUnO^#D-9l~cKniK zcqp?n20vq}??=x1XYM)n(^V-d`@a$8>Ah^ATb^= z%$phBvAA2%0yMC*wC~<5sOfoN7aGSzQ!sx`W7QtGPIY}fZ}9Cnd1hH#r{p#o&g(J| ziCe7CpZKsx{oV9CQsv(nmGvmK&M+E7zlqDWiLVu3PDfH8Z2G-tG8=3LioiBigfU3- zhDb)UxA6YV|LX-%Nd{A-fVs>eB!xo%6p4Vzc)WjBeQ!9Lcg z^AEQ7X@OTWC0(YoU!Z0M@bHcG%EwMg;OY6Bglp%%_j<`QGvQ6y`pR zAal@RvzMMmlkJ&cfZx&AYrwO0!1nt7SBn1A!0l4SQ{#cu#P#P75e|ZmOH*M`ZBFEN zF~KU;?~GWx|A)2rjB2WD+eKAWRGNqssZs=yCLp~;5d@T?bfkCby@v!udXp|KQE4K* zNhkDPl-`51&>;x~0x28c_j|wRdA>dNIs1%p=8v`3m}8MyxXZln>zZ>_1$y)F$%HW! zrmuLvIz8T__utG^J_TuyJIllo#JL|trIe^?X?OgJ`BAZ!tna@$K#KjceymUh!5Kn@ zt)5-`vB_YWoUGcf!l6~1|87rf1B9c7f-66I&MCcq{gj&4{{8zgou{|2=Dj+2 za9icUhm=Jup893*Qy=kJE+#-ZqTjQ{!pCDH``{#7)YHe-hjxwZ7e9l9ICrTpX0a+w zcLxb&Nbj{%?DB5SE*p=a`3(xDfs#~5F8Hq8nt$u2xY(1p{e~g<_;gff;YazWlQ%2! zW^{(MI5p7XbU zyz+^?Q@xN;`qGg34LgIB+4+WAFJ@71m#2A6MKl?SwHECGZzt&rUs6UiN=lnGsx!Af zpSBVT=247NX?IU+NfX6X!&Ow~Up;lOfMuvEu0h+E4ngv7{Q$HY&}Ba-4*LvoTxV`1 z`AP2!>2sK0&L{{#GIh(#pXj{*eRU-!EADO@W#ES>aKMR2*tT+Xz9plpAR;DfK2S}# zRFnEoN&ISA_qvKsjv|X>5J`Rm-Tt_$f>|~yh#&|Q_n+N1$GHRHYVA{Hj||m2-Skks zeg1+w70*9k8+)m>6XhpkHu6DV`rJi=N1g}syZCM@TEt)h5Z;52X=LVj5c*)<6_nKy zZL98}h0SzO#4_aZFk4Lv6`vjts;cD>B>FYlHZ-wkarQGq`*ZO*H+T7V@CoCu@hX+p zyb$DuM{9jU3*wfk?2fkLpOW{@;8D7OD}y!QvN(UP+M9IcvM!h28%LJ`WY)G8sza9+ zpK^2jt-OyhyP3+7o*MSxO#=I!e+~D)E)6NPRR^fMf3KoOzL@$d82m2*`p-oLWDtiY z7M;r}{j2@|x^$fz2n1g?7e>wK{JmN+@3hiVDlnn&i_HJ_{x1s1-}=SDvC{3)Jg!{~ z{byxRNx-+#|Fr$DyPv4z8~UgJXoU+fA{g-YX&o^7A8*o2pKEBgjQ)F~{__XT<6*u5 zjE$53qc&k_i}xQbn+`{Z?Vk9*J&H7m_EvgFqDh1b_lM0Xlg-(}o9&H{4}?wG0NiLLE`aeMJip^p9X7k zo&k?;?h843$CkGa3S}CaNV9}7%+ul}Ld3CWCB44(Tq3)9H(r}> zoh@@{!T0T&-`X-obF(X{5MpNF9w3zGyIe1dy!xEfQOEI29wZaTIPvxE@yieCWL?w# znIG`;r=C;vvEUOP45YEyxShhK5I)}0fDNBh3`>14TBssf1(jnGuLez7%R^fth6aho ztj01+g9*Ja+*bF={TiwET)(L*KIOjIBwpdPZ3iT59WcvvD)HNV|9P7B$p?FagEM_8te+AopOlzoREYS9Xg)|{_KhXU zN)tYAI62)r?EamZei&IK8|eZ!IA4DHe(bc0@H43laBc(|Ra!qaN-=aEc{< z;3S=`b+~Q?$?S<|jYk=WYjhJE+wT*i=4Xv7BGASIZ&WgKR#Z|8#rIr^I|ChVxVX z(V7xI-)`>2snU4YwN!Vghxk%NZ5Iv%@6WCd_d7LbtoLJR{}NpEZZ=HE`7(31By&Wv z^wo&;?pqB)0dt`@c^%tld}C?sBr2{NKUW)k_mWL+Af)u%{Ve>BZZ2gh>C_jc-knnz z6EUH?H#<1_!=9r-(-0MzIj??Pcx`8ymSSiu=e$APQ1s#*1+T&F4{wuZ>jGqWJdF|J zNhcqzmwO290eiy>_)QkYIr41#{%qNRPhQa51Jh0~(h-?I3x`JTvOH`h|DF9yk ze$_f@6Vn(BIF3-a+(ipt{rC(;2-=;?3K9FvPp!NCvjlZ>gQCBI(UQHU(-U}P1Kz%B z*cS`vYTdKD5nVQNjE@*A(WWsyz%f+&nmqhiyza|t+JjQ3WRxgUAI#$T)V#XcE$m#b zR7{y@kfT~c@Rz&i(nS?4w#^+56w7QK97^*mzW)!<`ae_naTyd5^+JrO;y_Op>C zyYG^tij)G7U((V_${o|_GSx^`-?Z{h1KLpW*is0dq}+OMFnFU*c$07wC*mNZQDq>p z4Ps?ZZHaTO^EE(u*D?F%n+)8y*jHhNkezy4PlP0F?p7xX1pwMg>KEuNhW3e9dVgqc zPNSTESYMjC;UfR>mnh_`|BkZXw{tZJR-BcjLhoRZk8R<_1E}IuY(P@_(pk>T(eCI6 z3^4_3HP?7JeQVpV{cSa%ycM1rjgd@~BQkUX2r;MpeEE*Ps~NoI<1NE9&BB%>Ezq~_ zvw;{9q96490MeGWYUj~BH5oBxQ?d_B7TUDkXEKHc9}TPR6E3j{Bp^BhwC}(1?o@qM ze>h!|y1%?0g)cHWR}}6RB-Lk0WKLOXW1bv6$nRd0JW2kP#vgJC8o-!V^}xf9tU*KY z0af;sg$wNX_@D>LND8x>QFpC?%*i%8iBnC^_RHX+)St|Fgj7$h?OE| zb%r|$p47Q?!HV#RT-b3Ra^p0%7-^ekht~hg6)&W=l=%~oKb9rEKIT%AfoM5yR9#BD z@4|?ug$m)aBi^3dx|)2s@>`FG_ngX|uu)!86C1FWtJ1)b6(4KHbE)dh`yBL&#$r=>;*k&f{W1k4u3tr<{uuNyzU+Q%jK z0AJ;7VncC@vupHyVq^L+lPAC56-fs8Y`Bh%GX!bJZRCIyQ4AhB2kF})@Dl6jt! z)!FJn1^=}x^S-&xr|Xwfe6cLM8Fe4F(>Pq{XUM`cv#ZIOZapq>b@_}Uio>((E}g1UMZbyAnd$l zbDUM_E(maCRg4Q)e>Xb-%@{{}mO~t~E5V27Jx>@Vwg&jf1dL_QJZ%XTQOOOZxpR(V zXKB#}7g1aWN~S+O1s-YE+vrR=CswMoC+#EYLI`P(A4VGeZz98CU5s+ z-SpSzC)+d3y#}b`ml{o;6{lkro{j?sEX-I3W>3rpQe{v<(o{QI5|kZChaM~_jI!5C z;2wS@di@nw;0 zc9P8}GqX*FFW*@GlxaSJQz~NDLB6jFx}znQPF7T;lrk?r1Lar2+3aIDzE{y!#aGxN zGGqYdxR{yN0OXZJ!ZsewQ5P~X?cP*9iI)%wXZD^+08qc7N+;b zS@B=_LhoQI0yfBPW3zh7jgkdZ+UZnv9`MaP8nbKHJ2SS2zPQc)Mci#wpvZd9x;?g( zyhJ}?C$NU|v`LDK(cE<=)yQGaZ9l6wfp5X-mE(=X)K^yB?T|Pbw4jLvbNM|b7C?M1 zv-HQPUlS3B-yWCP?)1K$vc_l0nI_-L4^qd}6|BPQj}g}lAg@;A?s_7P7f^pQ8zY0J zN6m*`MsB-yqh)IK+(~_?eEWqK7MlcO-+ZzIYC?3+-YDn_Q!bz7pmZA~XLj_sS_1ST z(bebv7~^1-zS;U}Il=m%QsPWdE~llFk4#x_pN-m$ z)uiWBS>0oFc$wEhpiEAqiRK___*fPEsd!va2*T93>zC)T-R10?yKfsqa`lY^hs+T- zeP6Ab6NlJlQ9wCMm)5u+zdbWN7a~5H)@gO`o1fGi%$rdqhc8r@;PNxpybAkO(#^^+I9ewP69yX>B={QHe19=t$#9QZ<}L!;BrD_*o;zs!*kzWyhk{qL(=^o2 zQqhc27Q=c_aI^wRH0tx{@;LfPk;`T9=N9aCI0j zRlb{6BQ}&>mBaVL(iFL>b|2GcPktq;OrJ%@u?*y@&(3l%3rO>Az3YvedGzK1g1{2O zz0>P-AwEl)>HEQQAauV$l6`49CNaS`&{K=Y6xDfq#ScTWyKGUuRaxE4x&qPoX&Qh zgo~w2EoRZYzSJ~i=I>LnJ#8gf`mAQ#n}$8zxah>$Pljb@?y=T%m50*X{qu+9cJY-U zlp{H-2-LbW!J)3^>sN}tx&H6)_}?|U1>+=p4|j^}Y#H78GixHR=H87vhd&#a2^jx! zB@c%a1MI<2TBb|Lti1w-5l2A&cCO zAWnv8{%`@F)p*}O*ty3mqSKdtQ9bu$@^=TyEy(NDW4Y~Y_+ zJ=0g$PP60MHW?fgH;D3!+GH?`B~u=GVLXG>SC;&oN}Q~PaFl+7Hvhq?u*xU7cvp!+ ztD7x}2rw>^)U{mw-H0#M97$Ac(Th*DZVA)1K;Ev?%GpY&4F4R}+-&FApQ)!;W z3quLS2V(r>7F+jE>dLyo>=;C_)u;=lHRH^-SAkK?=Utc$lIQC)iUC8kA#3`|u#-P( zyj8r+|L_4TtokAXdi!e!-)paZ_MLS3_ugO5{w1AEdTZ4kx7~#wza^t)Cw>k!i^wt2Rd;1wVfzZxa~L6<)UD%Qlo5_W3)3=!Yo zj8hEi0WGAaakg3$eqOz!6?Bu5s;hT}%N~199%%ERC`^Yn5U)Y*=YC(;6cjh!OX;@h z#$iVeR>;jQV%R3#YQkc2mAJA?IS?bf&4*8QhqId=4dm60TX z79q+a8p(bfVQPWAFG)$M%?&#@KLuhpK35;cPj>@(OHL~%8N1d(<)UI`j zeuk^^y@x@C;j_yAthRrz9($cPF2Wlbh+$Jul95g_tVKV~lYOn2zzw0o`AV+rXX`hR z*yK0f=g7r3oqMQyMpxUxWGLpC>|u9`@9I3gSHz_MVX51bm96MsI2nuOs(%FNnH^*nHt!a5W%kmvkZ*(Z&`=u)*;?Q(e z*1x3VjXi9no##CWGYDnuBkB)IAE@sb-$L{+mf%71uhL2ooA&7QIz9W|#UQ5FXKTIM!lAEOlwBqepv+k_d4)=-OO6Q`yQnrE`*k}`7dTR!@mmK`)gkC7)`%!3`*i)6r7`$xxIb60q2w9-BvzJ5;<)b~=dD;`dd9$bLW`Ym@{ zi3?npP?>d)c0Bhk2q>~nBM*dZ8KKVd9FbeG@OD@24b=1-($>rQH~E>=W-IRFoHMxg z;2qx&=&ONS0hCaY1!+^?hBTp#)!q~}Qa!L)37w4mGn<=nH`v=Gm3Dhky9wqkOdzWS z^h$QecRQ*Iu&JjGP=5$ZnNl7u=F#U(PqU^ z3?;_RF9%8$?iins`ET(`;ZGZ2rzIzEyJE2wqGZA7T4iYL~nF%f>hQ4Bw~;>^LDHILZA=r>8M{xWVC5$D>in$4~2uLj^a z@j%+)%!xdd*kmM1SVdE^r_4+bxs#s!NgD5(>tC7%sTQj`cL!!y8mDHA%(*(&Or&DST4GqBlFFYZ+k2< zvaaH)E_=bMGj3;!@s!TnLQ(PM!&h!{1hH={>t0j$FD9uwa)gxZ*;9W9_)MaU923n( zNW@186gsZ^r z#_viiim)rz?JJDRtKS$APCPPbH5fo1NEzKa>>vO#;&vbmqti_K6-Qn061mz?@BS>q zR=dk)z>`P##uqfpHat75s~dg}zcU)&{f7&1)4u2D;Dj7MpP(cS!~c?Wa-?c^lnq{#V`kDL74cT__j(P2}& z8x!Μ;GVy*7tG>w|boBVQ(&4bbz-wi=J0IJX)~rS%@TD(|V7Y4kp@xCu)O$k|^@ zL>_pUf`|bntzs_Ez3d`EphM_gA#NQ`qyn~&eVtOwc36f zt#JRp0j!2^gX}98huLb~z-1k_Wf2R$3gndLvaUoWW(fjihBIF5MrQzOx z3>VBbJT;-hrBfn)%(t%i#XAb+2gcd-BUsFrUP~WkE8TKQ>(vVXf5xaPXezV_U;2lF z3a`l{06-FlQa*&lw6gl&jD$kY-}(&(9r7L8p-DP-3P)r%?zCxCS!pZ);giD zk6^dtVQnPH197JIxF*r%E%_SQ7jEjy8C<(_ZB<23B(@Odc~qs45htNvcOpQIy^{aU zYX>ijJB7Xb^^N0Mnl|%dO*Cx;pT#wgCguYzVB;(-!__R=cqH93t7!_#T;|8NIt^2? z+ToUe2coC(H4doD&w1f0Xx(9z*cHdtw)b4m!+ta=eXMR_*m-*HF(qg);=tJh>CRj> zUD$ByRSIbMNVS1pUw|W>aP;Yfwf7yLM%OeM=cjh>JHA$WpUX${&QNv4`)*tz{hBx= zZU1M)e6dmg+>{u0TF;k!YITz#J~=ybFeq`6aW=YD z^CVAce9kz~nd{55{QGi=Rz}lRUfYV?nx@Z<^l;N3iC{Fg27l z9=bY<>{!5lE=2u$+r5jOc>`)JOA`uzectMB3SsxgbhX9qA_+~z%}C>U_X zN}QGdO^%<-?^2x-T2+DQVQ^S`OTBnPb%5qgL|U{)hVT>n6D?zO61PT z-DA(3{XHDMZtdLB2R4^#o)_LjcbA?TUgC_IpmDztEp>iS3a?qnqYKf1xSElDVS%jX z3Y}~7^eNcl*fGw4=dZoI%MJi3wmF%H0f^pDEjtUOPKtzc3VA{vsV=@#q(IUyj?PYc~B@h`y`D%F~(2edY@7N(2+|bbt5*H?jXy z6U1_AM6FGu10z;qvJr8uBBl66=bVMU+|`|03D1*U-`n=0ZUqlKQJWTHK?)Des_&UV z92K&}U4<*ouli&k-1vV5WU&krDQ4F)%n*L}35%AwS_ed7%xakqDs(7swJYb4v&4mI zpLsHqvaYpvRj#*^x4XWgrN~dTx~2N++N(?6P)OUS-@`Y4Fj{l5@CeSPM{eY7IS;c2 z2sLo+1ppf-VHwV5)kABq#P!c<5Wj8s;cK7WljmxhdEfWT#G3*`+Dv2gSUCOw4tR9H zI2mO5Io{~)9cyp5-Cj0B#F(hi(B!|>wSNw{>*SOqRk|B%m~hepG7`21 z(-!>l#0PXIEA4N8NK<6yc|O{|+N()QZCZPI4|>KnoEbg_o43Ynd`fO)91Z(rx_>mv znxpw001LoBgr%6dY@`QHkITx*XO^=~BjzvqzIz-oj;r-!vDjAVLy+nJc0BULVU zRs5^!bD6XuiW0-b-6{IYQK10St=g{{;O0@hucrARQdEi%OqD-qFbe3Le!E3!3Yme< zjuRq>yyHA-?n|DOIJ-d@~P1? zo*29U0(KKhWjpx%=kS6=z5L~^tc(TxW%;+P;NMp=1U`Oi{GIo}xIQxFu`d_Z=rx?Q z$ab5u7iPAPzJ<+P&v;+myit~Whxm1GTvYfX#(iOX{ob`BMUmBIU-G6ciYe`^i1gu& zFVg3yD`t!S;M&yiTwCGa$SJQK*8c43gNcE+CzpNonTNMT>0dhkZ_svNneV%2ykF1b zHgZp-wb|Vtuwigi$ zijRo(eiIb%kT6^^wL4mT;G6$dF5YGo&~unTn5 z?MJzN0czdSAHx$*!cX+4C)&S_31Bh0gWDR4*#}ks4YDf3raZ1#HAiF)XP=|K_h{2!>@3@PH&;bI zRWe*+;DNh^ej<^ekKDbZ-)r_502dcq$|z!U6bn#iRX_PYB^xi8EXH|;9O-z~%fRC< zYPMRLAviILaX)fJQW}X~2HtQTPoS3%%={rCKMam=EjSScyUm3KjKs-YDB|4U@m>p< zU>hL6YLo@iURs505UlqN+jySCZO%GOxS%bk7Dy@{>4EmvY8iJ4u-t`hTU!Lw3&RhO zaA@NT1t~KHbU%PCEcc&{j{0risz!uL(fY|Zy36Zotqf<>r|~8<_kCdVO!8+)lx!fY;D^%$XF&bFS88swLVpB`V$-MTo-;lErb1DBv_M~~>f!*-Bl>hog-96v)* z;B2#S@6CI`t9O;f_aC(H70Yi7CTlMpgWp)pN)W{4KUG3ZnDig-MV%Px{nWoBdQ#`^o9Qri$^d6_*RwpcS^oms9T&puH3w2ZTIm%9X5t$eUPhE zs9E^N;vZjyMkNdRpYTv(hKxE0{ABraUY~VUMx_5i6KF&aYdYR$XV-hIk?huysx%Iq zD13$7vWLX~0S)hN0DD;INLU`p52LWz{?jjG87EH;YDUX`Li# z>Z+~4&z9a7`}t&K5QZ1AK9JR%{lIz!L z7%**jF*3V4jlTC;ILnW8P3h~kp|-u8nh9pzmIT`$u&Uc$^PNYIbis)gDZlCfBM7vR zaq#8GV=FV&GE2jR1t)y=x-EznNL2?tWsLzIT3&-Du*yRR ziavE`xvx=e49_b?le8@lL6n*$+{m-W1yc6LA~dG0N8t-`q^oKiJjtVRbd-1W;_Zgg zN!{OuHncvE&B9j~&hvrs)pm&F?a}g=*nFJG@GdeS0QkfRV2hZCAY$>U4~oaz3t1(+ z_`w$HH<_k?IKTWf`E0?JZ)SaCym0r@b#wPRSoL(?u>ftQw56fQx^I$@VUEbkbfrsH zsE@kio2Gb{700oaf?Ea`+-yx;$jtjP)#`OANR%js3IzZ3VwKy(-{wo0qcV78h)vwR z>V8>g!y5?haS~x=5G02cF$-+iHoHIg`%=k_lO1^7>knmMUdbq}u|R6Cscxe&lQ!zc zF(=>p)yjAk^3M19YPUn^1VMS3Ewawang#ICX^UBu81dvlAG`iK1b`Nd;P)wAeA!4H z2kyRg)#(0+UQU{XvW1uivUdX7(BT+%D*-il_hR+Jx+~T|=t2FVlzsYfRHb}q>y$k> znnn61*MjEl50u@;?xPFBu4xL=@G91_TqBo`-5@6lCv2y?1n&`Hf`W}3LuJn-s`q3T zao?K?(cP8)@?->1WW-MGaslPDp{%qNxtleAXH?X|j{UoPU#t~8-4RVc<^Sk9XdG6E zuB<=i36q7o=TOBd69?vg(Wi!&a1NeU9K`TTO5Apk^^VFnX83X;$yx zR{sFpqf9i5Cq7k(LZ+@DcCtOOyhqs1l@$TLmI=G|(To-9>IWkDiwy`Rp9{H6Uwjlu z1wSt<3(1sY)&5xz8J^ZCH&B*J{h$w0!TD~FO2Taoq`Lai^wY2;Tc>2Ha(V1K<>oW%Fh0vrD&?- zvBah9?g&oZdg4M8H<{7K25@yd|Md&O=DOo!W)Z{nJ&D$dcB|T)FQ}|0hgwnP8-){X zWXZd*lFr@5^$=aE>UDOSDxb#mh2C2&K<-R&o#;0# z@+M64DaAcII9vkD++I&Vr#)1QIj(YC{gLU5dZ+%l3WM6KCa&ry2>RK2=4EpX2j7Qj z&5oY`P@>kIy=AC8Q!QFoho=*{$XQmV7AmCBGAm2g3#A+TFt4<=^2fetO)0+{Kk3v= z>kgy~Xr1ZcHCwtBZ$QcB_PbcFV0GNdU+srb(T3IhI5w#^`I_htkqT3}vV&jo%Lf}D z-vzf==(`lzcQ&}P0?OQ~1#)<~c%<9!Javm?^N+W4nLtb$(?KDv7l`etkS$)dGG|m$ zb*VLcm~_1Tj^bpRup)Nf>LolPqei;7&Q%Q3*tN16I()G{<2JmO@jMy<>~8^ky0-4! z5h`Y5CY`C1A^cCW8*Uj1B?pR>thD)6?Us5&ACOvtJOcz zgC!lGz@~Ai!39Fh{PESc+~b2SWXCSn+~RNztHT;?(kvD4vH6tyg*ID9Zbt>3o2)e# zccSgn&)`e>3wuzxSyQD&Kvq6sVS$ip)&SaP%Q3T!pI%+fy)d&7VF|e4U5%Ai=r9|n z(XX;@XRmM4sl0*N1`3&;L7Xx##$KkaTgldjHZX~L*!(xog#Xob8BJ@~>>&Lj_ip8F z(~X62J)?Ld6SD8Jv)Rh&!Ua15L(O0K7SES73SFkhQ6XPyb|pTlTbV64(9^q5EJ~#@ zts`wQJqeFd!<33|tqd{S#X#I7bXP9z7J*%77kLK?nh5)BERT?_kHyM-AK%(|w|{2K zVRt6q6#>gWaw_zezcFePvbQU-RPA;*S*jLQ%q7a?s>BQpg9z#I+p%@*qsDK%d}%;05j2=Y&^aM3Qn>y?gdM`6Q!Gue>u} zmrX)&%&~K%vj);Bf&6LL(;M*gbyy4b37B#(nZyXG+(;-w+n?75Y1?q5o-#hp-RkfYfk3>UoG6V*Kg34H&%&E(bRW<4ntq$bQWk1y`2s2rNc#-rVhtl-vH`@J6R-n+%M=FA1%B zG1`$oWYJ0!(JLcF3RkZ;^xcaW%xbT<5oM6blcflxSc#$zvOk;&Y|a{s34Gzwuy&=4 zB!WiJ>%%n@$Vy*3WQ*RGjH1W}|h6z}yh;HtlK`ePZOLXTJzn$O`iV3=uCWP3oexX!W zw4orI6{iUs^l>{T3_G1~cmwrq#LbKm3!)LTFmmn!Z8DdZ7FhsLJIh7xYeinE#YV~= z)?l^I96bh;97k|J^4U|&q28JGs=ZmpbZmIvedl{KD!*a{R)54}Dh%znJgA@kwBRV6 z;Ke-jnUc)U`I(0gtQ2`yzen3{_gOqd_?ublqf`=s5=}RxPTzcwa(N`8*d5%OBT$YU zvBuAQ|K*5!*Qh^SoIYYb90_W!{+W6rpJg7Cr$x)g|AO0H*+a^;k53+L0%hHBM%TsE z|1^`LiInqT41M}_N4Iw*vlx87u!=S6Lw?jhr`yJf(hmrE-Z~FZcry(vME|-lAgx4* zBXSvoO{wdh&v#1wmQ+o2ze+bqn6=u|oxoQcZjTPX0rA2-exr~ZzCiv%v|~gA7Gnb* zRRd)-K%gDbNVw;6S;)k;C#g4_7%7rt^tvahW5sY#rC%9p83rudwcWFxbnSJUdo;ck z;*&D$NGs;Z0~Q2CjWenhgX`G)!gTd}zl3(#hKM!Fdq2O}{xXX)?$59)f#MiLBZhcp z4|C@PO27HpKbO)>OxnF_B*no|_H*r;E-Ss^dq$6gJbN`Gsf;haIt9zq(ag-*fW)W+ z4V%d?3r%;~0BrnEZ9Q(;vfZ$=X0gLo5M<8=Zmr-Q#}UP&_dKj-`9KN18QBWoX`Fsj zf4JM#e$mx&vqIsLFE#s1*}+$4Y(Rs#xW<)1_}Ssqw3HcJqNzD3YIaM2 z5Tgp#>OH=bZLOHOPOn@3Vdj8G9An!IeN+kJKi$v zb|&Z@qBFe2`OlJdI$u~rpLw-#C&LU1M@Nm%DMX2Cy>DAceZ65(lq{Y1-S3gnaj!cLqjp0%P}PSSBXgC|YQgT8Ve+}y z)6k_St=#u}znA};?*utlX9UL+!*jOi6arg^ibJz*Z)BN7Yo%r(%lD^E{C;g3j*!5r zJ(TIL)>yRd)VZr~kqOw>n!feF2mntd*36y zgXV==FnK;DqGPX{fYOr~Toq@UmOZ_b0H2Ly6fWI7Cal)*np|oU>uzsXpH~$t`LGZm zB)6R=PF%jsnW26lJG7jxpUCXS5(EQ6o5~0AV-5c#mj%>bzdc*?Bap_DGb$fS>=TZN zyLA$0ZUASTP4FcF@;&)%Rk+P+pwh~?esNa)&R3R;FT1h?`gq)X)ds{IpwAfU5Zj`(iNKL;wz6ccFn&@!-R5u-^sRnov|4!N7jvt_DpteHG zLsFJ{L2+)YubcY#^1iwmF_uWtlIZweu*R_H8-uj`QgV36N7&g>vn)FQ^$JY#V!6`S{>H!1+{t6Omtb@B*zSCo5IsL4Oujna{?`Tp-8Dv z&xZOWUtmC^Ji5?t7%nRe{XcNuRA>LieKYuyZAR}RySCUGCSi7w>sJM>^Mezo!4}!z z3@Nsui;R*v0XQ(YI&9kuDvM3i(s?KG@lEoXXQ_Z4Q5$$}H(H~Ql!NMC00knN*!4%# z@e<%Y-DSjd0b)KqrT4;Wwm=Rf+ZHNgRPvZvlwm68sEt=Yv)gGk<&(xeH1R`pNtmUx`|fo@e{Q~e6n^&X%%v6ojyhfL_h6(|e^;2S*Q&ElBZ6cDqq1hL zAdRWIpnTzziBo%{HJlpb>-|))U@ZjP+Z=gZs6#DFcQip|b-Fe^B^zWF2r+6%BK1Ak zcn7?GdhL!@gUEVmSu@9@I2fF52(8 z+Y!5d@wJra42)v&5~RIuoqVhIXdLfK0{8D5g31l%fRYy+Xw0w`K6?Tayty919h{aW9@zd#WU-AmaV-8lF04uU~iG^&y|oDZAH zTlM;8#9|~MS-t%WtWE0*|I(b?`U}kwfvV28@tnwN&PmudcNC@uq1uQj@^f1S4rHwk z>p9*|rowOu3evvsjJm-aMoWquT(X%Nq(6gN&I1C!wM6e=OU^w1qzpriWtVU@={zHU ze1@k;s#!rff{AP7-sn+j4ugRZvstf2YfiH)5k2?bpQ0jk6%hZ~EQa(HUa#admlI6Q z@In!L->IK;1~;yj=F;Eyiy{wsB16(pK6*ZM9>k{l;=T=uXcT@`x%HI0?j+?NmjEy> zWYN^Fr@SfBH|>i;?IWFsj_fvYcu9s#Xwi7xTK(~yv48eC$aW=b{M32UGztIc_F@J5 zv1J+iV{akH!UV+RNRXeSs!QDjW7lXvqB2`%-`KITO6@gj)_c*eV}g1b_^`!{aHI8p zO_^QXZjdc5^=VI0X9)xL=Bs3Mi#GaVyJsx|b`Lcs!B5wQ*@Kf z?yyJoi@2+LvVjsO0NIcSj#SAGR1Y{NRCm8aKVk5cRgWKwh%ADjkU!}##B`X4zbqlA za>##^eJQ6gty7h5Kry8|ts-V}JiYRuBXnNsXjpV%{I`GWDTt`2o-W+?oCfN@EE%}!UZ}%l);!C?{+DIq*e`tcU|_Iy(P76OKrf- z&oaKDt{NptRs>MPTW}o7X%H!x*~xbG?fMI?>49~>P$}(s;xx;Z4(*xvz6SQ`{F9fQ z0&)|z=+!MoD0wh*zQ5{TJw|A#ia|EyAkrrzD=`_p!Y?H(mcOwoHlnU^lryun@IX9u zU!(W<9zl**Wou#$wTb57XrcBmt$A#-J*dj^L-X?soC+8=C{xx|*t;Xj7Cng@_C#k4 znRwp&^@EQJfV~G0T5PY>rn@p2L38Kb?};UE{*0OravAgkzki+bUua5E5SiV-HKkFd z@*8**3eJ#W8zR+4nqzWFjn;;U2J4q3g@#aG5Jcoq1RsW$>MIUVT^C$&%9 zeNQxJyawvu!Mdx#7@a`cQMBPPVnC?wAoj zL^?0LP!YV@|{;-{l4G1_niOk{v*lE-r2MEn%OgJp7qSE=xD;&@qIG6SM%DX zOKQpQ&N0-F;Soqdb-m$WeWQxu6{Jx>@rttXWQl%!Rf7I7SZ_Wd90Sr*Uq6f;tA4X~ zDYm;Cj}H}mb4S$Bau4SxyPy{%Y9sHKu(^a6UA*DwRi2p6S}7XnbZ3F;>#jl!YJN2t z{jvIyXEdZ_A-gg~Ti|AQV&Lrsh`D({=G}W!u zTGGjjldsFhQ>hMYc4_o#)w$i&`lA`eW-qVzJ@{XGMqE0P@S7yztDKC(j^*vUqy&Z;X%t7$_+SuksO$5&uUSgm_1!=WJ%xzzrn+e0FFtKIA z=B(uCw;;`4SfW1S^uZ_6jZiwP`Ry8#3r?5= zMcxHwa?5g`i2Uwvk@3Vh9m&KOG`p)T2Yv!qBC1*GM|N-jMSum(>@E@c8S`fXT0zCu z-lN(XLrurp!=9TFgCwm2@B3#-uF8Z@B223QN*kXur%s*X1zcv}*V9}su-RD;d~lL+ za!{V(mpgs(Z4y*aUf}0=`>j|UU3@`Xs^3F6+wqE>AFe${_l=GvKcE0ao4B{)P6I)^)zE~B z#+_1mpV!G=8HMQm9|c6GRRHRKrNOEJ-qydF@u)d4Z)I?8{S3*KTNZL7g;8fv z8x?)t1u5d2;lp9oa8SLA0d674TxnM0;!jq(|F#e!!9=K zx`Dpr*reien_`t?A0jUE-E3beS^zNl0kJZruW1v#Ir3MFHsL~|UNATfIKLmYa3ljaf{KO+kXv_*v=jrvvW4yzqj-(EKK)8NZ_BsIJN z)PqTT=!IVDTQ0bzr`|pIVn;7{iodsn3VB#AVzgJoTL7!65hunx0c_&n)xoKty48t zlpFJQtimg9pxE=lfw58jL!% z>7>3Zz4VWy6XI2Fa8v!%aC-(kJ>etcigF}HV0MosPx*&(mv-(f_<9& z%7X7`4<@ayjhVQ(xCNl zKwQAxW-#hhiK=+aeM6>bN!(40Ja0G_H*J4dGX-6I0xEmRBqx!dH#PwVWd#)w&H2zs#d4Vn~+8ypwKy-2ZP7+t?r>19zFpw-d#tsBTT$-!eV zKQ}+S?y>Xni>cgD!7ETNXStZi9yrZqd9=7XI;rMSMqrKl`qwJpYM!+1S|8RbL-+j8 z20+h8h}$a~Ql?daMK=rNiWund?SJFryZLxJa=ZXCD^XY9)yDG8BG$u1v_Dp~Wz%}t zj=f-}Eqe7^RFJC=1z&?Y_2gJdNOEPp(sA7^l!zmx*=e+5d=5q_=&i-)W#fu!W>w%D z4EX~f*20!=A@-v?oVZmHHQ!#IFcU#xW=eY*;B3=IA<)?EBy zybV$r>W{coG8B^`67RS5G7E3hJ_AwDoOj4~sWmXVf7fCE8_r8$+SC4rBnJ{Qt6z3K zH#LtAwxjw=6B>9Pj4EMFLfaL!r0u&jqPYq?_Ya=X$*<;=$?IDWsI{i==)LGkSRqcK z?8jXyF1V-Uqxf=Jk9@iFXi!9@!XR4SvC6dpSo|Rw#vVD)iJ}p=ePY_Pd3m@(t_@}= z-v!nZ91H1~(Ht0SP3h&4HRVtU=5aowE ziK7E;XCr1?A63;e=j_6}pm5yplZb!mk>{TpmUM(lphbh&QaryoT3Ore-z)oNe&`O( zuO_8OP0|flkMgd!$8!k>SFB}2cxd$tWiBiqO^***Y;j1hTTkv&XRJ)Wp@k9G5S9rj zcQ?7+$#Zg;Id(bR0oT!H<76WD-5d4tkc@?6%>HGyGNff(0P#g{m%Zz%=nB@V_(EVH znIy&3W!x$MK{9tAgqv|O5+`v}bCfHWGRICsO-<1U`ie5u{au_g{K&S3Lhyza`JQsL zf~?xOPI}MIm>FQh*=1K#rCy=|Uz6^)`OjEcUL@U6HPHw)xJ0GAvV1<)Z)~|yan`+h zgi&jA`*lD>Pk`aGzp8Z}IN$;@t4IUYc1DRjVop{h#Otui*Ub(gOPUEN0n@0q`Z{9w zb(Bi-0l*D=&0l_wuE&f8HMdK+*&_KkW;$xu=BRc|z8If~u!lB^=f>TBUK-{z?@fLD zJbPxHk)dSDFvzAMTSyQ(RL?0<*w$4j#Hv^vb?lZJmUdW`o^dF7n&F-hu4MKdSSSkP z7KtnX*DnAFttM8JxFMtLNT-tLa8a`45ew`qj%Yf0^}CVUWS)P%5QFO&N!(ynd9Obo z0kPiL`3~JbBJz*j0#WJ{IuVvd_u)P7Uj*MW-qr`0qGHBqybO85?5i1O=fm@cOEuWUofZm5-NL`Tt^Z|=pkvTBKGJEfCJh$p z1>fOuVry@irI$VytYse!2?@~VWsmlmBy7cV`F7iDu~cgE<$@SkM&gg*!!m4T(C$~# z@f99rUjtyeG}*6NstSBzS$vTBM&M$t4b1pm!F%VBWq9<6$wb|V<|tzHtTG=!3DBQg zZWL^C6wotACwzq!0hEo1T>GICc*`s!oC@%g^L@{tx^`Jtyb>8f62`v5 z@D|fx9Y;Mvrh zefabs+%lK%7G|=fyM|M%-&4*9LaCMO;{)=eOdk;=Sc?JE262GY|PONN0h~x(R~datp{FkxgBabDmXC znVWi3!?{XkuRqpnd;98_W+r(M@1u}pNS^e;2# zKiGFkKTt$FOJ!f6mRasWga88WE4dw)gIq@EBTrtREFVuSATV69ttly=a9GlofH3@y zL@u)-tX%Hc4Hq#$A~z!hsVcn24UqaJnaR~#!xN){lIWexz;G7HuPGMew*^N>p*kb> zxiaGyY^RHI+|)db#VgnK4Z$iA3I6rO3FO`@_P%`-%lL=7uXWfn-X1+b)Us}KdXMz= zzuR1&cb=xwev409 ze}Wrkvj`k`S2eJ53%|U6o&diN18jH|r6P+z4LmGUb#m(aWiasyoKN42pM6I|vPv`@ zSF!30ZqE{v1h+F7!1I*t_6{8xHsX#1iJC30>nV7{7B#hDW&_GCJ`XZU^`ysZp*O?a zHsl;~>!86kVCZ^IoxfnnEh%BykZ$6bQAn?R_#JO+6umenxonDSI%1cTX^cx(|DIRr zwrJb?#n7mUb9vypn>f1$Uof0sDE!7)wbdqWQ_jH-eyLhD%0k-jW{T|%75Al=rq=$> za3No(fTJ{7{7G}}^(x;Sj+K%bDgg_MHy(SyN#;%0v^u~gaT`c``0l4iM-3}QhdAGB zEjnbxbCEfq{j*Mnmgyq0*RCG5@w=Gtu(h#!P9M@UJnXtG9aK$WN0t>Au=ohF95(gr;^yL&*7^ z4P@%woTlzxSdVnTa9AFdNCh6~6a;v5qQ140Eh6qmtJwMF)r;Y)v{wdJ%_=u1fIS)4 zvlje`cB`);;(L`)cT#ggg;1-7iQgh)SFM7tkJ*+8p&zXjdE&*%3~~#^>_hAev{!wH z0G59(WbEmuZLoo+7QR8t0|u&!yqj3Po5lf1eXGK`h{0)pHG(vTtuzI9RK8iz>u51t zI)ApVaK|&5#WAtPT)nI_VV&GrwHxT1*mA3bxiBaY(K&ki0elr4yMCxuW`nQrvuPLp zP;)s+I?a#xweG@C&3vLp{)kJ*+=UBna<_B?*Gg*&A>Ptyi%z`85e_-#MaXX(+Dbkt z>Pbh%A^uz8`obiDC^(cH22wVkit$MOw#}(spdK5*u^pjYBA9BtRlD#p!@;63rjMdZ zJytQw4c_I0Qrw`d^zU8q8oHqsk(~YZtVW?3K5uX4jT!QgWa}S0U>Y4UAynVB&9(HU zbWjBJD5et7l?xLpn(R_KG{ME+Aa-5NrfW;ppT7u?-b?UEuO;CzuE;BPapu;%3#vt_ zotr^ECFQBbv`$fyi%o=NJemoZ=PwFtsIDOIn!;dB3MOBZV97ETcmzswS32D-4EuAG zgQUfHBQ#O0{VLfB=^dG=4$mu{AmKaUB)-*3CyUcX`dZ_8N1-sTl;+2t`(SBAPMigJ|@ zFFm>Th;t#=zu50&QK}U-TfEC+uHsz25?+SEONlgv+W^%kgOlu5D}6xZJ6~MekXwh? zfj$3}O4rqMu#)AplFCId{}-MONu|X3LTLO`MuVUx+Wh{razj-S@h5vs9^s!R&_meU z+@iKw|9vFuT02*`HinjrFwE>%(lZ^bfR*c)C`~#PDbNL)1 z>xXL%Kh+NFhLk*71@~()s<|$0VJ6i@1u54K@;6EhNz%^UNyRw2TwBF3B`cqR{66{h z%nOo-R(7g|>W?vc@Q);0qe7>E9T@eJ5frpip^LwFc4((l;4{MwU%YK#2%pAqJ?wb> z^Wsd|0bh|GY+i)c)A7X8a)>s~Ma4?XdL}me^&U62Lg$T#^zFidyz8^ZI(X{k++5HZ zA&yU&2O!5M51T^xeEk~qQ#Za?0L-Tz`=bR-mA|q1%rCn5>`bjtcKRd~pfG>+C6Q^NyE0G=11+hH^*;vhi8H;^HXmtw4=-oOa5_O;7B2~=?-gDXHkL}S z-cGe3{XJ%`FqOo%WG9#r$(wx+uwYLwPPx5S%fSenMJ{2^ZLvW#X-1dix*8*F zP`?Ur!471$nrHdwv=*rDdoZN5BNhwYcxPGgUE6WRXg-2qigpG(DQPGr2RXyRNH@*c z)YFoD-&S=RA?48l_niPZg;^Y7$5?zRN`j@%r!t+iD$Ew$_s&n9_oImvylQE{BR=?3 zt!Idtf7UDcvUZ7SdbdYY2qiC^9`7g`x4B9Gbd`D>gR z_Mea5hH0oKqK336yY&MfR!5^eeC76y6ySlgj%iU+Ih-nVFw7oE*D~k!E5DpQ^xjbo zH2y_EL+y>eq#hzE20~9-A763RFqS)XWR;6^F?yS)A8*H>JHvf;&ZcNE6vjU68Cu>D zWKz{$+;_RM|hQ~WI-U+XnO zh9eR;;N|ZDMXrGr;FqaKdWJdae{f6b9A#cQn+qV4l%#k2`f$_n7~)(9a%F#Ac;&_1 z%P4MNzMN-L@Evi>bdr_@_Q3FDzs8Z|ySj><0R_?NB`D0MKWZE*hp-5pwGuW{w(26N z66z>kX0XT|ezfC&d{UjnoU;vMW85;%Q9UEv?sv zyParPwgz>OwkUJZ6 z13y3>oas+Vo>^jzaXCiGY zABMC018FC)`Y;E$!HeZ9d~%@eL&>FRhOUZDB|D9I{XvNkSe@q?$15SItDfk9h0-hlN3dRrz;I40Pg zY1jxvenD0s)RTgHwYpSc>1h=9LUT!DXWEcR^gV?@i8|_W>X-x zgpzPEe0W9$;c>!ntaTQcdZoBcVsB(tr^2Ac7?AH;qiENLx5b?xncMv%M*d4-UtPZ1 z;rQi-V0Jn<|GIJ~M}0Lbj zetCEvJQVGuNT~HHk>_oEZ4Ccz)KpBM^5u8Od*STmjp|3KuN<^(0mhAv@v~20krN0P z6#GCtTX5|LOS^({hc(OIswJ*yu(zn$kPz z!v{BmLhUbH((&TWek_P1>>J3LwB*KPe+ z?WP?uJmQx>%8NebvZ-|6;1+0kj2c+tBE+>c}VX_d)d`^ze1LPSgIIz;6XYT%6K)3jg%k-PY(;`d!k8rLvFB ze@Mquu9~{|hcD30kgIq1j|Zx~KlsPh|KT@G)9`W4|3g4pn9y=Z<}XO_q)=J<@jsvZ ze{v@NBPRR0{=i^El-@rXr(UKAamz)nUjGF>pPZ?A`~TAwS|OmOGfPzZ)e=wSaq5iS z6Dxtz{}%ek9q_;TQcoIO&ae0Cfev_cBubb&TZyJ$v;Xx)n_47-8@(WShqV!gap+a6?Clk z0MQR~I$vMl-^$hB5f^cn=F?V5j2?LxP!9X=HJ_-sUPtLY=?Zam(all?myZM&p!qO^U+GZv*?wy`izl=B`Rip=x_imoxD+ zS0JB9M~hFFYXep}t?r}&pO;0y;#BW!dj_~?|I;S{8FK#HT@$CKj;91J-wix57ZF7y z)uTGif%NcE<&hcBMt`BkXkAo`+Z-Kp-Q+O+(*$9rt$H zd&5@l>A2+Pyu_>=J#r)bOd98lE%1+VjuPrJB7Ln_ z2Fjw%(qvUp8`pF2q0R=;p97aFxHN{Fd>k}+l)gV>z;*7jkVlnU#{~gqjpY~myi`n$ zn({qWo`a(kA*Oz`v2)*XwM4Pw>M9%6SP*y0-e9Pk892^3L+@C~P5j{Sz|HZ;Gm=oX z4rX7cFWydFgiBOZkvUPA{r6i)-WE`%Ip6&gx?Xn{g(t)Yko(M#yA$Pgg6+U=$(Fs& zHU}XmafjTsfwj}w^zhqo+d)Irqu$2kKXGl1X5H8u1=3Yk=xb#f8&W3#{ADhKQhpx0 z?{uQ>-^>k0RSpYG-{0y`iA-Nc)p2XK_AzIUv^fDAOk-2k$8m8}zOG?e>x@c!D|!3V z3H&Rb?E%{`HgzKzLkqMtZ>ZiQ>hU4?NU*XSU%<#XkA{`>*8Dipz4wlivmwGzI7$zg z{7+4uvNZ3gRi$|jf~}ffExWI6I~sw7`?aboi3S8othu&t738jn_X-NY{sx0NIrHPD zOo(sO{XSN`@}KY}3>Mlr^lR5g%tQ`l1!q_mB6B_C6IzpUK;>ZG<#;BexD;6L<%E8IbN@0S4u5$#xvVr=+J*a*?%%GrA~Y^n|9#_2G089cV~I* zF6HE$!s+n7xyy*l;kA#@XlD8dz~%z)-F5(1t#IxwEf>h$2$ja9Ut}BTOCOsmKaiCq_s*)E8EQi4F#$H8IqhxPhpar zcQ^AV+ce!19`Yw(PL?)oDj)u?iT1Px9yvB1chVaJWNgmK`mF4J2RC?u>}FAvN>Bfn ze5vI7A5Zq}4OAD7T0+$IMPqpQCUNcU>z$<%4(~e?@UiCBfc+<_sWgFU_ZQ*;D*1jn z)fKzl4D($Dk8-p^k}}_OmbwCjeMt+q$+DHS{}lW(b?!)0=ilKj5!V3qs@|`*gB8`d z=1)rM68^yDV#ctK3nVdzc@KNjae%0Q3Z_IWZq2vC+B+gO;Z)^PK;D^>H*NJ(jrNd1 zfT&|5xI{Y6A3!#1eHJwzBYc^V zDSucI$}+K*h&%Mu~VOt;b(fb4g-Np3l8~rpQ;qtFl+xuU7sQWC&sM%Mp`B$BmaXA z4;~oVhQ-Xag{*2mN{!XlkVl*WmDN<3zhK2>c$sLcRgJCVzB?QN$&uAC>4kSuH?)Qf z2O$q*V!|%�(q{;AaE$ni*7JM(UW6Y^;E8-wE{~$B5y|jIeWf{MDoEDYiOYm&Gm_ zyyhUQFb4CwPr88crlitV_0_e329QY3>xRpDvEZowkCG7no*w+FJ*l`#2P_}ZYMBaU zv-dhgUf1|-X1?s2(-<&tU7G9T9LgIlSs^|Wu5>omfp=2y4=ETFl!jIa+NXh^_k9b# zk^8@xRdSie?8fh^#s?Ug8%$zgK%wu*@-`2<^;gcg`NQ&x`S{&3uP8ssC(&z$1#J{~ zV9Gd>SL{>q>vetxT#uy|`57WA19m)F$BuSbkHh(|rO7J0jiIv-k*SyrPKA*$OZ@CF z!2HB+d#sH3QO4xvNVW+x?R!$(f!TreK))Mj*0&WxcKgR1(NkA{H!EI%5F3}BN!tk; z@ay=bl^B~2*+fzP$~bjODV=-q_V1*wyZ4u*KkVWc|Ic~G|3JC>=eGaB@H+t|{!^}h zn;iTHvF}9Y1z5!I{_xa-f?CeTwl{;?zqO3q)S% zy)&JK+V#Hf&^EwM)70lvr?}LVJB;c!3&vq|8OV0ekTA)0>2}<0 z?ASDxMQ!I>d9TZ&hr~{~|B)e6S(mEuk6!RA@#J_rNA=TM{UmM~H}V2tzN!3QY(j9!$in2dYjQBh zlYlM9Ndvi*P^8xj7|f?Gt+{>X!%G6#F1zh(KtYlWW(i*-NW}IAC(GmIr)buvUS% zF}s85X`C9&vyd)qD6zE8;S;)}W_F7KROrVr>@=v`x)1x7w|XO(DHahS-H3qaeT2N@5kmj{e8V)H__qbu}WRC!1s@WD%pDt8VFLXP*!q>)G3mfCz$oUi8 z3!@)zRhWEP7<41$>v9J;Wmrr^FNM)re+)-+QIb~?u@PV}E5BNFaW( z93w(U=CLVpR9`z<$gn6e<&Hf8&E7B5CCg{$WhA4(oL}ukc*x=IoKMb>&0=87TX}FR zu;}M|sg#6R5^`*(rQvooF6O3^ShoC%i#jhUfDQ4P38G*y*BXhUC9bwkYxJHFp*y^l zdB8oxHYMEyW`|fv+-Afxz=DNp@442tdF#{Km1du>a_7G3{bvk zuL5ZqB;@m4_g^3&^3jn9{7R#to+yt)Clh-0V3fbh7+7`^)K)Y<)CdbUo&MaKQ(mBc z-$VCM!g(;4BhRk0!N1eJwxN2=uTq->w%fQSXhkB{NqZ2qT}HXQ1*fZ#BQJeHXeV(H z(gb`<68^4wx8fSj#z2OG_DEs|336Cs^m+DVR0HIev2lzHp4~7gCtjtzs}J*AWkE?B zff?0CC(VSx%QUdSf@J7D6fxh3P02cDG<1 z)|OD6lf=4->O6ui*S%#m2p-)!>sUp?)U9Z%$PM z*j(BYW+tjK3r$DJF>fRa=WowC1u}3!7E0=m=2yJxKWUm|_9>VkJS>cnI0H7Z{l!gs z#ipNx`*-f8 zL{+*wQ`u$mv7F-C_b9YGE?xxL&P!9G^i`-y5_Su%IYIpMY3kn_wO6zKELBCEkU2iX zLB|q4|0_bH(9|1G@c;;+VBv!ri$X)Gx{;<8*T1IP)sIppQ0xhAX)vWQrH788_7fxi zAkI&^)}*U!-~GX-W8lLTn^(l0u)3QQM-2-~GF-+ClZ3|DE$ZnanU+-n7W$BdbA3F4zusWe}e^KQ$N9ilFYC3+IG{Qx>on? zMOA0>JmaHpbyV=L1BfX&2$$DwnwEC{$UoBg+sb;(#}q@8aRH2rQB z$RNDRyzG8lg~#@tM7s3YM0@P8$!W&WX8~kGR@X|NB8T-OH3(N9Cw!d*Vp>&z( z$9J#|jW6bj)!1Ean272lS+#eKYsB(djm@|3;EP)~$NVaQ_SvBsbt>kJ21x~Z^u9~+ z^jEUBzOD}yy0A`8&Rb9~-BXhhx^suhl~m7;mO0`l6l|aMM8?Nt;szJYJR~-TP0&rX zo!0{LE(Gjm`iKj0hnshLOY8AObG7f`AWw&h_A!K%uhJ8O(2uiucgNa5=VbyXnVk)# z7(@?^1vvr=r6o2$jCXbqtXWw8vWodm2$9}T3&tSMk;^$3jf=9(yvcc20~JyQN^n9TIEJ#;vP{2z52M0%aCCRPbJ8LUD+X; z0-Q%e@a!XTn`ws~^}D=+hgELHRX*-(L=*qyW8-nr-eJ=+H3k3si&o;bIA+|Y2qXv{ zow%$_D&BG0s|Z13R8L278WDG>SfpSnv1=iIof4R{9DW}@)ib!EWD5_qi}cr)kLJu|CPa6Ol_JWd|r+mj=_CtCBT&E z7VpdN#$C<1sc7s=%kmuKrZ`UZ8uyNH(K0)=A|8}HrXyNmKRlCjk(j*IZ^#MgO>2PJW-jS z;CCCdMXhI9GdnOEEtDX&evvF@8cXZ`me`XJV|&h0&wy#1c0^RS>fAfWeRqrArngEV#yI98mo zHx*|75HuY0NFt|3G5#)c+c!?|0Que-ZGKPU|9uYPbQhx`RT=Pr)r`fEqEWM{u$Y%f6Bh)S%4;$v z9*)2gUOqifye=}h?=YSqAlbm(5reca-shiYF+49ycpdd6z44hthb97HvP2)cFKCh* z_AdaN1DTfl3ajq+g0?6xSEw%7ai@0nQ18oD*c5-YdC0%C z4IL`x@lJtCMfWv`SZ;4aRB;P+$FrA+BaMh0It?*g;nMEg`zJN(EB`Ors$X_en5mRn zOZxlFAexj;`7xdK=F1FU4?G0}@WhdeMMYs&MXq-?FzG>o=s98Gk?K_D|As;O=@)}E zFhI7(sOd*rw8lKOLhzKnf%wWu=d??B=lS`g3`v4Q;O>F9zg}`y^^Mq;Es$lTYgrxh z&s8ihvO5k<9~y(i8?!3}dbv=^m55Qm zXk(C7SE*x6!kT+K@06xz6?IKTN;xWd%%eb{kW;y<$rLrX(e#pkTyfFC*IHDb%IL3? zJvlw(I(A6_UNifxX;+lacsA~&c*`UA#%*^w28EM-#A(sF+&rmHZ5bK6+j}dcMiqlX z*wxi^4UdV#ZOGSx{9lVRu2yL>)@rZd{P`99-MT5<$Q&*hS9zO&!nDyQsjkd#1l|vHI z$N;9UMNt)XWbb?ZmpY|xi@pr*vY0DyA;*{-Jnnnnu`g+0lg}1x7ZH4gvzU;JL9Qh5O=?#`M2vw(IJV6MIn~tKwnRGQ!Chp z3(2>)LpJ){#naEOo&W39vv7R@)Y&)r^d(`h9$XEbX?#-*F1`%nwMXG!y$Kr%d&7J2 z_DxmY3o&XrH(%eQ^emh>NPznjcYi3H@oIm+2@4|T zME%j&nqNlm$*V>dak<6u5s`8~m3q>3Q`0t!)@Oo8fe9<=6XmCr8AB!4Zm%O@sZ=+l z4Oq8_sW}}vH}~tqTdQ%|$3G62-JqUMZ1+NpL*+iFyL^n-imXm=}~b&Ckwi%j4beJ~d_hr70Vpn&;x-$JU4jFvM1E zQ&~HaUM2M@eY5&u5RoqSzV}!(QnHVBt`rhyBE-wm(e|`Ydp^u&|+LRPW3GD&?whDYPav%m>)1^KifA`F6f-r6to>4V+%LzULGpH?s4qXeQf__^V#wB zWgb<2v1R)H1YQNIw}!)fGN2NL9?}^~tu1PrW^5(KCUtxc_UDocrxvCi{~u*l|+hhzOi4vSnx zzuK!RHGKVs*-`xWRyx7V%yW>cz9+8lP*|&{PtGpg+p0bX-PdO~-N^H#V6~o#eokmQ zrA||7VjpZ&JCHc&W(!T08XFgs z`hvkRU$5dNMl3148>Aqwr9P2L8FlWpSnW`+(oSQ;c0D;$cXuv3SYSdV^d9YFz4cqX z-8Wr&EtTb}V{Z(`y|4GVVi>nAs#Cs@EpC})HnDd|QA7AkrKVge_1Ib-%27{DD4jjf zD!Z2Oal7a*!TqbsatuK#AeW(!3aiO21bt@$RuvP+(pTc6PZC~eY;A&NwnTSUBk7>8A*AcLuyxb^n0}3uui#v`jqGH=GRSxP)P5X~s_Dx`^>=S2^dCYK?ruX?vX39vl|4vH4A^0#%RvOuiIs zBT?jv%G*u8Zbkd<`#kCT{r?0<%86((edxQRb3<67v=W_i=yZu!FxsfW4kHzHm;b@l zacoLUu?f}Zvv;;uIO^#(E5&+dr}To|ROzs7_O`pa2PLkFu)4)$aUkX*P`*LL0{`CZl1;!O;rbGVwC z^_@kBn(~x-qUg1#>osk(v%_kQTjB$Rg`i4HDDE8?HzO$uxwm^<6&K1Oi53Yz=GbK& zJ4ceWHWQp(K3Y?B-wsN~*-X0KhpuoRvkv;`kL(ui&!G+}GM@8&X&lr|zi|b;ugAzV z30k-?H(+=f7m#OHrTGe-=qvM2D4>-VbScP z@cjXC*na8aCu&TS@KQ%71nny9=oeTVVTejxOj5%PBnf;se$7268DY9jqceq#y3$8E zEGDU7^rh{JJq+P5Hy16suCc$hueH9k!n*jQkh4!XpD6!*Y-Yl1xYy@dW3i;CdzHE6 zb8EL}7P9{Tbch3Y0kTt7JDe2Co%T&c4>3tx<6muHrZBAEJzQiTeRj3z;sa)x1 z8rj8$8{g@%+F$AnuvuIRwRkTpjOa)4z~s>OkuIsic_>S-=+k>X<`>r!8al|&7H2(S z@Qj``}E9mfz);R&#zU^nUs{c@De1!zLTHs4stND@&7{3EdjK)N&GPE=>VfMIK?`X)9bfq1j0) z?DDe7Ue*q1de4SCesJnn^sJ$02bsy%1#c8u1CydLIzqR45>$ow!r<00lRN57+m$6wJ~=N0B5e*KTMi^yS{ z(Z-jYm>)iQeE+jqaL)RZJ|x>6$qK5^s_IYoXB4eG1Ej{Avd+Y!Cp$;Kt=f*)F=yVI ziceLu_H4FqGBsd9SHgtZ*(R8=<>OCeS1EeI-|Z@tu)P-19$!SQ=%^MpxY~;BWQWaN zih2MSHy4#!*`ePBSsoi;X-+p9+x==9Gpaj zyutqHLxv2uA&*pzx8Q1mvo(JE%!}~p-o?#ZcNAi*L?yvK$L|FlyYId?9nlt)xlYpC$S?t9k2Z9!PQXO1=q=s^>1;V)8j4{hVj5*C|ES$lxPN> zLt^a5Ww8Sy-E~IwCy%eBbC2e%jWw^J`<_lEQgjH2xp*|)&&aUq{3?y{NX2am%tGN& z{qr~anDTb9GcA$PG>ao6wXvg>h=2)m!6m zN&>0h)AyExuHW?t4a&+aUtcw{2>(BGUt(vv?N9!z*PfRjT>E@p$6LZ{GxK|+AJ;Nv ze(=9C$-Yu=So%5p3)i{iacCyJo(G?#-57g|4WzG z!LLL7cX(>7OzOj|{_SgpYPdlahcU-%USCQ*QiuX>;pd?`P>{ zMuoGu=E0lE(^o&K-1hZ@|8ARe)~n^0SN;Poa!L;l$T@7iM^*RG-i?7rHulFSUVG*= z{kHk6A8XIP{C!PCE-(J2>x6Kl^P3azc%plK)w4(PiI~pRT66 zZ=QIR5nwxShiIYW;x+OwS*+3!`hE&m*s{_20#rqtV#qBcv*MCDSypSwI~ z?+3%j^3}6*(@Xl7!<(n6r`~7gB*n&w@u2}i!?|I8A z@?ybunEDf;JEw}CSE8uvF!9Z^dWv#4 zr;_i?tqYk^FS}gHDQXK(c%bCJ#4{MtWCZ7jStc}6^4r{I@sgmRcKljT$ z=jOvEn@sY{PLi2t=6SMVKjkHn5%Ce?j3^g+w#sw__t4j)a8$Fvk#7< z(kdU{Ca;gip>N;uoW83&DchPlxf(c_yfd@0wKidNG;%O8v2irFb-I8B3cVSzTd1fz zi8+`UI9b@*kg8Z%o4l=j_l}K)jeW1Jk(F&fGnAEUKc$G2m3=?WpN)GjG?t9GeNJ&Z2kbM#T z{Ncw%7n~?FypdJ7wbhz^O+BM*@_a|**~ath(yx@WF8bjh+l_;1BX>@IPt*Oeha&a8 zX8)(NecNZVRUE!xc#D?IUl{H`oAlU+At}vz=ltibe&6geXBf_^=4PO@UU~n;W|K#B zz{5jraS9(*NQR9+cQs9&W8?(f_ZBR$=>pbC&-OCLU5Ctjd2m z1Hy|TT))odzwhb(+qE@HH23UVkGl6D-u9Vf8TSzX@Yk?MDn{ZW!#BCI0Mjjc?7#(k zu;ayFPdGjjjUXBgSt-h;vB)BxdgNRAd`vUP|G3BLBQ0G*54F6p6-huQkx3v}jv!ea zbhU%WPnSMZ1veJ~8}2WkuMAcu{qi9SGj1Svn40w{&>WHb?83=&WB&I4-c*D1$9aU= zlEj~kUi6QdBX6Ou;~oqZmeJKx#UFKiC@KiDM>`56TjPX5p=Tk-Oo_^uP%NXlZ`utB ztXAkV;m$m|j6&fvQn)+tTYSQ3y(lyBO*|WPf^Jt2KeS!%Mbxyqsuv3&X0!`BgI5XN z>2kw|v~y*?isEDC3Zch;CW450Q|pC#?KOVaUA#uOzEWAsb$NdYDj3+Zc||A)AJW_C z)u1Armc*u4*466oH9NQ&kuJHK)2t(6W4=Ni5X1M9$=ar?m7Md8`PpEW#OgM}F9uQFS?eQaI_iA1>#Ec2!zD zqT{z8$4i9m4iW>**k(U(Y_&t6`azN=Q#pFO(W6hX>D!cR)xL}0<)q(xE>v$mx9IJ> zPP!9<_C5-c=U>U41lxvUP^k7_w#GTi{5&|wJr@|5w3Gb4!%s_O9g8729ZY5+1&2jL ze{b-ZhdJz7%PoT&@Vwd02D@He(AkE&I&-%|X8@KT#^280E|3+6Op_>r0mjOFu zt@3LCcMbVs4zuwGLU1J+mRerrN{ERfYkWt*ZH9G?u?R^~-iTv<7ayCm9( ze^=>qbUDt+p`uz;yLk;X-EcXa>non%3$DX%a3r#ts0Znc^q^8bf^3Laj|9D5{j`rS zuqLp!^LB~yo5QBe*nrVdI3)41C|g3rg$|w+XM9jm!_kV0h=)>#8OZ6#!4B}`V;@u( zkv4iNm`rGLWad|cjOC+Z*LIyQ+VOlNcUZd>xSJrs&Cd0$Nv?k(FMOb!k(A%dN26x* zxxCf(*||@I;-|0fJ*Yc^Otjr|pn!#05|inU5+mMr(V#%j1C%@W;_1=)NCyw;5F&seV=o)K_w=xKmgd-qp-zfM*cFVe1}OnT zugi{FZBHYxXRY2bpnyg2+@AUifX#>}HKFqt33ZX`(cOeu44C>~prj z{PXy`(h_XFGEa&AD>yK1=z}-$v2hyByf=PIPd&)Fm-T$} z9PxNWQJC%?$|Tw2YYe_DpjRr%HT{W$!4qbch_0%++=I9tc%~6P%7)oegz~(R#Itgf z@{Aa|rn3pvk;(nL+z^qO?vRl`t*U&VFP@W*N_?jVk!5`?bYl4AFK&?6xEtPZ`*{PyaLE(WcD^i!ZJ6f9mqdXh*cHmCOx1nazUDGe2# zsTG8I6EMpHu~65Bf%`s#-T1IS!|=T5a32fiApwvlm2_S3_H1Nc&Y~%*b-78H};pG5l)cpBZ9aCeD)1&w6vJyijKchb?$w{ zchm$@LD)%NlO+(%o#f)(soz1P?~d|4xh>;&m*pvVp0|7|q3XJ3mbmj^oA&s`3eq+D zrXYYEt&oG@uFUFCAnzEKm1M!%uEoN$g26AmU14=h+{f9Av2`tuU>Yrrz6+ z?bx&)hyX8BuCCtS%h!Lq1bFVXn)l~(R|}-i*;C`F`Ifu47TKo-3G}vOdO;=awV4B| zk0Z;M;PpG;aJ}x6-f4x7aY+0a`lg$Wu|l+GP|$kp$1eSA&B|xf zbq0_baayx#K=!H9L^~V1a%@M+1)KK(!1VG>hE2s|5qWU=nJ54g)&3JCNcOkSR zsq7kbIDQ@>tB-4@hjtgbJY#eb-wMmto&OeuL4PW=^7@26mu#5Tf!$P__XBxB6z?^= z`w;EZL$Ib|vKuKQ-bLXDF!&?bjX)w5F?{PHNA6h>xE7+cVYQr{?SKEavC$4p69E)9 zAu6kccNcq~4EH#cbY>-6!39=4dXVTZC<-wUr^&UD!g3y3mHi1^j#4@ldvv2nP87nW zZ#LA>J#+mggWb4Hy_vmv$uIRhXy~OAU`%6v5Ys1kzIpH1C@ztc>SqIo1p64$w6sBg z1CVflKi7KB4U)#~WuFqFm8epg`dXAv@0&*fXhwWqd{1pWsoM%o4XT#Gr7kS+Rt;7% zYxZe4OPWULeIYWdEi5{C13 zNDHyns~e}Na5Zl@xBB5QS~MD=XiyCD}j7Co~6akI*VV zjC$VNyX1KIbl<~6p60&t31_ba(|2o(tj;9U+D2XKsuY`UeTo?{bI#Rzu}Cm+#cQ4+ z65qG(-~SYu@(;GOo{XX+2e_k}{W9B&SGnYUR?b?8c#@({&!^~+txK|^qO(O%t+AJK z2lpv2r!0wno9k4N9;QViOY_BYefmI$u?_ob^gYGN*cEOeoRIw9`i~-rrJF7L{J@@+ zqWH`#IHpkl;bSNI=JJp2$%wjD(Inv^$osizYIY_OiOJVkNyro02?0v}Vsb*uKEm}v z>Uk`eR9qU8unBsB0%33M*1EKOWG@~`fY|j{%WI`|%x{{9@Rh2If$huyqmM*TFQ*oJW(aSBF zgQ;=eN7EEROEmng^fYUo=_DZcq(wcw@Ae1*kR(4Ghx-5=mQn@yFnhEmOy>D#$EAmH z>dvc6t;!+Ga6^_=UB|tuAMVyzs5uAbtQUfxp%Y{5P+1Fp#4noAQE^n>fKi*a*kO$4 zcziPiHRQeL`}mtti3RT$z8bH1vC=vMeQNLhByGy~#k_xzk_KUgzHZ!ppa5pN(=u0gBy3&7XXAPc z)!5iF=8n{cU|-H4(_#YM;LO%Kkz&H0VsOcp5NK~zAkF$;ExeWNg7M~dt<7!+Yi?e| z^lA$*lq51LfEBk;n#dGalAMia6dbv>x4SWGvb7_*uJ-BD_A`D#@XLA;uCacdhM2rR zw*5%Z*oe~9&BnoS8v);>2>m~0jd{SzdHJ{%;+mMjA#T}~`FaMZF;Bnmdwx`eI01UZ zZCq2S^-Mem1p~^(W0{{hKgo3p!ArD4!>uR%&*taLsAgX)u?r%URTz3h>F<+>yHgw- zyK-1rbMHf9g*S`^9Vl0pXkw9e`}tv`72pb7$u%cgke1=`_2Z`4DSRCwbuHW!BCUVL z?J5-T<#B65rL0hGM9Z#G+vBprT}4l>*(8*ZG?kE6N5 zj47wA%)GK4-?+{0?K9+djmJwMqSw{-T+ zy2g-ea$TytdBKFr9_+-F_?pn3RN=o=2G}X%W-if73~XVD5nR<4cb?o29JMu>E2DT= z1QR?Mo5{i@%~IQ+W5I8flZT_K+Z7{k_6fg4)Xj!CK3A@4;O5^{Sw0W`X#mh$Vvm-_ zC!8BKge8?PH5d{UjnlE0JD6+Qq&5kgj%E}koN7@UYzU>!E3n^@C0-%RK|7+qfXC;& zShY61piX=DS?>NRdXsu%@yPhSl32U1F^SePTBf{GrtrW@vLBDL6p{FNqkAR5iE|XDgMgZUg{8x&6x*Hqm&SWn@TpL| zVy_A|WGQS?N`@{#l8WNU#7es^WvZ}+#qJoF+$8ERbGLre(Ct5smZ_qLE~%=8{rEWt z=H{#W_TO{gJ?j{jBHF8#&vix6j$xoD$il~W!LmrmyPYz-f<-hHcLk7IRA*~ArCtoz zR*Z|thX6@;Db+^D=dB3TLKK}gyw%Qq*X^`2J+TdSVmo!|LvOY;Z89M0aHgW2A59V;{09s49o!BYm zmgAdz~6W5!hs7!{QQKz|v{kcfL=9-X8ALy|y$}0wq$>ygj6yQav+5{uNhvTtCb z6?#J&i{9N1zS2B*`7EC*x-lPxnOZ)p)~rULO^NlM^vuFR*w>c}X!oqovc*a|opI1r z8v|-*U`vs27Slz(1JPPd{-}wnZ+PTiFJL5r*#6cwOrd}MIdix)`}6mWeIi!w(@PER z9dY74$+ARtXt*iD=i|FC%cN#Ipc7Fr^ho`8c&*C87R`oyA4E<(5i_4FGAUig#I$89 z(}HZswjA*8qImrD8h692P-Gn1-k9KZ%NftprBmeCoBn*Zat#tMc{IVeO|7k-#?Y z>nCv74?LEL2oE4n6=p>%~E@2k(PS0BUhpUcR+= zwyd%wTNM;j{(>`H`K$2XaJEoF01=R%y}7sB%6ipNJDW9HBcOzh-jb5NShx@M5x$Ok z{cnJ43|S?t^Yem0&v%R7R6aX+9Qg-ioEV|BGH>Rcq_^rJt;Bvjsmt8EbI8gwfd0a0 z99GTY7Q8%`CX{h<{z!W`6r#Tu*I;%NLoH9SuGCYGP`%kWRyT$(kd&s;o9faVV@)V* zS{L1!+;KrDotQl6pD}5mso$MBchU0loY2YTA}KE%(xKax*}YZt;&e|ncFdc0GdN)^ zQPbeI*&tfDOZ#%vJsW08WUX75&droQoCy9jcFY|-ELL+c{;R39Yhph-#I%`~gh6Lj z7=AAYG}tt2#(oglR#}SBdE&nF7sN)*vhP?txqp14r!V$L!*l_X+N@@Jg!#Pi_`#B7 z?3g;W4wWp@HuMSfD|LZ8;ili|5e2NE<^zI@pnYu8P96h=ebvC_v1XXAS}6o){0&=1 z^jJn^(AKu?hERxv-ib`QXAsl}vy>f3kBt!bmz4+%j5vg*UwZD3MIP3w_bh<+o&X$! zqb(Ua{G72y!(-7$fj2?uzgrU;w@U1mM<;Kd?N#Zp1t#btM73*1!kjLM0<0dEx=pnZ z*cARvxA^x!kqFeWxEN57(_iw?Ir!d{(o4RY^CzRa>OU4)^ic1e4?bKP z+Wv7$b22G+(E&=2LJk2cZwOkC`T}xO^R`*@y=nNsF zOeJ!7!Ty4J4&L@bWk-EzV;sCZ8d#E=|H9_!JH&?H)1XYka#5GrL zM142lg>XAeL9+qxnZmMG5aRgr=?h0Nj(d-4WzE_5g)2$AnzgXoq^eRXzmGdSo)xgD z@H5xQJjCizXOB%w7g{lz*feOwF}6~*Wic7tQ_;4j?ZQ=!d1Qcg^uZm1y6%QgtFQER z=N}`zwb?Xt7T~3fCL`{z`$A5Z+91>$z$1I?7EiXtU}|Ud?-Wdi&>?mjIfcQ+%8SS$ zvP3YEn6np*W=36Y^AC5e`i}1-s|!O(C!wqDp$~F7@zwG~`t@9CxVwC|ho3ebQk#0mQVHKuUvA*S>RY(bIhesf|vorma|6m2ly# zDvhxb+h)K!@4=2SZx;flzlV>u{Z_{j8LgWB6Vh zqh03|Hp;)br@fvJ&k2^aH}4PUY+e%)s(pg8gwh(99eFtCnX?G7LT0}j%$=L=Jk=*t zZ#LoI)qvz4$>dtZABHU3pmDT)=51at2WA=|={6t=XagnJ@&SLfNU?3(B-_iHIUTbn zlva!<^%k|;hp0-?j=5h}cl)kl!?30}-e;JwxX4MLeo{>#tHPw_0WsxjrXZq}3$tDV zId}Ya#dLLb?-k?6D|YZ$Tjo|Ae3G8v(Ahono^QvI;Q3Q@yAV-i_pyM7x-%l^3E{r8 zHBN@a*N@*8F2}n$DS4Fma{vG!h+%|`2}#AD^(-m zJ0qyW{`jhN(|!#o>4wqqKww;=MSLtWg11SFW+A`gd62>MEXLi_BsqGug^8TzSzlEc zHqem7pWNy70)Ol{X8F;u+e`APL>74A|F`l5pZ5m4Zjss`hb75=V&7Wn(0!l7qm*w? z570l7{`2_4L$nDsxWa#?Ja`6wZ&Y{pi2FWobUKs8*)9Y~5>Np=xrLTSrzlGPDnf-# z8%iBYj`^#^!w%^PYii=xgd_q-Pb(KdSgHepH|&)k;q(}Mf-@%13w;KOe8zu(JP1spB zsHBZc4fi=3_(N?y?+rZ-n6LAq2jP?f&a5NNe<*BhslKG~GN7HiOC9zzNGOX& z>HQN;?@a0(CPs51i0NtxEl;0j*t5oqp4n8kmgOV}Ww3V8Y%ACi?WSNgKgF91fx{F7 zDeQLp7c+mkXCjZlCrnkVMzOz~-)Hm}cjx$sHjdH{Tlvl{rflsS3KGbL!jB{8(2v&>5@+L|sHw;tpONsb1V+>KUAv&#)(8i*DTIQe?;yS+7TZ_#J^t>qWUU;7oakak?(S zelj3@ol-))wdI<<>vsU{;bd20LHb0?7T$|Mnqh6LcCWyHTd^FOl^Jd|SNoFni0Rs# zATw^dgiBqo+jBkXvtO%mGPe;aOogn$|0lmCdFIJ0OR+haQ;U;Qi{$CflG;&{9-JBE z)gmHRk8Ip`_{ET*qaE;L)My40s9!TSqxkGXX<_sRK+M?rY)Dq}5^jOL{{|pNm4GpH z|Cg14ng`Q}U`(Olgc1o(PoLx7Irav{Mp5jpj>z^eCl|l@CWYLV+e`_F#lEu92b9V~ zeXL3#OpDM0VO@kX39$mNRs01;t@UfON0;zbZH-*zI(Ix_?~c@*Zmr<~xknXu6GMe3 z3`Y#?fiatug{RdgVt_*||h>fJ)+)m_{8*+j_74*As35nu?KFcq&6Fx~EH?$ef5N zPlQZ255bXQ`F1Zdn#X_=)+FmLRO$LWDg=n0*SpbhKFVdZ7yWtnjC_Quv*7h+QLzm* zgo6Al5Z-TCjX`rMSWCB9*R(_K;c%A;76Ijgm*{V{jK`LibvB3J8vPV(J(lW5Hko># zHYZCz2^D5~99DBUD~K%(RqLpO>b7`=@z#C52yz_9MchsubFXgfBCT=XeQSCD9if(? zvL81)yr!i$2j*^jy47&e;JLE%7uXDewF*^a>LpD6lX`k^3JTXj#zv&dDa_w@pD0#- zL+A|6*gf^b`fu*T5TK2vUnVpwG*nEB8)b;7^Fr?Py`;FX(xdZeeEqcR2s|rTA{Jcl&%qjF!kVGDFYVDj8P_jLIs+$wzW{|Lg-5niDvVzR)}v zhWt!h4tW})0S|!T#!rEB%dClK7!FX}BrBgYn`-wH*7}mHevOozNsE#@a?5?^7tfbZ zopyJ>IxijN7Wv_lDC3n)rtTVS75Gb>8U-BgA6SAlq-7Mo6=ScrWGynk2pTZ2PZm*U z58T?0ZKq!os(OLRNQCZ%K(^Ha<|77{zzFxl9U$x1jqy7(o81^x+mC!_M|Gj9I$~Y# z6}db&Ax#qyU+ufoYXhYExJ||k%8Kjd{5lNKL8>)~JIgb&5SOqs`y2nbpdJ#> z66i>hF`6^k9u4hO8vAb6DVMGB2$rFvcZ&TR7S=G^{E8kOsG`J1#&s&SXa7%De7JR( z+Hpa)yohFOql}z}wb#j>e{1(_JGB_jQ6yVToxDULB zz`sdKY=d{Q(T~(>+hrJ-t9t9(0xTAe1-=~O8=fAr4gH!Q`sD}YKZ`>9qx7pcAUOJE zR^k+RDnaliBHJ7`hk%w1Z*uofS7y@Q5FGqa-kfcIS3DMIdD$Ed{h_?Bv-Q)c5RuPP zRFNlqHgDJTwhCDJc}ojOIC?I>=JMH8VEh;m607N*J!hQg-yhjY=2V0>OO)~*=J@04 z-KRPeRqZ1qS_K8MghJmPjH&Rjk@a=Ds4^@yFHPk)O6IM~x7PFRCDJ;QLAiIA6ea$| zXwMep?a>%@Dq!9YLlMfBCGzogr^5K4bJ5*+Bcqe&l-vfegCc*#8d*UMjK823=xLU3 z4{mRm{)~MCu2g<7-)5M|^oB3V_JJ{~X-}$488_%{aJ_8d2NvZfoyxSZx8Cn`q^9l~ zU04FPQCk?dXtc8yIYNw!b}WJk4vf@}lKgyX84yMCQGn6U#OX5OUcUX%7wXB*uK4w! zrcJwemphRARvF$0@12I_I~QkYW0_u$t-rUq4x8)lpEg8VH)Zno9=!a3mmvRua}v)b zMRaWwhZ9t;qDh@~VIYcVovp}h+FePMH%m=U)^C!P0_9t%l#xq!APX@11VZ-Vk@L<6 zOqF3nFtj;b!b-d4C`4b+^5CClT#nzd0ZoizBzcT!gB)=@=UPAx-b){++YX^D0y2*p zRsyn@5f6(_M~~Jb$u+N-J6&I4k+L5s*{L&oX_ujU^I1Y13ka7DGYY5B$gMr=@; zQ0UdYe`7UEEIg-g2bpXBhq$j7L;{&Fj8hhxk1~xN7&Dt*iBy0`cxbv#KM(jeI?FdO z?n`S4I&9g(Nn61J?b~2a}mJLn9i#?WPlx9#7-D^Zk7(JbWT)zd` zSm7j;qv`LKO3(}OmnPiLQ(A#{L7j0Qut!e3sK@^2V zgB4_*=oY)jbr$b)p(!cx8)gg?v)P8L8%)uxGl;ykdLgGAY#mw#vh-O>Y(vM@N|?u8(nNiw6@w<$J2wNxS1+%rMuGr%16BUV-qcWN0 z%CJ)lz6!ujxJ4Mu$cYTN#!l#{z@3~P3+&!AAh%dU=9$dpB(!QZNGHyqJ z5F|Mt!2@=o$8%I9A!j7^NvZ7!=-nQ;K{@VN?P^+UH9h%}=!``9W}QLDh@?HSdI4Hc zIeGjC123gaU!}%$euXI%rh44qUWh2uo|00gwjlVJ4z}>)Habyb*sjX9lvJ!pOc zy5KDdrcVN1lzh`h?SF2UJ4c4xyu|P`Iq|R0@d1ciQS*L~xTzBGAbV@q0H04xv001_W_U4d$4Arwck!rvbq=hPWrir-1r}EI#OT>jENdQstq>5)6zyOl<$k4 z_GVPkbDftKmdC5<3jMGgM8u54L%ZR9EW_c^cqXT$aYA>%Q_Xxn!&1QBiC`)3R}vxR z*{dk4DQ=SM1yyMHjk!m;tSi^yNqdf(m$&ng!jo#yXBT zYLQNx8c>)P-RDn_lJ;spM^^{mlMJmRu#(;_$ukxkD;Qmq!u58=&C{=}U=|by^TF=6 z@?;`R<3x=6e{icP=Uup42ABW-?ferR-QGo_+X{rjRaw;=YlH{bH|Kj@s2q4i9}bi? zvs*1t{0>#YHnMpHfViKK)6)nNAdPb%t_C*5tLzAW&uZ1vn>aJkN@F zVvTuOq=>C>J31A={!h6@O;n325@maE4Bg^6eMtXT%aOmj!qiv^5U>@;*}o&M;FIYy_{Xi_ty^n`b#aT0|q%=TB?0LDw zRtVHcdT$G4h)r9Mv%GFRB}>c1@u&2wne6*^W0Os33UhC?ur(tj3N~Y;dwG}hnfC!B zHA4F#=tM;aa4$acsG_Z2-~TDLzEC>s>@&zgXal|i_eBas@71`wc*_XR`6aiy4RFsh z-Uy_r4{I2`BCcd99OCrBJ6#?;*^VBYS=mANbC}?OHQHI2-jJ7NQwDdxkle%{0ta6? z_!2~`g_%j3ZioA~Mdwt@#EY_uAf>{-OB`#ikpteZENdynT`<%7vGRh2(WP7V<0{y?%{He+K1-Miakiz)v3~EgOXcoE9Zi|1 zfFFL+Y|vUmB>h^|HT4&URj=YckKXp}c5|yb~_Fiia+@pth?u12Dco^k-sV+@~y;s^T}e z>+uG6mArqdcBt7%m}5kXmh4pOn#h2dKZYC=hl~oiJU2Nwb`)zcF=I;d{of;D%SG4Rv4FG z4od5`UyB4KekQRdmXGPWtqe<%s-5>P=x<~k% z?RLb|{=I31NO=d({frl>*0A+p8EDwMCG(sAI4HTa=fGic zRBcLmei-mfwa;zLY=^X0sWrJ1sH@0WaEnRZC271Bi{xcuqQV_&OVS^-h}@rdaNSci zS>GL85T4zUXtL`4h0Bi~;*7ukHzVq(=KxYj$$zaCj5IeKl;ep~_9 z?iVb;EE;`AGn_VE*dmaVJPF30-lQ}NdI*?Y7k+A~#ekqGIMQ*SDpQcOGos;ps@Q5> z);ck4+r86-5bH#Zf&(rs#WVa~t3`m~a7>MtbY5|+*OB0wPzTPIpGW1eSgOl!7laE+ zmxkkIH4QZiG{GGd$jya@u_X5#OAn%{Q>^=lnLdonNt~kqtO%EcD9-WQfddodv zv(oEDh6m;wmlJh(y#eq0OsQ5M-$!P~!uvPa&_v4--C)2+q?_@{JnY_^|r2mw<~1*RrS{o5xabPgX%BeDdjYNThWGfcYp72;`^r_h9P2RS{}KOF)BhL z;)LNbgWm~hm&)_!SCnrN@!y*A?-k5nGP3dEg?~|;NFQz~9$ul3l@XJ@N^2t)WaEO5&IzLzF9LN0-CTnbRFQsZZU``kL!6JL{9U!eI4215YdC#ILu?YJ z0-B}`EoYlpLW)CrJ~{zwEY8LEw5dseWVw~d z#Vm*3?i@=ly2UuQRgSt{4q8awI~RVB9M!EH=`CC(=?p0mt<C!ygWS(}kYJYaQbTSpDZjrjC`36vE-*SAJ5By36@R#i;9#N2I;*W|HLR3S$~_V* zc8X}YH689`#9$gXF~ezK4n4Ue?6|bY&4lIDVy?J^=!x=+AN->O9dsMsyq=t@&fZ z6MD9h)u>L;>Uy=I4C2~2CpT2bf~TMa!ZmURM`?-Y&;T| zbi1-@G(dYL-(sKN>#sutdGz@FS{S0vFh0uNLj&#Wy8~@)EfM!9Q58{2RXhQH;e7~j zyr7ZjrsjZoGvYfptCs|c&+|OGJaeUZO!%OM#xN`_(+&U*o>Na?{00aoa#I3l1Q@h2@#B>o3KNI??5;808G@!C|Lhdbl5&}&>;(4IM(eV@A8^``HrJ8=C3 z21RZ?U$X5!2<_!yMR&|&OIH3>f%Q8U_V$cnE!=tF0-qg0YWI%Z`BU$^Y@huf@VeY7 z_Xl%Ix++1F_|iYL-3VT%T|4`U)J(4WMsa2@Mm*gg!#m2DnTzUCtXSpqdkw~ON-jGN z5H%@Xe?DpVo;*(!w6zRl?G>5a1sNzKlDInc(mw~mLuQeNU8-L7C-S^nI9 zn^Mc6nT`(a&;rs-?|!g;SkG%}znHvyqCmCgilq4*{0lxOSVbeIvjfxFnpLJ7p{xnEAoY3sV24w)CMDT~-P(mWoaCx7F8IYs>vIdi1527dQc(RppOz@LrYn?!tQ&T&Yz=MLMiVT>8K=QoPMOa;*7WD|!hX zmv<&LpFiDP%Z@MZRpZY^Ie#GtMl*Te|E;`IY(vG@#Ql>)H-eEkzDFXmHdSdxh2laY zDXj}q30Cjd=e-enNgelhCOIuZ0!ong3@0#Vq}Gb&$`~)vdR^GgK4kS9GLRR;IRRJ- zZMgM_#*&Yt`~-E?*7MSw^E9%bV@I7SBm522{*e3Gkj}Tp-Y4c;(TVZq8Xygep18O% z$2YQ*I9IG*ykutj+XyFW^?h5ZN97zmfO^};LGNiQ^jw?@AK4KE%4r`-3~ z-C*b9zkXz1C8Nah&hPmW_&t8v&@7&4-8hpMFHlz}*hsNtZM9%9Dp!DZ0r>rA3!Iq^ zM170~mqaPNh+H;1eG*9b%Ed?RWsJFT#2(4cB%^vV6=W(~RJW+Y~h$U&IK+sv+? zw=32G`+C7M!{P>O5hkEK3dCkBBIKZr9%dok_x&)@R%>`MW__Fp@EEHzepb?w{Nw@M z*Ed$8D_fs=lhyyB0reKck=)G4xn3U6giAcmLmE;Yr@s-_XQhHw;@MXorR{G$-jMG@q;W-unGJp*kUH_d7X!0ciObil=GRf>-29PuK(Qu|aNL1>M+Wc8xNmyvY4v-jVIp^h&+|_`!d(PHFMNPzK$~H=63+Na-$-u&^>P*#rN%L7DYko4JsM);-}4 zm&_MF)#A?P@Q}%ggQNucow6oLdUyr9#-G$LS(E!ZGTY51X@V|HtI^xur9d0ZcIY1L z2C#z!A-grT!B%UQ7D3BLFciXzjdr)C-hb+ab|ZUfDSFuO&l~%jOAReC44iWF%oU7CPY>AfZ*(wj&pKva6~y#%D!NH2jP z1QI$V0YV_<<$k{JJV&3eoHPGq|7K^hXRoZ8HT$}*HT&wr@7xbR{uS#3Zx#4MvWRy;M z+E4isa;MEX<~jKC+{UL$JNMnKzo(}#(u{n|bTV$S&Ur5vyttzjb##>mAvuyNR$3;{ z_Y|KVe_O@Iswm}tzZ#pT)y4PeuVbsrQ*wwws%NmSRZe}!gDc!gew>Q4b6KMw8GOW+@xRPadSunVul_ti zxdmXbzC#!7fG=FHq@4(GpB2k5$W^9n0%XtVZpF#P1#jNoPRBydkMOMMs;$RyGRBvU z*xt2#8lbrnB*GEUaI#uo7FXgey-S4HXVFE7{xbaRxE__s^i+n^__Vub$>bCJyjEdG zVdj^S_z>f9e^QHZ|S>jCx)7pMv5is=&a-Sb`?+#0_(UQEguo962)$W4(#L&@g<-SF(_-tF0|=7&bd44(e?vi`a3zstoC?uIr&4TBF+|E@Ya zP<>pvMtN@F_h)5gb=JbZXHJRyKaTP5a?f|}Me|zO@697rD=U+Mf7C>%{+d7){86QQ zxj+)Ic%S3`f8D^pK5zcgasr;&@XI{=R8Mn!&kf0N@-dwxwci+H#EbS+jPWj)rp`-3HG{M!~1^F zYCE)mvMKnhX#lkHRo=*VdPPC)Hk+Qw1fzdMy-em|-}#+h!^KZF-TVzey^msOjq&EOb#ULokk zflzCv?a(^J39l}Mjj_Yq5)MzR?}$fjdfl{}K2?5mu-nIEwQIeOj8^pu@CZb_U#S3v z;+OWGeeCKPqmrAell%BaQ`YU!gM**~GiX9Ll5bADBp@iE z&RVRcI$&IS@;SD*ELVRuR{O(eS{7-Wzf!{mR_1)5Z@t27XWj)2>qjf{(0Dk1idKLC zepCiPt??K}%3loXU9!~19;DNh-~CY^=Z2ezK?<;ViSgK22e>*4u_0J{v#jvHENkbW2*YIRFjs!b zW^|)s*O)VYA9oEOkzXFOy$oNrtB<5}{yFbkiUyJnd+=RT8 z8&$gVIjO$-;pM!$T$LhyS}PnrQ36;DV#A%Q8BF&Wpg*m}esZ9Yh*nmw|;2Wt}17&=kTUGFE(fA1~ z=dmYijd!`l#y2LS%Ycf!n>q6eACr$ao1Rc(#;GDXlLf9{CE!Fgbe8UOsyD$RwZRf* zw)nN*#w9N-)paW^{@4F~lZ7Xg?u%KrD^ z7c9I`Baw}BHB@Fv#1_w*!eIof2mo4*7FYP~C5Er3{0gdT=&ZVVMi#5Ro^-nEH$n8E8ER9#dCpl%;cU zzdWSWteVkahB|Ym{ZSlD|5${RQmyCIeaWf1UsbldGiR)O8v0?EzU^sC{nYIRpPO(k zg^Dq)o%0osce4~H=|VDjXw+o?Qa-d{cH5yfU3cqYTku(IDOIRrbSyYJ6c*cE|HB0yd8G_Hd;JaZ(=jA^+Dz>o(H14m=vYYn)7ixj&muo zg5UWhHnUY)WW&=)AMh|(twduI+g?+cbPL-|l{noV{F%P$H3@KS4&KVCas7KL%ead? zSZh&vT7%p&fM^L$rgf5zxqVYk;(JCy?~yf|OlC!M^F+OScga0pZ}Nf{jWnrb?!+pN zK#ci1*M(#`^^_}~U3kYOqx$;ILy39w(R0R#xH6$@xBfd?$pl=2p$cBb9w}rXI|fi| zTm286D)Q2hPFFCKl_3E$oJZD7cy8v?`khWSp5p0Pp6}fyw3@w0+wwAqXe-cU!r{IJMl(;L!VZ=c3h(akLH-@x4X*uw137M+bzwcQH++p zxQMU^J!-h-@p5Zt?zjL@pi;y4Bc* z;z|b-c-F+IrvN&)sp~5TyCrv&CPAs9Y5nah z3+$S(?lo#2zT&hI?HY_>UyyuqmpyO8VP>uX`9l?C`-gSO({N5fZO0p7V@JEjjdun$ zu?M!k*d2iC=q1;LvrJaAMjTK5>b&Z0@lR$L$vdBD!>;9fSxc#)h^Y(|nI=p+p3|uB zs<{sH)1iR9X=bEkb&R%02 z^*13p4bC1hu2Q6`&jihb(CW?;p7a*z{%-Oda-{l%NdDZFlFT;XJ(J^3l2u}Joke`2OP%aS z$^LNBVg9R0&*3P;C=j|U#ME=&NxP@2n z1>XrQ>LVGFuDiA{EmP$0Yvkvb*2Mr>j)eVJVeyM0v^0@jyqE!6rwz)wUZ5LEJj%>& zV-8cU5FoSuXG^iujs!DDTe_U{KwZuYKv-X?R?*XFP+R8~#aUmn zg=~X^{)%=(-9PFM^OV`=2I9x8*nL6-^ZAlVi!H0s1!i5AEB_rD7!qo-1zml1u>*5w ziJRs%5a|>7Ab!oLxrT%Fm=E*zk4lFBkDb-$E}E7 z9W!^Sssl7tqvM!o`!ZMeUwm6X^$o^q(m8xkS8q|guenRr9L47}I!&#QS12&#WrM`j zK{6kP%)-rlJadYByatj}wDM`Ut0W>sYVP_H&y_rgwK=BpQ1u8O+piwIm(&yXeU1o& zB|q`cpxs8l%u$vJQt6C7&T8?g0x&y93fk$9z?fEa<&&G%QxIt*w|JVFq_i^!Cwmfo z4>DwvX0oe)`xg!SyipwO9bX6&G#X}snV)YpxY|-YUM$uKl8@Q-p@0M?7D)%Xz^H@< z@w?dWNIr@69v)=)xOjI@TqH6bRJa-=!lq5=w6=vddduT zGQ45z=dvZN07(G4Aeb^~6;I-*wB+iX{lXYRSQ-5+Lmt&mUpm;HD*PGt>K1=*Q1_rG zTOD5tfds6=__P}YA(YbLzQ|m#ShO?fdC(S9N0YAV@k_2z#wYX#za92DyHSgXROX90~ z_35@yoPd8KL(Z*4zm?-0oVnG(sgtjlq18z%g`>?(bLFkWIrwmq!Dcdh7f| zwHIDN8Wh?4{Tkv?UGQv_;h;qvduU~`h;HPk%s0mF!!etA}_=SN@8jKgG4@` zgqW?Bka^~yQr8WXu2o6oT)9*o6lsg&m6vE`v0BlM;H`$SjrdsZF0J9FGW)3_O%XtuOoO*?Q9(b^LR3tu z$yK~9`$=0#67bNrst;ZL9!pyA?5PRFkf_J`dR|qS-Rq;64VK#OTD)8mDOJM@be_#; zTw2~B@@1(*-^_TZ(Ga=RwOFY|jo`sB!37OrJ8kQlCvJEZ?87OG{X1Q~VxS&QQI4s? zS0g>-Jc`w()Y(&5tehP067FRdJ8_rAdB>NgqV<&OJw>aNLobU}BB!cg=iMTu-Lexh zM{eqv4NCLt+FK31GBlgK&5g}0p4DmCKTV~bO9A8Q%6FE;mV1hb)t+qj7ImtQQ&A|v zEr#T#Sf&ZZUvon=SS*pp+PAZ2fC$Jk`~u}1PuJYjFhi3Jz7QKIT^2vx730`x+r#D&? zz%_qX$ifrPdq2f=c>Lqt-_6PGK0OeCvMmB2A2u632C2`IULSR+_v%<`E^KL-DKr_34MQ&fSOr81T7(?7x3^5?v<4TGH~ zKbNx=*_^)^1uK5ptZmXY_;jt=6Lqfmbc6geZrTSkKU@{#Ut2=6W*sEodG9+O8MuGA zB@Z?^b`|=t>?LdloR)Y`gllFE&f{5!h=bJTlg);%C`wdm7of1LD**B8=L62~)}d-1wW?yZFid9O|I3 z!*@gj##tm^U{Z9_2&mG*%@DyfHg(f}EccC!5?dkWqTHJ8Tg=-)hN1rn&E?;_6Y|Lx zsm@Z}Grj^*u!m0$49);-y_Eefek1D-hR<7lzJeuQX*_vwpSI(~##_+_b=*-1LBMD( z@Q?#9RFcyyMadtAC?9T|*?eM+Y5P#-=R-jBtKbvLTjsZiI%~$FF4(@w!0HRrG=1sh z<<;o|@R#xnULLN~Z1RL{NS^uAZSODD_7ZYmqJ>Ob==Sa{UV2+_LSS}x?y`&9LG+&l z8QoxgekglId@G1Y&>xSC62XfeV4mkTx5+5(NnmE6KTh}XcRQC?)`PRQ=Q*B~J;-W2 zX^JD}pi34!7EeoI`$xpTPhLNuGxa~guLE1h`sl%s(RcMi#!r%U4C2FX!dqFcywakh z)TNlJXi+b}o7v6DOUhbJ{S#BZ1^?`BL?D(ekOL7e--67o$hJX`plnZR-pF@q5m*d0 zVuV-B>)#x($fSAjm~0b>3}K6>f-Uio!T%G%F7J6&G!@n!)Y7u*p6fc#wout|>r z{K5k6T-+s2d-`1p2%-}ogjwo-B?D$J8Ip7fDZ`#;OtrRt$BC;y4!7#$Lc5bfaKUX$ zt1B-KM;OgrXal2`YaIz*- z@Id)od5)SR!VviF5>Ko!ckr{FSA$RGE9MAVXI#avmjOxDxhD@4AIouxDS&8? zPFS`vG;(WaX+VBz&%d9TR22oP+lYcb0)t@qlV1;A>k8yPyCnL@TpyB32r#&ycXR88 zwZMbCZhn_&8N}E}^{rc9l>bW$P@&O*T7bnvh%fxV&7e!cy;AC7nDw5lrtRwDVRC6M z>0J#bNtmadIew(&<0lVfM5JqCRRAM@dvuS93ZUb9 z+nb3>Exm0O@0#VlB8~J*i@RK^GbtkM@B=pU*ubzWv~(WLLv=cNUI6C+-#d%K&QD__ z*k9L|+AJs06V^%Qb3U#6YR^k+eAq27rHq339Qb;olOyZmg(rorA8jbGP0J0|AyOVA>vn_<^3vRw_s}9MG z(H;LnSLw0yG++LR8hY&dETHCaq|hXFI@K#Ls3Fc|RyN^{L@}d>mfnw8$2d-z;cQ4B zcKx&c_MpK|={A=D(u*XXYK9}&=L}vlaNFvlYCKrU?>4Bo*e9ks*Ah}zGE=p=r4}e| z#V=#liT z?pK1%H{a#Cza?G0rIFr|t2U&@Hy)^cuQKE7q-=eNYEux3igIGeau zF~mMN5hD+*AwipvBQp)v4)Hb@=L5&VFr92nd3(BM1+;H#;&5OaqZmk*kO3MY1-4*< zlt3p*pbKtEiL$*$9AQL^Hgs+hzA+;!RCdN3{nE?m6Feb}A5tr#-%;eGJfML*Pa1Eya+0>Gn3ir zb7Cuahb^8lYc_%|ge%XqLQ>v`08OjvIsJ=`;m~gGQ9^&v>1-2_ru?Tvx0GVM(6iAT zD;SP|zfVE+Q3;s@+^V)KOPqGf7~kNMNUOCs?~EIA6Uqwcw(#Jvn8TN7X=*4a02)>2 z8Z((_wdLQQW`@-|yjk4xBxE3nj&&{WJ5J8-<8)tY0iV)7*?6*%*|UUPMj{k>j>on} zL}-U*#?n9wV_@1Yu{o%X;OSGwreFCCwQX~;Tm4$(`AjVmZGZ>NcA0(maS}_5>4&U& zDl>}(xu8N0Y8e%}FP;x$Hb;b3=9!y+BBP`l_nLi-0ye={8N>s8<*gvjDokMT_8A@Z zf;Lb2bcp5c&{pA~_alTOFl@rITd7w8@#S*0+F8DZAiTQjxo)2FBF@eLeWQkJ-)Uyi zF^G19{MZW6{_!!DEBcGy!^k8KPz~fU-%RQA#j`m>TaRYzlxE0R4=_?NV*;En3L*`~ z1mIsdga?ZuAJf!x{fH=k600m&G}d^(j7MK&ZPGF(nXvaDV2@f~sCN0WrRw%%go83G zJk@E{wS8ICXEFE!?X&!eE&Bj`aqDoE#P(>ckEvSbh^AKW-7nspAJ+|6;D_&Cw(Oc9 z_Lz3r9+SJpI!5wm7LF}RzGx%DKdjUyX8HUqV&uT3o;uYXsW5ZH)(0t@(z_fK(0?`Z zn@ytk0kHHsv+058vy)ici6Z(B(*-lPDD<4i2luJ#N}@(wk+KT6+ZI$R_bhE}1W0Z)dFKAmfp+%Y2TES#m`YAJ^l;v56C@=?lOUX26&sR$C*GGXed+1{07@u{p7wAbmr(f?bRiAR+*= zKZ0{4C3Wt^H3D;r6_Bi?(EkXhs5L-q84fy~mImki1 zVj35S)MAd54w^zo#%jlW49GfPg}HKj%5Et~hAz|5tUc~Eq~RZi^pmf{Y-ihh`qS#D zfQ0BE_|dOi2EDCbhF7oWM|yQeO^gB7z71o zO38RApQ~3Hsdd-${ky(oA}v5j{)``6t;UAJn{c76R;B)T+R&Ix)C<$j)fN>|a*JTD z-1RdYbyR`T%;qJWERR{?)?Xx+84%2Gt!?&@ig zq9u+Pqolx-XvU+5E8rgY;Xd{Lwj!5vGU|xcBep&qx)VuIO#5`hXwG{xd(-+AsMMwy zc=FjS9$PbZN4d@Ge%-UzM&utM@&s(fHta&Bj?@0>Fblk{L#FKilT*|^8IXTbF>pkO z8XSUGe3F)GANmznQKiT$jGB#hUW=sX%HO(Ak6S935&4yHpIsu$ED?DI&t?&@*Sn8) zH7Tftea;4N|71YT`E6Z$z^BxFfYPauk67)JfjsuP=x(*Di=B>h7Li)2j-Jxx8L(3zd((TI&rwy9MdXjDY$QN}%dY_lzIm{ah12tG|8C0SRi9P%dlI)oz z_C=EihyEF5*&KT$G;PUzj?@Jw#SJIXpKPohTgTSa02+32b%%$2 zTjaSe^3T77QE+{jtp+;2=*X_Vbr=sQ0*u;@V4Q0K4YVAaG1h0B@R&z6RVoPbT+d`n zt@;ryTztW-3}V>CXy*B`8bzs}r(Ba?O=n`u^K$%(v0V`o_ zmI6{dtPWIozc-CXr%clb_nL!tXJ$VH8u+|voUm6KKg9tEJRTmMkR;e`-6ijQW((R9 z4aW(s1CTX4rM;MM8#44M(s*>gGk+Bs+po%f&DGk*wRD!TQ6?iha_G9UuC53eVuQTG zzKbkk*OHst{!i8wz<7uVXl%>?Q$gZ>VGL5Tn?E74+Jo)!ZM{D{BQ_DKvf=}Vtj0VZq8W>5RNA5WTDL`=rrP`P!=Y8;twi%A!g`m1#$YHb)@AlNJ`VnMw->{M!;XtE#W zW=kC~N4SUxv%&J9izRgGCBxU0p;oeC*};juy+23nx~ILoqz|=vexUYi`!3Z=G<5Drv1I?si$}r$ zxn^Hh4{~#43%DWA1AW;>qoKX;N+Cw*!xngNW5jwW>hN6?;}z|~=S);z1R#`8UAcRn6at14clJ`!^ z0LQJ_8wNeFic&L|19V_xKM@DUmO^@JyvZ)rt%JXCMU-*2%ed-JDA zJN>cjmJ-vP&QK#ykSva_jU6&-;HQnT+w^fz3tabpK+oFSZQav`s6j5Kr?Y!K(|C7p zS@Pk@SFMnU!GzgsuD0)7C!KbQoe$&=FZV6nVB&mopQ^Ht!5mI~bdh@06xJcu_VZtw z0$+*HA|+&t88Vh~bVsrDcs|8yR%@nfVPrU~J^Stmc;XvKsyI+4QCCX(&EazO18)oJHiyS7@?K{#R+nog)+gV1QA;&*({)vGY8Ee*dNz-4VrV_x`ALVm24 z3B{xxc{ctGKJB->MMgb?)8-PM$uv}8ji84-<}+d>4y^=&9!sgzNsS_NHi-HSh5lB9 zdE%Pht(~6ujqAsRFe!}+A3{72MF4&|?NLLbAeZ9cepP_$@*TJ1dy0PF1W8QOtym`G(I`K|;uq=+mDrKlKha;lWxy@-GUE!z;ZP8096gG)I0iGu5qR z8ZQ#&W8Ov``*|LqP#nJ%=U3 z3+DBPi6iqw8Tbjm@VN1p6%>4}sPV*{x-^q=oH|EdTEYC_+8N9Jo6Y>f4lc{6lLHFr zs}MElJjK<-n)eEO;C4DPU>9uyJh@I1SZe6T4tr_WNie1SR-)9hsZhS2G<%j5WKGfR z?Jap6O>}bCNg0S>p)di7I^Z=cmGbWd9X82N^AFdQll)(qS^qR6rXa4$EIpPXpCnM> zBk$JaE(oCEVom`*;)%{_y^9Lr9tQDEG1*}Kr>eG!2(PysTX<=EorZrDEEc;Jq22%| z3A?!}AxXR&`Hgq}sUJ9&H$oa;QqGa;#vvc6%y;zr1*$0V0*>Lh+5U8X`DgdjpyG{e8$fnN5CK z(Tn?zIm2h^kv{NrS)Mbr!M%BYQq%KoV~tFuT+zCe@{8y`ELIR3=9qPK%cWw-l5}L* ze)pGr2f0niF6r;Z?w7|~hMk~>nQuVyfh<3oV@W#L|9Z4c`|aJFKIz@C{kW>ak7a++5mUsthMsQ~u6t+2O^9;)*Jvv`;1{?hG9BfjYF zbmrj=OPqU8ywrjI!Wwu+7(H#7rKl|k#Ivp;qk{p1`H1qvt4bG=aj zG6A9ED5}s*FH#c(V1CL9vM22Ak>|AKvt3SQA&Fe;BN7IcWdXpp&z{f&H$*AKu$EI#f2Tw|SaC^cc;;~U2T=hkYs95- z=43GXt>92JBv>CnyU*R09VeWfVvt_X%s(AKi}4`|`??QphM>1hL!V&<+v*e9AiNN~ zQ7IN-Gx~?L=taQ%R(c%FXh?f$x5qj@=k%+P5|h7CKVjx)h1KPE0yc=&Nii3@j96a7 zRcD(GVH(%Dt)E+Q&boD97oPoi`uIa;t*3nZPMusN*8}q3Q7t#iXw09%-&6n0xs?l| zuu$NyDu<3XiM);D;{%?-3iZ??oZ|b54a)U;6^$zx0bVK|(IheOXN(d!S4^ zv+A)0*9IHz@V1~d-u~FqF>G#08?f1ZkU|bTmnxVsDn$%Qdy4r~-yD@ag3ZHEV*aHy zn%w`|=dp|EA)8d*um5T!;c-Q%hA0pGpqHpDMhuq8ZR)b~HL|_g%KnyUv=sFacVbmH zzFE+-F|s&34~Sc-*UM3d9x3^{2EP1fWn!lEXl>2*NLit&Hk89>T2@~GNAkPP882)t zf@l&|)%FM`u{&fI@dzSM^rw;b3}+x`^b~-ol@Hfi=xABjfl(lQWuuU&N%Q1+&NGar z;H|t}ygsf8bo7N6#}$9VPw72d=L+xm)W&SSzA;$vJxunSYI;qVt6k(QCyAz>fyzo6mCicmou8 z_P!m4HhPl>S2UY$xG^*+_}o9_)=vE}qVFy%H~`z%HzBQidD^j??!)e)%$ef4YSOo9*H5=qP>i6PYEq!_Ih2>dYVNklsT8UhbwO+ zbDIrZEZoStmE_{dBRknP#r;BsH)YpOY+cX*&LacFKQ4^7X?=W3_^z8W1N(c+r7Vt@ zOMTvorFSoMe5+szY4FYWMHYQpj5(lMJ0^tpW7~ZWbC~RNDk)4CQ zs4-WjT)MlSTcK!! zvp}1HvJN_OB(vBZPMjWmEI>x5WBEdkEbY%g6v`Gz@fOTho()8cm1v{;b)fJ`Fe}pF zJ5mhtc$vKN8u{*2C0^A3#dx~;?)-q1%kXmjC~4yeBsFocHA5)L4Uo@V_MMr26a#Ej z*o)s$tMIXLAJdVWO}+J`j9Mb{s#{|Fs*|z;^y6!&kBwyZo#lD?bl%-Um@yaKYAaj? zx9p_tA+YvXCGM%=)a_!Wvv*K7iybTmnJpgiA>mc6cn@aI_FTDmL9^j35M`u&)$wvP zcfJ;f!~8?CC>jZR>_y}&r)aZ{7A-#rAQWgAy{t`YRRsJ}Jf;$B5BNYgBe@dha?7n*SgS&F+>H@dC4-X`k_|eS#S}ysk0il?pdbFq6 z#l-N;ab*2_A3A>IBhmAJq1rP8GW4XL>_wh&*7`NFZ7OJJ?>Zj7zggLP;75`3Z_DWJ zoV-!Yt9ySqMe2?mF33P~7PsUWAk1IS$Lx+PsJWe%{^CVg*81$=r};YpLo-Bl)g1d# z7ju_JtgwE(&+a{xc3R(0_43>!O&5_85MQ`XwX3c|cv>JP$vUXUUH(v-x@022QDSfL zKza(mrU}IbxWa4~o8(R(7KM)wxao3NzYu5WbvJYH6NBuDQt0&2+RryDD-rov}&Zcg>28YFUKy6VrH0Rh;3|tbk+7 zac;=a)aD`M#MUe8*>?FTz~5-Newi)Gwud-);Gd(0n6}ma*ODQ~9?BUj{9tHk^T^T* zWGxA51vK^GSm^tfF5D%gnZXDA%z}*(Z`>{wTJWM4rfWAR^V1;HnZ|OhlREFnkJHn^ zCej&Zu&)Tc7toWMS)|9D1Oe#WykgXT45YG8UMVyX{(=MvTThGO9~bW3p7!qPW$5lnIKzYP&+g{EH53MlVx2?zP-3t)YDL>_rOJ^`7+lx``&6V4nS~FG(3GP%1`J+;^JAFE!l#(F>ZedZeE?!s2ynr;d14&LF~)< zS^N<7zTXldU%+=XDR`!gd0M}A3;%eWG|YacLM|wM3u6cwlqj~;p8HX4Pdf(`l}yAm zlCxoGq-~97kK~tX{#RvM@>9>^t9=M2ib3nQoVW3u@5M$xpJsPkc@Z*D@9^k&SDpAi z!ZEmR8+NteMJ+f9z$`+-$Te0i$(0JeG}JoM2ucFCDD($F1W|kUcwf~yxNBMW&o(6_ zFKJm}C+jkS-gRIeoU&N%o`(j-k9MGZaMHmr^^M;3@dio{)@b5PTL)Wld1Czp*jx{S zePS-a4vjnIhE8!;>G5YYl&a{WB=t2;KiCR$^$+2K8YN5Z;XbO4#Me2c9zIu2LE@o z(FMfrB^h4xmtlt^A2E~iTNB_K>sv6-ovun6!0PEGu=Hn(8+u|XX%9nUocPlLZi>cj zB<`#!f=p`*tUizm1~)aD_&NR0h&1=qQlPVt6=F zaJ032Y+2q~>LfgkHz1q=TiRI*D}_sk zkK8~#PQfGt4L>LRU}shs7@li*X@xYT_VN#j9el?idaW^ z2lLz0aSDuzP<`uq?zY)pAnWA%>A9S(f~-cz8MX242EX_7yg`0FL6kNJNRsg^KH=~ew#ntv!47D&D8c`K$7d<9CgQ5~PULF%3_%>6D4 zpP#v6YYehB@((fnkTNsZi##d9eyRTJ>!Bve?-JA3!=2I&Va7D=_Q2t@VuAo9RcmgAB_dPBhuR^7F8 zuuwPNd&cxRy7D8a;vwx3H}`bOF)})V%nThie9IG~iT zaT+b|LQTh$nIZUQqByIo25I`pv4XW5589V(yARMY&Gof4K9yZ|+^P^zcd4ZPiIs)> zngDkAgdaUSKMyDbRD8Wq+n%Mz*K>n~K`qP1%Z**3f10BC3y1D~?4hSTcBcJr&Edb>&`hTiy9sOtjLnV7rvMXm%d*}0?n%B2AS? ze=2SpU(Eg~h-J9K$>|7WZN~gZ_vGWtiIcG|fBxvtIV8`-cD}9kj z-P_8#7X*dcK9zG6yZ(Z;u}?@{8Fi>X9=#Um_>iiibP&ZwUWwQYiC8KO(qmWlG=1aU zlBR`jo@Yo4uT^K3tt7HC{;xTL?J#h{9Pi)TuDQ zm^{`Bz!Nk6`nAT0u<@W3R(+eZod*H|>b7)W{d-=lv&Z6*a)g^lG`=h%gjB?%RH3*(R+I!S;vhK>-!DFMnp_$_2-=(%H+OuVEhi9aWLw2vR z0;y6>O;TNHPcu90;#VFe8@OF)2vQp$zJl=h14e1gp`*wK3Ets725K6WtrlM=l%cZ1 zyu>*az3nNn$unb5ZSGZofI4fu)TEZUX zdPgi9vF5x(bY72FNaN1H`7bQ|$GaW89UF z6Q0myi?e-e)((vhYu^1I#@;iasc2i&wKo)01VoyOfKsJ*Vg-~Ek=|8$?>!_c(xgOs zCrS~ip?8AxPUu|%1PBmX2rVJy#=YM@_nv+3J?H)5$I1$sYt7N-nBN?O7tgmqgwcr7 zEw$G_i6%Gl6<^CoV{YB_{{w# z!j%26&GNg!DAzI!K6DM{dqcmb;d5bXWwx3Li*w_;wiL!60-8u1*zENVntk=R$UuFs zLh$ih#HSk&C7J`zxotHCOSbe2)FTU~^w5A=3g6vx&L^?4`AYgP?4fTp&p07&T*v)V zyiok{7ht|C8)wQN|HJ{xtbJ0va3)L10lf66s%!5%k@a!!kLKQ^yU4gnU*`F9#kMsF zMK#&fp(3l>%G>@3upd2*DW&jD4nL4`+28X0H@s3vt(#i$x2DalowHp4{n&3;EU zg;{Q-P~z$N^==lXmv5fFZ25fcATR8S)UAfk-|vQ#5F@Z~UhIB9}kypL*nT za>9N2)!lDtO|yMGe)Dj+`OLhPw{@nCwT<&pq}E)Y$P2R(SOklmh*qpBg!$Q}d#^cJ zQNa%p55U2@>^Gs$YLg_XTpm(SJfxpVN=#D(FRNQUL|dE*P;kR=927Lk2J-A8n;;c6TobP-)tbD#KUz*>wlNCtdBtM z^-M!t>|{QQ?#w^WuGhUJ!1WQz6SO=UI(;yE9}x)QWdmB*W|gpi2P3|}g%x1127V(D zNJ3^H#??$)aXxL3)~19^K@h6DJg8(j-4&+S=!T1KHq>Ydmpd;FWVsykFSo;#T3W8* zQ;z3M4)f&StY{7!gT<}V<^~sH&ek6M^w;4xzaX4@9YVYvTC?+Ewv|=g*fY7YX;3Gh zO{943mF1sHpUDz$HMed0T3JDac_6#$uy8Xxlad|rj9hpKEPYe$XU@qk`)yEq{9eCE z&~ebLq4{grKrA(Pg36T;XaZ!6?;`>yv+b}Ep z`F=&D(i7xt>Kmc4w0)1RsiqG%P>3TTEEKcT-AmS}qCQN#==#`92dm;jaZ^By&FBZ` zCU;Gal1`d;t_e2-GMWtsPRQhN$`aTa@}AKTCJ3#&c{Z_lxr08X2wcgH9Ml{-U^*L} z*ky8X`llnCh6i3#$stgB^k}xkmrr0|-neCqk2@@5?`{pCBC|-QAF;v2pnl+cW7KKlFr^xjxJ; z?WBl-l^W3QGsB8xjRg6bzBQu$7DM#F(VQ+|1F!oWJGzK7LV;*)`$YHr^%7*WID(W9 z^ECSW$9~;-s``diRqd`dl35R#IT*>B7VcF}jM{YB4l_T%-q5v2$DmhykR;Y`gblCT zNnGyc*&}Ak$WYy0cs*q``ta>Kz@GNGe?&i0jYu+aYob%Z;AJlcOn@#w29YPa4`Y1= z>u?Y8HVnxCwsiRZ^6ckZt{59{!lUD-wWrK7RK#$zna9begyP0L%G$Z)Uq~pO3(?Oh zFu!oQy68v^(3Di{&~Kp8@}jEvW!R(eY_=meC7{xHEPdQsJAY&k{7%%Y@*-sQYS$5a z+cw9u+?fMAK&6sX{rqq09};(`_62CqNI`` zIp>*1>V$x~tx$@CH3#?l zG$V6*n({Z#R>$Mp*%d<{J&Y_hin?6*CwUb-n;h8jA-2v$D78|Ro9B?-M&#TLqo&Il zu#=B^LeFoH*j!K%Yca)T8By)Yqt8}Ob3I;?&aBd_GV4<4}@ zZKp;s8}!{Y8T{fc5#lj@u@(R`2;ZdA!yq7md#}=xeUCf@b>@%HDUzp6(6n-)B>MY; zcMc<7r2{;^O2BF9^vbL*HKDbk#lVomj9!Y`cQ_>V()!*_Mg-e4@?Az&H$K_=otsa! zs%qW3BPus0KG)O(da{D*I5dl!^AEWW_GCCk3J$WxsSn$ej7|zlnefN;FFr1=H2-dH zc3BxQm1gwTX3Hu{+k?QppNJbtRDI~38eH{yRWF^zE(9fy-I>^~9BzE6I5U5nx z2dk(O-l~7`u9~mhjZodk;vRh@O&dG(0(YL6o4P=6s^kbG@@Cqyh5>f_>SLP$1$d*L z);hqS*gSLmD-*c?Sbw|Ql)>KeK?aZ1OvFO>1nuUt0l<>}sVJDNOaNO3+(eqIbXDga#hfD!hs;y(+|lud zHO1T9>!71P@i-JOlw3+e4D9B91nPHkz@GTPIY9CY@0mO6o!5Chur_mSvYB*A?x@i_ z^NC%n>PsyXO@8}7@=2o3<}DFv!YgwGW;2)}JHUK=?-wVmXTpsE*Iio#@H--e>7tH$ zDk98J?f75KBwRkKI^;p`x_}5vUH!&x-*PrP?#8)1)Jkw<_v%~C^Ct{cUBD4-Xv&cA zd({oOw{Zet%((FGo@KW_NvzD`6TE^evm;E?rCfOMg25$c`N$(MC{>Rm^PMe{&{+Q9 zd`)`<G5(G$T9bXIbp#Zn6JaF99o8 zcPw}?H%PYjOp6(>t>CY2Kx#Tlg zw@H0%-+Z7=W0e7cH?3K|RCl9MF_0xZg%`wMvlM+ak0wxcCm;wv zGqfvJpPehC$Ay3MvT-tD%JwG(^vyCYTuf39f4qOhI#$jFZ>&jlI-<7w4gB>aF>h@x)8kz#j3BrkfqUI{+x+4vdV^F=ABEw(v1*boCEI6oflpsF@Ab3Cf zGuXHa04k5iBb&*Oev)I;9-gj@C}UT;g$aqWS8TKu^Sm^0R`MpqFG*`>S@6N>Db)tw zt&{aCwae+ia#JNKF!>fQ*yl_`ouIV0-R97R1bliSwe=*AL5M5hBk$=uZuqXf4Gc|& zFTdmS+WF9_C>9lzVtxPOwOr%eqA?44eqbr|ve3b$2Jhup@u#Y3&9Y^lfihcvvAf9o zeHNEuRAOqoBzF4eU1wH6gq^@o(V`|Fy(pa`)nC(^du4GZl+v(7>7Y$1F_FoNsP-sxJVCmvH06x#a9#KyW&I_Zj}!CrdQ`Guwl5** zS`wG+51t*Xd2OyTUe+^mM?Wmq#+f!$m2|Lxf)!jPD3{YbiFF9kp@^8%0tf8Fie{28 zm|d&OcaW(o{_sP&D=}VrHjM1RaS^Ww(}`(YDRc9k=8v{YeK`7qZtF8%uRJ(4u;Fc+ zJs)M#d@BBo=7DtR@d$B|GPYaID315))SQ0#;gIqAh^Dh;Pi)gI10jDR^f}pFaz3Na zg}-u?TIx9cG`51JScJo@hwnLGxxm1SI?l7}dP0SiKO-m|)(JD^$z}=(E`bs+1&^&3 zb{^S`6EcP6x>%rfndeJq%S?q;FO)gtiES*VuvZx7gQ#!nm1SapSFtVyU2Fh=PPQB; zD~E`f`M^>EHpVez;)meoFKRKpT%_6&m|Vo}3{Mw@}8NKW%PPemS_ z!85d|3&D!ANg-4W6MCy~y1z4E(T)NBnPTHcqjfF;&c7I68H6#U^kBlOUw*gaRsZz# zT(axNFjMAF-%Pl)MnetXkRy7(s7FwCDREZbw96=>x<;?HD0dgRxza8tx!%37FcFyJ zFn+1XEch;?X5dJN=!MDVDthU8_UP%%?)thy_y%NMKCv7$nLXw_^SOEpWcXNwDPSK! zYC_*1Fy3D}VB)opgmr#~dAn2Y5cF4kPu3aJUyc6a(h7e=mo6}xdbkxRn$kD4H{owU znfjFbmWSV9lU>%6-#kl70a3K*$qoo=fzExjJ31nvGF*1MUID*`s?$49KTl;2cCmcf zoBD*%RyrY9*(`LkLMT;NoXWfYb<)Ajc)EU4IWN&GUmtbFW}NGwa10XPXK`2r%H>9s z3=j^5ws9+od$ShD9u(%xt*Pjrf%1$}R=mUBzfEFRIkFzlq6xGfq3I`jd|iDOvj=p| zWa-GoYqPFuNp}+mH2PCXM%a;D7a_sw+j@b`N?7d};VqZ*r4w0(Y47?E&ruA^pRSLF z3?9Kg6PuTg*Fs3%iid5@v_9@J63)Zln2X6NffCbBG|NVtVbOYusjPWD1%yl{YNf;d zXMDH5Ecpd`2C_^b(Mi;8bXkay-Q*zjCH?>fw^FC*D9rC3>(b2FKZU04{3N&E?O3k# zH3l9L^SV{y@DL%7t%uZjZV+i|LOnl#QFK69l88SVR?psq@;v6GyN9}h^o65E zunCa&{N8LZt6$_b70{kD3qRqO$>G(wx~YuuDkd~u@*<;F2bZ`M{f^AS;dz-nLw>FN zudHG~kK>Pw=5nz@iuYn7?wmU&YVl$`E-H)FQ-l_EiYzb8+G(;2E&OrflLbpK7NN;x5Wk@C2{q>9`(4|GlUmIJ?c}mXe-Z3YUfWAJx$jn-i=iw^3qa`1 zasLN3&Bd$>PnE37VGQu&3yGKbb)|xMVm~!+y#9{rVZSG$3t4?QMh_=UDP@Lz z8wrPAv5+4eex70*1^Q+1QU!7T>Xu7zKi3>*bAe75cXpo$ew-94FK>SS>HtGM@p;dH z{-8OazM6XLS_;hk2n26KV=yJ#u)lI(hp;>*{*eDG2a}2@?C!CzU}Qgx<6%NvWIs(9 z;F|-;xduha%B(-9#>)dfPJiZ>4lzyxbk6R0-D_nZNR^&nh%ii(xfyo_(emOjAOX(1 zf46(+OoKj72{o5#C6zW5NPcT6XdrkhWy%CMC6gv3AfvJURR&oEIZ2UJ-}GXmbKZD~ zdRjADjEt%bJbpPt&)GZp3cfqCmXO{v=GM4%JCwotN!6wMtz^6T8pf4DN`EM7Y_Sd_ zKUy}SNo=s%#SJPVonS71Bp;EOnT>AJSaY+vRe=J0 zaXCq|-JoO9EBa8u=peO0^Cpfh$W3tFy(pJ0jjo|wL0Rlebb$ZcaeMU8T*qep;pnVs ze`L?qcdg6sSUl~hbp=#xn2+>w4VLWcahl1-k~X!D0q{0;M9eRjF9|z4shMOdwn3uB)Srnt4M~g=hwzq3TR=PLMsR~8vL{5sI`4w^BtC_t zE~ByI7oXQfpVbow+jZMhoI5()7Ra>O`HeHW(sh{GGB5d=|6o?TM&%MFQP2v3tmq$AW z1e5DTj&KOg6%Y0uWEFS5Ud6{FpJ9TWI&Evm0W9z_S4@|#2$D^lWx5ij5;RLokVu0N z_MQ;Ee;EFZW>@;iyzNFMu_a>3b(-nYKWNRdx*kyf(eHy+S9U?xAWT0&#ZAGzfTY|H zvqJa>W=e7T87O4cQ>-6zkX0ZAMVltgRm|jq9o|D9Q{ym*Y2jW~8ypO!OM~53;`-(* zIE*v6odRfxIZf!DKCb^POFar)b%fmco%zf?mP3%~5?#aL^>?)BZ%zHNie%PP)kPlM z9)-Ev48fx>!nJ+=Q_V9*JH2FC4HEZLTe~1;OSnaGDx~Os4O3R^&dcQvCn#ZQTKT0 z#aSP!d2g5`>O#jtPwni5NN&uLAJ&YOzmuz>`doz*WGoY4nW$xhgg2TbZl|7joB63SLyCihhv3m+l zDz*h6or$u7Q}H2ndVuZi06Nq9#LzF2r0V;_`9S0bKa{zz*G2CpJmCl7o4l=G*Qt7) zFUu<^Jhn_hTbb`94NaE)M$fSSJLa*dHzoV_&dUT;d4k%sA>f9*eJWx;o&8p|D2vQyIawosr(s{DKI)`z~%LKl?qp0AE>I|0A3_b^&z zFdp^o??RsrZHJCg>EPbLx`d1jLp+mEaT8ceF!&m$6u`#~+%OMPg56IOk(K5W_5?45 z5I(kN3((|;`PnM+WxFn+w}UW|e&Rnc6{>B?xi~~omvGSVS8!vyp(M+5DaXDcP{K6GDtAhz%!4aGHDw|5XcYdbc|>-Ko@>cBBqSH?L#({q z>tEcHRLWbGzpzQ_YQgKG=LmNOyx##-MkM>a>PO+)gd!k3nH*+oC?c<=1w2Imiv@6K z7fJ1BXc&1MJlEd`04~JLVsFGAO;1mpx_@Ufr;% z`^>RTGt{Sp*KG*Hm-*S>H)cA@Ye7fSv0Z1KO{8mfio8aTu`91DZ(4g>0V6}8Jj04^oQ-sw7(2Lgvvcd7LwhCV8gP41G zyvfgQ@BIzaq;j)Uyd--cG{Fu!Jfy-6o_0*+61a;!T`;Qqda+T-w=pnJr z0U(_Vpp_XyjwD82NpcU2&pTadpr>KpQkoW^O+X+GW<);WadrlMx_74n7dicUwVW+Jw@s;sWO3iEb!By87K>9CxJyK&lM%L|F+FsuQQiCIB)Iq2t z9lE4-ltyctvUSmVueWWSu!;RN23gZUfL*V$ppkLDr$N2vwI{f$l~5_~T0=*lE}5NmO5SJFu@Jf_t03jWa3!nW;Aqf_4T`%a_0*;hV(!sNcW{Mp)* z3}&56qpB!{i0MMQV~GMr^1u%YXhGhLZTMrj`F`%A1?;hpEkDjCu6v(8$HWhkG*B7x!?;+P9gh2bbgpzt8|eyoFnIT zXu(_pfI|d2%+MItx&6VRU5I@E-S)G>f7b4;(9iVMrm1G#~u@~3xj4U=NjmC(AH9hS}h zQQ0k(Byn<69jR*Z(kmsVaQm6~kf_2N-~7J_;eYNbAAM?U=0DO3Ea>uB2T*1+!oA(N z>1?#KR_0+p6CxE>E}kjuBSr z4}okp5YD~@DF%GYa>AyrZcp>yumwAwZ29+0s$;#UBR8tQ@D@ zzfA3mebLE(;kQFaD{#bCks0tY-~`+=81K;7aDyylzQ`V?(l*;SMZ6et3Ae3SUt`Qw!EM?j@}R9Inua zGZ&}oLx@TP^nniK6r2?HYJGJ~AmZuvRNA&K&=?*^AXNE|kWBoV)ZCPI!tp$R@b5!Q zP}iJA!niCo4uKsG(Z3_C#_XSlz3q55Mu$(9|EV+# zyOx8Z6`m_S&Hv?kmSyQ%OfDB;JK1Z{N{Q`J@|Xn1() z{RywwuPwgKIOQ9(?fNg*mr`k-hdqI8Kzk=J{jD_S1C|??79TY}&wpDXXhxunMC>_T z!1tFD4V;FHOsiFxV`-C)TEaG)l6+-pBkhQ&I^6~)BpWxz4SgD-M zIoa!8)&q|&kaBLb-x{g+aqbqVq6btJwzlblVm0Q!_d4WlDl$UIPUPN~LRFd;NM_%$v|CF|uSK zbKG@-LfU4tMxH<))OGyD9csi{j!y{MxleVASO(pXC)fM^9L}g!=f?LU;}Yz*laasn zr5Q5JS$|e$xJc2m>o=On8cMggUo5`1Qxd7pY5H=#*Nr#AisS z_zbb5{qN7Hb@dj4@W?0d%D+F)*V7eq(~tiBg*?1m6g)ruC@uTnpEK;k@0&|35*NB> zmIZCI#ZPuXVpkx~{`o8d$!G4{d141V8_NVm8-N~KoNYV9f2W2gVOd(sDEV{2NbRUb zWpSa~@e_6_MVBQO&8EXGyV(Lk%u!~H@1vCmkSi*652#^p)ripRxuN!rX(Ck3J_=lQ zXMg`EURr)C)&C;|PpWy}bE=o+t+2MLymAo@J?=`{BbvteX{yU;Lda|yGy3sLnQYKj zrkp@J3p?WVodI%KQl=g7{41ic#h5SumTv4T1phScQ*OeR|J)x)f4q~MG&iQ-qGx!^ zF%s1RJAqgnmIDdRHu5*$i!RwDa)K4jtb1FbeuS2g<24Y2173w-+w;NU4t%hcF3a})z@fg*3W;(d`_gviS`rG*3PRh2#@Zy*y;!(HNTfjTc8AI8E6p*BiJH0Ry!SI$)53H3n7NAB4ZJ_KuehcV` zytsNXm$Z7F6{QyI0O*t2(X5`8dL}+iJbcILFOLPz2P%CSKMLG+Ur4aK$l!XvNua7} zt9?se{quv@9Q%{a!#RPb{e`S&`5HBS;8l&Hgp1XAw<<8mTSt5H?H=f|G0~jnS0`Vy z7TwTxZb(c=6Nx?sv?6M$aFequiri%qW0oEIW)eA=FN+i>g~Me09-Y8Q&+-jB+86s3 zx{|(<1ivOO0~fFMz;c7TOd)=^^I;!4NB4s4!5(3eJ3OyiXmk^K!m|U;*lvR_1V0{<#0rpNcM z3%Mc@x*3ku>{^_EYa;0TIb25L4I~)b%q>7s84LkPd-eHiIb4^eIV|N{gXx zN~N74^p52HOPBf2+FfqnoNnEi9!(Lo5HDMIekl9x;CyA89}O=+D9-Go%yVr}vgslV z>HP^a;%oV{b`v?mk`B7OmCsJiAJVmR&G!8aMv1MU&1K*I#uxOBHKqh)27b(}k^Euw zOL`p>T^7(m1Fm+AC%AkLzX-)U%_m({q0hlHe7~7GI@lL^WZ|?5qRl06VyNy0jAj_ zcljU{`h|(K4Xu0-Yi;~9(z*rvJR-u0R+7kR`2C)8Ssa-F6iB4k_-}wK#=5tNsu#lt12(mJ#vb;1k3xBH4+0>tzRldB_4QAlj_my%WURqs zf5B0GSl9LoGTW=Yyk(#b6PC2@O2Osfr3-123m7(^LvD#U-bcj=3?$qxb>tE8?zW_L zu=MlxKEun6Y3n7Z>>RL!6r&2#;dL8l)u*LWS64GY6GZ2qJ2j>_O}*5nn$P(_1{}0fX-`8ya#iM8Z3@)I zYBvFH`yu?7)K)-}BfuRi>>Y7E?Z;Y94mUo$URvv%(qajzL8YdkWP9LqNE5QRF27_pBQ_4~?kx@a953~Ob&k#p z358eiX~r&^MqiO+8?M&0Fgo5@IN9v5_9|G>3Rm%IkBAo6TLWZD&#$vV`&aCTb6(zg zRECiWxED6Gp|M7qyI5(@+WJjNTqYL7KQ%=xdqdbhN|C6OP6+&+=$@IJjd^@N_=aAg z==&3-_Axm=8rNZzX3V+$R2-#~<+HgQ>2phCo9$)aiR5N@7h&g# z*m&B(0&XWz7J`1voKYDtMbu^PfyDw21hxs(F4nL}8c!Pqsz46yk9mL}VP@mThj(EI)=2rpGR=s%%o zY_MoJa3i1V0M|DK%9=6DtZ815@man&33tJ)N*_HOL^qVs`ZZB5l%&H~l@9fAS~dSc z%bfDPG4uX09HbZ>w#5lx=_B_s zxV$)23{3H;bf(^JBML7NxR!=ad929$IuWmL5MVZcl5JS=>lZ$Zw%js+HXu@4)dJ=4 zbF+a4;_qTgfH#w|R~Msz0XOWTtOojkVyh95@IDE&Ih+BB1Vtb?GFLOoW?6UV>WeU$ z0h1QH{lHpyl?ZDn1l`91u%7=K^uP*uMji3vg>Jc|15)1~sevEREF+@uk2(d?Zz zbpy7p6)vaC-`@tk5$?q3K9A2IxqPxxaavSJq?LOMI3A9(T8YiiFNk@ZM98q=CP=Tj9@vr;A-=UeLK z!Wn4G4~d+`!~#tUU6(<+*ijRQ>n`e>DqgT#hw9)c{Vrj&>)VMGQ_6!B#`szNN1Rbm z7RCL2E+Fg9ezeMATgC0+b&ZLR=~HwqPNBGYC~&l(jq&Q1EKEOfxkQiE2=ISl;1Ul~ zzuhy(^|eP6dYya&SG8y!={ArFDIIFD#q(EHCjX@{ZvmVNoU+e~6$;3xYyZ?1u(rZ{ z!-{KXr1Pt9TMq;>*;-~tePWXBTJzimwtaULGpXiQNjhcxxw>AzVnX6j`u%K8 zj1V6lsTY;bP`J#sa$qlAgpvaxs?kNJ;BS0J6S?mvtK-S`r~N{u)X0OL1y(JbM=Z_o zx=X)GfCc8T4c6vJn(N2{z59m92$`LtW-tyIb z2`NuEXYwQceR;ba_4rYM_>vo(6ssTJY$-_rY5y5ii?%nv-;jm~!od^~x0F-fZ;ynn=eS2@lI?ii zhu+ldikohK0n=u?$>s@)Uf{+?QIHyVktkUUxhm zn?>8EUH_`FbMvOkA>KyD!3OX3IT)Uon(f$EtPdIzN$M9i~zs5|50KmiAGjKI89?qWSkMQfw8Zirr z!99%lYvEZ{|Jr*`T;<*`@k63!6<7y)lzY%d&R=xmvtGqUW|T*?Z}N%dWXyHP@&w=k zdLx%-)*%Mfn|FI?KzFmJFAwZ$Mt6w>)9Ailq6PPvo;_rD+i8yJ!h-^3GosC5NV&bm9bd`ipCyZaA7-9KMGHN0slIVCDMxR1 z@JzZtRCf>he6A9V-6hP(G&(YMiD|^I4+VR-_zAQ;8$g)mzprAXVnrNZpGHsec}1It ztT2ur?p2b{1GVS+V8v6>J2dod$hY|db|oR$A#f+}GaVL#>w_HO4B8Sa9WY&41phZb?laPAFXZ0U8{ z0vLJ2DdNefdh(f|OOF>PR3>F#R4Ji1hE@~5CRbTbXi_iRq>k{c$fmt_q_}ZoPJlNe zeS|rnVluT}TLUNgbJ2;Gk?OmBs3BF$NWgVD@puLwT1{8qu7eU?v2V47JdJWwpNda0 z#LIZRO!WzCb%bJIE3+KFMY(jVZTd}l9t4d2wsEtU1j4ZayjVjG5p8_W=DdEhy}T~m zaQ4DPz2~|yU4&4GE((sUcbLz`mYp9Oh1^0O&0N_4eBHA0B;7HkDhq6{AhUg=cQ#gV zW4Prw8#D%UL$TUe!a^b>IJi02`g8P-LJ4nUfO#UcM$meKSNSx zzs}!a|8RPo@0D?DzCq8`>d|x=qu&ny3Fb-@x$!S9?9DMy{9+-;4t>f=is-^+(oaO& z*$jXDaZQu21m!UsOTP_exsFuFrv-s&6(gUuVhSkVZE(m0On?<=UB>)5dN{?mZl4RK zgyX3x2}ry!{|!MD;3av^*C8!#b2JA(tfj{PILzk4^)#6NTGn>`Jn+~w@Hs-|O)*gI z<^B5u-~7IEU%X~8Fg}V->0JUl0D@83@hTU0` z;#H@qZ)_)CS({Kb)uG=rl`J*mW$ys>kuZ-9)Y`!-Q*zgD(1*886x<0AkMVs?cB{WoEXm9>P8m8u7_)~QLI=hUGE+)8^#xtnZ`wB25p7VfQkY>|yID=y!cVh(4o~?%#5vX3Q1hIvg&&*g`&UGw%z9Gp z*D^P}eoB6NaWcb2G)&|VZV8zER55=mL3h&3iR<02Mg%KWzuY6R`XRdJBgMjra@(bO zGWe2*gu}dVkchR@lBzoY@dd`|9bH7~P|)48UzfyQAK0~8o*8m4%z9ivc%gE_oJP_< zm2}8e1N9N+ggRCi^~60o3XCe|GN^oY^e+}b?U2u3yi9fmpkPn={<@1`20XoGCBq7J z|GTP=iRkf-4~_gY)%OBD&nh+K7qq|AglKX z+8KEXD&YuHcE(A@OEu&$Zk~6)R{ZPq4p(apSwrF=m`*^iYk5+KpX4 z94n&n4w%9^+UnNjCng%n{=dN%}Fj$eR)d3B#Rk!COE=mVmNAQI@!QTvrHfg4lX;Z@5&7xz1Htc z5_&@bc}$mD=~{1d%cbYao2j2WVjp1R-uNI}|B(Sv{Ch~>C5y@;Qh`7V6bbJV!sz2s zYsb2@0O9|In57BjuRhn;E(SVW9k$tgQ*l$bkYxx!_dOn%Zf`#BD{AH^T}WWC!bB%}56N_e4XBHptZVJ|UG}Ce_>?=jEfq$J z6{t@72!1xkPiaK2MhG73B5N~na+ z%xpP5*c^gpz462cki<2T-Dnyl)==6?v}=d+^`B2ZLkpvq&w0B%|NbZi#Zq$5&>;W zDW@!Oh4-x_-Ho$cx%ySDnr{z|N$mNM*&fChHlJk+Zd`ljsW+5+yL!Mk?go_>C5lSyIUE$BWSPahuTyu<`Cc7Y89EkqBJV?z<6XJaxoCG>i+jFKPCFBh;BY8m1nAliL^V7PvOEy%8{h-A%!Gh$6;s0&K;x%yr0rK%Z4v6-{aV_vhQ zOAaxQ^`(kRzZU^EBS*;nWddB=b!d&ctv121n;OBx61E%=7jP`D_lkv#b;|m=Zb@UyV+s zI{sYxjRWDPPo?VP`zkCP|4AC{S3kRx#y9XT;A{8-INL8^IqD11vdQHQns(9zdokax z%ENv_ClOYC_6{zB7vEMQp?*&qzlUV>T|V^xvK*LLDfuz1Q}U6Eau<#u`<8l$hE#wd zyvJS(Ej9ky1AwEZfz>nfV>OSc0c8N`3HshPeb7zhv7IUZ z6moAC?@~^Z`0__Km1X;C6EV)5KH;wcvO>2H2IkmXe-4-jHeaB;_UZq%`g~Hm7#ZQ1 zDi(Uyj`ta{xs#3C=*>La?-wcj#mD9-wi5sCdLyObVT3;(dJh+CzPN=op*~6<#x2eH z>c|9PRn#mGDq-PehQE$~8z^5Zh=O>_HVH`maHug_Zl1$clH$yNp!4?#a!)(6KlfQY z{2O7`OR++~;kqveA8|=1cKz}dJtk@vgU6sK1v|Ofx9ag*xGP-IJ1>jNWfeQWbZoSC zctLnetgLL5qV;LNm7si2PRB1dhSIY2=u@v`3M!37$Dys?LgLl1;I8Rb*)HC z%5cJu?Se~e{GCC$MagaD+}@3M7*@B+GIncJDnJ`M50+>Byqy&%$_~sDC>EY41=UG; z|CGl>E(J$L05leWC`{^_I&|LxNm4Cb;B}|{56n~hq|g*YHP+?QKYAJKch|aB?}N z^nfsUH4UUZ=`{KOgLcAznQ$FjAU{-JJe8tBoF5AAYToI$SZ7g{Nm37~x=OJM+7)-Q z2BA+Eg z_uRX&3Vv$WStg;FDCD8pw!q9Z>Uen^Whb61U^?#~4bzYO;5DC;5cJn>>gJLpVnnEp z$nG?G{0Q+t!F}zz&C*B<-^T@h-AmGKRh)?IREDVUMzECGJh8)KDfK(EshVg+UfUXt zQ7S&Cd+GPA$?tdB$v~aHYw|xK1xcaU7E~`@AjQy^DWod)&+`_7mk9T~XUYz9x4=05{ z16${Q>YPWgio)hzk_0e?tDuuqejizwNn7hQ z)m3mht^D46PR4xS%quuv74!F$?#ppUsC7^2dyql^UEWQNb0Gp;z0DCTvtUozQB+!=Ia~C% zW$l<>KQ-*8YVVxRSD6xXx#Hr<)qPS}f?K;1I-}pD6qR!X;(&@YVG3{5xJp17(gru2 z@?KS)yK(2nXP>2~6G%$XbJotTh)0!d+{!h4kDV@#W~Q|K02%fTPICd?5oz_tULLOW zJ^i5T&bOodr5v2DfNbj8>MMR`Y6M+C* zs!~LxLn1YFgwR5l7J8&4A&~NA@9&(ob$ix2@1M+%Bu^&Kz2<%1nQQJL9XSvdSW`CqK|8#1UJyVjBJsf9@(kONGsJ25|5iQWja= zzdTOB4mbHpL!I4^c;c*PK5}Q$% zz@dbXb&{V&iMbrgb(jm%cCX!~C7=1IC;{@wC!#ne1x>Mv>0l*7x+B>rrob#U(5J(+ zlF(cnIW;!~MKPVEfcrMc4J^jS$}?a8RZ=u|SjpH*O;tUD6~DP;BS0GcFD^=G6=B9e zv>!RWQ5sKB%rKLxrW6iO7sWBXv6>{ip&~>1UmuJ!HGp(ll$dv5=ZhkKAy2rFwj6V+ z+Q4lLjBWsFJ^tp5DJ31djj5Up-PQnw^S-JcL#-xOmM`E>Scz-+y#~|W(f*+0`ulvD zURN0Yf>i|E{zk6$7=m%3hM*BUAhQX_N8+^05Gpf2{>?-XNQJ`CN;8V+u@cDxU^KFc zL$mf;a^<;uH(@#Z5~fubwV;vV{1>`MAtBkpeR13fe z)IEDTF6fE0og0*EkXL^)=iR1+^a!+5TI^S^gI@DL8tkF)s)frNH z;4nu=HyeeV(aRQ{SdQaA{(|3j+xWv%p$K37VsX;#U(D4yjnVhw5@kvQK3u(PR^yqN zCp>TD|0S>#IUbFD7DZ2Agg;D0I+hF62HA9tDR#366eugmYdY$#{um=r{`LmAxGm1q6mZ405>OKTZ_=r2&Doo{7b$3SadQ~g zv4HuFVEPfTxqv_o+Yh35vk3o-)BQs;0sF0f^zlb$cN|v!AJi2^s_9qaR;R%;lmYDQ zH`XfzbP;?ERU0iU=Syw>TXaAFI(o|KDqFwCdwQl=t%Kh`Oiyd7fRaX!8vNE@0sYU? z%2NHIv(-O;-QOS=y@t!34XhXk?DFs7_&4)47N5nl3jCYlx&|B$+fW4Z`N^nk9Q+ne z&DS1u1T<(NHU141W6kxCa^ynmkF|rve6d}X!TzRaC*Jy@{@)XR%hD_I`nE<{z1#aY z>sGy|*=+}RgC9ONK2Mq6Og$QZlh}@T&=91zpzxLh)W=p=lAp?q0a&uBiXzhYXu>T* zwOI^40t|!<2JEhO0bd-PO zL16H+fHxya(izs&{=XR8^-pzgewbOvcHwv2MGG(O93}o@PPZ;-9I#m~LH$T)|Ey;r zgpDmcpv+U3JLV$pu-Y==R(6D+c#8klxeNy055sx|^P}EVw@VhO*VP^8C_X4G$z_#E zN_DSRevOtPB;4F(V zqU4WWVBp2Y={Q)<_CwlOs6zEcT^prR)ASTEbNKb|Q(!~?)9GjzQ0K;YAi z-4-MuVI1B!ElJ_SPcRb)i{^HpT!EVVbAl(<d`;qirU-R`lO&;0t1tOS9N&yrBG+X+|pTMy_xUVApZQbWb27(Ke52W|Gf6SV|P z3w|@{$zpzYO|?vK{=Nk-bbBzYBIWE40>WV9i03E2z8sD`^XHL;UUlz7{lhpEgrm(h zQFW3N8R)ba@`hb9L$J#Q{(TafiC|)qwP}T;OTFmkB+=lN<`h*S^M+o1-L}numfLA= z@~MyZTpw9VwDyrX20DH68Ycq&iDu8FIa_tOpRvhyJ@*{Aw}7Ka^mssA-rQmZP!n45 zw!%6hQT-KCdvaba(2|u&!->ZWKd3#mQppS7>!?sU(m_7&J$gvX+pxlfzULjGkk7cp zcvYX(iI4&fk$F`F{Q;OLHkAkJghb1>eXNyO(~YW14i`Vg=UtK3Wo;?H7qxyZ)C)A} zKKFbnwds90I_GAtWPHIxYBkf^8BUKCopzkQZI{AVU|{|v4)Q64{Kn1edUj5dcco+` z-dAAUu1ULcd4sbw-;&civGVS}CC7`j`463X^&oS5R7scYbv9w6;SYBpPpb4Bm?I2q zW2*Vc%psccK2+_b6x-LvzR}e2@aU}i#ZS8<;<3u&nQp0i@cSNLWe-IARx!g&)*m*Dz5G>|idzHyr1vU}nY%;HkUAHWTbQ zOSrz%;+2X;PkJ;ThG8n{ZN0CEhqu9(BlgxxM8ohuMPxy|n4F z?$FH!H5E^{Dpr4?E6BEt*><`*Hg?BRZ_H@`;4M>MV6h1=QRyf)#2tlpp~P`t9%&B) zMBEjuPk#^MY`pz6;OR3H2M^Qf*!mgMvZz5k?k5w=^pD9?!sqWO#SKb*?(9qULIgPF zC2C{1=V0;x*@1XQg*M3e6nY^g;Xy`8$gO$S5;3c-d)}5@ue4vSsR7bx66Cb3M>IU z(v>VTlGME4#$vmM9ZP0o@9I%z&n<JLEQzp==LIM z#yzP>XY5*)3#0OgnVN;UH?Tpf6pBQCk`p&mbbnZhTqi8c2+xJlrhCqfm%3Af@(Zj_ z%%4oAe%z?a9f?`?ax^v$Zw;y*$QS!Ogr6X5E@2mKIQvB&Db%6`ef%WxZD!bBX?697 z}%|dYkr3#IY-kw zG#+sZV8>1iHoC$D-pg9;BYzoB*yej_iX`O+Y)98-?i#A0_l5#5EZ;#_u#7jMia{fz zKy%xAWPVe@oP+uyHtt?b^&eFco6JjR0gC63>x*BA72^t5I%LAutPfg5%tW$0{LM); z9Tkz~fJXp>US{E$p4+>A)vMJd1H&O%@!1AMTs-M=q zR)!3M?8I6pitMq}l72D+`M8UY{KBPM0^edJY4)_Zmve2>udCzKrG;ITD#@YRh!6hv zMm@ahEk+B)!mn!3$Z?9tazK(DCghj`_Xde8D)4e1;-K#vLkD5KW|LaKx0N>)=zKPWAH(p^kB(N@X%L*@>Is2_nm?<-onj#hy z7Cw=Xm5UF2bcz7(pJiNgwsY}z8rfNRT$pEWzW&w@iH4vf7U#RHt8lj&60YmlwuL={ z^d^c(uz!$NE^Q9$h;N%c@~0`AO7+rWt2Ez4%A21@3etR(vG(q`uzcgNxv3@bG`kn! z?R;be#G3MQa{+ z46jeWyVT^ZZcC z!0GO@pK!9}y%|O9+{}b=pIa<6G?8-g4-<3>%UqY+5=hDT)RQiq1)`KBa!M~huja0F zC+l}yn>T`Gy79X9147-8I2~?HD)0|nwn_dok*en1mmD?&-XkMXQJdP_&R3Pknhh+M zs97Mh#p#o0jsobS=^pf}q7YieRBCU7wH#qe5RTA&{9gY0iZ34xV#_k*C|2IhK^~1a z5mk1EgI9%%t+n>%sW@avD5bc=54R=_)k5Evj1_kNx&CUh{Nrw?`PBI@a?Pr>7{f}Y ziaL+BYitGRTxyEyh*7HCp6$R^u7Q9|L`$&g7HSAoS;BqLZqX zyY-;Rj9@ULZ)?{vG-Bk|!BTw!H~&#*H|6pVpB?k>5n?)0?-skiER&~YXHzR(xO5ig z&^wx#RV$7fkjh*#B~MY+ISs;e_ndh3c~Y8;i%F3t1Y1WePD_9`*dn5Odg^xR@R6pf ze1JP~jNHJDSouOe8QeW)*%d{^}TL zCM5@v#B)e=tP7J(e$T)7gSI+00jaw?Itoi^c7#g;BbpihDtmH#IqFvmw@aS3tVox$!9w!h<>}=&a*=l>FF;bWf;3*DAR5gNmk2BYYO37y%ejSI^r@7717L9 zh{HQd7eGlmB4Dk`oeP+5iUs2QX`8MCBrG1 zsgaQ|zZ*o)Q3GzBi)fVQ4sjfyi1ADDmE7QIA-gPfQH6r0;`syi0chb`EQf*Z-W?s{ zp?sPY^uD@20+rryV2?k`@g!IrwGgz eKS}s7Lm;IJuWF8qY*r#6URn?J)oN7iV*Ue25TyVB literal 0 HcmV?d00001 diff --git a/planning/planning_debug_tools/scripts/update_logger_level.sh b/planning/planning_debug_tools/scripts/update_logger_level.sh new file mode 100755 index 0000000000000..3a789f3416c02 --- /dev/null +++ b/planning/planning_debug_tools/scripts/update_logger_level.sh @@ -0,0 +1,41 @@ +#!/bin/bash + +declare -A node_name_dict +declare -A logger_name_dict + +# behavior path planner +behavior_path_module_list=("avoidance" "avoidance_by_lane_change" "dynamic_avoidance" "lane_change_right" "lane_change_left" "external_request_lane_change_right" "external_request_lane_change_left" "goal_planner" "start_planner" "side_shift") +for module in "${behavior_path_module_list[@]}"; do + node_name_dict[$module]="/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner" + logger_name_dict[$module]="planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner."$module +done + +# behavior velocity planner +behavior_velocity_module_list=("crosswalk" "walkway" "traffic_light" "intersection" "merge_from_private" "blind_spot" "detection_area" "virtual_traffic_light" "no_stopping_area" "stop_line" "occlusion_spot" "run_out" "speed_bump" "out_of_lane" "no_drivable_lane") +for module in "${behavior_velocity_module_list[@]}"; do + node_name_dict[$module]="/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner" + logger_name_dict[$module]="planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner."$module +done + +# obstacle avoidance planner +node_name_dict["obstacle_avoidance_planner"]=/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner +logger_name_dict["obstacle_avoidance_planner"]=/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner + +# motion velocity smoother +node_name_dict["motion_velocity_smoother"]=/planning/scenario_planning/motion_velocity_smoother +logger_name_dict["motion_velocity_smoother"]=/planning/scenario_planning/motion_velocity_smoother + +if [ -z "${node_name_dict[$1]}" ]; then + echo "[ERROR] $1 is not found." + echo -n "[ERROR] The available modules are [ " + for node_name in "${!node_name_dict[@]}"; do + echo -n "${node_name} " + done + echo "]" + exit 0 +fi + +# update logger +node_name=${node_name_dict[$1]} +logger_name=${logger_name_dict[$1]} +ros2 service call "$node_name/config_logger" logging_demo/srv/ConfigLogger "{logger_name: $logger_name, level: $2}" From 2175b573a0d19aeba5c77539357dd45037462254 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Sun, 17 Dec 2023 16:18:11 +0900 Subject: [PATCH 69/87] fix(static_drivable_area_expansion): fix bug in expansion logic for hatched road marking (#5842) fix(utils): fix drivable area expansion logic for zebra zone Signed-off-by: satoshi-ota --- .../static_drivable_area.cpp | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index f6344b94a6bc5..af4bebe183d1d 100644 --- a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -1183,6 +1183,8 @@ std::vector getBoundWithHatchedRoadMarkings( } else { if (!polygon) { will_close_polygon = true; + } else if (polygon.value().id() != current_polygon.value().id()) { + will_close_polygon = true; } else { current_polygon_border_indices.push_back( get_corresponding_polygon_index(*current_polygon, bound_point.id())); @@ -1217,6 +1219,17 @@ std::vector getBoundWithHatchedRoadMarkings( (*current_polygon)[mod(target_poly_idx, current_polygon_points_num)]); } } + + if (polygon.has_value() && current_polygon.has_value()) { + if (polygon.value().id() != current_polygon.value().id()) { + current_polygon = polygon; + current_polygon_border_indices.clear(); + current_polygon_border_indices.push_back( + get_corresponding_polygon_index(current_polygon.value(), bound_point.id())); + continue; + } + } + current_polygon = std::nullopt; current_polygon_border_indices.clear(); } From 0b587253a951fb4f7c02c8d8808c750bf6cfc89a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 18 Dec 2023 13:07:04 +0900 Subject: [PATCH 70/87] chore(motion_velocity_smoother): remove unnecessary info of non autonomous control (#5891) Signed-off-by: Takayuki Murooka --- .../src/motion_velocity_smoother_node.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp index 5e3924796f95f..90f7295c4cf6f 100644 --- a/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp +++ b/planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp @@ -799,7 +799,8 @@ MotionVelocitySmootherNode::calcInitialMotion( // use ego velocity/acceleration in the planning for smooth transition from MANUAL to AUTONOMOUS. if (node_param_.plan_from_ego_speed_on_manual_mode) { // could be false for debug purpose const bool is_in_autonomous_control = operation_mode_.is_autoware_control_enabled && - operation_mode_.mode == OperationModeState::AUTONOMOUS; + (operation_mode_.mode == OperationModeState::AUTONOMOUS || + operation_mode_.mode == OperationModeState::STOP); if (!is_in_autonomous_control) { RCLCPP_INFO_THROTTLE( get_logger(), *clock_, 10000, "Not in autonomous control. Plan from ego velocity."); From 68e74342840c26faf84971966adebbaf03da8157 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 18 Dec 2023 14:05:11 +0900 Subject: [PATCH 71/87] refactor(behavior_path_planner): remove use_experimental_lane_change_function (#5889) Signed-off-by: Takayuki Murooka --- .../lane_driving/behavior_planning/behavior_planning.launch.xml | 1 - planning/behavior_path_planner/README.md | 1 - 2 files changed, 2 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 4539e15a55954..b36b40ed6a980 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -210,7 +210,6 @@ - diff --git a/planning/behavior_path_planner/README.md b/planning/behavior_path_planner/README.md index 884767315ac12..40a23a09030de 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -139,7 +139,6 @@ Enabling and disabling the modules in the behavior path planner is primarily man The `default_preset.yaml` file acts as a configuration file for enabling or disabling specific modules within the planner. It contains a series of arguments which represent the behavior path planner's modules or features. For example: - `launch_avoidance_module`: Set to `true` to enable the avoidance module, or `false` to disable it. -- `use_experimental_lane_change_function`: Set to `true` to enable experimental features in the lane change module. !!! note From d06e42fdf538e5d8bda9130f85ec03a7e126783c Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 18 Dec 2023 14:25:56 +0900 Subject: [PATCH 72/87] perf(planning_debug_tools): improve calculation time of perception_reproducer (#5894) Signed-off-by: Takayuki Murooka --- .../perception_replayer/perception_reproducer.py | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py index d837abccc0670..b2b6a3c0ef38e 100755 --- a/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py @@ -84,9 +84,14 @@ def on_timer(self): # copy the messages self.stopwatch.tic("message deepcopy") - msgs = pickle.loads(pickle.dumps(msgs_orig)) # this is x5 faster than deepcopy - objects_msg = msgs[0] - traffic_signals_msg = msgs[1] + if self.args.detected_object: + msgs = pickle.loads(pickle.dumps(msgs_orig)) # this is x5 faster than deepcopy + objects_msg = msgs[0] + traffic_signals_msg = msgs[1] + else: + # NOTE: No need to deepcopy since only timestamp will be changed and it will be changed every time correctly. + objects_msg = msgs_orig[0] + traffic_signals_msg = msgs_orig[1] self.stopwatch.toc("message deepcopy") self.stopwatch.tic("transform and publish") From 37573e5301e8146143b99eb975d0841446e79a5a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 18 Dec 2023 14:57:10 +0900 Subject: [PATCH 73/87] fix(avoidance): unintentional path cut (#5887) * fix(avoidance): unintentional path cut Signed-off-by: satoshi-ota * fix(bpp): nouse pointer Signed-off-by: satoshi-ota * fix(bpp_common): nouse pointer Signed-off-by: satoshi-ota * fix(bpp_side_shift): nouse pointer Signed-off-by: satoshi-ota * fix(bpp_avoidance): nouse pointer Signed-off-by: satoshi-ota * fix(bpp_lane_change): nouse pointer Signed-off-by: satoshi-ota * fix(bpp_goal_planner): nouse pointer Signed-off-by: satoshi-ota * fix(bpp_start_planner): nouse pointer Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/scene.cpp | 28 ++++++++-------- .../src/default_fixed_goal_planner.cpp | 5 ++- .../src/goal_planner_module.cpp | 33 +++++++++---------- .../utils/base_class.hpp | 11 +++---- .../src/interface.cpp | 16 ++++----- .../src/scene.cpp | 24 +++++++------- .../src/behavior_path_planner_node.cpp | 3 +- .../src/planner_manager.cpp | 16 ++++----- .../dynamic_avoidance_module.cpp | 32 +++++++++--------- .../data_manager.hpp | 4 +-- .../interface/scene_module_interface.hpp | 2 +- .../src/utils/path_utils.cpp | 8 ++--- .../src/scene.cpp | 15 +++++---- .../src/start_planner_module.cpp | 14 ++++---- 14 files changed, 105 insertions(+), 106 deletions(-) diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index 783877e9c753d..ebe42f73d538b 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -220,7 +220,7 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat // lanelet info data.current_lanelets = utils::avoidance::getCurrentLanesFromPath( - *getPreviousModuleOutput().reference_path, planner_data_); + getPreviousModuleOutput().reference_path, planner_data_); data.extend_lanelets = utils::avoidance::getExtendLanes(data.current_lanelets, getEgoPose(), planner_data_); @@ -233,8 +233,8 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat }); // calc drivable bound - const auto shorten_lanes = - utils::cutOverlappedLanes(*getPreviousModuleOutput().path, data.drivable_lanes); + auto tmp_path = getPreviousModuleOutput().path; + const auto shorten_lanes = utils::cutOverlappedLanes(tmp_path, data.drivable_lanes); data.left_bound = toLineString3d(utils::calcBound( planner_data_->route_handler, shorten_lanes, parameters_->use_hatched_road_markings, parameters_->use_intersection_areas, true)); @@ -244,9 +244,9 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat // reference path if (isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) { - data.reference_path_rough = extendBackwardLength(*getPreviousModuleOutput().path); + data.reference_path_rough = extendBackwardLength(getPreviousModuleOutput().path); } else { - data.reference_path_rough = *getPreviousModuleOutput().path; + data.reference_path_rough = getPreviousModuleOutput().path; RCLCPP_WARN(getLogger(), "Previous module lane is updated. Don't use latest reference path."); } @@ -910,17 +910,17 @@ BehaviorModuleOutput AvoidanceModule::plan() } if (isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) { - output.path = std::make_shared(spline_shift_path.path); + output.path = spline_shift_path.path; } else { output.path = getPreviousModuleOutput().path; RCLCPP_WARN(getLogger(), "Previous module lane is updated. Do nothing."); } output.reference_path = getPreviousModuleOutput().reference_path; - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); - const size_t ego_idx = planner_data_->findEgoIndex(output.path->points); - utils::clipPathLength(*output.path, ego_idx, planner_data_->parameters); + const size_t ego_idx = planner_data_->findEgoIndex(output.path.points); + utils::clipPathLength(output.path, ego_idx, planner_data_->parameters); // Drivable area generation. { @@ -995,7 +995,7 @@ BehaviorModuleOutput AvoidanceModule::planWaitingApproval() } path_candidate_ = std::make_shared(planCandidate().path_candidate); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); return out; } @@ -1169,11 +1169,11 @@ void AvoidanceModule::updateData() helper_->setData(planner_data_); if (!helper_->isInitialized()) { - helper_->setPreviousSplineShiftPath(toShiftedPath(*getPreviousModuleOutput().path)); - helper_->setPreviousLinearShiftPath(toShiftedPath(*getPreviousModuleOutput().path)); - helper_->setPreviousReferencePath(*getPreviousModuleOutput().path); + helper_->setPreviousSplineShiftPath(toShiftedPath(getPreviousModuleOutput().path)); + helper_->setPreviousLinearShiftPath(toShiftedPath(getPreviousModuleOutput().path)); + helper_->setPreviousReferencePath(getPreviousModuleOutput().path); helper_->setPreviousDrivingLanes(utils::avoidance::getCurrentLanesFromPath( - *getPreviousModuleOutput().reference_path, planner_data_)); + getPreviousModuleOutput().reference_path, planner_data_)); } debug_data_ = DebugData(); diff --git a/planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp b/planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp index f028b8aff8b98..cbbe5f585dbe2 100644 --- a/planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp +++ b/planning/behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp @@ -33,9 +33,8 @@ BehaviorModuleOutput DefaultFixedGoalPlanner::plan( BehaviorModuleOutput output = // use planner previous module reference path getPreviousModuleOutput(); - const PathWithLaneId smoothed_path = - modifyPathForSmoothGoalConnection(*(output.path), planner_data); - output.path = std::make_shared(smoothed_path); + const PathWithLaneId smoothed_path = modifyPathForSmoothGoalConnection(output.path, planner_data); + output.path = smoothed_path; output.reference_path = getPreviousModuleOutput().reference_path; return output; } 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 b50387b3f6b0e..2ea6f1e100e91 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 @@ -282,7 +282,7 @@ void GoalPlannerModule::updateData() resetPathCandidate(); resetPathReference(); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); updateOccupancyGrid(); @@ -761,7 +761,7 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) const // because it takes time for the trajectory to be reflected auto current_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); keepStoppedWithCurrentPath(current_path); - output.path = std::make_shared(current_path); + output.path = current_path; } setModifiedGoal(output); @@ -777,14 +777,14 @@ void GoalPlannerModule::setStopPath(BehaviorModuleOutput & output) const { if (prev_data_.found_path || !prev_data_.stop_path) { // safe -> not_safe or no prev_stop_path: generate new stop_path - output.path = std::make_shared(generateStopPath()); + output.path = generateStopPath(); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, generate stop path"); } else { // not_safe -> not_safe: use previous stop path - output.path = prev_data_.stop_path; + output.path = *prev_data_.stop_path; // stop_pose_ is removed in manager every loop, so need to set every loop. - stop_pose_ = utils::getFirstStopPoseFromPath(*output.path); + stop_pose_ = utils::getFirstStopPoseFromPath(output.path); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, use previous stop path"); } @@ -800,20 +800,19 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output current_path, planner_data_, *stop_pose_, parameters_->maximum_deceleration_for_stop, parameters_->maximum_jerk_for_stop); if (stop_path) { - output.path = std::make_shared(*stop_path); + output.path = *stop_path; RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, generate stop path"); } else { - output.path = - std::make_shared(thread_safe_data_.get_pull_over_path()->getCurrentPath()); + output.path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Collision detected, no feasible stop path found, cannot stop."); } } else { // not_safe safe(no feasible stop path found) -> not_safe: use previous stop path - output.path = prev_data_.stop_path_after_approval; + output.path = *prev_data_.stop_path_after_approval; // stop_pose_ is removed in manager every loop, so need to set every loop. - stop_pose_ = utils::getFirstStopPoseFromPath(*output.path); + stop_pose_ = utils::getFirstStopPoseFromPath(output.path); RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "Collision detected, use previous stop path"); } } @@ -826,7 +825,7 @@ void GoalPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; } else { const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - *output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); + output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = target_drivable_lanes; @@ -853,9 +852,9 @@ void GoalPlannerModule::setTurnSignalInfo(BehaviorModuleOutput & output) const { const auto original_signal = getPreviousModuleOutput().turn_signal_info; const auto new_signal = calcTurnSignalInfo(); - const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path->points); + const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points); output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal( - *output.path, getEgoPose(), current_seg_idx, original_signal, new_signal, + output.path, getEgoPose(), current_seg_idx, original_signal, new_signal, planner_data_->parameters.ego_nearest_dist_threshold, planner_data_->parameters.ego_nearest_yaw_threshold); } @@ -942,11 +941,11 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate() BehaviorModuleOutput output{}; const BehaviorModuleOutput pull_over_output = planPullOverAsOutput(); output.modified_goal = pull_over_output.modified_goal; - output.path = std::make_shared(generateStopPath()); + output.path = generateStopPath(); output.reference_path = getPreviousModuleOutput().reference_path; const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - *output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); + output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info{}; current_drivable_area_info.drivable_lanes = target_drivable_lanes; @@ -1054,7 +1053,7 @@ void GoalPlannerModule::postProcess() void GoalPlannerModule::updatePreviousData(const BehaviorModuleOutput & output) { if (prev_data_.found_path || !prev_data_.stop_path) { - prev_data_.stop_path = output.path; + prev_data_.stop_path = std::make_shared(output.path); } // for the next loop setOutput(). @@ -1086,7 +1085,7 @@ void GoalPlannerModule::updatePreviousData(const BehaviorModuleOutput & output) if (!isActivated() || (!is_safe && prev_data_.stop_path_after_approval)) { return; } - auto stop_path = std::make_shared(*output.path); + auto stop_path = std::make_shared(output.path); for (auto & point : stop_path->points) { point.point.longitudinal_velocity_mps = 0.0; } diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp index a7a35f07e5f30..4bfd461a0815f 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp @@ -107,14 +107,13 @@ class LaneChangeBase virtual bool specialExpiredCheck() const { return false; } virtual void setPreviousModulePaths( - const std::shared_ptr & prev_module_reference_path, - const std::shared_ptr & prev_module_path) + const PathWithLaneId & prev_module_reference_path, const PathWithLaneId & prev_module_path) { - if (prev_module_reference_path) { - prev_module_reference_path_ = *prev_module_reference_path; + if (!prev_module_reference_path.points.empty()) { + prev_module_reference_path_ = prev_module_reference_path; } - if (prev_module_path) { - prev_module_path_ = *prev_module_path; + if (!prev_module_path.points.empty()) { + prev_module_path_ = prev_module_path; } }; diff --git a/planning/behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp index 1e80067842152..4a8eb34b088af 100644 --- a/planning/behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -201,8 +201,8 @@ BehaviorModuleOutput LaneChangeInterface::plan() module_type_->setPreviousDrivableAreaInfo(getPreviousModuleOutput().drivable_area_info); module_type_->setPreviousTurnSignalInfo(getPreviousModuleOutput().turn_signal_info); auto output = module_type_->generateOutput(); - path_reference_ = output.reference_path; - *prev_approved_path_ = *getPreviousModuleOutput().path; + path_reference_ = std::make_shared(output.reference_path); + *prev_approved_path_ = getPreviousModuleOutput().path; stop_pose_ = module_type_->getStopPose(); @@ -219,12 +219,12 @@ BehaviorModuleOutput LaneChangeInterface::plan() BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() { - *prev_approved_path_ = *getPreviousModuleOutput().path; + *prev_approved_path_ = getPreviousModuleOutput().path; module_type_->insertStopPoint( module_type_->getLaneChangeStatus().current_lanes, *prev_approved_path_); BehaviorModuleOutput out; - out.path = std::make_shared(*prev_approved_path_); + out.path = *prev_approved_path_; out.reference_path = getPreviousModuleOutput().reference_path; out.turn_signal_info = getPreviousModuleOutput().turn_signal_info; out.drivable_area_info = getPreviousModuleOutput().drivable_area_info; @@ -240,9 +240,9 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() } // change turn signal when the vehicle reaches at the end of the path for waiting lane change - out.turn_signal_info = getCurrentTurnSignalInfo(*out.path, out.turn_signal_info); + out.turn_signal_info = getCurrentTurnSignalInfo(out.path, out.turn_signal_info); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); stop_pose_ = module_type_->getStopPose(); @@ -366,9 +366,9 @@ void LaneChangeInterface::updateSteeringFactorPtr(const BehaviorModuleOutput & o const auto current_position = module_type_->getEgoPosition(); const auto status = module_type_->getLaneChangeStatus(); const auto start_distance = motion_utils::calcSignedArcLength( - output.path->points, current_position, status.lane_change_path.info.shift_line.start.position); + output.path.points, current_position, status.lane_change_path.info.shift_line.start.position); const auto finish_distance = motion_utils::calcSignedArcLength( - output.path->points, current_position, status.lane_change_path.info.shift_line.end.position); + output.path.points, current_position, status.lane_change_path.info.shift_line.end.position); steering_factor_interface_ptr_->updateSteeringFactor( {status.lane_change_path.info.shift_line.start, status.lane_change_path.info.shift_line.end}, diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index 21a600d11d83d..3adef17fc3b4d 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -145,38 +145,38 @@ BehaviorModuleOutput NormalLaneChange::generateOutput() BehaviorModuleOutput output; if (isAbortState() && abort_path_) { - output.path = std::make_shared(abort_path_->path); - output.reference_path = std::make_shared(prev_module_reference_path_); + output.path = abort_path_->path; + output.reference_path = prev_module_reference_path_; output.turn_signal_info = prev_turn_signal_info_; - insertStopPoint(status_.current_lanes, *output.path); + insertStopPoint(status_.current_lanes, output.path); } else { - output.path = std::make_shared(getLaneChangePath().path); + output.path = getLaneChangePath().path; const auto found_extended_path = extendPath(); if (found_extended_path) { - *output.path = utils::combinePath(*output.path, *found_extended_path); + output.path = utils::combinePath(output.path, *found_extended_path); } - output.reference_path = std::make_shared(getReferencePath()); + output.reference_path = getReferencePath(); output.turn_signal_info = updateOutputTurnSignal(); if (isStopState()) { const auto current_velocity = getEgoVelocity(); const auto current_dist = calcSignedArcLength( - output.path->points, output.path->points.front().point.pose.position, getEgoPosition()); + output.path.points, output.path.points.front().point.pose.position, getEgoPosition()); const auto stop_dist = -(current_velocity * current_velocity / (2.0 * planner_data_->parameters.min_acc)); - const auto stop_point = utils::insertStopPoint(stop_dist + current_dist, *output.path); + const auto stop_point = utils::insertStopPoint(stop_dist + current_dist, output.path); setStopPose(stop_point.point.pose); } else { - insertStopPoint(status_.target_lanes, *output.path); + insertStopPoint(status_.target_lanes, output.path); } } extendOutputDrivableArea(output); - const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path->points); + const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points); output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal( - *output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info, + output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold, planner_data_->parameters.ego_nearest_yaw_threshold); @@ -189,7 +189,7 @@ void NormalLaneChange::extendOutputDrivableArea(BehaviorModuleOutput & output) const auto drivable_lanes = utils::lane_change::generateDrivableLanes( *getRouteHandler(), status_.current_lanes, status_.target_lanes); - const auto shorten_lanes = utils::cutOverlappedLanes(*output.path, drivable_lanes); + const auto shorten_lanes = utils::cutOverlappedLanes(output.path, drivable_lanes); const auto expanded_lanes = utils::expandLanelets( shorten_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, dp.drivable_area_types_to_skip); diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 4828a0d62e7f6..85abf774d159e 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -738,7 +738,8 @@ PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath( { // TODO(Horibe) do some error handling when path is not available. - auto path = output.path ? output.path : planner_data->prev_output_path; + auto path = !output.path.points.empty() ? std::make_shared(output.path) + : planner_data->prev_output_path; path->header = planner_data->route_handler->getRouteHeader(); path->header.stamp = this->now(); diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index c867bffc8e9bd..36d5c7773fd24 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -198,7 +198,7 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da void PlannerManager::generateCombinedDrivableArea( BehaviorModuleOutput & output, const std::shared_ptr & data) const { - if (!output.path || output.path->points.empty()) { + if (output.path.points.empty()) { RCLCPP_ERROR_STREAM(logger_, "[generateCombinedDrivableArea] Output path is empty!"); return; } @@ -206,20 +206,20 @@ void PlannerManager::generateCombinedDrivableArea( const auto & di = output.drivable_area_info; constexpr double epsilon = 1e-3; - const auto is_driving_forward_opt = motion_utils::isDrivingForward(output.path->points); + const auto is_driving_forward_opt = motion_utils::isDrivingForward(output.path.points); const bool is_driving_forward = is_driving_forward_opt ? *is_driving_forward_opt : true; if (epsilon < std::abs(di.drivable_margin)) { // for single free space pull over utils::generateDrivableArea( - *output.path, data->parameters.vehicle_length, di.drivable_margin, is_driving_forward); + output.path, data->parameters.vehicle_length, di.drivable_margin, is_driving_forward); } else if (di.is_already_expanded) { // for single side shift utils::generateDrivableArea( - *output.path, di.drivable_lanes, false, false, data->parameters.vehicle_length, data, + output.path, di.drivable_lanes, false, false, data->parameters.vehicle_length, data, is_driving_forward); } else { - const auto shorten_lanes = utils::cutOverlappedLanes(*output.path, di.drivable_lanes); + const auto shorten_lanes = utils::cutOverlappedLanes(output.path, di.drivable_lanes); const auto & dp = data->drivable_area_expansion_parameters; const auto expanded_lanes = utils::expandLanelets( @@ -228,19 +228,19 @@ void PlannerManager::generateCombinedDrivableArea( // for other modules where multiple modules may be launched utils::generateDrivableArea( - *output.path, expanded_lanes, di.enable_expanding_hatched_road_markings, + output.path, expanded_lanes, di.enable_expanding_hatched_road_markings, di.enable_expanding_intersection_areas, data->parameters.vehicle_length, data, is_driving_forward); } // extract obstacles from drivable area - utils::extractObstaclesFromDrivableArea(*output.path, di.obstacles); + utils::extractObstaclesFromDrivableArea(output.path, di.obstacles); } std::vector PlannerManager::getRequestModules( const BehaviorModuleOutput & previous_module_output) const { - if (!previous_module_output.path) { + if (previous_module_output.path.points.empty()) { RCLCPP_ERROR_STREAM( logger_, "Current module output is null. Skip candidate module check." << "\n - Approved module list: " << getNames(approved_module_ptrs_) diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index de76166e068d3..99d7931dff907 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -264,12 +264,12 @@ bool DynamicAvoidanceModule::isExecutionRequested() const RCLCPP_DEBUG(getLogger(), "DYNAMIC AVOIDANCE isExecutionRequested."); const auto input_path = getPreviousModuleOutput().path; - if (!input_path || input_path->points.size() < 2) { + if (input_path.points.size() < 2) { return false; } // check if the ego is driving forward - const auto is_driving_forward = motion_utils::isDrivingForward(input_path->points); + const auto is_driving_forward = motion_utils::isDrivingForward(input_path.points); if (!is_driving_forward || !(*is_driving_forward)) { return false; } @@ -401,7 +401,7 @@ void DynamicAvoidanceModule::updateTargetObjects() const auto input_path = getPreviousModuleOutput().path; const auto & predicted_objects = planner_data_->dynamic_object->objects; - const auto input_ref_path_points = getPreviousModuleOutput().reference_path->points; + const auto input_ref_path_points = getPreviousModuleOutput().reference_path.points; const auto prev_objects = target_objects_manager_.getValidObjects(); // 1. Rough filtering of target objects @@ -427,7 +427,7 @@ void DynamicAvoidanceModule::updateTargetObjects() // 1.b. check obstacle velocity const auto [obj_tangent_vel, obj_normal_vel] = - projectObstacleVelocityToTrajectory(input_path->points, predicted_object); + projectObstacleVelocityToTrajectory(input_path.points, predicted_object); if ( std::abs(obj_tangent_vel) < parameters_->min_obstacle_vel || parameters_->max_obstacle_vel < std::abs(obj_tangent_vel)) { @@ -435,7 +435,7 @@ void DynamicAvoidanceModule::updateTargetObjects() } // 1.c. check if object is not crossing ego's path - const double obj_angle = calcDiffAngleBetweenPaths(input_path->points, obj_path); + const double obj_angle = calcDiffAngleBetweenPaths(input_path.points, obj_path); const double max_crossing_object_angle = 0.0 <= obj_tangent_vel ? parameters_->max_overtaking_crossing_object_angle : parameters_->max_oncoming_crossing_object_angle; @@ -455,7 +455,7 @@ void DynamicAvoidanceModule::updateTargetObjects() } // 1.e. check if object lateral offset to ego's path is small enough - const double obj_dist_to_path = calcDistanceToPath(input_path->points, obj_pose.position); + const double obj_dist_to_path = calcDistanceToPath(input_path.points, obj_pose.position); const bool is_object_far_from_path = isObjectFarFromPath(predicted_object, obj_dist_to_path); if (is_object_far_from_path) { RCLCPP_INFO_EXPRESSION( @@ -499,7 +499,7 @@ void DynamicAvoidanceModule::updateTargetObjects() [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); // 2.a. check if object is not to be followed by ego - const double obj_angle = calcDiffAngleAgainstPath(input_path->points, object.pose); + const double obj_angle = calcDiffAngleAgainstPath(input_path.points, object.pose); const bool is_object_aligned_to_path = std::abs(obj_angle) < parameters_->max_front_object_angle || M_PI - parameters_->max_front_object_angle < std::abs(obj_angle); @@ -513,13 +513,13 @@ void DynamicAvoidanceModule::updateTargetObjects() } // 2.b. calculate which side object exists against ego's path - const bool is_object_left = isLeft(input_path->points, object.pose.position); + const bool is_object_left = isLeft(input_path.points, object.pose.position); const auto lat_lon_offset = - getLateralLongitudinalOffset(input_path->points, object.pose, object.shape); + getLateralLongitudinalOffset(input_path.points, object.pose, object.shape); // 2.c. check if object will not cut in const bool will_object_cut_in = - willObjectCutIn(input_path->points, obj_path, object.vel, lat_lon_offset); + willObjectCutIn(input_path.points, obj_path, object.vel, lat_lon_offset); if (will_object_cut_in) { RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, @@ -537,7 +537,7 @@ void DynamicAvoidanceModule::updateTargetObjects() // 2.e. check time to collision const double time_to_collision = - calcTimeToCollision(input_path->points, object.pose, object.vel, lat_lon_offset); + calcTimeToCollision(input_path.points, object.pose, object.vel, lat_lon_offset); if ( (0 <= object.vel && parameters_->max_time_to_collision_overtaking_object < time_to_collision) || @@ -561,13 +561,13 @@ void DynamicAvoidanceModule::updateTargetObjects() const auto future_obj_pose = object_recognition_utils::calcInterpolatedPose(obj_path, time_to_collision); const bool is_collision_left = - future_obj_pose ? isLeft(input_path->points, future_obj_pose->position) : is_object_left; + future_obj_pose ? isLeft(input_path.points, future_obj_pose->position) : is_object_left; // 2.g. check if the ego is not ahead of the object. const double signed_dist_ego_to_obj = [&]() { - const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(input_path->points); + const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(input_path.points); const double lon_offset_ego_to_obj = motion_utils::calcSignedArcLength( - input_path->points, getEgoPose().position, ego_seg_idx, lat_lon_offset.nearest_idx); + input_path.points, getEgoPose().position, ego_seg_idx, lat_lon_offset.nearest_idx); if (0 < lon_offset_ego_to_obj) { return std::max( 0.0, lon_offset_ego_to_obj - planner_data_->parameters.front_overhang + @@ -898,7 +898,7 @@ double DynamicAvoidanceModule::calcValidStartLengthToAvoid( const PredictedPath & obj_path, const geometry_msgs::msg::Pose & obj_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape) const { - const auto input_path_points = getPreviousModuleOutput().path->points; + const auto input_path_points = getPreviousModuleOutput().path.points; const size_t obj_seg_idx = motion_utils::findNearestSegmentIndex(input_path_points, obj_pose.position); @@ -1027,7 +1027,7 @@ DynamicAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( return std::nullopt; } - auto input_ref_path_points = getPreviousModuleOutput().reference_path->points; + auto input_ref_path_points = getPreviousModuleOutput().reference_path.points; const size_t obj_seg_idx = motion_utils::findNearestSegmentIndex(input_ref_path_points, object.pose.position); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp index 3dcfdcc2bdcef..d52906ef4684f 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp @@ -119,10 +119,10 @@ struct BehaviorModuleOutput BehaviorModuleOutput() = default; // path planed by module - PlanResult path{}; + PathWithLaneId path{}; // reference path planed by module - PlanResult reference_path{}; + PathWithLaneId reference_path{}; TurnSignalInfo turn_signal_info{}; diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp index a5e2c3245f3c3..0ad30520815e8 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -405,7 +405,7 @@ class SceneModuleInterface virtual BehaviorModuleOutput planWaitingApproval() { path_candidate_ = std::make_shared(planCandidate().path_candidate); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); return getPreviousModuleOutput(); } diff --git a/planning/behavior_path_planner_common/src/utils/path_utils.cpp b/planning/behavior_path_planner_common/src/utils/path_utils.cpp index 994a7ba1a19d5..57a5743a5963b 100644 --- a/planning/behavior_path_planner_common/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_utils.cpp @@ -642,8 +642,8 @@ BehaviorModuleOutput getReferencePath( dp.drivable_area_types_to_skip); BehaviorModuleOutput output; - output.path = std::make_shared(reference_path); - output.reference_path = std::make_shared(reference_path); + output.path = reference_path; + output.reference_path = reference_path; output.drivable_area_info.drivable_lanes = drivable_lanes; return output; @@ -692,8 +692,8 @@ BehaviorModuleOutput createGoalAroundPath(const std::shared_ptr(reference_path); - output.reference_path = std::make_shared(reference_path); + output.path = reference_path; + output.reference_path = reference_path; output.drivable_area_info.drivable_lanes = drivable_lanes; return output; diff --git a/planning/behavior_path_side_shift_module/src/scene.cpp b/planning/behavior_path_side_shift_module/src/scene.cpp index 69df77672cd96..6df8c1ec629c9 100644 --- a/planning/behavior_path_side_shift_module/src/scene.cpp +++ b/planning/behavior_path_side_shift_module/src/scene.cpp @@ -203,17 +203,17 @@ void SideShiftModule::updateData() ? planner_data_->self_odometry->pose.pose : utils::getUnshiftedEgoPose(getEgoPose(), prev_output_); if (prev_reference_.points.empty()) { - prev_reference_ = *getPreviousModuleOutput().path; + prev_reference_ = getPreviousModuleOutput().path; } - if (!getPreviousModuleOutput().reference_path) { + if (getPreviousModuleOutput().reference_path.points.empty()) { return; } const auto centerline_path = utils::calcCenterLinePath( planner_data_, reference_pose, longest_dist_to_shift_line, - *getPreviousModuleOutput().reference_path); + getPreviousModuleOutput().reference_path); constexpr double resample_interval = 1.0; - const auto backward_extened_path = extendBackwardLength(*getPreviousModuleOutput().path); + const auto backward_extened_path = extendBackwardLength(getPreviousModuleOutput().path); reference_path_ = utils::resamplePathWithSpline(backward_extened_path, resample_interval); path_shifter_.setPath(reference_path_); @@ -286,7 +286,7 @@ BehaviorModuleOutput SideShiftModule::plan() output.reference_path = getPreviousModuleOutput().reference_path; prev_output_ = shifted_path; - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); debug_data_.path_shifter = std::make_shared(path_shifter_); @@ -329,7 +329,7 @@ BehaviorModuleOutput SideShiftModule::planWaitingApproval() output.reference_path = getPreviousModuleOutput().reference_path; path_candidate_ = std::make_shared(planCandidate().path_candidate); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); prev_output_ = shifted_path; @@ -409,7 +409,8 @@ BehaviorModuleOutput SideShiftModule::adjustDrivableArea(const ShiftedPath & pat { // for new architecture // NOTE: side shift module is not launched with other modules. Therefore, drivable_lanes can be // assigned without combining. - out.path = std::make_shared(output_path); + out.path = output_path; + out.reference_path = getPreviousModuleOutput().reference_path; out.drivable_area_info.drivable_lanes = expanded_lanes; out.drivable_area_info.is_already_expanded = true; } 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 0d3892cde8023..c9fa15d855268 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 @@ -402,11 +402,11 @@ BehaviorModuleOutput StartPlannerModule::plan() path = status_.backward_path; } - output.path = std::make_shared(path); + output.path = path; output.reference_path = getPreviousModuleOutput().reference_path; output.turn_signal_info = calcTurnSignalInfo(); path_candidate_ = std::make_shared(getFullPath()); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); setDrivableAreaInfo(output); @@ -512,11 +512,11 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() p.point.longitudinal_velocity_mps = 0.0; } - output.path = std::make_shared(stop_path); + output.path = stop_path; output.reference_path = getPreviousModuleOutput().reference_path; output.turn_signal_info = calcTurnSignalInfo(); path_candidate_ = std::make_shared(getFullPath()); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_unique(getPreviousModuleOutput().reference_path); setDrivableAreaInfo(output); @@ -1182,7 +1182,7 @@ BehaviorModuleOutput StartPlannerModule::generateStopOutput() { BehaviorModuleOutput output; const PathWithLaneId stop_path = generateStopPath(); - output.path = std::make_shared(stop_path); + output.path = stop_path; setDrivableAreaInfo(output); @@ -1201,7 +1201,7 @@ BehaviorModuleOutput StartPlannerModule::generateStopOutput() } path_candidate_ = std::make_shared(stop_path); - path_reference_ = getPreviousModuleOutput().reference_path; + path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); return output; } @@ -1258,7 +1258,7 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; } else { const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - *output.path, generateDrivableLanes(*output.path), + output.path, generateDrivableLanes(output.path), planner_data_->drivable_area_expansion_parameters); DrivableAreaInfo current_drivable_area_info; From 5a2da99bd716b9e8f93f891a9863be6cd5dd14fe Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Mon, 18 Dec 2023 17:42:27 +0900 Subject: [PATCH 74/87] chore: add maintainer in map packages (#5865) * add maintainer Signed-off-by: Kento Yabuuchi * modify map_tf_generator's maintainer Signed-off-by: Kento Yabuuchi --------- Signed-off-by: Kento Yabuuchi --- launch/tier4_map_launch/package.xml | 1 + map/map_height_fitter/package.xml | 1 + map/map_loader/package.xml | 1 + map/map_projection_loader/package.xml | 1 + map/map_tf_generator/package.xml | 4 +++- 5 files changed, 7 insertions(+), 1 deletion(-) diff --git a/launch/tier4_map_launch/package.xml b/launch/tier4_map_launch/package.xml index d8f69c124526a..f75a181bfb659 100644 --- a/launch/tier4_map_launch/package.xml +++ b/launch/tier4_map_launch/package.xml @@ -7,6 +7,7 @@ Ryohsuke Mitsudome Ryu Yamamoto Koji Minoda + Kento Yabuuchi Apache License 2.0 ament_cmake_auto diff --git a/map/map_height_fitter/package.xml b/map/map_height_fitter/package.xml index f50eba9218d67..2dc864b0cb925 100644 --- a/map/map_height_fitter/package.xml +++ b/map/map_height_fitter/package.xml @@ -7,6 +7,7 @@ Takagi, Isamu Yamato Ando Masahiro Sakamoto + Kento Yabuuchi Apache License 2.0 Takagi, Isamu diff --git a/map/map_loader/package.xml b/map/map_loader/package.xml index 5230d4bd03214..c8fcce6f7002f 100644 --- a/map/map_loader/package.xml +++ b/map/map_loader/package.xml @@ -8,6 +8,7 @@ Ryu Yamamoto Koji Minoda Masahiro Sakamoto + Kento Yabuuchi Apache License 2.0 diff --git a/map/map_projection_loader/package.xml b/map/map_projection_loader/package.xml index b128c2cf15e15..76e40d4379de4 100644 --- a/map/map_projection_loader/package.xml +++ b/map/map_projection_loader/package.xml @@ -7,6 +7,7 @@ Koji Minoda Yamato Ando Masahiro Sakamoto + Kento Yabuuchi Apache License 2.0 ament_cmake_auto diff --git a/map/map_tf_generator/package.xml b/map/map_tf_generator/package.xml index 6dc68911699aa..6e266b0ad82f0 100644 --- a/map/map_tf_generator/package.xml +++ b/map/map_tf_generator/package.xml @@ -4,7 +4,9 @@ map_tf_generator 0.1.0 map_tf_generator package as a ROS 2 node - azumi-suzuki + Yamato Ando + Kento Yabuuchi + Masahiro Sakamoto Apache License 2.0 ament_cmake_auto From a38d1db078fdae7fbfb0d47dcedc694ab1ce4131 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 18 Dec 2023 21:11:48 +0900 Subject: [PATCH 75/87] chore(crosswalk): remove debug print (#5896) Signed-off-by: Mamoru Sobue --- .../src/scene_crosswalk.cpp | 6 ------ 1 file changed, 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 69440aaddc2d0..b8a34bf5a9d00 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -371,12 +371,6 @@ std::optional CrosswalkModule::checkStopForCrosswalkUsers( const double direction_diff = tier4_autoware_utils::normalizeRadian( collision_point.crosswalk_passage_direction.value() - ego_crosswalk_passage_direction.value()); - RCLCPP_INFO( - rclcpp::get_logger("temp"), - "collision_point.crosswalk_passage_direction = %f, ego_crosswalk_passage_direction = %f, " - "direction_diff = %f", - collision_point.crosswalk_passage_direction.value(), - ego_crosswalk_passage_direction.value(), direction_diff); if (std::fabs(direction_diff) < planner_param_.vehicle_object_cross_angle_threshold) { continue; } From 81f5c4beccf046428ddc26f1496e128ef5213c30 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 18 Dec 2023 21:57:20 +0900 Subject: [PATCH 76/87] feat(pid_longitudinal_controller): change the condition from emergency to stopped (#5892) chore(pid_longitudinal_controller): change the condition from emergency to stopped Signed-off-by: Takayuki Murooka --- .../src/pid_longitudinal_controller.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 12f0eece1e477..698d4a8403069 100644 --- a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -646,10 +646,11 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d // in EMERGENCY state if (m_control_state == ControlState::EMERGENCY) { + if (stopped_condition) { + return changeState(ControlState::STOPPED); + } + if (!emergency_condition) { - if (stopped_condition) { - return changeState(ControlState::STOPPED); - } if (!is_under_control) { // NOTE: On manual driving, no need stopping to exit the emergency. return changeState(ControlState::DRIVE); From e6b41a8e280d40c73082371d14c5890a886eb671 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 18 Dec 2023 21:58:05 +0900 Subject: [PATCH 77/87] chore(behavior_velocity_planner): use DEBUG for launching modules (#5897) Signed-off-by: Takayuki Murooka --- .../src/scene_module_interface.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp b/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp index 6f596be92ec8b..362493005eb17 100644 --- a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -174,7 +174,7 @@ void SceneModuleManagerInterface::deleteExpiredModules( void SceneModuleManagerInterface::registerModule( const std::shared_ptr & scene_module) { - RCLCPP_INFO( + RCLCPP_DEBUG( logger_, "register task: module = %s, id = %lu", getModuleName(), scene_module->getModuleId()); registered_module_id_set_.emplace(scene_module->getModuleId()); scene_modules_.insert(scene_module); @@ -183,7 +183,7 @@ void SceneModuleManagerInterface::registerModule( void SceneModuleManagerInterface::unregisterModule( const std::shared_ptr & scene_module) { - RCLCPP_INFO( + RCLCPP_DEBUG( logger_, "unregister task: module = %s, id = %lu", getModuleName(), scene_module->getModuleId()); registered_module_id_set_.erase(scene_module->getModuleId()); From b9fa2905918eaff4a3be761b5c72553d74a2eead Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 18 Dec 2023 22:07:45 +0900 Subject: [PATCH 78/87] fix(intersection): generate yield stuck detect area from multiple lanes (#5883) Signed-off-by: Mamoru Sobue --- .../README.md | 6 + .../config/intersection.param.yaml | 4 +- .../docs/yield-stuck.drawio.svg | 750 ++++++++++++++++++ .../src/debug.cpp | 8 + .../src/scene_intersection.cpp | 83 +- .../src/scene_intersection.hpp | 6 +- .../src/util.cpp | 161 +++- .../src/util.hpp | 7 +- .../src/util_type.hpp | 1 + 9 files changed, 961 insertions(+), 65 deletions(-) create mode 100644 planning/behavior_velocity_intersection_module/docs/yield-stuck.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/README.md b/planning/behavior_velocity_intersection_module/README.md index db26be11b1c9a..58c2ce59edd48 100644 --- a/planning/behavior_velocity_intersection_module/README.md +++ b/planning/behavior_velocity_intersection_module/README.md @@ -184,6 +184,12 @@ If there is any object on the path inside the intersection and at the exit of th ![stuck_vehicle_detection](./docs/stuck-vehicle.drawio.svg) +## Yield stuck vehicle detection + +If there is any stopped object on the attention lanelet between the intersection point with ego path and the position which is `yield_stuck.distance_threshold` before that position, the object is regarded as yielding to ego vehicle. In this case ego is given the right-of-way by the yielding object but this module inserts stopline to prevent entry into the intersection. This scene happens when the object is yielding against ego or the object is waiting before the crosswalk around the exit of the intersection. + +![yield_stuck_detection](./docs/yield-stuck.drawio.svg) + ## Collision detection The following process is performed for the targets objects to determine whether ego can pass the intersection safely. If it is judged that ego cannot pass the intersection with enough margin, this module inserts a stopline on the path. diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index 1e6ce843de528..997addd48d7f8 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -29,9 +29,9 @@ yield_stuck: turn_direction: left: true - right: false + right: true straight: false - distance_threshold: 1.0 + distance_threshold: 5.0 collision_detection: consider_wrong_direction_vehicle: false diff --git a/planning/behavior_velocity_intersection_module/docs/yield-stuck.drawio.svg b/planning/behavior_velocity_intersection_module/docs/yield-stuck.drawio.svg new file mode 100644 index 0000000000000..e0078540ba407 --- /dev/null +++ b/planning/behavior_velocity_intersection_module/docs/yield-stuck.drawio.svg @@ -0,0 +1,750 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + w/ traffic light, right +
+
+ (Left-hand traffic) +
+ + +
+
+
+
+
+
+
+ w/ traffic light, right... +
+
+ + + + + + + + + + + + + + + + + + + +
+
+
+ + ego lane + +
+
+
+
+ ego lane +
+
+ + + + + + +
+
+
+ attention lane +
+
+
+
+ attention lane +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + T-shape junction w/o traffic light +
+
+ Right-hand traffic +
+
+
+
+
+
+ T-shape junction w/o traffic light... +
+
+ + + + + + + + + + + + + + + + + + +
+
+
+ + ego lane + +
+
+
+
+ ego lane +
+
+ + + + + + +
+
+
+ attention area +
+
+
+
+ attention area +
+
+ + + + + + + + + + + + +
+
+
+ + yield stuck detect area + +
+
+
+
+ yield stuck detect area +
+
+ + + + + + + + + + + + + +
+
+
+ + yield stuck detect area + +
+
+
+
+ yield stuck detect area +
+
+ + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_intersection_module/src/debug.cpp b/planning/behavior_velocity_intersection_module/src/debug.cpp index 8d9beb34d05ee..83e218185a5ad 100644 --- a/planning/behavior_velocity_intersection_module/src/debug.cpp +++ b/planning/behavior_velocity_intersection_module/src/debug.cpp @@ -196,6 +196,14 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray( &debug_marker_array, now); } + if (debug_data_.yield_stuck_detect_area) { + appendMarkerArray( + createLaneletPolygonsMarkerArray( + debug_data_.yield_stuck_detect_area.value(), "yield_stuck_detect_area", lane_id_, 0.6588235, + 0.34509, 0.6588235), + &debug_marker_array); + } + if (debug_data_.ego_lane) { appendMarkerArray( createLaneletPolygonsMarkerArray( diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 0d483b501d1ee..e036fac13fd3b 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -1056,29 +1056,33 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // stuck vehicle detection is viable even if attention area is empty // so this needs to be checked before attention area validation const bool stuck_detected = checkStuckVehicle(planner_data_, path_lanelets); - if (stuck_detected && stuck_stopline_idx_opt) { - auto stuck_stopline_idx = stuck_stopline_idx_opt.value(); + if (stuck_detected) { if (is_private_area_ && planner_param_.stuck_vehicle.enable_private_area_stuck_disregard) { - if ( - default_stopline_idx_opt && - fromEgoDist(stuck_stopline_idx) < -planner_param_.common.stopline_overshoot_margin) { - stuck_stopline_idx = default_stopline_idx_opt.value(); - } } else { - return IntersectionModule::StuckStop{ - closest_idx, stuck_stopline_idx, occlusion_peeking_stopline_idx_opt}; + std::optional stopline_idx = std::nullopt; + if (stuck_stopline_idx_opt) { + const bool is_over_stuck_stopline = fromEgoDist(stuck_stopline_idx_opt.value()) < + -planner_param_.common.stopline_overshoot_margin; + if (!is_over_stuck_stopline) { + stopline_idx = stuck_stopline_idx_opt.value(); + } + } + if (!stopline_idx) { + if (default_stopline_idx_opt && fromEgoDist(default_stopline_idx_opt.value()) >= 0.0) { + stopline_idx = default_stopline_idx_opt.value(); + } else if ( + first_attention_stopline_idx_opt && + fromEgoDist(first_attention_stopline_idx_opt.value()) >= 0.0) { + stopline_idx = closest_idx; + } + } + if (stopline_idx) { + return IntersectionModule::StuckStop{ + closest_idx, stopline_idx.value(), occlusion_peeking_stopline_idx_opt}; + } } } - // yield stuck vehicle detection is viable even if attention area is empty - // so this needs to be checked before attention area validation - const bool yield_stuck_detected = checkYieldStuckVehicle( - planner_data_, path_lanelets, intersection_lanelets.first_attention_area()); - if (yield_stuck_detected && stuck_stopline_idx_opt) { - const auto stuck_stopline_idx = stuck_stopline_idx_opt.value(); - return IntersectionModule::YieldStuckStop{closest_idx, stuck_stopline_idx}; - } - // if attention area is empty, collision/occlusion detection is impossible if (!first_attention_area_opt) { return IntersectionModule::Indecisive{"attention area is empty"}; @@ -1124,6 +1128,32 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // filter objects auto target_objects = generateTargetObjects(intersection_lanelets, intersection_area); + const bool yield_stuck_detected = checkYieldStuckVehicle( + target_objects, interpolated_path_info, intersection_lanelets.attention_non_preceding_); + if (yield_stuck_detected) { + std::optional stopline_idx = std::nullopt; + const bool is_before_default_stopline = fromEgoDist(default_stopline_idx) >= 0.0; + const bool is_before_first_attention_stopline = + fromEgoDist(first_attention_stopline_idx) >= 0.0; + if (stuck_stopline_idx_opt) { + const bool is_over_stuck_stopline = fromEgoDist(stuck_stopline_idx_opt.value()) < + -planner_param_.common.stopline_overshoot_margin; + if (!is_over_stuck_stopline) { + stopline_idx = stuck_stopline_idx_opt.value(); + } + } + if (!stopline_idx) { + if (is_before_default_stopline) { + stopline_idx = default_stopline_idx; + } else if (is_before_first_attention_stopline) { + stopline_idx = closest_idx; + } + } + if (stopline_idx) { + return IntersectionModule::YieldStuckStop{closest_idx, stopline_idx.value()}; + } + } + const double is_amber_or_red = (traffic_prioritized_level == util::TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED) || (traffic_prioritized_level == util::TrafficPrioritizedLevel::FULLY_PRIORITIZED); @@ -1376,13 +1406,10 @@ bool IntersectionModule::checkStuckVehicle( } bool IntersectionModule::checkYieldStuckVehicle( - const std::shared_ptr & planner_data, const util::PathLanelets & path_lanelets, - const std::optional & first_attention_area) + const util::TargetObjects & target_objects, + const util::InterpolatedPathInfo & interpolated_path_info, + const lanelet::ConstLanelets & attention_lanelets) { - if (!first_attention_area) { - return false; - } - const bool yield_stuck_detection_direction = [&]() { return (turn_direction_ == "left" && planner_param_.yield_stuck.turn_direction.left) || (turn_direction_ == "right" && planner_param_.yield_stuck.turn_direction.right) || @@ -1392,13 +1419,9 @@ bool IntersectionModule::checkYieldStuckVehicle( return false; } - const auto & objects_ptr = planner_data->predicted_objects; - - const auto & ego_lane = path_lanelets.ego_or_entry2exit; - const auto ego_poly = ego_lane.polygon2d().basicPolygon(); - return util::checkYieldStuckVehicleInIntersection( - objects_ptr, ego_poly, first_attention_area.value(), + target_objects, interpolated_path_info, attention_lanelets, turn_direction_, + planner_data_->vehicle_info_.vehicle_width_m, planner_param_.stuck_vehicle.stuck_vehicle_velocity_threshold, planner_param_.yield_stuck.distance_threshold, &debug_data_); } diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 4c33c0960afc3..7366bdc1bc0e6 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -336,9 +336,9 @@ class IntersectionModule : public SceneModuleInterface const util::PathLanelets & path_lanelets); bool checkYieldStuckVehicle( - const std::shared_ptr & planner_data, - const util::PathLanelets & path_lanelets, - const std::optional & first_attention_area); + const util::TargetObjects & target_objects, + const util::InterpolatedPathInfo & interpolated_path_info, + const lanelet::ConstLanelets & attention_lanelets); util::TargetObjects generateTargetObjects( const util::IntersectionLanelets & intersection_lanelets, diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 1c7e366347fec..e491d2ce7c5ce 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -31,6 +31,7 @@ #include #include +#include #include #include @@ -298,7 +299,7 @@ std::optional generateIntersectionStopLines( const auto path_footprint = tier4_autoware_utils::transformVector( local_footprint, tier4_autoware_utils::pose2transform(base_pose)); if (bg::intersects(path_footprint, first_attention_lane_centerline.basicLineString())) { - // TODO(Mamoru Sobue): maybe consideration of braking dist is necessary + // NOTE: maybe consideration of braking dist is necessary first_footprint_attention_centerline_ip_opt = i; break; } @@ -1179,40 +1180,145 @@ bool checkStuckVehicleInIntersection( return false; } -bool checkYieldStuckVehicleInIntersection( - const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_ptr, - const lanelet::BasicPolygon2d & ego_poly, const lanelet::CompoundPolygon3d & first_attention_area, - const double stuck_vehicle_vel_thr, const double yield_stuck_distance_thr, DebugData * debug_data) +static lanelet::LineString3d getLineStringFromArcLength( + const lanelet::ConstLineString3d & linestring, const double s1, const double s2) { - const auto first_attention_area_2d = lanelet::utils::to2D(first_attention_area); - Polygon2d first_attention_area_poly; - for (const auto & p : first_attention_area_2d) { - first_attention_area_poly.outer().emplace_back(p.x(), p.y()); - } - - for (const auto & object : objects_ptr->objects) { - if (!isTargetStuckVehicleType(object)) { - continue; // not target vehicle type + lanelet::Points3d points; + double accumulated_length = 0; + size_t start_index = linestring.size(); + for (size_t i = 0; i < linestring.size() - 1; i++) { + const auto & p1 = linestring[i]; + const auto & p2 = linestring[i + 1]; + const double length = boost::geometry::distance(p1.basicPoint(), p2.basicPoint()); + if (accumulated_length + length > s1) { + start_index = i; + break; } - const auto obj_v_norm = std::hypot( - object.kinematics.initial_twist_with_covariance.twist.linear.x, - object.kinematics.initial_twist_with_covariance.twist.linear.y); - if (obj_v_norm > stuck_vehicle_vel_thr) { - continue; // not stop vehicle + accumulated_length += length; + } + if (start_index < linestring.size() - 1) { + const auto & p1 = linestring[start_index]; + const auto & p2 = linestring[start_index + 1]; + const double residue = s1 - accumulated_length; + const auto direction_vector = (p2.basicPoint() - p1.basicPoint()).normalized(); + const auto start_basic_point = p1.basicPoint() + residue * direction_vector; + const auto start_point = lanelet::Point3d(lanelet::InvalId, start_basic_point); + points.push_back(start_point); + } + + accumulated_length = 0; + size_t end_index = linestring.size(); + for (size_t i = 0; i < linestring.size() - 1; i++) { + const auto & p1 = linestring[i]; + const auto & p2 = linestring[i + 1]; + const double length = boost::geometry::distance(p1.basicPoint(), p2.basicPoint()); + if (accumulated_length + length > s2) { + end_index = i; + break; } + accumulated_length += length; + } - const auto obj_footprint = tier4_autoware_utils::toPolygon2d(object); + for (size_t i = start_index + 1; i < end_index; i++) { + const auto p = lanelet::Point3d(linestring[i]); + points.push_back(p); + } + if (end_index < linestring.size() - 1) { + const auto & p1 = linestring[end_index]; + const auto & p2 = linestring[end_index + 1]; + const double residue = s2 - accumulated_length; + const auto direction_vector = (p2.basicPoint() - p1.basicPoint()).normalized(); + const auto end_basic_point = p1.basicPoint() + residue * direction_vector; + const auto end_point = lanelet::Point3d(lanelet::InvalId, end_basic_point); + points.push_back(end_point); + } + return lanelet::LineString3d{lanelet::InvalId, points}; +} - // check if the object is too close to the ego path - if (yield_stuck_distance_thr < bg::distance(ego_poly, obj_footprint)) { +static lanelet::ConstLanelet createLaneletFromArcLength( + const lanelet::ConstLanelet & lanelet, const double s1, const double s2) +{ + const double total_length = boost::geometry::length(lanelet.centerline2d().basicLineString()); + // make sure that s1, and s2 are between [0, lane_length] + const auto s1_saturated = std::max(0.0, std::min(s1, total_length)); + const auto s2_saturated = std::max(0.0, std::min(s2, total_length)); + + const auto ratio_s1 = s1_saturated / total_length; + const auto ratio_s2 = s2_saturated / total_length; + + const auto s1_left = + static_cast(ratio_s1 * boost::geometry::length(lanelet.leftBound().basicLineString())); + const auto s2_left = + static_cast(ratio_s2 * boost::geometry::length(lanelet.leftBound().basicLineString())); + const auto s1_right = + static_cast(ratio_s1 * boost::geometry::length(lanelet.rightBound().basicLineString())); + const auto s2_right = + static_cast(ratio_s2 * boost::geometry::length(lanelet.rightBound().basicLineString())); + + const auto left_bound = getLineStringFromArcLength(lanelet.leftBound(), s1_left, s2_left); + const auto right_bound = getLineStringFromArcLength(lanelet.rightBound(), s1_right, s2_right); + + return lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); +} + +bool checkYieldStuckVehicleInIntersection( + const util::TargetObjects & target_objects, + const util::InterpolatedPathInfo & interpolated_path_info, + const lanelet::ConstLanelets & attention_lanelets, const std::string & turn_direction, + const double width, const double stuck_vehicle_vel_thr, const double yield_stuck_distance_thr, + DebugData * debug_data) +{ + LineString2d sparse_intersection_path; + const auto [start, end] = interpolated_path_info.lane_id_interval.value(); + for (unsigned i = start; i < end; ++i) { + const auto & point = interpolated_path_info.path.points.at(i).point.pose.position; + const auto yaw = tf2::getYaw(interpolated_path_info.path.points.at(i).point.pose.orientation); + if (turn_direction == "right") { + const double right_x = point.x - width / 2 * std::sin(yaw); + const double right_y = point.y + width / 2 * std::cos(yaw); + sparse_intersection_path.emplace_back(right_x, right_y); + } else if (turn_direction == "left") { + const double left_x = point.x + width / 2 * std::sin(yaw); + const double left_y = point.y - width / 2 * std::cos(yaw); + sparse_intersection_path.emplace_back(left_x, left_y); + } else { + // straight + sparse_intersection_path.emplace_back(point.x, point.y); + } + } + lanelet::ConstLanelets yield_stuck_detect_lanelets; + for (const auto & attention_lanelet : attention_lanelets) { + const auto centerline = attention_lanelet.centerline2d().basicLineString(); + std::vector intersects; + bg::intersection(sparse_intersection_path, centerline, intersects); + if (intersects.empty()) { continue; } + const auto intersect = intersects.front(); + const auto intersect_arc_coords = lanelet::geometry::toArcCoordinates( + centerline, lanelet::BasicPoint2d(intersect.x(), intersect.y())); + const double yield_stuck_start = + std::max(0.0, intersect_arc_coords.length - yield_stuck_distance_thr); + const double yield_stuck_end = intersect_arc_coords.length; + yield_stuck_detect_lanelets.push_back( + createLaneletFromArcLength(attention_lanelet, yield_stuck_start, yield_stuck_end)); + } + debug_data->yield_stuck_detect_area = getPolygon3dFromLanelets(yield_stuck_detect_lanelets); + for (const auto & object : target_objects.all_attention_objects) { + const auto obj_v_norm = std::hypot( + object.object.kinematics.initial_twist_with_covariance.twist.linear.x, + object.object.kinematics.initial_twist_with_covariance.twist.linear.y); - // check if the footprint is in the stuck detect area - const bool is_in_stuck_area = bg::within(obj_footprint, first_attention_area_poly); - if (is_in_stuck_area && debug_data) { - debug_data->yield_stuck_targets.objects.push_back(object); - return true; + if (obj_v_norm > stuck_vehicle_vel_thr) { + continue; + } + for (const auto & yield_stuck_detect_lanelet : yield_stuck_detect_lanelets) { + const bool is_in_lanelet = lanelet::utils::isInLanelet( + object.object.kinematics.initial_pose_with_covariance.pose, yield_stuck_detect_lanelet); + if (is_in_lanelet) { + debug_data->yield_stuck_targets.objects.push_back(object.object); + return true; + } } } return false; @@ -1527,6 +1633,7 @@ lanelet::ConstLanelet generatePathLanelet( const double yaw = tf2::getYaw(p.orientation); const double x = p.position.x; const double y = p.position.y; + // NOTE: maybe this is opposite const double left_x = x + width / 2 * std::sin(yaw); const double left_y = y - width / 2 * std::cos(yaw); const double right_x = x - width / 2 * std::sin(yaw); diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index 8d0e673fc931e..33e511d911b82 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -131,9 +131,10 @@ bool checkStuckVehicleInIntersection( DebugData * debug_data); bool checkYieldStuckVehicleInIntersection( - const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_ptr, - const lanelet::BasicPolygon2d & ego_poly, const lanelet::CompoundPolygon3d & first_attention_area, - const double stuck_vehicle_vel_thr, const double yield_stuck_distance_thr, + const util::TargetObjects & target_objects, + const util::InterpolatedPathInfo & interpolated_path_info, + const lanelet::ConstLanelets & attention_lanelets, const std::string & turn_direction, + const double width, const double stuck_vehicle_vel_thr, const double yield_stuck_distance_thr, DebugData * debug_data); Polygon2d generateStuckVehicleDetectAreaPolygon( diff --git a/planning/behavior_velocity_intersection_module/src/util_type.hpp b/planning/behavior_velocity_intersection_module/src/util_type.hpp index 3c7ba3041b0bd..d05031bf19436 100644 --- a/planning/behavior_velocity_intersection_module/src/util_type.hpp +++ b/planning/behavior_velocity_intersection_module/src/util_type.hpp @@ -45,6 +45,7 @@ struct DebugData std::optional ego_lane{std::nullopt}; std::optional> adjacent_area{std::nullopt}; std::optional stuck_vehicle_detect_area{std::nullopt}; + std::optional> yield_stuck_detect_area{std::nullopt}; std::optional candidate_collision_ego_lane_polygon{std::nullopt}; std::vector candidate_collision_object_polygons; autoware_auto_perception_msgs::msg::PredictedObjects conflicting_targets; From f40425bb3713ed2c64c17063dc3aec8cfd17620b Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 19 Dec 2023 05:20:01 +0900 Subject: [PATCH 79/87] refactor(lane_change): standardizing lane change logger name (#5899) Signed-off-by: Zulfaqar Azmi --- .../config/logger_config.yaml | 8 ++++++-- .../utils/base_class.hpp | 2 +- .../utils/utils.hpp | 13 +++++++++++++ .../src/interface.cpp | 7 +++---- .../behavior_path_lane_change_module/src/scene.cpp | 7 +------ .../src/utils/utils.cpp | 5 +++++ .../interface/scene_module_interface.hpp | 4 ++-- 7 files changed, 31 insertions(+), 15 deletions(-) diff --git a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml index 11dd050658aeb..17955fc5d0b9b 100644 --- a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml +++ b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml @@ -38,9 +38,13 @@ Planning: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance - behavior_path_planner_lane_change: + behavior_path_avoidance_by_lane_change: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner - logger_name: lane_change + logger_name: lane_change.AVOIDANCE_BY_LANE_CHANGE + + behavior_path_lane_change: + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + logger_name: lane_change.NORMAL behavior_velocity_planner: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp index 4bfd461a0815f..aa3ee0dc4c98b 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp @@ -264,7 +264,7 @@ class LaneChangeBase mutable double object_debug_lifetime_{0.0}; mutable StopWatch stop_watch_; - rclcpp::Logger logger_ = rclcpp::get_logger("lane_change"); + rclcpp::Logger logger_ = utils::lane_change::getLogger(getModuleTypeStr()); mutable rclcpp::Clock clock_{RCL_ROS_TIME}; }; } // namespace behavior_path_planner 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 de4db37571122..67506326d92aa 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 @@ -20,6 +20,7 @@ #include "behavior_path_planner_common/parameters.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/utils.hpp" +#include "rclcpp/logger.hpp" #include @@ -207,5 +208,17 @@ lanelet::ConstLanelets generateExpandedLanelets( const lanelet::ConstLanelets & lanes, const Direction direction, const double left_offset, const double right_offset); +/** + * @brief Retrieves a logger instance for a specific lane change type. + * + * This function provides a specialized logger for different types of lane change. + * + * @param type A string representing the type of lane change operation. This could be + * a specific maneuver or condition related to lane changing, such as + * 'avoidance_by_lane_change', 'normal', 'external_request'. + * + * @return rclcpp::Logger The logger instance configured for the specified lane change type. + */ +rclcpp::Logger getLogger(const std::string & type); } // namespace behavior_path_planner::utils::lane_change #endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ diff --git a/planning/behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp index 4a8eb34b088af..00793532023b9 100644 --- a/planning/behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -44,6 +44,7 @@ LaneChangeInterface::LaneChangeInterface( prev_approved_path_{std::make_unique()} { steering_factor_interface_ptr_ = std::make_unique(&node, name); + logger_ = utils::lane_change::getLogger(module_type_->getModuleTypeStr()); } void LaneChangeInterface::processOnEntry() @@ -78,8 +79,7 @@ bool LaneChangeInterface::isExecutionReady() const ModuleStatus LaneChangeInterface::updateState() { auto log_warn_throttled = [&](const std::string & message) -> void { - RCLCPP_WARN_STREAM_THROTTLE( - getLogger().get_child(module_type_->getModuleTypeStr()), *clock_, 5000, message); + RCLCPP_WARN_STREAM_THROTTLE(getLogger(), *clock_, 5000, message); }; if (module_type_->specialExpiredCheck()) { @@ -111,8 +111,7 @@ ModuleStatus LaneChangeInterface::updateState() if (module_type_->isEgoOnPreparePhase() && module_type_->isStoppedAtRedTrafficLight()) { RCLCPP_WARN_STREAM_THROTTLE( - getLogger().get_child(module_type_->getModuleTypeStr()), *clock_, 5000, - "Ego stopped at traffic light. Canceling lane change"); + getLogger(), *clock_, 5000, "Ego stopped at traffic light. Canceling lane change"); module_type_->toCancelState(); return isWaitingApproval() ? ModuleStatus::RUNNING : ModuleStatus::SUCCESS; } diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index 3adef17fc3b4d..f0972d66416c8 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -997,12 +997,7 @@ PathWithLaneId NormalLaneChange::getTargetSegment( std::min(dist_from_start, dist_from_end), s_start + std::numeric_limits::epsilon()); }); - RCLCPP_DEBUG( - rclcpp::get_logger("behavior_path_planner") - .get_child("lane_change") - .get_child("util") - .get_child("getTargetSegment"), - "start: %f, end: %f", s_start, s_end); + RCLCPP_DEBUG(logger_, "in %s start: %f, end: %f", __func__, s_start, s_end); PathWithLaneId target_segment = route_handler.getCenterLinePath(target_lanes, s_start, s_end); for (auto & point : target_segment.points) { 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 b5a4fd15b4c6b..9ff4ed95e09dd 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -1159,4 +1159,9 @@ lanelet::ConstLanelets generateExpandedLanelets( const auto right_extend_offset = (direction == Direction::RIGHT) ? -right_offset : 0.0; return lanelet::utils::getExpandedLanelets(lanes, left_extend_offset, right_extend_offset); } + +rclcpp::Logger getLogger(const std::string & type) +{ + return rclcpp::get_logger("lane_change").get_child(type); +} } // namespace behavior_path_planner::utils::lane_change diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp index 0ad30520815e8..62dc690e6ba28 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -362,8 +362,6 @@ class SceneModuleInterface std::string name_; - rclcpp::Logger logger_; - BehaviorModuleOutput previous_module_output_; StopReason stop_reason_; @@ -581,6 +579,8 @@ class SceneModuleInterface return std::abs(planner_data_->self_odometry->twist.twist.linear.x); } + rclcpp::Logger logger_; + rclcpp::Clock::SharedPtr clock_; std::shared_ptr planner_data_; From 320bc2f697968f7f7dd3f8af3a571a2eb896cd5b Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 19 Dec 2023 06:16:57 +0900 Subject: [PATCH 80/87] chore(map_loader): visualize crosswalk id (#5880) Signed-off-by: Takamasa Horibe --- .../lanelet2_map_loader/lanelet2_map_visualization_node.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp index 082dc95d6500a..e14defcb47f26 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp @@ -224,6 +224,9 @@ void Lanelet2MapVisualizationNode::onMapBin( insertMarkerArray( &map_marker_array, lanelet::visualization::generateLaneletIdMarker(road_lanelets, cl_lanelet_id)); + insertMarkerArray( + &map_marker_array, lanelet::visualization::generateLaneletIdMarker( + crosswalk_lanelets, cl_lanelet_id, "crosswalk_lanelet_id")); insertMarkerArray( &map_marker_array, lanelet::visualization::laneletsAsTriangleMarkerArray( "shoulder_road_lanelets", shoulder_lanelets, cl_shoulder)); From 1837f6bb863501395c7d2b1d24fb8ef9000d3bc5 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 19 Dec 2023 10:13:08 +0900 Subject: [PATCH 81/87] feat(dynamic_avoidance): always launch the module when requested (#5900) Signed-off-by: Takayuki Murooka --- .../scene_module/dynamic_avoidance/manager.hpp | 2 ++ .../src/scene_module/dynamic_avoidance/manager.cpp | 5 +++++ 2 files changed, 7 insertions(+) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp index c02ee88d3fa3e..9e08f309a78b3 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/manager.hpp @@ -44,6 +44,8 @@ class DynamicAvoidanceModuleManager : public SceneModuleManagerInterface void updateModuleParams(const std::vector & parameters) override; + bool isAlwaysExecutableModule() const override; + private: std::shared_ptr parameters_; }; diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index 2824a6221591a..ca0bc070d0fdb 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -255,6 +255,11 @@ void DynamicAvoidanceModuleManager::updateModuleParams( if (!observer.expired()) observer.lock()->updateModuleParams(p); }); } + +bool DynamicAvoidanceModuleManager::isAlwaysExecutableModule() const +{ + return true; +} } // namespace behavior_path_planner #include From 7faeb911b492f3922739a840abe80cc4e68196fe Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 19 Dec 2023 14:04:16 +0900 Subject: [PATCH 82/87] docs(raw_vehicle_cmd_converter): update readme (#5822) Signed-off-by: Takamasa Horibe --- vehicle/raw_vehicle_cmd_converter/README.md | 24 +++++++++++++++++- .../figure/accel-brake-map-table.png | Bin 0 -> 409971 bytes 2 files changed, 23 insertions(+), 1 deletion(-) create mode 100644 vehicle/raw_vehicle_cmd_converter/figure/accel-brake-map-table.png diff --git a/vehicle/raw_vehicle_cmd_converter/README.md b/vehicle/raw_vehicle_cmd_converter/README.md index c033f4348b927..5767c4fbf672b 100644 --- a/vehicle/raw_vehicle_cmd_converter/README.md +++ b/vehicle/raw_vehicle_cmd_converter/README.md @@ -1,6 +1,28 @@ # raw_vehicle_cmd_converter -`raw_vehicle_command_converter` is a node that converts desired acceleration and velocity to mechanical input by using feed forward + feed back control (optional). +## Overview + +The raw_vehicle_command_converter is a crucial node in vehicle automation systems, responsible for translating desired steering and acceleration inputs into specific vehicle control commands. This process is achieved through a combination of a lookup table and an optional feedback control system. + +### Lookup Table + +The core of the converter's functionality lies in its use of a CSV-formatted lookup table. This table encapsulates the relationship between the throttle/brake pedal (depending on your vehicle control interface) and the corresponding vehicle acceleration across various speeds. The converter utilizes this data to accurately translate target accelerations into appropriate throttle/brake values. + +![accel-brake-map-table](./figure/accel-brake-map-table.png) + +### Creation of Reference Data + +Reference data for the lookup table is generated through the following steps: + +1. **Data Collection**: On a flat road, a constant value command (e.g., throttle/brake pedal) is applied to accelerate or decelerate the vehicle. +2. **Recording Data**: During this phase, both the IMU acceleration and vehicle velocity data are recorded. +3. **CSV File Generation**: A CSV file is created, detailing the relationship between command values, vehicle speed, and resulting acceleration. + +Once the acceleration map is crafted, it should be loaded when the RawVehicleCmdConverter node is launched, with the file path defined in the launch file. + +### Auto-Calibration Tool + +For ease of calibration and adjustments to the lookup table, an auto-calibration tool is available. More information and instructions for this tool can be found [here](https://github.com/autowarefoundation/autoware.universe/blob/main/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/README.md). ## Input topics diff --git a/vehicle/raw_vehicle_cmd_converter/figure/accel-brake-map-table.png b/vehicle/raw_vehicle_cmd_converter/figure/accel-brake-map-table.png new file mode 100644 index 0000000000000000000000000000000000000000..c1e756ed9a363232ff25f4fa429a919c6ec340e6 GIT binary patch literal 409971 zcmeFXRX|)#ur7)uNN{%v5G1%egy6w~LvVK;Tm}p7?hqtcaCZqZ5G+V=8wPiGxs&YV z-}l_-`*`YQWcBK<{_5-M>Z%U^s3?v0iue@_3=EpAjD!jd3<5k13_J`H0`wnbFu^$V z;|1WotQrzje2`4TpudS+B(+>r9n4+ajhxM3EbJZZ%$NZt&Sqxz080m#WB4u+Xd_N5 zH7yr$XEP%gD+hZ@H7h$a=$|k!9Bdq%n=SS199vmoYa*#2DE=-2aemV;W&$zhtg8xu_Cz z*MxO#a=yQYWtV>9qp0_)-gspZYyyDJxo3ofLsh7TWgm%$+o5AH<*vu%X{GRs&+BtJ zfUyeRyXNBf3Ot=s8x(f0tv6W)33mjYiQ*2vFZWj~U+?fqKlUYa1jw;wibb4G?Bii! z#orXN{SVh^(7BFvhecN((Q?&TgS_~mqDo>S8W8KeERMpqkTD_XOim^`QX&9`}2K2Pr|i1 zQr+iVpVLM}%i36U_=m)n z<(6U18hoRvFK3lQa`KVK&*$KWlUHeFndx%?3tYb@V50sa_Qaf)U$tthsw+{_VY-K0 zs2jx(7*EzfW>KyS?K9lq75ra>sZmVvPi`rMM*0mfz~iLi+D>Q6qQ^^J$%x1IbSw4v zCmqknZbiwaeI+U~!?}Hz1`n%CY`qwS&Avm$54;v~^~LFB*?80LlJqSuUwUw&E#L>=k{(q z%a8G~P0c2REW805E|Zf!>=p1|+FFti7u}}JiUGft<_lknd{QV{l(ydc=`De%deW+A zkuMMJSr&%+vPA*<<@a}7jkw0U4_C97pwdu z8Tzde6knX`zz!~M?ulO%11F|zMrZVjJobwL@vBs9GJoHq{t;b=Wm4RzOhP( zUy29>@sRty@(k`brO8g8IG&K9P(ZZaMb9+dz>mw#jZnX7@F3$A{nO*US zeY|9LdD+|C!LWfJ^VR1{lF7gcFIBHTjse2Kr%%vIMpkGKLeTd(vdRGh(T)#Gidv{& z$PPu38;sqeq&hviY66DZOE)ZTFlPCF>W{NN?QsB4>Fx1pI(@1ebOsH;+?@%?DQrIPD90 zb@n(_?Vgy6^2RfgDD)JnjyFZ$zM11ZpZ5B#2P9W1FK!#D$ua;~a}*-R3#;nVecO0X z7w`4A`&0GTnnDjY}Fa|yo~ZYcu9Qaa`GVVmw$Thu4+kYvD6B$UiF;rP7>t7Ic72u zT*vT(e2?D!z>EBO=(_pXz3S&NE4Y<)X{=(_U|>2yD50GeUby05zBXj_`3{()_xx7$ z85URZhTEN)MWjODursI}cth~8(Up@|v~09jTXkMhrQbU(Ych!HQT=|Ii*#;CuIu@w zD9{q#M&k+9;RAl~H88n$2&=B&0fi?8m4{rT#c9caaj@$_g>QnLTX_27NyRfTtRH5bWA zLUN+~o*84>Er?g!peflxzho^%^6QPNFolocw*ZT$`W$=2NluXSP_o?6c}^*^Gb-v* zvn~Rr>3FMXHS6AXKI=0zubx0^AQMLXlQ~aUb%Mdlvv=c+`q`r2Gdp^cLVBMk^3h9Lt zTERwz{<^M>E{zT`2SX}e;1;@lhxuz9=}pX&jL+g7T))(6uS%tF4k--4x2umy$OO70 z<6T_$sJ;Zy9W5d3U!0v4mpQRLZZXz3(XRJP?7Rr%(Q;OGW83l!U*(eZ*#5AQ>7q?* zGCXE7=DAsjzUtKA@ZbQv`1xs}LY}4b4#j7C(XaQQX186`)eqTBwTO*&^h@1sXnX6u zEAaH&cFScxE5&kvk1oFJB2V?+I4hvqB(5+#7Yq`8Mr6rNa-HUShcjH{v{LUw+~gDZ zJU=s5q^WVXerG1%ZvOow+9>Jr*_YLC$pe!UfIaJbWPfzKzlmGaDXKRyGQZ6(Fq&7n zbzi=EO&crJ8AC##XsR|4o{KIsMqkKAOv`OmQoOjSK+D?XpP#=ZzDf%Dv0Y>N^nypE zGn+TpU^K=-x4*v>6jK=5Q`R8VvP(&baI4A+iI5D=nooB^@6d_c%XZa$9Q6bHJ&#t% z4+_-#sxpv}eKFt0FQf2_y!ugmtDr|Ds&y%Tq^t5B{1v5W)UdWIM7_!u(rt+GYjHIX zxMn?>5UVBp-KpeLQ%r^kA+H|?1cXP?DdwIfvf_J*wh+kXbYv`YAIu8)H6kCQTa?%C zBfv?wiG$weVJ1!YSivme50Rk%eL#Y-xM`LB6Nl0Cc+`$V%HD9w$Xyv?sGS_BE{2hB zyXNWnt)HSX^Bvh1jpdBj*B*csFM#?UYglF8RHiW*eZOXX&(bIj!-g||c&6%)eT^)N z-;4NoyVP55*QliTWqByZj-+(%*XPX_T6edCEeFuHH#jmB4QXx1pFWdh#sqnLdQZ^` zgzyd^Yo7e`Ca4QUFZoTyps7s=8;*O3vTy?W;9j8508Wmv20OsEp4rS421MytnW0VmIN8MHN6z zIFqB#$%ri;P8rgK>=Kbr7kWTsD;4*|*GZSmfWsAuW#P)nEScg)vh0 zt16M`)}Sj!zKbg=90E&Ktp9lA{@lkw$3$)?_SM^=D$l!J^@kfj<_SwtsEgxg_;KIz9EO+N%z7+EF>trQ5w1tLt4FcJRG&r=PWTn++$y zF?*K7B5qC6Fo`Q$!b0~ypUpG}!f65F)eckSUd;ZK_uuyY8R#mQr)QOH0GvVSgjW4Y zxE@M(UhYp?5ea$+goK5~--1_ikT&ji__U<6Hw``7X|@Rxv2HxtQc#Met;2qgsDR%!ktJiy{ z$phG5`ihG7)MTZ9Ps4hIwvN8>QRJAzJleAhXMXqai{J)~a>lj8hUl{u#LCZJM-Qd= z6+BfuQcn*h%u_vAf*u_OtAodstb(i9H%WR@THFX25ibGnP@sLr3pk)+`>XDGqoO3o zq5NB+vke3R8^+s9zpBkCQ60qu*tzBQ^DV(?E|+(P90u+Cug2Uoz-}$(b86 z$IZa~a@w_qumJN^l{oV5>4M+6A7||Uf(h|?bzVm+FtyOHrQR5Ys@h_RvH5m$w>6|i z-Nw?Ll!HUAc_ZSDDftA${v1yuJfXcaXvB10ogm&lLwLUb97Sp0_3C7rJ!bQ}qvGjG zNI1KY@v@VA7I>S)HiodpzQverGb*-LGP3#00ej=D=Gj>8(e~)E?!Y7!2Dq`q)~hXW zs}d;~#bL8Zn?kpnKW9$Qq0UR3nZ=Lz%_e|;^wDs~usJc!ZOGzgBFWQMzbi-K*uKEo zo%_D5Y|ed+(xK~&j;G^_3nMyvhJvF-Ver)Z0gYX?I-HL803P*KamCssigWCpyZHwmZIPfLG2UPZ!O86Ni3tl6 zAK<*TS(yAmRy?~K+(V9FyI)x4PStUNq2(ViyWhW0)XFR`OO#PE(8!E{*oKt5Av}if z2PUo5=EzJYDYJ9{MkkLSY_1E^sdfPbbsE(t95znp$MqEQ=sH8Y-P`Y9kr4OZa89NJ z!7oj-PK?lbiC&uNx~US$Rgn}n)Z_%+U)NQcizefdcz}ZmJl$s(AC5Yu5ZViFN8MAw zk;he1(3y@=jWYe&mZ+RRsc4_IWD-&MU)}k(cUYk;r}S5HS1C`-p@oD7&#n&kO&55Z zEWd=L$8EyWy?1aBj<%cN{FKa#Ny#gi=nw1WfOAPkcRUcwb5z{I`s!wAWRRBH*YYv2 zd>zhN0lpmR@o?1Tg1k-U4Ad=e0>0E_rxry69hogpjeivUIo4?BP~&TW$biGLy%i}Z z^3*z3LYZmc8<~PsXsT#FmNilAYGUsJw-KE_nDr(VaK7C+vikJ={M}dd0eyHYDx^~& z$LGY|7OmefH#{s%X6e5JOa_Pf%6Hegy09yrTJL*&>kJ!@%?9_~12mID)~%v_I>5nX zcZlCBg7GnUriDz5TEL<{72R!=3|jZgMkU4!3S0O{`iydDKL=k+$i zWV>d=Hy8al-A)JSvOZ#yt(1oZO<9QNR_@Xt>(x+1*>)UdlEX5zc{Z z!%-(by651NFiCRA?xWl8k$tg^8U{^(e?_*>^o?^ z!+umdUKzXkHC|)CC~`;5V>Wzjto&4?4D$}37kK-s7Imj|wRiZNX5Ida>_)d|ec+`# zFMFvi5AVvYoV8+s!>r>ro7s<-Nzrof7IAdP&&>A)Ad1&VT5UH&;|Av40TqV=j<+OmM2RHAq4<<&NZ#~hL0 z-QDf%S{IkvGj=^~%{Kc15Lq1X>sany4729+-B11UZrRdVHFI)$r7;fF5V=tWKAn71 z`^7!6G9l(|!>O(_d)}?oIj(x#2v%T);NLSkM%x|M zH*rmI-t^=h@1od4&d=+@E*eg^_Cn`A;u!z<{*{Sb6v0pT+Fi$XwK^F7F^KSpovGDy z%gG?wYeh(kUFJUE75Pnn*Xi6hylLKs$@ygk2M3I0z3h6fBa3AmzxDaq#-C;_gl z0i3RptWd8{hrcTR_D{qrA)5eCoj?)EPuD`;G>i%4UFUNkDYB@A(JQX4UZ{ zEMnkusKrXzI@s@#mL&IHIC3jn8kmx5C{2y$(9zSjXia!w%6T8L*nFL1qeRF;IxNq+ zStQu?!PS?f%hw#o;bBXT$?sStg(XAMDJ8e_3SQ0DC;L*zrp9-EMB9te@4m^PPzbVv zaT48??APLsvU&qrJz44GemI|XKkJK1m(SLXnpl+SFXEloo|RL%@~G@QB=PaQMOA4p zW|=%xGCoM!-9T9RnrB7*>@~jJE>fISZ^#Qcy2CSQtKCUswdF9l`;jcvysIpbudEy3 z#H7y=s~qekBKfgCCHnZlh>fsc^iG8(V@vdCzui;QdAvzP9Ma)uxNXw~X4IKw16(l` zDUwTm>XxqVN`x0|tZp$DRPeQzQfkX`cz!G%iroM58_Y4De^D#NdrIa+PfaGH>AE(4 zK0|mbUEna9{6%&<9gp7t+QU>=G3O>&^z7`8S#7o*Wb)h*W7yY&gA^B^4BBWJPOGyd zYVtk8-%=QS_~^Qsq(9cwd2C_3TTrfl&y(!E0;xgNrz4D6KckC}Pam)M)a2OC-(0$C zQL1ac;5&989BJ7-zUg|RBL8$N$y)tG@ZgIrZh`nb>DTUvsz zjslP4MXb?8a-yT#4ol^gqtK);Y;iINpi>Yt$68Y#w zASEwzbVd!4x!e%B2j5WdcF{?JV7kTOwIuO_HZ?AN{qY^0_tj^Vn;%Wj$&5OP zL+Q>>P9i-t7H8N`d&d@zo6&-E>gsZG(ilBq!NUZU!kn=aZ@$Xsip19^E+Kotr8Bjk z`YH4H@h1zqt1kZhpyY?t4m-(-!jP^e<+-ah`5>(%3y~W&@7EKhbkJtC>gOcNbni>V z4#^CZMY+j5ehl+uY@C|r_6H-!fejI zF2&88r0AIp-t{GJP}34!*$GR9<>>iXXlAO+SN3_bHXPUV z>srKd)^AdZAcR2p=yaR@=YT3fgWo88rp@yBo%*x0#o4Gg#hOm8aBg8N*Bf9OqJ2(x zHsd}K;EDTTCqVRUNSng`6ykwn2h8qjy<~haS9r5kSXI+-CPJJ30qr;8)j#RU{2oL? zLMln-Q1xM1^eNqKc>MD@%jO8@6;nMqc zZ%f3)5^9?t>Q*89O^QMg z-pZhCG+QsTHwTw6vk^K~-#6AZm7*+8$h?D|gZ^c* zsn|F8jELPTAOX1#X&vxua*8HuyS6OtXNpgo-c2fN!c%}H!TO`c5v8NskrThRmOVt) zQ`_5qiyMG(cTK79W9pLUB0Sf;G%H3)rXRH9iOaub)4nL9J9-v_5rSvh4}dvJ=HfIf z0w$x~bs|%bF;h%K4%b_Pn@`Huh) zjt58w^Th!6QlW9rKapvltPl7N(qH-iqgXp=(A{WfyBOn2^rzEe$-njA!BA6ed_ngk z)6op>i;IiCR?`1DM>>OA{}x+3jG+zO4%TA*9;nI4$S$t00sVNIYv;GddKtep9z@># zSC_%a%g+x)r0|K$$RKWQZJnz&f`>{Ci`;M8Y!qIY{ttMARtvReDA&vG6cd)X{>lYX zPWOjRiShARkRQJrN+|v-P7gA?2ojsAG8nJ&d$b`1^=vw`JFQFDw`}5nkdrgf%lR`r z!@sf{fB4v#qQ2)QUXJ$>KeY9s8>j1@T4mRh*ULYpZ*1Ow?uRrK!dKtWaJmG5Mpw%M zfjyK(R?a;y2^^PQXW7k1(zH_lMAgm<|Gm)bM4FM2;jvd*>;cu4h>);*)7j~EGquj= z*4Y^VFwx8Zqf2Q1-$G<8H5=T&y8s)6(b3TlPuE=*pct~x?_c|fP%vtg8_w676&4ou zwF>C~cI!=n5f{tfDX%V)d3r$?;OcK$mgR#Z`18WEzawL7%Nz!3rIw@C{WN}ndDJ(Y-^%a<{z5v)Z)Irc zzn$xsGpp}?c!C34XFj^VmFZx<)a+EltoTO{)PKR?c9smy_cHZwT21z3zP`R`MMHrv zQJSw7Y#3NrVq87{Fxuk3Sr((BqB=f5UaKlAi_znLhZ<_=O{(K4_bha_IQwV6yOtPx z^>_bv9@{xQ-0ZwRGMTN^WtqkO_vB0io^MnzF`>o~ zzQAmAKOS%*O-M}CZuem4U3S3lHP{?hgiw3KoLv9lLP7C&rU{OuAaFl{f$8Pm zulo9Wn2#D718BTU-AN3pxG(+~l3)5Ssc3MAYk#ZE+HrvmH7Q|;n6@@i?%i~88k0S7cZYEPZC5(*na*%%4!{Y%de_Muo$3T8A zFOT9V3H2;A*dPbLZ`Nh`F+AL|U)eVJ<41&R_#chgzy9UZdIofv*4LjL)Qz9r?N{NT zho0X0jAU>}j{7~G7Zw+TS|xsSDn9KWPn;?$D`Sdtff>;xyx7rFvWkl4LkVw|T&5Im z9-p*Q>3(<5LG?F15Z|n>r#Jc|nQ^|+j-=5pF+F`~@~fP7qiuTNAI}$0{a?d+6A(JN z=LVLwwKdG(=;-F&w<>e+_h9JK1U2&gQ2|TpFLZs`(6MWsH$M;)6T=J+4?_}jA84R7 z7ZJ&29r*Q!O;P`fIyClkjidWjU1Lxsc6WAQC^Ep)N7qXr!u*mhnuR6%`W-@nP_|6>wXRaI5&tbt#4agJ9+P7b*)3qc~S z!g`G0(U~ zm0OP29>Ywzwm1#;YfL0ZXo8~Fxc}Avcv&inz`qI;#qaI!YqvPR$>enysAYl+fQckv z-75Q5NkvB|9r-fyH|Kni{%O$1?{PvID{@B<-D|pQnV?P*$|rtJJy$#{E2|n7rQfTT z=IEbEu*_CFeT6Q5iXY6^A%dJ>ns2ut{Crj4(&TG~x;!tVB< zC7i(Y8&u~I=rVS7<&G7;LPRI!gYh5Vh5&N!NeT4%c>m}1!Im+|>H4XMvEG1zyb?kd zEu(df(=r0-l+jbd%d{e*{RG8KGi}16@KPA+*Yh!A2AE!mXystr@ptzEGo&C`@q4N( zQc}d1&D8!u@CyXgfk9(<)WKtTpjx7Xa`0tC)#SyQ%Zw?y$t=)+# zf~g)ZQMBZTQ+@evyr(;a3QR@2aa&EYr*tz;pFV0y0D-{r;hRVX)EhQb#}?h@W&066 zFQFFmXAzFN+QG4*XjcYj{CYQ?2cQClpv`OShESG}b^7uTYK?YAgy!$FPu3HI%;qyx zj9)mCB7$nz6%He{0Jh#cw8KAJsAg;z2iQ=v8DSFXiPYi+saG(BNd3~M#cpT|?{~5#1u3^>zMDRx#jhGR+M1)B)hGPI#wt9snZO z`U-qAwCY81Vy~?7Pn#cgA;V_hKTp)KY(_b?LEIxKp$R4IYo^85xHYgcr;8hAEiy{b zI{mNy7zm$>tIHb33nZF1{jFJmPc+zh1s%}`S-MO1*=NR9j*f9XPe6{kI&Natfjcj6 zn4qNTX{}Ue#X9E9oE-ay02pAG=*(tc6b=#P(glxf&@q@6DFj7n!K2nWHO_Pk+^1ap zj*YOet17kpfV2UC-0ei_<=qP1Y-!#UTjtWjEY|KE?)Fe1tqF!ME=zFmv30Ml!D!F( z*RV*AK_BiO?hfpqVT!`H9r@b^0DuE0FFofnwVQl$%vL85CW7d!dQUL3kHtc0j4>c13#K!KK) zjQ6})T+_1?KYtEop|~g{B7Fzv*%Vwv(L_W@8D*Thl2J;3TQUg8BmML(3Vg|IX8KdT zOa{&=9bHx==mIzPyFXzqQz8vTAwtMia9<3LE7r+eVR5tUL}yrOCru(vmAF@gPPQp~ z$^kDM8gv@?XLB_7uepa@6^|mHRur!~&vDV(c-QCfVNB@8&4*mw*RDKFbe9dxtH){9 z8f2ADOS0u)Cg`E>tWj9A;vw{jRxy64#ZXBc0n{!lNC?9w7J}V0*A3`RF;=BBp(Fn) z#@a?_g{vSn?3++8qoG7xjKD^gu6Bf6Lai$=Y{V1D-x!P+Z9G4Azm446%_T3Nijr!D zZ4m^I;~!+QsMQ#3$3GVXPe@o4VAbl_A}@cKR5##cYs>gyx^|U9g1vn%+X|fwhnV5~ zlz&=E@(`jsM9i{ePhg*FuOWioi1&s#`m9IK$go-0V~M3ffjS&wxQL%(XR?SscG5y4 zG}oKrs-)8Kr~tD>&YC!;Gtxfn5Z+b{JBAlyXQYjf&(dx`J27h(BkZF~+`L3SO*)X< zJG&l2600-of!tdY8l$t=rB9AHTv#IuleJTE)V48lB;g9CdWV35|1dLARs4PEg-InRNgv zDq9B)K{5b%OL#Wv+gd{mOG@{lx+`)fM8KLPWB1^Q4!0&;DoA4S8gs7_kuol8API%V zWG`zN_eGQzzFxFu4i;3*HH@X457JT%wIuKwNl?~ z(*(mN7}^Fdk4|eIe#vjm5i3spF@!TXBu~vRmkm!H51D&$FKA_FmA6VyDaxAYk4VZW z?=CHT?|p|Pi6)dNop{9g>(sN6pGTuGbqn5mUR7OArz?n+Ke*l$gBHIL!bTW{8NEcn#?KW4%FYtAPLRG|GXZ1n9Tyc8M2bYvlVwI{iW~Wp_?dHv#9s9cu3;WI zK-O}W)hKLDeiFUn%nta3K+$`g{t;mec`%j?D^ zao=-2_i0{2+=MZ>zrV0FcZ~^9eTei}!L6o#l+T_fr7z21X5uV!)xusACPDT2G_h!G zyl$k2N4HtkIgQIzAeab<%J|;0I<+x`xa^yC=?Y{`R>9(f5eNBKQ;Xc;Al{C&+ETNP zuN|VslWfb)!uGB{zEP-3Z;9q1>FhReA|VbyH2A5_o_(iMy9j>7>fMrx!m`!?eFxY# zI3TdgVR2KdH9Zm=>SXO%x`+e+8?$Z5fi zsm03cla7Q4DU^2~%LCAf_cE*wlq_cQZ{-h&Hj?gm*tlOqR?c@U3UJUjF0o&QEsQXY<* z7s76-NY+Qz#jA$u<9CcW=WxvmuKqc8Ax4I+?KcmwaI#NehJYyW^X}ra77;B=Z0tJ~ z7>ZCSN*jYH+!&mf#i2p!4K6xFxY6X17S%D2g0pNtm*L(?X~1q9IO7z2_yKXNSpy`( zqt7))+v$YH@+>;77_35zZex6)S5s47{wXoE)&jyCsq%R)>-5mj_l!W9kPVJ620jL$ zK``e=inyqF5gNzTsrXlhL{Tx{ z_c^2>WM|+;G`4AK~N61wXyY)Ju^Aw!ZIqn)5AgSA+RJ_H9mGzOaB3n#Gv8c-kQQ>}; zeQq`w!dGa%QES;xFvLO_ZPkixyNK~Pq*!t&Knf=jbm4wnU<_cDl@;$cXPaLmPQ#%(BsX4_T0Bj&cTn0$oF%Z6SPH z;AchL(1nb?CFuV3#qD#?kyn`;KcD$4Psj&`%#RWpWdzhcF~6?;M9J2VbHHk(S=9IT zq}`3ObE?DaS>T=*;Z!S&D#5VSJ=#YlqCT*h?+{lI`S~X7KN0U+?uV8qu;UhaINgId ziX1tQxp-7o=LY697)?87fhgR&E2v_P6*cXeAl!TF#hA_gg+4rVhUw7;juK32OWEo&92(?_vOs`mt z9b|3{3-F=!#N)wZ8GT|6Ca)y=(3MTF@h8-+O5Y3{~E=6bel9V~T=akY;!xfO=xkCs$VoJ3F$)VY|TnnMq2{$|6JzPgoRD zWX2e|&yMS*z5?8!#_Awn)R6qo;@*~rOA%yf@Ns%e`b*OCO50E$>VQzK8zIkgLJ6EgB^>P6+aI@UOmsfqeX`o& zl^Gg0_K^}83dm!4i(}Uo`u-c(ZLpSo#G}=MFB$A;azj22&1ZsM_qc(>-+am~{0_s9 z6C-~(jv&~Ri|TlQ1g`Yjv$nR}zvLXiD?I8JlNUrK=Z(+7FT>#B=%mS=u(Dr5c0t=9 z1zhoQ5ew@t&@Q@#u#9wA;o>Tq+$9-LKC)z4hFuN3z0&wqS3KFbkHKcU=^0;qKn6fI_WPV(;Xk98;+rI z#_fERfpsIx49eb%xTJ*7bU9LkXtNoPN(gg2@iIw+@8C83a1hXocJm#VaJN|RxkOSG zddHgPTz-!C&DW)I31n_~h)j_7#4NfUsfAQAF3T3;%NswnI~Cpvhvqgm-0znxb!LW8 zif6~hBvL|q4HX38+z-&$fI3e;5Yk9a?amrDpr#g2vw-2I3^@ck;%9M32E`yj-fN$_BgGHdt3n}_TKjcF>ouCvx&Qzkr zhXjlQ8~>*jkw6WEq41=f{tmG6M91<)Fls{WByw|9GrH}1Xuxoy#3wHV?OkaWN?XgE zyV!K2)>8zPp^=e3l+Z3;&OE8u{;Gf{eK%WRs-Yh>!rIvleGXfYHi4d;iZ!iA8$yQ$Q4<+Qfa(#9zEZ}a?e<%Hw!MVZvrz$MLeq?e&5?H>p(eW@}o(%ZKwOI<~o zx-cWKkg;Dfq-d_Ih;2XB#}+c_Gt7SKCG4TwdLoob3bRN{9E}JW0_x>m+3fZ`Jq_BWUu79 zII)HrzWxP5N!9XufUodqw#guJGmZst!NY>hWebpxdgVH~v}4q5V=UQwQO`U1QzVSe z7k56L!9ziBBTEmVXi-UHf^Wd(O7+*z?jyU`cadi@C?0HRk(PZ_5^oEnx8sxdW)=G9 zH?$3m|rw#u5+T1SS=1*`?HhYMAqb^tgCuaE?yNPuq^) zFmOkY9B}z8;5o-QlV(CAx5lnZIJA2=80e`~c9;m{FPQ1uz z)c04dr*{uY8*g@z?>w;4CTD+r(5pZhKQTxzLNRbg&?aJdfo*$7N8|}zi%WoVHoNFc zE|<@zvBcua`T`6?0lnFeG2@bM6Z8>vZ%Zu8iaTo(YroUzM(9YtfQN_P)&rqVDQgZb zDnO5lv_-o;`{#)%!Wp%v5TeA?K%&%;PW%_D+T)>yb z@fm_S2M@L!Fw3f0WFc1TR3Dn#(j%Haoiyut23G6`@t+ zlBxD(J+?3J2bgBq7I7BUXQdOB-f(?Q$qFI`6}7mr;*sQhtpHM_;Pr1_Ij;nM8yaKG zuWSrh*s^Y<2s4~#<7!=^;TH_1=|Zr8CLc}5KI)L}9Tyt;;Zz8}&QC!r$}P{wrcH{W zTeK+Yi1rp&Lb_3LCe#r~w!9H`Q`4+7DbBs9cXo!e=OS_TsSYILs=u84)qH>QSU;Tk zer9fWBwasn6*4&md-go%Jx<9#^-z6$9WvHZOlKkg0)cZdsQnf@R!BuUMJ7Wivq!!0 z&7yijXUPv1zmM~q&ioT^wDHaGm{mknQR&W_HuQgrOn|5}upD*qU{k)#W<@#SCXpwrn7*ce4MApAE07Y0Ubt^!42D}9O@UVo6H}5Xb1E3L4>~?ytJMK*c9On$ zF%d(jHIRqT8(%Acy-QkF36EVn8a{vG~@J|i#@5R~rIdT4?Y>K`WHcX~AYV@e@ z@DzOR?IcJeVWZ-MjN}nnW_jonG-z~*oGW+|-0M+ZGLq^q(Y%LL>~onm#>P|4v35l` zMgIb>RrCSFwu04|PyjtO6tMch{1&6(H4<%(A;V?^0|)<0bzZC&$n)l)-BT>omKvSR zA=r0)2D+e$DWkp5lp<{x3}o+IQhxrNkqtMd#>8fRTT{z%R6X7w(elF5X$>yL9!*wt;3C3eCA zRb1gz_owrcjAE9n)c%$QC0F#>D<4!mA*#QyC5K|BG$p#<=m0SyQ)BQ@tNBil^3nWc z(VmRots!&ENt(8$*4}A+82!FIv)&quDM7k|`85agtI|Erx86>d7s>;>XyB92^uWn& zjofxM)3(fy+T3}ybbj_7 GZHr2>4Y>()KA)OXFl-ENRWKb9Bb;8odS3O~_8wpO z&d2L_2Qp1?lAr3^JO$jgbxB*L)V>KsZ||Wyq?!5T=7{Nd_nxo)^@khVE@U27 zFb9Sa{dD6>B<&|3*cVwjl<4j!;g2>>Fqp59HG+lD>h>#s6(i!oW=_e;HZ+|W#9l#6 z9_=nqd){Hv2=%Be^%Q%Gly}zOI9CV4;u|2p5c5#rWtPBm!hW>NIL>N!&2yDueCV@<&9$&6e?IGAtaog6|sbk$eo zK`~#?ecx2iELKsDr)6sRQOK7A>*f%(dSFoglSs0>jk=L&H^6m=Xg`~age88RLKf{3Z(YG`We|2Sv9 zN*Pr^Bab2L;{wzccWWH#{`XG0}ZSC=iGvh6qaUe2oGE_Hb|#U*PCQpPi@$~f0J9_&mao7y&WzVPFD?)X3W!zx3x51-sY+Hh2&9( zQ3b49?+NPngBfW%@mBX~j~I4MvGr!>7b0GVr=+|7oN&$d5s3|#^Ygd(NQiD=BwHpYu+T}7pR#SLgMQ=K3HC%j(*Ug0ngW7B8EjYHfr@1XJp{)EO zbgE@`^kzxx(;mtf8)BPp?B+#uSpCar2<_$XVEjcfCDhgN3AXezP$N4`d=Xdw&yzu+?kXap4z6@8Z5yO>t zR9Ok7VTF=+l+g~fHuzQ#De2HcUf#Ksk5RS5mL)pxnDVUt1)+}v|yF&*|}vl$XpVnXD_Wo18{6Asxa1REkEBCc8)3~aa* zEKE$ua>qkw_m}s#gc1+u1TdsTsIJ&BDZ{9w$J-?#HJXl|LEcr9tj_=L0xY-tioZ=Z z1^^QG_N;BP?_U`bBJA&z%pLLs_FzJ1J%dQ5{wqw17rn35riQbzscC*?rKqULyeiYU z2E{UCY~W6Sr781Wx5F(LI$u5)Y*|1rxbW!XOENofhy7$F*sbll71;oZk?;gAEYN>; zpBfjPTDHwyewyo*HXSP?VchU`_51-Y*;+|*{}ggxLN|vYl`IEKDoK~9p2NR;SL{Y9F{E>gQ5y!-@=CtG}B?b8Zm=`gQ*XB3&L|472>wDt3Y^TJ3Ga z@pXiRPf*XILmdZaRM8gJn{d@CU~YlMN;kMR%PQ75Bksf3)7ytOYeuaDwARYR4_|8* z4{siUHph3bzRjJShVi&jn%nuVXLw_q$h4vWTY%%%r2%AcceZ-I0_I!rKj|0ih3=65D?Wi% zgtn5JH@nZ*U2##;u#TQ^Szec#mcpm6YDYUk%=Oj($&JweF(L|#i-MV_TT(3WjE)8p zeE-I$2MNUDlRAS_MLE>iVW0nR$l&1q?Y{qG&@WqcBMKLQ=LLfrG97qIHQk}p$kngl z9e$c24l<_y1f3&A%E9QLoO09U4zuw)W+J+;7)bO98 zd^=D@BP|S#OSE~mLWpwo=}HAkMV1uB)v;b+8TlaeU&OEb}=)>#h^JhSIsRaA#Gu<;;*LBCwBSd)l z%YT4Nsnpm=pMopr(zQQO9qj^>X zV`j)y2^Y57MOM&VWx>QIn=%5)*eH6TiVl%m9sI-K`E^~vGGS{BWkfxxU+`4b(<^d6 z4+5Gr!VqPx{d%SA8p^P++9)R3w%QPqkf&;jDCrqGSTUbwO&?hPki5LNZ(EJv;PP$# z_=-CX3or#N2XIUueR6$@@K0qjFG2Vp#c;7C ziDdEJzm6heor52yUEq7!fKLIGR1wBTk9S%3ttTOJBp<9zjy;37O)Z}(4JwbAYu&_K<+sUyjE zh>MF$LHu4K1uau=;q-yS1y6m7eC*eEFRDeFLf_IZpP@9`*2;Wej-xlGZBa~e2QvQ; z0Omj$zdJQe^rzXjf`lkaNV0@1eg1c?Ysw4isse&+$N4$*xxK_R3;Kqt>4o?Bf_C(? zY(PO23;rWn+=X#(K4OnQ$=(z{>G$W!G7SBZJ^4|4TtJZI!d@W=me1<|VFd#$_61se ziN*fwd^j2OhY4=T4#E=kKUdK3{B3nv6V){hT9*Zw5E}cQ=Ob>YoIdh#&)3kw%}AutWVN= z^9mo_=woh6!(a0ae&e^_;B-qlt}py^Omr>7>dX*>y?qRfPO-QaBbn7OL_02bkg}?J zTG~%=ti6favLH_RNyeUmmQN91nWV3~n+L;_%&lya$Y_XmH=&Xm>YI;p_TpKZE5rDl z2gNaCqUF;>m&O?E@8`kbI18(r#M26<=)@B!qN=`ywvOYRXm6w} zf14lOTtGKWcI@|*Yy_HrfnWcXSGjn!6zSt98VZ?2l!ftrdU^*Kn_eawPm)ngM4O91 zxRmNct+ckE;7ms?ey0taba0JuT}d$Cf0cLNd6(N034B$@Ir;kc`N3QD$Y1D3nV5!7 zCb7!g&@KM<$5$9%OCg3&@ang}$#=iej$h<6MxCBdu+aAoKmN%zdS{X^)Tj196)m0L z;Wxi~hMHo}zUvb$pJL?0Kj$a!-(+AZ5AfXI<|u0A_{Cq~_y7JWT*7DH*E6K?;3xlz zcW(4CyrS;t9Xd--a_+Tn@*n+DJ8pr;-k*t~D{QY#Gt$?^z1~q~mZKyxI>=6fkxCj4 zcX0Cb2@W4BC*Y9woso3qul|tf;VuAVo1Nz4uW;t|@8fd&cH!wJYA(s<;wb&y_vsm$ zVsR}_DraDG`6#Zar={&UCr`E0P#MPk1gGDQq?kH}mScIMm)@Q}2FGStT91>-8%Rzc z;nF%94j<$E`4iNY2JpRLKNxzB==6O)_`AR5`rrzxJwnS{{{_GKdJUB!`@Wk~F9#FD zP)KjBF*Dpvci#w;bF0J>X|k$`&EX*sDW|@%jkaUQIo4W%*CD^)-t~wqT_Lftz|?Rr z_xpyKU05TQ%Ax22vcp3tQb}#&5ssfc&e7%yympDts$wRFmLsvb#Kb@ky#u36FRZZ{ zPobDHPPd3W|O97u2y#v}~O5_x?G5dUcN3jogm+EdW=^5jx-eRet+h&A2{U8%zvc zC$%xf@Pl4@`-hoYSRdT+3UmhF^Izu|X%w+F%{_gLt zF}bPWEIGwDzV{v8y4Z|Qe0*Q}^!E*2WqWm$!MoRZ`)Bvr(0r6OUE)`M^-WGRmf+Z} zmtz*zh}hyF-5*`!z3Y9f=Uh~^f1AJe{mXRJ7e7;$Y3dkyo|UoNTz&5fU4siGq-xH* z{%wBoJ7=f~IA36||LS3yI!Y$SRNseOy?UGe$u(4O2XB4v+kE$}4ua2lIi{hLOKvbf zIY58^07Ij*tjCjN6#?1lAy`yFU2{9fPqcHise*vZ_BrN_&h+iSiDjB{Pfvbi|H zP=6nNLlZ14M@gjfn6eX>CrG5MhK3`@ICJ7KHRU1P^5;w{H4T(}lIX%X1O2@Wj7+n% z8e==7UU_ zxx(Vi1QQb%ID5X6&ckIm4}jy-&=qpYD2o#Vbltf_&)_8UD^U`85zUt(uV@(0f6Q}a z|i8x!)Wfo?~86G-H=cUV>K3Ye_WBbGiHw}$c zY=N=fTim?U$JqQjiF6J{efS(9O)42@eR+X=*5$4TkPq z2ZcfPV?rsUZJ%rgx9`PgVro$W+_=RnamDO z2bdVThN^1l$WWF=(SAM>3^m2-%mDXq-QsTl6sub)@~ZYpMv6Biz)9FAdS%)y3WZIaZP?s%N`!kIff(tf8ak6GWG$=d<8$;-ct z)9u}bC!6GwD~#O#h?}?WGd#0aSi>Lg1!5*mIuT=Sd5+1+87{u@I;W3R6YnHkx9mhF3&MK z)X&hd3tYH(f~LyC-nC;%rjC}2F*9_ZJGZ*%A75Z2o<>m%nZgDj2uTuKQC1hH7#|s= zzvCRQzkZt9VlVDbqO~S!W}TU#9zME$lcDKVHWL~0idx8kHw7}OB-@+oEX_?aK0HL* z$+KL#bc&`@_W^K7eKAbaAfH-iZm5foZr){Ja)r%A21U`(3==^}lSwAnTwP#pYJ$mg zuW;$Y37X4%yvPAL6EKxL*=&|{CcA?#=%|W{s_A%a3DS9;k3-+4siEZ)%=TU9#_b*k z#+QgC(&QeF4HHNw5^P6TS)QL_Z0s24U%AYgjygilCk2c4H>RPX<`S&UkJ8(9hpwJs zCT5q|&Kme_2{JkL89MtzoguTy+-NU%?{v{UP;fft#60%mGofG;xxtKB+v#j! ze=|%VLn^UNY-5@E=@CW;J2-jnJQq3-Q|@~)-3Zel6`N+T>lU}V9x%DMNjj$#PEH~q zkY_8GA-T26{M0am1MQr zo!BC}GSB?%6erJL=5l8nmHXTtwZUeo$|Lw(GJ>Iy-d<;ZYMj~SDF!#UNhx+*E;nb6l;g9BfQg#j zVs_v*A6~mo*T@Q*qnN6?4jSqz2zhPj+3kYTIyukuzy=vr!r`#vIN3z0cfTGrHBmF$ zEcCt4l`A*t9p6BagH+acP*+t-&}+w3GHgc|nVOhnWp0G%W)jmG#`TTkv{VMz+0`im z&QKMNCtl;bzAcRBoXt1&EV0!oMn~pYPl^(>*ZF zMq1yUv1DpwwpW=M?&043UWO(XSdFXLY$B5M{I83$gFxkB&b%T~+Lpz5rsZd%=VGkP zP0&BEfb8-S4hL}9_NU5cnktH-p=u_ww~VHiR$A(co>`Jf@|02CScdI0nflL^1mwx* zRa9NX<}0VAwS~r-AP(v2vTXhu>YGZiJ@zbJ&9Xk;#q}#!xIM5)k`Pr5N2slg5b)R# zv^1N`Q;bh6FgMaoR(Im@2k{=SBIJBQqwXbAfA}6{(~OVJG1`+MuL?Na9?rH^5p+H;SZSi9*O?ja zzT+c8=jt0@h8amoT(KFQ|F3}YiB zOpN!iwVgv3?YQ4KK|`r;hbO8`bS25^L@&3lywA=4Sz@Z2qKYPt)>jbryRnNpN;bjT z!ZfpUi_8p1iN?~%Za>aTtyD)m$be~NSRB32%`5No;r$uXf}fJ=Mvl}}P#p3iqmxZ- zvbHe8^y~stgPUxp6ma+{|Ak|CMA*U7d|)xu6wBj1+_-v`8@)3mO+TeItu!90rX=XZ z$ft;{%`rVW!{S6QsjQA@bK-gRBsIaEu3rL@?4+paBCm3oqewJn2M~+0kL<*QXeaC&`%( zTpll{nj?4*P#F@_)JSbDGd`y0*6K9FefPQFGr;)5 z7TXySms3Ddceky&nqgycoT0vM?sxYyxtt=M0jEjxp$A={t*`A zpy?uZyTA^@M_+ABoy_(!^Am&Iy?vL#u{qWfIvN6!B<#q$V451+t5fvedY|{M^)Vka zaR$q1KG{HdB!EjcP|{nhE=)5$yU5INoJ2;)bQST-uN)%emS12kR0_d76=YYKnufz1 zX)M9xc>0`baxk4stc9W_8 z+g!VHjh=~3Om{Jr_07~)mJsqfFtvg%wmdh*^!yw{o7*JwCQfgF*U!}8dcw)!r^zz3 zBvXC2xPI*hJ(F>4;Tl>_wo+eRLcncDFjUgpYb?%;F+4KO@VywByok-=#&@Cyj|2jR z`MEfFo%i0qM(<=4MUGJM&>jzZWXybm=*lc(qtna|-6yM&E`H z3@yH9n3#r%uIm(PJ=(F`3pKzGBD$uqxwOn$bc>u(X@vm}5Qdg!alDUvcY7FHRw-*a z&DmEjajv70(y$jBDw)I@OH=(^d-n?6Bhw7tcM&YBr>5ixA&0a-jYm^QOH9&z<6W+O z)X(geNLkZyTEaT9@!NDw?T)%_sA=L$BV7C7CWA9k>}AI|ec>_}&a_fp8p7)+1Oqb3 zO%^75`S9KM=^bBZtnWUx4fWL37UK=t!B9v>C+O|EN8i{gX`zhM=U(T+`4hC(7LFh4 z`6L^QV+{4&|vx<&$m$-QD zI1N=1{B9elS(33uhI?*u{n{Od7iYP5{T7YQm6VqRD6;QFl7K5zMbn8Qs*Y&SS%VC6 zi6wfjY%o9L!fmVJM8_d2OS}k}7+Qk$`9XTRhnbI=_-oJdtzY^ECy&%p8gS#ViI`fB zL~NO{-Uu$`Z}@0(n!)aS)HT&nSrR1T+;2VcGz<(a!@|II?%wNXAt@3F7olu#e&H-p zJ-f=x;7#8C@du19rErxsbK+t(wz&_uJ-W&BYf8uDw{OrjvQB(?p4I3!4K)#5JFHt_>M7Rdhq-n2 zCVjKpcuLwh^~!6UKXa5rl|^{$0$MiC+WZLpcdqd6jS1$4?{TNNimI|O-U<)4XP&)R zSf3f7`%V|b%L+DMhyXE^U3p6f1k=D!Hklvmr>A#}m5hUumRI=B_gDH!j$t4yT>b*}_ z{}fRrMC-{5yz<(4+8Zl~_?;L^nys~2rUviu?)$eHpL@XlI}wV?tEuQLM`mYhuV`}; zX}QF!bvl~l1s%{7_a8ayVvL)TV<^GKIPT5)K&%Y*!EwUwx^+|mzf&)h`;@t zD~zw^@l>>M@@O&A?E73FOFr|vrlFCFPH_LmRo=gLpXH2;ik6dfl-Y>(yiM=gZno4U z6CJ1P+IxI>>jBGIH}!3ubhwkO4qW5@^0U8ds0mi5y1DYsRk{Y|NZKlCKih#jG0f!9 zATwX{Xn>K6GCgpc_kQ*v_s3Rnl(x}+wiPUT)p!W^&CWQrAJ} z<%^s@-b`88i(M`xDn*ya>H6?0H@k*dogL!Vl?qODRN!)W@$7IdG|fDUqM@i@^F*jW zdXaCw-a^FZc7%czp2Ka` z)VKx29lRvd)KHUC^mlbLG_`@|Yo_zkTfBMsIQ11_d``KLOp)AVY3czH+uOX~HNnJ# zE=sGbsc)>JF(4uuSrY4$+`alC-6JccZIv89^D37wpQg381iw?lRMTv&&M?${m3OZ^ zV0p5iTeqtyEsfxB4B>i4vW>;wV+8}g#+ZhNmW?v@pr6r+IhLadavIp(0ZJ+l(a_vV zOBp-5WKUN!q&F8C9Uft3VU_h*lB}X5$WFY$2xXP^G`6(RTocCru$+pat3)U6a=WXW z-u?#+-d`fGlMa_vWdL}Kt~cymFZ{CtE0W3V=Z_xykC>B;%7aEUs=Ajw2JP8dsPtcQ)Z2><(RtlAGp>%!Mz(-7@Uuj&(F~H-oNJ$w(k@4hpFj!lQ&M) zQXF{trf9KusHtTpMkbh?-$D*I({|<(uUsexUbeQqxM%o*T2+8a_qtD31h%XLuduW3! zA*x$Dx%A3qIuDmUQY+g}FciXThwR2Oi_sC*)<&6M-XxYjM9~h*Er_xmr^klV^X$LV zaxoG!lZ=fmk}?A{bzbIlTQ$XgJA!FoWaDhD&9l6jL2wpR+kT!i?TwTN?T8Q8S3!0X zD6XZoErGV&!`-PdGVvvr*Wx5I1`+4M@TllYhV8{}u3fp!$f81|;V>nR9CJNeOiV*5l%~)?_Pg;0!h}O%ypHFMn-?w3W`da`m)Fq@0h`l@KU73G z9DZgnpdji|SteRO#p>97dWL4$)QUOMae=qK@d`(){Wv};8Rx?nD8lb{QG95bXxdIm zO$EMvnw`2^fq+6b{T53-@6kIEC1IXoD_b_>)SZ{>T8_qs3iPIEn}bGPbeJ3Z6t}UF0wI_W_x3vsdbHdkBtMeb-g&I zNn&Z3$>~Kll2F{#&go09apBYC^+3X2%)o8>RDDIVE;> zbW%|e1Z*xJ{^x96hMFN3A7f%s;ViA<_hc4ID;!oEH5pvzTHms4oidW2lUJu%X8DrMs3s{KhNpT z6C8?|%qDMeTTDLN@o1=IwicP3TqGe?aqMy@=gxIdBCc{{{O^!AcJU>cCfTidre;>j zI_o%dzLRsEZ8*0ExG{bG`CnI4M3-lnUdrIDJ;Q}FXE}AOhS>crHl~Jl%RD)-82K1W zb2CgX>y#gRi?f|)XsNO@cXNS>@tp+&)c7p3QCblrZ?D{WI9rWOF?{LhRdGd-%UIp3V#2W|`3WW*#pX2us_IasY zQ%6rNFg`j>REu!E185^D=Yx3lPSgvO4uTzK^&XPP39 z+-u^)9}E%>2XUkpSyrOK4lw$Xn41dUZ; z+#l%O% ze{PTC#~%z+6n2u@h;gN7o|)l6#*VhoP!+)G*`KzDMS*?jw)*;EXj$TGODwL$Q3Ho) zsq*6doR_HW6jRHPiq3H7XFukrAKc{bg9#Saw#n!MPEUxknr4okzRa7Kj-w}XJUyAi zB%j(~cBqS6*FWUi&HIc_FR~gmP9aqdVN|8)0^F zomeu1qJ!}863g1Ac8+&m;;nCei;G9g@Hym9ls_Z4%;3$p`M>}9+pPPW_am$rrBDZW@0u$W5|wM-jCL!fFSv(YCcJzt%8nI9W+#UiH$EJJ@ewR7nCBo z@Rl@k?sbWll#8ZQ?HsBIV1FztKoBJCjsT@)MFjj#gvIp3W2J@2qpm1K7v|VXE8vLG z(AG*_RWV-MqZb4V$aXKml0%&DY@u&vlZnj*mKPUU**=Cpy#Fo}HcbIh@=|%^I3@NF zji)5EHmV}tLTMkfP#;rMawvw0@-2a$* zj&y8}p6gfX8s30N2OX!55lT(4(kDDu$$uWA07pZe2 zJSV_qV(KZDMtkY$9bqx+qyEepPPErk>~rp`O!P-FO@+Lop=uQB%i8S-qVU}D`}xR| zS2Q#oY<3&6&4wVnsH{TG*vWx0mNpW2Do)XSq@9+k08aVS2CX1S1S(oNQPPBAf+)$z z^8Q~)wX52C*>WM1o*08Vybx*ML{({wmS)z6yvl#z7Gfpf{feaAsh-I z3iE|PpQ`UDsi^P-5u2xkhPHFO8B_>XHgNQCIZo+un@B*C-GswMl$Qk%%@~IMP?lj9 z+Ttps>DUG2QVoB31IJp*@Vo7gjV}q=<{=V^P!jPWizy5}Pc~mTvAqAz7w!(GX%JhS zCmK(X7yMK&51iyM@L5s!xMAN4X&}aFu`2(GQkoVo9!7wKE-qP zu7~#*ObztVH@ZyLRY&K^;~a0Tz$F!W!7v3R*+X%CD~H_~s!pBaa8o5g=VR-sAR#*< z)YOy{3AquMw#cTEq|-XjshGI05M&oc70sM^y`8pGCpdg40*N^m#GUvDL~O1Q)vYH9 zcGPg}_+jcRyrdSQFJ(l_&JeXnIw|+maO^}YH6)SJZ2xsCBTk&Q9o2&PoT3dfo3jjk_-FjD|KtBj&#DIg zGAiqia3t)-CTQeR>kQxc5tBos90{(loqy8BKPGxU&iuete)RADgde`$#flc7qOy#J z_GUZ|5kt+ey}8En;0HXocbgmcXZX+l!4LS}<-?TwB)rA7965QBD5K1cJ)nDX8@s23 zhNDNQFAw9iS8}+v7_VfKi!U;G?a%n5fAwcv9b8BElu}ty&yfZvvS6a;(`;?5FnaT^ z8R+X{Xd#d5AO8lY>w@?`Hug*%HJ>4!NRSZI45Ifok}c%0U>+n*T3mlue}w#f+ripwe~FAqMs zZnYreE32WRtb~Ytob_as`Po&nM*^7ceHaW7L?mAWXI^i^=JHbHb0CU3+q>+Mvblm( z9lk_a^94+kf@9|?o*lzb$z}4WiUE=bx7&r=DI#E^YbsltF>njneb$&1 zL}Z7D%9dtI`~%Fa#@O80U~MBuQ_#(R^SFu52$6>K{Mv7{pcoSV(wagB{*(SzlCeAN z$dZU)e(ZVLO-t59Nv<+Ga+eS9&X9LE(RTbK9fwNrKXU1>V0Ys5_;K4L61qw{kwh^J z45Y`7^P1?YN;;jvKtQs2@Oqrsca*}i*BIoIYs?OH@!s_jHjPp`Po3vJqV&_qc>6rL{2 z)bnJM%S_B{5KjrzoH;~wbqP{-lcmKN+o?2p#lS?w=5*r=gb9ZOcwP2=8<5#m^c1PB z1$u|K$QwnJ)z(rT_MpaBS&zj@rnBTV6G4)3x_$TqA;KXa?q}2#ej52~mgIH<)etdl z6_l0v@p){YeU2bvb9yPSuO;lAU@;bDX(>uPp+M+ykEVg4rdc1q#fR6snclQfbEcE? z=Z_&wZ}H$DENQ!lfQaby;C6d($pT4LB^ghk8a@mjFY92Ssw$aG784oC=E38(f7UIFndJ6Q`Csc&z^$z)X!iztc|5e|Ji@uh%(AloUftD&?wj6)x1 zduxUHr8I{_UOcwl(RU3!$Hx2+_j^WI*pjF|+sW~xjZ_DJK9@zChoYJjeDjy8*-j{U z%W5f&xS!akf*@jdII-L0eOq?qc}UI*8jeM%I^m}{=)@+QBvLzbs0yNtFVe`FS6gs+ z`~*EVBvB*tGTgC(fG5(-xz~^4bbAPT?TCW5L-kugu=%KHJk1;RZbAVMF1v(jWL{D- zz`;XwL})yAiHZ&nuz{mz0~9wV5S&4ZDeG)Rg& z4{`{iL`ma$-aK^np{`l5kw5z$3ilJF(>WAHLy(*}-5z`{0bz#=njlKZ-XgqCJ2oLt zE|Vdf%b}YNK0SC$OhYG|$)Tz`h%TH?H$Hbk2Ue9l$?a|Ont>q|Q&JKn9C(u5Dj>-& zN^5H<2@PV?=Gj=^Ai9~uEZL2Fs4QLSh-4 z@p2QUPHJ_G8*l%RKYjZyb15%J-})_n_Xoesw=cF*8FHW{R~fzg4uA6(f5spG=p#n1 z{u_Q6si3kf!naOUQr-D|{$b~@@LOY7`SHK}Z}_kO^)SJjv;5{i`ltNPcTQ6J@D@2! z%djxi&3k|L|MEfaDtTWcmw);9`TgJgHl2qn2-r2!8&h=s>@WD^KluxOc7KdpfAz2V z%QNSx3VHArzwEL+g)HS0fB(Ow>9s-H{*V8G|NW1C%$U8MU-*yz3IFsze~XgmmOQZ7 zTXbU4D9KC~!5$$H3K8^4Ppr)+2m(05ghD|g0g;7dme|@FS@jS)&V6Tm2!e?0ucFfb z(ghWq*iRkm1?Qfo`7onb)xass2xw%I z+hh%ed?rIqF%cb3TuvtrrxT~cf!+RiFlq;KOat^hc|}LlMO-!;B08DmHW@8PE|(>f zH?cY0xLgG}PNxIA{OLN=rkW!gTVo}jC1dy~iuiC#aVGkDxcSi?9*oYj9?znSPC})1 zv>xl^{P{Dqw^R~z6-t!s=l=Mj7`Zg5=rXh0I)*nuDB!@zF7e<&7q{+oGd#7zR#HWB z`6#Jrq5Z^J&YwF*Q%wn8`-_~KDBLxrYC5JVfaJz*lb(9AKoBKdfgoOo4be=o726_} z&SK#C)L1g~Jel|$H-Gvb{ZpH`8ot5l&eI&L^D#dEHOy8OMI>)2r4?0_g$CH%+G2XJ zkL6Qd9FiZGO+pd{3`0Xx(yT5oGC8%1A-V`eYN;*{;Cg{un3#rvu4^dS z4Q8gN7@1f@uz3lWHc(mY{Y2KYp97|0plJ%(Q%ufAF{C2GWrt|4ka2vaEo2i_ zRWJ+#BnLK|4V(P5?0o^7H-OjU!6oWsGijphF;vZk$!?T9Gf>i-O!VDjWIl%OKgy}o zM`@}FeX0zRAldPR%4i6c?cmqxWYQ_JITc;>;P(3Pcn;2e0RWOaOvL@@zr29XAj&xW zrBr-M=YLs0Uclimdra2O5p8b#MQ$Gb`T;t?@zN0;0g8$PkLZps{&r+nkkaZPrOz`x zFvw>!WYSqQ(}wIQA{4a0SW=IkL)8lUoFqv|qDd~DB9>Lj=Q3n+I-=c)^J5*$;lys2 zK6Bc5zaa<`vZtKN=agQ39-<`k^lhmSFwq{~9rs{xlC@|Wo41j&iW;hlM0R>0M37`0 zC5_aSg&3QUvoSxz{Oml<6-^X-o!Dd%OcPzplh}?jIXTbPb{3njk@AX4s)`G`m|+;G znucMT2(lBqT}FP|-Y5vzeE~dfCk{~~8IKc>r_jyd=Xg^VUlw0!RcAkA>Kd7i1*T?J zFiQ?|GE~a)#5|cVLAJI%%f!%q-nqAmAiFvI%5U>Kzx~U+d9oUxLqxzwdGlp{@dw33 zJURaRfAKSxROK->!o>V^v{04(W)>3XCVVl@|AJq@~;vI z6%k;YfA+(ErtiGN&CAC*(pW}QXlFyv)Hhk*SYmR)B=G;U_h!v;oq3wy?<~3RnE(>| z4gw&+eP2Y8QmIs`uI`?8ciR&&5srz8n3%9H?C_1hg2T5CU)Xmu9qt}GdZuT(tGiTE zQ4&Rp`woEEcO;fXCURfT_WB}0iIPAOEU8)~h3AH3@|=86X1>dReV*oF+E4r$|MS25 zZ#dr5fX7zLUOJkGxcFx(l~R^?>_2idvChpa_xYD+Tj{E=-<#}v_zqY=nOv?!rD~$O zJh(j`9M5gXm5?MiZnq1sTft0e6f+#Y1H#g%lu8teWi+iyIiF%9HqGNZ zcNm$CQ*pO*>huLp9_pjsS*rk)WCe%Ig)C*U^fJYghOUE9cW`I6scbA^A%sPxT%uSk zVhZuvIuydvNGD=U&#aIy3;fLo=x&cv@B5(=iUKV&!^FrVu8(H%M*2B)>KNUPAskRX*t6OzdXtQt_XI%Q~B z$Il$4(ILI^)##R1K{Iqr1VYQO{Nx({_0A&WQ}e_#B@C-3pzIDb(9w5@qbH7XWT=~l zfb%Q<`Q1Q(RVkqvCZ=U!Rkv6e{fxy=CzzUBCY~!5~^y$?yw*s_pDW+mfT>pqq zM&gvc!<;{NiW3J~a7ei~JB#yN$Vf_WrEGozvplMI>nij2k2?7BjA?N z3R}cxA9MHC9Ud-0UHc#>-a5lTYvlWJ?+X*lsF2AN&~%+jIZq}LV{+skk4L9jCaf{hI-owyhH-&>u+hHmsXjYTwpy>!WrI2dq*eDVf(IxH}|lIpCp8Zsi#?9Twr!# z1K|h|={!nbvlH(Q=jrocRco37x)5L#h|k^SH%}Iso114PkwZ5Hl5E56ucxJZKSz!q z=kQPuEp260SkIKXH~oZbzcnakPIF|ao92iI#j23rSYTr0E;sKilCkO-K69QECx&TuO30Ex zQ4|~w2eK?7DtSt!DpgH@Yv%_M!m8O=LQpA{C>2XD7FOQFkBV2^O@DJCDJq_5FGtQb zG9+|1XCIPYSovp21_+9YHCE3c@s~mdj{{g$eAM zM)ggHu+R%JMsHr@lh2=!s_1BjMzvg`s>}Erhd6TRI44gWrl--1eS70jR2$*?I$VxT zwhCLUE^o3m)J?t9{dEUj2u!U^a$$*NzC_sqr>>)G8s_Un4*Lu&vq~Yk$oPX>j4fuc zoKX&+J4tU_9o`=#7a$O3k=XPEqodQLq!3*Lr#aByNZ7Xny#_K4e=~z8E}~gBu3Ue> z{L~FTTpQtYmjk;ZAuOFrsYpeaa5N2Z=G?oSJJCl|=+*0zc@{z#RC8<0jNIh@_y&f% zjZ;6n#DUH_f(`|=ANvV+31L#sCzyHsn8~G0On)E!`-d3r^1l`VEmPCb4FlaY*jjnQ z{oD#p#lkee?sQ`l7KWiy+*)QllVELmf!OK=&YwTVK(h~Jx0Uw7!mO0h3=>VSusQdT zJIOh0l2#kb<%aF9q-=bF(bNX9#d%`qFLCzNA$l7@}%#A$8=lA33 zJjwB)ep(v>xMZDjF3#-OT^@}su)aFZ&ClJqJs#dU-AjYV{(7~@zXS|Tqg*Uv3J}#4 zbK^Q5Z;+M)7umP3o2G~xI~tkz0uv(-7@b@pKL3zUKJpRpx;VbS8UHRPuG8Zo7z*J~ zRw-83h^-{abTtvSe^V&b!qiG^#nwm_$~6s?YPF_o!c#V6fmTeiJoS*zZ%&ai>KK0e z97hlIyhMWHO@)lRu7{&%-$BR@KD+*irIF7_%-_Z3vSX7aEVK5zR}Gb5*D+4Kb%|4l zJE`}5zs_7?QpG7$xl9=?vR`A3e+J z^c_C>@D_8MIds!RtCXl{7K*Ep;j>3La{MSq`Wtp7jQd(ck_pw<;qf?-;%O4`IGc$g z?LHgI*P=}VVQOU8)<~o>6fIHf%BWPnEV%eyUzMd%&aU(L`fXOyIp5%Hmc{Ow&YlxUdO$R~YpT@0|Q5tV*1TyI1+`Zyt~|%o<;Rr9xE)M|dA+kDTV%v4ae?`d+fIM?#Vu zH0?Xh#dkq<++<{SmfOEuW%Py{r(Ho37FxALxuRpK^$fpthI8kRGt~CfcaX3!Q;X*t&m*wRDw(x4wlaCD0_?huuIm`DsXzWx!Co@pM}j0N*xf-I z+(CqurLtz{pQriQBDa-fBeqV#R8f7M^z}Cp4tz6cBO%+ogqnsJ=x)IGc!R>TsXfai zmsn?Ua+*X*BIFLy+GMAc*&$B^zN4FlzyfROG;<>(%=EQT=j|ZkvZ2T|j&Gw{AiKH9?dv0~rt%noFl$EV>sN^& zundh{Vu8tfpK|5;81agm=KW{5cxHh1I?oRh*cHM;%PuiBKEe1x4p(?T2Tq)zqu!76 zIRi+tio@k25b)t~*+9>c*(#A&6cj~5SSF@nA=|tJLv|c44^F#^Ec5+?1%E&o)eLL% zBiy=vpS6;Q)`O?GaH5w+zXO{r(0}X)+$AidOlD(-k&#(eQ-a15`xzYUp>b!m`&SN@ zVS=n;ce${HKye0X?;m8ax1G9x6Ui)-O|G&yIm*cR9P4wBD3(nO9EAVm6!i|7U3IYw zurwXXX2a%mQngGJN06SuLHfFysSmo5%`&NtCFUka8Jk!jHhrIxreNYA^!^d*T{T*) zYNd*4nqcKfZuyAz3~}kbiwt+v5%4-uB@?q+q`$9&u;(ARe0`LqxyOt=ZlkBWnMjB2 z4do=S1q&Yho@IS`iKVR~6-!`R7OKNXB;dv$3=xim z@HoDEEFlak#WWkSWfs>m7(!rKU~~G31U>kJVL|~vZin(ppIbi!BxFLZT{K1}aV;zp zo0(*Cyoa{%AWZ=$>b7yzM)LpwAOJ~3K~#-p>J`fQbw=(#VQwXX1}K(=xlJ4KeV2q; z$&g-o#LWjQQLhU)O{Lirs@R;K%QEp`cUDl_?f-D5``cEKI{fNGk471iQnH%V|ed zzVh8{E-#UmHkt!2;+Y(aPo6N<(?)ZkhtRe^Uh66;Q%W!M_~9hW>nRLCeQo{mpB7#Z zPw`E~KfAKJ0AWzb=SZb`{y8xFYqu89d6&WMB%;Lm2W0P~N zZluVS%4mA6EeT9g%M*+*WNKAuR_*n@0PP-L3=8peqDVFF)E7}0N=QiCYCggeyuQRV ze;`N_inET+{b%_=ZX;i*QY>WH+FWIMd7bsy2jnwbBr`=WoHZyq~0O3hZ`X{G+|15W*lEpXT0` z5Bcqt2gGs?S`VD$z4tG0uq%Ss{zF*D0%2)v&W$oPGs~tHpsQ_=OaYub4TcIaN|&F;4Sr`ee!EAUmsz1 z+irMBBn8>o$i71-aW<7u{7rQB?qgqfGxZ@qZl{W58B~fx3=Q_u8v2mm-56zM;USOi zhv**c=R&Wi79=ywZJWcu(>Or?!BdcDS*YS*dQYz~^dK2DumBNp3W?Ou%4rFoWO zDTZ5p*pxR@M@U!#!>sXJONvaWbw7uX9OXc76Yeh!J{4~;O84Ml^!zG|D@l^GtISR> zu`;-i{`$II1t3&+JuO`W9P59?baI*4#5F#3nv@GCI5^No$R(lWH(8k(MLX~1XS%LIT$DLKc(8=vyo^)Z%G5FI$n z!2|o~XbRzV%IL*3>x+|&jZQE(|A1?HnNsOJ-Z{IU_B!|P-zBEFaR&Q&`;Y#V;X;{W zxkx^Ih_nuI;e7}Fxe}Fffpl`6)z})F zn={yXthdQZyu6?tIJ^Yj*u*@>6Q#ZK!*;PKjGfm0S!QoSv`1z$HbcSp% zy>29XgpPqDoK@Qp?l8@r0}S-G(bN#a>$0O@QZ4669T=di@e?k8c7w_IG*9k(xOMm_ z@9p;!d@k49n+Mq*qOJcVAN+YeS>2#q$gs7!Ml7~Ya%qHX*%XP5bG&`&JcqjiFSR!c zOJigDCZB)$1$W2R&|GaCId+i2eQh*`Tu5e>?B)t{Q%@M3TxIO$Zzz?@Xz!lq)KDW% z2^5E)NJ~E_hZ>pN%#m2U&li^^jLKP#ALyapuOcd0;>%M!zH@`yBP(o`Eo{%!bG)(V z=o^Ap(?{RK9}qfPwMw~c)I`DD0bGvf3%4kWg4^Rp`KHrq=~T*Pa``HjSs|ZX;QnU| zyLtl2?nEz_DOaoL?9#;&7FuD0*@vIpObU-a(%owjY;nnv2TZQHh| zZQHhO+qR}{bDB55x9V2C_ufBJsicy#E7|Alv(|c^{aHu8H#&WjE850%=2uTS?ZYEc z=9~?E;CY8(Navuz0h+r8UOu5A$8fXbO!%OX=TMbb+15xJD`?g%?*9%hY)3I^-#TX> z1|aPnE%Jjx<8j+`2Nr3Ml)hYA#47q8wE4RECwV7i^BH93x8$F~_SxSB6=fNjzRv(_ zHzV~RUwAx@+50yT*>%`?+4U}w=j0TWX%Z)JBs;<`?yX9C!K()>`OznXJe{{ zRVf1^ivP@&__3whjGBywc)n9Ub9|+R8KOqY%9Lk8bi4k*mR5+uyNlY}J zixXrM&4SJL{Jqc6YJf(lmC(xNlNiNK6W0fdwcF`LWaQ8}{l9MlEQYW0IRxQ2=Kkcf zSL5`xzK(Gj?J`5(dG}L@a=(|Cq;&g3mMDzXq)i}S7B+OoTI3m>ecykT9+7BZl3ZO5 z{xIvH&Iu^tt^4BR_0203p)Rq}jNnbgh*A*jo~&LY6YOmWCFyYB^B=zTiurKg&rC4{ z!uR0uu0`76oN1*v@y(pP^Blg~JAQnl8Mncz$fP(tF=AD!yQeqVBV6TDfr`sJ0~$o{ zM>+08#C`PEP3-8T#!p4g$REz>6C-$TR`oV}`}8i`Glq9q-s{_WTDELb2ohTsHI=w^W`F{e%lN@Ps3FNw;S%9}`DgCJ_@Z3D1dsikG9*GY>eBd5qOgLbxfxLpR zL`P3yRv>Er80Fj~J7$h@!nTI#!6IQv7xXP>mhhpdcT?eu)eYg${%nXzw%IB|2rx1F zz=~L>e>gjgYIizi;Jy#5lTTZIQ|T#c!9=B66w7b z8FDmDv3Iq2Wdk6(kyrqFzVQ|*&CfG5_l}{Q&IEEd^q1U?_3*$AbEp{S?A2G?+w0Hi z&rF^DY=fnTB`(kK21^d>3iutz^7SdJ#5C{8!1G*tNBdfObJ&h>qAsv1RH=m;zT8an z?(S5GbJi)>V)f^s|Hi>c{YVSxs7z1f4UTLhbg1OO!PA-%D!{_Btf?v_e`&Z{?{IdR zERHaGesfh!ycj!+tboI(86o!we?qW+|5qI4iRO-uk&7(^@z(v@5Ky{fb}=IylLy=% z@yj+g!nuWkp1OHo&>|Yx8uQwdZf;HV2OxAm%sT5pMLE%oZlCE=q&Z3K+QsU0k8c?Fi0}Z8t_}VeIV0Ox zn9o!1x0GPx|FC6UF7bFWk15#GKI{F^9!G1xV>lPNw|hD#!#4#4mF=Fq4cJ}uyr^Gr zx`Qe+Cg@}u08$GqAUK-);#Nz?Ye6dNU{uQTI>iW)2i(Srn}vhog6X)S+@F?q?&Cwl zmgvx(hmEU_s%%;7VSQmF1>GPlZJ?J?diH*&8a*nl{g$vl1r;k(*PJt#tgcgL<-VU} z26W+TrV2LhKYQML=*;PsMY2dR{T;eYlvJTfjwG*K&GMF@Y7E@jU&jb)JG}RD;L265 zq2H?S5)KAs$OepK!n91X4ltb7M-O3^eD#Zdf9h{q^s-MTWso0SF4@qfk5{7F=f_%D zBbLd%EbZ7Ze|M3u0-UJq*xkA!Z7|j~u#Vp;)idO`EI3^PVa-FWTny_LxZZ^anBgBT zS%9@;Be#}77Ov^@*S*7|051@R=P73a*LG-jSLc4}_$M-!M|FuY3T#~d{)TTepV-s7 zgxk=->drez-K`%Cs0AT!bI2M+Mg+wpet*`1#W!9tulF-6nEe=zKDJb{iFG`NPq($S zx`|Ioev1w`CRAa>+wx&b>DJ)-_-%9(sWf^^NfGIooEk~<-y4_b9Bv_ zfP}?bckl)k!Pz?F@yaG0(^~iPh^fi2R4I#GIuuLk(+@Ap+%a%9j9gF!-Pn>_>y^V9 z+)dMR7ULXxKcHf-^%<>!WEq~a<_%u;Xn zx(1+Dscy>(cl+L;oXW#5tQ?K~^IpW7bR$eCk8_wA7fQ@Eo})$pnb~o9c0u)JlIBu3 zGPcafUX@kp-t;o&CnJ*_*?%%}=Q|{2Z(Cg05ObC&)c8*KR)&q{^^kC0`)|Qm@pBdv zGdx2p<1LBNgQr2L@}lJD33@h{e?p)Nv#hbleTs&`pZEIX>Mff*6=SXAckA@@5l7KS z=vfTwezK{G`kzo=b6}TQh45y+qlGuTs(VqfRkH*%Zae*W31i41ObD#)Q`2L$)Mw9n zPJ9l$IYYROA=;oGmWMJ3Nug9zGVEX^jZnR+KYp{vLK*&e$i9qhfheJ*6N5Sw;*vSJSi{JL(k-Gvw7iksf&=h6N>0%SnBu|<~ zlB0^Y?7#eTtdOF|enHJ;KG<-Jye1l0ON>Yi4vrqum7kku>M>RZZthRe&^C5u6MVK{ z0aTP$9XyDib3b6f$J8{t%QLk#O44YLCgZ;eD{gjvtgo#}WqIfRUdp!`2R2^W)|*TF z6{(Is$V_FvmOx`3ar-!i1o2NLaV12QIa4aXBIEm;!pH8TEt*?0(eZ6?`4w&f`wf1g1|_TNvbYi4 z<#XM?e(wIu&{#;_^Ie#L4EeQ-CTq8k+r~5t zal#Ko1gFbQR1BatL0^|Z{j`MPSlE5%+xonf{R>Fe$HK}sv9Za>@JXx?Z#tS4jd~(a7`U7dziq@SMH8q7&LT z_)Sq76rg#2mv`jqfJ?grM#%919x%VSGWPeIpgRQ_r462@GkEK8;L!25fuj51e*%*u zgCR5L1E=y9h5)13MmvMZoXb2}Wy(C-eB8bGzbUHO4D5b=pc{)77)`~G?|`ry#O||@ zfzc}tQg^~e4X1hUzi|HVbwBh!CqagTH}*E+g92++$+Rc#U?y$1NQI-1y+xFaKm`_9 zwtR+Azq{V2HtCn6LhHY7G&XTMdf<%A3?W|^OqL^hqU+GfRT&sOaX=}z?>F|&IkWV$ z&^TK`=~%`%_rVr^QC>qLIdi}EnU`RWqz&G?9k314sgP(;$hU#%o@-8`0U++b7|ymK zI{TF=w(yJ`V@2phM4FcUMk2#|Srv)VQ-z9>@(Vf_|DT#Z-|@E%hW!*1B}4a=_ic7@ z-RwOi)>5&S91B0DF^gtDI-h{CH0;doY1X!ohRP&);|53|l3N;Pp0udvE`4HTq1U}P z`cblEiAKIgMIr2ZM9cnIU~V+>o=l_aD$`Vw&$m19QJ5vwRLq}y{5^((AfN31v+^@s z$3QS}`gX6@jf8VN2*JW~iN<#4?zV^lkK!QP7-d+gnwzHy8)$NM5;L{+X=lm);|)Y+PCP2^xCNW>rF82aT!fu2IVgrfchM2K z81(REm>%S*c*d#%M?wOj}?)ogemzvi7K%CZ1a(FMq`~KH=F!xjZ%l}EX=|8Yk zCMvWCvMP`mbglMauZ7pVRDpcB)O7`NbuTy3~?@e)>H6TyUB<*d_BI1 z0|~$rfZ!`zrA1k|`)$>)PywODYcL#d&eip)hPFQ6ka{>8YvbZZO{dV9KV$O3##mYJ zAG59jOpi9Tb-(-4|I13UcqN)KMC_UZhoYk&n_LDu`!3_!UktE^_C^}oc8?EASn$r_ zc!eb!!+5U>AOe_ZO#r1GzQ=7opXa_9PI6oj^7oJWUxBEQT$WGY4u%6|4Jnx9;9zXZ z(mtBy_obscU_utfhmMUSG&l@G2~higP+h}rB@)Si%man_pgriU6y|?Ap^Y6`CK3It zY^{mdtUDsl9(V2d95&pry%LGh)n0dAcpTUH>NLr)oRg*fKhqkCCX|bS>5W#y*&EhM zQzXJYvK(54Ry@{FAu!?Hp4mU@c-|9#)In%~n|~~4wtk7(g4k6ACRC8bQSts7jS(fyeOjGcMiJVT6t;-wIVZ8`Eh65^_`8A;gUHsL%069%=XN*j62XG3>&B_+mxbV?%C9wll}%_g6)|#Inqd1 zxpE5j5hB+cZwiDVEyd(H6}-wrF(;H#1pZ>QqLZfSm^e|(nElg40eFK8Mp9wHwV^;E zgF&f<;E%DDZNCEeb;kUn0A^F-dA`Fd3E)l_e!Cwl+}XUl(hg%-@dD{MopuHqEmAs~ zYOTiJAXBX6YE@^QzW|sFVW3-Wtr)Pvv?#cFWV!SP92XJGE2uTj-JKKv85*jvO!I#S z?)kdJG^EfB)S~Km{qWA>5f-xnx3m^urizib%|3{Qx+nr0sR#%g55ZP&6kpph6Vu7` zM4D;v@Sj=}Ps5nX8fc49sojxnuvsSzjC@`^IyeM6EzS#U&&sf0N! z8ZAcT4$!BfM5eM5L5o-N`>&CfWKv{ZQaEKf+?&IdK!>Rci-{9BjA;PU zn#jBt2bODDxvMVX+FeT>;`&MG#0Xb4WeT^hsFNFpPrK8oD9hjwOSFyj&VjL?H)QrP zK>P(Hr}sYZZihqo&FJ4M>yK+gM1B&WAA*l>s%MV>WT~pi=7RV=u5X0#=M4q2s|ajo zkDW}T>GWa3)>|&g@tuSf5bD6YmOG_9Za$GhXCgX+4|k}x!p`bpV~EW;+V=)&$E!(h z*X(ff^~&L2m^L2U=>RfKlWCTpMKr-2+5KThDG8!kdtDA>c-ekza@#cy3Tfc1R0bG= zR7TUSH8+zH*SF3^N~r>uR0mG?hcWO$x`u{&5g*z(yQ-qzg51t}V@zEV@3-F#X>cCs zM4T1YgeNryn4!FX=KevV(IuID?lUcvLg+lul}v&xDPI;NxG!8e`r9V`uF`B(BVhiW zMx?$t@HOo}2@~*6!S(SG-kv5=oa*V|9Nf~z<+!o4hf>5^rHLX<>f_`IW3J8r1sQr~ z7x8yPl}U6tSWEU-VxU!&;8S+RCA;ENvRh9zHjhkx6$SQ*~ zRi!M+$;{A@kBl$He025*dO0RQQlSc)<9*`#i+6CjE5TI-W;a6o9l&*QQ9<0mD{^Lq z90POp-2P?%jt^B26(d#6z}79ZBn2KOG0Q?1w@24d2jLlB9s-JPYM7OdjyN6-UDQ)+ zgqjo@wkX-a(J&xcucV|eZT3dZ=Xus1+g)fG#QEMN)CWBqUe5;@21|k%Doxa}u>6*$ zOAwEEV&Perbbiw$kPN86oUoa7KKaym5GL!j&18 z^3X8>lqOmjAynQ!p=ic^kw-STeZbV}a3u{nxoUs4Wsn@A{>*b7? z;ZqSZY=G z8mjsysJ~s45(%z0k>X;5jotRRQ0E~x~%Cl4`-Crf+~a{346w|GTevq9I^ zNty;3s*AMFbU+76DtY$vFPtr{yG>jDoW0ZtyG)JLa>XwynnpMjkfKcE``Num`8JI8 zWgHHNZ{6Jvk6^XDYi;8Ut%T)Cx~K+OW^`zI<9G{eQaw>I#q9P#`X@ILEX{2LXV=h? z4ox+LmU;AduX;tO92uK{b*(@b)e*u-qzc4+4>tC4La@e}ApXVK{qO#`{9PSUj_ z7uK*zE?RtNR+%R~6KP?G6FsF$b81h-E-nJ~IVpvBn&u+xubl@g6J=|exH+esc!Y~@ z={~%(DiGKE9M#YyYUJsbp2-?-0A1C)!*W5K8a-fx0lnS$;SdyZzpq3VCJ3gb7@!G1Rn{Tu{UpLT_ zd5Ls!dKBXBdAs;~b10WEUCR-%#Uwt$&?ja6WAbEg$Qsm8NoowM%Q=NsKf1mG@{GeH zRsZXJ4(pYI5wW{B(#-#jdA@5Ig-iU+VW*^va8jM3OPAZr@{o!ILO(&p+c-xRlNFFR!; zv?WI{))8T>qvErSX7l5oy$rF`=Ru*vO*T+1?Fo z?03R8^MIil6MS%yzh}``s|pYr`Okcy&qTo zA!fFR32d=EIuv7_uXvM+w1IZ z&xkJT?|lqzG`Ln39vQ+n3VllrH=zbj_PF_`~@{Wree!v**%)mZn{ySoD5RZ%nWK_;j z-)!R>dvS(cSeN+j{d&*T;rA-Jdn9Ip2Ys~GW#Y=LHP({fVwHu{6<=yL4{Tcm)QH+X z!z!00N+WGaC|0L)1StZWyoYXB^8$4vLx^qsqp(ZbgVBN%_T4y7QgRn&4G2#1c!chiXB$UzI2J&(oS5 zJj!hM3|wcBc}~sU_5bI~Yx}lBm|cAZ3CszAyYIJqK8fSZ4$p4%VsmMFA@?9k!h zuRYnNoo1l7S}W;_gc#5%G3E-h{#u_AX<_!i;w=D?mJ@ci3AD)zFlBx|P{MNjAOQ4l2EDSYshxUn^ALOx`Q z`sHgp{;vz1uVvpg(Ls?q4v9Gk2O4J8Fi3x0+8tir@`p9g(;2B$5vQbQ6KG9W6uXKJ>@K^`F2nvOmW72U8y%RZT7rTtEF)VVN&c}=ic%F7)eanCoPplat5)5QLJOKHD zk43FTgo|%%DC;#tV?Cb)^33YmMBm;x#!RGf-)U{hKR<7^LKOveYC4Ahz|I`Dmh?K9 z7eNI(xI%Gy)WgR=IOCYCvnTeX6=5?|czy54BJ!yJ(*9t$LwGxS$DFsR|7>WiStO|3 zH|7m!b)tjo5i#=2977z{ltfF|o_Ts|U0i%qOx-B0HrK-E3P@mKg{vIN;&ghZ&zuN`7RLMM{kXD*+Et-7olwi2 z_v3ul!cd@SMLlit>U0GwHXXvWEH1A~c@N&4_&relRVCG+#j-4|Y)85K1b~I(V`%}dO^K8_+Xl8((N}lC0!b

@8N`|mO(8clsxTAlH+_L;yr|Ex}vF8ot7y|k?U_z#)nNdYGAPn>AeMZ zKC|p>RN!pz1@va(_V*hz(2>1@v&jRVjd2ipuvs9bdc=8p#*Rl^?s;_enojdB^=V&2 zzQMNo=;<(qMi_^5b*1C#GFQD^7q~dk-pTl=AVL~w%+yNSmNcpGWks>0<**;@RpY&$ zd8P_7HOy{bEOv3TNsXC6yE0grJi-EsLp~JfR|iCLx9wCf1FecdCdDedErje?y;U9b za(`D8fRO6%`er2^t9!b!E~IKR`%pad1G2pEW8iltD{iATGF`kV7s(vD_LS_ zMr^V-x?VH1Vv|r23ZE4>xw9NLR7`Sjy0YkMN~u)n@PPAGq$qTwCEjY~ytv6P@D)T4 zP;b*n&orwn3;O#_F{nq`dffm_(9(BJJZ+LYp3yv~_z#hY-Cg7a<)zMfp${-NiT=7URx`hK{CCKWcV%;+;QgQGR6Vm}l>GPp?b|cv@8F`C z!y!>4_0$C=7P{fZVps@xL)=6qd1GhToohdau~v;v;CSyt5Z!JeMZCz#R*4l|g!lV< z{=+Mfmtb6*4j65%RiEyU)xZ#>|Jcc>Z3+wb_etq!2fHJde;neH0+d)_drlo2|+EKOU_>6_E{ z^}(2~%edfprQZD-mFHZ$1~0MRgPi$+=v?{Am(`)FR%Y*{IhClvJ)2NKP-ut=P$cf^ z7+&we-S*^|STw`l*b>$M;d^lfZ|gv{<=A!&?g@0V3rbm$udjy5n6{LIYe9B7D^@f2 zaCwDbzm0B8t_Air9!nq~9q$|h=X2#c$oO>F*besNvEcqUCzwo&W-(A&T! z!h`#}XLrm7lQq5b5#RUk4q00?YUuVyo3Gs?{d+X$2?7jA$eS{uR;|nj96Wp7b@q89 zrjlWs7pKgAiJyBmPv>;F=IVSvswf^T{xgPi10X$Y)>nESL>X^)eRJmd0K~M^%dIa> ze+(#NkYB6RD;OlZP?{6bJ5DTCyG@GApfl{ZE6K|`{QtRsu30~>gUDw8H2oyFBZylz z^RhM2O@_ez(+Nnl^L^H0kn1cq)-b?Uh1sBARX0XEx<2ZvE^HTK72{!}+_x@TP5d?C zfwBX1Vv6_Q4&T#6uyiA_o&Mf*|C9S7X@()Lk<~dvDHd@w3N1&lE6#c(vIs+Fv;@SK z4CREO0u2Z4MPX;W9+`(bdfTmK(9AIpleXXc_H_>?9Rj|4mJHt)eaAX^xOKu}4c|~?vHWouI}H*2KW;KzfpeGsN%W2gS%b|5Vx4&2M+gd|CbwXz^t?U z)5mMhF74KI{p;?s?NlmVReN63X*RF9`)yAa5iD3oyWk%%!3X(2L;{IXpLqrW+uMm* zJ^eQuyxy6%8>!?Q7a_&#k_~IvPUDtGPi;qtN+XRnQ>o3x<*%Sv7-UYn<|i4iuYAw1 zKF{Q9AC#I?XH+&k657J#$F-0VLnX^N&Or6nes0&0I6PjkHRyiJM1($%1f#ayCT)!0d0S#3i`WP&I}>dD#1r~PkI?n9Rd!n4ZT9xG8*?fFL0^=bViN0x!GQ1^!+cIpdPyH4)_= z!nmD3fBsZ;2CbGNo0$p0)yg?MM(s5=v<~;)m|aZ5G@OwENTjEucMDG47>AZyXIO5Xi&r1glX+o?8Zso}!|jQnA)YAM z?aCm&URm=~bbx#m!`@E78AzA+R)zjdu3*x)o!lt~)MQ6V%@TCG3Y+`6^6JeNA%~TGA=ze^(R< zEl5*}rLiMsXp()TsZ^d<6hBKiwQ4tRgd!0V6!Hx8TX`rdr_dISNEbc9 zgvVllQ8h%`ZyTJpEMuG}3T}op&@4~J*D_P53a|!^K$q{`;6FlKy;7_Rg2@8JQ)V_X z^NS=E-p}PLMeN*Eck92;S&s^nq7k2$xLYHyDo4~6Bj!qx5E+x+YNuc~YedoIU`wxS z1U6C>8T_B9PrcF_QdsXcKYp^=x1#PeTK=RSgfd)IQKqMB8QRt6G4ju%X!8#D&O*@m z$~7xxjz5r*`m%R;ddF87fCvk+sM?BiEE{sOB&QE2L97&yMc=v$CIWE5T5S5f?JDM)!F8~mR$?QpQ;GMaHDVTMg*1u(C5 zDp-e%#AMXi4vhw7GrAUD?HfU5CPA)m>TgZ$W}7;E0VmwndoWcML?>pdld^MlX;)A% z-Oz^Fdxd;q(l0GB&sA~b5tH|G+IO@%{4*k96Ikc>v9{gwjoU2;%k^LaC>&n$%2p+G zs5HubJbl+#U$+w2&Z|Lx;sCYHe%sJ*Y$blM_jgYDx4ZXfujci3*aytW&yb7pCf;!N zQ_zKegUe6JznTAR%yF)&MjS?{E5dqMb#i)Kp^Y)fJMgkjcl^B7WpsZ2C|)s>m;oe* z3q_K|DiONp80At6Wxf+&)664=A^v6k9Qx4nBWkhFD{QTGP`zi+`+QznQt_-!h224|Lb6BZGkml9kD>R>N zpT_d2M*o{ra-XoBi$mVx9Uv@aYt&tjFqzGU}5mQHpjLqGTA*FxA--7pL zO~>ccLLe~pBp*Ggkvs`wMApPRsvHW`BTbUGM~NF-mw{cM(mTB7=Nu|{anjjqWcE9y zwh>dy!0jBe;fX7kt!Mf~@6)~-`Q)WN_|Hal%;WS)QO}lMZ0dy}CWfluFLM1YAdV^sLE%3A5q*?i7s06T;_n7{|9-GSC;ZTfupw^9BzKs&CMg$#l^? zt`sZ7EXayNoEh&3&c*3=LjS^+w!hu-e1Apt4=rnfNm^POOBv^2;<`KQ)t_iY=JwR* z`Pfx#_2z4674Uba#kG(coSIwo_8(iRca25cDIu#F;!CCSXIkF{#oq=V<_Yq|xsr$x z=5efrtm*Wpy@X6d%q9$0hoc$P;wH~oeL_;!9dRGi%m7+IGz9!O$;L7T?mgChaq!UI zKmt(ke9Dq-hZ_u<6HQ2HgkBvIOig1~*j7x`{P+D|kXX^!U%UNv?lNSy({=~zz>%&t z$zY1}9*Y5s`GRrJ#tL|p1~6PpaPbYn*gVdO`!yVgb3y_rfPstJ!zA}@Q^thz{t1V4 z5^uJCUcqTMc#xa*v$l0P7ZcZQ!YFI=b!Eumfnjj zL$f<+5?D|lQt%Vt$f1HZGVS_#j_EJZcpDY}rR`j2XDie`>j0G%;j&OW@c z(UsPy&NZf!ri3HQlTARoeZq%%d=E8q4=7KzUx4_c1_ zZTQ+0OC1RZOmyPL>aI`Z`yDTZGRYqO!)9Y(!B8R}rshau8XQU&Jy4-$$<99OkNN8CW{)#dQJo6$DO@xxyKScCrnZ`t< z4`#t^Yx+qU!eiJwS|sE%G9Z?t@xOI7O>AIVNDn8gW%j#79ZX7NvLl2bJ(EFO#XEVb zSld`rXtu`uj~5?187+!5jnn-GrDy={bu{19(Hev(F>!)L_%>vZY03NL`&Gc4dU)>* zr|vDO7Y3lAw=g?R{^-;8Oj-T`4tML+yFNWhPGddGid@w<|J97`9ma%UVSZp{5OxT;cm`LQ z)1QGw_y9)4=!9&9hqZl!i|p}F9mF~1ip*Z=A(VZGZn{rZ=F;*!df-3vrU`3Ux@vm8Jp02yh64}S!8xKO?0gL5AF`?Y)(=R$2cBes1a6iH}0fA z3(ZsI?c^E({%O!TX*U`;k_!g3b|)#X-`GF0yOV?r+Xpu`;TsF&A_L(&%0jZ2$a>z7 zthabi@n=~Bma9o?G*pdFeZRDsE>t_q2agI#3ByfMHSRtt<%mM4*d!1Hd6>ykpxIk1|{ z_t6HFyw6wSbX8CvA_zK2?NtcS-Qq>to5>K{V?BC!YyNh_`Uu33hn$R`n4rZFB#p#Y zwdaOTa^Yxmo!QtISI)o8eCW>SFKkE2;}+{Ft|$u3Na6Q{n%j!Eg{9WdMgX=f(yui6iq|1OMneMWZH+hO{@O zRDEe}b97zWQuZ788Yh*JdS9j&ta>{F_08RsRh;7ye{@RA&EpdyG*i{pGW2H(p}e9o zAaez{@mpqGuJ^>PjXA*qLviiuy?UuVe*IT#=k;DRXCBvZX6}C`1BfZigQ}|;8$094 zDFf8(x3zw0?#hX)0w+DEnN>~Egx#0d4QBAmTcv8j=g>hgW;ML0JaV?^*5DyoiH&vg z=!vAt+ED0{(}~2wMa%|)Jzx~0(kj#9`YgYvBpM`Zzo0jSz+4hPNBkKp#}7h$G$T{n z$kaBc#38gB%Bu*wY6!?I=2m^4X>M&>*i?yhWoIYLMHaN~S6%EMIJ_-zM{_p!2+SB! zRl`slkIZM^bnue4w5u#>F(%x}iBZAWAmn$rYw>>S+8mlxgW*#YN@P2G@`9s)_1gc~ zns1~^oH9ZB6{9B2fNn^RZg>p6Tg7`wj56m#k3M5pN`*4vk^c9SRhc%eDc zOGcPkcobes_nV(Z*5Pr%+O{MTh2^)9bVJ=&6tA|3sdA!?Vc^QKrdesx7B_USo>~o2 zqExUX@3PwJ8NG>2i%s#P_ggeTAzs2>1d3sriMQ`x`aLMU7W430(C`}JXU%RZgnM*# zI~zx~Y{|s26O|TyWI8d19?1)sE@I3;Xsu0D$@@~*ujpy|KUErvQpeJr!Hml)d zDsYXN*j5T}8E2+F$7{?VGHE@0Qd`_rloghS%)yUYPUUjH&MyuOq&t?Vrf+0o8L|0v z1my(5@eEoisk>ET#!ROw-xS#-5LmpZMpJEZezIk`5r7{$Oq!mB)QketoH>a{$A?G) z@2W~J9fi5b+OoX0C}|jc90y_8Pk59H}LRD3@K3+au#IP zL>8SdWY=``imcdj4-Y+YeGwEPr^s8F&j?7t|L9CHbEW?75^b zRDi3INIpbjR8=AAd*aK|%Ps>kxC;>`(`9c}Kbta_cRUNx2vu!?v0p1_>EJG*AT(RC zk7c6A%WkhMO=uK}<3vXN7c|9<1wpB$S~R-U7}5O4b;%3>Ht?$|Cu0^H-lr!s{uyz; zzkP4^){@+`mh1YFejl=yE@s;)9~@t>pdl+C9bIVT8EXbkXo|b_aTh{c(#%+QMkrwL zV&2Frwsn6Q7|IG<6Gl>80m_^v%~*5@I=d*7RWx^)9Syhd$Hq9#T#)c}-9ZW|M7f?1 z8&o+v@|v#y@ovq)27$YaLfZFOmyqTT>F!FEsQ0Nlze^rGFfhmy$G11*QeO zG5Tzg>h>GlE3AD%+;-whTzs;wq#1Y)CVV4%F8psV0G*(5zov?4R#EsOu%$9)khXTe zGPYA;bUvFwxwrcJwHpXdPL#lo-|l-wR`ZB>{_NxWFOi(Cz|tVf ze@9m|>Hgd?1F;3=5OE`KGnX)4)i+8nIp5$RlAtGn zR+W+0SRTI~Q(MjM_v97>IhVe zt7uPQm&+=TGO5QkvuiMV!!W3?Cg_=e*I>GP`IIVT zwW(JCyyV|kJyX@&jM|GWerH~{!%9IVt1D<7jGDcl#6s6hgw*Xr+52lq`6w3`m%!yc zUOLJlxun~SEE94CE$K@yeWK7_Iwn@&p>)<C-ikb=O zst;~_UB)(j#1nd87+ojUZP#5&_Ryh#bA(mc2)Gz>je;yjH7jTe4X=4ck;*}NG zxM?)KWeLs3g*v+UmF?4(ej^L+Zb^zxu;a!h{~x?oO;V}4TmfTT{5YRymD(*`S!XR; zT-zUE`!6(q^$TwIHouy3Ezp-jt;)!@*)&fTzEV_oLu^<2M>>eL@L_gfexm(lvDCA!B&L}U)i&e64}NGzmM?1Vpw#n2W{>HH zBFpdjxu6AX6-P5xys|CtXv)+@ZMz;;R-FBw3XYLBBw~bH+(-h0;{w3~C<_ZrRHC8% z^uRYG@TG&+;-%1s9NTMM!b5d@!!2iE&i6JM>^Gp#?|eoQ{r0xKtij5gJyB@A90Vez zRg|PeLlDzuhKsURzy+h!Zi^eg*s@2^mjQE4-8jSz8G$2~d z-9N8R$Y{sVq*KxiX*2hP-|s&K_i~uWB@~e)Q&UqMIda)@ zr*fF$&v3(sj%sRZD|(7oRd_v zR?y?5NR;Az^ zA(;Z=o>(}a)D=xkB*heu%oQ5Py8Rf!lBY<_nCFh4Rk@{S%@!s#S(&LC2^3YvqZ+-| zXAu%ju@#lZ?bkxAPLD*f6*u4e)M}#e$)zS=e2I&42ilt+3ImDqN6YXjA|GCyg?!bn z&^;A5{7$IG=PGpT-pfdB+m69v-mf-kTW=KEZf?jC4{EjYyao9f{cGm(V=c>7=EAtJ z??9B;#Q$@7Z^>bpl$KRQ8}>nn0feem?VKN!=l+sRM0)g$9#vF;WYY7AY(!@S z|CQs1{=D&guocO~O+OCfHZ9F=9sQqr$K zbW_ZQR5u2ex%4q&K_}n@`U;ewe*Y;>v#@i|^yl!6en0=nI5`@XMLi7z+J2O;W%+(h zK1HQJ0w|Uwi@Uk*o0j1I`}yexrOFg>T;e8g?a@DgmR%YwZgeUy>6$Gsu7Z3pCTdY47r7gZ$v;*VFW z5-wXx*bD!U2~le;r@X8*e|`us$EsP zs@AMIE4cBEgk(j{|Eagv#um^{?Y{*LW#(r6`TaYxx1iwY_N5evg}}tdeXU36j_sz2 zXn;GE}T32HWhhwD$eOndnJEIP(c>|D1U3f{TY39 zEaRA71iB!MZIYO?H{Su4#{amrt@$Z428bko#vY0SXqYf!5x5gF7o(tx>EewB)C3&{ zZJN}U|C%^t&APXmC*ly0OKQB8z(@4q627SRGlcwlKV_^1IvrXYjbSKQu$i%0c&f*d zNm4MxWGi)cP*%YVYo~Pp;{Bc@|7!`|em&pZ_86HIN-2jM7k>3=vQX)HMZ93edF*B* z@*-JG3!gnxQBGf*0Y&vGcC@l3KX3S3t^q7N`42ocv9zjx`Ohik6U`5gaGdywnhm!F zU3^8UfhHCf;ip;ju~KtNI7fxp2}4ofrD;{25^f03<UJAT<;ERsz$06=PBu6j8Yn<7y|?Dy-&L#OYqCN&(6Ue_{vt(i5Iwh z@c?9wKgElb1WABYOH1>p)kAEWnwPk1bt{_nncYp_p=b^`)}MwxQ}wxr?&M=DU)bhH zzJRk18Ye#@bsIlkbqGL5%C`D9$0}>aeEgtN5+)IT2VTcae9s>x=yOT~T?yM^y8#;a z@8;4ch_aBPDtmLtbCKlyec>Ys*ux0K4@W>>Hb- zoTzPN;>{;ROGuG9LNW52E31Z25EDl31_x`qR@mH1owBxscW0ZOq0F{?h-Up zp@fCTVz<14v97(o*T*l}O;ZBB9#;W7C)X6B@N0BO{E#6-o@})s+wjJ-20GqzRHda; zimHL0qIlusKuK~j)tF4CJ2p<5HgW~pnoQz^JghDSbs3Se30zRE8a$EI{c3UMXF8gz zHTRNMW0wFN_ngjc(tk50_BE$g1UkkWRo&hG-&m+#Y^UE7UF@W^;2efFB-q6b|8GfH zP~D%<^#``9FY>UYQw#msEou0aJ%1YC_6Bm~2e$0YZw_2Go%7~)$tV8-%w~IB_bp8$ zc(5c$|0?`l3>kUNM8zvE5*%U*^z5+;bvdTQz zrk|0BRxlL9cFSPo77U|$dJl+R=Z<|jx-m$Vl@4K4K;&qz4jQxqRkueC+K>=ufA|LS zVCevSOtZpNQeut!v{c2#{ppzNcA%mhrgF*6N9@XLc)KL5m`0`8#g%?cA1i8~JHX4o zK|&08mA@3nrYCgp*JhYga84}uGxk_P11loG`wK7?aw8_hWx~4%i<=7dyRi13`s9EG zd@~z-FtD?UnwlWHx`Yx{I2i5{bndhoflifEg*3<&(Eh5F{dRhZh-Z5 zY7EO0OOm_|53J`?ONfZE0d|5I+F;`3h4{ALq2Ife6W3mHI;GXF8T19)exV#>>P4$k@bnLQ7MrSsP zHRevfynH}L5VNlwnJ0|uE5rx+`V`ZpMI?(Nt1zE3ZLatgZBct?h*THU`(CGbv;=cq zkB?R6_UNjn09UrS8l;;K1$H(@dJ}F}6>Qa5@J`7K4GTw@pGC;A&9A}()U%n3sZ1Du zdn3}HRnyO)*MBWPVy}OQe5*rKYoR$#K;W-$L_Z}s{Y&R=^5e`y>%U^E)Id~poH~k8 znSFh02pEKRImwI~@0c_aBIP)^!<^sVni+rTu&PJ!7lGF(_p37IZ3%5pCfnuxgR|u| zv-%xbLAK6q?axiS0rg{0V+nBbQi(sS49<(mD!|FpKyRsw0vd?+F3(pMAA~^6ZMS% zfZyqx0)4TH%;<6{S)dD-YaM_gRWdD>MB!h~~9k>6|iVY&~6xXk{{ydSfsUH(UCEL8^nr zA)#inF0+f2pgBDmb9)Zp2AFBA0yKE_=KL6%Lsml!@NtXG&sUYAIn>sUN8M1cA7BOH zMT~`1l}8Vzaj&l8TmOX@oORaxo+u+FJ|2t2&dJ&jOr%Q_Q#H-jk$^2+U^zCDQ2Q+WHzNdO(0#C4mcZrNLy~fjh{X{sn z!<%i5CJE|0b;J1kx3CZtb2+JrPajj0={9wLm&lHWE$w(cv-O!+7s7z6FU+s}0k0K= z)1>(MWJ`yx#yq0ylvdM8p#OG?9fHANcj`yT_x|Jng z(IjrNE7@X!tXe_rq}8B?ih_m#hCL8W{4gWaZ98y}NaKyELy2Wze0<9HadVCoo{qje zs>}OwCubvHe(Wx&R*at6&p$S2hKPvB%F8}--b=sZm1JiqYRS2CkGacIRa8Az#@G?Un}E5G2Xim>)+vdOp*&;zll4xu(0i&JnYsxFYYW%uDn!QJ!PPE!3&UB zdl3MGEVKrj{T@7XI(*W%izHTd@@{Y*#2}#3XgZT})&TYazhb&xnYudp6`?5>q=om> zC(++>(`he9$qC9hVv!zPivuHf+U_9xoVhvHoR<#r>uVhtE)KSi#-%ZQcm@j`z zZHvsdgj?52={$7VP7ULAH=^5;5$_*n*Sd&2&FE(Tvu2M0*qZ(v7r+g-CZ6rUMQ5$i zpAui<~!eEDcGE`&Q{daIUt`Jed)Ffsw`qW?0f;Qss`4)BWbi za&GN-8nv~uu?B%Eg0fsllEfR^%;*}?gH22 zqPsXaDTZzClgd)0rN1!9T%rRndqXL4BTn<%vs?7_IIH}edhAp=SXR2&yP^Uy;U7#T zq&j7aesIZJ-rZV4m9wp2EP&OlPJqtkbec4Isz?Xe+&6pAsqV_~M})U8pIQVN^zae- zvmkQcg}fFqcr$p+e8^(<#!BncWHAXMXVDkfxuJ_Q6`5m3A=tNlp!^&d=pSY*CuLb< z>gnx#+CXcXYsWwMW6FFG1}4+!o$o4#S3=sItcc`(KYgT-T;aiBx312}#oH@0XE1WY zqDR%ZuM9&)B2mF6IV^E)o#-6oX&jCc_`zJ|xugQv>R_-s@QXg4#Z4Fa5Xv(Ik~Y(s z)UG+>tjt({$9DaLPWHmW#402-^!6g~KQE;IG+=wXMuNV!d%6MP?ZeZE9bGP{Cw9W7 zaQa9BA@Z3qb02?C2q6|Jft}qw&yb0`0)>~k+k=n0kOO)pmRt3ev&7~Gdn#_G6{DH4OwVPunOia z)VF1klUtg_>OY5W1uph&>m&96dMxg??~YM16Ycm%*0+%ki;6M~<8P85xBhg@#vEiK zn$nUUMKQ-udzM9vQJCZc0yD{@0NhJDK$4@=BTK$O-!x-43{_Rb7vf~{LY-`q{nM7I z=YKSwkt6(IDB(jexgh^nzB~#dgjrAL+{An^y;Rpe5XAHYOQftZF*qZ>R&aBy@Jw6* z8bjvRbEz~Vo>jyzt}gH`Wh{hD?YLUI!YhW*ii`As{SS{OUI*9I@-VNbWx`!@Uhb}O zh3A#>11GeA*Y=A{Wb9z%!sYM&6G;`y+ZDu`XEtVqO>;k=%%|5YC(}Tr zOG_@R;z)qHt-@yO@V^gl&0Rdqi-gGZ=;6avLNkA!=krCuk@CpFCzlK8FO9-e6Qttl zB0D^J>$?t47(I3ahu7PWr{6cD+v?tzGO}|37JQS+TOvxfEd+OUv26(A_nW6Xqsz$y z26X9^f&#-@B>v-9EOB*YXEnL=+z^AHilYr*wB24}P7t zk_s5PXGfz)d3TR_$iIHMYoB`%LP>hLL%1-@(>F?74e&`t4CzFF(p?eS7u8Nb#A5H! z?$4p64f?it`KO#rL)RAg4NZ;dVKgpH-o1+Gn=hP;N_4=rfg^rTG>}wKXn1xU z)3fRIUsZkDZlm9rSmclqtSt5j;C8q+cF=fmr`qf_ej_n>@@M{ZOrMSM5^~JnOW%>~ zM*0N@(&YGY4wpN^qsn-UNnP3!d(*9+Z}kgMPMJ`*QCNqAuPqy{5m5(t(9Hh94XoW$ z@hLr?LdlO`bjHz*@DEQ1s+!lEz7K8}6_td6q)}8ZJk5AyD3{W4udWWHrf^*mDDqemn27A%n&#DZYYH^jDSP$Gh#VdeIf!&k z%8%GBfnh0cw;Fz$?;HjuFLt!FYH1B^MmGaTOD$ZD;e%MeJL21%-1KWaOAaNwTDv3#C+df-Qkol0DBDMvB)lW zhhLJ%IPMJvV>>fRl?p^nMPp_)$OX z!k(j4eH{LA@OKT~Zz~En`TVW$#>tbdR8nf#h#NWuDTgnDbpv>fs%$}vNs@H zUlLO+!6{>&lJW}bJX<;;$TBfGhsLSUEMIKmTRrW2nGYd@f1bym>+{#|6jqX0G@U&| zeSD!D=b_zCJ}Xb~pCl2!FfpYHVNy{Z>I7SQ0sUHcIyyVlV(6qLAp4_Dw8$ZFL?;5L z?Ep0{;8op|6bmeG!Y{tnpr?OjL~6-uGHKcQ+Cmybxpaiv?3@{cK~_Zb255wnk-wPIOqEhKF^?4UaT73%5Lv^$05t+4Rh5Uu*;x;{LdL|V>1MVb^b?b zJ57uB^I;Kx@TYFK#dzm=8rP9fe0CP}F;TwiOfBRr<9OG9+Qn~@>Z3&_ zsrb))TT1rbA%?Q(NRzCqfe{2ko^Wwn`vn8RE0_B}q}lj)tkd<9Rxs`x;E( z?dC&7E8-{ZD2!)e`a4~IX)p?&U%`iImbkKQD0zftNxS_HFYv8BJu@=2qdqA9{q@A5 zqUWgQH(07|GT!;s2j!cmxWamSH_ar(x#fepmZ>kdGY|W~g)L9ZOqa~2aevNOfTy19 zB$@%?-eK6C-wcQHs>*jWUmTd$wZ9B3{SGNBh%BsZg5CelLKG^eT=!g1KFDdHCSA(g zYW<(fhyN^6H~T+>EuCwuZU(Bai4%`#vo3v5HJ(e156d7t-#e@j9mF|m{x=}adtqT$ z#i_FE^+Lo}n_=qi5XzALlA$XfviXzw^TJsx(Ntl*wLjfR-x9!;P~0BYSJgGRGwCx5 z{y0HpDv*!&_J3LGY#prV@gDT83R)DCe13gW{JrJ=e!L+iimfg|UFGyJcedWy7C)&j zB`*y=L3Rnfv&o`G6jbp^hjYwkk4~`o60c*!UUk<%{tJ1mvftM5uuHsxltfaG{_J=S zM%ArcS)SuY28Gr1u{|a>mhqy{oIjxS==*=S4IWwbvR=+fADd{JY7mvR9-F-GNm^?R zH~izr4Wvi!DbRA){0df`&ArA>iJMiGHC2;}HT83j+umx!mIdSS@oa*E@(Q&oD;~e* zu7JjY?r7K`;tDBIdL$K1-PnmQMt*$V_q~`xTE13g{P6?EzPk~IF6LQav3G2c_xXoZ zd=Bpj!Ry&|%LOiyE+n8Iyl`47=S%=KX?SkVNoe8h61y_|RghY!jd`P-oZO=K-soiK za-CiWl%6K;=ybS`cIxMFZXu*A+M}hWpc;fx_khsZ%s=_I%nCAdpVz`htrp%PEl8rl zLUBHlV@Z}*bvZ;p|Sc+2furWpP$J_oxUpr&EpQE zd{f8q`rkX{!ke~+#H3T!(V?S)@=(Y`nv9pwHp&1n*XI@ClVFcA+ri5bFit5+lnTDUg6c!2#dQjx~djNM9Bpvjd4^0GD^WsuA4LZ;U`S})J&!! z&@*=P%BeYVr*!?w1(be%o-%NnSomKoK)kBXcDKVK2o2ExovsrdMKh!uM{5vnGHzyT zORQolYU1f0_--JNHd5FdyMB6fc}`E)ksV&S7 zE36F^i?}qaeK2s!E~NPN*PX29(cp0hSGT_YpXwU4xpCf}`DCDXt>rKtH+hWy=Non1 zjv{9zJuK{)Xy#H#G!aYzM;4qE-8n9teg5#RnyT!*L$Gm0-61! zGlhSTPHlnFk%MwNW?xK9bEZ87MF7sp)8j;y1|$G_a&_&%pA=Od1qRKN6%25iAdyxX z7GAtRNWmN!v9aUTS!hn_o-QvmSG8T6%K3eOf?58vY27?t8@w$$Y<#mOY4c1oZx_TQ+>T+Q@fcj5QY z;C!v=Dy=e{IG;l{BXYJVIXT1}r&#Z@;Rh5Iaf_wl%pXqsF7<}-(9aOo+n2}Ib@4$> z;GoOho}j2m@wpr@KLt0#p>obhV-k0b~G`YwK?HnTYv zgOcnu?YJ4F_~hA%_g)k-w#RWnJse(Rh{s0Ze_)iwN5DcQ>|Pb=QO{g1MG&hfBzyNG z6!X{u)tUF;{M|0{J%1@o=Z+7@QISo6z2C}=iOZZAV$0WJw!?O0SS{C0Q!EV&k(;Hn z*5>p~u1nyq*CSBBc;!y$7AF^cvtovcDND%`4Zb0jP?h@1sVf8>LJah%s`S&`y#!7km@d$jPuj zi^oY#5Eex5$7JB<$)$ecX51NliB z+49L5j(QnNI<@H)1z#@#*ubcNGQw`dk1pbiPDtu*@-@xA&7kj^T4e4jnKDLPHz z`774rd$l^DfMOZJA#WoiN6v#;wjGXJ_N$T`^MwGjHIdnk%8->ZF;+V%NmKuFGXCr` z^Te7HfAjTrlhASYs5nMFP6{Nr+RaI<|8>}veJVY3>T&hxU^%}7(cLl^z8N>8C@LRz zQ^-GWr>jNY+9Cyp;_e*pm^v+S#flDUn~%AYA+pJh9rt2)UTszRQnPvYhVXG-n?*Y9PIoRqjR|7 z9}ztsn{elK$%c@?>>T*U>CYrv5H*ph;?XDdmpXG2JQzcEx}7Hrf2sSEyC}`0Kwi{y zxgmht=^4>Bm#p0&$l*;QQcMO&Sbf7ZORi&_hp6>!ay>rhLq_y49i2_~wZ=sw7mwgm z&9HQ~NHbd30qo9*Q!Aera1gAyLF{RSz!H}C^733Mu^YL`UM^1t?G^LZf?_i0MOunm z(R!8}^FY!TczBt{mz$h>6n(LiB!D$78R*FF!baY~4hEc-2ik<3lY@H!n9PZU^mFzx0dQv-F>Thi*E`B~KGb`ke#aB1rskni7 z2VgB%YgZhVpDS(f%H?L)op>^${&I7mX9JHoR>;((V@Txw#x7#o&SYprJx9Pd$6#$X zmd~^0->ms_mt-hefPc_P4VqN(7^9yjr5pBN35my6oLf3%PQ#P}@x02Gn|e6V?@r7bEzKOIP7$6(P1N%?M( z!o=t8ZdV4ZCJ*8eI)a^}=i}WqR@i5Fc$TqYml0G)9Kk*+Z#m^}k7|4{gol@FTDkoT zUvTh)LYj|tUh$A_ZFL%{UcT! zm=W-MSaBz2f?a*MH2I8&L>Y|G(d}Et>@C*JuzcDSrL!R)2SoOMqGs3{y)@ zy1+QI$@erCFla$k-9s=;)Cke0A8HIT^bwfT$D=b_NXsyAx#8FFniOr?!U{DE8JvY( z0VIA4Z(1It3*QjK; ziL{AUIWqlkK9)o6JqUfC%dP%3sQC#7;PCj+nEZU;c{@$-+D<3&8!uiWW;1ejdSB9i zJwVFso}8-T6&g`cBu}!kGzQN>-Q3Kfip!J7-Dd=*rG0-;S6g^JdF9G2c#|!?+kX%J z`ma#O;t)(H%+5q4WJhvJ)**H&2C?$T-uP!w4>P;hyu52{Jd0}6qBTX}p}_3BwD+gw zXYA)g*DJ@z3Q3-svM0KkBr2HrlWP~e;xv3at#>k_(e8F_A2Zs|YW57RX*D~uHq>nl zi zE0uIf6mnm08TrCxQGAq<%YXs<6;|SSyZNgqm^$S*y`#%gUSFBU@RS0FmUH4i#8>6> zVuo~W9dEjlj413zk`;03-Y;dt$IFb*New}VN4G;%a1;v@xpkjEMcy4hVntr(@@_6W zk$1yuZ*|f!-TEk#qsTfS;0S!J)1EW=4)K4!kuM{9chu0jyxS#@(m<4G5dDK4$- z>|liBY~XzXlPQ8wWth*(H3>>m{7ZejCj4F5@EI#@JFC^rPEP>4{O~f_of8ubny%%aT)0SK4J}0!R5J0*ENUdUSWi|P<9dRWb_Y2c8z?DkRa-rfX10J7 zXu6o`7GAuyp%=oAWNI>2EUYe%{CPQDQ{_13S8F2s$CtvoW-sBA@XDXiUBXk>6}E35 zd%pAagl$SWI~77i{hcxGdQ2)AgqDBKN$V-sJP@Zh5)B8KQ`nN3?k|_6wD`jhxi5O3 z3s1GS4f3R%a|m#%T)^N^-6es(`%(;KfV zSv;YaC-4Hm(u~$dSKT)}UNv4A2Hs?-PljPFC2UfII5+paCkj8+S=jtP;nS*|tc*xD zRx}`b9j~*<{v;UztjQ9X5Lc6k+#0A@m#h|2CLl}f;=#;B?|!K*C3vMB23xmWfxf8u z%HDL!HQGa3=m1?^Ysa{9K3H}6`dW5fs7&Jw(8~AraUmp& zthb6yh;OLZ6e?dLsu(QEx-f0nN{XQIhU_oK*@^@fLSdBN<&ZuW>^yo~|IXs%VmNypLiUy~@DR+W?tkR^U z_>P4YRHEyCcpVMDZfDV-2iPkC=*kUqxiO%s9i7rd$dfe9)>-I;Qm(^di;{Uy^vL5P z&cX(-v`Ou>11fzpBq(yL>iXvHdpk57pj&N7j}nqWGOALfJs)p;!Y`0S0h`)QLuoPP z_>XV}Jq9|-X{#UF+O(zu9jN|943&_%wso9sGA#}mHWl@ahsVPeh9@kt>^|*bjrs^H ze|zl;$9Lb*m3SlRM5NWU<}-;pC&IRj_MHcQe=fsK5^YKP7Tgn+H^bGOX<%DoTZabA z{E3Tyz#QQ!od#&oq=D}usYE5RO{^Vq{W?QgYNs?(E>^sW4O@l>Y*FZrg>nR(ljdMv zRgSQE-pc<-4ZB^DZWfvzeVd8fkM;-Z}Gp!P;%8lWBk z)1n`4_rs)J*WAMfdCZjR%cBehce>Q?&dGJn9o8^mO%OkU0r zaD|^2;Fp;wl_DgaaI<&=tRGD8Om1KMo1&9p*p1FUqD^3ML5E(`;I%}WW?f7HrY5yW z_ilR2X=iY%pd!}q93D7Jpv!!3cdZ?1Gj;LUm3?duWhpmg(A6uEX6#eGV_20L=9Qz5K<2{N?r;?4%x$@O@E zba4gtV6f2l1!rsVK;%t#+R1pA6UV@wg&BCMPp}|{@c5)d$Siaa9n*#^b2d4Fsy1V4 zMqXxNBagUXf#5$wc!^`xaUAW@^c%JjN`AcKnWg%^t!-CM|BJ8_DEhPza8OM&%x3BI zEv0FU1LEV;5KAH@@>PtT1JI=JjqPkM3jU*rJ}l<0~{O2;zf{q+0R%Q}Wy30#=W3vzK%eUh_!QB+C&OUZAlyZw8z zv$8eQ>>}G#67y*8(ud5)Gattx?wO0D!r&+DZ6@=Dih}4h>6OHf9b6KuJ&?; z(1xf55_Ob&ss*+UiSp>txultq7+hG`HX5g?avVP?;X;pgU%o<2Yvk?De`8j{%*ZwR z^P}$O+w?f?jT-~e#y7jIO>sT?*2A{Dm+qk&f)sgo2+Vp3gbHUO`-$f2Xq)<9vUpbT z^U;zvanQ)Y6VV0bh=vHEU&zG7w(?cMn_pbL6=QifH$chIL{q0N(eM`+%3Lj}ZGtfA z3bjHo$pc3eFNj?*mm;ZKZ}flZx9P=-P^9wp|ELqtY`^GMQ_GF*hQ~1Luq+9 zk#tDVVx2WO7xv3A(7_T9`g!n5>i?l5+KhZ5pA~I`d;ERHoi@GfsS`!8>TPr^7ImwR z4%>#eGJ;SxS%EULYD9=V8k+*B@GG)JK^Mv90DVElc-XFnpXm>~d!Al8i|c`Nrpyvq zJdl4p{t_{ZHjt_7azQN8UI#PUUF>^|x$Gc$hOPS_dHT{s%G6j>EA|GpDBXtWfBMnB zUt{`~THKzQK~P~IeM7v?UNk~@Vb9Nse)^g-im5y<1Ips0X&2RU;4U9-Tp}wiV?0Z( z+Xl05d^%}1(N;K4Evj^H2cc1W8`Cu10XbA@0ZE$@AZGx}63%fB(8;>iK`>O&4m7(GDWh{2i66UEDB#&q%>PF6lip<5W$Vkdm1LgUO#?qx(XYMy-SY zX7EQoK!id8zw#$Bv%2b^5q#`XO?8mq2cX50W(stYoH1OPzDa7%#6q3`Fb$IFaAM|5 zHO`N=4aoekiH(kC4}4=&F`?s$j-K*~+=|VMXqH|{pEQ9s!pb9P!)#C!!0oy%zut~D z6faipF}0fbgRsBhvgC7OOYaea!~z3rmJc&)=tEv7@YS8nu)Wh@II3!eHY`_Irc82F zYk!;}+n2rQbJZOG{=yc) zWLNngHrx)d(GKYHjnf-E-Hjg({JQAJRUIN9KHG}y+hO3ZIQqWN-u_SO6By1P2|iMm zrP~;xrV~4ij@S62yxK_FSqBs)Z1vhXe@n{^7RarSTV(}Hzmkb|#2)x$BcFD-z}n*@ z!HmKEnt-*SjBeRv#UJ_3qp-_{h33WEK#w#v6sSZOxC3rWl$_2EX|bmI8f{Xr!R(QF zfX4GgT;AamP_ft1y09+NKdSjU6j;A(wE;3%C>u_xc}_M;ZJ~M=vJvQ+zd_dYp-=?H znuWw-a+|{^2-iZ{J{#1qP;!E@{jAyo*oOAgnnZ4^*7nClXl+` zj;c33{qaGtwa$vlguoi}WjCWr8lRqN0)|8+IN$bzXEm!b_*J&%QC|f0mkJ!bLu-Ta zl+m>c-E$qGWTVg$POPFyt>*u(F;7+CQb2?X4aJqAWEwEeToazALewQ=C`^ELhTC|Z z&tV-qJcEgVc!r~TWQ3}}uVixc;dpFO^6V8_6Kavb$jV6-jXOud31R#q&ACejAqc4!m}6TFC61S&xf z=#cActQM28OZ42BWlb0E?5?<>PuvvG5%5d_cIdd7?*W<}*XGBt%1I^WqhmMTLdW{* zBCWz3iC$N*I7ppnS-=o5p{b3SuA`ehYdf;L5Ds5ly9CElfxCqeQbeIs_w4WsiW6ul zMkPO@&D81Xdfc1l_}Cb&Dz!U^U?zP3d;`y; zAGeBi;>j&H>w@dR-#k@@91NgfejwuS9l?-ZUP;%JOnO2xG-)I$^4QL!eu$vG6}7j|-Cv&tQc`LGiBs0FctAr;l@qa}WQkgzfaTg~4e%3{ z`SSLs{fNp8CzAa}BR7`f!n8Y-SVVV&bKiE$D|M(AST?u#?V#(8&n!(IR;D(XSbk2R zKEcefYiI=nW_hL4=lf-tIA_C$-5L!dRFcDQW&v2+ihRnFs37}hBb2-S#Wa(Gck8br*NKo^&(;(ol^|M=GmgolN0J^pJm#6*n09Zl% z1@?hLDk;YtOFysR!sxMt0IzWI5GE^I{>Cca(1a_233n+;HU$M)-E*F~ zLVjqSxg$S|y_vtPuud-`g~}+FkSa>fnP2<+Ee)XQ=>UICm$5x=qX#xSCG52KKGf0h zy4r{UWid2ry$mHUvPrHA?x&Cuo{x#_Sbvu4oNx7ltyW8NW6r{5Ma%ltOLhjwdN! z8@WH{LnAJ1kzQ|hi7V^FO7e&CeuODr*-WJ>fbYyrmp4we@OHZ($6?+uuQi$W^g^Lg zz9>9ssI)>9j(S^*sC zN%Q%ek`NUknkJtyiHUWM-UF4N_v>C27AVer&M+;NFF->1AeqI*=DmiXge#W2N=mNB z?~;ajp5|BvMu!`Ncej`12`mBK&u19gQar`V!2Rh-;-oq$8q)_) z1Z1x84{w4XrYg<+ol<=tS?-Ppp+YIi$WX<^)HuKSS)y`>le9)JgUuG*T*4tUp@j|mo&=!uHUrAYrl|rl zi=aKf)8_h8Vkebj$R92@x(c)&?7k9L?rn#&=Np&=xTNgZ1vj(F_}WyE$r_3DP7jqV zIYHFye#j?ME#{Mw?nQ(oqGKjg>Ic~ZHJW1{i$zFPTO14Fu znsU8J-ol6*vbOh*+1%%^Wnm$L>@+i3L%u9Uvw)k3G|j@#TIZbXRpI0lSLIHV|AJYl z<4ggO$NB^hQlkPF!_%8{Ln`9MyS@|OOL0i$i5Cj-!mor#nXin0GboNfd5p&v#iqwy zG(R!$s)8>rIr}J0t%k`d5wm5>6sz(XdAytWCLS4X;FIJia|6MW$dWR`FWDi^tqFwx2S&Z&hQT5C#)Y~S@=a*86-LtKw}`XpEZSg3d&@e z5Q1?mdz;ug6XoClAjZ*B*YeML)&Ahb_w6GDVI64mYsEQ<<4CEtOei|P-61{!Of^q9 z){7*Z-t+>IL+M)=B=L|!z5-6$e#c$KWio^U_9 zkul$RQbe&}rt3mjq4QbFCKiL;**MwWbMDEv84_1NQt{Ov+YAxDP^c<;Is21^TX#JX zI4weFb2Uf2mYe)zH9hlMZyz`ztk+I<2t)Rl%HYQooE{ggq@1HqAiI&JZK-p)MB`G4%WA_v3xg)1x{jhX%!n3t9seLx!0)SzaRmJSUxc-R!a86cyXJcW8@Kia$pXF2YJ$;9-_;x8(C+G=AR23hm29b|BWr-dH_mp)%; z+8MMPtu=*tY>l!a405&?2julT`QlOtw#O3!dTW9Z>C70w6Pi-_am6?e_RM0mzkgO+ zPZav2h7^9#^}8~jF5tVbQHXF1_C){zNz`q=9JE!oWJ}Pn-%yHGhiXy8=F!Igp$#KdZ5KwN}4*eGV`8f zdEj9Z6V7aG&v0`)RiaKpPuD|xz@^)Q!p}MO4TzgdPsa3lT%`HngQ`qIA?ugQuPrM- zQ}fOm_}O**d*_+gBhDotD04(sYN*J|X@`PZibnhI+b@#b4QW07qip4$5zYU|DV9Xc zIIoOfr*x6nYZP$4`69Dr*g8BI36h(ti;fo&zq$N&LkQ0dz3(ro|N|a z^UpEmny2fFudK(SP`!kJe}{oveNkive<`_W26?7jvhCE2>C4+zSM#KmNs=@Q@wM@1 z0RMxz>Op!vyFU~}^jrdNfZ*s4bFL7*0{3m$ws4;l1@7nF5g{xBm~w zF%~j|7ri)ItICvAU}ntn3M~+Irks|~hXKH_T^78zHuMgVkqb@B?P!0UV~oJ(&NWk| zV`k$K8aW<@#NZJzckl^+-t~RkzXBEr6%~xo`xImg!Jx46b$q{gKuq?Wy3_jX9L)D$ zJF%8G9VY(QO9)CJW)n6Vhz1M~5HLoupc7Y3I-u?9nh!eaZ_gBTBpv-?O}0lo7a4h2 zEV{H#F3VDlq<$?=IAqM2^1dvwGzCpTF*m$X@=OKx7W%qIE&>UKor5U^)*@}jh^VVH zROo*2G0=s?c+6MnctM9Su)A=} zXnV9?d??YA*V|NNtxeskN`d`pO-en%XJ^KpSb;27y*8Br|sO8~?r1{1jNPaN!mMnigQzS759DS4>ZaI9v-rke z=|>W9Pe0;XOQ1PYX9$Q~t_A z7#OSoPIZE^+l$HjD-OWJr?40;;%ZX%b3vEzM`e^>@yvIZ7Rm62Q8xlOPse?C`prh9 ztHRw;eG$CPzCSM;AxkN%%e)V1!dv|JsGCTH_vcV-_s5WD@;aoI#om!^CSZ8~LG&## zv+7Ck3@0(_6+A@4{e6bquB z$~-`Ox`Luj##Rh#wG+mcNu}M^?es3N63YnO<(B_&B~bj{a-4@l#mMx(c8C?Ww>v*A z5AZYtTgL@l4B9wf+vJSzbQOFe3ZpFfTiQyvjtKY8QtH0A+SA9{{i^?}qoMj|sRI6n zP6ofUl$1fOPQzZ@I{w!*%Jn-cC7#ZLN|#(}5IR}zg^6-)9bYvE;(UJsaPiV`b2E|bIZhq~$=e`#8F2fRM2J?+i~5>w1imHTtUYg2)^pIV5yBQ8 zefIVa%VFAt1vdC6DXgfb3a5LrEiJ_eeRL_QEPBw@Ue%fgDJrJ`O0de$0`f8&S9S2s zw*4Ak$|VgfRBb89mi}}u@r&eOB(?QIlk@pT@_H-Rq@PLJz={raF?O{_A=^?;=_|YF z7vUICQ}cDUax<%{-T`i=kjVHihqFH%bQEJ?*=LHVU(=7*y-0|nXuGcyKby*J{*G!* zAEaPXGKp`+Q*MYZm#e_}txF}AL}>AS#u(kjoPqR3suHd2Y0?#E(w`5dU0#&pN_>}| zuKUIikAPU8Bx4?~`!IMft!q(d^rf?Q2}5g$SKM20QwV72GFjpDj_dzwsR41?t-y;L z&ED!vaM=q}Ry#aAf$(;?MB?hd&z$$nUJ@kq=B1qVLqc>0`@na4yc*9Z-G!x8FcL*+-;P81X<9M2MGay(pi}1#;QR~XCSY-`#+q$Q*>nC7cJcB zPN!qrs94>xZFFpP%!U>JV=bGkX?<`0~Ala0f_;>sG z*G!vh;utaLdw&5Lfy-3aPdB^@`$gWiHB2OT#vup)1Q`YBT&}E=7=<_USl(l3v8o+R zXDHepp^K*ojcW!xt6JprIxD_xR@MBp%a$hc2K%9h#Ps~}l9Qi{_Z6Wj(nD-ydUXj@ zOE=Aw!{-dq)Be7K)Pq!~)v8-u(*z+Dw~V8tunM_R%d#&9WKWQD?j_@DU|2-O2^F3) zm~s~rwHd?Y!n?OPndq14(2~aq#}LwG0hzgVZaQ0kB_q@G7F1W;RSY>}-w0YUhqG;n zwv0#ML&JpdmQotQ!OV}Yy&WSj(Zv!Ak!5cwgKwE8Vm#%pUN`Wl*byOzpe_PlctiI<^M(cYo)DCQdEt$EKYs` z@_5p_u^}Zw3$wu>)V|WUX&<765tf9sCZ+wEnn>4me3+))vVRs|!DTi+e7cOLBy1+Z z4)$wr4yTJTknXiaS0E&y%%bGx0JS!EG3V#|-!ZUdT~-R6KJ6wmxO)YhPuoxTi0t2I zRQTH1e)F;pPb+O61|K@l&Zc$GB^R>2|8@s!+na~yx^^Apm-nr~qPITaZ&Uu5J(|8; z`5-V*!ECv`ws|_TbNcQh4H9~-QhFn93*LyBIdjx)bP?WM?OrT8wtUTgU4aeD1G;C& zE60nhei2vVo$$R5i>l(^jV8+%M>PxT@r@70A;>hgI)S)lW*#4BFd#A`YrGeA^S6Q7 zY-lA!WbQx{4LQ_Sd@;hIN9_RzI(u0mRb|KhQr4(J z34l_;#v>J0*!aZ8ACof@EXHWtlGiUVx9M3##L(Ze#R`RLU`drqe?Am1M0*I}(rB99I+IH$nm14frnlDCDJyW>s*Dl)_#yy@0}(O?ZJ85E-wRYWi#Xv01lwcWkusk?{WSBw=yj&nCI zbNJo~RG?2DKBO&w>yjz7-u=#kX4D#LP9;IwZNpO27b8%?3g8xj2DgKEetcbK`NirL z?>ogxOkI-Z_o578OqWHBq9P#*yx@ECNu`r_#6 zC>^h`2dCW&JSAcQ)n-@s6{9e^5;c|^c&I5;t+i!gDzTLaD*) z4LODdzOS3bNMvB3jt-Xuun>U{1=%Uwv5iKWi$@VFD^cs)T`6mKI*P&9!Sgk9h{O2; z2$qELz8Cp2VR4WeoD62R{|wX9bCY2WvAgoPyp1R78mc|#Bz-CGkETU|B#hKd6v~yD z)*MN8FAUm;geD=QRv<+|P>F>mC@z)lEZQacTjbqx4k=L16q~-Y&uU(L&y3hfhDZDdMj=Os@&I#avYeB`RgL zt11hwJquYF5&(h@dx!`+^4Cp}Etn>FC~}Xttp;bdu0W;YIohg02SXQ0gbZ5 zVqv*d`o~qi&dU!OAUPCqgdOyCp5jsy@2cvOlZ7r@K2AXvO-X?*HUNWTUJ?wG>J2P6 zq~fLIw7URCA(>?Ry9gg#ZthH90dA89|MlqL^VSAmGy-BNak7f`WC5|cHk%L+k|bQXnPu5-sDY4%a?<&izmHayL* zU&K)K>;u41G3TITay=#S!68Sh5gIcQT5GgQbnDs>cbV33eZ%H-NeqK~ncHAhe zxeD0HdoFDcb*ij93@g?e|L~x?5|4Z96yE#BqvC?q`Bb#J&9c)X=zYid@#FWxy9z!B z3~w4BT^e;BgKi!Sy33(P{hcqCudg5M*KhyteGD4LA1cwpzZHWx{TJy7JWQZ0_A^tO zNt{GVNtlQ{I7_t3h}n1Gg%iY{D_z80N{Ysh1b3!FtvSQU{EhzL!lse>5}`hQVBU4< zu>iXNydHN=WnXag@oN`4VFL`7!Gy$V7!N^&Bq;0(A~@BGd1ryA%JAO(3e$BnS(>Gvgfabn%~%s;0`?qC9rE%5#O))i*J`U z`)*Vjg7Q)Up!0ePBLPax@VF535Y8WMs<{`ev}9_mVFBU0bJS}10Ra61=6(b(G>EY& z{!io71lC1))qlJ6^^Fbj(l`-Q+r&oq9m{qJ6`>;?! zd4^&JfLZe$8HJK$YE3?i89?Spj^(Cj@ZjQ)M3FJJ&c~@wzi+HIDp^Vs*vnB=Fv7hm z2#O=ntrTc%Wpj84xVgj~76srY1ZIP#zk8oJ6R8NQq~hqH?0v3MF$d>(Un#j%1MWR7 z|Dj%F_TeVp6v#USn&5x}R@o~1CUW!2M^Q2waA!zed|s2^Y}kE%_p>a!Jy5ng zT>xHJ^+e564g(|d$T^NVI^ z4td^Oewd1Ro5xw4?sl*G^dm(9DbY0ea*-jOvtseGug3J=vZNnPO3O1nKeOK=Tz(T8 z$?1*JW!iO2q6kG0c6dRL0{ znPcu&Xl4PvdNzqQSZudKSg^^`VQSUc9)?c^J{58n4Gv;!RLBDZ)?S`JCqM1I5jH9l zQ!AI$XL#6sZf#QAUf8jNMlPB@QywP?3l~{J$n#3V0*D}&qM9ai?2e@sy=O2BBXxO< z(CJ5FeXgdC-HLr1!loIhaYq_;SI}@l)o9V;p`xrJJw2KS>kF)|YMzsA#z-W1*dr{G z!t0QiK`aMiIC$v>t%~9iy4yCN6I56q{JS_r%_D6C&*Vubh`x_tKJAIm{_{_CaD#0s z*5xzglHizvKf7450mULighpCgQ9NF)1w0L1*aaw3EB;EXxlqhX&E2`^!_ra&xgq4l zTww1E`F!x(kHV^L+rW@zQKW~XP8)rl0K|volruHBgAZ)@c2rfb=V+FL=fMdQ5oR=! zLi%;2idudJM@Q~;w=&JyE<|4E#cux9C^m5rjF5gmYf4nhlt;;}PJcDgqRG)vs*s5d zZF&DUniucXa(r6%7ov$TBu^JXI5eBX)S%;P&NOhdU1hdCRhE{fQ^t=`*5u-n=qF9k zBXKaJjWNn}WRqpW5lyR5WWXFw)(%pPRrz+GtCFLvZjif^hieW3a_$7xhK}YU2Mk=z zkMUrq=WkIiHCi(McyNqoQMDAbwy-Tv3o8Oo#n2afK52wS*%829{n=kN$x#T=7)N3O z4;QL3I{8*uRG8uD7^d*EiOI@Zj?e*Hb|6Fh;dBwDge|1li&%aYGUv_WcSCI?-xm8KBAH;QOWv2$$eGs z>KwMt{FJFmGu4z1rWpA<>=vMh`aLDzw_I_v^I=q0ClPWmB$ikY=Ga1G zAPAMjJAYU)S0MMm&>1j%pcyiX=MV%f{B?>f#)w6S+)6nmQ@t|1xOC^FjZl#4%EI{I z95);kl)N@LIar?1n;Z&oxTA2mvv#c@Mh%a(l*|9>Z5ZpBD>VTtIiSYpL+WT(=7t&0 zYK1fd1R60P%c{7Cbq_sy35klTea+~l+YOwrmJEQ~;jcB2(UI+tnIYN)2h;iGf7 zx0_4vp@t#1gvQLby^hP?XUGyC;hD@4wVSA_Cg95h|9_iz|jhH`Szo@b#6~bk92)Oj3RR-#U)U{l~53w z7#&0Bx`utAjc~pfRkh_WARXYWV)m3XU;wb^RD2P})DC~^MQv=0{Ap0(*%%OfIZv&U z_PD?zOB(b5yZkcNzS@xKxHu^OLx^lPjUrt(CnDKg88cP$?pPzr|+=&vs}?9_n#i^XpgHP9f|fS$N1 zt(xG)^`1w10CnG8pn_gjx+-y)ViS)<=xf(;^ee>Cp!-KN@g0HH>cDMpQGa!n4}GSW z&DF#<7=!g)P*sL0^V=C33~nc}r-f|=IC07w6Xx95Vht9lD2!Z~M4VXxMBebk$4k#O zHpI={n+~h~QG=zMocyVFA2WyUwaO(qNIuGVbkb!m0TLojCR82)Cy#l0>9}$z1Tb#-V zMX4IYO4ll_T3W})K+)$JuF8fWFit_NsLsE!M6y%Uz{EYOWdQeE>0MZW%u!o{2}P<7 zl_G+2-RTvC^IZeVY?h9m?-lP_FM3@#t3{Q-)SzUM zl8Ev%YhqZ;&mBokZZ3(`-2^=8wKnFlZS4e1=GHvFnL10lC?11GgWd99t?pdIMTS$5 zd1}=kSfm9CDf=IvQyU(vBeBMA-u%hAqG1x1P83YBp#e~^0>>9sS?e0Rbmr2X|01;W zaUwVWzCpb~dTxJwZdlL^jAvc>9Vi_73G5c z?d5&b;ezuqYgMheHl|N+URK|W;5#AKO!y9WQBYPGD1F?tz)goiJM0F=dKc^F9$qRO zI*b;OcS=WZ6JJF?Sj>a>RyQKzqOPZ5NCqUO_2pf6;%DfFmc#nvY0@r|JlNuK&(*ie zfa`9bFt4^neZT9*z&SI>#8jXp8Ha<02Qhy*L>?-!v{WQUifL?08ASbjg^{R$>CUHa zeu!GZz`(@ZBBuI)N>^1tvoqxNm)>5(NkLshO!D8*+6u#Ixg{OFxH%)8`|qyG3_%0K z#Qg@@ydaT+nvk$CQ~pPTOf+Sp*g@;g7afw!+A|wS9|Zds1|;v6F-2{0YMVWI59Wpe zUD&cTa~ijE*_Bs#h-5|q1!K-ahExJz@cuqRqswf<>(?oBP^xTQ9jJfhw_nA1UMVO- z0`NAsZGlA^7f7+PmFI3ku33%H3wW*_2s zJdE&RJTReuw@qfT+pCXkqItm+G=e(=)Cn8PL@>rX2A5j%OUVIa{^$p+3>tWPjIbmT z8XCL*rRCS#-ss1)mqepv^c--}BgkjkoBW}}FAOOHOG85i3kL5mYUpSfI??}D@`Za& zHTw%p?N`Ip&|TGEjDZdeFDa+(sia|SfFoK#_T!eQX-w~Wb@67Ib=OqNCKadXoD})Q zW~Nn0xWR1Y!Yzq}gvL~xRn+*)=onBvfZDoS{Z9uN{EBr6O89A;$Zl8C5t>Fy6gWS@ zB8FIX(dthURyInl3Ke4NqOQHxKNMW^f3X06iYt?tsy{i~{*4zc>FSy|u?L#8m6p(u zDdM{~T!fLvbtN2R)xG^%k`eoi+zQJyb^&I6oc39T6H4KN#y7ymdY0023`}PbcB6K%Mw1+CO{4346>`&&O zqf1Y)8a^lp1RajbKcF#^h)Y%N`WRLMl%IOG_AB;qAk?2>YPlj=Cz>_#=jD69r z<8OQq`gEXBgoB|V?96py6ZC&>dFcx;OkWvS>j zXZ-0F7ZgzROIU!SuAE?OR!d#BvV(-sQah@f*TbL<4`fpGt2`T?pWN(fZDW_xKqmf z6W8hOY((_LjN-Crs-BxCUokK?vicV*)4=!*Vrv`tEzzWv`$tDgu9BLb7&Uk%{Vgad zDT8yGGE3Ix6Eb#kRK=>PsT;nT3d(|3hLPcvxFa^&dt@9!W^6G87Y)BnurUJ~502Y72gPPY=;`uHJ2Q4_POl&2 zS9|A}jqW|Ce@Qy+s@`gx`sHjnw_G(_p|+*>kHfq`9hgTvQ6uoQ?NWe0x`CM^=(;vs zDBWJsfq=ISIVJ~b`jQ+_Yg%isotVpFDj|VsZK2;+y&g1EoYf_;ghpTL)Z)4v7W7BoVs#vTZU5pO2K9pG#C`In?-+Nk*bj*_?vxoG zDTr)$jFhOViP8RQgshCv(-@&%6^p5}d1CO5#jp>}kv$`)pO!aKTOYul zl9^)St`9eXQB)5~dl~(Q#${@_&jL#G)z_2=gHusaFh)_hR#q^%B{53h3Yhoeg8K5l(=}7Ot zw}5IWJX>*Q(yb?{B+QwJGKJ<9+c)O~@<{CjjYUe2WIHjuNSpE4`?mH~FU6Xk|Hlkh z*=dI=^mp_@$@4QfzFzeSnH=U=R2-XwM+jMD&JVWC!h#A(ju}VIR6@+A}X7~@ra?9%`YVD zd-#_EuARc~Z&yX^N*Dy}psGfCs*$}xQsc=_R=JghB;V8xqjsN&)B$=&wGau>Z@>n@ zwP;NL8{d-%lRtZBZx;gdfu!Lf7e8}f(B81-hrHW(8+#sRct6}s!|x~1H%=HPy&nk< zSHh9Mqe#YeGZd8FH+_Zun@O6U0^s~9r96gOcDl26`O%%4gq)Yc2=b6ucoRieVV%~n zOVq-XJQx&9v98Q*U6Q`SS(mk9VB+JMuwd~=F3D@j%?P7(S{&8K#?@Hw2MIX4-8kn` zk$k5$<5iVXx}<%>w+v4G7_(Z>CMFLm0Sj>Rzio5eqfC*lW1M~Y9&2%88IHZGt?ywS zg6GeR{*qS0aK|%=*d!a*b}EAu!Gt$vKs}J4lAxfB%uxe31m1HQ%JRxu({BF3=eM0k ztaXlg-Y(XceV9734}!I7z9AiiXway{(xh3Cxn^@jjWxo9!I;eU(N1cKD3B<68r+nm zmH1wT7Yw&`sYYJj{$|Y)56nJ8{24UlTd|LhSfs`%LV`#;7JlcE#+XTYEaY*XH*;25)4EiVPY#~a4G9DHGJ#?Oa1ut^Ex8! zGrNJ_s~fkc#i?2w16Sw@Dk`GF##`jx9g+2FU6=YfYck>*xSbRH@AnYp$3JO{A}Emy zI@UhNFA%~rFpaH^5{?5AP=h4g+;EKd2V4QM-#oJJA-Z9pI5<3wL>gjdPE1<4EmON% zhFAItsFc8>YJRm(_P?LLu@=~OHl^<5{75#-C2!Km#MxTJ6ON!Sgcid+=5Y3VF<_K?$r-$$ zBg>zS7#F`rSN^x=7H|+oOsE2BG@7<*UY2g`>=f6KDp;ilOKh=TzmSA>(-IT-w%o^! z2M532F8KLGW7i{UZcd$p%_(N%xIwEH7vDCvkp&70Oz>s5_BteqO-X4m(=9mx&3`sHTyEdoUXPJ`N<8hs8Cs02UT< zdFC*GK#oWkfU=^58zSh=KwMt_v}#|W#gKpvD1L3amKB_NIZa$=(I>lGE$j z!jic}(KPya8ar*4dD5BuH=tY|I(Atfc&!oUwCU7jZ(@|;i^ZrU*)&)`~v=t1!1 zjiv98*M5>RQj)c>$kZ@U3&-TSr3-dOB&l2Y5rN5PQr}ov)OBqG&?jOO;do6U z+!Jj%hf_sX4rMiM5iovT$JoR%WaJM2R!gHd3ywtv6ZvL%Ni1#YfT<4*KYIUQIpt)> zKp+4U%g7%+;;R?qd{G#{D9L+O=l)iA3SUY0)ANvtKhW4+i-wx^E*F|&xgT-XpS{K1 zBjH)rKd+TyWkst5p1-R2&mjwHIocW#7-LQ=Tk?WD0VdH-Y`eu#ii@}@3pU47AMMLY z`%4`5Y`Cu+sHR4-bU3Ul6w5W~;}uftb7pF2m!P%S+bo*-(2Clt`<*12ys>2%{HCno z8Bm$E=kWQYJcKz>F46RNt^6jQ6)vLaP^D87>a(}y4apO~!$Onh0d7W{!y1|@y{Z{S zB*j$G=Q=uv;~CW}jhT)PcDMY1rjkVsZwgq>h{DqGAwwZj2l;a&94a##)eF!%bBK^eZCoRgKW%oSp+ zZ-uh;&W#FNQo^a@>Mxw4Q zX=zGJ=D;0M#b|#!M0BkM69slZ%mzYZ+8#E7(&_GhkURz*FAE{fl2f z4yMxjoRH-$Evd-II`)U!r_M8M z9|In5ZO_aZV3%3Czw)O_WrwFnZagR__%1wZljkS2L|8Ov(Ahn@8r0|!Ub_#&@X0wi zX-~;YF31CtbT^Gmy_TdnZ2HH8f_P83yEbA1+i{|#wH=Yk8Dyh(Ah&o3v*=_PkX8}} zc~$c4@jSMAbgX0Gz}=G>iXe8WP0`xft?WQg{+-WAW~P>270V-^?gWga2T|Izzo@0S+;bz`PzsOJknyHf}kOkg(G&!xG^65i+X^s8k; z(em4Vpe{PMuoW;ib{hthjg_Y`GK0e@Au5Q;6D*1scaq;;nVeOH;EXCf&IoURJcK<~ z7s;ZWjC?b?2a;@5!%E4@Ft*o68&i@Qs*T4#H7{lY@NZn(BBL0+iK^7!-`RTF#fLv0 z;B;KW9aoZ@;FgC5Xs46{7cdX7ak5NU>A~tuA^AhCCA0{<4La<}p>@CPf{8wj6R`C) zyBLaVixR#vKL63qNmz->$Io0Qc5?~aU-o$0m(v<=VpUX8l^7AVI%DFqd@b;{^pZE;3s=DuxRABjtYq>(BEPbzryojp5uEQU&B zfIwuY;Hazf0DJA!X_URlpfTadAfIw4YA; z@gS9;y_Y}Dj!TOs6cXKvzAIec$T4caL{cC4gK{!sTV98R?_O!H=rJ^;0;=SgYclkh zHEvnKr1-}ZIi6`lN9@TAGT}6!wxf4=3meW7rXWw#J&Gv5tuig=We<@l@@W*n?(-hl z7SFAm4Ov>lM+EQsEsGJI9{)|?%NM4sKQNVgo+H<#I@a*?%*!r`j#in=MYvKz)*{R! zgJ8lZGUkdw`d(Io4Bka)VK)ed>toT<$YXEsk1-%-BM6_#k~%73&mW?C0uEO8f`Ii7 zJKoB`KlDQo(`Cl2WynX5P|Jwc{7*VH8|GlMm#FDrGXJb5GI@JoLwy6Qq827k&LKV= zF%`Nhn|*Urdg47t(_nJ*`z$}2R%%ghYrxlR5w^z3wLNr0v@wx^FS0rv`1~tkqPdr$ zI!0{no{`5t7N6w!Wp_%=b_29!O?9RnhA=-=9b5%{VCC*hW$m5(rfbb9)XrrNt*F~z!%3t(`OvR=}dwjm0a?yx9!EZdFW~3eY@lCf&a4KR%+{bIjM+DvHmlJ_F zM{T|2*$XtBQd6_p8L0E0jE)=h{3JMC>g#`EQ7Wg_9&mEZ<{HQyv=^#Y(l*&7{hI^U zBb0fZ?yIowZ((leuFU>OJ-T5*m`CZ=jg@hfbD>lV86!z+i?XjTPMxWFG+&RbVp?zs zzQE}E?s8*Gcc5o+h;JFm^6&3j9tiZ_1EvL z&oCtf!FG_uiy`~xH?k1eDtUSx%Bi?{*#Jxb@rugn$5SRRq^Wvz5rD=ZUR6Q)D?rc3 z#rHyL(;+G(b9NeJjv5NEr}4KwfP>`|xkjIz@xUCzjMa9*)>_lIbWRCZ@|VlVPMx|@ zR>ms4zsKitPrK~m6f>6h+HsAQgI5?N;OswUoK?>oFHFy`sQzu|VCQ$*DEh$;GhCJ~ zFG?2t+iO70)T1Q)DT`Z}#q^{=i5h&v(uk<%afOMzodLAty>udjoaW|-KVgvrzp5r9 z|M0H)(S%WjrQ6EFtrs(1?T;W@z^+F}-ymc7k<(|i$55EUt$F^Ouy73A)*6G~sDGI3 z7=QFH7=Dr}E4kzvYTC@oZEHbqa=aqoAHgUBwIpx8PZJx0a}x95!fC#Ppo@b|b3p-g za`dL`(IkpVpHBkHwiD_b-a3`V$=KPt0!3<6Dx>F zN?|am`X@)5q@!_|7ToUInuj+VaTqBmPf>kdLTk#r^W^~0Ac*rkU2}zOesZvfWrvz3 zyV*}O*2k`a4_ZDA@Z@jiNnm%G@p!@C%(g6^tM|1;QyV_VQlj+FSQS5-*`h1N4-bjQz|0N5Q z@A)c>-s9xYEqrSwb63aY{5j1-9P+I5r!aB?pZAmX(Bp&(fybe--B|www^TVzgjANx z(m<0ak5NXkO?vJ5cuG5S3Gl#yD=_)^gMeEu4h9!4PaZ>9oaF^uJEK4wn(r`Lt&_t$47cy>DV;tDt56Vl9#g7` zMuGC8%sP~vTWiV1C9uQUeDI8P^V1z~W>JYvtrNp`tNi6%LNgRl#OCmpjEFqZzb^SGIxYHMkfm3ZF3>$B#q z94v$^3XmLB)0P!JwCj9(q2r||cSZ6fo%uN2(&R)$e1#T_xe6%f^xP&YDY4w2Y_Qbs zV(%YcVWTEcwh57Nq80z0y?YkQkS6u*#|w6XDGDG^;F*NsEgdXMq}lBJ48=|)18U7A zwS;jM4xD3gu|Mej9_7*`uXD9incv$7FDU3KxIjTH;Tmqic?0A`(BZw?Y#qt;AdC3T zSVu7RM;$4=Y2lyq6G!nBeqr4)d7vX7t4N^4EVZ|uqPW8;kU_6yqWcN8TuYKgs{pJ; zoK%&c!T0%nh}(ktuG7dJIm<1GakLi|BTTDvZ!?i?X2s5bEcud&rDfcN&Y!vr5^mJ& zn6D?0aSB{q-F$yUMOGogsHA*;Jpm6;*AE9Hx#1%w>Y72)Ld+=2?17>fa}D@A{Vj}~ z%LnZ9k_WsBD?(GurJWplbCw7k|ue&%}Tc>Ax;7W;5=$rgm zB)+@zEW?2;?`d40^};((uM@G^HBrg^4PK4`1j-bcrALp>mX{=tB;d{9a`MZH!iDV^ zWj@plm$)!knSArj8`WH~(cRst)IU&l4k?s{oR?P6pwASavfW;@}y``5{<`+etUf=C`Qh})y~H+v2M899L}S` zj>S8F{EiIpD_nevSI6pBfRwnDFAVqh)zFM)+NzDi{SEy^Beb@_1)$ zQO~}`wmU&UrNn&%Jktli>rA-`_o0d6zwxH+GCj$BmYe z#8V`&WSuExssBlCNqy2}ele%Z1tdWO${XWEKPK{ki%$?z*XNBL197X6a(&j$B`x03 zN$cdk<)iD*&f%5cuu96*bfr19yWqninY&hU7=#*c5msI>dXmiIofD@Qh1rY_Z9aZ2 zi8?zPaB?+&!-AZnvU#VL!L>d{r>2YOHo*fGA7`WP69fvYy6j;Ks)c47cDt9qmKRtN zts2ysF3<$I*7-%WaGu2le|s)<*Re_YAR5WD4b!V=?|eP(pzcjR?eVl)yK|zuAJwvr z+R;d8fV`fNZ*cim&$hnfVBh<_F70`|OVT0+%*gQ8_xZ0swx?~a-8=XPSsfi1qI5#x z2j1Z1#dO9$xNAkPbMl-+8`ol1SNrG99x2?Ekx`OLa`MQXQ(H zv(gfX0Vody4jm4hD=HLVF-~e}`ni&dl2(GpL2tf4y{E#X5=KnBEmPr_D}qe0_w40N zN~oH(33&+F8Is@D0!%e99UL42`t)Jp;P}VuT%`$3f(vGGSa`ca^daI3w(Q%kUE7;= zM&Y8tBz|aQ@kZ=fLd|10mVXhw`g;nV z%5ceYfthA+akTwnrkK>$3EOq$I-ici@gbEcy_p=QONg;4le#`X+*Mg(pC&nEOcePn3&Dmk}EGlb`^j9|BD3( z&xj@I#3QRr-P2vf$AUCUj{ZaZcPd_QJY>M2qPlu^X(@%#)BRr!y?v1wS0ZWr{4W`} zvBvCw(s~=ey+&&Jld>o>Wsqf$p+Rub{31)2?*4wAY)cfSt{Fz8k<@KhPjJw$S>C}B zjtS~KlA1ns2_}MZDD%YR-wDw*NR!8ETU*1*%FwZ}d^8;vJ$f5u9O;F*GR0T^v64^8xyP;Gz#V)7**I1@qb4FBu=kO7C}bZ*z=xV;B$yDl`UUv$wO6rE zXn69j&pTx{G_Zmtczga_AzaoH)zrdgTCv$w^H#ReR0TWdl6Hu=IDtwbr$wO1Om`8{ zQEohJJEnh6;k&bmTFJTSbRy?stt3UST4{0KS*6KPNQ;euGcqloDYhH;>*nmomM_lE z&P!m=YH4{!SZR(1TSqKuPWbZ?W?cmx%eopXdMNTG4iZ^fE*^XYz8C=#{DETSb%Tu~ zFqL&NXaI=Au?OMl5zG90-Dyeh*lJ0Vj32q^@JBlT`Kv2k&#O1udtrlBHhzEK_|2O? zFfcG%UufXe@Gye+eKO}5s>t|qxy^o~`qAC4tAEk^Xia#*LHHA?nZV7$EeEPE}Yy0H$oj>1{6_&QmyzQzBnd;<8K(2pV*4FvI!Icy= zDd?o9+WpGstkE+p1hs56_~hZ5ZHyw1R$vK(_-$0~AUf^}O563Dja|MRwqSyt+qdS8 zonV-}h!Z%a6OVheaUb2Db0yo?jfG`YWJsL(b8#nbvYi2F=o#+za!?qhvfp9iH>u$+ z?yN5iQ@(iU!)3{TPxgV{sX4ANnC>v0Vrz0S=xd$G)|*;uM<}FmJA=i|Zl}3U|4@vT zqlxBkF*96R&3V~ z>!>y@_q=GIU1JCdxj>EuxlBt#NM55xx$5=tebVEvPmmGQFtm@ZE(iJ*?7(1dyHUOh z34w=}d`^qJpMa1tJkO!WtuLe@5@pFb;Q!Vts@wq?-VUk9kXmgapzG2%(4GZHMLa^Y z@z;Ip?MMzmP|?;6LwkeWhneu@p1gXt)bDAS$VEHazpqEy#`b?NS6E8yt^c`fyY2iS z5dY`;f&c%!$R1gg z>~U^oNIfYqbu9Pv#iOgSZ)k``_Kb1^Z?$n6;oGmrk4^I6#lA)$_$Lk{+M=WMu?4&{ zIJ~ayM)vKOk|Oo7q5aUbKU4PXIUxmY2m8e-lE?OeEaKUS@GaVitCOeN49Txc6LzlR zbYtL<5j(b@(Q^9tPg+ra+mDFg*3-Mgo~>NqoxBUd13PD*Ykj}D23uLTg&+4x45bIN6yPuBd#lvV`+K8OhC;LyKexA+%$JLh-t3P_YfSzi}LE-+f= z-aj!hF?u~=icoeo>!rGHXj?xnR3E#4_d0qVKlt&lc^Y<5&&kQjkabv}M|UHTMV2gm zf-q$ue2QQU^p6Fh?;% z`1gdU)>vB+%>8YHKOSut@~f}cdmdLiJ_&|6G9jZqO_&ToF@lPks8%JLJ;}JXu`y`# zk`f!<`|QAT!KhAyDHR?Zgi6X@YSV8u;w1p!Ck2OWZr{}C@rMUCKVo@x^{4-AVwgs; zy1M%0$@k{{`QPJu5U0w3+S;TQ>`>z36KXGO>B1{3>Cr_=&|x_p79qeSr{Fkx_4@wg z+4+BrB)~&RNf^y-N$>-5mSuTmrFZul86GN=K;spEcDSa7-KABVVRUr#3RBr^-XLRAMHJj}wlDC{cve zml!&V&&x<=7JwPP?cA2x$w3U3n4k)KYVQ>9^y~W|Paeyqf-NiK0{zXX0T^M z%g)~X=bOIWEV6miM`ZjfFi>YUGCF(uSfd~rVr*h$M4vS=&M&_q^nd)X75pt44gPU9Nj#z%@Zx2|%ueYX9!B{X{u&c1h_Kj<( zvk`}cfc(I@Ses5W#_{|5%zyncK)g8%Suj0KGcVXb*yC!DHbuCD&CQ-oOVU#~;Z~sp z6Jm_N&+iYOtHzRFXZoZA_kZ5eX{rjd%gE6BFhZh8CK25ymkoE>G2(HX=9z^#{H8NIY=Jwt z!Ca4m3_uZe+Rx6t;hOq4$mCRSl~hq=n8Hbi7tq0{qRejH1Sg7#66iHU)EJpK3nrkG zo&6bs&xt1>;CYwTs(^94?h_B(9||bSJsm{Dr63LiA3WQ!Z?h|90zGkYeq}34qKKc2 znTDqm?AgEGer%K1J$?Ow4z`hn5tD}FdiRpYq#sq@@W}>uwvQbDu$F}ub}HnEV^W1a z$tXkn2QlBHhimXhLyi3r(!C`61B;f=KW?zkfqSw>A zF3(B%feRk3X-=V10W)q8Iq|S{uRebn9qCz@#w)MBVd`Lh3rn>F8!@pIYS~!kV%B4> z17nNN@2NOhN=YLbWO8M>zkk{J5%t~@+b4>R>&#lSh=!hF4r6s&b*$H{jXxvGA47q$ z%=hA4rU&-XRt6dhwk>PT+C;w(t+<0r3ndF@j1b@iowpyLU|e-S5SNoevnI}#ktj^O zK@&|HN!kAnyb2O8(ZWbSKh`cv%TP^qD z?;JBkG>7VS4@bd`)ZWwE?OPg&Y}rk|^0ouChr)oe*3E3M=eXCyJGxZmIHLtf$-(_= zw5!(G!lB18ABx{nbv0J6_l%6-O*r`PRQS++DxER!%sPClwZYkO6>-?`jp4eA9$R(C z>G?Un356(ArXcg}L*Xh`|0muD_F-yPodGP*E)Q@eMKAuYKz6=y8y_HQk5L zZC&Nz4dik&1Pr%g5~In_J=C@Fgo(q;o(kVA{s>x6dmO1tWjT%rGKUEX3zlCBrtzA5 zxcJy(R*?S@+%&|*)X#2$b98EG>lw5kNkzRbB;Ssnpgg;@F%e4^Y+emZ(t-6}H)3v= z=iv2r%l|ogHN$|T_D#I&DTt`^G*2RNW7g~A{^vcq7981H$LiG49;)Rk3{z|136i3w zhMdQgf;*R1DV=S8`))Kdb6bTB()1#G|K1x-`ZPMux|p*Y64gn;lUYnb z!5b`~y0L>J$Bxm_P)?Emx9(*F7Rk+7Mh70y*FVYp>JCZGLiYG5h*VJD+RgD3UDTI^ z@VtAo|5dOpgT&T6ETpownL}M&bhK6x33zz5-I-&1u8*siZgF#PfuvMU@A|F(_)NX{zv|DZG`z9gVN4#_~Z9qaJ;$jH}7ZLIWoIT4BxuU z#p}Z?#zoXf5C8Fh{5RAW`|#|WN#gxtTNbIEMJ9#@xIZw)-10WDw2mdJ1dB?jZ|$O| zw}-ac5`ymcmr(JT9P!mrZvXga{_*w-a-f*j(?9UT`ED9YJTLx+ks+};M}Oaah9~A& zT-za$F|kFJKtY6x+D1AL_j0tmhM+2ac8;%Qq=~Oia_9Cvh9?$S*^HCYa>!mkk@8wv zyN+jn3-O|tQIriUKT zKRn6I!a7^A6b2$Lx1YjD1+~rXbax-3p{fwS>$eg`4j{ITncil8e2~6-Lrl!BvK32{ z6BWF{B1)_3={|mvuI6e=L+S_7T{9bH=+Zy(w`*f8L=DOgf6w22f0m<-;V15AlZ~x2 zarsaDzgH&Mh#S0Wc}tLFl;SqN{PtVEJy}oKvybfccfhuCB)8@m9~$Jr;5c(D+r-lb zmgFK>SVBYFVS0MIX{(74_&~ZFTN&o&-~NSvy1R-JD&f%CKk~!*E~*RN4;x8hb&MN- z`zL-J*dUqBy|ObMd+BPcrN}3LMuECLY#TGZ#oX8+eSJer%&)Q)&0tFk-cS+c zwapwpdYqo-DhdN{r(0Go%gC?)4}ZNr#_U%1wZ@mLw2QC5|CT?TYr_4K;a z;QD1Q-5O^(B@?bb#ee(Xe@A_xmv?em9sbqX2i~EB!^cBUZZLW8S1w+<&EU)myU7$8 zO~cIXWm3;iGdViQz=Ol|e)UIwI9^S_Exo;AVrj%TW*E46nTyx@7@J=up2;Bwz0}0g zm^QC%EPWbSq}L}Ix^tO-`tcr%n=zuvEZSbirzk1R&de|}G)P}tFBiW3iW6;R1l@1C zqH6;Nn^X6=edQ{@-kxA(J3%s&-OF+!A8DVNVRWRQzB}z4J^Ll!e9=K!(9PpS3Y(lB zV`c0fS1w-W_Q(?J+i?=I&(y>?1NR?r=o3S*u&!%c8iDtc4s@?&_ zCbKom@a>EI=O6o+TaOY;X30L%IeAa#`gzcQlyhHy&B^vM!ru3{uwv;cVv7&><>D=_ z-I-=RsZm5Btx1#IYi0y}OzfOSe07Xlmw)Bb%`xWJcZnzS`fUjUlB_U2InMBd`#d;) zfv>*)f};)L_v%1eMw-ouOZ;-_F84-Oh?@dt$u5a(?zh{nM_CxV$JJjhbEAKT<&78_ z!H3_dLCZbdnfBhAxsR||8Tyf*e!j__p*hxf_jK;zT&m{h(!mD<^q%{g@6L8o5q_Ou zG*=b|F>VzToJohS=f&S1#Y=+MO}h5*k6nPi@k~vhC;k)Yf;H8@b1& zA1`rla)r&^B&oE9Zkky3!z}43h6nF)`(_h8C%@p^uZ~goaKZ9`V;LD@E5ls7c!{fb zCs^2sl1SyVRBb`nvv)WcU^St?^4fx=pk@l$iD&k9BprM#GtKhgul(i5>pU1+Vq^EQeQ66K ziffMPiE#$|`{_OR4d0(RL|MrFUUgU7o@V6kb^iI6L8iA;cnVEQI+EzmZ0E@78Dg7j zEG#S&OB=6!eNpwIhgwNyUmXzI|JbCrrWwC?jsNs7x0zdy5=~~v>IRl&BS z57Kw{Fc*IR1E<;|@7=zPF81@w#hYBaGsQ+)r@$_tHECd5&-Z|BrC6UD;M&hWb8TRr zwe2{`JzcR7kdy^xrY0D;f1j?C7x?C@lXO;x_uWqWx5YBj#FmD*{L3Y--!sgw_;hiC0S*o?#3q;7W@YjgSFT*=?&uOR zD@aZAA!;ilgxnIg9%o}^j=A|&=0@%i&q6`y-*c?7h$7z`W)|5NdU}WD=^^glxx@XT zNv1Y5WJyGkbG&}O#HWOf5np7u?;3yo+f4>%qPPmnXzi_~s;rQJOCX!rVsUnk*@b0> z?qm>M9^CHp9BYi=R$hM*+BS9KtHa#5^eaDK8)jxh!&6jB=ixfaih_6*8$B6iX?BMB zG8o!kG=WNp^EIA1Jvt$mE7jxV(nmqt%oZ`S3_N;#+IXOwY5t zJjI<$ITTgFec=errGYnc5^N)lwmZeezh30Z?MW75HsOjo4mH#e33*Y_NbamLJu%D5 z{5ZD_P&_`=GhNgaxt|CK*yyPpmPT*!%THIhKCnbu4pQBDh=!_Sd@cbq9b;>CnX&PC z=0@&t*%!v^^YTS^H6D>qGGo&=Q^XeTaru{P+`2!@wxLqiaESVvatZ@3FjDNUFEcs0 zz|!~tDa|Gj^7BP!HIX;T4zV?&Yt!`o^cVj6Yd;II9G;?5I@)WfC<)d$=38;#QmcQYLcwGAc z8zZsIc>fLl`q!I0nELtA+EsI$!yIt{BVGwiB(bs<2`)y z_lB@da$B=Jd2pA1-F(b++`tvC=FHg^YAgIWgibcO$pDb zJGob3=E%gSx%AL3E}7z?Q)vb5icAkcFOriX6x?ac=ajINPaeKd9S&{SVV$g3jsJX>qa%+If| zvM@z_JBKe4M7w^9uDW*{AbtNJFmoGB4L{$LU&^=l@T8rCWTCj_2s3q9Y6krT**f9`1#L2_27{?dIJ6fg0Ky;@fim0-saoe z!^|fPe3kW_>usX0B7kZY$?Wp({MsCYw`~-M6SwCIC#v5S?`F#d3*S6oVsV?iVI%D+ zHE1JjgF?~376L6;$MNH>wAF|AEWnav1;t-acWVWnUrL_uJ%X)gNG%WX?LThuU}&Li zUmiR0gMBGm1-93hnVDW>b@C}iQ^xJ{bK^`im4SD~yW31ZeayrDahB4>AF9+}-Ki4p za1C9TuJgC*3xtLJmR1Kc)-xa21+1C z>*-U}*F*`r74+IF+&rpB#R~pi9Kz8 zVUU;|q5sx*{PXTJ*0U0U$_CE$Hd0p^M74|T#MhXeSzvKxivBwS&E>-FxkN|B>$~+n zCJ0L>voX!1JGc4n&Ik)hi$G-~y%(COi}{hQBAM+C7H8&}Uz_F8&3}R{;qzXhz0!4r zJt{!xlu9P1ka2|S>FR3bSZxq(AE#amG}C=7hT|t)0cCqPy*|aWp~pPxA7*qeLAnTv zCL{gM?cEO@pOOKe@CmPhuyxX#b3A`|hbI$jTKeo0O%e*q9yU+rNLy;N&_*S2aD?dho2?;@R9fn;%@9 zt$YY=&OW36{t%C+(>N-Rap{X2TsqUmv6={8CzLWVmGr8F|9QD8`u{dc^$)&zasdh&6R{^~>v=JKju9)Q?9KlyWInXP@%$&O`3?Pp~re zl*fZjv^G}~@;K3CFmkJm4GnU?f0E^#%CVE@xN_|h=et{}4117_Jjsm(rl0on-S>lx zFHbOV&r4-}GZh!=@M!O2_}RuXvdj(M=KiBmX5to=?Ps`p{VL~Ax4Ds-}vXXgh&JCuS^)`2=$Vx4HFjoW+zvZFetMKD)xXu0~=(HyS#* zZ%H&fd+!R`k%tm+1Z?7@ZKZtJz1a>Y@zq!MXp^u#j)Bb zKBtUPNVBy(!|Z?Mu#Jq1=k!Pdl63jh&%)R~z;*zN35mbtK4;~PR*3$f!ZoD#Y z*A_2KvWX=oAKv8Kfkm>ahk#E|c%?G+C0IIodV#^)|KcCt4zjcZ;ieN@im7Z(4l%y@ zd-je@3YkqN?|j4E$Fpo2URusv;InHN>29qfx*L>AZ7%R^;2yVb4Kp|QoSQdmsjm(b z@>k)0t4$%W%>s#q=L|e}!t>=FT(JrQsV#DQeXU&}vpK`SoqmQVHz_(R=>6<-`g*%* zYpf*bQ4xBM#Of@gL;c*mImr0>9FOllqPd}xx~d?d4@9Ew=qPtyZm&%7_|YH(6LEyU zj`LrA#g*O@wA4ijxE0J?lGXW99^Jmnod=Ul4Lu+jtDzkAVM+^^-_<&$&2pdp}`P*jZ=v?swc9nkQ-bX*+j;&#qnI#If4l zWI&$e`aDku?sMz*2=g;f`R=$`XCp=%t;EGk?Pi;|n z-PcMIu22n~7r&9Tn+kqWA6DsZE-y}HKtQ)xDr=U7f$qO&%HCQIZuXBeMaWNE92 zzwT67O6Ynw)&3W4?g2vKFf~;{L_SM)XNbAwS%wFmbLmtSb*lDKHT8P}tAvqTrvLsZ z3mX}5-;pJZ}khLhbboQNJW8DN#jCYE`0 zZ;aJs9!K>Vdar)L*Ef2obSpmu=fjZ-Dk=ilJ4w>tJ!5)ml<|oZbhK3y*wyQ`N?F#X zM;RVpX3GrHd+~Gr_@_QjH@;MX84MALR#Fpj6KYu}V|l1=4DTLn@7Z&pTm_fen&aN> z3APFlYCXxdFTUXV*=7RH7v^1vNVI~WN5$CLVe`%;b59;Je!hd|`Uth2!#TA2PJ*q~ z6&80a+`dXqUHOt5pP!NE!+!nK=qs*K=PJP7lBOkuWC74ALi(~XZ9ARq1pr+>}{^T-CV{_!+ z(QW?H(6j4IjZQPYn1oORCog`+*I!}3(Mu&!(@9UyH zsPHx;5zKso#qnYO^{*jTbuaB_+fY{*m|xo3^E1NM(Nl8_4UVx^^mFXo8LoYHi5hvG zd)t%DY-RbqrUQgoAiX)yt#6+b&zS^TySVcC7u>kmPRR8m&xIo~!T~2nI>q+gDVClM zGCtc)b7KV!Zz1(2ER+295+e`$c|5j`6|UuEYbDt`_n6(|e71{8wwA_uHnl-sxT)^E z#9#jUHQfziyxNP;M2Jn~eA-*^oNbU^dCuUY zCrqsuiFI@m&c|7um?O2vXY%nyme&((>l#%}om~FnYi{&567~LA0UZoQsHmzSpc0`(%3(PMk_PAsl%Qh$$O>7%9kDpMa zg35~6N8Q13SO_CSYIA^mkpJDN7KjW9WX{?J< z|5m(fkV`Bw^579e;~R)*9VeS(WbWN(eh=Q2RVQx0lY{EPt-=<`nGMFCFOf8zoH~7( zGbdZA3_9NUdf$5p3!x`ioSI@{dYyvir>Xlh{`}`J=&JcC@5U;k_!N`ER-A7p63mQ^ zGIOSbx~LD&TS(XmTPL~noWV!K%xvn^c6SpU>QxWsyuuANt?lHSE$H?GwzUXVA#>xK4y$=~eP)wJ3cVT@8HQLUZ zzR&r?jdL^xU(8zz5{^Wus0^Xzl5D32m|mV??CB`y&K#pPpm4Z`VgVE=>1C;8hdV$x zQb{Zp!>t{SxNWn5zCFYJ2V=yI5M7tfbMNZq`tL{Q$0-tloILqBI9#ON(Z!z{s0?n6WozX z8rwTKcm5o`XHQV&QC?}=m(&2&H8nIgL{Km&6|wo2$%BqV%Q!iiq z>973zUvJQRqKS}Gey94U?+Rvio8;0Y&sMTns-NcLCunP|#P9f-D=TXRD;nrLag6Gq z6EX`-&aAP16oX6k5v}jw`qy9a^&h_C`uSFBBA!E^3t^+@;>Yi543ZpCT2G$ii?6@p>l;@%+f{?#^>e8`30d(F zi&aov89-COwsdlNf%up;=7k`)KEvW_oMb_!y0w$eu2!mjKMSr(DvGm$EM@M%TCt54fiYc}h zCK%r^C?0-v#0Li;d;<`>yWl?SStHlX@xK7Nv8wPAwpBkIn7!aIT>pH8y1woXb{2>L2% zZmPiRQeTrjlhAx2qIC^41{@?38P-=fN$%vat6dzn#zJ-kscyT#mknNG(EvV=iYn_L z?DH44NqTLKcp^zoxM&R5(ApZs<$U#>mLvsFq>}1}Ix0Mq%;(Z9Ev!*A8u2>i0}n1q z(QwCFIDg$s)5$D~zk=F^y;>t>R87O_)XL9Nl8|1~Mc+xK$rlWS>?IV65{bA`Um2h) zAuA4|bv0C1h4HaQHod{Za)z_j9&o&00aCMAAhEbaJXgd}!c-`WYO?AeSX)m`MHs)j z%+_X{jm;$1@d%1!P)IMcxVlYVSE+4lqc-M)%qH_&+oUsjN~T>N4(IaX55=g62FiQ% zy){e(#Y~#`{1RJ+z~_$8&{#zz__~3a5~|xrxTco6ke8{|G^@*NB(^hH^`1i+U(Qe+ zZReuYb(;uD#qIUtd~NXF#xhIf^F>S>WX(s=@4)p^5KPj1)V7`BMxBF5G=$&dKo}n` zKfNp1mPuw~gUzjNGM0myNDUnwmAEwJHESc|3Pz}EXrRh7&SHLt<;8UhdK&@v!94dW zOiGyzrXSzs-q0ciXB9ntmpRi>!PvxyWIG5_>#J;~GL&R5Rn;}rRtIssQq3kI$tu2@ zdTOgty66CAUv;I^ZkDpEHaz3j0`^J@k9c(vXjsLaGm3^4YGs#^SGoq za0HvV@I@nTe~3uXgVP~MzqkDJYe7)TX4qO@C9a#Op$K(#RYb#{*9Q3%mxpj|JvCuJ zE;+&K$~y6Q8mr0sMoy+>=2)K{VW9sh({YK$^XIsD;UsnDv6J{N;p_WS63Bo$Lo2{8H!TX)J(PK z2@AyxYpZc`g%Wl^eS->ai{j2Y3&Xd#`CyhExr$R4FLLg99rG(s_pNC2R(Emfi({NI z1&UUdK6q6txjbaCSS(T~=m<$ga|MV7Kkguhz-D`Og{@Q$UG`I3S3_-e;5ByPF7MVh zQd=D*tj&{5ZL=`HL9xw^c6|Ta@vhCf0stStyd+QYt6n0WL+2wcG^4Gon%`+bSdDMUyGDlfnGqg6dd6%*rs-mtcdH7cZCvYQK3hh2SJHdq zE4rI22)jSpwjJPweYwfz<`!8?BO0ovtFv-X-gSp!R5mqH?HOh%pJ8=nlYCLf_9<`7 zyK_Ug`2Nv6S+$y;OBXrYQO(4Zy3dhkv$LHdm)8-Bi$E|+WrZ8ZE53(>q&NswRZ(3V z!#lJ_ZfAp;`5n&1!uT8?X?RjtY_F`4Narw=0Cn{>)KmptA7@Y<`0JXes|XR+)<|wA zSX$gfZ}%XahnVjn$}&Oa&HxFQ!-2!0mSY~m#fp6ST#|(B^y3f3i1;+-wu)?T#>rV0A)y_- z2V@n^7o(vyLftVNWEn--%Sf~-6$<2Xh4K(jmzRK7rF;$x4Bf!81jrf=hZEijo;cyjQd;&`U)&R}&O;6UiAQ91aumE3f4ck5Q zxg7EJZ46{IPn1~Lhuigf=T}mkxcw0-!(JRJq_^Uv(^+(?4s5B0a1!q)4Z8Sc)58 zFh*U4gT3fScKGmzE2s!)EF?-K<8iX4NmMvFs)B~4XV_XA=k_;`SV${0UO30)bDh*h zicGzi@Bix{0F&*_1eu(U&?3A1q`ltBkR%jWlyEpe*sHQyEU>k{LBVLi=J3h)@=x2C z#RPNDpD;K$K|+eqe(5VdKUtYMQ+gk}T~eAwTU3uqozqY;C5{1votw zL?b?Y?mc);)^PbE#6mvY8tiOskxcHOi(1@AevJkBWl@kj6qnCzVK$E$P^JkKB%K>sdAy$NB#6cbQHKnl7HyJQzuxw1DKrX$`)bt#)%PDNlPqem~wrUmaW1ayaOcEOjvUvl^ zQ9&dUBIMhLcimAU;Q(Q;!g?W3Vq=4XQI8Er;$0zZj9i?Vk;e=UO|q@T=)Ck5*H70Y zZ725knS_mH>J)VgTY$r%BFrMGtxfWU0>wfR-2&C&!tHk9c6;!6JUAW7dt4;)u3%Hh zW!c(HV<6-6#;Az+@a}0}I(B*2i&KMiJWeXLgDz^`fOl{ z(;Ol>@iyx&5LS`I(hSc>#+XY%q`ikPKkK9_=>B-6WB?G@wn1t;O){CoRLXIN+6o8i z9ve>5eE33@R0bU^CQBr@5@dA)o1+g|w)6}e3uD~+ulvlT;Mk=zTsqrDU9`l^p35!( zfo_;smIaavRdeBR$gkxUNs@4Qz4-h-+zKR1IaZbv7^nU3nIHYGP=2O~%@@2IAsP)4 z^zD&ckz^E4j9A!D(4(-C$&lELQ#2bm$Qv)i2CGy~1_)3!1=}ofo!@#ii7RZrg8CjB%C4r%r zNTkNtSl+MF;_s#QMq#Q_qJP7`n)R{O8~J{9?zE=5_pfFew&uB$EY@Wi(#^pUbg# zBZ;J*LDRGjudWa4Ku>#cm zQ>3uHP1YzoJ4aE~vy39inI{Z9=;!G=)So%SfB*OMRQeP$nZtaMgd{6ROF;ZCU{TWZ zq<0DkK=Xz1x}5v)oPwhH@cUh8nv9uAlgnkxJa?quEq8jX4Bz6xlUY`c2-hxOYx(Hwq40S#r#ptO@Ft(zD&uP+GM6E@k+ImRB|<-eZB(dsVIcjYWy%`sd`{4Hos zfUqd#Q>-maF!Jyox9^WIv0ft9-p$3&`)K#d9JS{C!$FyM)9E}V-9q;G@Or$s6lovc z_2Too@p@FOc!7K}N$w4J*ER}l%?$JK;bWd{NHm^1%isQbjtZYlI(5Jo**3PJQ?g8K z0jgABW#SQQ-;L1!e1Z5*0o@cxib}AuiSFLZ<)P&*Rs39q4Q9OQp9uID1uihCMWFNtR8?Rfz+Rl?trN~(} zmf+xm6&vhg0mHVjg^fanv?Vb zWqbEiO!DKzr|0^cp-h0PWMdj73b{0i&2^Tyz}FDN?{R&4IKLG{3BxE+DB0!eKc@?q zx}OHQjG{X6c^pWRgwTtW41@PjKK@sNjj&7P3ndKQM$()(+-{umUfnekprUFHTrL$! z6fyHT@|Gyi&Uh#Om_S%1HpcGK-~WWM4TESy7d_{Ds13asY9tYgMeuo?NFu}5)&?8# zJS{;N>d!q`VUypCv$dTjX79!+k?xY?OX9I$r>)F1I;00XG@eyMM^eUmPIy` zL)UeRxdg+vZX<9JZSUj%IeUuM+At3CBvxh_9~tKU&@9QhLH_x7AF{0Q$G$ea%3k;Q z8$lQtx=uE4f+V52T{zYKf{7Bctl@TR$g+f8$WhdF44XHb_G1@Gtvut~|8HvtDX6Nm{7i*` zmCsYKEX*VEoS>APW2FBP|L4vkYNUzFfB1rv$Exvb@(1Qa39t*~i#nzykUdVE&T`;* zuZ}Dv2M(tbms3Sp7J4CvZiyq+C<$99voX%yJN-NyO%ZK5$CVp>bVZ#g(wl4SegYs& zOhYH1FLy~OZZ|GX-6vouBg+~tmjhLiu!;prdI|kV@3Fwrvt*a<@sFF&S>Dm;ywJzx z^CzedI8daw(87NCS8S8a`ZS{h54bzIg{1^Ib?p)z&9(SG+N@BS=SsyQ#iE6zYG^JO zo;~*{fP$hr@pv>8bj)Irf@vOc7Meg$Ein4{5#K#r!t&Jc#lQcBQ*Ctw9B;;RLf>X# z^bvpmpZA#9+`+UAj8d7uRc{S_e>unb3+Fh~S^E(u0sw4;RiKd9F)V@NcHwmFQ<$*J zyH2MQms3HQ7Dge5ZrewC48kgsUU|m7y8{ePWTq$#Zn3VNcN?`(lhML-{qTIqpW5f9KUph%e`Gx`?a^8 z+hrL!R;R`p9vmYsLNv7XaP4$8?w`*<_$X0MvJ?tB#o`P5(#;+XcDpFsmmar@B8uf_ zYL>fbj$~h^=6F6>=3U{h)u!Mv0PcVA(bTflplVjB{5OgWmWgE=7(yTpx+`HL?DD&h5XhQ_yzg&GNXRH^S>F}Y#4;^Rz_x9Q zg%YM^VpuxygqxnL7r1)mJUuP7L;`LUO!CJXXsoZoFaICD8(Ls}<|)sfHPYGMNJq?p z_A3Nvgl(0Ls=c1Yt{$U|jb)qYyF>RRMMIJ0ef%y7Sys@ra*Mk#%4_?^p-LezjRMK7 zI4eu5WNaJTwh^)ee>8;0A0QA6;B!0nkjMDFKww)I_CEY0D=Mcb7Op_swz;nXJ(zls=KE%M|304gc?N`3w;;CjTgH9A#@a8YbyMqt{+b*x+ zYax~2ZAC5z8V$q7vOtp6GRqqs6951p07*naR3GfiH4>_-pr|rf2DYwailYRj1f|Rx zlOw|njLcE+HE`)%FK0Tc@qE%{+!I3B<$bZ=nWHGkSlE_hckdc<={<1Oh(XPWjid zcJqi-4w#&P=g{AA|^*j94QAn>bIyA)4^JUEN zF}izuIn!QM?o>U@9u;M2Co~PG%ZX(PoPi3CwYJjIP)We8fmI-z++=2Sl&SemmZwIz zWve)xEd!m?~6ML|~8L-DSvDoDG2^pOJV!ot$iER2rOKQP9+<)ih&S6n^QOm)bOD%pp4 zrV_#WCTc356P!$vSY2T3={POX9-1ory93_^wy9Ih#+ezNV0>zgtZpLIAN}YL31U}& z-`?Z8C8=EeTjpI8)3kreyL-l$b`=YD{c&MgyY}uOeFh=0N(Lwzs#C)j0*9}Hw)R$< z>MDr%onRJ8ZLTmkJ|t&P8Xib9YkCocUt@t%J`HF_>Cb+3W}nkIUG1N z8MRPkCz&Q+5g_0`AY=FmzYqlC1=;Qnm_2w%N?Auu5@q8}h!3nl^PQvYWR=gx-8J0z z@1-Ay`R=aa(Q1zNx(o|Fx6R7r5O;3g=Jvo0IY$*eS8nk27rnGp`f$8d_3x=_qqDt< z$(eOV*JpWr_a+(zE}rh7CgMdl^Q1PHnHhV^!~QWAw+lEN@(%{|ud`hRmQf(Nu}Z37 zV!q;yNoZ~#p=c!`Px*^BiJ>7ICxEd*k3}FjVc6S zW11#H*vN{Ev$Bh`7cO(D=NMtviwM6)FjkM(>%nJjvaph5Xd%x0+$=N8DO$oYv^{4> zyc-B%QOqVuCK6;yudb6ME4choBH<7|$8OSSw@gQRF|g@?1$wbQLfGYfv1h;S0gx2j zfohJQzl2)RLe40W&!pK-B#0+6tV})SzFs6(viR&=D;0j{2kvye8H8<;-C8A?DN-j=qYOTL%<~nUK=WC?`uZ|$ z)d5_p%zKduKw#;4(upmS*}`l12{gB#KsZL!Cn011$T5dHYs-7$ML_3=^Y&2NLV(a& zn|MtBz%yo(4qE%pbFue0^DAzZB*{2^VIq+Tey2d}p8w_l zEc4v{=^cK2?n0EG>0vKTSQNHbnHjpr|GGUxHq^!Six)Y2yn&E=H^BK;ri8#U3#3+O z7@tfv8VKeu?Ke6wmFZ z`ghMbTkOjE9rD_2t4MNrlA(u#j4b5wHJs&-fBlU1Y9Ag==8d(A6&IoER?dH>Qn*3h%79IeBr58vg;-s?0J$N@jFdQY~FY7(q zFB}#5Fg7~8IKOzw&pBMyq&&!Sb^I}p2F6&(xaqihfs5z5s0}#}e~XfaJ5WjcsZ+S> z@@TuDtudgENbs!%_*XTEe zO(~aRdn-;>e;w~CxB?L(;V?eOuKm2b&!j`~?u&oC5%1==SDAi%kH6oWB_BS{^-C8y z(^*gOMF8Gou?YClk3QUE5ZGpsd-@4)gipzU-x899>m>i8nIMZoW|L>P|IU-8EIXy21^^{lB~;hJxodymY?E3ZLiEBo+;tWXGU;qv zV2j-fqkXH_fAY)aO8;F4TG&>(LiiBBC2X;4=)U-^AD@e&I;m>uq_L)w;44EKWmKn+ zniD5ERx`-dN}BX`f{pbpO5Ks8jubsIgsqcU9H;-@L&i6Y7(emWBvglon&X$~yVOg2 zMcLSW(P1KN>&JxI9AsLP+`$G;U5e0l#=x{n6tfw&$Y8c$Ta0cN(SN4*BCAfS+k3fu7h?AupnMJ-{>%ZZm}F^kgj?SaGoN#D>B}ozINe5V*!50qFk$9dn;K^D-d(=G z|BSV~o7xkX`0@{5a{Y8YUhVML`u;#*n+29e?sEUx;_G=%b<%O;|K;k5C^5%NLj#3f zmTNg67$JoHl1;1}&|Uk|=WLroa+&9Y{X808!VI)A7pH~K)CHPmoJ~C zy)KA$1m2Z2H=&v?KKr_wf?=ciB19u00v_$9_d-Q;dhtghXm*zEM4H6#GE4Jw%q?!w z(;PxmK8(TQ#`tLhp~7O<7d39Xm09`U*_`V^K?{5yB)zV0>Rb~g*khEKm1ss zenj3i^Klj@o^bQ#FbjDPm%qBgg`QSw!p?WXhqfMPZgQ5H`7PvdGmR~6G{w9hc-QJK z?+)MQ{^$y;ui;(I9iZdd|Hbu_F?`5BBvd6K%9Y^<^6rnZ2w9O2zejD0d~%7W{g3D$ zS-}dmaqj9BE_Fun9FccrXB8c1&vQAs!`3&CSzdU~tz44D$q{N}epI28Np7*W8mHt8 z6KiNdU7Ta7Bq3`K)ZJ_TFbXPda@#A6-n+xV%qBVg=N^Deq^X}l})nQ@*pHWB?EqS z2sBjHfm4$~SeS;sJAh@cfh}dpmO|0QMnch?I8^m_JXladk~JJo4Na2~rirN+(QR<; zxhOW4WndTHF*kS1+EVvmt`xH5QVj zIEgl$;L;6&;`B2(I?M9GQ`Z%?$H+X$e_Tad|wbyKT9@ ztPvwHiW!#2pE5X_Ad&xRW3MEuRCUT!cYn^Q1`S!!aJkBZkuAN1VU!0-i9PHIfr+k{ zr8`hHRHqZip&WS`MRDM8C`gioSt?dWG>5jEppkGmw6b%es02d+ z+-~RVX8_0wil>r_um`VGCR-?w&t@rEFFI3xIlQPMpB#C@!-dQ%K{Cx9pj~UAv->P| zOhHvOTux=TeY1pN?iV~3*p@-5WMbI@$>GGIsYe_%`!XbCtbJ2-WMLO&cLyEYcG5{Y zwv&!++qP|^lZx$hY}>Z&q+(lB|E!spnSb8qd#PHhaM!)(eD@ygv-e~K{lP%HmL>@} z3jw$2SuM^Fgs5)6x9FEq;!C*9{4OTx!r3q1Nu6hOBHFBr5a?{)Y(vBH=drJH1bWTk z9FBDbiJ8*985U)gz=RMDYK6MqcEstlWI>5$Byp2$03!4AhUoNQnh)DZP=ExABE<2O z-j1go>}NCF-%c;6d!h8C6VTKqrQR;(-+!mdQ21wuLS9hHn6hD!`Qj!X9Q{2TZu^>8 zp#ipuTE{9S<=VYoGbAgJMdvvE&0R%)&iI?#1B>OLKCed5S5Ot(JF7lG&W7p3IW^1) zTaur~Pl*MyGC!~>TWTcMc-UyMO|5&6iwR!v?tZIwb@i-J>|WkFljAg|B(0Yo(i)LFY%J zG!uaGsJUr&{LTfv>fw_wd5US6dvD7Ww-N~q-NVh(h9L1X4_aj5q)d)1m@*OrT&_@q z+jODB6nz6AWSd12IYJiQLcg=@3RlqtbzJucWzc?x_$(XUqt1@9)!}S;hY5TMzho!- z?H|fj-3WaNSB1q5S*v}eY`Lo1G|7Y&$-m8-H-v}meoE>G09@%fp50lYNAxX~EL|=< zc;`&6sDJV^%9R!4bl}ChTmn^16W>j?8sqU~SuTjM({GP!V5}!%n4ay!&C0o4O8Ad8 zwmKTq@c*dv zI}$QO>;BWfJ2QjFly7W!%GLI5I(u91Xj5@iNSrCMKSGI9{IlF!$CS9Y56FP{I=o6U zHtKYI!hKiVQI1r0wYOpRL(75r**di7;Wr4P>~0z`e?fv&m0SGDaXj6SOK$4X&=hP~ z=I-4^_zpw_3siK?C>m9OgglnO^ve!TDjjVLZ^|CV_j%oczjD3R8*iX09?7KS9 zQ=>^!G3%e~@h-YF7*{++3`1E%qvIFK-`rs|7-%5bg3Z z1qf5jWt`oU2%=DNDYKTJTvn4%2O94k1$kZF`As=Zc}zK=p5YhLdxV56>eRj9acg0h zSyH;zKd)VY>9I%a_c#g7<1CClsERq%FRcAbb~JX298s@Pm!|gse?JsKqE)wX%|t*A zEF)SjQ$D1`QfZ4OQKLe`HE;7DJQ^@)>=+`?1_$pA9k;Mz^{7}fPoz<1#czJ5LTrew zVz*!^Q!Zm_BQkJkcgPr^WWo35N!KQCW*l$i_nji_Y8kcs{?5Cf>3jCWPUdkI!;y~| zSE9%GVRnf>Vw@0!%^u!6#aMq~f|nUMc|?w-Jh?o{V^-eFcsNr&qsB-2!{fwP%wr+IU{d_!a5C??VQLF_8}~Q@87)g)9(juF^-za!aWrD>kmSum6yQQ*6Y$hRS9REc`0)J;Q4@u0_3& zLvfS}CsD6(<*|irt0GmSS$G6vUJ~2Vf>0?{qGp#@#veWFv#sYpsuv@;2||&7`gziW zd17qt9n1}q)*H92b$5%uKk*Gsxa7Zi)8zvnm27bfmS7d{c(#YonYAwH-duMy4#&up z#dXbq?$j<(D3zae_Rhb?x=65KqfQ)`VG-;*a@=QSnlQ|~A~#xirap*tp@pn`KqJFcX6Yq2OrghaHqDyB9O^zidHfJoov8Hk0mUxDVS zo`ZBv=6Mp!#VCOS1?rv9sMh8KT;xhB3)FWsd~mPjtwnzNlp8}I z!<~QMy|Ykl8t33vF5{Mx_Q^7Nox!wFeo|GJzEV&^OUxp-)%(O_y%^kup55XW?lT*@ zol8u2#|Y;La)6|e6A~+5y%Pinq>0P1Bg@eMt(#UH+JAqeIz(wKeh=1Mz$sHKP_!T# z$4Qt6q27ldSr9|3@>Jc_TfH*Mo7F~Hl~H6-*YDU{T6mpSzUQlrR&ATK=gkxfxgN5m zbXnKzx*?fg6%_Cat~~5eIyXubG)!(xMtR@1)3@?Q;(X5 zr{c+K%UP57eElrFqGRS|om}W+lhLD`luQme)2sD(+d*9vpl9ezEuK*}Pj;%1@f)S| z{1!JXMz;FLZ6oeNLG-zEF6Ze>NGRdG;R%tcqoe2i9K$V&TUsZ}=t>zY=gh=o>W6Ac z&Qu=b7K;c$d>-|V%~=Waxd4hVcx_QTM!mmgxnkvVPJX*e*?(*lsqbp&;#JGvIQ`9h zlB6hR{rzYjd&$*!!#2dxG$6xo!uxDf;n#7B#su0w8kpBd5~UP=v8~&^>rjg;Y_eTe zgJj`gQWH(+RD9oeK18~Vh)T~a&q~pcqEl(=T^I^14iA*tdX=vaqWo1!>)fEfQXmp^ zT2*e_6bNVdBJE;onvu9hdKI)H(bhQuRcEqh-1bcemd(mSjnvk`#dWLm(H|EG@e}Xx zT~j<2?d#=E=PYPALTML8TH5a&L;1_HM5}UcOtL*U7xW9?)9&AStTH&M6T&{5WV!aT zKRoZ~nSTTt6KCR>Dn8CWLT$3H>fDp*aQr68uc>ZlL-lNxs8=k`4>)FQD?gJtFbz>` zji44!&9cobE?G|jay6clG?x^&cD4ke*w4~lF!)_aEg@z_&k1brFDZuBRm{;Is&_q* z`Pron(x8KXq+VVX=s|*?XA|iZ47<@tJ%IdmI9~>+j zmdmn!z}6FRFALFYD!7oY48v_*c}d~{2@SciqNitf>ogR+c{H$JOKPc-zDP3oy3d^H zQYl!kYh1D-u-tokvsd?3D%+ltwsbUm=Cp6GJ~Pi+R>T`A1I2F}qgK991`%n3y=gqW z3%kP@A!jl4!qBE!(oo;iNY8g<_jQTOlpZzE15WsUKb*j_y(M52)izV>=e z>B)IBvn41XP}J%a<5)YPt2Aurh7$YCm?7;K3iys9>zCl<_pyCT5%*m8v0beaCojgl z4i%~y`(RlqUZj{uefCUfLVSvou9z=RrBp_p>P@H3$4?heY77~kI?2|Nty&{een6#S zsf>=lP1;>v6jY=bA}KS7=eqCgWgqz?e>8ahxYw4A7)T9z4wx!^Cs5IQ6jY+n0h=Ww zPLl~I5#u6wDEZ3~#fd|S8`}}OJ6DwWHEe*U=@WPW3 ztV$Wdv>b_y1!+|uIveuO`HB~4fHqrVDVvKh04!%aVv&}2j}r!p0#{Zq+u=l&K&(#HM*UMt}Q34UN`PqKf z*SX#e`*(KLH^dit5$#^tsrP?D^Za|YPuGH1;5529u;q)vs{iEaQvR_u4ku2}%`T!0 zI))gEh&HG@K>TTumUCk%o5WeXhp9gy8MF-P+oX9PUM-LNc>h?dxJ!9C>_hjB5U%(F z=l@F4@dmPVn)ZH!jb8xgzvP>W+b!iXYh1hW%nJ8c991Y=ET!40r$ahNSA^;tWY;H?sZ|wft2)+E=t)=l)`ZL@WLI-hG70 z4~y!0QT@A3vY?}XY(nI7zxxAyd0A4Ogg4Xk4b1nxH={6c>5osSuB@;yAS%G^Q|Wd4 zD1wU;>W8M%(4pg=>pBwK*}|CD0WOzYv4weQW=4?uAKQ{*yg89u+s2$;j#BAxmV1 zDDtsGCKU~_<{R+MO2vv1aaEd2eWYV#XSMQ_Qk&n506L`#_SN2t62zy+0){gWbTMD|@5l%cPEl97Q8-cljelo*IfS;o5J4H7FO{y>ecZT7EYi zo9GbWEY_~vd^xBJ%kkr!k&BS<=-P3$^hu%-LbakwOEs_WEjo1BmN@1(mJTV_6#b%I zLXB(2m-Bwp?`Cmt0YBTkp3b%zypWM9GT+C)Lc2dj4tDkZs{+%_EDVA!HenK)!_2j~ z72;md#s8wkOVfpJz2QP`AO3nIr*dH?s76g$5B*z(Kes7nJKVq(vqsPw7)`fk|LpBf zdsK2&;F2|TNs)1a?@H~`aEi~j-ZH+QJon~Q+BL-9ZM~ZE+2l+2{=k21w{@e>3f&-S z$#p%b7%irR=XIw*Umcjx{ijj6kjzSb17R=X8^-*&v!YTT?%DCi^cz7ZVVKXawq^d| z(CK5#6Wc1`TE#q)v*3!jmFiQRwz;~PNOXwN%N~5F9Txn~4q)CmuLyI<$DG5QZ$XhN zeM5>k1AG^|D8r6NUMWktM^iE=_%CB&LC)xxqhjnGs1-!<9Y&Qb!+Ng~Z}H~qi$}sR z$hPDh7cCa5*XsY2pLCqbFp+Hio$TnMyeY(h(tGUSQ(f_>1|h+O9367~rY(NTHYgOj z=nRN0L?3U)|IrqzxM^f(7G+%@6!+fV{gDnoIXIK% z_VPl%b!_YhSMmad`}~oX{N~OMV$Umt<{I@kz^*xcRt( zXjsb`?lR!8YD$IX1R_1H^GI`F=xat42c`?vxBTJCAk|ZGaCwOsG*XXM&X@18bVG`T za8Q>%D8rsx_i*&0jsTJ##Z=8vS=V=Fl&CLXL;eWv`#vE=GrxcwgX+A>X!5wSwP9E- zFEopv+HErd#A$02tCBBSn)$2Eh9^tOwma>#aBmJj^j#Q_0P)5cJgP>#KHbEsUAVMt z?}@Ji&B`(Bc8d+Sl}Sb<_csCg&J)3Jfns*?X`Q|CZNIU>A{a#=+Sj|DcaK2E7h{@U zrRP(bDVG0rkG&sGzA*(7^xjiDgN22p7j`lm&V8{p54DM6Wy;8vb^I?Dqzl3P2oBlt zS!Y?6v|4T*_l_+}f{&l@ty{UXiL)Zm^^2j4)~rGEidGVWEWjZ^X0O+`?6?|#b*N4(o~p$>tQI&*pT zJm;YnQK&?xy0oroUH;Y{X3rA6ZhA;{N-BwAjW9gxTs50JD?byQJhe(op-uNwHOgNg zt(E^1tov&ZM@ogT6GT}>$C>yISGPrt4o-MsolNwvtp1&Hpe)hfmU3t@H0r!oZ zkygDDgO-9>HmnmJd`1PQ5hunJPz>i<0+uoPid8u?djM197-Fd-ShrTQdck7|`y_Oy zxIoxi8R!L+ob1GMS?E${i;>sGNDcGiTX27&TooH z0xSkioY(HWz#~dtC3utzeK}%NB2-WkYVUDLp3QLcOq6fUzgh)FENuKx~ z1JBp?$GU5s^KpGLajJtso_4{azXl!!vUX!r1x@Lil|5Ti6d55D`Rk%&7=sq|crtD> z80WH-TcqnLV_iNL!N9^y}ddjC4XfZSdsn_WZZQX zJGpq&ukA2CJ9k^yG$#ohZv1wlEu{p@gfBbaKl@Eb|H5Pl7>UQvOHXshOGp3T|v?wr{f;0*Z&xFmKeF6ehKo9 z#@$s-U3#Ydk(&lylXX+NJhWRxyT(6lszm0B@G-9FYPnH{O_~T@b1j*QE?CN)qO4WX zYg}h$k;!-J`PH%RRl%@S+L!-60AreURlybd;>8of!=TsZ&_I)H(v!>>=Yytv9oX}U zknL7hv{O|H0CK!qtj+ft$KmOh9SBq@d`e_XD@%m30J z`wZ5+AC$CbPZ1~vRF9@eSyxupwj>r)&TLV;-0p~oR3)uys++QA6_Ie9L=OWm?+NWy z30!etpVDJ5^n~lUZz$FzUUZCMJ(g0E)pc<5*b{qP#pj(DMAKqgJ(id~EEB>4nm8^T z=<|sJ^?P^a=HjmzJG0H)UJ&kRjP9Kw#64+$M$_R}Y82J5^xwJ$l+tg| zP~ia+NM;b#6dx`Iy*___#MbI^L07W>M_oGkk1V>5RZYs4{>>DVhQb^{^O9Ri$8-?EoJ>*Nxnzs-=9DIWfD54zpz8!>162PR~{-W&Q#_2hB*oPN& z==K-m)xMEMLFV6j!PBxTub?f#j^wQ2KsY!!8a)zul%_=QK<^#%zj{iYfg zC9o23H;sPpBf;3t^9;bh_pqjAk*uJjt4}*An8fAM9@ks`mvUP%`MWNunkeJL*=;Z) zY%@;BNt3I2J9=|@Fe2^~dvspK_z=3X{Q>1<5cmDo?~8T31<3KjN7%_JYPJ$EPDqTz z;BYl?`I<%J{rV=gv1+?>!8ZsZFoxaYn-v3^i`D5$fczUH8bxjZdYyd)jcKF9Gezmf zpyJ4m)2NZc>qG{_b~0WC+`5V(3m-W%?C92aE@Uaa;OT->uxIfDk{@(U-S04CD1n(U zp0PCDpZGa`jFVO6F*mSZ!8y{QH!WH|S>CP@_?2T@w#iAAI>K_eQYV7mSs0ngcB_zW zqV)~qm#(4Kwciuq-B?1;T4S&Zf`Nb;$=IU`llt6%B{Du zj7)sO>dZ@iqm|I3_gMNwUlP>7ikKx{-{jo#zfT{_FHja?Q=v6q-5yr+?e0nAyzQ)e z-(OGMtuQ4!d7|m*q`O0Nk)9YAFidX#a!wJ5HdbYx-+Uc9Th zJZfT7&&;MQhic(9XyfYVuoj!qQ5cwaO4fT<`;+-KUIMIY>M!zp#?SHQ{4=^dT8j7? zi6{!zvPtLN3uRmGPlvgpsbOlu`bXq`Zi!jgZ6oHRCtG(JJv|A|ss3(){-}q5XoFM0 zPu!FEX?7Y$5Y3_4B_3*WM_1d_#v$S`iREJ#VPmP^>wBxNfzJ_L`3aB7tRQs)(cAx6iFRMFR>&t{{s}@5+ zk{c>IiFaFxG)Q`KP+-bQ9Byijz|0ng>!X+JcWs*jDK>Nfg<^GO)N%&d9_6uAOz&jz z5C6^{mpBCiK-EyEE~z!KnYMR&;bK`9B5>>g>TQ8%A{Hkv(JHO2n~-V=GH5vb+z;-E z{qrF0qVq>(5v2TcJLV}hzFs7lf%lDV#Z^`s~D z7KeDbu5^RtrK!?8oTK@V0dEB91plfLWvTUw?XCfK_9G3NQ*dr>Y)(Guflr_k_%!aU z^)SY{kzrv>W2Xn(@=@G8VS#Ndr#wZ8odWEMhhYpej zRLxXe*7C3qE|!`&s^H5VWA*bokYxW1?W9}&h3UFFh7qq~4}lsCW{Zab&9Hm(GkhpW zy%Alq)uc+dLv+BRFClWT;qs|)Rt2q9mbiZ8;%vUcIEpGECR_QZLHC=l#!sE)8Rdt+ zOH?35gv%7gSr=y+k$98z+W-nXAuHR6YV!jnBaq9jYk~!l}T5gjF+l_Gx zdt(_6zeu4NRC_8KpP#6_Bz`d>^Af|7Tp_3^YKzp|G$93)Xe%*tcRc@5c$Y0*+}J=R zKaAvg*@&w8`=s1@=Aa)hOj|{C6H5U3v;XZ$jwkV>*y0IKyYk#nL}BI;(@{rB%c_Z% zbXyM>Tv$RFMUThFQ#Bj|@zb6Dcxb<{+C+SMbMLj1%-{;khR^FPYgy$$GvMJxOS`p8 zxVUi7lF)!CiRh9)*GV!+(jaBRHomQ5AFc`cw%uN%XbCTZ%pok>5ZuD!{1$@_5FU)K zMkFg%mJ$$LpOi`rlgs++qQd?o4zsnkMrM9?CpeilcUpSRY%(PxejSN+-L9@+KDVcTAs)Ikdr zUfTozkR3Q=v5K14?plc1W|9^giLv1?*HJRTY5bAlR?_O@74NJ9Dj&}C&jqbp3Zey5 z8jp2ttORY|7p|qXwNLe}>DX>d&tbbU%^eL}#%q?ip8ekZIGTgIJA;t^1jqOJ14m~4 zb|_$eVoN?g^hj{n7P@*uiUqUpBpyydqbe6opmskRG;89TWn#MFI`P()0TgHCKw4YY z`Nu9S+}Zm$1PR-ICf*ChSN&7U4?JZtkP0TZ^q(Z)bc=eKesgE)7J+qE#Lw#|{sl2D zeXh=P#b0Z__Xu6t7}1ffvBvZ9Dk|b>D(LD9|I5o-F25)m_LP-hRxN;jxW|ErH-t0W z*1zQSTKRbm&g>}m`!(TEs+gbu!0Zlwfz3IpTjKuSOsZ%Jf^PGC1;%ca=X}=aQcD6h zAAZ9mag_mk&TdeyHIVdnA8u>IDWosixZ0GQ$&W^9O+aQ-s(N(in8oeA;>d0HDxZ*+ zxtWZSF$PtX&FFn3_#fY}c@fXYt!rb=9d@CG!(VN}1N~Q#$t<7vHQZbvSTN7F8_vhm z7bO_7^Q-v-$8Fo}^iDnF54BQ2v9y*o6me{4o*^H*u-43?=TDUoPx9&4306A24AWoq z`%*3pJfM3dwfFID4?TKdIO&3noLgY&D!gj4S&K`3R%|LDuccZ=M_^tahuks4?fG>N zKY8ASHUOc`^9>lK(VFvCSKWS=#!C$kA2lyWgk}j+svsfSt)V)Y%a}NB`fCH~5YVG` z8t@>%QYZ*7t0bBxy&wHp?rs@6f2Cuc9TX7z*;z`J{DF%9`blslsKFBv_3kIC-D8L$Psx@7J&FDqK{GyXr?4r@Qvb z*Ric{zQ<;LVe{wIoPT)%PA^fGt7RGM6GdtV!y6iro0dk4mZ^A3MYD|ucOQ|V+Zd%P zx!P>QpgR@xJvhTEPDUO`C`H?#+sIBsY*denTVE&9ZD}v_y|}QkG7j#=;WADjVscIE*B*ydCC{w$Pb;+++c9t~2A9e<=5j*qGJ%=0xpNpM(MyUd7YS$h}X4BT;x;?HO35fjVG~k|LSU5O^H0D0UV9epJ+Mi@4^qB`!Q)(L$^w$rBzERp! z4%Rh6;me_0E2Q;IGsPEHP(lNiRg8`!Vh{Vj-vr{#-y<)FspmyctHw~EouMfct& zGwHpsW(;TMuB&1{DPDKe$nvw%w+$?ZZ)z6?zkzkudwFn@Vvyn>0_C8nBw5>T2h9*YRdP@}_jdYttu z&8;{0p1RuxvSOIJsu-ubo=|07K;sM{q-;v_TD`j;Ucb+CjsRpQGZADel}c-qb!t_! z9fTIDBeph5|JW2%ASyM;I-4RZ_uBNbr5ILkUO&J)V=-UT-X+3SH+o&Cyxl{~al6gf z>idf1_(dx(8Tl4OCd~dQj~T0)f}GQ&YVs;q{YP{*->85Z+?8Nf`9&?~9jo8hiOrlB zyyEd!C~OHNR&=woEE0HO39pji8sanT)7ewx+^$*KlItj~t{vw{+0L0n0-U-$4EEBv zT&jCu`06Dw*7dFfPuZ`&a(}3V4EM5}-FOWQcDtG;@1*VbEb)_jj*l$HAF>gi#FKLq z@N~Kzy_*%$l(XZ&0W2NH?ST0tuE|bT)2`1lm!&9?v!Cyt3Yzu$97Q$5KN-^D5wbS;O8gVyT z0D07H;;wMFj}gM-y$?Yf)0p4C*YiqGUlRp6(G*r!I6U2AifhJf3@~gu&?jh;cQ;OK zmg0K*n8aVCryU$Hpi+uPtRVoaNak14_xAO4OzCvUSDXUb>Aia*WVu!AYY1t*#_XLh zO2!%IA|&AX+FYo^8~tDn`&6XfEUX3+a>05gX$gXa`(w%Yq+5A78frS9ut z*t~3#)R#l|WtMdQ=KZMBj<1`5iNbDuSF?bq9Penw&HWXDp9(qff^_j3t>cS!RrWRp zn2Q+3=P^of&cZi%P%EX4cr>6LRz7Vul5Fg`{Zis>Z|bkSB1sb=>FJ3&@6|>F1@)%+ zTau)BxC@S}j219?P`YFc4j=>#n5?g!zFn^oL+LvLfcW~x#<4|{8P;^VAn*{qB9BY- z=MtV}1 z^R{-q-aX$LEq(s9%Nn0wsXXqPreuu+YjbQa*v>@*2jc8E{`f^5<7<6z%XB)sYgxaI z%`&^<8D- zt!FCNG{?#}adY#%k8RgiwY!R?)NX4BWF8YfCDH}ANT;igap4lMatVPt4s+bB!s9gx ztyULRTc1h0M(USQg;y@4=S_@z(~$EcCO117hr?4iEpiAu$HduMh0wLEw>NWql`4g` zO=2~R>m7!_LKIm=>VR1mh@z(9rBj%tggaksn%?t)<0sVnwVeJ=HV$f0hMt}s1t<#Z zPqtTzX(!hb>BI62+UfWB?F(8a^y|F_D09c8&P^NFTUKy4N+Y|^R76=f!1X#JwuENE z$kq}HyPfXvfy^GzE2Yev=)H=4q*CT?(2n2Kvn0TKyEa#0WsOM5GQZ3M!}dL(TSjlt zae9_C&A~-y$9n9=to`>kJhYs*ztXW|;<(D^&A7*DyLcUO`cD%%v*`HW%@*C%Om=vj2;p5JW~+*{1y3} z6se-0x|<}dquuTbUN#UED%PB+Z)}v(v7cr2O@KX?W16`fq{e5VssvyE>As)!qsTF4 z+OCSp?SsZq3sxJZttJxZVUD1EU1RPA=kkEVY@2iXDhX4Z z?Z&z2eoaf}<^LD}&G%{%u(s{fx3C7;On0=Zo=O39GGvVcN&+-Xd!`-{21CQSm&QwB zukMEIxrxonogrC%6&}BwHs>%kc8S^W^QtbRM{;A&4N|lvm^qx%eD+UGd?aY+uLgAA zaS(R7rN>_qRaa>hxom?#jmaCf0e;Vh$*nXw_3f@<!_5Rv4wSX-OwS-!+*HoS_ zgc7lKD2|CRXW7!rcnuBx(<7ARU{UjyPaeNoe%yRx@&(SmG$)8#FB3XhJNvtG9<8Wm zD9>|os>&x80J&bs%FeGT9rq|^u-*O)F&U9xHuW4{VP|(9By}m-0GKgme!gW(Ca>f1 z?c2jjmAXc+JJ}M2Up4iuVvSXST*K90n_ofWuen3zprX!b{jtZBG-7s2rT;@baxKS? zf#I#=em6%dzm}1qUrEgecnnkjkq%tmv^~CjC_xiwVVjT$xe=@^6>UGu8 zd$TnI+jhwVE1cO&Hzb#n2b%IH^y43#d#I+e{%t>c)n|bmZ$<9fTyK2mGSMq5+jaNd zY*g+9c55>m#tEkb%q1t*o1uLorKfjQ}#`br{98=q| zxa|u86z4?GBq86FbK8LQ%R(Fb=;m$y=^Iz>N3{;^a`QUWOPs^XI}ex;>J&4z)<=)* z#Z}y39#`;6iOPoIsYg05m4N4K>@Ck@ypmU;FfVosYDvcay-jXyJ?aD`!}~1xOG*SD z8nUP;@nx#3k3oXL)2o)QmdX1hdhzOwUB#ZDMcTl%Lfu~ps}u6pP%Z1B9B*6g9WHfo z;p?}ZICfn;;p&-!3HzAteg)zmZfa?IZG&bnGMCyn`%M`FHVw{hCH|(c%p4xEh+BB% z*v{VLT@^|oPk*djw?4w1c_ZEW_cdc?tgPH9%cqw|OcRcQ%a(z^ZnaiYve+!#hkknW zoR)m~`9V2PtNoGCImt=)qRl}|;@CKFDVuz*i!b#r18~(bomOibIMpw~VOc3)YLbo1 zj^W_y-(0;$E%8!uRdrBg<(vTE2C4GU)zx`N$-!!Ew4M&1)ig-XonO{u{hnj^iOua0 zduJ9G57SM6U^IF_w8lI3(tL*&nd9iLK0 zySacoxLBjbD-4&097PcqjB?>^TA5|_nk>%g@`AQ#&CHv*esm&GBbI%lqkvT^5l1{O{wkO~~mMMKj+Ee9pFnlI7O?_bks}a;Ej-1$o3~ zws(kMY+fTLfkkZw&?A`{8vc#H z*_V!fjECdsQt}a(Q7KKLRxXD}(-AAhSka_S;0$!y!UGCJ!OyN#v(tuCblmXCcEOsu z`Ijrz(^g*9uyjf&&Hklj+vpY3J zYhtpD99&Ze2M&;^*?&whVneap*{6DNukO^Upm>#<({$90c(Y7Ays|ZnsI@Qk4ydR~vzgFq7)Z|EOvSjg(%d{Ndj$sI>&Ob~cYwul=6I)Zh zh&G#>q;ml^%j+3Rn1LS*U~lztOIw^&DNe~S4-B5%?IV=9G5uoLr<7%2%p^H**Bvx* zNi+?~N+P$Fo2=2`vgeXpp1uD-^*yD#o99GmW1>Y4F`s5UFuVBWHH$PE{)mNY_XS~U zm)K<0+|pjt`*_PkBZIEPwCns9jwsE<;F%dQY834ZX`h}G=6N>qz*XcOADW-Xf{Vsn zE`7!0;|oJU!^qlqGx}m-|BYSi&TiaVtrjXUo|TYXjM>6X=2X4JHD1KtOhb76M> z>>vxu(6L>4sVMJ`2^j(&iDkRZhS4pJEKQRK4_QEB9CPC?#wx?cwY&CS5fAv3i~Iv4 zK&oL;#TLDvKMRQrT||J`{KIm;Z4K45+S;=*NF>!SWPi-+LVCVpV{;EZs}qif-zCu@ zI}^@EPXdf@v$}f@pq)OB;M_1l$Jnr5^+t$`Yw88S#l|o*Iz;axd_C3B`+akUm$8zs z9QzlEfWT~8j}5rCw_99>?mZ_-=9=Q>Z`y|$Y-Qw~9vh;gN%PqR;jW(hqq{hJMxMbb zDMW!#oH<5U65rJd!;FpvYCKyUosvTq;m(}aC)iEE0q8080&g?FAVr5c85u?W)WF}) z82G<~LzjcjXh7?IVvoYXCUV^^Wp$*Yrg1?SQ)VU0HqhoH`T@~tZ$U!zjSFg}>+Ay= zY0}q|V(P}IJ+A3;eIrfJloZr|as|0@fO+4gBXYRwykBwL>xx9#x;1A7pQ9PiGa)Lo^z^1BwM4ox~_QJ{1)ut5YdYLEjO00-z#{**iD$((rg_OzEj=Ra~ajh z;_!3G?#ev^0|e)W=g}$lJQ81hOt`DO)U4Pl3`TCA;bdGVCs%pD&-))*VioeS%ekdb zQ-A7FiOPL3Nu62T7U4wF8921uKomGX!u^#Dz2?$AK*d2sB4hq+`YziRGyvFy`&|hb z#Vlo02K9wJevok~7AoSC1z!GiIYcB{?HG6+dI3@rjJYJm&bkWG-8FX&ht6+L0auA? zA7vrc*wwe!^5m-&QyQ0sW@Jh&C1a8suPFT7)v7QXDkIx z_Vc$0|GPniDIQdC+9{%oAj)g8b@Qui6B`<-D*3!T|Iy0&3)02z zzO^H^5J?&=eHTw?VU)txS712AH3xw$PK0?M%IWUJI%YWHvi*?fNrXDVeGccEcnudR zT(&zH??P0m&ELnKX67Z$fUzkfK*zCU%`(U9qRb`7pHiR_^OT;iCIOyXN1Q}Tj=2^l z7>EXyOPENY!6UqI$o-0xvQ-fPY9q@=Y81 zQqL;|KG~!Ta0rUIv1i#JcTA=9(|NN&K_x)g<>vtC2qR+Az@)5<9p4^{jC&8Ek>p$f zrza!?&ismQLxEWt&FDpV^skMz&GyX8A~d`O$Im|nKqn`bn-#A_AasME_#tI& z>iSDL{mF$LO)BB^tcdiq-@?mX28E0{S)AWadj>eddP61#gh@l>R}vi9m11!2ld7l$ zd>*1NHM_3RsFsf5fZTrf5ha>T+|^}%5u?xMYw3+Nd?k}u5m55XF!Sdj+)Lmapc$|` zC2#fHT_xkH;|Elmt#c(W%%mv5@1y(EF4zc}@A)L`Jp-2VpK-JO%b$*yoG+S$ebnu@ zHGXHX-EuWLz&S9tp#JS=Ygg|bc|F6pncrJCQmejLLu7E<5a;Jsw{T*Ym}+w`v*0{S za!Sh0i#Pa>fMedwWe{9y=>46?$H!;I8qtmp{?q&5&coHsO`=G#+U!pYX1Fs~3=x!Y zftQDflAiJ+%tt#c42zKY7~+FGAsEfP#f zbmJL%?y7ZyYzgRa?mXGYym&!o0(2=xZf+@EU0uh#XhCNF`Bc`{);o@^P~bnHs$~SO z7KJUAp7*{!2`!dz!Pkbcy^sC+@bP@N`kDNfiQ)%){@dDN9fpF$`md{F?>|BJe_KIn zc%)eR|8-qQ8i9ks{nw@I5UuYY@ZVN1P3(yW;*N<>vWaRkW~;{sb=?NIfCAcF1}+ud z@>5q;)fte>|I-@s_4jEbPLX2##l;2T!7Jo+iZ@?evDMQT?Kl%RH#by1V`mO#Th+WZ z+pi=^s>s`puscoCaVD<6jkA`ST;t| zj)%(JMdn)I#E63FEGwuycpwh%$O$Xq05!*_HLBUg?QG(!z5TXNqJo#t2G1V&t_-~G z;HF311eYyXa26~ZeU3l6=H(Rref`R4A>_cyJ;5o<$Ce#cOSI!x!^hW9K#FnVpN>)W zuQutyy1RS>uiWvniu$R#|t`Wf9J&C^3|S6-{(e%g>~B*Sm|j4C{#-hFe{ zvErRKy=#p<(QvTif2cDA2kQbejSBgUC7#OU9j+J*giDKO!K#23bIy?20y1o>{ z%4STGgvi+zBZ+?&tg^fIj<+-s-t7&YH*ESFK8#F$=Y+R-HrW{snKLa$gyg=}?@yJkz$Pkm0lPP@lBRk(i zguZJeM-1^p;CjW7}RwB~d0Ld&})PF zY`#d;|M6zee;x+%zkc$c@BYkGWyt-%e)GTng=427@caMcZ}SJg4__;F3q)Z|b8FU% z7Nrv7z#z*Mj-Zz>;8Fw0qfNQ#^!%Ir5#wY8DS6iG7er$e=>%C&$g{=c>D5ZvS!SZd zBO%)7qxg6FkDKzbbTienm;T95P(WRXhL_Z#NvfQdh3Ybaz~9%eLE!HM6_ErV%<%b= zm5HS2@TjrmqeoK8mhkE6{!>H-OzZY-ogkJeZ3I$J!JT-y`Sb-z&V*X1c=br>DuJRU z0g*7l1jck54qo3MzKF8rfx8-%pAdx_lkt%v&>=>Jbr55Xkmy#qkw=OnhBt#A>8UjRHk+ROpZh za^{1m!%nv)?7uM}NED*3pMUOlXd$Ni#3@&e`6TtBcEV=Xj2f4kl_gLFqJA-8cv(~{ z1G9b9U)J3E&zM#d3f94;zU3Qe=pNr5~Um=f_h;D8~ww3RRYp0ENj0!$AYNnCAUw zO$Nz>cB@u6jfUxygBEN?5R$AedUC9w+>>iTqJ25?6MO4Z#L$jV9A(X;1~HL(0T+i$ zVaV8F=cf5$RUMol_4Tu(j7DF+HL3CC#6JXPP94eWN16>u*rTW69!oO?to9axUz_EC1 zVFuec8iSk8&i~Ps-?bpzKo2)p@>k>d&>CcWEv-tgkd_-E*oV!E@eM?+iLZBqX_Dio z)aIljmCECg1}M`xcLx*v@tt1wuKu)2v_O+6CA=0lHh%2rmm1*;O9FD#ri_*sQulIz zhUcq}-27>wTe616HgS4o9!JpqJ^T!24d4FDm&l(24Vr`qG3by2GLY;-(opv07)6CE z`{$$U4>}r(m(>bb8JqJ}gLtZV_XO!K;i4t*EP_Gf{*xPIsHWZ8jK5uWF_zSeLg~V^ z(o~s5S{3p(|DZgP2aN|W;E|x*9o8p11Z>N4Sowd_l!!zTMr+aoVk_$F82S$u@XED_ z_f~%#rbp__*Kl<-xFIqz`36VS_TN8Gh=&r^!C&EfqHxpDPE0bfcTcRzrYeIrcU7S8 zH0Q3(nSs80bZsp%0%C&^M$S`=Qh~x$!io+^{Vd^RRfWyfu&_>qS_Xd9eCWiY;CSYL z0AfL%zA&TX6O0XZ6L6c6et`26wMr(o%f|8oGc)rnt?dv=<)i)JBp(jm%5tadlS?mmV_4l_L5 zPhW=*llY=I+@1}sS*KP=u)Z|Q^wbP3J4cc8Dai zl&THTOPFj<+PnK185?JO{4j?)TqvUcDL$1(DZatX<&XGp7guOJMKnOr8!!+4mjB)2 zpxtYJ@Jx+*B}Xc>$I6ZB2_8ns4=rKlzdT4W*kPT03;A^1O z$R{GKFU>JOzrft$7SUAxfzItY$t(^hZ5@3K3=K0rHcU^@gViWL*N$jSQ>hh`L^hU~ znwnv5evOUYIGI9)rl3bQTXA{Y=o=nmVtky@LmhbS@(Sd`^twH=T`|+Mt|{u(mwM+}r~5i<^Yv8FHm6 zO?A(?K)|p_&8&S`)T)Dk#s+gy#h3fi7i%_W|^FtV_|uVa3V*s(m>N0Fxecm zb@nklHo?T$Fo(Llm}SG$kB!!(Uda;OTxD){mbt|>Hh1ErawTew2LV=-1-G}2zQMzc zj0`b!s0*LN^pFEtqnwQ~dGS3yzQ0SnQ2+kt3Id+dzvjP~tpq%lCkBiT1{#e@o^)h` z`ROSpXO>voj*`rjDA$`9WD|C`kFNefM#qnEWb_aLrxE$7_O89>pw%g)B5W=%GCMoR z{L&WTM2148PNNArgNViM!r$J-q2Wx)cJ%`mgD&UPqCrdUA}49FHMPH!6n!(&WLjB|LP1CQ;8 z*>h^GKq9=!%HkZevrDXRMTw^Jl&W>B?YU~ zOMA~DjvhbG=uj`6KHKAizM4v-Rv;bOW^wu!SFcVoyB?!tXyfdgzrz{yVEtJJ12h`t z9I40#bJLSd&8)Dt9VM0hT6Z08KV1VujE+xmF7Uy{yDUbEc!pl$H-F=% z(`WhF1Oqg+LA8)zcWr^Gsaa;{*V&Gw$QCPm0Xwq|PoSN?p)rmf9cQqo?T71bqf92c z&D!ED)3b{#t?d#`<|vfwXnGN=!%eWWm!Z)KjvgJQC*Z*P*r0ENYLIXW>+m*0W%gM4Bw{{KY(&;R_-|NK+G#EU?)*<|w0easd! zeS`f>{h$8_^-=-JXrgocIQBr>GyHW8O?w(s_2~$QL)h(h><;H&>=_3UO|4RhuX5|c zyS(+@XWU%aAy?JV8zf{_@OP+!QwLoIy9-qJWC*Jw= z8q@0$3N_FhWMs*JfhN^ripb6~ODmgf#T&S~d+}H#>bVq~3s*4rhzJG&lOsT&_ZWii zr#F7JMw!^^ZNB*6UH+f9uClzFrrgvJ6&Xbq5!4#lM1<9aMV7Z>Xl6G)j}wdW=`v@v zW{q-ciyNQ3%iC{#%7weD#PSt1L60bjNTLp%Rwti~v9-3s+`<}>oDO$e0GCzyD)^wO z4GQr!?tT6dfBfUeT$|k@S*jx{Ml2RHW}}EsYf#E2_JR)c8^j6%-i{93RvG;RCy%CS zWHK2PMZst^{)I;OCqQdb%}3e1e}RAd*Z2A4>O4D{GMe6itVoD@fo7#ZVt13d=@~+K z4U^kX!2M;W_>X|vpq$=f@{5o7=<*yJu`K0k4O`D~CWg8Qy1wZkY&06AQYqYSHwMFV zaIn`J)Qd6hfBr6idh0VT-&-SIs-Y7_6h%f9G-|~RyBlk)tnLu2$OJnA*iF(?=}ILN zCcM4DYP5(bNyzdO{z(ROs8mX2%9RG9cbMZ7{qzPb2neW+GV!%3u6*QcWc;uK720gH-Z?IN`-Q{jMM2vI6#gwtx+MdIms9A zzs-O9_sh(0rzkZvL|Hsu~^Mm6bYSLC!dP4zO=y1!WJc+1*hMK*ZTEgOj8?F z^I>MMe8~U%Zy#{s#v;4vBC5`SB#TG}9a^JGCK_UWb&2Km7!|#PK%4I&hb5@0N5FFfBEmcdufWrP=*?Mj3zT?i-J+qq1MWzB0DV1&$GInMl-t!c%7JJ z{ev~wq?C>@eeDW!+Zpl=9Tuwzqar^+H%07iLyQl1)8Vsz6%43Ws}zexTrL+n-N8wX z)0$P1n^Ro>^nL!Xf4#`;MuK7k^pc38i0HLCg=CENr6m?tx2Y&Td>#ijqx4ix9!+gh z%ZHi0_9^eY^&y|!Tq2ySp_gP#W)l{ZjHHKZAx&swmD#yP)*>~W!FHTB<-wk#QHUql|Qjwmx|B1+=4z*FIR4P*!WQ@UMynZ~0%_O2}8ihguy2vSGNM7CSuK$Y@31gC$7ZUAB{m+-U zHnl;rSVt#H$g+s2*Ql3r?5?e{w7fyOCgJo2@Ys!C+2^o#rY{r}-(MqM_@?gGidn)N>nyEolB~#h0|A^?`68qHds)b1P?|MkD~ z$4~AswHBjLYa+^fbD`Jj6w`ZWrIqyvb=i*J=f!H0zH^ISYu5K}8?8-q<^8vL`;)uO zuE)riDpXYy!M;Nr9_hkmeEiMda=A>oT*mEo|IpEUF3}oQ5}T7;`{X_T>%U%NZYx3Q zf$ka=@vF1#+R`G6YrE8pK74LFHk0&p_NAs$FC|&Idy)6v`hfQ@&9ENN(bVhr^wXe2 ztCvWIcUfLsWFwqM@pKY!@7?PAeqB_dSz+t$`+V@pZSF3GDO75Rjvxa=hZ*j&V|Zx4 z{L(g(BnhL@c%XE*UP`bvbA>{ZZJ2uOj@(x@_O*tjNjD* ztw}Yv!@Y~|^48m*@x|mO>57U@6pp=))5^8oP7B_rzZMo zvl(a>qbyI|yOJOx?Q4^;-*UtMojd^Zgy3WnT5UY2-;DXtP-Ra^~ zx8+ADr=-!WCfHfN$LE*k2xluG2ngDXGUgi1T8{YQXMFJSZRU4!=+QC+J-p!TPGc7D&PA~YQ0Ek`3@I9 zyT@XrN_S5iPRExef>cV0P40bhfe$Xv5iY10Jw3ei>N$=a?jz__XciN!&EDhYjVY$q zV}#}}@yP`*9;c1t10KW!ye2@SnqKDK)h~GW(|Hm#0dMzV&c1w#qlbI&Sq&5un@nE6 z%B{OgtZmM7{bLE6-GcqhA>5|@nqex9dY<*WSGf4ubtX4+h^`J!|LQ;R#_18d12&9$ zjanhe`s{T+{rCzuX0}Arf!lGOp`e53@iLj#tdR}Pa`ob6KEJg=UbN9ZG{*T~ zyu?_K7o$)nvAx9o>o>VEwa)I;H7+P-%nlE~9(6oL^D7m!0<)Js;qy!PS&7x~ADZC& z>%ZjXV}o>hEeL9jTx^s1yI1-6lbg(Ku5#tmi|7m%g8%6ZPEkV#)Jqw5?tRMJ?_XhZ zEsf6NWnkBD9@!6CnC|6`-o zN$o6hRx6O)Uf}MP3w-eT0@1Z;K6&4a$L-+! zLV~uD^zPukSsX6j`6?z;VkVg^Ao>cqS=ez=j7m5BGIU4x0t+fh4(+5AzBe| zwjbi9SI=>Dq?dqQq@3Dj_RbBiUY}(xyvp?t{*2XX#&YHmZ8mA&&uP|jY)#$Z;wM+Q zyOu%k=;Y{Yzvg$Z9HGl=!6-t#lwx!CCZAut#us$kW*y}|bV%Un=QSe$O&7)`AZ?EvhCl}F)76N~N3a3Fshejn6Vfl;qdF!)D zR%2y)0@hFf03ZNKL_t)H-YyOwJI(pCV|2J=C@0xnp5l{_uCp4AF?sm{CYuAB^A-A> zhHsUUI%w<#)nkjF@#pt$vank~u(dI9>I`R29;U}@Mpw_WwK&PuOShQWiZXrWV-&X^ ztNAGXzWv&lfYu}zTH*f3@ABU-E>qRXxI2e9e)cq{CI;|X1WJi5X7AqQi_6pOhF7`q z*+pz_FZQ#Ca2X%EEu=Lm=Rz#p`hxf0zs$Y$B&yMc+ohvYERfz`#kK>AMlHL}y=#|w z|I=AwH68AbLC(E$j-w;p1neTE#1=ERZ*cX-9P7I)T>ao3>~<@*Q~h`?;=Z5Ls1=FK z-{j&am$*6?rfRSf=sUujZ=7YY(}hJ>A+^20^~*Q8GrPt1{2e}g%Y?)E51i<6Vv(Nw z?a>-#>X~^ye(whJ8%b*D&3Q5t zRcPi}otkEHYK^2S(>{EL-~at@IDV)Nmqo##2Q?U^qa%pV^(h~Hbc^ksbtZ33GB)62 z$Zy$~V_mCPDMpr=oL^%zQN|J+;_REh=Wl;8gv)G1k@V=$XmFnrW zXt)R4zx*p#XCti5OmVNLmtOxdyhg(_l`2siMM6tcT>1D4Yh^u-&Q3h31ly_NkM}wM zl4unQ$!#vbf0fO68QD9)%fI<8Z@e@{hs%sC>OpO%qoa#}-^Iu8UgXANg4>^6X1Lph z*V%)8pI#?}V#OUWV)K5FKB!f);YAigA+l8gN8f3Fd3KOqp9ujCt(GLbF~i-d4U%OY z&Yq+E-GBZYP7MX|*o=Gq4Ad^VyF2L&da?cS13q8N5nY*Ob!U{mPB&iVfUXHtXckzX zondlvg?K~6+k2G1|HnUYe87+AL6)=H9;Bl)NJslc-g)~n>(MQy?@Tk&=f~dV+Mgp) zty9bGu(Y_w%60~WtCzzs|BnCiyHj{9rahe#z+^Nsa{5gqRP^-{AI>HTtesJuyw`_G5z*14GuTFNZzpcsdwh0nft|%! zZe8tTV&E5eC1HO7C$&x^v%t*44%^8Z=FV}>z41GK_0k~%PVNmXk%2B%9W@OQT zPHWKK-cB&!#s24yxv`Yu{^e_o9SY)g_2LxwH#llFO>}pSyK_-$O^xo+SNYYOzu@%Y zc5EgIgHDHLG-5QGvDjTSOaH{E;7F!W~jFft7|V9pf;;iYbxj@Os;kY`UmOs zJ~q>My!-~g`OSGIy4)CLanGI$w$tC=jqB}q`0U0K+Y2+? zzTU@J->Z1`t-Ceq$ysI=c8R1L*t(AL>YKmi_0#h7bv)5D+t^f|Yd z;!NGWPj`10zSG?}j0d>Pj8-9++~Vp7*Vu@ckbMK3`_->_D%r`%jgbMN!3j1L6xID2sHGh3ipjQ&xVLQ3W&1;h!?(t#mb|O6}=cQIsY)oC{gO6^qoYe3RpXZg=j$zoj z!L2KINN4`C!}k25f?8mEX`bonRiafL-kziU-T(BroEmJyV|&QH>}sdY@8G>ZUtuY_ z&D8Bl275f%P3{Nd{C$sVP|a>JGdaV|Qk;hDVfe&r{HOo;1_M4DX4!yFQ0eUGrn57M z`~463^ztI1jXAF0SfJB+6r;!d*z=vHR>{TIx%>V*++NS1d4u#gD`X5b$Sc48HE*6Dr_*Cak@N`7b^?Jm+Jjy!f4;!Y(z@+~MO(^Q^_{w2i*R>%V@3^AjD|Ofr&Qho-g@?C8Po_Hb=#i%`ji z$)HlJYjA)ry&gnb!GPxlO{Gz*P^mN!BxSEO%z@5ec)n?tlSFq`SlCQa7k%^`KEau> zemZ?-zV4SJqsZM1jf@lDT4iQylI+$bD_chy?g?PE?=Q2xSxl2lB}vr`*u5PLO`K$6 zxR17PY^*Xyqr#!VVb&MtnA=^Zkl$b@R-)_soP9q9YLj|yhqbjWHo`?DX9q(kUuI&c zi-7Z?>t~XTBn>ceBuZ?1i}2k9kRDi z_S?R>Vaf_dlfuwo9}816Oot+r3K=r_I?X1ahk7AHI#-}jQ?a@Ow0CzCa9h8w?JWrC zMH#crOJ8pX0j~|+T8?rdMLb=n(edLC<@18ptdfs!v9cZ}RcPQDJHnBp6O45Guu5OM zOJqsHY%y{E>@>TH0{3=zSYKUbD?Wmw-HiT+rckPNa-k)rZr|bNVg_T|A%+h*$lfmz zO1~Jv0JV}O8(!x2Y@DKIqHFL7N5@C#3%XIhTI>?Ctk5?!&e5$6mUmKYZO^c{cAAmC z4(#szW%>v@J$juU{gZxNYf{O^2`}Aeb~Q;u@p1Ir>Ag8s^q^@p%LQ`DIJr7lJpl$z zz0AqcJ~~{+hqCNs6h)^0&>-1~DXwi~spJ!Tb=WH!-h*lgs!bY&FdJ)ItncQL9DW8) zy~c^*Zrbef*X2$m8ATajbUexK$_l$TqC~e>Slm9zP@4mT^!<)cO;u@@a-_0(a+M~g zPA{DUL$tfB-_SWhFJiR1>FVmBr^AVEDnX@~C6#^9jQ%;Sh)~UJv%0p!ZnAgmDfFhA74K|n7m*qlE4`+|5~CKkg*p3!3*IdPn! zEZ8hv5wm%eiP0(MR(IK1&X7vRN#*LOK8=H#b*xr%WFl)^pNvpw=;<67S!F$vWhu14;#!Eo{!X0U{biDCwKBzAhFHD==sb`}kb0w;(fIrYdS9do) z`@_v^1@xlvYu$C4SdOG9VUmp>leA zy4yQA&haB_tVgn}?9Q>cc8-DGb{wAl>25U>C$hcGda{V1H*@INNybJ7X!qE@p$D?m zhbYuJwYWz5ZiL9nJgbqDbO!8rjrzSZ^=h43tqw*nBWDLWb?O*{y-v0(b4(rlD_4(4 zZP3Vv*n+s_l$vCRo zpb!tUwH+o}P_g%QGk)qc3vKb9mbg0VmcnD_H)`_HI-6wgVpt2qS-q3o?%9h9A&h(4d+Aq zqbx~C;s|HYth2He4|Mvo}w%uE*~2;#3R=)zm#O9B5PLg+beE%9Yrj=f>qr+*yo}F4Uf? z;Z=(tms&1KY?Iev(M!}wi;RS>b*oOs-JWCLhwkwUSt=iqtHP}L@-=r+6I7|F7L z!`;rv#2{{q@|_@;&S1jZ)y=?AH%>#7Vmiw5dYo!we|JN51{rJH2AZd072XP8_(Y~ z{HQc*6*A#%b`yC@O%vTigY@T!CrtWa%#u6#Ln~_uJI5OCd-MHUtus=Pue45nO8ms9lNOrmh`{@ig9|{CKK+t1$ zcJD&~nH``U4uzO}9e9XioU$KWA)I(=BQGU@mZi>pa0 z)u+&v2NDlDL|HK+Je2XT9rP{!v1n?ON-{!tCq%rcVR8f*J$V?PP3AinICRRM&W#P=5jASLIGfvX zisgMYWd7=bdwrKQz+e!O6$PE}DD@H$B?+TZ-qS%%d+J%LmlLeaOmXMlDmlqV-`H_Z z9d1MU#@ru3G>v>{uQ_PGArtKFqpvTBP5IU#N6@2_EOZPH($nF^qLxX;c34_V?X8vl zJ&dmwo1jCKWJF1PL=A8OL8nJnNTER?<}v?eq)|(AnnvZeJZikJ0X-`%o`! z4l{;YlC_O6k@$Y?ON~-4ODdKmUl$MzJ_d%m@wv_4(F4JtVDWS@a=06}Nlz`a!|HaL zbm75wM*u;u;OQLUP1=rn!zy!|udOZzgk8zx=^vopZxi4nZkN9(Su zt&_pgK0F4Mawf*wR-96Gf4ZwR8{|`IlIbiJO~&O9GH|Hvflc$RGrR1dYoL$e!8YVZ ziEMm}?MQ)A?a{WrTFVjHoag$LN#-IoI*y*_-RyNZ6K1ZvKI`Pe2vc(#RHah#d=xYD29tb)S zv%}BuSU*9x6p>aAEw$+-qoRgH$3zCR;)k6wFp1Z9WO{0B5l@Y86t^7`ajnO?1=I z?#AtSe44T1>BR4GV3#+ErPIV>Nh%FDR-X3iy$V{H&6!)=xH`#NUZU&7%e-=C7;|QZ z*%xNWHOhq?vF!*&O~7UH5DYl5KBlIpPBLO~`v|(s$eRh`;V7wej)rFck!tX(6yh5! z-nqf`^Dn~_72s#4vby*+#nMIQwr$30_CXy_ch=ih)YIU4u!}mI#1f3p()rH&X zz%J{^XR|~@AES1vLxbJRGo~;;>PPzke<7S0UDr^jzr1iOEg3qUauFQ z%lPPqqk@3s^yBlnaGP{&6!V0(!jz7=P!Yd3yG79H5#2$2b|YqemTWvhGLfRv`_1Oc zpwVpBNF}o5@?|u=6`S2lz$2p5flg<{);7r5*E;qZZkw%Go=}@t)6@sPFax3}?Ul1Q zuxM0@1>&I?c~!%t_y`1?IING+IfIPZ9U$PcVl;$EL}Db88S0u7X&*YLlg(HhE&^7G z^=z3$C``66KwVS5)gMEp(WsD!rzzK(=w%mvj}5E&OLs(rW}`;6t|FjEQDpSO-giQ6 z)@jrmG&KQ(C}Gg+IM8iSzJ;nb$tKby;%O?HjMMICp!@MUr#ISg_&aE`Nu){@;?X$y zN)?rT+_De^3}!nnrxS;wC!Nm`k3=Y`K}?U(xqL25B9^5o7?90gJWeypeoHlK4HD~f z+`m7^azaPP$x%+67^cnk9A2OLQPI$}Cdp8QY@tF^wBz@C@VWN_VBbN|Avps0ye?cO zfvrN0&~}9KQRhB&*MQ{iz-u$2=yGHeaZ;%?)h-3eVECr)Hfp5e8S;fPn!$?Q?#1sG z5d@7!qfV(*q0!V3^mgnvGbYnx+=+q?i`R?OZb1=3WYQ@TsUpoj2M4oI(4K=nz8j^e z30RF@f&mA%$Jv*n@<4YjD26ccaFk>+Lql`y!@kt0RjZUsRa8wtC%SOhW#mVmTLp9m z8HeAG!z7`Loq+m7^M(!(YO_H$mLQQxQ$@jJ z576Ib!SI-KrorU+N_R80GO=)sVx@*^m%dkbHBF^bu28Mi_k0T`3wGP%Y#ITh(}m0L z#jaB+ma;_S87kE}n7_3iwHleoI+HhUaeqC7+;xW6e|d_Lwj9&b2XP%fi9O#zG8`pS ztfGnz0s#+Rm-5I)&w^f$}JzMc4JhIxv^mQ9^KVY)h4-YfqFwjCz`QY zO_)vkM>b;CixSp=AD7jHOoB{0MI@R-?ed^$Wr~?7tDy|#hQv^35U*WNW^0b6#TB;0 zDYB&+nqI=<@Y30Lh(mpy1l*RNK`*6)K`R*WlcGVhOe(y^)=r#)-j3Ijq1IYFKQRr8 z#RA!E5mhH5o9)<568gs}uTDlb+VRo3B@d-m^Cy61mSUR zp*s0&ig+wVwW-Ho?xE9f#3Vm&R+EOR*2tvu6pK}m92jjboF?64$57B4F`DeyEfQpF z6jCX2^(JnO$7H_l|6Me-NuydOpG~s6Hp{K6cbVHMV)b<~G`82Y^~>7|qP2rV!~OKF z?s7N0&dlv=c&#c&hq`fFjTnRml|q{M&NA0;&a$$b$Lt9*c;q+(Ug^6TN(Tm&M!iBN zU7*^~(3xF0tR_rPICKl53%k{f*{GvdDv-}+C^sHBil64mjS7X(3^%XcWoom4qvr&# zymp3uzlBWkMH0&fl~R#JJdY;mkjxJ3W*PZ$yRaZ4DpuSM6OuuokWP{>6sTzYC{19s zYLe}xS#I83BCEG?^zbpp2HLS1zZI;}i^wKBk_jH9ML)(7)}WZru(=kc)&!%)L%?Ih zdSDwzX{gN_`AnW-u>zt6qixSg{kZstpjR-O9XPELLcUHhohDyz($L_0{Z~2zqQ%eP zNI!>`Ho3jC%hK%&eAc03tS^YqVL>)LxMdhx<<8AX?yqK$?LK-BkJ1;gVSMf^a}B7G zN#!V28t4=YR;vw*tbfdROaOxoo7IfXBGSxN$R!h$8V#EJ*(-D+dP@(ZWBshha?FMn zxOd|V+{V+4_O;`-8_{bGO1T8PYqMOtwZLYyf}>-Mp|QjCIKO-^JqFo?T{2k-BAqIt0tT}iyIDbboM`C`7-Sm`yAeea zNM+LG^LZ-!SrdRDS@CuBa{NdaQ=u7ROEciXN>|A)gAfxj4zS$sMva zk+wtQ9PV$!^`$6c z`UVFW>RaQ+MvUcqm-#3tacr;?ufvR@heoYHGPK6zt^3?vP9d6I^o<{*Kj?U(UGgx^ z;tmUwGt93g(EA4%J#v(xcIRFnoCA#pR7s_Bl&cN&iVeHff<=1V-Yy`BHtaStHnV|7 zp-ldP?yCFLU4yNk(Xl>O!dX^#=DBm-gVk_?(Y|(Eb_Km!ryqR z7#tg+%b`aQvXTbW`q8=p`9h6fp=Y#X^xnu7Ikl9L%B!P0FPbsdN$bL4uXT z`efY|6&nt_30c&UO{d8{m3{g3o~LQrgAC%w{G?8YK~eTf@o7!c$uy;M84c^+eCkDH zqX7vX>8Sj9vUiToW{c!=6*Pktqt%7mqaGq!wBdA^u$m0i%O!HDB&B9^AG*6YdAbL4`sK~m$IYpr z)1j9Y6w!bIm14d?CY`0JdC=D?l+r2U#TpGPSfnC53s<=}KgsO!HjzY*Vx@tm-%Doo zcl0tmc8oJ;PcYo=!T6mUvn`%CTET#y3=K`KQB3Tzxg8^`+3D)@Q(4$1bYKsOF9=$V zO0`0V2hABDg&-I(h(;V%2|>_kmI{=rRce4~Uk?->Yy^)NOifd%6(Vdb z&#}0fplPttF@Bc8HXGK$^Hwi?Z^J7T%9Ja01W7@$STXA!XR-?*$VjpolgWUfmZ{}) zJKh*KrD3VKVGc&bGx>TZ4DUr*>*;?Bqk}4y29Ol(yr#XN6Fm1N4OET$2Cw=25 zd8JUHab=3o+8sVBMA?|{#_Kd8(x8+}5!=~dWiyH9>gDvr8GdB$DB&VuW)l_hl-__S6+IV zGh=O7ENI>s8q{j^HmT8M3V)hBtAZKLeOC_7_pco^ag=Ou|TO(p{j!Qna{FK zvf&kGCuf-4u3+yv&ao4R>Gawj-E8cu0Oey9idsI-*2)4`rXnFSS%tstx7GQC*Ro9x$j>SI`pE0?y(b`&y}cs zai7)jJ>L1Z94iBRSvZOTYULcU?RC~RqhysfPMti>tLG-@beW&ShP8X1mXhxP03ZNK zL_t)}@_eyEt)`+=Oc+f@Wc}mzLIDILMxzn4QID3WQ^{s1*Bk7!s2u2BjGTUnOjV!oLjwftPe?9!(a{>zYGv|;DgdIzicyxHu#fA|8;qDu3Ils#wx2N)6r61XocQHy>}H$HZ$+58@-eBMWqLcjSWE`Adinoj@4cVoIP)~WPulXn zs;k-?G(6z}f}ppvyL0PK?(RbRMIq_$QYfUj2q{9VyN$b@9S(;a4h;xz8$frXy{UHP zZQ55qWPvbk!7*fG_(U**fzHax$~W_Qzy6`Rk!OB-hQ+E*&*9fN|L!GT8_W>yRI>`( z#%>!}j*DqjS)07dr;By+i_0vn*JznG0#I~6(PS3`qenS;`W&yHJ4SCROyDQib@RuA z5GJi=i$>Ez(tP+rA;QWI!3ar1)j~wV8ZvFHMxDB4WA7yyfP|t)={s_Yw?3$0eszn< z{C)oG|65`1$Piu0Fab?qx9hAg%`h{!N>R^o_N_C#|K3@KGLbz96$`*-b^Ho<9?Xz$ z`Z;js1gB06lM3s9U;)a0fIx^AwOSj)6es~tA7f|U4H5|W2?kU|(V|@~)3hBN_7X^t zk<>ItFI-}y;UHfhXa4Rt{HnOfN_=)Jjiyw~W8<7;n7&9&esG_&x6`s!A~A zM^z<6vrM^Cr`~kgQrtm+-D=V@O)LSX(WcdEdwcDx2w`CuEowE>>!1rq32HmomnbM| zfN;o%s!G_6D$Qn-_MYrZ37_9bFz7>;T!dAiRBn6X>+0r;DB(Jo%_c3&#&KPm^*U|C zd_JJLZ4umGD!e3Yv(cj2dcwP5LObxTgpQ^KiG(y{VPVzl)GY@a*i8vSl4Se=KR&;X zB-%6^HOf^B5?c#?IYt|^*`nnNEZe5lXkyy-GsRv4r(I%c{0>*XyT?+~&)|iNeDc;I zG7%l8{+GDgF2Ze6s~MPA?PVQ-VKNR1Op19(xzRl(z4w>*t_1ywQxLy zrpmaj29-*kdefmRx_O4ba2@Pclcs55BQT9N%|-*qb+Jv8R<%amvT=aI%x$hbZd2N5 z6Uhv5V%U#{gHbQBvb4y;gPY`+*C;du(l6fNXkQHfPtW=I8PDM7WWbLEAzaL6nWeco zHkvB&!6AksH73V@np1uMvS4A`25r;zL^yRFUEZn5PDW95`~ekN5(vw{w5&g#(J2IG zqsa23TU@_(lc@qka))^P!}IjVgBU-#1iJvv1ZTOey1ny#bEJ7uzER8>RQR3um6 zv|AW1{NM@mc8%ifRsQM!_!Z-8Rob1k&_Z!~hmUaaoey~D&9jW81JBL&mSmM!_aV+* z61Y~IUw?UriCf7nQ!X>`j^6)vu8U>FXr3$o9T zrmDNN0IKM^j;1PL+t`MQ<-W{BUl*%cWNG3SzrXy5rACnBADrin3&+U@6cGFEe%si# zMXTk_q*i=>bVb==W~PiRtN1!?)50*YEQ^%!wBtyC69s)D_6`r$Z8WxuAA}cDY&xcRiX%ClC zRUKVdkc5kCv}ijn_O{1A4@p)Dq(?b@QDB>GTED%{y?d9LzVq$(PM83YR3hmfj+{Hq zTOYi~>CqHn-^-5Y`g6b=0cNxvY)2rg8k(l>QfaNAYbv^~A{-m1-Ntmq9+Lq864Acb zIDg5-YB%}KSN9mdHqV{QZs)HckWlmh$?jp!o_m{j-Z;V0{_soHle%`BR(YA*U;dUG zkCv&(ab7!pnv=&zi2L-P;9C5#;PKoO9S6nlM_1Gxcuqo=RD8OZOc!kf%QRn#=d@6o z?!%Y(@BY!`|NG}JxqNq;?Q3({fP$`T=$e9XZ0vUXf(-d6W!8Y2M zVlVctgraD4_4N=AEI_r&(!w&!D^>c!F#_^4%phE>W}VfkIr60%Ek_`Av;b^CvK`v3 zHn!s+oC?zqS|qwhIC}9t-g)yh!?_p%*`&HU!~JXD@Y^qMF|oYB)!+Y~bXS^m;uO8n zy$O^5j2{O-Cj)*I2wba0B|p#nnt?BOgaiEvlxqFQzObKx*V^W~F18~Ol7uWP$U9ao zc%yw(ML`naIu6cD1t)fbi_t8y@bDYH`1DhLe}5e{cbYTr{55}bI!Q#8S^uMa&t4#~ zO#`bl>SZgax*t^*2psIreL#|t)!pXXNyxH{qIfQWYuni354eMpg6a#C$Ykh}{Ineh z+p>{#KbquFFBe!_-5?d{A`$jI9oZmU%vOz3p+KSB#E~>Y@f0zij;?Dcct(%WHgMcF zrPU=C=9d`CMaX_Hy1IYhIySatVQ(X)hY+)|=-!mi;Li72dOIZJYd)kQEh8Q&A8I*X;;? zOGt`>Eblyf+T#@&Ns_$4r{i?);UDmvxel$hamF4@FurV(92wyCcg~WH24A`hM+gVo zsFR<##^;}Y&KEb9kdu9!|M@OaL4T(;91R5Tx&>dm`%To>072t`I# z)Lp7dB_!EByh0I!CyU$1Bd(dxaz`sH%pl3MAp}72Z~%c$~4zb0{mF5hX(4+7_-5FVS%% zu$mQ0#UjOO8&~lYN%%(@LJyO7KP;n78d*IiU-L={d-6V2pp?TW#uvB zSAWC*`JeAlaDxnb24fkWdIjW5fxfgpwRS|0b6%oaE?8H;JHvRo`G{>?T*fy~5WwCdjWpe zW`lBZgN;%HQz-bO38H}jx~`(h-Z_m{8%uJjt*@{+J4-$rq%R%DuWcnD{S=N_qcL}t zZ|*L!-q1Pp#xaf^86u+Y&OJY6JmFo-*?L8v@UEr`5Dtzb5UxP#tm$st_QamUb#ZMQ z*L^wOH5wH*3MEQ)1EKnfCj4FkUDsaV-6k8$^DHd&l8FUKcX(F|Mo13~aWETaxv<2{ z?d#m?&yq`=r7s@z3VU1|+iX%iAz$Ue)o&T?j}Zxsk_r2~#I9q}t{2Ep-{h;y z+&}o9f@)<6DFvu$dZd=8Z^rbT)T3MD>vt{TClMezztN~J z@$lw#zWQzoCv}7qm)_yR!E~qi?$ug(k9SS1ZC=u+yvz5z>$=a_ySpfcDT?gHC>#gZ z@pyMH^L7-9(=x7g^rj09H5C*2w&xyDGnt%A4OAJPzCKW=FI9-E7gcY0r^yw|`%ug`(V4TB8 z4$vJ*y!3tj8Gk^Vm<=ecC&MT z#-9#P+W+DCxs==C$t*VE6)Q`f&;LQ!AVApEi+Lt*f6Z54f5+{q3W1)JoO}BNKDcy% zup<8%CtrGP)hm;Cn8_EZ8k@}+S@F?(uLMT|Y%IhpmKjg;syNpj><<~2DHp;)`AO7kL-4T5sjS6yURaTjQ zJi*L*bBpzn2&V_>9~osNBYpo|1JGHk-PY6#(h2Wnc=q$VUYbp#FwfYvYuueHBj--= z)*B}|KAhau82)oYxE7VwS!SoES*bglg2%GrBbFOxWO$ISFkaWE4Bx*KVt1qN3I9lv z^!_0BY@lWja`E-| z`Nt1C@6EUbr}B zm8G%E{N~dyx$HB%$fbBOoOp629{LAsM+WMNV-t}r(-#?6~!Oy2)J|6DAxTKbT`{ooX- z!1f~p5iXWdWo708H!pv~=U?BaB!w9{_ckAWbcvG(lI$)O{ZoWXZDWzyi3##GdsARa zl2xKzgA5-yKrRAL3M7EeUa|9n3V7z2m*hCtppu{9_Sc{BfB)B;G}So$$KK@h>Ej$8 z$`K8y2&+MPb)LzwyIj3B$=J8QW^JuR>)(9Dxg*`gdT2e zk5nv(-{*~W(qdT-o_&j0GEPi)`F}otNW1u$hmU4Bc5sN~U}T?6Bk%Cs)Lo{QHmDc? z5JB(0o8M7MR>>ZEozd?sDhh7@z-hp7p}t@HZcy=SW`y-*$$AuxM2`xckj* z7RxQ<Kym|eDS^9GU4J{WyY`khF^bvod?S;qP@rX;PgpO92ulL5khiJYQ<${CmwL?#(gI5 z{Eq)r@Obx^@1G#;SCEt-@vZ}0dgB;##Tru^b6ox6S2Rj_P9Gm36Vbq|QOwVA@77%w zN;YyRM8vddOR`sR^l~@#$AxgHt}ieNqI5$`Q~!kq%KZ85`h zU-1I(?)43j^d#MbM|kUvX=XmXOJn6epZ`~z!tx1@kM&=?%};jp9EW;>D9`9Jcn;U@_N91+cjcGyqa_tR z+{4im$C#O0rZ%?1?7gq}zy9|smo6Nmzssxst`(Mf{9ugn`65+4MpxKi!-kky@&&BX7~9EF z|BN3Wui~4z58z_8>a^Nz8g-NW)EK2Xu#7sTibcbiXD;j~77fsy3jh29{kb72D6-nA zGVv-i>|F?32nWk@5JEyyRn$FH*=&C@7u#%5FD`QX>(9A-bBxC;ZG5@cIQQmzymkHv zLz&Q@IVdUsi~0MP`TXh>^JR0>5t={3C4GcstcNaLK~ufT6yZ2H9f3!&ZIZ;r?Npv4 zN#1CoKO~`|_z1+hIrLf@$8m8S3)5^(cRNSSIm#}>#z83e3IK&zomD0h!0*% z6W=!mk3+q%$k?}E@ay}lTR09fJtyAb?NC1>89$PwqID|ggl+FwIsN4Pj@_vcl@%0K z+gs;^aIjh>X763$`n`E7Qi@Y=UgGr80n#DuClyK)u0?Til53y;mYd7XO_d>$ z9VHi(H?`UCa2AAPP+pzm!Obgt{ml&?E>!VlMmc}!ZQgtHG(+hy+P3qDf65TJPK(9+ zm-*fG8K#Syc~12OIVTU1Nd!r2Pk9d4#d%WczwHlqaa?b&_@3u>sowkk%3O=)#x!@X z-Q@b6d762wL~yxZb9oxMVqku?of zmiAQ9D_oP->Rql}zQw)C4d^<~xpzO|-Lu2=q#^`-Dv}Ubxh%PC7nzub{V(5e@9{lu z1Y`7%jPUNE=$4~Igkxbe3M@?A~EqB*Fo-PG^AG-9t}LFJaZ@*I$h@H+GH7J%e;-5=47~ zNLrY9&k-)fM{to*^#I|Z?|GqTRVNTm(ld03(-)VxetnklYJ>dZ5^IGD_COeYUsUf1 zT*qK(>2Ef_`s2q3c-Wa@}Op5&Ysa{>#_%Jh*Y0 zo`D{6$uQZ-)*Xbd-K4TU%e7kzR9b@GQzHxw^bq&$ztr{f5VWeRj9>qn&u`CBX>aD; z%;-7Z)N=G^Qs~n2yt{ieKjp@96Y~Y$ReeE*&wYYF z*-Iwub$4iLCt+vXd$2E^O}x8jzg6}T?>@k(ci(5d(&p;K3WfY6S4vBaT@9eCGBR#w ztZ0fur@JUUyiKE3#P#{mcI_5_6(Mk)HjDQz^ToAkW=orS*B6d)^52Y*OZrJFo_(o$ zg!iR46HtJ#>LfS~r7T2~T6P<43!W-RYhcJJf`^*tXYAfGne^d*@w{k@Wpb=C zAaJZErKN{l{o*rzd-Xm`Rh7)>1>X7aBi=eSL{}`ZB?Lq=9~{K4lP!gM-K zA}rA?Z?L#2vF9*i$={!o^XuCXyQ&g9e*YjusoXOD8~>~V&A;`pB!F_MJp3lU5E zIeh*M3$wFKO{}oAIK}PzbDTdAB^ua2wMVwurdBSowz|GW8^4UNuTIl&@$RP&zt3~F zoK_Q~Gf!|^2$Qy9Vp=Y;uA})qV{tcMOgK$y>l1wQyX#D^TO^OY!RseS$wf3=%jEkf zPZ*e{)wynguq|xMz%YC$vW%jrfAUH{A-uWcm12Rl)jH;L?fDW~piQLe1w8 zfC55zvmYIM2VD$-B8y6YfA0!~ld)g};t4(oXhDVdLELQ|0 z#}9JhowFS1i9S=HDWRx-!ig*gPMoA#T;bNWIr1y>JepYG;;~+mp+9{<+Op8W(k?G|RI7+^d5$#qN&!^C!6WWOJM*O~NBud7*FV{USi@#Pw>n&rfW zvm84zL|62g`>kmBLUFnVe4My&iplXM@{iVd@Zd2QPakBoJBTK$X#U7{dWp|KMhnJB z^&j9+SAf|@jYhddrB=rf>=TFA3j`YV3dQveRyVfbIXytRVd3R1HFTd3pDshq#%{N0 z3kYw!rVh4a&}`YbNa%h)eszbAnrE-fu_!OkGchsEV%eqd%m`;Lp5|a*`nh*pR(*ux zT?`+8jap%m+gE3qTU}s$Vx9}f`pHD}EjU47H7cynPBFGz!4Po|ol#4Co- zLPUFx^7h|`=o+}m^&9tiIJLyu`U__=g%{eYcc-WD&w|5*M0c?{-0E5 z>F#i`jHmXcVLxwQs=g4hYJ;{VK=Sl<{C*W&f!*>1U3auEU5j?x^7MNA0d!s8Bky*; zKae1I@EpJV_epxMU*+bVM?9WiV?AF+_612~dKf)^g43suk(L+u{po7=Js48ufnIsxx}lsIrLgL<{Z z`q~DS_GaEyGF2LejSw<&hj$ePT+_fXO{{G*cCN>}Z4<+^k+mRNAb@X=iFE);Qi=B* z;o?U@QrRAE+`PwwsU_A5t856BNHW9F!DE~}b%dkCIyW~a8FK_apPyhT==pN8g3qUY zpAhf|{GPt!*58PtM~H-j_D{M59510S!@Z(yCRdyMmY^ZCOkvTmz$Bqu#J^6%Ai3PE_4}F6~Q0 z)(NM2=pXE-J9>}tW{vgLHL9jX8d%S-QK~j^^aROthIAr;z-rG?001BWNkllNyTf#E`AyC3V;sn=VyS`LaoNH7v5sP0~U=Qc}}r|xp|@hYozm+IIz{L}gv zzt&$EnI;@s^)jmq>zJ-f{?5PhA6KvPuh9^>gJ*d2-FG?G6Z)YyXHSsT0DZ^briV+G13H;!9 z!o@UdEKJU`yi&#q=IH4inZPUJRoK!Z0UsFH|5Qzry=?YG@Nwe9&aJI_^xZpOa z*PGOv7Lp#uA5Rj}b`!sZCqb#@nI)=C14+-&l}(dLzEJ)BvJ<>%cogf;JS*=&u z$gk3H4iZG>*{S4KZGrpWeZ{Z-;&zb4cMK%gmEIC9h*+oxg2c8SWh^Mo3$8~0kZ7S;6?qk0VVP*x2=DyE|HQ%fHg_q4gg=rXl})273J@R~ z3!-Z>Zlg}K)xvPLt59`8G^p2G)SEW4?jsOO5LEZl!6R_&HcQjXRGTJ}uZON|nsj_? zp?FDA@kP7HrsG5cGV8Sp8!M~SolycE-j!q@@!SDUhLZFjKF9mjIxWKiNk;Vr2uEY2 z(n;Kn8{9YBG%Z0e93~Qpcmb__0!i}Gedq%J_`mh?ZgUI!QdS8ibL4V5vJ8HIkXY2` zby?IaGz<&Ng)Qrogo9%>sMXq-mW!Hr8Qy(zfij97Av1W4OVKV4oqn52y@hGJAglNS zA)<){$(YW@qe)tA6C0UaI!Q1X*oR{z|4_&%TA1U%_;;kvHMZbg2}RY2_4JSltH`!S zI2<4p)Dfkpyqnn0j}``&QS*3L_IdWDuCn(Dpb|(bfmoIUCn99}4|49E3XQgxoKRGq zKsZ7onIa-DbAP%)sb!-ib>fK_IyT1Q18zQ?XMVkk+nVO`zx+ogzw(~XXII;?nr!4( zST`)3#WBA4rveYY2oVS+x$w(>$HhZk><`UZg?P_l-urLFX4|SNq41C z6&WG?L}NjGnvBz^(`>cbVj5`&0z`vay+xyGBl`jbVsU~mscj>x0TQ_pPDU~e96rnY z)jCbnK?oVm?HV=Dkiog z@NE^fv75AN8!VL!99JfqOc4!-UUIyXz%}cv&fMaw&wk6-x2ITjdbse(U-8bHXE|{o zM?COj$_`3^N^0ORsezr3lO%y_swC5KB9QODcVv`Puk{n$Znso5uk%Bb5r%_hn3%2$I2bJh z%W{w;1y%7J{q29MjG`#0stk^UZMHEx;}G^oGC(E}P0=4o(ZAzy-hEVcKgo2AfG#6S z>ueMo)Y~rUZ7fZvwMMC2quO=}b~(;#-42AqbY&CBZXUBypjc_rG6j*X zBK(elQ7^Gps$8`CXmGn$ox;KxzyH;* z`OPbKUw@MiKYE)}qrJp~9U;zr4oTKY4jdu5E6;&rsKk>oqR}AIe2sc_ot3gn ze_Gj+1cce7R#|7gVt^VX-jyMu@2y>42-mBcH#=Sg%kim#H)zdc#`;^8~o<5~XsLQr$)m2S{ae1hw6S zo4pSUVbf}v-smz_K~)vhZM$M5kY&`4c$;uK0+&yG8wqc`O>>!>zyB@2{o*Qj=bOZa zPVw%??{n$QQHHuAsQarFbsNY86Iq7iS%!ByOp=fg_=6$RnHUOSH`ggu8Z-<+EVvcV zS(uFyg>s#?DTt&p#A8wRMoTWXZDSZ-S0=KKrb=uZ?~}Y)_)15(-L(u%>v<7x(Gj#wmWQ}CsArgJN94CQmsl?(D63H;~T$M(3gM7)M zKeM$9DXa#~$|`GR6QM+ircy+FTL*tPeO5S_rpI$a@;dy~U3gBGJ9d~5o{*#MY&~eq zX;Le%FgIVqv|UnzqjaSb1YZeHSV9lR=spnJ6YmP4k;)_q1vK13iBgAma{+Dh{_uo% zOI1n@2R#}jnavW^v_0^yi|bl68U~K*B54YWDsP#9eR_#;b^d;POnQA^yv0>mSA-cO0L?gZ* z@=g035|XTw>OVqqN2jY}UkZ&xGDbWRLSCrTsBW-QcIZp1TicgbgGObI^@<58bB(hsyUt_UAA-_V=mIwx-WYRHwnuOb|Qfr&E9S66v!CbY#_TF3P zovxQyd|YM`g+Q!}?CXEWsS&YHk^vIFaDv{033_)qPLjZtbW-UALBEPyDpD+0s5TvP zesy!FjBs#U1=fpo%1sx4Izlp&A-D%WdegVd8vaOvY&gMIOX{>s6la%NtJG<^KDy%x zvRxr$Swhx*1mkfMew{_pqFk&{uQw2$I^?Ev3CF-_nOK&K?AOtKKD2$syMK9jB}|}K z0}^^DLC=wMgo7EP!Jm}^emqD76G_rN-NdyOTD5g%=Qn5`&Jt8N2jtCqnZn{c^Hmd9 zj*;ull89}d>AzD9#lh3nEPuCcl>&ql*ROT-u$>?WWon~fMDHqGB~ z%qFXk@AB2>*O;osIq~+#bdU5h6y7={FYGq$W}RBo21!BF^-krc*9xbqGOpdG)oRi* zx0_xq5KfC`t4*WjAjy6-e_+pZaeq44yQr_G`$=|plMIieE*F`d&9kz8kby{Si{I>0 znS0FAT9KNqkVzrilm6pi&q-T}KqOArP(Nwy0j<^s^YiPJjtr3r1YbCZ zz-l)rEHAQDY+wkTLj&EUQ?V@q?wjx7RuHyDtGLGEYKd|ix-uEE+4SCKT)S;bOXFPq z-Ix64n@6lT3C_LuF(1Bvk<$me3G4gosoxEI6)=?*l}Ij2CX*l}7pWBUJet_xWGsWG zyqL@sv?~Qx=jK^!xTwh({R7(R2+>lfh}zZnvm4UD)p4I|l7`gId!; zAfxC$bVdF%wdTKsSU56?o*vSP5WcxpR##S7Ua4|06+nFeit==unio3`m9sVchPkN)I+7dCdQ zz@w{Q^4VwKaet{zV)P6j{ME<2b@m|LG5HyKT#+%B-Vutu@e zqB|JeB51eOntBN@O;eGCi))mrH7!gVw#+677u&4U zXqi~HK#BO!H5E;AsckGV^WZMi8#Y>`hht}s(w7Qv>BI`FNwb`1uF%GCC1TMikx=jl zb%Xw>*yG+M$tvND*GUsm3e+pBJRD!=WULF{CXFOPyIf#xc82A;jT{ft)0-t6^li2i zw&XblO?$#~2JKdZ=JutN;F=gllWN08prh(K`Zk3mPPTGesozv5-zscqFSj?tu&Cr8Ip+@ z5&w%%mcX^k%s-wZzgEQwWXR@v$R+&yPbB&!>`Q+%L05k_Y4tv}R)P72HHwD^$Oc23 z&SABi6qXiQF4kzfI-~tLy1L?fk1vL)k6%x2<^B`*&eCDHqGs8V2}dBocAL zz8AafZHz{VnMZT16l&OkG`a2``ZGRc31mG$FqLI69bs~%N?~!1{OTIDLkXgr9zz$S zvdVg~Lapr(%*KetqWEQL|19TUAbw5;{A3{G4<#8q@y3sRAwL7qA}O-HLkuOxc-UBH z=HWx;&kPaqNAW*H*urj7T%Kcce3tdLi<%r}cpyV6_O$9jxL#Y8VLC{X7nJe3K%N}o z&@L}Ae)Ai?zBW$5O>_ACyZrqx-{nwO7~ej8OC?#spBbRPH%l%w$NWZ~N4M{DZtwy@ zJ^b9J=Nc83XJ&Z#aFMFe=}Pxz%)Q6>ffA#%whyrE3>I>EVHn%#7e_PNd}0gQiN3%8I43bK{(_?TC1_Xw!+GKo#8~l zt2%oY!o?`Au(noUy82+-%VZ(XgX_1+A9{yDHTYa7nJ}xYEzI)p!2)GhC7bGIbSRDgnP9$fZEVxR zv>lKYG|h*uc|4~mI(6m6?Sy$Kolr3Vj*X4GJsEtkzBBu%B2eMcAkR zBwO=?U4!&@r%66qVQpcC>8W{+4<_h;c7VHUIm}L?KEM2<693~v4a7+F4RfM9%;oha z3saNKE*@eqGe}r}W>0o48pUNEKb$6CYT<^uIWXK!Px@J&b8&1F!*X!l7kN%55Q>mU zM$i>Ov%SRJ{05bw9Ep@~)3fe6Ce_tNR!eo-u0$lAAsz|ilU&NBCB`p*%740EK+7KG zV>QCRdE?;bj!a?ED6KMc{}GRiEi3}0yR)Q|(Wi-`R}7LY<4fk~>F*;OonoTA%7bgS zSUU7Bem#uuS)16Zv9>tF{W~*MT!nP9hv9(?A^%fDR=75{Wno$#M`fG>H$l4vYS zEE+_fuTmnwXs`89^ao}W^seI7GWqi#F3#G zK5Yx$b-jI2)AXmjtNO_HrwQCHU{}iImseTcXp-p(p==6(Su{76$*-5Fv>p7J2#Iux zpe!R}Q7tcW|ME>9%&egHo#p(6)0`NJJ@ae`glkZqzsLQD^W;kw(VjsDM+V7+_tMF* zf1!mFB>G1;P`5QQhYm5)ogn&yTU`Hg zASo*TbT7SqePkmuOqN!7aQ!yR2j9m3f*&oc8mkL4jNP51B2>ClJ&X*d3HqM;X2P{P z_NDujceT!&BLq&n#KQO;Zry%NRqtZt#3kN8*ZV@jkV~^L%fkngjLnqMBVF{49-=oD z!tW2FcAw%GfB)JJi2wjWt1`)#|722F*r1ge=G^;#$KSm%h+maaH4Ryk{`7@hKLR94 zCY&3gKX;et#2U-flT1w=-F6PLf0M z6OMIr^k9zfrdQcmonmrglG($(yw($b=6x5qc7y!XW9F9&)NGA`Y!}(Cq&IH)6FF}JQ? zjn`j4L2nprqk;XRR_`;A6dh;hUH8X-1zV152B-+p(K8{kOo$g#9{-EIg5)@(K^HUgP@hDT+d+JJZeZa1SA$ z2FP>`kJ8^g&ZGHhmZlzY`}!c6zzK$ONrHYA8G&QAs8`mRzIu!Mgj%3?x*vC&sIAXsu6k|8bsT($YuDDU_)<4O}@wG!`Kq-Ss9T z>^f^R54e8iE{_Wq;oh@+{ELeWWdcZMlZLtNul45tYU;ic1A8e*3X(s^fy1L58J}Y6 z>JqazKjU|!2`;@hNM9<9PnEEZ28D%tT>0)A*TxITp*{uxlQ(O3dEA!<}0b ztlBckWR{TweZ)fkpJeBf9_{1s(NP{wF0eW|&Al7nkxB-5>v%u0kPjIfqgG&T_6}cM z9%FK`L8SXQhfbd6P+I+dbe3>!?D8CAT;Rsx~>OkEm(en?t`c=iDAy?c=HUp=BYeUB?wGDL$i zhkFx*d@7P_(k!p==;md>Zdz8O?kD*y{p$5P6zQH?GTQ{5y>{c9`_e9gCY5zO;7ltlx$6#*lgBEC6EZ}&a!j_)G+ zil}UAr=dKG_pyv&Be}=M@*-2KhseGtMO6(nm4{Iz0Z~+ml$26cRZ4U|PHcUi!R`SX z@)gSSgZSJkvY0D0oH~xPIyTDv!D%)%2ow}jQ&UDX;CXKG;7mG2Ja$0Zu(9QQiVEC# zo_nDBhk$@PR7GQREmhOY3@lAEeD5v=d2T*xDkbD|BUn0_<2`nkhWVy@g1L2INEeQx%WRo$LhVJoA{{nh`jEpJZQQ9a8`%pv+ zBa`4Lwod=QentPx76~~_M@Kttjg|O+vgqa6Ku|(Nit4#>wU)(i=GdJbq^CDRz%9^N z8pi9A5v(l9_$HGB-E{K7J0RuG*lK4_2ukK z0fR(roynftd^NjA@tS}nSqL39krvoQ25nN*6T`snyTK~hi^8TpLcmsRx*G}TS9)W6Qsz@PcH zCXCTpL)l~YWqf0To}PR3Oza~0N~mgTrJ*#0TY2=J^~4@4iwn$e93%VlD6VRxsXTbH zgVDw`Q|v8GbMMDHEb0*&cP*mfkEt#U;#DLtG9-`onCbhGp8K<`q$NsP8@OJ z5cH`Jb$5MsfIr`zVr4f=sIrBo)>dkx(!-r>wq;=KFETp4PAp;I&8wigwvN(>a?+<3 zwv}LMY=9s7mpKlslQaaBYps;!1#rtYdN#@K>I?(7d+49tA}L3?+|fo$V;SCu2C9rV zSU~ILbJPwmbG*FA`2BvOkqDj}%@hPZF_t{!2CVK9?y zObu{*!}VgrRSh(?n5<|;GelT5ECa23?hb)}2*E#-Kn z$Bt04433ru_|xzEnBLMT>-uYc=Px8bpdg;iAv$;hzSGB@H@$>&G9C{KR5_ zjcIBeAE(GFK=WK|n{0fOrO9EYSK?$Xk$`HkHF1xg74^m0&ytESuacIA zDvF~|AA@vO5CDaO+7>!5Z?n90%=pF%Km7AQvNP96U1cF5k3jlhn}x|qrsp?Fx}wy! zU*PhEMhYJbTG_TmI<~^dov-+P&kAaB6W9KxnC9|e&S8>NJcYHK@9Jc0_lUuTEv9<@ zz~5)LIoD7@alRk740`&Q-PL(UhsT&&;hx8o001BWNkl*jLyqfxPGY)ufU_D zXH1>!<~ZN{%XbVd9+Ka9g)jcDnu36WDhauFSbm<%mlilm4KcbtOYb*2$=xNI>&hsM z`j9b69_+BbIK#-$6!SYe(aKiNcU`2jHh?4wn5iT7mL?dOT4V26LoHQEA8az#{XNst zi%T+y-h8TR>S?UXI|GGcO!s_CYJVd)Cx<*pW`dp71;)o_ zS&JD&Dw_HD(=O^tqfgXDG1CWZO!e}g|GA&FScaD0g!r95e6kn-vOk~7rgMCJX^Z%e zW5j2B_|qSb*j#R+uDpPNM+PI!acq;NnQ;b&mWUf(Dw?{udcL00yj-DUSGb7kj*qxJ z8>44@jm`1z`F~Sev@}*zQ543j3h1c=HkTKfn_XmaGle@^!TB4vINw}F{?Dqs`Mx0l zGSTunIxlsyv6p0UVU63r{|91=&D2&D67kApk9Js^nPy^og##%_O>VGUa zZ==Q6nCktS|NEOcJf%%s{31e4aR@~c5JU-2K^1N1&$GI5z`*<-Gkt&J|4Q!A)mlwa z)Q3kFFtQ1D*A|!@n_zT$A2nP`)A=iOG?ozdJ#P-Q$Y#?V9i}kM+;N0KpYmSryge-> z#YaW+IWDbkv41?m=JWtxrQ@u&Hd0*_LNrqx?5r|BHN*7M9)!y|fB6bmyK0`)T|+0c zImVy=<$Fd~5)`%F;@92^3PW-(OI23!RbAxD#Wmu`_nFz5=I)<04z^oqt}V;i*0w?N zV28DZ8AgUDS==+ot7_xI#V*cO`;kNu1UG?5C0*CfF|`$EYHN<(?@W$%muapp#48)5 zPwsJlbctj9)U;pX`o&i2id<);e#?uk}?*X6T*VWb*ExNyXM^s;i(NnwQH++u(zl~Wj$Px@3r@>J1& zp_Rq$L+&rl)BBAr|!bXT)WspZNZZ@JtTL4a9tOl z-B?C5N0`}};qKRI;#>1HR^}5>EzyK4f_OZJYw&2Ood@5$CG&@F-u@B@&gaE%VkdiO&6}_&MLh#%+l^IGyOlZFm(6P_E_7*GEEFiAW%|IL+2HK z_30%l!|J2V_cMy9c!`uXbL&?rGN!=b6MRLroV$99n^(_K zlka}wTwdF@F|`y&2ZzM=Gx!o|G{ZiNrz<^$fT;M0R9)iZPmeK#dyLL)u{trp`t(pP z=!=bITG*nC!kT(IuYbaga}^Z$pVAe}L`$cL$K%9~4UUspbn~ZPpp9i_Nu{&sx`m*+ zak*U2oKgAARklUyFwWM>I{V2C*^I@`+#p|Vj3WMI;nkC0>he?6a*IGDpQ1Cn7yuyP z3YOD!{t92DGT7e@vl`!I;@&os10tf3dyl4Rqqrk9v~_a*vzv6(7U6$<@zA!h4UKf- znEm|&RQEB->|?1kf{5bDqyGFye3CUlz0c&zJ`4AMWMx!FI@ua*+ZL8-V4C16sHD05 z3ZHy@k-DPL6UTYHO9-NZKfjg>SJR}kI(P5Sv$?ZC?>Eczizfvytz1EHB~nhyh3kBB z^CHb9z9)A9**2D*;rQ^7*nS-8D49E(`hl*BL7W7tYRL(}VQPTyy1ZsbXw6IAl5o9VoEiyNJ_6b7Fv zN@tnq=@bVChwQ~t940li$8=7RJmgn2bM*^@WL9TrahLtIN$zaS&?`x~8Y{MiWtmu} zfvtq8u5aPW#~*W{v6Rrs7!;KNd6n(l{QL+@?qg_rgM+mx`Zi`6c({AV#SWD+R`++A>W?u!_(AnZ>SU6~#P$#Hd5=kE^ha~QAfmXV)U;pXR$4=F4KltQV|DZ{o0EMHbq?FY zG!0A()VvDnn!5Pa=T~VgjpBapxH8bS45^fcg@EMthY@N}&n@sdRrMsqyg+yL;E0=D5!i|sGDDpih5HI2m=L@2)d) zcZ<+Gp8$Ri0Xz5-1y`M7n;lPtM6Mquh&69QUgS*y7=^qV+^s6vH5M*CkNS> z8Gg#XRLQSy;QaMZxY1cnVc<#K&Doa;;`;~0;#rQ8xjHM49;FZ{sHElEExz15pm%ng z-Sru|H|M!0PCmYx~%h`iXrRC+j~ZnKd5sxdbG|OMY!Tm#)P*&e{yk z@31!B!_G`UqR7cSYGDa7`PJ=oT)xg{H(DqPsAsG`(l3i3xd;{2bLD1Ecl$<{*jb;U zdm}e?;6%r45qEwit=B%|hTc?N0Eae{BDKEk0-W~ zkQ5i8a1@(djTOr>uwHW3j9`fvrj7LuM^FVxC0y3Rl`rxrs;Xn4e}t*|HMV2NqzyY) z-M+k*){gUZbhJ`a6vqGbI}`*2MaAp$6N!fKg?vwCGz$o#iYHn{*JmNh8(Ntf9cE;5 zk+rQDhlw;<17w$nyu2bRYMW^9I7eG^H3cCr?#GJp2x87Ty7YOJvf5_GN5`0$S!87+ z#!)hZg@EGq6Ur~7vaXqP9qqK#S5g@Dzq5h1Q$-L_y%9>AZ}4A4ifI@bVetM0^Q$`? zB(m6&i$Goh#Z~oO{OBXv>MJPC_v3o%JZ?b{kX&8@p&-$;n~>j)D*v3KqW}Vutl|p> zh(<$%d@718JX4_ZokI|j-4PluenzOUocf_*hR0@E+1lqQt%KqrQdmNL%Q-sFchFj2 zPJYn+Of3LGlu+DWB9SnbVi54UUTlyH7Lwv35DJhdM+kb|yvlL^HUhG$5)22i(*^*R zX}omHrzjd2hWSqG)2ShYErJ9cOZOh4t-y zj#6nXL|ncg`2{6Z)wgi2qm8E8GV()S9+ZHvPiocpg8`z3a&okRg`vOvfH=`Gu-?U^ z{Z1P}LXiE`od2A^&99(#c$ndl8J4zU93^#ZStVRhLQPW}=Pz{9T3#vX@>%!$sq2u8~&tE!{* zTnFdc>M6I>QFr0zp9bcnL==Ji!PaMf#v?dw_uK3Q|;mkza=jscsly@cuY6 zOPlN+rm#g7U$l_oidxQHyhLYnEfs|!+|TH4uBMbf6eJoI2?c!5>aL&=EpO%KZ}O>b zYGG`2oay;BHg@7q>TYQ%)%7iObhgo0Q%ZjDk?uk+2<*+PP=7M9c8d6}-x25QR-9vZG-`CEl;j2Qs?Q$PWZO2Tp<@_2`eSpbsJQScE_@IEU>Oe+ z=>%KCFh3ysvZRrVpGGLItfBwjFcWjDIr~zxP<>$vOCRZOeR&=}^;vBbBo&W8Kr|A< z8}jFl>wCfml~B9|G+q9jKz=FJgZCMlm}g_>kfdgU;w2m{qNeE_U0oftHk6U~)cAZ= z1X04}^Ad`La0Pw1Rq5UL-A)Yw*&U>){xW|ZDx&5@cW0Nk*gHyNODeu-5oOg4oa^f1 zd`oWZxSy_FCv%d_?sxD)eQ^{jW990%FaQOtSR8~MJX$-r1ktI zI@=qlEz862Rz8?seV-9*`$JIDH%H5A{2%|@|4u=1Az%FVOa9MKFOuBb#2?A$`hW93 zP|++Fl(2$rHic-=O~w|1*W3dJtVA z`PH4A|NOs4l$1C8<)?^kVQ6WRoV`_4oJ|ug9D*gdyF-A$;O-FIgF6I=;O>w>kinhc z!6mp$a2VX3!QI{UJm2}(xqGkvUUT!THEX21tE;+d?_FTHlE{#Xbh=dREI81zJ=OS7(sdoM!_u^3?s(H>R51>Ds&6 zbYc|ARCHFYV@;5YlPenhju4XSLJP0*B_3Db9$mN+G36-V>fBU2xo>I;Ys2xk6{j~6 z%Q8b27vfliq>JRAur9a!81g7Hl{k2Kq{YQy?HixyPH(uYsv~Wcv{VUeTH+YJ8Ny|1 z!l6ffM>m_A*#_T!>BH>0ZpJPcBlXlcAzp#u{KokYV}ux;JUdmWf+(9l1_!|fW$obs z&5rr06E^Qz$DAPdUN^FEANx+|u+W4-WP~yO;69U?xjCwE%L$=IMFk;wsyK?wv0TFD zNG7rP*jen%EAOvae_gnN>D%9r?a7Y@j%s-7ZFv20AB@6^I7N}y6TvAy**K?W!Dg?) za^XDXcY1ny9|A>HR3=%@saD?&iw@_@(5mIL>!3_Sq(l?V)PZ$bi-DGJBgG3v*%_Oo zEv_iXPAQnB#C+ooUtvF&b~F1-Cb1G*=L1O?4}e9~K5_-PJS z1k;Y9c&ot)gES@TyE$W&vh=0MmGhzFM_y$U8)_*wve7Zfd;;kiFCZ z&M}uQQZ-{&KB|Z;qvy*WI_fGAT)XA7X7%RxVpraVv?z`h#hT+*uEmUR4b573jm@SN zR@c`{@{-UJptLWx`p^x|$_@+8R42fpVfJdxtf+7Pc*)}ovED+%!}#c(+!!AWWvS>d(c&{GYyBEcYER?YB`1T{;qCNlo*z^Nc&9F2tN$=SpF3j568XaE5 zHhEG8AqybI)aaEZvJBIinP-3c~S zwd>?|3%ssc2Di^fn+}d@iKy!GtZ8PL-q(H)Ju1 zD$tlNfu*93PgY5uJ)ZP;>%4{=N~_E5hlM@Os&GV;l@I}bc=i{xzac!~s^e^Y%YMUT zO8BHZCwoQrhW+#39FOl$w4$Fti;b?0Paguq%Dg`o8@`X5ZvuKo$9SK=NhoMvz=6F3 z|Je_C3N*i@X}!Ypu`PdLCKnM{rVIs$mT#?Jg31a2{yM?Z|``EVR* z7Z>|khecl0{VA-;uafna1cQcVR-XRQ4>c1T!@$2A9(b|5^vi@JS8jT9WcuJ^nyWit z%o0C8tYuJ8c~jvewRI;2h8_ z{NqxK=<8IE!`=-hMggKr`gGU0Bu1P%i`cCExtp!YtTgNR9g@prx}SjZn!Fq00L#bN zx57sLh%k0$2aI_eR8`CaTsJKY8k`h-AZI<=qAqa(_rd2qZ{D@nc1=jz(9y$}Kp?8d zZ(kyz8)$mjn4ggc{y9wt=YHgH$_1cgTgl@tF)N+lDZO2ATM(A-c^)eCtg7~hzU9L< zE~ckQX5+MYywk&%Cd1*6IB|k1;lqYxLRblmc3t|bh#VsjG;xdQ*_lJKv{8;^CZRVM~`0L1nT-^zo}`?0e|iTvfo!U zmcAMgXt zhd3s0GX(^G zCkMal-MVO8!3kCCo?NNzgMD(gw?DPx>Dx$TRZNfo`XWtQz8juljmlVy;}y1WcE%b^ z_a83jCuLw@pl4wTfR1|FW%T{X{+U}^SMT9?brti__;wROnE{>(;? zo4aFq>__T>_2p%5VzS0FJG!Ii-(wwq#_l|j9`MexGKs{Djh6;Mw6(mP2{^F2zMb3g z>;=)LkJhxeE6K`!EG=z6+4Y?uAt!fn^^}mc2G??|Ghs*cVZi;g;(TmKzZ3&j%*V&) z-dFh9{|#y%-SatCffn4qm6(`FA*-Ycd5SjIIX*d|9A@8eTu5yldlzDi5z%-4^m6ap z-nc>%saIqj1T)RKxU$l>b%B9`kSW=EN1`@fQC zw|w1@?#9rxa@x4^i>Dim_liOzOGN@!)mMF-=){-A44{yqNqbwmt3T1ln`Egc`a_Sz zoHESjIY$362JxqKLOzY$y|1B!tXD+&V->Jqvhf*CcWCFGPIsPyXD`2A+ViZ5a%ncN z9x{Fm>FwU%6Nq7u_<0Wl+YmI|v|?YxGWH?FSdc_-%%t-v#yX8YJg~HMY}rj}f^&3o zg+q!vT@nXdDF9gM1u67rD@(TZ7s!MJ?}4~Z@&)31xbBU{Wd=k?qz?lBZJS>IziiV9 z50>OV#~APb>e&A^dI8hgZ>64&@@H*VC<~x|BP1* zR(jzbQ9x2}n?gA4#JaY+4rfHN?MEz7DlZ{q3Espea6&sxaJL|-@LA&WUJ*t~c=_ezw0c@+C*N=TH7oylPfqjQ6W;<>85 z2NIH}bsKSl_|_xCVamF1+<7@Q)BGyRvWIF`l&7Mk*_-^furK>a6`wK9+o1~v zx4XA)HgAfR+)4OWW@~_x4<&?&V#watfBf_QDYkMKyW6!bFn#^3C0Evp@PJ^cP_FP3eV2yM-Q~e+GkL)<<&1dfe4(T=pp$3hN6QO zwN`0A<2a@;B`|k#3>jF?TWxJQ@FNDyYJsfPR~L9OPn^528tNL}#=~~Qy%V)&%DxC& zG=&%R{_$6^MuKx|2DZZ#=}J4hv_RAX7bL8%!9V-39cO5fJ;ATyixH%%l7!zItORLJ z9tG4>TC9yTeerXD*V^C!9V!Ya+P<;?S9sv^N9HgL`?SCP6fffXv@g{CKXdeixs^TN zakLCR06STv%q^^n(3b0chz}L5`!COg=DcuUI?U{ zbGjB83%0GAdAxSL;c{FnJ z^lfjyXH0)0DRM;->)t|F)mM>s(IZCH=mTzOBI6i!ic=R{Qmp~ox999nvO!Z39UH?( zdsd*Ef1TD|{Z&jTLZchID0e_}O!nHb9Mb%{4Wy1I4+9)TA^MKQpSHv#Ws0nxduVGh zXF0zvt()#Y8~M&C7z0wx%@EH5DI>hO85(r_=qM)B9`KvUxa(C)Ix=ZDX5f2C{i z_Ha?|4#V5YngN9FXV?#Oi^Z(Nt$u+Q1zXw)BfKy?I2z?&Ez!ij4^G4dDr-I%=lqi^ zJxs~8j}IGTaC)-m_&isGDLnhdjNLC%*x7wkZIw+Ny#2@ak4Y6@b8lP?+lL%Ptb3V0 zSb+&5?i{ZAPh}g>Yo9ZA-f>kX56?SXF7^@mR-pI7H8P=4_e{=_i2K1VXX~3Ad8lan zB(1%id>W!&<(c41-&*-Zd+OU0K(_2zzzEkTUR9TA6yOxqkS3@HpXc>fxTO{Ww>Mc+kNE*}f!eDT-%othgGy zu?Q@>ma~OYq=(hEviH5jSts+D9FtqJ*2ltFLTp(#%rKmxRnsg*yn zJtK{qQUHm4aq}5uq|YgB2k%0NYF9KMZ>m2ptncwvVt*By5Vf( z{Axhdcc!A`rm~&V2jO;84TUP8ujB<-CEvi33M_O7+{a{3X=C=e=z3cp(wH29lwvrz zn|mRrnBX#)_;3-NoU%gjZZg6lW5juDRxQOhy?x#IpmN+@vgzTiI)vOvC_YVP)vxd+ zsim~PpTqB+J}bxEEc+=?i`&}0N_g-rfQ6a#`LpH6@JzCD#*lS1ZpMPxShuG@?b>3lY3Qqo^1v5GW@_;T&(!P833rpq0 z^I%)Z5V+P&`MZXPJH|TA!OBvTM z%f}K>%6a^v`z8-5Jp7LfEFIH!M*YyRKi9N?%_9a%kpnyIl6`w0SyLh?tILKUH*RHi5Xa$n22t`xR9dHe@x1OQF7hN&dg4lz*C*Jz*)OLi(*w zpTk(%|H*00L_B%9M5pe2v&q_6wLiT@<6y720NT z`Gnlk+bM$6Fr3J*&d+rt@%Rg|nt+Lo{jV(O3Q8ok|Rt?yD6e zkH}ME%oxwtZ690TMSj2}?pMh7PsvT4of0x%sN+je(tsW&RE$VKeQbY%RU?X2zttmqG~fA5qPd1JtFL4a#?!3}SkuBaT-PF|UloO_NWcXiLE4EfsHfu*f` z6!39apHX|@R8-FIVI{6Y35nV|@dK_tpK!s$&GzFdje<(<8D7?W70(u^B5VYD(c+s| zAjwe_a`enR!U3^48<=T;%HQtjFsFuull=I>2R%BMy3yqqveWBj%Wt-EQEhM`tt1{! zuqm!rFV$z{{Zq2XOdP9g!b}qxI>)=5VcN9E?SW{it-JQg9qy=oCn)i!2&1u#Tpy8ksNO3{V-k4;QlG1DTKEj)4=1w?EBD?v_y|~3hi|7L=8(BCT z2d&&=g3Ut8jDI?Awmt;?xu=h>AE49kAL<8Fa(t|aSWzWc{Ox}-_0|ECM)SHMWy&1v{=CORsCjKU| zS*I`|MVi{sd1uC*Gq-05RdwsY^#H}n3T)(8(w7Um*qB&p<^YiU-*8owBQA# zyMX7k%64)K3jxKdTri_n>1W0dTQ2h2i#Qi2xE4iwzlq3ATsWk35f38dIg^7`R&~TD zq?G%0vPlaopU7aTYeyU`W9^79yv7b~Oo4kX=jazlMEcU=qVo2z*t?<_B5VW9@bBLp zBhY=3h$me1eBF?{uydN~(qfi|V}E5|3c$f>gZnt$nC6R0#Q z>$vFF-jX0JJr|UfSB`-DD~heZ(%Twb6J8aGn}Xz}-yG{&$ELcG=qA09^O z%GGxevyeiLtN4W^?pFLyl|j{b@>GLoV&Cpre%O7_N8|oYNcgA7GIk>swE>N5xl}?* zWCh>sz`DT_@nPf00oY8*O(!{3HAxY(pML#Ave=Dn8|AXtoBMtE7H6i}E3s2qF}scl z52r9C4Fz5M4WGR^rpNUOacYIdA96DTaNX;HZx*tor`3WS{fCDj0Rf+5Iz`(Hmx?-^ zO_ABHXeE3#dFQ6K&hs`y@3Sb@YF|;ROi2|urA9{Ex^3Zz9*_Git;Pc~gB~OtmBl#) z4Qn$06wzJJn42AQJUsk;=rUy#@s2~~v`Tu6JjT1so^mgU{Tn#oS)9cN5#f7NZ0W7V zP{h@F36%x6n6G7KUo&npZOFokz_v`n`RgqMSMY0pe1L7_2qttm0p<1QFEfcwPAuDTl*=CSj@_r9UJVKBET!As56jH& zQ_ONcp)cqgS{SL|s@60)V+|i>gdH_e<(iKAk?RqDj=NSqg+&UV`~1IwReEBb-R#i- z>m<6eqh0>(nw#*GsFw!g-Y^mvLI2x#l0I%716^}#uaMCwyUowY`Qy#2hLH?{6Dv%+ zPwg83&Y62_*vZu+Y%0y2ISC(wcXCC-H*{ywOB0`NadCw@`F*~gzAb$xW5BnM*k^?Q zAMK;+WLfTYTa>3~+J*#*NyKchw>yhmH;adTE32I<&W#Tt*gq)r@Ql6zLw$XUGP^|) ze}-$J|IjJ1o3jjUg7ORv{glYh4H_mlDE!;@b1D$S{&VArgNI#oPP_dh0HI#V%GqnR zA8SncdJ00wAZrNDS}?KC53THYjEmb5|K<4EfE?GDWzE#;B?W!ZFgo&4eT z$zMt<`XXs&LX$dHH{0BEXEvJIiw{qiVeD|iz<)p0#Cn{nqdham-f&OVhqO z<=Xd-Y0V?1HcOrU`!UV<(l=A5;9xCzO@BpOTSj?XuZ-7rW7Yg)R&s5%bZMGFmxsjutyJ#|}S9EZqM2hhH|^Ibh^QX(D# zxcJOseR`yKF^zl|8t{_VUV@6H`a5|T|NMB_^82T;E^DEIxd|>(#l~1600&iZ{+DHm ze*Eesf0#Oqy=FK<4@ap%3EE7}LAKnVt!#be=6~mbuar@gEt=@q?04^1;o&hj(l8Ot z^PBW^TE*yzRDMLSk~ z*^nF^D;ifhb`!!Z%;@0bH2MyTz^N(SL08>87S0nBeyIC>D39K9g^!)%_aK*d$4eTy zH=VXH&Ojxfbl$&lNVnisWrNu6&H_SVPQuvkm&vXv%?f|#ps`0^|4US4AQwovekaTy zw4~tJ#MRTe@)XH(n%9cN7qDeoVI(YVs=-EyZYA9cQbKd8EXqF3!7cReC}^#Yvzie9 zvv7xo$f|^>Ct&7xD=gys0=srI8he4OGQIlCxo+sV`|$H&L2&s=ExXVc<#GBeAAWen zl>6&iVpmRe)%Y`MTvuRQ{3bixJ6)kHGzl$ZVXpOQPmZ^GH!i!Umnx)Lg!nK`{yNe* zf>ziO28l-aSN-{M*Q986^9~zI<5JgU_D0(N`pArZBsr2ie9J9@|7;Fq>mtGH{G z3GNc}M%V*m7G89Jst9oX+3@I0B}_=|H!wDY(j&Cu8Uu2vtL<7ELI^dO^%VSeWR1qN zx8E$(IdP2V{U_2TMR@aYC;BbB?an)TOJUkKz?z}jX!An4i_)=_Z3b`kO6`iO065p`T|6rs492Pt&X88YN<<({{JYO3#BgF@^s}(= zk+SDQpN@H9^l~@z`xP{aTG8Ea=?`>0%deX-TgW~NBHj|_ilkBX#)4=Mws?J`R3+tn zAszP_%5Ur=a!Q3|ISF`N<73CzyHj-c6Pj@|b13L%Lf_0Rh#6-(3v9HSU2}p8OX&@9 zF9+?C3#GjrEq_h*jkP)9smaczXf6!iY-*XQPfEz!vkP6u`k-4bFc+)W z-8h~+nz!hE4?_^*{ghxr+qKjUcW1w1>}mURG+34lZFX{1S9ap>W;`4#Hb}^;_eH=| zp?vRyCeI`fZ)X8ADW|5SlN@bxke#Llq}k_57@am*C)L0E>!0wS?FgmnF#S5NF}Bzo zjf30gcET^$+{&6$GL!uL#Og@I9KZ)DS2&s<;HcRMw)>>C#^5b-`PJQ`JNlhd+1;4` z5=5KeIIbM$xbDM8QLd=2t?e4Rq?}W^vk4N!is9DQHXhPsr0)Z+c+7lN9+#_T=-_h4IHcMX$_-e^>Ertd z;?K6T$}4^758G{qrGbY$gDkR6*d+(~=&;rSaToQn>;m$jiW8R!>&z7sQTvFU5@}zq znrPLP?)q04dqX?(8xKZX`vN}R&(q(JfNXyuGz<;bs5r8w#(5}@g$04c1+$8aQ&D`L zi6({Es42eml3ikhNm+aeA^7DJge;Q1C6R8`A1oh~a$x7mb{U||+UBC#Cr3>GbwVxy z2CXssYgtBk%_Vv78cP^^DP7p%Lj^Py2i>Acq+{UFoy_6Hiy750w~aQ;IX8jM61^cy za*c2!f`x9O2DT2}5V$|f7a!f-Pp|U3fD@3?6;agk9O=o9Q6#`gNoqP|4`PE})UExy z&jfk3&~11YuD!Lb#2JK|F`zo#^1xuEdUnj?^1&G z#t}HaAw#$`NuRWXyPQ3YRZ&K>9`BWmJ}Ohm`sDemHRkS|$8DO2SH`0)y?mUT&}g~H zlRf5Hv%3MsxfNNEgvi`^CBMw&$KQFxgR(?|M+ei9{_}bEy|TzrLCMG!s-+J-4kcccsv23JQESLP z_$#KfUu|RE3|ji%;gMrpl}xd*mHS^tFaKiZkk&XP7YNLgW@l!#j7g8rTYZL)?U-0Q zvexz0c6j`A%IS2{eMTk**!h%EQz{KMcB7Oow*uB{GourV;!T z9JuM?Zg{O4gzN&?!VJ$5`%w-){-Ft5BIOgWinr%^U*G1`Cgqo19F*WK^?D%KJ{(H2ajbLxZ>4gRVyn*3*Ay% zUcjo!H_GU3xUzYPNa_(XCkalT$3*uk`L1K;WRzRVtnJ+#NFOXEijjXm^wd|Hjf*H}uX(A&EOqPx&Nd zzdXVs=uwTUJVA#37CV%R50b{d4D({AGnQ49*Cz2x7o16wws`Q$dupM0npRaaMcFb) zG9(pv77w6O@Gakq`wJ=slY9O1v@kYvU(n4owQv2g|2H@1={@O=fAqxSprOfZl&c5V zCBQzw8Y~)NvY(#TRpxy4i_DJt+;q`*xPNf91#X-OXpaul@}rEz6?IKUySl^(uajCG ziXTlQSoO$*q5G(!`VnGt(7dYn76mib*ozq-A;_2hFmm=01}@l25&7jt<9dzY&)-#L z6Yn<(yGV_Z*kxT46FxDe1gq~SxozcO=R4$&{$jlw<+)eBjM%k*LDBYAHUGLVHF;1e zZwM{-^cJL&%NN-~&V;uw8YBz?(D9-AWi*Yy{UgF*7O3Kn3rg!l=N|15nB7#!wNeee zNBgVoR7Q@gc->>5=oSmy)YrF$`K?R45ji<25zIh^R#?rC`jTA`t)C6djhO-! zm(+mM!9vG&C2H|^KS}rzIgFoIf5uM=3+PnMW2++DW?y&N9O1ZS=2}oSo2hGv;rJJe zRacigL?FeF|2$O3G~~iPpA!{L%zzs{I%u05E;vd#um_vc?J8?$+~}oIOxLO4z)L#) z%TiK-_Rgq+&|ZQOu^DNOKlr`)=?iK_7zwqikt^z6j0y5*i01!^%{!;@+I-H}j4K zH49DsRo2ltqn^}>>3`ZX)PNyWt_qx6#ZV05X?AZ%l7!N7IoJ5i%(&QsK&(8CN@A$f zlau|@FG-%b2f;4VorEPtSKg?0T6S<^qKWx?^t^CgKY8?J_e4Ln@l;GhRiYCO&F{)@ z_mt3bkEzrrWsG#-Qz~v;D%c{cd3?G(s;kO5k(Dj9R|YBimiC(`#4Y{qKM1AoJ7Sfc z?ewIPfr#M%m@k}!Sf?mtBYMiaJyf(@VSd(L_xqRruo&bI&asDw&Q!)c-H*b$)iOC& zWROKmr)(tpig!t)d&OnP8;_!hH|7k(;>t?5+zn#PZ9T_ZI__8RUt3)Cj~sFsHifBH z56>k^`0s?@R*hla=Yssix2zYDRvmFy{N59e_D9K=tN#*`E~r`=MsbjtL92luf^L{9BYV+o;RYRy1;ro1*_ z3T!X%zq=2|w2j&9yA{%u<_SZM+z{VeCy9@i`B|q&T&}v@ffQ7OpDv7sF+^`wHRly7 z4J7L>Nbp-r(X34jf9w~Q!yM6KvJhqJK`Q=53fAXCIdglj+YD;6R@h)TDVkK^(({U{^LObkPIE({YL$HcM6}!+-LJ<^)20j!-LGj1?uhoHlPJ_PJ z!|yABe^LwE2_N0(coya*-nSFn+&Br2ZSg0=;~0g>xS_fU2b)oiLLRxnmGVr*{|^gb zhR0api>`|R#o$AtO~;%zOg^ZyKKKOxWWdAeLjVK02-Xk{}lI+pjRE^hr{Ih zDt@2Q&;zRUFFP3?#s5uvIHHN=+P-eLSHxD{1)X>$_wv(p*^%tTCIV)#UuNHK$^9JUS zl<~M7^?m*L7w64rkBbe5#|y-uU$FK#Isu~b0=)O?l}#W**}N(z?RvL zN4PxrBn+j{2q>k~H==EJ9nR_AT}dA+Qv!qsTg+jE!HwQ6O%)PLo+GLjs+o+|A&0cK z#D3U&AvD|ad!o6`SX!CdxHk4uHAx&vI9po))N_pG2BvQpe6S0U$Id6ls{w7fmKwcX zq#lKZ2T9T$NP`}2_Um7b-zwc*1<6JQEVegyvbDu=a*S7=Th zMwLtPDlTiIHXN%@yrmpKW@Vnxbqy6TiKjWqu%Ff?%eGY;8=vne)i z;Y+@kQkF$mYb=|(*u(@SO4ZMMZLXby#J+yvG-#5`?@^SL{178w=;+w3CJXGUWlKN5 zp!#x>Q%~%h(VJhvRD&mQ2MSrfD*bh0&c(bdh5)qBzcOOWOoT=&V|VqackH2<9(mIV zY*tJ6(CNSeCk7#{$a{NXhqH|J>{%gm6liE{rrL7$RN^aNqS0AzcT+|cV&*E)_HKT=}t=i3ECi5U7SOVC!>_X zjL&>SUVBi99k@-SztZQ^aZH7QhI!fSIPeJ0-fBptOV_sWe|RVEsJb>IBRK)iS~6zJ zq)cbYP3O+t7Ika6xPSf?Xh;%&u1`5eSWOX}>XwM@)yW~Y1gXx*k?NdAzVE;t9HA$oPyq5)Vaa&GF z?I}Ijg%x{3uk~(KW*%*Z%VS$})6CY)c;N&g22&Q!0#1DL?sp>=a+^IVxzI}CVa(XgV4^=0l ztD(8Om9cQ%cMm)3!J*;LXd+cw?th(y)F_~o%LuoQZ!Uve7<~u=Lml1lQFq7$EjGv> zYR=956IvB&=(=>#xK#D%%2B6`tI?-X2z=F`V{XI;h(Z13o1Ulr z#-`~7xq-$D12thFoqTuhL9?rEB(Lx^oku^uOaPkr&ydAXSvK)W;S3vy1i@c7-b);? z%J`wW&o@+$spASUR0|L`R%*PfcOU^@|U$D@On6}z0D+IFKD-ZYjzIMSYuw-6QMfr06x{Ie5p zTTU7~yhD%UhN9P-Q`(eaFK9?ET#0-Gf9g04AiH6SVPrKO`OOUrT|f*Br(a`ZLDl6p zG+44zse;@rvRThE6s5vc=44+6LM2xdZYk+ihzhZfPfx2;us?VT!U+=nokl10;v74k zqJ=&YhSL_WzN-%B*X3{7Kea7n!0SBlG$hb=4F)HMexTlRe3p4`P6(vW^~_Um7ERpl zq1qYD{?TCl=LA&Uoc+m?VJ2i*W*1GFe3YGwujhG+8*B^Hwb4r)sj4%tV5voCr#Rc2 zbwG~?pfpeDe0{6b8D0tbb=j1?15)Xx8D_`5~iP82M=B<$h=CC=achU%m&WP?wb zZbe(^gYQ%{ogUQn+f$bNx!GK!Oqd79hB&d68wd8WeqI7F8dx~}H6pF94JwSky*Ba# zHNWV8+)ytR=5Bsc-xa=Qk%a5=W_m4%TQauv$j;1&`n#-5^R0?cWa#l&tt2%yrGGPyc+nUtm)#jeYAlp6jFoY3YcHp=*$d>GCq2&f&b<# zs=AcW8jdH8a^ztl#f}^82X-_Kp>~*V?!i6hZD)9euAfj`3bOdvajF>n#7!$@LM}i& zE*^brKjAG$w?#_0dKBWHma&m9v?*47_nXLn=zfb3Z{D46;QMa?14Ld}m=kq7=FYGC z9SpxRVD$797}kSJvF|+?Ws5w`NxwUNT*1WtXa;Um$Mh(UK0K6Tcwg{YNi0@n#eXJc z$)MKE16e1&byzS<*O;zk3$QOW1F?}kUUea#(Asd1hh3hJJ-wWg>H)tlm%NDrLp9oZ z#@cJYqX#^*4(!$DPr=(xf)8(#GXA8LhZX}$fD%Crxv^ry`2)LGR@`fU2^?_>-v6i| z)-DvQj@|g?lk_l%84^myTAk5H_P5mskx$7Mtwg z3S1f5D}usc5|j!vMM9f$-7U4?b6t&&~i-G*D_EAMBo*0!0B;9osBBj-gRT*y~IiitQnPY5YI$ zYO+1ui1)^otD88+AT#*SZymL=24{JBIgwTKKQ&~kg+;o~GX;EwTcWm+CcUd;fSmfX zv!}O;Nge5!No4mbu1I0Dyrw;c*^OivV2JXemapiyEX(`&@xe4cw_(dB zC!1KB15G;>t22L&*|cRGS<#%jWo&Tq8j~#X-L#54pm%XAqA2EBC4V@wW9m8{U?M9Y zWoxTbWY_Dh>)N=+0R1g^+B9drt(*Lc*G%mPw;GF@cIb%&c>? zSn?UtPkwd3iTIon;1vV;ji0i$`29x^hhWBSh)PZCkWE8tgSG0y(l$j=jt-icX=sr+ z%YoPd<(L{cN%ryfv!{GDJX5C%=P`ZOYdXs z0|sCE<&XE3(pU`h8;dg8E1li9zKcmD_RZU~jGDwPucFD0cB{f4Uy~R;`^OC)n7dDT z{f}ZM*P#A8bLV1#peIJ_;iTg=FoMY(E;=)orK>?fp{J7-_1YwQ=9M-=nf&Vfl(k3s zuIgXXHHu;3U+xeiuU&?~Fq*dysTk4sDV2!c>|zW_ly-7W)q@r27mE|(yD5#byWv(L zUNX~EtQL>~f>ng-UGcCILRd2XTnLZVr(LOqo`S zbohu*B{2`}lXF1CBblUP_+Z+=8U-S@AucQXRAol~QyZ2k2}wk>{UDK<2cwF(pKa z(yLRfLT1uEXGvfr3dHW>ky!A8l4kMkcj$~j_j_eJI>K}S5!2tXo@ZmwD|E>t*_wyn z$cmCzryNDq>>61AAS)G0?tC^W_|%dLi9;k>N^{}%0yb?i9#X|e|ppn+B7VXcBemXH0q$~_c8PJK)z zSuWFVWg?FiKMhv%4_1-*5})BI6dm6+?Yzx}x^*_fxG0sjQXu_Y`F8O+K~EN`<)?9? zXEZ#Qg7_QDeycBdc#k;DljQj1waw_7bajKqI5{ICBgFdW{_VOtj$z`WCthIjx;ie7 zWbY6TJ>Dfw)&&88+y8DF*zvj}Z0Z6){pXu+Up1CCnMq7;`!hZHD7C$lgLZtLcdpoy z?<92*92^TOgGyt=>3zxD;XZ0LMZco^gQtntSsKaMg`NrD#(SAEl;A^YO!N?RbHXfS zn@Y#7($R%?5Bs=@HdnRah(t(#r-f7yTP2HqH;wZNSQeW>#&Pz#Y`H+qE~K!ls%z@J zPM{McZ0e%R{@35kU{vxK(ooGwsyNSP8*x1a#CKYrf6Qepk#XE$kIwlwANc{jNI^nk zQC%);%Z*&297=<-}Gn?dST!VinIqf1lW54 z8YkN9Mc1eyKQY6(4AIk(i-MqU=SwxbW>LsJH3Kcu+d~ica=%jJ;(m!FnV(n0+S>-^ zQwZ38e_t{x18rjnPx$$PA_&MasFFfnOph-gezLkoxw1!D?B`$UMXt!I(htnI>u*RY zBSx7En{o6!F2kXRl3nZ{;MJlF?*t4fB?i32%AYvRZ29ubQ@8Prt-YSZHrPC-CzV$Gy++mFoqFId6|W%Yw!TBF{GlkEz~nZs#}AJ3YJZ$YD#XaSS#sDv`A&71 zFsVvBq8#aX1}HK7onC(GF0>K=zddo8*!N>j0R(FSiu%{sx7z?eh$@x*>rt&Hhsv}0 zweLNQRwe4xin{E=);(F>z*;wZ_%TZ~hoE40?{_>SJI1|A{oFAol02Bp=|Jm!GY&$e zv=DQsAZg2J#&PF{^>$v&qxE0#I$ngCdvdC;V+_=ExJ*f8Q%(H+;vh>U7p6Puyr+rr zj#ks%V)nz;Ud$rH{_hZ_YVBT$E@Fo*tvA=GVfF7g%7Q}FD$fCrAa3PdbBC2K#%{P#b6=FFlP{@M zEhHMoQxSy8U_&g0#`Kp{WV_#92|P%xjTkm^k&d#n!DCKOuqueum$%h5&Zv;0Z(yK0 zgY7hTv)I}A#vzX==ZTm))U^WaDBSS<TMn zEth)&lxuPsiUO9z1(}f*|LEw|O=75D6D}rnKut?cRuHfA=75x} z%%1gSpDf{Iwl_%l%UCubQ@Q*6#TMYqW;1?E1JoSo;#{YkFRGsq zLA1W#_-tgE*Ml?(0El?QPvB1W-}+UiQ;As>JG^Ie{7uP`%u zpW%TXZZ-$;9Y?NhWS-&Rp71hAJv|;0kc4Af1BlnC06qq*d;auU!;sO zUx;YDoM_OG`#S;!%gB@3+hJ*biCx3Oux$iU#uJL;@rQ`SVnl*ooQ{`I61~IO!MkF> z8-gH6IJ{A6ThHN)WXR<*WKv0X7ao%-7?|yi)WrO+eH`f>j)PrF8d#JL0^z&F7zIE; z5QVR+JlOw;2#%!U3D?sz@B!iGG1!%fiHcv|NTv{sw(5@o&08-{D2r z7+RimVvmD#0sWX4C959%p$H+b`h%RAHwzn6%X6^3NwQ#I9LYckI9y%=p%?+TbgJLW z2CQ$KEAen=de}X9C^o9t9f_P3l7_|*DduvP$eZilHmMQw0>A%#^h34|ZZdkr&F~Fjb+T`iz zeZIOo&caR+e{DNG4YgFn0(eysQ_FF%v&qWxI%~W0Jox+%*xC)QUuvf&b~@7mmZ_0F z*dvk5P&j5ROOjPQfe7KC2j!H5QNiJ-snezaJU9f4d}g1W z)m9oR@9@P}qdeVSVr=LRwcY3WMMn_7A|k5+s+(H5sQJ-VACZbi&i8auR~aSbbEAkR z#q0rF=US+}bBo(|#(AqIb%WD;8}w>404>q~AwoMB^jl;J># zhL#2f>%E9CH9;1+#3u8Tlgw`C5q%9@8El~{`nFHV*c7u#4t94*Yt|8;Ll8t%Pk>-J zf>(Xj6y?c75S;{KwRHFQQl2;PMH^`8Xs5NgmWpT)mqWnRvn01y>1wUzZ=Zd^$ihBz zV?*4jZ=gI9pe61`_CzRa>ZYsVDT(P_mdC&3KmJ2z?_wv-l~KG-&~pcDEzdGBHpcy_ zeH5oizIb}y^+aKtWOg^$Pv?)dmk1KRNEKn9`mNaKX*`x~W0@wFX@PAbd%{$;5AgH% zda3nE-*yx$3T1Wes6w9X?gq1~$}!r+Bg%AYv{yrD80Tneh5V0~kU{fQk`mu8rp-=iy9 zeylGmIYU%6pXY;5T%>fJd?80BdBDzIlGMf=556?XXR}x^23ERY z9#a$$P<>&-p&-6vg*aayEX%^s4J_M2RGb8=ySRGgGCghOc)tY=YI%OT3^T)3nn$-ON${xU^sdx_z(H7-`U@u|+E7nYp3{0$6z_&#;1EV*KVTsq0# zev)ivgQNF-JGZ~$*3c~bVwCQ|_jvEhd75G` zBe#DYDCGxI+Z!Yb<}vmXWTzW{sGN}Jl;ddIF43mh7T5-Aw2Af$SGanymDn@(!l63x z1cSVn-5`<3us*cR>e4(j%X_qzdr;*Ue0@PcP=eI9^>Fj&KK6@6v_hU_BEdl_M{<3J z`+qgaq%JYg+eK65ODLoS0m&JrrtLf*eBvQ}Xm`_z1iOheiPdR_Z)@apc?K?aP#g1} zdd&3>KMe1R0dER|i0qC~*$|!+5R)*^gbDKX8lR{>f z$vdAhwwfWWJ@3T`f<&OIg$sipaK6TKs^3eXv~Nny;-#Y4cXdnJc4_}03W$P;2-s$k z#L5#M4vjIhZ4hn0!j(&1G*$Rs*_C_Ruq}=K)u%kTH_X%B;n(0i?je*SOrGoNA&`5FJQ? zCN8}fqN8XcyMsidUnj>7pF?sJEUUvC@Dorpl8FNj#y417nq_=?i{2VHvUKcFJ(wBx zHkO#4S|x2MMBDr5t_c!wot*;a-v@)_#yk&h-)3s3h;BY_=R`@Rtf`0o!9iN%3gRgS zeuCUkLFkS>Q8@UXL*+T>L@-{M9(JJSXpH!r6b2{X|VH5?dk}Uj3k!M zuCsGGy$TkVnP+X{F87|S9&0ZpS*7XvzjCELMtR^AL&fJ_pok|Nr?$C`I=^(x+3z4w zR!x0-3)O#_WVV=PYh#;qwtyY|=@kR=sV%05@9=PTlk5?@D-x_~rK|5Mms`T8OGzty zy{rO~>>yIzKz)4;VYlOjqJ)U7cqwacrlIB$k7sw-Pwcb4x<#QsjsxL^-++MRj8fM* zK%}-C-OwrIGNcnbEX_{xXn2gN(Yq|K?^Cd3oY%Xl4ZB`*A;bm@lIycP9D2y)dgh2< z2qNVjR~Wo>fwqd5sB*qe9CkY^E)V66E!3BVj_CxJa0Mb%wYAX{zRP|g#m?pyyL$&1 zc8Nmdxz{MjIQ=!88w}IfQ$*K`6tXFHH&&RRe!|f31fySVvAUB*@%p&jR!R7^`-LY5 zQ_rzB^^oDQ8P-xqg`HJzgvOrh4E8h<_q~DCnk|4J;PQv4ZR?^UbTk1ghzf!78X8&} zC>xq5kH_p1tux{j{p$t3sLT%Ke6;Rs_-9`l!_brN|C z)%hM>HR0#=TAq78gJODzwdpbb`sY7!|M4biM~tp3@A0z_207Od!+EOtE{j5Xhnc&d za(_8TPCx3W`r@^8Ui%FL^-f%GWU^BLL}K+V)YaD$Ju>Yk04n9pZPe9G5gJ=z|6rf( z%^eDQCH^D6zJTBe(Qs~nSVIrGp;IhmN$jk%I5WxU@Hi6>Zn3htkA?%cua_#Hbc|M( zfb5LX&^1V`t_RJ~DdsaIcQ;v@o8rO!5#}Db95=qf@bn|fJ^Vsvi#^Y(;}7FzCrxkvZ8HL=TX&Uo&x zf+$hmUL@Fjg^nusDSj^rQFNdv5`rLL6btC4iTR3sW7{U0en`nB%g7D|+14l|*BQV2 zB_neQn^Y@gXGo{@i{?M30BtA+}1?Z$Rc}tc~+)oNETWs!-?VwQc)YE z;=67rD1>X9X*t(M?X79%@>zD*H%R6Sn7DYo zO<~m2w7Y_Y=!#L-9Q%$BipYwOiq;O=8XogxcAK@-0h=ppWX(EUh(|egZ5t!A%f`|S zvukN2S0x>N=ZJe%)VF5p>}4=X@2xR$?=GJ&q)LL<&p>iGY0i16?&zmEcDhw{L3ZJf zRpXCUf5#^!9L^B+=g!geaE|5eHTKrl*-NA-T4l(hi0X^ee)%RvLq_q8F|)kI!ss0) zhb@p~Tpk~hvMQRo&(ql&V(EX*F(()(s*2(`o_G0d!p1T+wq_qQ^yOowj@ZjmAv;_9 zGdkOce14e0aT{wd*FXb`(As7B}t+=^_#d;*gK=@&o}v z@!|_ai1<~+q(*jcm#l7L*c_#F6=WpEOQg*E+<$jl>*I zdvOJiCar95=<<@#$arYUTh}StFOOzR!m@FVRsGd;^WI7FuSXrI8^%AKN9F zKiVu9ZRkdA`8mBcDyKQKAPOR~Lq-%uKq3$b;P-i6x>rO`gitU*&@Ho-FOW^A$safB z03a&3{bAhxXa29bm5%l%8lp~$|KBa1EKD$TuY!1W17+ReW4rnV>6q)ZcF@z?MTKAF zcYhq_(cCEa?p0G!SwUG>?C)-neTUbNcg27=1luww}@2_Yz5Wn z;GNdd8-k$VR9$%7GJEa8M0isBtvX$D1dTRXOr5j5)98SFM66I1MlO|s*qS6pJR3 z(~atO;nY(cERS;Q-Yi>53x7l)yFSgRwu=00bZ-~gU46>hK@QWlNN-FtJ}i)5^WhCw zP+eO`)c1M|Wr8Td5Y-@|kRP8*!p>-DnGAW$E^#3rsRigHceYrX zSz=$8a932*-4ez5qtJem@J1?W@4tjyd(32jtWe(EK$%}Y+X+}vLh*zN1>C3(fmA+A zzF4Gag9kv6@J8zBx$Yuf)4=r1BJ0~pGDQPHcH$4msIG6Kp*DacGsQ?o$FxN}J})lU zsg||=K?sPFLaecai+L~Q$Jk3zR%xm6<3DBYeL)aWolcxif`QHr^FNl39sLaLzeiKOaE1C>OfH(CC#Ct zg=rX=KZtr&KvY6BcAukda-O;6J$5!WSY6vD-xWWFVt|A%T21@Ke$2A;u~c~#owdYX zvwwON0oT0-Eq0Op$_!C@MIe5~4_HZ<*!~)58-LRDT7X7rU99T4OW0!~E0& zTm7x*)n3lBJN7IjStVZIO79@VlSd~5oW2N+^)bB1aqquY2squYlD(v~p0@ppd2B&K zk{u`x5rIP;szaaVdmmtuhlE* z5LtS0BJ1VXk(?1)dd}1ObcMNne79^f6$0^St^-Uw_gD^GG~oz3k7 zbU_ANr;tgoyOG2ZY#obPaQka4*^1pF>UJ4Z2>B$?MSERIbY+h&1cKFRh$ z0m~L}`h$4guJ7sOnB-GQ(y0^~y_CF;M0_t1T@jF+J_4Z#QLlnvXUOdDkt;^tq9F7% zA>s~J(*54AX&%sz)m9KC2dc}1`c@@uBwWEt`hWTFbQ?$cn*l_Jip%9Wh|}q&w&w=F{O33U_v=04MA1oEb1xrNwsZYR_ZNp#J}z7? zM~QaqG+^79nSFM)wpiWIP$-xzKKwIVkL6>M02YQ`Bv&vnIAH$a=WI>hL6TI?|Kh*$ ztB?8#<#HS(GU&EUz~v|GS6(UrCrB!aJ4nzgBkdO{q*G)I1@vP($xadi4rh?Yz7MGA zx_V6TU7DCtoF3e7R9Lc<2zjLjjUXV3BI4JaBX%hicw^aiK5zUCxfFwO&Bi4{0I=5lND9C^|(<5(Dfp@YyrC@SAX>LwuNn37^YRSc~a?|dwbU6 zq#)o8SJV69KhtsjWp-D^>2kk;<{(m}B&wwj>gk!eb9?4t>W*FITYmIkU_bfQ|A8M|uCmJy zez9Ktb&C`;7(p-~;{XRI=dhC>&H)ILpae<`5Vb#5DhWrx-fN$=*LVHa z`u*1Lha}5L0vOFIMtG@7rfy*By67u792xKZ{N~IDt!y@=vpH={5 zqCEMA?Zq6esL=p@DYaW*r8Ce9u)Tk7T z6pJNlhK$=6AQJYXh&xPGMt?8(;p3Km7S7 z3wekPALf(4{*2=j{q%(0C~qwlwun2_!{N{VkulAB@&16@^~M7_L`BBs_u)|$BuuK6 z8uhw{#S2orS|+ApVHy^K*g91w3hmmWJ3gknQX9-N{-?&FQmDK>2+JU%~>Xc&b8wMvHdObyMj zaP443Tg@t!{07VUI)Y6P;1ZWFUgl;}repLBKmXZDhT^^#Y@P{h z9=pW?%QUbo>j${-*&U*!;PM7=dB6F0zds0wl7c4?<_%{%`36K(hl@xogiDdJsvD#; z1@a|>Zs!hDjb+j-rO9LqlL%iRvvopV9|E%K!l&-J9>p{a484hNm^3vDm&b)7 zi!a{vSn*oZOyVQ3qf(X_`1=FHSEv=W&@9Zk28-EN!?2MSF#7VmK7i;GMzmuYy9@E`u^BgT3{yfD^c z+t{@X1Jn9C*ZST=5caBl2}&?bFc82m3*@U+QtKPkwICMH7WB2iYS5^cDOWWtK|=8b zaLW>wR$%eYMgH>THRj7f#*e?xXFoYchx-K`DzxJ$w%PjT_R~9-L8F*p=E@iR=C_xa zFG_SxoZ*-M;qN#$7;c>|eybYYT1UJ5kv(Upii(OW6d~+&;}Fv1GHJ5eJci}nv7oPI zmZ?;$RO<$kQ^nzO;}8wBdWKv7_Mf;sU!d$5;@pov;>?i&JmOC4Vxd(lv;E(eWnvm8 zCOW0e5;wp26JOn3CMS>aSAY94rw;Yu`TCfqb}Un?5b_W4tlswt+Zpgy5Rerg-6Kbc z_D`Z424?$=mLSWhs)F(j(M>k57iTC+tgnv_*Bq%riboGtDNl9dRUOZ499UFyX%deg zvsBixt6%+MR8 z9?!9o%uuqN40U(X(-TGws0^I@Z~31m{~q1^nx&gnV}1T6pa19IbMesz9jE_}zxmN| z4)*(SxP177UYxQ(t^RFPoS-R_{SCh4Fb*iUk)wpA*rlP%CFi=9=g+aO`x#-E5#$Q>&5GI z;Mi#s=UrplLg-1vz6msVbm9Ny*T1{Sy|jb=Lm%<)|KU8tVb}AyPHMU24Kj{mDMkURyU;SVF>e4(LW*4V_`WZhtf0(F4d_L`u-lUdVW-+lrx~k(0 z`-yaP;**~LT>!0+BeTBFM#IF};iID~iu!IG3)lm^z2bNL2>H$)^J!{>6^`H9~GJL@hWDJbDl2D*dXSxAvwnP*{fk&W>P{mRoR z6fM0;ePfBG^)%VKjwj|P-qnFilBgL5=^E(AtEx!o zG)q~Q=O1%7A)$Ms>_0I{-2JRWp@rEfP|T%RFE%kHFAiTjlD+-QdTounSN_6({Vx}o zE2{J#I?Lbw@@Kp^62+z1`&;m0y%Z!T?qD~AJz=IFB}mUdU}<53jpIFZKR3QC>KjX} zt*1y=4LtDxkysR$qJl0`Pc86pHbvGd5E&k2bhHnbS9;#wH8r$KiuFv1VqHgxdT{yu zxJ3!W&?u!=nVES&wwY)6@P39zdhzV!g|#fSN`_3XNV#U9_}#eN9-Kdbb;tJ^+Zph- z5M*RkMpm6I51eU&WqZ!{3X&^ASMLZ125xd;F~`c?%Uqu7<^73HLM|Cm6tFA2o1O|^X(ibD*d19PeT9tCCKq_BDkQCg3C_%5YogzUd($Pg%cMSFZL$YfR zxpDP2-9CkpE`KYRp3w5H8hV}V;zJ(Xn`J3q2iZgaa6du6hm<|Fz9K9v(|RV~UMo+g zY0}QNVYMQR3JAa>?54LbfQWz~ihDCU&}zLu zPrAYa3=Gq3r>$s@cf&w8jBQR7p`G5M^|PfnsFw4j^HmJf!WD=S^0!h$35pYMNX7F_ z=iyB^T4oNXBqB=+ZeN7Xo?iMQP6Px*!NLp&>F)2u`|u&9LV}xDA21bj(H(N3%2Mm7 zsAXapI+av{`5QNxFE%jbARXOZgaf`ky8&%kCe~B=rA-WT(>c#pUl~R#l6-4bEwoa{ zZ1#oOC{rvH$d(%jqJl3RC*V=r=@=9|ZW*IlV|_V6RrK=JP%rLdgLDR6$n9g&mZ{UM zWLUU!iyJo|lc`yF;~kthIfBonB8eIsha!@Cv5-_oZ_cA48>-C*X?I%U&IcULcC+^T`&F?4q`w#aK^*LIpD=ZVeS!C({eQsQPK+Y8L2Rj)Y=)muNqH~)kJ)X4L zc+%$fGdyWCPsX;;N)h&MkKmnjchfGk+Cje-X8ZfmpV8edyU;Q*>UmO`64j=O;_~4S zhVVJXb}9)GL5?yqF+|tHHIhrK+`BbRUv~uW;eLW{wVl?YNhO!y?$tXyTuf0HybN{q zGddhamLyzmADumMe9l>t#U!_{-C&?Aitk`AK8M`yuU32YdY(tqcX+t4M!^&b$6|DL z#Bjc~v?SkvWwoN^w{?YO8Z8ZN*I2MDtM#7h#&h)zB>whbKrV zur2Md;K1YWWNd#ww^r}6mVU&AFQ@4WI62T4!r4AOXy{c^%k$j0beBY>j-^H!9O|LF z!-s%OARM8yJA&)h8s+jL*S?yjC*Z&_5XGf#w+oxp@~hmtcALdi5lwP1G}uQZ zPSC49N%tlB=@}YgWVD037gyL=yv5b)LqyyPeGzXft*2?C)p9J)%y9GOW3qJtPrQpm zQ{8ynDw1px>4*`F_>q>^S$=$nrCXRT3 z?w&4u?p7Kb%Pg~W`x;ljy3T{FMQm(}vmd?3L{Au1urQ6UsX8Hud)RJz!8+R9o}=G- z%1+(nS-sS11+w`PmAa1N_Tvu(3Aox@vVx4$8)0-}fbN+^GOMf1-nq%;eSLg|vvX_IL@&c#Jq-4Ra3~70;AUuifWW;R>l+)~oxaInZw&W=ZUSyc zd(B{B8XDF78uQnunO#Xy)J0;kIK91{I3*d&FkKMboZr-jo7?NY-fOt%?=2%hiLC8hmTD%pS#Io z;x@nkm4kBXFb4)Z3A#m$T9(zvce!!x8h2L8D4rgUynlw#-YDK}IezrQ3X9WU@&8nTASpOKL82kg9*hRHuuPp|dYw{Lqp_9S-XOJ}rcl$cXyxxuClf6DO*VrMM8%EA z>n9raAOdEyN^W7AfBoYPmeVz26Yul>`=>e5-#+dws(6Ck9Q)uXH|EpaSx#{C!siG^ znd1kB=?uG3tUCFPCGK9k#Kqf76ip8!hmJ5gF-X)Sw-)1~^nzmD+Yn`>?S-dA39`_B9|9~>WNFzTSSp|*?nP>_(NcI22KAV?yTBqB@gzqKq};Z6n*OfqsW z$<5^qGZ+7jUpuOtJUB{UJc!pNV>YYgQ!6~Ud6lpJa+jv!x|0u&lcbQ$xkx0yP@pr#Q&mUrPY=Ew)582Ww=aa0?Kj6mI z8{B@J#`H!RJaCMUrXqM8GBQpgeM5{4_405zPkP}lfBubySvC8V6B(UaAA>gOn91bWSjF@Cb(neC%9%(x6-_lgpJcP;j_> z1blC>PRO3aLf2}P(n*Sqr*&>Em8a6su`H8jHOKnuGS0epo6h+N2K@xQt&IhP$T_JoH);?M|*I#odKfcBswt0eEO=eMOdX(Vp(``=A7w^1WBbd*zPKj3hm zs~z+tAc#(S_aA2J!3t~X84|PC`9ikPE611|>A~-?C}$EZ%-rIui?>-w*YNfnVtnc# z6J0IGs^|&PGcv)Ekw;`o^Q_HY<#R=+l$v5}u#2EaMY5XIidmK(-Q~vBY3?V=2)-`% zjgGOeFZ333lz$x-x?ZD{%~Gs3pXjC4WNjl$xoKb+8udz!qV z9^KEr?hp>KNp5YPyEm?L>FPWcLn3zIC{yDD^n_GE#2f8nc>jJ5&aCq12OB)P_9uR8 z6-gZ&XQ(@Z*C}IZRr0A-=I`I-tIM+_N+#~;Fh>s#(H-@)?Q|2ZQK68{wQ`%cb;UC4 zB(o)Int^3DsT9(zuPh@KTY4=BB8sauS9o3O9#mh0X0=E@n}5o_H1#s+Vx2}?FUz?N zRu&d1O05k4f+!+6gTx~~Tx!c+(~7IyzIc&8-(10R1)2Qt@A%+AoUnJ(o>K_-jWT&; ziU;!o6J zGLN`@<0jYdt18%ep}_r0>rL{@_xR$=>)cx^5E(hnd+(p+zL+5&WGD zkB%`p5mVc&vBp|4ZI32B%K( zqf{F0iyJ&j-sjR68!SGYCKmMIkilqFC}uZUPo^j|6g(XhocZx*oEVLvWb1GK3wlQ} zwGxZBzv9Y`2dtE|_NNwlz0CS@iE5*XkX_>HAAifzE$^0qO0FQ?6KDDCgE6B1y=KH1 z7e)wJ`hAVZ*Pgt;N^pRYgD3dKhoh*1fMql( zr&qXr{W|xSiwx4s$kfSg_YzQCK{_YT@ySOint!;?ouwHr6jChS>m=lJAX`l;`4mfw z>y%74y$25S;kn~X^oMcm$%WdhM5kU_WBRxMmD?M2%G)+53hRp`a&^!&vP(Dlw|`0E zamZU6>5h(reE7i$j!$$TBVaZwWLF<^<WC7nj+X$~D2d9}?I1SD6Op7Gptg)6Z zp*zBi9X-nj=Z-Pb>BsRFi@SauhE`(!)>mA;`H3Gq{3u8KfP?O-^BnAHZDWbD15eLk-v1y$wV`w2 z_A)b9z96;ykgj;EC>nZ`Qa(*Gkz^xZLx~J<^4te}bY_Zf-%bS*0W|8hD&=w$B&AhI z&>`*3lSyv`ooarS+rRrYSJ!G!ZN!#RtE^;dpqmud?(qBnlE&v$w&~myr%xZ_%)#!q z&Q-}L=DB|L8Veg$N*y0CIX<{`C&d$G@W4?%&gRJc%U@Vof54?bW>}cLNj&Vw*|wkZ znGF&v8x#!(@qGt)|D$spAMYZ#8PYF0@yCWZa_R`n=`XqZXr2qdudwpqCh?FP1&wkp z#p>!hnTkNL?;t<=#b+EH=^(U6ooufT3uuyFy2n>vUgu$|vXy?$(5hq-%j9bYrj_F1 z^}q1XsTnpaD2NUpv7y8K?Bk>KL_BRrc8;~V87^L!#nW3x={e5%LqL0~5JU;Z-_69) z_sC_6l>Ru)?EEx;_*IUFH)DjoDuP}my|zkXJxj^*GH~z=AANM3;f`%OXVpmDzsl7s z_jr_VZas@uFOyl!QqxR~(i(RzeNJxi#^&u29e!N>@9~d6nZ=lJn^gG78zFb(wlDl<2yxi(*< zyB45t@(fcw+wUgg>m238nfE9ZD|~Tnj>k7IlHXY3PInZyVo@(8ta1CxzcBr1onrHeUY0ZKtYquxO^uC(mR??Qwt^4@QN|S; z;pFL4oIKElLlUsG8rAhjT)%RibkoIzYlOpx4#2hwTB7QvWB3s7pUY6He97h61+M+{13t#($f#in+f`N;?(juE#llP{A+L(nD3M97v9g+`CWjcEJkEz79A_}pI$udtf0VR_1|J-*53xreCVu)#070z}6@=9eE05%%ph-8Iph1?H}P!R471 zl9eZRYQ2tn8nj{rh=M?XqOH!;hxp;e#2RAN~Nz8MzBTT^UK(utK#Vo1hMr+NWhBL6qWuRr|7o5=wZXMVN$y|&l8xoZOm~F0bhlp0v$2*SnX4msJ2-Is z9A{5W(I0iS9F=dfyKG*Hcin=uvH6w=2(p)O&m?Eg>nNT8*KW*znmboe2dc4eZ{?WZRcOoQarq!;^DTBB!4Fp z;s_s{93tY|YpFOaOry%`y=ksoTVkoWbA<`5lH~r)IeEJ^qD@hjb zUgch`iDsAxqJ-*l69`2aJvPO}p%a`wb%^1P0P0@#?^qi7TGPO^1Z35LHxQ&} zVw9oL1Dts86o=aJJv&@nijrO&#O(sl$v7gkHSi zU^Qtro75Wyh%RK+@x!kBWEs@U85V9_KJBh-vpC~k8-z~HsDygPIC)^RE?>%-&40?dw4f^;2|?^Zt=O z!oJp|$2fNmcRsg7l1zF+4uW@%K(~Xrc$dW3Otm zL9?1={@zV4UVcovwzFMW*jQwG>B0xk0eaR%eA`?nOjQo;KmYl%|MV<++H7%z6p*_9OmSECpdDT3x~Wp zCIm#qO?+sI_kS$o4s~$-?gN%qH&}agm&Z*F-LP7zjy+yNT_a2k?&ILGQ=B?JL5JVb zZmUHplciLy(KJo0QkKP;EQ?>;_!g2cPCrxp>~tSt-yTbw-A*;Q{_q}GFWhA={{lNz zPcd`j>0AwJbex8}kB`rev-{X65lQvaJ9&yvbOC?#Cet&ISxwF{z1ToAK~hybz7PXb zlS~{s#`~v_Gtuiu6`$y(DEk;be40-s7r~BO%sg5mkxcRM)&ljWfr)_PaN_j`=^YEwIPoLz_ST~-nmrug!i!*%u13tq+eEJ?UkCs^5Sm(j5`7Pa*RRvY21e#sN^FoVRA}fHg6zZ>jM3TK&){G` zJrN)34y#wm8>f5!d;I+8-AL{bgQGD5&ZkWmQF0RK9OcCM2>qjzEU&Dwp2|_K)@d3h zqU^xo_7RG9(%UycUr(H{Pv)Huq<+JQvWK4W!+fB78LjNT@~r3x(y^}(ze_4VaHoH3(IYwobdDV6C!hH!H%$7cdfRDfUZy=R z{IOw9|MbUnB+~^-)z+dmQ>d=-P5#$-XW|j-27I)gdHzfbju8 z-e;=gNsbWRW5@V3(#!s(C05opNaspaYE2A8REHa1Fib~JAN_qjbVU5P9nUOr1rgB^ zrvJbx{P8{xEG@IRnj~MWQfssp@rvrg7mU!=J3wDw4_#3&4rOmU+CrxF`{L?z^RnveV*IF=SoaVImzGE*v*e1E zwlm<#yWHK^Pk(O*5x;xe0&52Zg-GuRr+)Ma-E}wJ!=uDJDtk1Q@#{yBa0faVKldS@ zjWwwoFQao~jP-`L>70+)@Iij`V=tLP<{R#^Lf3>FA+v zpr66s4gxOu`D?tBv}&J(d-iei{Kv!()?To=wZmU39wL3?gguU}eEhP%gP}vG`Gq`$ z66|JpD1@@Zv?IuFBK-$=-ydUWY=Xy2YozlPs!anyQtci1BM8MS=!+Xk{du0en4nKVdj&fcIaT|`O5kzEnl);1V5s3FNzOck{B1N`Pp=k=JE)V`t zjIO>xhWfjSg?7+gK|*px7(MYJ(f$z*EH1ISmL^xMP;2V#Ik4qa=;-QWpud;SSOAy0 zM{7s{AmQ}JnKYz_^I7h9Pp_7~#LYv`iv5}}XxVbPMXu?KxiUh9;6@)3@J7d@R-bAU%M`WsJe zHMvd7>Y&(lr94@+bxu?uz6bG*`|v@Ma<(NtN&M+EFnA!Y6P*2~R;ncjF82eppg0&=XaXzz8A?0mQHIg=*g}^+Bqg!@ z-5ebkfq2^@#19)qKhQ~S6>*2b+1M~PqL*o(*WPIPE!**>8>x1}Ff7a`GQ4??V5v1G zWG9L%;7Fu4NR19Z4O*pF*${j!!NBj7NUzEXczW_Vh;O_~Ywv^aIi0<7UAK)!UND=-3so}<>#FbnrtDhY z+Em+|ld8-zAyFcY(Jv8+vm+XBRQ>g6Xa>clpvoS4i*rH)uQ7IG>-_9qcEV@mU&bq-;YzUT8q`6|9GlBrPwSx{FWV(UgPp zYL5$7U(*zYrTDe(K{Kx+tw3u`exafAKvg$2$4;?QdwaS-E+#H+%f0iIp-Y>R=RYSf zBiAI!&+ur-q`i(3)G)&I_!`BWw`Dnw~#X1l0`p zQ$scsu}+s{0ss)G`9b1>wJEs`z>B9(ZrGBV-;y29Gi`n!3uT%FQ&5cBmh0TPtxMXW zrOTEl9POol&|6>U^M8K|u*VPJX~y+kITSMDX0NQSrbdD#B_(CQzo>?T^7^}C&!Qp{ z+Y8%3w`x4&|2SBoBG{?8G&aRwezU$V&KA-46X*J;d1?Hf>fv#BS00p*z|qfaAx12& zI;O!wh7E$!k~e6{0@&+I$JbT%&2pLbjtXgHID4Nur;fHcQ}Ha|cAO)JHkrxkIp z>U)Sq)6=#7LDlTMfeHPp10?h+8a=Y|(jr|os=^WPS0I;4m!Wv2L(>rI{y+S&!g0%_ z+gp#|Zi;}e_m=nfqS|G?5R-KF!n7~??9E43x|PAdl~=7H?p#qXyl&HRb`w?&Do;h9 zh*7~D`U^|#1NCmD43r8z7^eW!LE^otN%H1g14oES6;)MRw?4?>y-r=<8Z7dU^?b>EBD;J&Nngi)Jk9vn=;~;f z&qEyTUyG|R(S06?Jia^4Ka9S=iqBN=Bi)l&ZWX*E8}0n7>ihy)i1z3DH?T)+qa09| zA8=iL_OOqYNVT~r1M)R&i*}wU+xI zY{zL6Spo*F`Cue*5~MGM@7~EI0a~pPJ*BcZ1Lda5*yQh5T+Qxk{`YioPQyifT}0W~ z7Px~|YuDckRH4%4?M>dt&m-mF(Qz00^ZA%heW{k6HsadRCW1ht>m41 zU)b~7Kwawrh@GPbMi~KJ{?PnZGYVpbtg)3=@u{rb$UcF=OQ#;BExn{(yI(BvY|00=K1D1zOwC{EX>4MH`M{$PAx)M@G*0~!Qqm$klZe(LDxsNQ|zbHXoF+wHvQOZO;Y>JSx;NW8++zwI6P|36ck&8u1D zJdJv>>Mcrga)>I$*AD#qh{|kf)JelrV6YkczjdzT<71>?2|2kzh~o$*k->sI4Hi5s z3~bOph-2J1^Y8y|x`$_HvWb71S4sZ+bSf$<^U9c}t!H!E)?lD{0KEfr)n5YM|9b@m zXgqP){G=n!3*KNs*TA6v_!bKz+`;PKJxPbInW6n{9^};2+4_@_`O7Ka$j2JH|696V zFHU?Q{$By|B7qP>^XGrWb)1#c8tx zm92*GN1-Plckq`_7MjI~(8G@a3C)4pXT!l))?Yqi!%xdX#J8S?AN~&(p#Nhc^H+|w zQRiaJOOKTcUehBFg%+ISV@8yek3}T;ZPn3LfDgNkqS2u?)|y~umP!l8d2}47bij9V z14+cXhTd3K><;L3dKAcv!}uNA#UMrftfuWOu=)T?*^~FdusMpxZ&GM0#UyV|aYy5r zCQ|4m%~bRQcRvi_+wVT6@Bsd`={zT%5$XS1l|{KY$9ADpK4~7kFKl zjVk~Y?%CI4s43$kW44m7Hj%jYHBkxQMu+LmnZBcg(~r&K`~8%y4D`a5A3)c}I7>YW zXa&pa|0ELIn@91m zBEEga@96mK*VaJTpcmxFr^siN|D&>i*a2!3cln^#dhAs$T;1G>Q9jpXP9@1@)Qh9# zmraf4@zmd!l)5&h#uyty)*>e%PL{}ILWDNv%!rU8zr&B>U5PtWsTgABSCvTp%wj46!RF{9X%@$WAWsI2SWJ`}%t zo@96SEsUwROOzsi6MovRelx5_S1i_LP0#`STRkNH(c+R@s7VML{&2GX9+Ero!cc8< zJtboCrbYfRz z?>FRu-8y5@PnGPB(3+1QAGaC$o=fh*f@W8Gkdt28wBzvSe;w*))@B6p=T{R+eWwcDiWEFsZyOvt5kX}pHb;3E_dUNQU1%(Pe)TNNLKWOcOMoYk0glYblR8288^Q-` zp2zQgy%!z}SBX9uwyAm@A26ula7)6%OJGS))WV`LXjUx`VvLdTTHM+f$r2SG=yV`R1@85GoP+Wo5)o0x zA||+6C*PvFp2y{nDo5=0lf^{bxgeDDse9>}S(ZMIq2KJ&q=n=p5tnQS_u2Exnt)9c zj;%tV5~fRIjXr!U)B*`tdgy2t-t1nM5b6QKY}KtT_V4{I@C{vA69106?PCBEw!t_s z#-WBsxPNDs#Vr~n?S=Kn6#-3>O$aV{S96XZ41p-xY4Gj_(2qouy(qyMj3-2dru*`Y zTy!ADOxh=6wKrh4Pa3`7LK>FapUKM5J0wiJl1k;aMSOUAS7ttLp29B$$5H4z1N@S; z=BKB@a^HPXW9MM9=B-GAptl>v!mQ>J78}XlL{wsz9sas|WAqZS{(8rQUaiIPPhz|< zqLTgWas_tOcO_{74SpD!8F_!&!;0oTTib-J?aF!_u#NmMc|B(BgQt!}G%yDV+Mg44 zzhbS<^|W=p@dl~|kaU^%h%GF*A~((Br)L8C9{Na_L7bi%{T?j3_5fImSsotnDn#+S zFLsL9vqn~|(4%J7#R!Rp23Tp5t+t8KckHsRKWvovcSTuh>K)V;K;OEIx!+@lG*)N{ z5YpJMTU1<}kz-&&P4u3#&%y`oA5u9;1?9OZLzehV;AFGn0O}*sU+T*t$A#-GZvRsWvq1?>Ve7_t~=n@R+r5! z{X%@HF$r^7mwy`+i*HoFU$J162fvW4jSupt`|wOW6cFyE@kiLxlV4YXw~H&va^iBt zT7@%hN>DZg4wkvl8&>$rv6~;CjzKYO_9lzL4S_e9FR#A0iveTJFAB!LEtBjk*||h{ zhiAvAnC(8BMxuF-OC+<(JlExi?KP-EMRZD$AXzz>E< zM%@~nb3l4tq>L#cdb7F= zRi$gfpQ(ZmQlr47*g7uZiH%qYnz$Yv4um#a1Bfd8rw#!l_5Kx>!(;Y@j~Gn-qwO^z zvPF3&^XD0aHU-QXkf3Kr1hve;B|~4^0F~dT#}`f0qI!Z5qQ~PTrsZquTSf=2M7Fn+ z+%dAYzjyhhRoUW4F_4&0@6mRzxS7g*PbX>Vjny}cnGBcz!;K@&Z%QF=$Q`hAuRCTh zZ$B6j(u7ou&`w70dHgoeMHAJIC&mw^$&JL;&EDR;Aaz{JFg7uZHW!Mvm$W`o zujd7<Gu!NB9H(_GKS_LdIp$X4Wo80LgqXkW+T57x`>z;*&X?VaVq9K~46=h!LYXb85qw2Y*- zIZb!pH}Hx50CF`OC%5R}Y!Bhv)%t7ZnF9Tt6q&R#>*(DwPBXjF7DU)hS_45zcfeNd zlgyNx{1-(C6yeF;RwKK!djGib17FJ!a=*aA!!>Ns)T7oj%@W+N^3TloP5>T89_M~9 z`1QrH3n@J;E;W|R_Z;QBV+@B7HdO&CgEoRp;wJ=b*0#|n&*Zs&Z!(pM`n!qn_IFQm z!-5xpAAz`!)X z5x84_eznaJg<1@ylB3uC36ej2GxzcqS5Rz7C!_Rpa?k zj?a$>GH14sN$UYa5^kR$s3be+tg39d zW)5ecy_{A}4mM$rfu!m!u=)HFRM~+lT1kF;bO7 zFBs<(6ddgtZhqYPjxV5gF5KFbRa#)tqyunHa_S^BcjuE<;I7q))JX#nW3k z*|jsU2x})Sm|$Lk*FwO;qv=}8(l-4`(T!UqGi!IY9}{qXYBq~t&(3)LwA(wYg$0x$ zTj`ug`!1^+MZ+mgxQo1|d>XQZQO*5&025!d@UW3|@BOSvjCmC(hKbJkVw`ge!0R{rmdd2-@70HG$$|1)j;{k6ZoI90iZ zv#bB8M+92~wZgGu5)nThtaBtHa-Z(2rK4Z2Bu=n5aBD&~7D|@e_}cXAqAD_T$?|ZT zlr7LLdb3oy&JyT_EB{5Bz60BozI}LQhsN#LMeJ>Z_2Y86vu*$fd69}(ZFgU`Q;WMp zNMxfxSc$P()cQxgIDmD=&@xlKn_>tS6S<*)q*>|fMbj;DyLvnF$M$Yw5%i+SRE*k( z3#RoS9ix4+DBW6vk#0^<-C3njxq+{t8N|?${SKwuDCS?n)d2&&?&_!V(%UYyVG3;4 z#=gZ3(l9bMtVxiZK<^zP2d_F1;cUHgq}XW1gt02vw0FBs?OS8+i-g0Gt|y;WOMrL8 zWg&r}|GSrUi9DXHU!r|D2&34 z)o%Y+{G@Y5i@OnhgFWUqJ;N}WjRUeBPL5d|=579mr|4re0F7JLh{dfI#w@a1|<=wxhT(WH4^G7^h)kb^EQ&`vc=bsdrlaqZ8 zo!ELQGk%5@?J|}SF{r#W7C&NkofePT`8U~zQ<&Z-YZx2~_8d#n*NXM8jv8H5ud4uO zSs%(W1#agFee`WF1eLDZDE9`>xp_poO|5~5!#sqFxbKjz^Wx6FAU|ULuW#aax}s9`A$*3C zkBM!;tvU5C#qn(kp;ph22*Y9YI+7Xt2cx{N0yw|;ftSpFPlL=Wpw%y0E3*x^u6OR_ zm5qgeabl&-Gl2TdE#i#>11kjIJrF>niid5a@F(HkQvC|C*(sczZ@u4FNOX-wsg3J} zTp(IEFRFLH#VM6$m10_a7aq62H+%nW__b5|`}u+Kql)`Cqdi#`Xh9~>e=x<+t8rWr zW3-)UKX~S@;aWsi4j|a$ovssRiC^CXRabLAIEVf@=&|tHz~yOjMQjVpiNnfl=?{Ek zPt#Sgjp(#(RYi05`5k@q6TMEqLP>mQzLCbnn6A^ub~>v%G>6c|~}<-O1J{L>=VO%k4-hTAK#BE<@rJv2heIQvf++HW32a7<7CT;3$JguJ{lOQR zH82q4-i^yTkPL@=h#Gt0@#xyA<;^&|eJj7NG~8_;>ej*BZN~XkHqG1l9;0`A)SgXj ztB7gy;(@`tIhyOYkq5UZ{S)DVO@5!5+TX()h3riJ>399+FT1k>CP3V*QYC z@4~}Lxg=TT359R@!J&Bnze|iG1p}l|0nl|)3|g#jLh zlUtufd42z`(Zq7zvcxv8{BmodTVMCW=sk zJ(I@nn4q7?-HAmJ#qHi5O=rM+j+gJq<UpC#%aGrvrM(IO$#+A}n+AEV+_ z!|9c4ml-pDO6^>mohT(Q4P3WjmI z_^29Wv$v!N+JD>N7_Ajal|VdyU40+&9V9BbSyH2sa4M>83CbLy2z=RYj&Z1PJ)U9J zV_qxn(~sPibIFA$6Yj}_nj@+SCvp4I|vOYt=!goS9kZ4&Qv+sxBB&bP-d z|AE+Ai>nD+6@Ng`nr-^aQ*KNB-OO2t2~JdISW(1Q>F>_Mq|UXnR|^&C&$@~6C7ik; zx?i!4S_it`-mnT#ArXZRFGsJ@@LsY6#O;HgH?*ttT{7k#slo-IKRl67*yk71gZKhq zgI}Xn6sS}LhJHaG47>2LI1Fy6FLZ*}~U-TA|BlV81JTa<`^>yz1??u_oG}--JoZ`7%1*Xn#c`UYV1#rh8*e3l7K@>7o=* zXQTUFd=DI!!+$D4Z><@j3N8gN&nqdq@t(au-~Y&t`=pz0>{*p!=HECg^aoB+EyFhR zVud2t-zUSD`!i1w?O}_m9h*{UFaP+;Z@n zpumF}>!HKGCx^=5hbC|SdF=E4PlY|Tt{1srB7-OCWLwnH5qVUn==ZkkfY-#Y>j%h{ zy9ATm%P+=f>Luv@PSCSBxPznH?=i;}&!%7Bgz62MEsw7H`U)TD5tC+*C%+#TLpMnn zMUaec_O4khe0IN;_|$0w%i{rc=S$k;!`%dnu4r-Vbr_r8r4$qE1*c+tca zkX-txtezj=*(|=56h8rmeCo5&NKpC}_T-aERDSXL=2jKQ!o|y_AR~jGeM^5iN@pq7 zeK&&BJb;JXe+|%|xISL@AM>Rrz7(uvNQ5tnGd%cHUY-*5exCdAbcc3aUOzTDUOW9g zeBDvdN8KB0KsUrvK+Rnt&6Qq7C-wm8+WXb)Q-Ul&e(ebHYJWBgoV;xz06xm^;rSjM zmHZiSxp-Y=p;^jm8Mn$cv~+hw6`h)J3V3A;>JzxHTBW*skwLKxI)!rP4Tvq-QoHq* zNBY-aY0tan6s4x1GHJi5yG4DSJj<;JrTXFHI;ag)ZIQGCPJ!d%Z}*UjJsMlzwXNC9k1@l{(4BMey19z#oK00^ zt9ua*#26Gcp9D>vH_R+MrmHHJ;Jl`p8FkgtbMDS|o{^C&7OCa|>+%5NG>7W@TwRei zTutoZz5Irv(6ci~1<@v}^?*qg(K_uisOqEM=EV53(zx94`BGZob2Isjy7rC%GPc3- zpTf$ZDDf8{d$owUzeCPrDPgMbF|q*0glJJJC3K!K`F6-%g*Kklls5g|EquejoZfol zd&WXaV`^n=4e@O!rlNile4C(u+1qYDD7!UlW{N0Mk&+UP^+*8(ydx}-Rd8^Md@+*} z9iQ`mxP#p)%A_Lp{#VG1nPH&3=_K5bnCsW`{E7}B@lE;MDr@FO%u8#?ww`T8Yfup& zzmE?4tn^C!@&dp{6F}imR)YFvxTAsLrD=4TQt#eZ%%1sCM2Tq|gnA!(_z(({Ti4v$ z{VPJBT=7!}@1k+b8*}2$w(TofxH<$?{JhgM3LW)qN1XwNH#jEw7F&JzPOgXZQh1&f zJa;$W_D8tAxW{1NdgNe>GHJ6JjeU*;-Y*d*a!>v!$zM31uBqx{Srg%KL7)fF@ycnL zEz1Nj{znda*>nX81#{tez0(c+%6^jr>lPMa`J}puYZ77KD6oI*kZ^s49*y*-MWG5&x@^uD!(I-A z3Qt7OHaO7u(=yM;06Ha7Y7m88t2LQ`?E6wu)4A7i69H@^Xf8PLkeBWbT>7OP-`l^(bOkt!ZvX1s^y>~ zL@sBK_h%C}U0utttiqtin#BD-!Y2rEDUv|vq)xp~&60z=r&lcx_o$|Ike_K#qjQ*h zcF=c0g2Cfqt-Za}bVGSlsG0m)U=B8^vgSvF_3y1ZI4laNgU@Ca)fJx!BR}a8SOGTS z)|}ion(&z6u0lITK7fLI4+k8ZFR5`X1EI%9mZc$-=uHEz)~{Mt_^(!z;02vHDZI{H zjdFBFWnupgRHX@)TCt8%PZkA0+XviK}uez&AN!<4bSa$=QTGy(sw? zS&1*ySL7GI{|5_zRG&ay+tT;s`LTEF&u*WL%H92pxfG_)j4;a+ z**hoK#X;V|P`bH0adoLImc?E!-?JQi$zB@W?pY=4A|8a(^30$5z%h zwaD<;VO2Q%xxev_Yn<2EYZkpc!K;{;jUzoaw+V=wn`Ri!=G~ju6w0Q$quvwbn(I70;zJ53|MpD&Ymx(MWsSTSIaEp`&$9Frx@NF^E+|(!b>lgZ|#okDb;scv9nhi}dD^zB@ z(4zsziChB{T9WOzWvuA>q_NOvf|3T~5~d|34DcqE&fcH>6GjyhyJ9BmcW{(ZIeJ?` z60~Ge8mq47YaVs<3tw#rGs%>j2;*_J@st|1x3}V`RMGpmw!3plrdJjmNF`|3s8?cl zw)N_E@BK*uOL-7U&di=3t?YEBo0bcmlsB!2!pB<7BPMBI#ihMIsuHL*fH~6ELXg*p zFhECL60GEQuKO|0WBSJ<+*+d+m?k4jTu^@Jh$L@LP9#fM&fh!1XC2&0hOLync=G9& z*BN(bp2q65REMh7sbkcGow`eLzm&a$eNF1DOPV&=<7mYUr22&YT$dA9MYcz8l^)HK zs8~_c04%KT`RB{9HV%~EpUz6j@;`^&SMgBW*3QuD@ULlfJlIJBjZL!E)a3MG+2_CR zc(dJzgnBugqGkP{#>1$0wM&W(b+KIVEkXHv3F$NCpr}4uD#f$MpyvajgHCU6k%(>M zez?bmPO-^r{jTdsd#iVvhUf%c4+jKk6E|h5Jo#8=WawLZa7}o!C<&wvmhfOY5@!g> zij6yt{Qh&wg0GUjwIYFfH_LUbji4qVf!v}-L7r{uYME_4LNhfZ_dcBD&a1iM=C^)5 zWLoN`dQF)so`1 z2%u-5=D+zEE^_kQHmo$S0QZ%kf{ z?;hJLou3m$zUe!;i`NC^sPMOG-ha>pXK_&CYFlSl=HQh4psQA+lTtj2f((mSjvGw{ zM+a-13EOi_L-RuQ$%14}!Dq57zOf=Q?oMc=0}Hq#CPd2~Vrn5_$jhNrvs^KBg$+q* zDemnslD$z2WiWGD;Bc-baq_@+7*By;fki%~EvCr)X<~{(fdsujx_p4oS}en`j>Ej^ zB!c^$;n|vpyL*R3o-qXy6(1xCJxF=1!|AQ$9`S*Dh;4*eNWg76_MjX(KaEt6KSeA& zhDE|#Arq&S#Kc2(^$F9|lbOTlT&$n=nCH)z=H4i+{8LyTsh<0a7|sKuR*PLxl~-F! z^xpeP|MJs4eNR?-S+~RIs1z6kTrKVd3j|OH!6IX-Wni`P`|^1I=+EE31r%(A#eNo2 z$^71h7p+YBn`0^srP>Gni(j{sGY5SUlcW1SD<^gV!ZtVeB{Z;F%NzYJ=c_L|N6SZb z__)B&Lp`+UKj)5_MU&1`dLS&TQTVP33)A0~RHJ7wJD+0OJd9+M@r2^CA=&9R+2_ifmO=<>bfjyMBtLeBnR>-m0teP>E zbuI1VGp-TVB8pPZPNc|q?YQGve#K-?T2R%N6oE=6-~u1;_W?)2bQrle8lMJDP)Va=1fs9ftEy)Pk8Jz%XanBc@3Sb( zYFkR}7X)AoY%5Zj#$vp@1iiPVxsgc{A(hw3aV zy&u9T)VuY`$^evuVTK$PY#{>Iap>I!l3qs47KYEcE||dx#e;J4k;Ks~3E+AfjiWqY zDx|vTkv*|BkDNc(08DgTm6*P#ZtiLHSbLVSC)tq77>SzFsQI`etBa~%bx$AlmTfOE zs}k3cYukya=hTDNEfG*~W=%OHJco5yQ$<0uFK6#t=|=RzS`1f?)169Nc4WVcE00R= zXcK=K%YW!v2vR!nT@#%}w_urY6;kPv`u;nosmZ78m$vD3`6O`Ri7ZTy;p$8~k;IdT z2xMJR4b6cy-{6qB!{W~Rl;s(hR4GshKfjKi;?#FMX)H~yVI+-h=00_Aztz)*CO);z zM73){v|hjp+}BSsI9>=Iok#w@((T>TJs{(MlSp6|KBpf>PzI`7xMsIRA`J@${<7Wt z?~^oyUrK)AmES^=tG=DF6;>^W-%e7&$b7}XT&uG^^2eL66U@&;x|Aj&-A85N$hN2I zTX}8s6XubdS?(4to^-8iOMX}!v%@z?Ik9NCNtvNoylgX<2t;VgQlM(>dnH~V$XJzR zIo@1>)<_k=2od_$qQ7ttB5YYv5<(diWb3rmh_%eB6CIH@wlrJFiKQ$>*8OK_>SUS; z@l_H}ia``h&MAB@d)eAq7{q+hAvQ1Y+_recNc*V1DKLD*Q7rhQxagz?8q;Vn@~J@D z%SJ9HXa~Qb9aK*XbqrISzU&!YkivCfBM}p~z{tq17?{vbcBhMuyG1PgOP85x=0y*k zlYeFj7*Qbk+XNyzoqt*CP>;V zZy%bhoJD+LaA9EJ5u&NcdZu_I!ln8=v38`18{bfD%SCl^Q*UXJ7#zjBuUr)jQ1VuB zP{E^r*i-Y&x_P3ye+Ju9jdJmUZe1uO7BqQQKd8xS|DjHMebA87v=?9&0z4P!J#jPD zfnx{nPlS9WAF8?=BWQ*h!gm}c8;mb`ov%){EBJ^p%Hi89!pOxj;g?iu@^Za`Nq0~_ zYCCV3D$O!3LWaH&lglH)?0y<%eMG1;IDOv(R|q z#`-(L#=agf{C$=DF>mGl8bS|H8L<6~Y0%BMtXO(_p*Fwy?_B*8{4e*TjV^xo?7llb z{aOLR?l^uO1&7A{3>dy>;jh2T!fcy+3jD&X85Ee3deN2>I&N>W(Wl&5FcZ<6Cu6m| zQ3g>dkSI`Kp}d6%6uxq2no|_XrcDN?-IeE*8w*YIHsa>V)=A8}J#47QQ`8k}IDq9p zOEmAYRVmA&Ev%wnt9P-%G2I9Ye8lzS@7t4Ueh|?)VcmqApH$%r*VM zM@;+~MfOwloQ#bbdtvNkSFw$GM8Bte5$f;1mw((?YAN&?}jJ!&G`{-a>rovGLQlZ1ur_n`KyLrLz>$9ZgCwXXtI<7NvKq+on30- zt9^fj!{9J7hF>?=QQ7L`o`Dl%_lPZ%0akqr8t_}P5?}mbGgUgY?}_d(snV#!8j&9X zbw<$R1j;7R;OL4yDgU~s81f|9J#BwA;ia!*s_XqV`0T!h`+KO(_pb1T^qg!jAQ4x; z2AG7eR|9caWDRd*kG2ZF*kZa=f&r_mXlXGPNDS zvl8oxZaL8jD@sy&Bi8yYo@W5mOHI#Wj4Mcat-@)C4at56zwkVN#7M#bBr% zVjntG4V>3eA`?B{u<3(P(a=>nx`2ITC4XA>1z0V#E4prEm=%UR`C%ZcS#u^t2exEd z%$6d$=GoHbKtzaq575CAtjhxhB`mx6yd-PSs~hP@t~-eSsPD~%%a1uh+u&x*ISI(G zskXjV(_Zb9FydvFBCb%yaH$@NGdRmH>Wf}wGPM;{7ygV#7X}p%$WFG*t2-4iKre*v zwDU2wwho0YtD^o;mq6dnG4X{;)?QeW3p6OvbL6~rou;O(D<$Pmh_Sn|yeW<-y%Yzw z>pkSID(xyc|;@0oM~dfzyvZbkCG zW&MzpYx2ElUHxmn1rBHZ8iB_ikc(PuU@4kJ_c zhgs>w6DRX|g4d=MTK2t_?E>i{xU|F5u)-0+=7DSDg*v)Oz+t7=?hBG+)~^gPopUi{e%h%CkEzPZ`{ ztS|N{!BkKp8;nb^ zVW3=Ed8lM>l|^?Kl@q|B|IU$cnq!(@a7(xj%|0eESTTB)Hfezrn%WMj0gjp@!8&2i zFQp<(jv`GYz(*5HOR_6t*Pz=2wqYe04RvP#tR{cM%&Kn|xcJ$+48{1l+4&7HeyQkX zK&ne18{}^PtG^$&$rVE(3s#R!ribTqu;&T;*8`^uEMq*yH83HrhC3C6L;&Y;X*oSO z#uRGi!5k4BnW_vN-e*iV7Vjg;)CC#=fGCKY|PouZf>=yx}ms+ij&I`SKkTq zT|p`)SN88JIq}r_gxGU-W+VBS{F>kd>1Y*y7Oi2oH-f0d1?1fw)2q2Swe^n~ZiRtr z!*oqh$Q_qxmwdO@=;av^e5@Mz$4WX%c}cO6jW++@F;??Dm_XcIe~dO?vvFx zhyJCOCZjzJc}N?vGf}}7v@GCqMdP0xtNAfYC(c>=x3&4XSxF{csAfpvBcWw#Gbavy zV@I(~ne(>DH#dIlF_BWuxF0GqniY##Rrz7BU^)0;gy^}r-aHBdT@(oCOj(?5dPJFm zq{g%owg>;%Rj=L4@etAVsL6k^vLE1CF!&2o8hN~Kro^XItrU4-ig*7hQyUrKEX=)y z(#PkpGd>-WI7bKp8hE>A?|O=v$gQ{yV$~(n~>LwXvs#87Sq2L=gK2yM>4xPS1Tt zv1+KzZ_E4&HYM(sPclhanx1!H?ahB4UyC(?y@n#My*w!9_1<;5q}`^ywqC}N^8zdu zol1;$w!#wST=^t5Eq4j;cCp;olcKz&SSJo)?$NOkwtVWZ%D(udv@@So&IAZ1Elg3B zl-X-)fIXip3ad&pGJn1z)bR$QO&${Xq&}!%XmJDmR8IJq=dA*$VS|ka4;xGx6$na2 zTFet0Ot3f}xrGfU2O}%0>uLz-%5jG*6Z@KbSjNUas}RA1d=AC@bCN`F9~`cx4It~4 z)BYbzcCn=wtXc$H6}arMtnG?QJ2SENxnY?nJJzFrr*9-o;y!m%Mh)eBz>ry^e^i!E zBo#Q3A(mD?OB~)E0&P5;mFcBE?1@k}hY{qg_s=_rX%wqY>5}(Ropt7PFYRAdsZiot zdIv-;?K+_KD?9AF=rNNB7%`q_`nH3pLEz7oeD-nsmsPmXT!7F@NmJ*l0M&TWB!>3C zY2nWCFwhi?iT_nG2Smr-asUA+;~ykH)e4BhLp{RIj|#iq2@F^p;d9hJyYV=4tSQUv zLC4>ww2A$?^V0rq+`KRl)FJBkuWNI4ecOVXtI~DCwfdDhIghasNcp5`qhWJYCNyq4 ziSk^nk>%egKuU>B)(1tg56jeH+I9Bf8ag5=4aswqc|cYAMU+roqAo>i?jBFs{q1{| zX}#UGcYU8FysDkXINW)x+ALcE1E~=-y3UKZ@ZEiyZaZ2jQePF!h?thLd5dHb33Jd2S~FWN zriE{2(>5BT2-uBecJM!9qothAA90>NUBfkKBSsN2BbM0XNh26(A;LKk z9@qwrHW#P2d1aUS!sgRZ8ADBNS}8X!zR!4H(d@Hl6?O^!ydAf^pE1t-s3)c>306ZD z`~o)nv%VXH&NR?<15t5M+0skz>9@Gp-$aSqy7%wJ@?kZf zM>P#{sT7O%2Z_2|cs))^tG&o#QJXTIOt8B-&)tOi9AjZy$6wRI#ShL<>$77yP~fi^49MlxV$TIxMzPsYg#CJmYyM0vqOAs+p3t3X}1fjWytS&FJxDw@)-+aWG zo>~IVBbpicieMTV`Q#=OcW*NMaFLkqp{=KnzV0T1wx>(WyuqJBSJT8+XBfM4m)kQ@ z3}+SH{m1EPtHu3FGr&wRHB_}gzMx|YB9g<2Ro*9Y0|8Mit}R&9HreLW%~vTVU_ zml4ezT0Tc!(=m!E*3Y{exkQ-x2SeN*8fQ5rQ{LIZsnflbTg8Jl$322D4UK#v%+%c* z+`T_fDDR+QpqIYxW=dc69$*@nMxJy=LpMOQSg=}@eFJuaAQ%5e5ivE5LM}_;iJmx5 zTpTSEVtV*8|M>q7vZWblhJj(2NOlkPZM~d2e}QuY9n=P$uXVDHUPu#LnPGJBF1Kd4 zFkLltpEyQGQzb6x72CR|MnNr*&+qZB(}`7<_My=4c~=s_%w@?JRMhV#)YQquH<)=a z%+1kdGS+I&zWo*_I_nA8k8Za3kAq1*9br7=5xIIohE+2J)G9(Q0*$k=O1fkgn zY%H&^9@-)G@dvznycVmpZ;H;5g{c?FC&P^2zP4vyx@hS+#%?xL)|gO)l! zHglKQ{C!3z#?WOePM4h$$1imwJj&3}4INcCK@bro329%)VzC5JmL)_J3{6MZO^id_ z(NL3YE1 zyk=mN1%8Gn|8X!4bYq{UkAi?GimzU0)ig0R9YL0mtyWCYN=5St&b@t(vwba81RNNd z7%Nj_4BfcF*SDwG3e9r;Yb%P)Nkzpu%3ip<@{mI{3=HGhJzfN{*wf%=(W*7g$7@y) z_jqityj2tdL%w!|72R?ikWrlRU*kDT#MMOzPdQJwHD2hmuSe!q#fNm6nkfx?% z3Lq&K6jQ?GE$8^VzvAMlPMWIyI3<A7pKrhDIU1#p>u6eD>uqli>p1w)31le~!LJ|DJC0FAt`<$4~ok zyd)jO&NML%l~iV z$zqZJG#yRX52b*96krF)6n4kelCJ=9@dq7{Mlvow~rsr>b$5_X_J$K2J9D1%-KDQM z5MW~JI{GsPEeHaL;(;>yO;bb7{{QT~*K=HFn&$aCF1=4AOu`!i^d#s#MTwHCRI2Lg z>hA5`-iY3dy_vg-{bM%vVs;|7FSaLUyJxDZYpO~TMN$;K0Z77o?}1Dt(&w>zaX<lJ1umSqnUwXAiS zBT;((v$^h1Numg*iK*KGt<5fv@aWp<28LmxoAw7?P8SYEMilIKr)hmBll3<6T6x#d z$S#lZ@a8xC`I|mgN)oN7KIP<*-85IY-|`-{00YCY<(hxG_kO-G#yJ25gZO2$OK}wv>!jk=_7k- zt*^jIp2W;B4{u%Lo2&Qfn_i^r_I2{QljhdHr_Lkt%&|7F_pDzl@0PO5Oh5RN-~H(> z!%G_B9Va<<@)&!YLbx`YRr5w+t{1kNSeAe&+B0Ls=lLG%_frx@OvAv`bWAJ^!$4Ct zOv?nTL{2T|Nc)HU`WL5Y3VjzwuBeRD(AI)aQ2E`(hxAPM(c8O&wzg&}eD8~Gwldx) z1KtrVLq*jMBu|9$cn#H+J`^!bB&e{QxJ_ntm29q(sK@hT3oriTII%1M03ZNKL_t&p z@H}1BXT#z^}4XzdYMW$fLZH`ERHhCLdhl z%RgV?YR?kxibjtA>erk+yoH_UB)_)A-1rz%tHn*77H_ngcx?l9(H|@r`-31zPD0gtIQNSXd$KytNFA-sbyURy zxE$-(SgBy!fiqOrHBcM+7yj$zKBiM+4D|KVy=w=j+d{bBa1h!uHPTBn%uG(Ql(PfA z8zD*x{#YG#b=7ua@2ytkX`~khxqtEB_9mAXwGR&gLq@etW31C?n!xY*FV`kmTNt3TYY#0oRrup?{yk=>c@i@dOwKKl-h`iIrse+ebNixcNR9_H-7BA!3T9%!Ze6(J` z?pksNYuR_|Jb|V|2;MScHO=g9DzmG3L9Rv5+odY*JO=FK?i>riQBL$|RZSr7X*ny+zn4DQ4Re1V_$__V? zcoPlPG5pWe`?tU{Q46b#c3kH2r5jv*IEPTajpOG&<>%*i6Ll-^u(;vT@4kE#@UitR zyvY8xFbx&0n4^jN0Pe11Tks1Q;L?&llFa7ZkZ}gO& z4Rb^A|9OR2vag2Sr#|ODG#n+bmdIt2B<5%6?H*vd{}vMi-Q2r>nxFmrLyokS<9EH{ zY?vPelkD;gGt*Nntf^1gg&+{9Xr#Wjn)2Xto;AxvQ!^}&_i*jPS6sR?Mp6vX_QA*e zTEl;`3Qn1LUnyJO*K(`9w&+{A>gN?VGn0wRn*4I`Q!h% z#LeL(3!|NUb^8PU{#Xp>8xJ0vlyWH+hkKYz>8P7j1UUT>DjRlDAC*y_nHgDE`j{W3 z>)O}+?u!nl(-u{GPV(_*pK`Xn8lUp6>`P(8{j@jWb8qQ}e+rLYr0ah+HxP2HwVhqt zTd8?!R*8fthuMB;KdqySOw5lkH#5u3%o2K|?|r~|3*-I0c~=lbL{Y#r?EsQpeXgLm ze7GF2X4utE@9{1mAxZ1xZ`oBT&#yGHFijIpv#T}*Sw<3Hvc=fa$;|iD(|MblLm503 zdpUUQ04-JFEvB_?0V)#@u5#htDATE@Jr>33=h$zm@%!9wF&SWCs2P^WySQNQiH7PwTk_CI|2H)s+DjGZxLqPx0ZoBeZX?A?$OZ z$RZdaLg5IZa0I{SD=yp^X6oTJuC+7~_Iqh5cOg3bl-2FzaI6Ij3B~2b=TYpcy+@D~ zobDi%4J{n{;2^gi&M{TYF*h~K@@krvDmTg-by_X7QikciJ6yQ>fQeP@sZV&qmFzk5 zE6Sqb&65F^iJ|35CuZon@hvy*_Aoe`B~ZVI!>7-3>hMmgL+&4t2#}CvTT9(COpHfW zjvJaUz7Nwh?DxMQASe!GQA89a6mL1ryZltQ=pZ|By1n?^8v{H7g6zO0M`_%(hkXlk zbPX(%%%qr^nq@8DNO@o@C7GWGgJL$p!1XV%r9X%no&O>CzpBSDx07bO&PWJpD@op~&Vzsdb*q zuFlhS;|kYqKV)bwhqq=Y2Tq>l%(30nMt$!txg*F(vS?TOo9h+GFNk26rirGSb~mRi zKl|7%6TOsSWpRtoEDPg(blkYXjgA3kb27F2k8}3iX^!k^AmozYO?M(9f*|8i z>`oQaFdlcxJ&QCf%R<-fN@YX^QE?zYBlaxH9zqqhc*0ef>ocZG#T@Mi_tNq06|UbK zW$gY9t_K5zgJ;;cE+P5mVDs+k>>zh8Ugpkt>M6Sr1R4(if=_*A&rAkbrbaQn#8}@0 zZhU)<&cOvro+|dWALsnJ<7}&XSG;T6G`5dycTL;8Yj?vx%lk1c6XTJ5mn_>=%9c(( zIYocxO*)2>$dN{lojFQdJc#$LS5iM8hL&Zj?+zEQJ!CYo3Gap~*nRp}1jFHH^RAjF zvpPrD^>4U#r<}Y9XD@qqjQ*rqLZe>CpmrkC`WeH z5OBWbBCyAJ#JhGkfMu*ps9D%?s!i9}aV*0$5hMvoR*c}P?q*v&fNbPRuN5AB3cZviTPWHFm!Y8+vaGGG;gm!QCGDjuZT@mtl=4~9 zt7{}zOW*sSfZ{U974=Q458oI}jr{5iJ$LVOuV)4$yn}5!chFR(P|Tz$KK`H%dX|E! zV^|i3u2RfrNT(fOIB_`KI317}A7prBhNY}T^S&MIZQn&xbrjcQ2?=360PSMO!2?W> zPcb&q$-?v~UAj?Hwc~1rgchC*<sv@GHXkVZ8$c?trN->zxVgI z0gLR)91{aW^v`9%TgUFh2iUozf%2g9I~tQ5xP1|-o3>L*&oVSP%lyzh-CZLb*j`6t zxeHlTaC(C{y)XJr5vMOgtf7sjvaeZ~)5s>1tmX2k7H>S@W?3d`F;6FS_6#WoQ%B7um>hh-)o*Ul(K|)L@X~tn zG#{Ng!tRzhQNQy?k{J1+u+Y^KxpbOja&>*c^hSt;vISIa(@kLyS6!W<=k5(|T<_%m z$P!|>j(x{Yar$^WyBf=J%Fi8<_+}x<$chuEOSXe8*$l zy_K3W-#eAe5(EcMhZBb)Viq*CVhQy*(v+a1>qYW;n=fUj3#YtEho)ts6;jNN^>FLz z4X)kkV$H*||_Tx_7` zlFW^E^X;Xp-0PcSx#*Tkn8G95< zrC8F?Gy_3)<8Zlg3c}{+AV??c$)?k+CR3w%KYorx7vcrkf@#=+NuL{dDQ44w2QmIYtOAl@`d3AIDcRdNY zG&M-)jq6;w+09HE%3Jnv?DT0)w6{_j@x0TybAqVgbU19@EtOD9CDdnXTmcy9T8Vr? z#}Y+kmkXyPAp(Nz!XI?K(Ek!d1y3YSb!|1}!9He|O03S!kx}MH5t_cL}P_%h^Ga}(bfFm+1V1XDxzxqA5q9sM(;OdqW$PV&*&W9(|KAnJdYyelDy zZoFPwmb6qVQc~?%me1wgqKc*(;Beq@yK#yFvLxYj*#%&N0B*M%heLh_{|HDdXIH;`AA*Q8SV4Jtl$cLpGLvC( zdX7x76~l7^e}+s@EwyD1#J5@=Vv=n2G9i% zT=;x$+%5$(U80!HQqWBdo?(DlC5pv7*{p^o$~dEC_#M(K2P_5IjmzaD;FS?FCVELl z)t_HAy|p0W4pegBv;Ud$6Qxb7+MT`-RSm99J3Z9gA|ns)@a3Pb@NhhV?u&Euqw}0Q z(N0Ts2(R;9NM^iE2!Kpk;~viab(o#$(kAnM1pMW7RL4C}t+q@ZJv~Lol}lW>beqA2 zBA)6UoIU>`#}90$p(6MLl4GwE_W3zoZhRgGqGh3`6694K&4SHS@+O9!C6g|*K#mM43-dhr{s-0Ec}>!S7W zY0jKI!I52!!~#E*=UyKK(SgU~!sC{)QbmgS9Qo%}m{=-m$+o`{6&zkaUWf8M8_dE~ z)65QaaOtZn+`tpZx>T6FSAG0>lCiZ;*-x zH||YJF^&8(6FqnM>Q7hb7+yg0)v*8E89qLHgl*MfeD6dWXd@&<$xS5ULXicGLXLc~ zNXZ26qhix1U}Bkhve`VvqJijg;|>IDdA^rE5dlH=602{fp{9ax?=%Z5D=aUqkTV*2 zVO_&t1e=#)jr;lNH)ZTjmo}9N@|V|BSN^nZZJ9b+dXl@BFY@)}y9_Or@Yd|)gYzG9 zyuFRO^1znhU6*^^M>b8gRFa&kJ;%;7F|-`HToK){P{JX+ZWnTTj;Y~(9*iuLclena zxW^xpLpYW1bv#%lR+ko-SSZSHVaL&veE8vM+S_W01)T4Aj|vE) z6OYG@$0cK>AMx&UtVOFxsgxs~Q9<(H^agC+eWeqz3uE1G4_>znmWrOwqZ+n-{AQnW z32&r^1HbqO%1&yiPo1lJaXC zE3*$Z2xtJOZFl*|LwymN)!UuK>$5(eha``2s~<$6TIf zaCw@+7cERLGts-ugdh=XT*KLXoZ~Gn3WbtgjU>v*ij4d`%SM!uWf@r(z%bB@1=RJS zSU-+rfQTnlL35~r=68K4&wyoFSeA((h|d`YY=NawQthFGqAVfH$}`)_Unc}nAy84z z&Wids{7bJ26HO~oENb@9JlTO`U8-ht*aN0yNkS9^j8Xwr*Pdt-wyZ}30H4#EZW&l+ ziDJpXu+}9TURE;gFNCCcC~w$7dBcuZSY=^pSr*40@a@;%@a?@3R)}%10R0C*)vDk(;O%2-5TzoC@KVkegZ)c!c2}# zCPgBnLum8QTUwS}I>Ewf2|@M{h(_?coKFO$jADw}p$;y7afutx!JpbqpFSLXU=fu#6jAsgE+PX&xuH~ zlgjEc+|Ct@e2UdnhIGLs?3120(o6%Rm?W{9AzjdMMSX;0Wq3r3VtR?$(Ge!+SILRx z?AWu7hIk0aGi*aqaoJsYvVftflu9bvTM0}__+zzfkJYmM6;@eBkz8Vuj&CmT#ib60 zS1c-84{`33a~$2P4MBa^myx5dA? zM66XxlT9aBTGJ2}C&6e0pX*5pN^4!RPZXcULv|;uuG@od1wlY`I^L4cAmZ?bsoi^m z+E-j@Bru98lBo=t zfFI4z$-t!Wz=kn#OxH4X%$llQ4y~o9P+)?%S;T_v**}( zsMxo;e8oB}Bg^v47()XSWR)mobvtNpisEp3i9{+Fyqe}(KZ+#ca45)L#AY+1ibiz z0o<=tN%m8NfGjIG6dA!ZF-mE&1>M%J-Sh!9(DXdHqAf2WI$Stp1qq$>;xwauJxnG+ z4py=6@E+npC!5v1SZbca>I~C~5}GLx3q?lS^adwX7oQ}g2 zpmkRR9+!ft=2)5>VsK=F#jKOc##VOkYa#NCtg~5IBb{7iK2-uafHxSztGp}S=(hyR z#M0LozIT<&7jAHGB!#DL4`)94h!Y2QQXlheks$UKhNY8Rou=p3RsQ_d9fp%4_4`k8 z_S`9s?{6XEk+(=d3P8XW2vSxVBccqE&dxJFzRX&4oS4h?l%s0sD#___=2tVQIBBV^ zBoYp6%4I((7zL7ZgWR}qfva~%Nz3INI(ddqKRQZFJo=h=?)5+rW&C9^%3~3{jFCz# zFfp0pSgmi9c`X*j)n%5ZrkKkc$WcF)Rpt0RuJ1mnrs5nxzRO?8EWA8=@0ni zgTvIteD746;|Iesv5YmwAKv8Rm)~-GU>>+GIjY@0r0-R^o4QJ7ewx|EBxzM77>-d>SB@eI|9eR&!{Ai*1e7M8bX?o@!e5pX6_p zrY8nQKLxAE^7I75{gbR{BH`u(v^RzcheE`+H&Eu=IG}p#z%ueAW(K(N_19eM7$@hf zFeCKi~OT;p)uvnlTu5(_L%PcvUIaRdWY zRhQ#)I}lKrALwLgY>uV8ld{?t_UvsU?AoMjz_Kv&tE?syBr+<3?7~-GiBFNYW3^8+{0lzcwM3Tlb3ZxdM85x>jsbC@n>u9VkC$gdK&oT`RU9u1kH-@*MCG^^0*|Qro z4b89+L=jnWphzNu;v!hLm$UI*oPKULMF(?+f6FCVTgs4)HL~yQZ}{cGGW>2CNmfuK zi*O`}*Q>x%hQ!h$iz_)ALN0rl-4owup{ABtUQUw8YRDcJp;!!$^8NPo_jnd8T}9Ol zTf@EvY04$7Bn(@wW__td#B&-Tf8!kTg`KXJ0F9>ZJXoVCrJ>87XuaVP4B4shk zD`U8%pLmGJGS_*Dnlvkn<^L%~VTdmKRt~ za>(SHIxPo(ztPU1*^S&hM$l=ltIFwKTG;3ygR7GLb5w%R$O2 zD~SfZZ+Lj{4~0Q4IZgk)TU@<0#Hw6Q>%kNJ?9-EMi+NvdfV*i|H>tV>f`F_zktN}A z;N4YLLv6f*D&I5{D|3wW53|1^M934^P%&d+su`9hCm0=@W6h8WL~Cf@9>wF7Fx3Jp z<2`)y$4hk1K--Crk;=+B-Vk`&Su=_xXD1jN8f8AGBUk#Vh*uEwIDf+YWMLXb)@Hi7 zcI6fw1B+OZ77m~Nh|@>+P#f{QyyTT->o%*J-3~2EkKPem@i~5-u+U3sW{0}Ceyx-K zxdPGcC-~s}IZn1W5#4Ms;xoU>1XH7^u6N5xGRhlBMk&59W$|hn%DhaZml+%AXKGgs z@o*gP#zdK^Qd*m5sCSHowGw!%XlkgWEcD~ChVb|R03ZNKL_t)U@$x(l+m$Sn#-Fh_c^``DUyXMyL!+dAQ{%ZSCRX^485nNBf2(9g`S zYT}_PJWud$i9%|gp}ujJ(i(!difxS*M1w9IzB<~DRMT|ud2`7uFjwim`W3~wWzt!N z>iwVcSD!Rf6Lld*>7)7!*>o40PP!%Jl(Oh_G|tF+Tm|Bs;2uIA7&}O&v|w z(cU!gMk=YPt|aE0WN~SZ;ejC*_m)%Pk)HT1Q_CC;obbJ@hF&9za2FX}Uriq`XVl(lGP5PFhkx!1()7{D4{#gvcO-1Vww$;Umcs4jJ#WhmP za}3R_Au4Vn@g}Nc0lZETL6lG&63TOq1x$3ofkROc1pz^@Wl&r$7fwk)-a-{XPr|}9 z3=Cc8J2^fRwWOjOcJj-@4rrE&C5n${^a_ZQj3P<4lVFgwIrR+Z9%_J%57U6gcHC0i9ZV36+=i4ZxSe&0@axsITxGAq| zB_8qMcG&+H-Eo??HPY5J%Gkpt#va_Dvp#~~*+eYhMiMLxwZPiqARV3ec{sd+<*uZ* zbr1V%9Jb?Vx`@Uigo7T$@ma>nDpMf)XSaZ(#rKDsD}#u+)Etjt6nV zeka>1d?>R0t|+c8Fx7XBYxk#FEl8B@*unOuswXs_?c>ofo*3|5LemY*b;&x@(AVE@ zvfX4Q2;Xt@){97C={e>`d%1b#9wRA>>RmfIdc2*cs0-^AdCn}QS)7|?W+{y!Iw-4c zqqfZZnCHO0U%H`h7^G=ZEU9R^iG>B0iD_t*)DlH~y<=?s8aiYNK@d^A&d!J2>03tfM5t-oM`Kk8-}>=b+8U$x?{MdK zFViJAJNNJB_^~}y2OVgoBF{ecb-PlQwqC`trK9GS=)QW5d)&*#2u=ls=Au0@P_xq`ZKQ^=7#QNgOaLZtjpC| zrh%%KP)o%pcutZe+vXExRK(mIXe`6$QV=bZQa-`#@B^;i z8Dwf9kFRzQ&8<6VjM~9ow?9NpQyuZhAS;<9efREAQywPb*g?$yNV?3z)KvQ&oV+7sO3wYO-NHs0XuGlu$d9GA^9K(BpcO7BMs~c(GQ_0<# zRTc;Ca_?cBkk3JL#d-&xsZ&^+W1{;yHy+H8QWeT~?q*j*8BwnYf`Ft*NY8bEEwG$8 z6nQ;)Cm=}<98MQb=eyS0e>N;V%iKs0x2|?FnugjvyEuBhorZ`LOD#QTkJ?=Lgnd~| zvp6@$%u*Ulc2QQdjhdI>-BL+KGfeFM_I2JZ*}nGEyepx2%W2-$L`(f3^8*Wv+`rB@ zZFQV&D}ybEs$B6;{MGJI=UyxST4#d8adovhu6IY=Vh+*Zr7Eo-0PVlDMdKA_b_Kp z?xM^sV5r4s#<~STL|lKDg3Xu3wMC|87FbEExWiS%tE;Je3Hwr2?e1-R(74UJrBdm; z_tf`z*AZ%E$MzcfCYBhS?BRY#oOsO5p86?IGq8Mf~;cv}|jk zKKdxhCgb&&vE$$lYVJ>vnO>y#!F?(!D+!%!A>?tQh+wEW(#vDqy4l6(Yzos|PD5iI zb@2d_C}6%%25ecpPX@fldu#$ha1e<%vG4c^##gRze|(%P|N2iXj~!%RYaL~N2|csO z_&^t3y(7$~6@pc5od5I?ja6Ybyra=pCm6i`NB+;>cOeJj9Q^Em=U1n<)97?O`v89Q zumFwJ!W7dp^Q;ygStus?)I4JgYm{^gQ%x~5+E0f!hiBc978MuXNHsfKs&FY17#fB7 zey;wHKlA6iGx+NFbNuuFZ9N(Adf}_xP5Zt{<`>rJnjPZih2OKbGQ-jRZB)m6C>Z2Z zi_8r7aP#JU2BuOt!Zoz*J<9RjW%%By_UxO6iCRpvG(E}8(i+7_g7TKm>f9*vX%$Vk z$gj=QcfW&d*kiw71Odqzq&!|reN_;bB4HUiYr|LhZ~t%G*b^Q@IOjREY7vF zy`h4jN5)jMtj>?q+j*DU55`$3IjLxA=hUGl>dM>*qJSq>N9)0(>>E#Udtjc?o4@5h zCq_81cRLO72tFs2(#uQ?_0iou%QZXWiHvye83)V8wk=yCQo zMDV?Q$>@&`Mk&kc#6zw z``=#X-f)t-BcF5rv(Gmq159)^!_veUGbA&AWI_Q2Z zPa(R3R8`kf7Z2f-w$}T?C}o%*?%=`T9IFMBU~?H{7a4w-W9&KW1VKRdMv2$dQd{mr z7DeX)So6kNVSSzj1e=*UEDP~4SSy;mXirAE)O%@)5X1!6gYx-d`>cRBRt4WZ>snE2!bf0 zgd1qBk5Lw|Z7pqel8%di;9oBfqPs#I`VmZzDSoMmN$%~#4M7@J?E zpqiLghK0#NI&T~J*Y|`VIdFz**x6En-|aw@y~JC0ap3R_vxz$lP51D-|MY(`fAR>e zbumJ2i^A$0{SO|}-9JqdA2r+da_012;!)q@ivRq44-dMA=$p>s@K@q;2_(k)=v@c3X~r6 zoX+gXEQ!31Wfoam8mITZht;sh=3N0C{wiu}s;DWqc{fzmz`iplIn=jE|KcLIzxW-= znNjxbZlNORz{;&KHQdL&yS>b;L8M_jC(jSdc(R+{{og6( zP8_DSE=JI4l26Xi_n?ce{ux$9KaJb>bMoYFDg&O!$(m@}VcPdEu(X_`dv2WDU;Yb; z>D}zz(M(N60NE^(TAXIMx0kNI2^O;!k%k?#pE}Et8Yf$1jKUKzN*Pj?*?pNJ08NV$cU1U)&qyxKb<6T zYly*{7bvCX8QHs?=Bf~inPYx@fUXC93``^t0<|1IaftTa^^bWMK=y=)?l{i*qZ4Ra zFC)`kT>3+r<=I2*-BwB1Ws+H*qW9iC?hh@Hv3xWgIL^WSJE;jewq8>GJ)Xc8+;Z>n z9$Nr{faETty6q^ZRtuQY1BPakOg#LS`F`2Xmaa?J82G7fZDa58k2t<9M%44<;AhL! z(TW8!*)*~gq@ZrBl>e#10;|Yu|6RVmc$@y^!sGv#x=KEsCa0O0#vDC2FEZKVdMsZd zd1KV<{*ap57*0h*z_Qz3iv_Zo99FJKL4PwBP;r&fcJMd_%|gD_!_?{uLw7GR)qNdB zwyWCh%D^IpqJh7vndaSxIrq_FY68xmxQv8JF|$bjt#7z+cZg)+yE^16{KRPdUStG`1e(%()XBXsf`rWe26|iq=OE zBoAe^+d1=#kI@|0=^9^Vb*h`o3&Y%StS3t>TlS$;ETJo5np(DV=+s&EHpJGeD+L6_ zPi50SPMynwqm%BjMb@VKxV|*X9YsVE)++-`Dw-h>t!bjA{S4>M?4zkFutf()S!9;x zS(slUr5ad9f|2`ISsHS@Fo`5c4$AlalK=H{A0eMTK+7_9)Ix!DCW}MPQPhp^&43Y5 z0=2a6KgK8NBH!K}Vm>ub&&?HvJM8y~VQ6Toj_EF=b=zK!oj%FlhVX_;O9_XslAT9S zkk?G)JAI5VrkUxz#qwz9y0pW3<#I_w7kpH2t7p&AGn_rrN=4B1BbCK?8CYn=0xQ!q zEUacI8YbG}1P`w!8N2u5fV-n?8wXE+OiNt^MG&wo3q#jzeoAM_7D}kv#v5u-%q1AO zb(xDDqb%m1|TfLhP&i{;xhzHprf@xyuC9>HZnW9F%plzsH1kfpD7U;b6M{W); zkt%*yHm2s%q|-$#9TvwQa$$7@=Y~!Sf9*le|LkL`%6%vT$gVK4hIW4QcdNKBJz!uu z$xQ!U7Dpc^pXv<9i#4`IHUv5*pdnY3^M31NX+0PjYi6O(s*q zGBl6jad&ML7u@{r4azQV)B4K|;lQ%tXsD(aZl z3WJ^BvM_S@vCStsgM?bo6RQZ}bt_1sgyOGe$ARNy^E%?~ekNBId3fyt{fdkz+A<4j zNyBu8*|vQb$IhK+e?x@8WBEFh)wx*~my)ch8diFV!Mhik>s4OJ@scNsf9L1aSNZX5 zp?L~m@6p7}9E-^`dEG!ZZqBb6~lL1&5nnod?C!NmW&lgdj za869r{0bxYuJF~Z0p_#XIrh4x% zKm6cH-qqbyZEL3e#2Jq5s(Ye4?5BxGyt`=gu90H=;Z+hN|37>0)f`8X_WS*+yQ{rL z!+S@7BmjC(jyJpe?(Q4s99<}MtI)MRfbMVH++}K!r)Wgbp{D_ ze?xUm;6Qh6i2g=;F5e_y)UXW9vYFgr{N8uWJkebRNm9XGNq2iMcfS6DbIn0K_NODC z)m2N+^*hMA1>wOITge=okA~P?n!skWAQ(EDs-nmWs?|%==?*U4yu+Ovr|{W0f#+Ho zD5VmKt!;KwS&Ev5w715@y*R7Guh(6BWhduud`U|~uxuL{2D+k9%;(8ua`+1+q!)Bo z%Eee1_y>O*T41lBKFqyUS6ofkHktqdg1fuByN2NI?(W`r1Hs)bxCJM;HxQiQfyUk4 z-PwJ=V|-`N57>3sOL|nz(zz~~Hq>NETA5Nw^iaWlI>`6L2TFMjst7KKyrhrT)#glm ztJ|&>bT0rw^*8EMEs$QB1Cl;xf9a(=sVPG6hDaj1-*Jj`&5O$qB3cLPNSvPQu>{_6 zQ^ydyS|m;EqJUA~b4$?meInW*Sv1+rieFVXM6IHKdY|IuR<}nQq7?$7kC52deZB?{ z#+Makb`u(-mpho40h7a;nLShRqZ@(-&uLV^-{pt#eW&iG!D~{@8}BKd1HlmGm7U@u zir5L#fdc_MC%(eYf@7C0)KEHae{aKDB_;p|+vpJwg3tBS0k0$i3NLxY%O-8ETKDDd zhc2B;D%LG6A{xcN1tn`FA~;~>5ba1aFw=# z+{5Fm7$-@1QEx&%lHzqsSC5Rg)%Ha@090Y?4jX5P&arFW>V-*aZirfiNR2lblG)BYo?KgXfe9QT@iYj`aOZlU4Jg(cDo~t*b?Kx=hBIK?~S()=s z+vu`qtOiZouS0k(^s)tI4|`h2+_fCxm5GXbsXmcmFi~ePvUNdvo?Hc$j(<&k^t&m{??Lp)a22f8}z7Oa_+#!Q9yI1(8VF6xZT z#A|^605ml?mEt5swA_yKf&)F#D+k5j`SD0SqJZyr3nS+k$<=8gFJZ&ay91=~D!LVz zx9#~+eS+T>ROBTQ!l0gBZ@xxKBqSu3y>3j|l9P2r%S3xZB}59i4Cy&|LkBS2x~+hB zF?^o5GxQuTb@E9_VQlNoT-&~e1=}P;|5mb^ zr@F-DRljTHO)JGj_8ZGD+-;a3^2~6sPn>QGtoXfPArRn9N7Xh&)yykR8g}*^P2vz# z0$Fnq%}i{T#e9tZS;as?3@nVQvP&FB&Spue&2YtMd>3CO2fU_(}b z@E;TB1Gtx%HL38=U3|tmKX?GhlF6g~6tyA?-IA>t|HR7Ju%h}neKH*GDN3vzL_SSp z7d?$@c3)|#Y;X*YzarS{yF$DIJ52g9;lZ=BlSg?*&%Pkr3V&DL>@V5<(rqOf${%P& z753?wnP1WuicYCHcje`LkN_PO4o-y?XIR!#d3ykD!e-Nr>B-^8K{hs&nOt8;Tw@!s z{qfeYs~OUZVylIVg@dtU`sL}c22>0mg;|eTrVh^$1tO4JKPo0G)V|(D5wn{3^}-IC z4R6&JzYIB}g~V|wD{!_piS6RA-Dz`!{R=?WO59+ydo$4n>3x%RYy^y!l`GI-fBuKN z!fVdCTnWXDeGMiS^c8K8u;m(ZggD+hn#e&6{SlIeX3@`&r*_XvOLs@b0adkscLyH4 ztAKDqV;}g1G!HLZ^M{J_j?UQ@Znt9x(ylJ+Lnmjl-GD6xgqRQ&e_ZYEOH3ylOHZr3 zl4f|pEB}UeiVlYMOgNlk}WCJ`;G0@hqn{v9s z$8bvvJ)$czEqRJ%@7=!uVj_8UB<0=V%KZHJ7giM2JuaVa(oxPSb%;Z=eB1Bh5?uPZ z!0PTy)zY$7(O6ucK`Zi#ezb)3CUI?pTsH9 zm#EX|3;2PdeRHAytWg-8w+(P2+2k3FDs&^|S>Zu0E{h4!t-~=>7mU&xohChp9h1w; z1idDS(b3VAsW(*S1*2c?&Dk-IghsbS>4Ohx@M?+}4p|Pac>%lQBuP41oerC~VHHRb zmmmjL2U;fSPY`-xrb0ZhFcgpo)9K}Wg4;> z$QDmws;)_wR!Y#|kf*bd6HDg6e6H%3mu!n3{ef8}*`s3F1dN@tfgP;d zyw+C3M%i{1iCfj$gNiytspteyF*otQg)%aJg)m;};TC~BJcG>41_bxLL6)ARG0>FJ<59k0Mt50*3q zjHzxe@%Jf8_{GjS$fAAKKGu@XvL{2cJ#deR7mOU}fvNfVfK#9>S(!R=IN2h>>_*pN zQOGpwICw9WV`~1JwyK;D#}QH{upZbFPi|7bIO=W1M)+6j8>?RutNwG9>EO})A zFD{jZIjYDDaqK6{YLwgkBo|qxd zUfl+jrV$a+Mx0*O!MGPC?X}2CBzEvAn^DHn@(XrQ{=%9Ajre{2`7vCFp9yZaffs7X z_W)5zq4c5xT^CI*6+3@&cWSDt zu8I4{-v2bC`T}&lHU_$HNe^r0)YjQ4_tZ}ZlYb#1pcsGIa-qgvFYBlpm7J*;#>jl- zq(?-(VZsfHma7yOoij8{qu+1*1=dAKAodIXp$OQ%_Wla<>TPhp09Qpophm8Je(~hy z5@Ypaj={{U=;g_BKl;YJt;tKn-6HzIdvuAhBB{}Ca z%|&?14icLWZVnaX&J}Y3XeE|XNprLRRj!jDmlghJ5ph$n{t@-R%7}FQe+QNSRi6H` z=YFR7pM{jaWrw9FBDCgY*Iid_1SY&D<750EJr1HpV?`a+mkB5FKbt)28P1_EodX<6gaZ+apBij>1 ztcsNY!gG#2LgIsv|Jd0@5`G=f%aw$Prs(G6)2h*RuT8|!e)t~HRmutBNNbG`ZY3ls zPz9SFDhH%fMcv(Tqg4-U(_w08N+we!kLF8P>M8=rQvA`)XZ;Sy@>&Ha2|c zW}WP%oSX2A#3;{`#=9xC5Ep=tl@B@ge2D81*rzgPId8qSqqXp4iutfxe&5>qt9H1p zjYGiy#mKBu5yt*1Y_`KyyFA4w{(h@{%-}!unff_c9@g;c@*rl7=vhAkV6MiBil!at{jOrKP3+*E*Z^j=P?qtCzR^ z$sedhnk)^xc4F$iJFejQ=^#PCb6d=vQr*hguwiIxA7re3ju{M|Iw)(XJdR?wsn>Dw z6M}*2C3yRf$YF=y59)Vkx=zCQM*7>^qP{yZfiqz}W$k}(E(nzEzDyk2iS zz$@5AAeS$9a))K8Hf#7O$bcoIy})f8BKu7SUn)Y(3F&v7j!g*&y6NaJpUc2eb9U$d zUjI#VA!kp7(?#zu-X)nd>(wtg@DZUvDufX|SY!(ZN|aYd&)NAGfgs`OmukMYs2H_t z-oE#~d;$*Z(WG$v|6*vDa`p`Tud+)y41oRlKMQboF&^}ZhK81;|J#Blg!rVY!DT4T z`$-I9R!tsF;W-^|uy|AwK@wk+7p>Zphy|BrI-0EW6a!f^Jqi1Zi;*da&URrGC-|a%HCCukuify-c zmqp_@5f4QlHLL$lntL2E^QcR;js;Z+C2C)FwWjM$uyehIP^xjZes>RorSZz6V~gnM z>~#A_IVer)b?TNO!ZQ+BjylY>K1HSl_8iGn#pMK9rRwSZ*ZvMgk^L-YKH8Qa)NBAQ zP5K89Nq;q37)ZB_o}i&vmV{`;_O0A|iA$?%TIjL_##pcC588=0t<=ZxRBMgdZ{$NP z(xOAD7|SceYY6eCY-V@-y3SMbWJm%rp9*q?of@b7F<-`IX(r)yTo^gf|L zkBzJpXOEftrW^4*EcZW6Y)PNh@aF4Iq|d$A-cFv6^|w@JhYXcPWMc@G_ufD_7{vKu zcV*C{(n*;;!e}p%A}0(J51di$iA&3&7-8x!j0Uyy9iHi^;gf;qA!>ntn`U2Sr`cc- zi@-4}rv6>OePr|hxKLo9bH665RJ zJH|(SL;pG@8>kM|ExPzZh1wGw9tud>i*u9L?m%oltGh*vF1SfXK2|)bV+M2BS zfv!R7il#))LcxT8pQy5nMKAj`QZ>Z<&#;5%!kPc|HJ@m=d3T_+KDvWpp%v5q4)W^$ z%ri5y3TfK^Roa}P?==ZlJL-QX_YWS%Bd9c>>H>|due6n z8=F#M&?eE7oj^gfTudyP?-U(#_}8Surh;~$*+jy6ygoj}ON_1#_49J$i-VgTPuZH?*0Wm#)K%w}>{ zl$WvCo9ka{qi2nc^*yiKG)Ze%nZdE)Um_NyEfq1D9nSzQyl5^aW1T&g@(+5H@5dJ3pz%I z){F$Sne=2;CXIrZkK!5&yx{e9DR=)bA`96MDIv6GhXjKTIloKrX=rek83Vs;Z{6xVvDP zAmLYUqP?)#R$yt3998Qx&dF_vZ&j9K^Vg!33hDu&+b3xVi~@ zs>F8&?H+N6!f}s*^H$#PzV!K4&VG;+7&1?>tJ;#=3O0l_7=&PVoMn4rQ&Q0al`sGL zBUlIm>XxRrjFOz!(KRyX#GuR^p{&^Z;+Y^SQc%6`rKWCC41)3(A}Yz zmr>$|g^es;My#O&CBxk0O+sDgyZ zGaV#qP-ATEhv=ahkmKC7sFU|#fvI0Tsl+MLC??mkQ+2f8`r(_Rmq5HywO&wIEW@vs zgk4HYT3<&($qHk`=aIAl^vnB!9bZEM8%~oF&%`DoG#j$rWHg?1qGG{bk-sP!gkLC2HeTnKYcVaQOqcu z0z4DNHdiVo&AyekLLNz?0pJk%M>MD?lzpwRaj+{j24eyv!QPLWZH~Xn)fnJ&%L8|8SS#B|1(;owd~|zqq&?>gtX}luMF= zaKp^sBdjFN(d>mkx&ehp&?xYW$HW-`(DYA(aLBPW;AgMQACCXdJR^)M@-Ge($eet9 zeUGOcNjk|2?@M7#pSF%^mX(b+XMQWUdz2zPB*iJ^0`0QfxBOn&G8kfx?d$j$u5y2G zHD(*apd5IM8gXR;-C`;VKR?3_|NNWN>0VauC71Z;s4>G3*bTW{^(0hKpiK;pCZ+WnU zkhk6UiiudW=0W4xD=vuTAkvYAgNN0rqz zt(bYhNs=B8EhInKaTr%-=VKe#JY=#@!lJH^o*W~uSv@bEc}W)xM9SO_2t9g#xlNd8 z>_oR@O(Hi|`-cP#gUACy3}jPqRA;n)hKzT}GJ5>V7qD$Oo!H=4t%&0Gu*KIXpM6R- zV{wg9iNX_s=}abJsYqEiWxSK3%mSWM33{QOY{3jIR8x@F#XBntv%3d7|J2gMA?*O(E2jw5h;zYMZ7Dv1sh@A%^d~=}U!AG? zJXy=oo4~{Acl%^K9_61X$JmT-XqUvktZ02Sg;HyViY2llv2`0@ zkAb%apuW@m=L!>95z^Bw?8@`sgIsB>7M8}a>b3SO?3{}q94J|dJ&=hNCmTRK!!946 zLMXxGOwuE^C|Q%Bqr+kq8nZX9;ox`rSUHa(%W zdq6TADl8tpv56yZoI~wik&)t57*FL}XJ_D{8$Y}W@TVVYcxKj$3GHu_M`cW#qk-!m>eFAW$P6Uihw)hqx<`MXSeIW#cU~oD*QB03^#;Jg4&(VX zjXHHi{$_~zQy=Djpl{?f1zEt7&7J*&t_sOXP!z9iT(hgK$_j_2dHMN(_?^a-aF=^J^w$l%`| zwqme+wbNO$!U0{X1{ZX7QRE6P!@|X_Pt8W>X#2S@a9f|LlitTu+Zr!mQTgL97h;v) z?xi}I+GU4#q1^2z`fBdm$gpkz*U-Nnwh(i7httxe)8^X|P2lx}4-i(GHM@|~x|m5x zXm{hoH@_l|D!44Vy9c=@w}xW(O(k5Dm_Ogd+%q<)*R>QP&L5TGp`APiA|_%%?Kb(+ z9LEf}GdgHgo&@Xd3_q22R8`3=;Z-FJ9g;$fydCm>dy_0pe^aV1dH619+JANJ?8f%a z5{vBmumulx&px%nirwVzJIl>Es@d5SFOYJx4~l|&crvy9P#MH#Ts~5@e>__d=KHcU z(R`HAr!q3kn@PyHA`x?f?zscupI3B(*J-u^FYuaL;91vj#Ee>(muKC|)p_39m0sRV zqSLZKlh~*w53?nV`z)c}eVpg#EMwL6hVyjCq5xQFk}Df}xpkMB)q{ervXuE}1S7#? zd}_~hDSThPfxovHgh_la?HI{LArs+aXT=SrLHA())yG{P+z!I8d?GMwZyx`b01Lo@ zHk_<$32Yshnpv_8&|_ftH(a&uwcM#7hPsct-k1tlvtG>VM5e313;+*C_6 z{%sg#-R}Q~ef_ecfQs}_v{_7u_NKB}4atza{VK9I@U_SILa8Bh-ZiZ9sAE=MvnQ+o zN0!!eX*H6Aw@I2JvxE%aySqc8S)Ole+5$Fgm!|4Q9qA60oug|~sq)9O_sNx@nDhd6 zG&S}b8=C)IQwulPV8`!BAD4;8AxKN$IAqaS2DhM!+AWGX-KrGtkkrDArO&8CCr=Xy zuT+;|a)|IUEon6*jZZ*e4RlQ~D2%*PT1k*1$2UFi^?E%B^!wXa6I$F5ub%NzUWK%Y z^#!R!f~R?S{}|x}EPg7nLlpz{vBj%xQ*liuLZ1+nx@75iP5yCzK)LJt2@EsMrFe{ zJ#X}r5_*$a_~Rss{xmX;xu1lmy3HiohEYvfA0r9-U6wYiXN%P$H6(LFQy%doP;-3P5q;3ah6+Y6eyz7JG$9KcXW zK5QclIn2N=VImGbrr7UvsPRw>&Ugdj6z6}-BzwI#k@+q+>aU2}=J;zEolG7-6O2~%f z8H;86fqrbAY(iz}=@G(Vl)E!ex|SpYJZqFkRzQP{g$lxuW=A!*eq5qhHy+`K)g z9{~v<%CTP-NtNNSz8#ETea;Hf7ZWZpmXUu`0k)lhCrpCnYd*u}Kcg#mK4*-mB~XBSzlRR~!U-eX2#xTp6Wk z3z_w}b?N4a>@TIY@uvjGbRWzGs|r+1ih{pldv^+ zC+uIUuefEcAEPN{2dT+q4A=c-*r^x3Pv++WWdycQN9#j0n4B5Hs08iZW08Bc6YS*CZ=DH45;KKxWaM#%u`;pE?A*h{Nmx@;x&L1))vWz~`W(K|=%_Ud`s; z2B*k79(w42Of#qazsCYegY*hnw1N&2+VZ=_3Er1)UO+GBthm%* zMjc6eW!$vSygY@SlrHujxodmUrxFh```k?1)&>r&(%U3o#8Z+u1jiNQ**W<7{uX<9 z-pk|RMf_U{A$Gme9Eu3X$0ItJz9w1vj{f!=833&*SI;ln+Yh(HBn_sk?9B#cB%n6` zv~n-azxeZ#bAEXPs#0uQ|K_y^%sDHOhHNW2A#qrC!qN2i-=s@*ECQNk?=3-R+gQcqz6k|m zd%x|!(OR+r!e+109zO1cH&9vXwJ|Cj4tL!Y;q$@aHM_FsPW9dOeKHiXl{URJ0h1-_ zY2HTdep9<`|M$s3G{lr{*UWw#Y2Dlck}Saab#koeWOP;xD#`jW7R^$!WSDOb^iJFw zv7Dz3*aUT;KyBP_*&-2{f#!B1=pnf}2>j>%(;V@_%|7?znvH}m2z;3hKpT&#MII@wSa4KZJ(lJz;l zwlmFmsz*P6n5xU-DnB{hyS}S3I6wQvvpZC@FMD3iDazmX76GpQEn>FW9WfeC(=DtW z*6;b9HX%GdZ^NYFgXJNBXlL3AR@;NIYa(&Qz`~64rG_N5h8`=1Aq%!9i-%?XJ(`u3 z+YH-?rxgv&LFx6gXuS2*+CR$%zcC2WZAvtd$lSxY-*{!BL@DfTPkNkYLp3ST77(Qd zjEV^SAbg0hS{l`@5b_98vdsQ_49ocBb%Q59(a_31+;st$xva3`c)B-K=GErj95HnK ziDf#t25W?dl1TyS>T~R9!T-YoOkI#(+W6%bf<$Mg=f3~DD4n4vT4kJCe`Z3xKxXSq z?a}f}&u*=CeRmL?m?O{O$u;xMXl|DsdXB(b{)?e&NJ$_lsoqR_A$tpZ$X_(3F7&uX zZayY^x<$ic+&$hLBiuBrwb>A&wQB9U)19!{&hsGq;}5*XN1k-o9*8RkN|+?^&{ zt;jyVF|}!c)UQ3&ZB^EAit-G91U*DlrU6xq~NdyhB z*c~6*Wu1k|K3^no)F(^8bGe?~JJ#e0O1eA3=c|94yl8CvZ-0#@zB6{pq|DASD`Brr z{W;<7@{W@WiGF0cm^|R|B_WpSG_g_BWy@3WdLK_--`1$T*HBxfVMSr}&)7yFo{4L1 zXmMo-A~BDeJ!f^!rt6c8jqZGzw70j{&!{`3JV^8nK%;x^YfbZEuFIqGJ-N+3Qn2B8 znR>Jhd=vd}cR7L^aw+mX0ikn9U2S7CyJVt3uY~#%yzd3^>IchgW@8G!PrE(O_2hnY z-WLc>GM}cxa{*jyG$~qnhP`j+7~>(p_;&98x4_k%_Z}pDNjODo)-7fybX|Sx-!6~7 zIeZXJ-$w@XhZp>;bra(ox94S#8l&^#s*-Sod}xSyP;?EaApdB>!;nrCE9bnZg1b7g zN17oFs^ct_UC`SZ{&`?vMg--JgGDvhok6ems)@U0$ep$ai}-M&y2CiqRl>yurw~X| z58m}&k5CVgl{P_D(Vr?dmb!A@WlFQq=xsmd_@HLY>v)H4N$W{7c|XcT`PLsRqG#=A z8XZySJDF==copgRfGa&#&n-In7Kp^rkUF5cG+t7r-R|~|Y3<9@5zgUM~G); zW0!V#&Gm3G2X=1>iZ6g3MxVEdRqL$I2z*H@%w$FiBqsJ}*1;T8V7=%Z%HvI(Ayl~E z*va>j{+WQ|qTT9JGZ@^--v9T0?ChG>OC{zPMa=5Q7J2^-x?GKbFRS6+a!DhAOKZn{ z39Shu%ps?_{p)|-r>kXn{F02@!-H%7*|kgY_Vr~*CD9Ee-n@{Q_onLJi9VeH1A;f)KFMvN4f zIe=S*JXJea@92A#vjrW018D5^^5D;<2{2Q5Nvy3n14Vf9_?lt5_2(vjxB}2WJqe3W0S&f2_jk9T+?;=S*-j$!FaU#=+xb6)5Qw+`Ah5Lr8g5i+gdT0oC zNjEmEEu6BenH8p*t!Dos$!E)QM9_zjQ;sl1L-8n6J06^0Mks?SZUv1+1X~teeSwQ% zyt1@+h{cvmIm8FOq7grJN%REC)Mp)2z3V zYux1{?on&)xu5u$BV+*?dfV~{?eJvTcutKWHY!4Gtado>*0%mpC`;9vfk&ES!lFmE z=s^(ZklS?z!YuM;DC!rZ_$CmwK!y5W zMMton&XLC*QpR%=zp~FKK3-D?RoV>vT51z4z`U*VKKIk3o$XpPKGef+)nb6i+58itJ+ zY+^FYtzxXMXx~ie$`@bTK#%~A4rtpZHir_yw$E8HhxDU#m5%hQd(^*&k zCFy(i#x%a?Rvk$vZE7_nALd_6y2e(*o@q7V2t*OYUdYJIq^1FGsY%kR zv7=fw2HpL8jK+>+i&BYc`P$yQzCv-1N->5a1rKN?2n1L854 zZxce(H>?7zf{wxrxva5?anCQ$oJIE(#5XgYXJq8w6CWVcnodMNc9EpZAyvVwuAq zwDA+VeYrPOu1{-}IfXiU;!jI&`W(C8_Yt1^HXg}wAm1=Qhv!h@>zZ6o!$v_pW>4Ns zkbd;so%=#f-DZ~V(;V9Ybua`aNNei;bd4YHqeQvq!azsl|0A@^TO6Va>AyLZVbNnX z*zx+)6;*$!-MtdiJ%nFSh+V{_5XULh9EahsycX6 zoBpyts6^@~S_*N3?OM*`EkM&Z16o99P6+kJyRSa)(h#p>HGcSH*8e@p{hXC*F4{3P zE|t^iQ1Wz*-2Hggy2`H~_Qnt05I3p*o38|^!Xi9#O|gZCcWErAn0-^IeezSY1bg%3 zze@^xL0gA3;T+Htci`)rhu!Kt?PqS-v!-TVlMKXP7~}e|E&cw6x6Pv%SKH#p_BxN? zb@m?{YEb{{A|0i=eJW6s>*)-OcRrHH4sJxYw?~D8iUQJB4vBOKFnTPP*@17A8G`nC z3u~oP1a{Cie(3j7Eiz6_b=@9GZ|-Nc{Fo3I5z8h0TnleN=Fj8en;FIKw|jz;>5qs% z!{)WFu;q}}ze(ANRghL?)N2Rq@faJ~TRegIKz=U~?yzL!V|$;ZW7ZVwDued-_uV=M zv@Z*ZR%@^+m?l`+n(JbY;lZxwJb#|f%5of$L^x}>X6EN57QePj1P9Ie7sY^?2L6<+ z+l#7=Dls?q_6^`cr=Sl!E7hz&rLIdc3W}EMtSTh>?ac{1En=AWtB*TkfAz>aXk@+k z=dfYP*ZjA*tG~Jr&qghMcNs<$g}E^e=djHqq&Dz@nHR)ZhXALGjuaBU&tnIL!a%dI zG$~Ml&}mtzpJEIH#&=P`>yW6RQ)Qq(lzJ+_HRSySEmmjZ(dNp37CDcJZ~Z!5yyv;J zWMILf2jeX0h+E@c-@e`6ODOiOF2cs5LKW9h3@gY2Sk{R(I5To6JCm$MaxoZJ0` za+W0Tnr{X(v}HD?>PdYvIeSb3-QyrkkV&*7A&;!QZt(0AkuvxL9tr~EZ{25FsHv%I zL8s=xw)S(1F4@HnMnPYZ)zlb3z-<;n49b$p=j z3K(BK)^|~j^B`Y2-p0E|Ve1-;qV88dm_K&TytES@!m^Z-#&D7hMUGDd4?%#W$*fPF zCym74zo9|T^0v$@srL7W;raMv@ZXxP-*l;Uh zsCiWIiw2s29R9JeFrV}y#9tIQLOCNdZqo^1M=|vnhY99}wl>Li&9S3(<;S&LobNb! zvZ^#>@KEc|MozO2ZaaqEO%IW#hjf|#91!F`SlaxIz6N;DU)EQ1;ED7ViY(m5&UOdr zOf1SoMUQ<^~Y84hFZ-oLlz zZJRL^GjsY;j|o}^0A@8HE)HThFt)bm``dGjO_~{~)xcOX_{CGPtd-@X<8muA_e?eN z-shHJJ;xmzQx~!hae&c#4x@2k|3n_c?Epr-xKiGi>c=X*Hi&PMweiNbLrTQjQJ1)V z)!cqj$M1ys`>NOXDtC<+B$|aUBDbB&dKEI{nFTf;7?o8eCn-}$jy3PLa`IK#CT&S4 z+AELXN1U(p;v8w@Dc~)-$xr<~b{=X=%i_ZojKG^g$zy07t9ewP(sUNG4(O&F(8Q8p z{>{XlXXq=6pfq2I)KWqUJ^f)G88b7SW9#TgaGp**KZA`UYwOz4Uj{Yu$)T2DHIIRo z7sTRI+P~OT5DD1uW6w$BE;&EPLt1|@1+0yY-JXUta_(Iu2>YV8A}gQZqoYr>?Es-f<9~ zug&d+!g{&NMaKx(ja^lo6(3JySGk|LCaXe+^%qwYsekj=y`^FjJ$1@2Bt%c+$Vqwa zc9;4D--{dR2ZSFJ5CvZ^LPhY+_}O{##A%9L#sX%%ny46>E9^=8tb3+lzVY7os{F@S zGEtur(Fk%f9iqo$fy1|nz|9yzVXj9moMdrl)3IYby{O+KAR)XQQ|gnwSKN%F%Y&cm zF=+nMy&QkA^y$Per^dK3ahja`AY0mC;V$5v zPy{k*=C3&78$LR(0^aD7Hj4yJOGiYt;-Ua}Wlo+1Zv&pc7#lhc{&m7cPhhj=wZPJq z)B-r55PC)s$Lu+xwu$i5Rq!nZ#~!2nTb-SF8q2Wxjq++?P`@bN)YLpZr`ta;kD*3C zsdYO6SlFs4*qJ#nc)I6ZJ^%fEDVNqqCtId&`?uY;+0Fs*c}~$+uajzDOFDWRhBnsNurXInID0gP0dV4vH{O>*_yit?;rDncCzNEM;Sf~c+Vo-ubc(U?eADa!w&HJ)w!1N2MF zn}2aC3p@4O7%iYY@YMCYO$3G5V-2t!h`zrJ?cme??Z z9)}x141t^%d9x+4BgKXU*1i5`{pm%doqqm=NQ!^N85H^u{^_ub7lT?eO`~)zcg6m^ zn!ENUVq&aXmlNCys?spzxW$r1qY?}LB=(8xlH^En(MP5{n&NYGq6C`Bm0wbNXk=`p z`=rQ=!;SxT!U>}cL4AiI@HQeBuaGXv`;+dXmZg}z_{^pD#s0zvFh_<)9n8Vm;RJkT9;_74EHjB2&@(=`pHCpqh z--007Lkukz*;17vi)FsN2(nSS%J6f}OG1L=w&s*fwO^TC)*`gCzDUXmDjQm1fy9KY z^axp{h47p0>vm8dih(1Pf}H(*YRT1Qs<>69CH&!qe=5IH!c+KGCrcPIrw!pvA=rk) z<)>U6QEaEUL?gy3PjYmrP#I_|+I!K8waSR3l&LV8E}_)WlF4yYp7$ScvH>hlw7z$L z5=&JzXC@MQ&}Z=@X+yk)SfQi*0~L?5RQT;~%%Sf$MMk<6LTvBbV4mHV4VkobHVQ^%*_Kg3nIza+VMP+P3jDt7Tt`04&2-tQx`*UDUX$xJq z$3BF2V*}~`@Q}#7VD6t=iO09NKJIKJAIfc4k`o9p!XMYhSCIXvhTIj+6g=`UXiXSW zu08Gls$Pj2X5$oTZUeQ%>&SrJLwd2fTdSW4RIOwTvAG_~6Z<+~EBwg#{*dRc6aRw* z-t5pmA*pp#-${@plAxnz2i$UxFQ@Sqntgv0@llc-wkOov;Yna0=V4t~Sz!|$EW!V@ z?*xd8Cg_!bJNPI`Q(=;_WctD6P>`?q72SSy_|H43w2f^w8NogIqG;LJVn2JM1A5U_PVs zIJl3cR(-BqPPok03$YQBV=AC<8aRJuSn_%0)Pq;crCV8x8^g#-RX`lOPPD*R)YQiO zT;&&ak`_bUYN`PJExy_Pwo^(`nENTJry-& zBZO00$P=xM>3uWg9rVqTwk&Wh{4_yL6I~*OXR+}ZXT;hHpG2QbJNWsY=h%)hQC>H> z9ZC}1=V^cjQG=Ac!N&`ar;%TA1AdTPk>g(~k&#u9W868)NMWaIqYUXhQH`l5_++X5 z17PokYz_$qi?gIy*|JAP1(QUoV)LrZR|KGILI?7R`AeA7Wzse`NeE;Q-%~i#gzwbY z!Saz5u@uRWlo&))TZchJ%SW27V7_QB{PQ3c$w$qvDRd~9I5iZTHP={>l!-*>ptzPo z2oS}L&$O~~_)%rNVL?%*(tPrX7S%%ymyzRgS$W?y3nzXjxV)fJAdBKRr6+AcXdjGt zz-y5-N4}}2XJ#_?&`RC-I?Xq<#P4@puo6_NM!93oVnGY;F2pHCN1Gi`l@we2G!=Ug zhATyh*;nvYq9(E;`05D>7#?5qw-#t6rg14*X^SHNH@S%bYxRBP69oTT%-ke_jiswc zxpX`B?N%~UV{TfD*uu2*?|90vf~Te$W+i0-L_0yHG=T%LdR+PD_DRS`zK7Jgs98i| zfHmk~3yb3yj+M^e#YhoR?m2??Cw3BH-@liOd?}5x*DW#Ih!|CN1r@(z{QU&V<09C& ze8ymlsEt#PaYX9{2vNUkE-cutd9XuRxla^46v+hS1Zvakbk`@JQO08Asnq$2mZZsY z3K&X@YdpHh$n3=Wrtz){Mi+rm?bevP<2(+-{c@}vt#t!#Mgu) z1^R&;F-OsdLGYS)zX1S``l_nT=(_qlVs|kK9<$jdn8<|{@8H-<#uF-JLkLf^U4cY8 zQ3W7cSPcbc0bq0Qg`znc=6zK#!cjBR=?j^Uxopz?1n?)e5vt~@&YMwwlDt^z^ecJO9iE0T?r?qmZ;Yo|tbR(& z@!HgXl-#rPb86^nft~Ps#NQJ&fJp=bUYh^x+9NB&JCv-WBg6|;=o%3t2}J(n7u5F( z8>vnA%{6_Iz|#GmE+Mo4+!>Rc>xtxT5G>kMmy|%S&aeOCtCTd}r|tywNCNdEM$Uow zym!(3R<;$GUbzS_Ysf2Mw<@(frH$)A_BDdID;y)GZaVQ11$Z#fB0y&aUW4$0M|drs z?c!6ggH89x9BuSg6vnYKlf%s^MyaJaKS=`>c{Ixt0E5k4nmogO=8_hzs``B!*F>^ls|UPDDwTkLzPHVBo+ z#On(>w}ztlH()QVFE}}a!=Uk-lTY4N2~jCTy?`Uq0pkAh5E>LTER?THk;W-D4==%B zYj;u#Dhp{TwWA1#WA2U%_(Yog`2rp)8G|hA537Mt)o9scGLO^asHuJ>lv zZbm+*i+O5VJH#V3c~>4KkF4YI=~Uw>}bk=V*M{{?$}fH6PO{%K*@9kMW54G z1?R|L*nDRy;-I4~UAEWrQs{CVOTF0Z$+J)XL9;AR?%~7slf4%ojlpQCZ*4u~XeV|I0&CPw(*EHE@c1 zXm6+>pi6jWj^z9#L;bzne!PV1i_^XT7&{xkZ)0|G@;S0g%VbPI^Ker`d~^2^PbOwr zO6MsQEi9)z-p|IKF!*qgk*CM`_@g82Y^froZ_N=DL>X0+QD579=i%9T7UyS}oLI3x{ttirJ>7Gl+#RS&7(cSO zJf}n^wZPD$Y4RlpU!sn>>Pq5)4cZPtL{jvh_$|w8^XJw>z0utDTx>JL?DPziQ!6-< zpTtj`yPFL`R8V#0N9?7CYv)*)E$?Br;3HbqMrW;tZ-cE&f~5Y;wWF?#+TVpJd;K+eP9NODT%qTIv zO#;QQK#-7C3Hc4|ZaTTZ@Z%W@mWNT(NNsfm5o4ovS3**xcWQS%vxI4t&(DHeBsDuq z?{Y6Q(=*I0rZF8CK~nGqA|&dX>FVxgM|%U65&wp`^xqZU$nJVBj+JF@bziY1AMxro zI%-t(ZDw~}vqT}8WVv8s<3}=QdDQounV}ITm(t{mCYEhe4wpP-Y;=_2vE7_FbA}^( zT8R5)q%CcDKVXZyI`1(A5lI%2WbizPLM}&YZkq9IhS(!B1Y@VF!;yN~kd=ATXw`3|{)8M)|rb)?hadDX& zxyR+Hhd8+;$#kBQ?NIJc7f^MB(7+H6hjw%7sFF)I|vHF$`{euiV9b$PojU%cU#xZ&tqbS?d5%gS#{Ngi) zAKYi~c@oJNW#_3gv{nW&-Y604f>*8#DwP}rMMX6XbWvDmKM?>0RnzhL6a+7el}?hk z94yD7n9Gtcl(1ckg^3aRO3ztdklAtI7$;h)i5U`BZi#1u{oJ`f#?!&OEGcp{q5uFO z07*naRHuq~s!rhCZt7yjdl2Y!$<2-Mu>S#lPg3|oHMI5Yq$v^JkQn9%{BrPIi|pJ} z9^Svt&_o(F(n`m^{d9yR)DH%I8^NQLU0`DPK9}xKk+&qeyLQphQb%M%iMH(n*R@Db zk8r<#fWe6@TC9W4efw#DPv)-Y+T`Y+GkCwBq46YAsGiP)2Wg9F=-b|2dN}!MhI(&t z;o=}GwvB0-6!Te9=>ooZ1N+Y&;K-2!^t2`jsBglXzSU9I7F-_f<=(&;<4ZOb?H%ms z*+ErE-M0R-Yo?fg_K+)A`WczC==k_JM-J_#rP4qW-Vds__2E%W%`iTEkE?^T6l|IH zoqK3&t|hb$?XGKlZeQ^Dt4ba zMN?G>pJ+DB|n6?LP`T-(C79p03c&9f~m)1>Hn*j9mD zra-W%gX72As7r*R@ZW!b1pfx<-`-EScy@-d{$9Sj z*3YEnr|rmjPV8@^CgMYSBOXkVXng~TSP>DeIrKKcV^5BJbk7b9$_U>C{k?4+fkis+xe zrUOiGV1UX-e>1+)^IX^Kd*5vt(jgHl9}`xs*l?v~&7je$TP)2I>+a ze2R!`=GfiSPJQAVE?&OFgXvKo^xdYVwVr4|C%6`8_I811k(n9d#>GoqxH(Ev3e$1$ zBaZEFBN5WyOrz%meqp#ICkN=ge2I%UMo7yEy7wLB?4cHn?HZZ-yM%|CnPue8HNL*k z$LNwtY{zL%9N$AnU1ZxPbYBmLm5BkqyL6e$y<_C`YIg2F%GpEB@5kKr9MaQ6^sVk; zD`K4XJxBTYNGl;#+O~n?7vY#$7N?%lfBO#ej*H^~h#0XdDq>YMw6xG%pCDq$?}1{dD^3*>lCMt@1ngnjJyr)u3K8A336RZxeQs=M^pQ54!1W_ z6Az&ZCh6rlo{tPO^mu~jkM5EySmZ50DmCAsI>Bqs;CdEp`#Z;p^r5_Il8 z%K4)$1h<{t^>A#PQn7^NxOi@c*;$#cLnkSQY=i4 z(s=ti*KXZoc=j3huYW^pR}*_eo5iE{^xljEk`(e?kKI*!40+K`4eq)wAS-zbdJ%PQSM&9gkP~Z)YC#$)CW$H%+fUD zBM-TL^&!s|a>$B+x%wQNEhZybH3)>G1oSr$>is1l$Y{X|T6?t9iZ2i*9MIo@3)*CP za)`UvFZ1o?yF5+FH0(LZN9T^wQ|m($-!$x8uHy5)Hw{9WUhK!_w?me<|KMM*7FS^0lVm&gMw7RT;!^Xe5YfA^5df{(UCM>unGKke0lxAh7i z0DxECd(vt0<{BM|f`Dp72nGFX3qHSiC(oj=GR^Sa>s+{all#vz7!7;)^z%-A-4HWYkd8yg-|5`-T#G_FNjg_pXKgC0YjbUm>KE<=SS*hZ za_j0vE?vFP^R!CK!NZ(6b%-6cfge&bZevJVgzDxlj-7*)Wl=2T$)(dQCbJ}G#^}E( z;@UQc_U@n|ZfyG5#4!uxlFOt^E^BEv%c_q+IQ9m|ocfF4~*xNJRZe*yNH6Om#I=|J`?7?Hyuba+o_egY4M1ljBW(0vpsy_&M-g zi+p;8bgqcCmfe+Aj6nE}?e4-@Kew-6;oEBunJO5x9XiU{QwQm+_HRqO>#d$Wyw&$p zV=eUTJHpZZJE%1NMrW@141$pm=E@|qi)j`f&GBUH8P8{S(UI_dDAw7+_>c^ErzndH zW>=P2T+ZVK8)&aK&=g^NX7}G42#A7E7WVW!JlDf}t@^u%hgarm7J$`Y&zp{+s3&OX zKEZEeyYN(laJ+_^ir}i?ZW*fTBM^-fiyB~MS-Q~A%*qhA?>(btcbK;yg?0gx@dwwr z`*@1Q{L4G0fTS37o%n)%ZI#3Wo9D!MjzwW*g8myfxIH+H6=~+gsWTkkRY^elK2`H( zkb`yf95}%2!ZOJlBRqR}lg!FI6Qdo}#RG_Tt}M1XHbGhp5{$TtLevWpB||BAuc99i=vhg6UVRkyMG&?$D-8yn^){5cR6KjE5gKKi19yyc*WtEfs; z5DRKAjDm({gospDVu&U3`77KQoMY_qC?h@H>~0943fseNa9xw7smJu+zQfqEiSyEF zPf~nTwjJQ${@pakH&-Cbv(hX)d%%T1{)zv*HG{vthr=gMa_ZioRjnl%sG%rO0^kG_F1=5jBq*a>KX7|pwmb97e|k#!GQ4vv{+_Q@c< z*RF8syFtd&GA(F)b^6!@SlhuFqzE2jv{wmk?aKE2RqJ$s_uZY`* z5_Pof+(%Pb=H)b#AZWxJT50d;pyu)jQ@Io~Q!``>?Ra5rll%)0+sZNd;3|D1b1ddx z9TU|bq3Pfk9O(!V_pjrQdM;LBg~`zY`mSB!!u3ZiI04!Yp5&vC&vI&aHJZ3FJOB3# z$I9{i;Z5!jPcXmcI*HS<{}lUo)Dc~8op?5-+zN9~hq(65e{t>J1Phj*jw2`ef+Q4tVCg+%934)5!tHQ`(TPEL`PnWqf&UgPrR zUIwR2gqn77An6sf>^VuiX&;ttQpl%CEzL3Z=ppy}A2EFE5>F=<$XRgySU2@i-zHY( zy5v%`3}5?}zUd<7E0sF}!9**&j(yDDdTmYd=kjeVvMV!;KIrB8SbinCEUD^lb`&W&rY@z_bIRV zb=w6}u!%iK4QjiKhG!Tl#sR$|9g$(H%Pg$NG;o9wSb|%^| zw9TVHw#_WhAKv2L(DOB88(OfUYFI>O-oY|6}&Lbx|fBrNF zyKC`nQ>vUFmbpn(wsg|c+(f1E%E<#!@>Ac{Ma$h021n;voSS2IZVA&#ymigO5BTYL zUp#_s3(v`uTv;Jm5D3-R5Lbl{%G>W4f}kMD3W_3@MPM8g%YC)#_iylU9S762@jL-h zR*+@+jcFtVElfpSn2Nd|`%8sTRU@rCI%(=3VJ4ep_W3x;=GIMemnSdPT) z;Yk*z2KjcZAKMd9)N<8itg3;7r}m-E5A$$&foUW(-G?k~hWqMZ=9U@0b(OCkF1`|E z6GVyXuH*O`57AL$peyU#=50VyF`~6}MQeZL4+SJ8NMlbA9S_DB8kr}#FwflF0(rNE z?ZRZ@xfaQ(G45Qx#Isw;>!8c33atVjr=h^p#TCSs`4 z+TkHVG0-Em)W>wjawdgznryL%<%0B<$J8-%Opgq3<(uyqUMRf$WCSW2IHI<&tD}*~ zS{L2ivl+SLwvo zKI@e=NNmf&6GcSbhbjojf`BBg3Y;V24+g2IjIMiN6!i$fNF~)_m8pzLK9weK+BkS` zIWhA+JX|Zs^us$`x-`U-}#NZvSTzJ6a#h2F!1S*;+gm=)SeBsEWfh%h_cF#d?k&o zZR;chR>je$M!0kJGGBeu%UDvRwrd}!KK_JXo$4a0%kNc^&2ue^>3N(Q6 zbBLi@b{#**r{_1MHYs;1xHAj%rur5c)B+i0#>^9FcUp83gPZe93>Z!Y)qG%eDy z`zR;QeavSkI|!@Nwzj*XuY&rv3hH0`R|2A>lW6H+M|T_j15*rVvy6{CAzf-9;cZ?A zt8Hc(AH2t*!`)+vy1Eee@M#)t25<;y>F;r=YPzlxq?XZZA! zGwf@RZ)=}O6hvgXT$BVNk!X})z*u{Z3Lo+$ z;9bIVaf@j(=^Q3LYAeG?8>lG%fVTueMN@tFbs536u?htWtHP&i`zJQGohO+#aXpZA zKR#9EZ4_h+vOypeqbjT;kjBm=DViqgFaJ|(Kq6YxL`RQ+KW)DJWXP(Yy14HL9Sv_A zo>L+-KSuA(2RwSdjN05xB%qL+807xciv!?*JI~Z|mV)DA=9A2gKVr~`5)OrkBxjBuG1wlmd#fU|N1Pz(xVu4~lPr>zw zyz6IsLkNO|5vioHqmxvy@XEnJ*8J2rR1!9RoEqkrg-dFFmdPjMELs9;tbv_78>x&N zYqo02Mv&^Zb{Z3djLxKa`uGWRM|WU17$~ZOVdzMrh$F1h*R1z0f`lOI7(NL}EbFIO zw!>x+nTe7{I8jG?R~K5%tM-&m=oo$tO_T7_CZ$}Kf>WlETO-s8o<*rtBv-IN6j35k3|U4IC3K&L zrm2X6i14GwMFmCC@aZx_#>278BK7MhA%1y?l18MqiH>f8K<3pk(SmWB;wrlQ>a6q} zlR|oqCl7A&UteBkU_6Z%ZRX^u^PD@ekM718+fZBYokNsVqBV`QcU$PGwbn@$brk`$ zwbqGal3ku)uGcWBu z0)nK_&`?3hw`PP9yOd^T^d6VKy1^O3mGasGiaCZX{?LA8bI3}5;afbSC zaN)uYZjUVCukPUB>5n;gVn3brk$0L1fYr5G-9USH9<}D>itFH{L+3o4MHu;rF zhVR|v(%09x@pu6x*2vLQA942NL3TC8QU7k%rhuqdvg6=>c8yFhKJ}2<$w|h?=P2x` z*u-RjfTD*;w6wF+t)ghZnhc0GG*KCpS*zjDwQ?-ajB)SUCBD7V&+{ZycJAlM$G_&| zgDq5reA_k=0N`Y2crtj8%Qv2oQxeowgb`AcJRY2XVV-*6rFk+wPr78|IFO!u!sDS5 z>6o8Dw2I1j1Y@&0palsdnxLtD2RVQC)s8Glp{YJjP+ucx>^a!QG}9w@xcJpYuHSpk ziWg?*i6eY;?lcFw>If;@I}xxU2qJc+OM#qBZwk_XceJN)0auoua_`%<4!{=ar6k#s zi90jO%`X=jx};K3-^roh{C9qLpbA|E1PNL56R+#wK%|zggC$C)jkmffs+xgeXo%?n zGMNlX%R~1CNK{2oSF`_bciWTjMQSW@Jua@3M5G0-Ij)VLv(ave>RZdtzl+cVY;qc~C1c6H-pCgsbV+$gN9w8jm z(bh@S34)BO1qu38WYHs+Tp?R1Vj`gXd;}vQbV(p>TV&EX9LI$<(+VDVHn#2Jc>;nY zBa6}|a779zz6k9{KBlt!7^OArlO!wnf>9#IOHbpP%gb`5*rfJ#=)b5Cqgfgh=qE=6uhlm|kFV%*-=6e3!p`d6E9H1?)gQ2M-?Q^vT2QsE-r&tM8TF#Va!^yf&sG zlxdmEI?-i~t<8miqDSdD@hj@~oLN(Etn3p-3BPo9@SGx<#R>YqyTYZbcX>QpB-*@( z)1Q3A!QGv-RE5#y?MV&vA|zGA2nF#g5+Ww~e4b*-#6w+kPw{YY92eL15F`mnlHM<> z!S@g!k^%1&9=7d*q!9>)2>Q0a(Re=~;tz$1SH{qUrxdbF%r50IZ5MqF{t~y8C7YaM zGFikyCQ?yBIOu;v5oiyqn5R(4Qz&@|ibg0DSl4m)TobdDCtI+<6OnX3s=QgtSRxRw zCJ_JezuZg+qJ$O*5UYrmMVs9c`P{3N6yRXl4zB0nx(-$;Pu{aB6iZmnY9QKkacmpg zaqt8QUocJ}@^Yxn!*fb3%+4}5zf8tes0dclP#Z+s6iz?^N%0Y>YS>~G^yNzMVm?Q{ zSi*E90-+#&Lql528T33{D^I>qq-45?J`GLRwpF#SAc$yz2$g}YH4*@>_Up^(SE-E)3;oEFohdx=D_jOe0u&UtyK{WRoX;O^-X|h zlTS`D)OVGyzPZJdWsi85ETN^1cB%VF7j+jnK_=^zs@(`++cXl z#8=(JXMgxLM|xVQjvA<2-;4FuMCKS31!s^8|h zF0SLShUDv8L^;?WsczbUukL|slbs*o=A{c67y@D+-drj zAPC5sPADG3S=CT174vKSp@&(ra8~vE9J4?%?;y$rN~W`>F!S4cW)VFQMc>dOEz=!N zkKE&{KYqjYhtmkrR*s(en2$~!pshNBE^l`C@Y{lmnahwXmN0FQRfAB-_$!6(58>fC zMGD0{`GSKWN~nP#x+HF@*sLi1G@q!Ln&I)Ct9*Om7LOM!!cBYl^tYdJq`QgAu2#Rm39xHw?L$Ob=Y-`sFKJf98`}l3qX8nMtgXhe0>Hqq7uJ=77U$c|r=fB`wPn1w7KqwkV zlLcHW%i`=bGqa0WYMk1}W~w9FOI6)2uAO9T_$lM#OITWnSZxO#RT|o6^7C&wxMY@| zbNAc-;x9KJv**z)ieyh zir_ie`6X5|X1Swht?%pESfw=SY!S=$kOKjHnu;b0h69ryR#jGBMo8U;g7;?oZqJ8}{oAgukcYS(jJ@=?$PIRF4407*naR15RWj8C#q zaL{5gcJFP(@TrKRha9Y?wz`r;P~q{?9Fva*nJ#wIpbNa*^xGG!vhd_*fN z@N4R(9Nn= zE&sld_l%6MonL+NJ3c+VhnBd%+&T1~ z!84b5^57O<{>K#t7on!-IA8qZuQ{=^;k}r$+?^j*Ryh zqOX$b`gXeO?s9!{iSdEk+&$RFsm>}wFYy03#U&=54AJ*soV+dItKUm!Q-X@%-=bum zZBi=aNasxuWmF@GUsqQtB4l*M!!eVLKbv8xq*B@3LL%5rT}1ldC{5YDu7GKKD4K!KFz~5mQBy?}Q7AAyHO)+Rfg86P zsHv&qNPFz13IZ1^H^cqg{R}^uBkyXo*Voe6kU$o;vRA)#;5im%F-Im>rZ7{DAby{| zTFEXDibkofiK7b>ScPc@2gd2DjuCr7K=^xD`3!TTBTOu%C?Qhc*gz~2Mim4Qe8dv9 zw6#@pe{z)6%zeJPxR1nd_R(7PLS=|sWNGFZH^1#;CT}5zYiMe&As#ihsC6=#fAWyq zm#%PkB9FgeH)nr+p2It8i5l{T5&@oFB%jNZD_S7R_yQpeP5x^VQ4TfI)>2PP%`c1gLN5;&7`UpHimVlGHFQ?Ts`y#Tk3B zz|507e0}u*e>hQ3WkCH~)xVo%e0Z4tJ0mPRA{F5ZTAHf~7}^#c3jhz#EiylHpWYjN z+@H)5sNTsJ|LwON+)+(a@8hwwZ$Vye5`R(VN zJ+_O+=mrx3j)hgqk;<94h^V?Bzp)i*OG-=*_Hyg$4Ia#th;-K%7P39!`C7hQruq|Uy$mW7@7=La+?0$ zep(x9NbIYBsmsp8b90P89AMaGM-gvIdGKE zeshMd`VA%mJQur^BbP5yv^-?hhv7HysavP$P|*B@DhvYg*Tp_OaF@wW3=&Wz#FC5= ztD&K>iTb#XAPPUqVg7F6kX@eS{`G704bPBMs`=;-UvTC~5A~4^CITD_vy>&BwQz;9 z-3=Hz@|Ll?0-z93ZE~qao;}HumHgDTHW5D1NX&SF3fptBi%CWwJmB8FF_!W!fvQUO z>~ACB(-0B1aO}9m^rJi6x_X`dnG%t<1DyTzEC)Jj%khLazRzlGBbO&%v_X_Hf)RXM z%I*S!N+6VA_r4}BJenq(ddh?T2eh`-b7p4(`LFBG!6_{<*f+rF_#y?*prfIdhPoKC zDBx|~0sXtjhh)G9e83tIWrNCw4)z`1$f8TBH4Np^)LR5Er#POYVR5*)Fyt_~J z8aNa)DKgnS1?&4=z$LRV$4a`0<9fJGk<{`$Q{xk)S9efBl2P;^@u(j~6!9F3!rU-7 zZ``7HcnM#ko$h0w^4ady##=!|{89hb14O=;_bux#NJyfzD*9W7sFafoc5a!`@!Pm~ z*o7nP?`k3z5Gke?nH(MD&dpogemsX2sH1E5A&%{<#ixi{RQRdP#@+@W zQ0B_4?btzA?J()l1;*}O;Y*>&^1)rS)~|{gIt9`TlMD~s9*$ik zv$#ag_Hf+q>3eKum(%1*E}m;s$|sqdof4)9U zs^HRg?01|x&`DE;1_&4xbu{hhW>5VS?o6i{y73iXi#hU#cG6rMBcRK8R-Vk#G>;$L z=GvtJ##e0AXe)>Iwb57=Tn#SE_+xc+?%qw$lLc;$F7x2xzw;m7GKco=ptUB9?B-aQ z7@@!S7T5YFDTx{_oqO2TQBOr+YqrZ+sYyl#?(yB-adKjirus(eqAJ;?84AnmUnhtn zvK}HDGSJns3uP`np})76i+3jw{c(1m`$vv-RuB)Yx>$0EmR-BqKQYDVS3^ucy2aOD zLS|t%UCq@Psz-i#nrDyh^WF76M&?XH_3i9Gx}TPixLWluAW1rvZ9Cb$=Q&TN(u^!T z<@%rgZ=~!o_IEc?71p7YWNK`Hn^(&MuTm&MOV2)bHpdBU;a*+OwJ9Yh80zn*e`uP# zXwcf;MN?d&kep{Kwf?n&q@d~nqGA7ExtEIzWAyjlby539g;|1hkExSMZCr-8p@ax}y2ZwwrNj6t_L2T0{ zJvUD>TPjohIR%o-^GuFUkov37@c*;-UQKc=S)Si7WNJ}bYXww6Yg~oCx5du%^z`hE zE!T{+p)GA~`N|JKegl33KGBRcKCF>TVaA>2bWh(4t$`|_w8+vTOJruH&d_|wLZN_$ zsDfw|(D5_74>wQ|;Ti7!_jCLlcUMrnLF%e}WD^PUMIB?$n6b8zBwMlo8>5tAYkiI7 zfVF$BlPG)ehr)zB4!P}Z3c9tU%>Wu3$s9$)!m)J<*(B?$%XkXq!`KBuMDq9vheHIs zhxgnsyR^-EY>4}hXNc!)!Yw^?HHJ}2Db`nCUy*_!BB|xy7u-pTFbhdG#;)f#cbXHVbs1qp`(cohjfHOtdSLp&OdWB8)f@3h@~ za-F5r>%Y~@ZTGNZY%ef2^pyKgmMO}9I$AoY3o8^->ny*iZ;BG4Cqhky4^@`HvCy|> zcyRXt_r~Jjujcp<|CXe%|CsUR3{J3~uAUyc+bR!reL6;-%-RIkZ#-pk zIgM1+M{{d4RZ5Z6#tLt!(%o?-67(Vp0*2E zB(oHC8^<=#a!J;fme3{2{+A#is6nEU00FOxAPTQO^Wphd0Z~E}#ofIo1wllVWF+aZ z??mokm6F6~o^XFK#(Lf++S*H3LkPK)Vr}Iuy6f>1*%?;=%tC_r$Tj}Y8*`Mz5FIDK z;mU=6>Lbr=Y#UQ6l1Zf~zM#808>u`cqg*G&T$1?8GE&aBTPLz7NHFL@wl#8@JSFS7 z?rPZ$QkfElY2#2No!Ve!F+_eRup~$_9$$z^$d5;nsp&mNcl$iCDg?hHaO1H?hI;(h})sePoaB=C_k&o5*@T4sXO0XDyG<)ALGuQN63*DoW_eB?`huscQx8d=dlZX zv$(raWF^)_P1KJf*y#BroADKv*S07K5gK|<^4(v3M}JcYGoJVaU+8T( zfJQv_l*f-JSj_0V*Y!f0`0NG+-Nts-n0#~#ZDZoOWA2Sm-F}i^Ul}0m6Uy71WH*_g z7~#(CMFJfrYS(ukrPPwAiq3&!oL-5uachE=$w7Y1Y_Tw2PsA^x=eAj2S!RA|i;`SL z-&(wDvz4{*)wFZst8Y1fypy`%v&j@2t+2(!!#j-5u9MdGI-je| zCrTJ5Bv+@n{f81$A@5F*M?{UbFmUP|=lbjLDTi%{Gbm*@7{2tKbJ3_9i61WZ(oz#ZK)@;_Se_c? z#*J~*iU#~ge#Oa-y&L7rR5bN+>_UpgwG0oY)|q^Ci`4o8V~y4LWrt#VgSF*Vmf~5| zns!c{zre+lZFt2!Ax2R`jW%=S^f}fyQWWlvvl4sEbuGoxWCK-U6|^ktOAE{`ZIKtl zbe%ZQ#S6!2tq!6brfj2^a4eJD`XaH|EUT#krYw@#nBng4<8RH9l6+C>I!{y<>rk^Dmrz%&1d+!-vI^6LAf03Gf#LtG{H*Nz_OoRFR>EaB2&^a^*Cb> zu9I6H#dQ&EW zE4#(q#3;9K&!N&++%J{>Z z6xYUf9aqU;Nlp84{{H7}Oh3BD$m}MmJ#~^#tTMk<#Ia4X8`C_vT4LczV0RKq4mHwu z;uL4v;OUK9Ovkenb`uyZwiahtOY1m>!`jRcKmF4>;hl+pL6QkI9O1&blN@cYJfsKZ zIcV7=tJCAm#?$0W4nl67kvl&zKltXUI6;yL)b(-h>?uxmRU#migUGAX+`l_WRtQlD z^>X^eQJ!y%Zjeu{Fm&}g(}^Ml<9V2S!d%@UhkU?EY!_Q`Co&G6vb2BUAu z{uVuce9ag6?YG@!y>uL`e1gTv5pLg_L5w!zKmPZeYX^Mgca`n=Ck#FwV3%OJNk%fssy z%Ok<(eKS~3*Rk_lIoFC$^;6Y+gs-n`kSyvvoh_gDvmIY#qPdQ+Uq*5aO1U&^3-c^* z6|vMPy#p7xbp8Zw)&9ekar+WRF~`=z45RZKqzXFTV4CHbC;YfQ`PO^oNHYT`&T#o; z3tm~mu}$(@ON>1k1?me6VGT^y2a+=6aM-C-p0Rk zc7q_vs5Jw8duf29?Nx_VFFz0tXqg1dGvmy~(-cY|<>EZO^+#f!x9P4zxZwyFFP!3N zYqYGpdV%!HH23Zfl9!?s!+o4RVY7Q8wquY_E-`rR2C=OY1#?f5!rT(^jD};t%Jd*V z+G~V7@~+<$YCOitPbmUuEW&Pqn-+1#_G=UIuZlPT%gtTXZOCWVzzygL&eqBl%q z*D1a_+e1TT0Ds*PPF{$U%9gk}G|%$*Bl5{LW=89&j`|QBgTi)#wdG}&<7q5!6}_j< z^X+$M=!{5*e1&~kcV}i7SxOeM10J@PC%OC6+S_d+Pk>k#ir9HZ<9d0g{RMLA|=v7&#^Ond%78~EFvlaLJddx z_WMiZjoUn!h%@#0CfURaV+|DqREJ`Elcm{tR#G~i>NZY)bD1*(ZB+TcgjIN7Hiz94 zadG)X2nb4u>eiEd`-6q*4>LGA&C13E4`+)QmV+Rv_<~WY8;;UFaE1%tUg2a*2#N>~=z z{77Hm{cyn1*_<2W?$xUduH|3-XJ&$#;RG|o&o4=#Iy%lr`R;OGIg|X)h#;v{cO2u= z6&pwL@pycJmG~4lr=MV0HlpIeABs@b)WfNxXSn?Jc~0~-;XTwNosDJYn0tJetB)4< z1ZG}D&nz=^clm{DYW;C8iS_*KQU~%|4xj}g=_vUgZj1(`n#(4 zH*gCok-84f{qk=ReNi3^Pcyf?!NmP}9v1a-=Bpqgdwhf<71VYgr+45Km%qM9Z$os~ z&@VqrAyV7Psc%ID$xFrHII*R5W}hrGTrzM336C#8q^g!QY|Nrw$fa)-?L#r@Yd3H^gMrU3j}XHW^87e zmDy3|hD%ru$f}oMq>_fdQye>Ufr}ST(_8oQ^UK>d)pZ`{n_miegAwjNoo01?iNU2w zG{ZuWWPE`zmGzw*?K#GUufOG7e*+QU;mulxa;APhm1aAcL9;BhQi_GAw^?}l_Iu@U z1HG3+oI2J)%}y}jEpNlpi)_qJa_`3<8Qv)F$t2&)CR0P3ObtE1A_Zy~D1>N;Hn8#Z z5kK7;V>SC~eL`R6-cK)SYHdGuxS112n+U$V-|C^mA-k1eJDsOw+c?<-u_p;)`?ymI z)(|<>$geK8QW@IM7MKn=8f#Nex%=aNo^BLh{b$83rk`vv{p9&2Iod+k`4GSPp@!Jd zeXib(v7CMNIG5X6;PKYN3)j@zqv(NpdZI9V=O#BM*Y^Z?_M)>kH_qDJ`0f=!_E3A& zpuVk>-uB8vdnSigD3Dw)uMX5o8rs}buFbvuK0)?S*{f0A)Wz|xef~bjqL7X=eCs+l z=C;|^Ui~e%7RT9I9N%+IplSd@6&@^YiU(JJVrVV5CzE_HNn*oEVtZ{ze-(X~gY+C} zr?J}qV%yCmh&{Qp@3vcUriou(Xr&@_SUaghE}0~?ou%YBIE6HGBlnpbdHbD`FGBQG zJ>Q;br8eq)`wakgiOsn&?)~@^kJevx$SYtZh>awO?J0v4Zlw8CfM0!6$=vV*uHP7E zKK+`$nOJ7%&Wn1f)b#MRr=82ETky#ezHl9Vmw&*P{nR`jVJPB~Bl0CF(oOQ_l{jULv!ZC8r_Z0jS}B$>_^z9X&FR|XK}C|xHnBY6V&A`cmhEwi?{%#)=lN`{Gzh@yH4gd<0bUzF;z4SaLDg__8Ig3J!s z8u6*8-23q!gX^!ciHt2~hPPgvM~O7iayrB>E(Mt#e!#Vx6R-9Cvs;S{ZY{oW&D(IC zoV`K=M~;F-YtTZ4v^Xf&GY}y})WuD6vAe=SP=^MX%n^bGR+} zf;;ynhHxBCtlj-P2r|X=kzAJ#rFkKnQLu(kbdFXRU~(u7K&_}QD=Es#-Dc3S8Spd( zD8|UoYXY;xABKKMk}zuX3wWPNS2$wqVs@iewPHXgysTgDzcN~;$<_+P&LXHP^OTyy zMwS&ic{Z%9%E`(j!j}QQtsX|=CX|#jm{4|o-bmi)g`6^W9-so^G!9*)GGlu@JaM^) zv<=V>c9i<;kkiX3LQr$7TeH~wA{C|K%Q&;NPwn(KlUuHbaDrksmRA`htwEQ@T~VQ5&KFT-k};YxG^+1q)H}bzmO-BQrI8mU0t95&Fd%v zi&(m=D_)W)Mj4wMW(KGfTbuVyTO}lbM(g|<5_k4wKREJ|rtoM*lb$urRW;lyp|w7v zyn2xSiL_dX8vC;&pi#cmbbd`+cIdfql1R!RcqvEkLmhpZe_;riI_PYXrO@YNbBw|C z3Pn_AO6c%*o}OD4wvzllQMc2%L#n*m-DE6eb9H59<{x$T&2lvuL`MJEqjHnKa(#N3 zUr`qQOG>zJrv&B;)SJW;9BeC?>bFNXqw&rxhvE~IGkDTm*!0PExI-Tcg6X^nsaphR zR}vkKbbwlFo@3=6yxhmh+TeDT6?%lMsJ1HZ>5AX3#jq~=T50_y46VH57nP^Jys*wb zv$#nE5G(D*?Aj;Bt0`^h3D3P&;K`)9rTJH|Lu-hH{-GZGkjodX{K+HvuoTe?>|JF- zU9XjjLu)K-x@0@Rs)Jeco>e1Wuj#gR=V*zm@{Z0L5+yRP-du<&rXO#cSJD)Y^?YWx z4HnD1-;6r9hhCRXY+c15aQ+NB2f{G~qP6mN6uCSx=W$0?48jdlKtP0%5=2{E@%Z~S zjrmoIb7yeeW<8L8q?|7sDCi+Ym>ZxPc`bE)EG>F)lE4~d0$DT)KxPh%IPZ<5bSb!d%Q37a(`pj!p3uYWx9~QM8h5C-H<8>OE zX%2`PeWG^#^=TzP++dvIinfgMzUt|(Opdr*?&#IqOw;5QB5zVK9&3Qlgx#|v$!?YP z-dJQ4R?1r2_v<#Vx?s=~gor?Bqa7Uyc%{_^?~JAfym5VIt;4LOsFRI%roXR zvcjzONXmQyBtTQI7Po&}TM91vuOA_U0uVCRfl9TRqfDI3J~J* zCXu(7pBzxVNZFn_kO4iGsBQRNQpK&IqzlZ)smrTU$!&fue{SDG)YMiMHn*icENCB> zh(FFxj8KF6DpN=)XN}cQ5M1-}A)q{#Q6B^r^g*b#M16LkdmAqPkhZukd*6=DUa5hl zR4yCD<%Q1)+maZPtK-MMBoqA?@}@$_yU!F$Tt6Q-%!!R#@5(cNpHL|~SbkO3DTbP) zspL63kfoEd!p@+X?IKqXHWf{5S5S~V=-`9)vgK0B7G}z~`Fw zovsZSZRP8E-v?rIHs9yWtUKO&5dqQ1%e<(Lj;@v6#S7K!_r4RJ?W7QG3e_1;sa4wZ zKU6X@ZHY%ufal^0&vRTwLCRh6Jw!0o9v~dxlcFgn#=DvtSzu+^8DyWn+8P@YNE9WN z7*pu&zWwOCw&ZOab@9FOEp;{P8$pn8{*;vcwzoqnlgC59E!^ zTCu%O$a({LG;~0j0mL_7{hXzh33vb`tXF+ zl>Pik`g1}g@nJ=26Q|Lc>2TLj|MvL=-cHuFFvH{9mGSFpyyB8X0BxwN%RTuF_$ogp zN;XL+;KI@&twcmJz}H95znK$iVjY_P+Ig&H#U&cdVDs@uiR-cSLX% zN+t4vhWL1Kr{J4}gu)y}Qx-g}(D<21Da5razO^Q~y*6K_*H8`E7DDUO^nToPjEglpPnN;yv^Ubih*MpD zan8HlRaPfEv!nczJPO;RCbHlLw=mF3&5P9-Q)3S$c2BEtB24>pA_#D-6v_cROsOc!Ke zymM-Ukqyfd?d~k~xbjTDz47Sl>r4F;zD$k}w>wXU(Y_)MdWUIGBru{;@F^Y>3ihv73LY=}2j+^xoXyA$vL>BrH)5nwv6Mhy5mT@&v)Iss=G4iGGA*utAJY* zp}Y$vYDIDG#?OjiXoN-HRbF(bMS0Rs4NbgQzfY8&GNfk_OK!o`%q-N1Ny^NOe1JGZ z%im!Op1(;o@65i}H?Y2V7hd8^%tN+=ZrJ$DsFQX=sxm(6PgLr3GH40pLlM7#An`YC ztI+o2m8@l__S02?URh%B=*3{sL|4$bMY?xF77zn0$!MjA0ve+K@ZgCd`p;mZgLt)`ZwF*DG>1PEZJfu>5DDkv8a-g! zd+LS7C=qJC3q9d!&Jxb$jj40*0@5nCU?hu|C!kkyiBvcAbin%yyg|#iXS>Wz6$9%j z|AwbSAek}-)u;XSC!mNhqg3>2^KUp22L5TB`L`LG;@H9;`EDdM20xJ*gH~d&gNb^+ zUy8k-xO07b$F`A_Z{91>liLg)kYnCFKTnDG;U#W+--W)nO(fdyR3T#o5elpK5jFk( zJkdn3Lw6aU;w8$vv-e;7CHBXZF9<3ZkvSKZ1bELwOKWE!RmIC-%8fc@<;wSV>*Yp* zQjhTB=L>!~obuCdyf2oZ3X)l}&;vY2UqtZ>lxB}&{B3vNY;PN1W0ax>zz>?^93jAd z%g-=tjIiRP{vPY*Y@-WL0723_B>I1jNy$NYi1z-dL0iH^#f<22br|=(oJ5*k;1Hg7-dobTGXeEPWf{$ce!T5sSjzXQldtPzB%PWrl;w}#;>;XU`Czh+;VI=qRq7PI=KSoPs0#|STe+vlNI$c z`)s3zNx~Y66bo-FqVF-~3zU91UIi=0m}w`=kb?;etvo8~7I{eO-PtyK230P~VR&^QvNVU410&TPH!aJqL5VXn=KnoJuRmI%vaSQ>06jDd? z_KtT1+^tNN(?Af>!c5oLH9rvgoSg8q#$K)7CQwvD5DJpu#Qs}deNoQ6xwA@$;vV7; zDXuJEKzV1b&R0CYrLG&A9mz^EJi(4Eg~y(za*XWgT6N zp1Q7vdVcq922OPK`PWd%8W4AxP9yMrs=nDkoPFHn&K1}W&y`gTqTrVCC?kxxZ@9l>fhYRNj6m0wdj@JRF z5D!Qn7A-_ZH<5Goka}q$&*47 zSk&|abi9l1hV*>RPDs9m)m_j!?AKhq!9U)SKSZYWu7%so)&-0jY`^q+RLp+zJ=X(j zcTPlmFJkRp^_#73iUjjIJ+EG#=bNAWT5e^R$`o(Awl!e|9R>Y6==~KwPg6d)-D*Du zFgND9nzInqj|JZyzFlrh1z-rrMY-|3Unw?*mbOBA0Df-Qq)#=NlTR6Mx_JfHz1s*r zx*6XnAE$jrTYi&G0y_;4jHv&oX@Y^bF)#;v_|K{_lqA#Kcnu)}rSY5`2@Vw@6zb&= zk>s=0E+5_5^dI(JC`zZ*9ubiYOy!Cq6CMTH!$HcoGv*Uls{(bFu?wxdK^wBE;F8;t zn5e+vGuCgs(Zc#3VUh%jD(&}9$v@p-g-dM9VM;@@B?@?SJyIMwBpDMbY_?<$$!~8m z10Xj(^w>>su_DeXo|V7t*BttUk&u&rEG?<4iGN7#%RZiPt(r&bQHXMA=I2|bmjbhU zGFmDE!XTye|ATiB5ImV}U~ZusuL0@>A%lWD)Ca%4!E{GG2&dj~$AzX&{+T`+JCZ#O zi#!S>ijay5Ub&#efWuA2mxzhK7K0=kwj{*E`r1qmnDfBgod zTaqP0B0)nyx-BOhb8@YZA?dgx(~YFdgpcABansj^eZFt8ZIU8RBTX7traHq)jXeki zb`$voJ_?xjlz!x$46Z^2VBi7E79h!5$^tgo^%Hzcy=T^yGms{l@YI7leHgAnElRC3 zFepY)O;}zYtxs|-4I{GzufsOgwpK`)lW9^UoQl?yUqB=QO1KZx&Cnz?L|H0HjzZc( z7OVU>Elouw%z>&vQRilV1AUB2oGpbchoRVle6_QvxQ1GHFHwPGME*_)i655kNCWT; z&kiLLts^m#{w+d7Q&|;VWK9y%oes1nnKWr8_3GE)fb$PwF=h4cAfi2`h(9}%S;cD& z^3A@fa;+bD(@YKcAi`(~>WKaU5lUQAf2(@iM!vb7Mn7&&O1mTyY$-%3H1mtk z(oR$bq0WR&2o*{13N1G>?G9(t#> z2Y7=H9sF(3%J>`_t2~ytxlWR@;s}NvV21jbBEXjyiFmn+;q7$tei)tXin`&1BnB<5 z0eA)F?Yt2G5?VLWb+Z}fPhsH<``S`dq713+*T za#m}GHeQlMmdGuW8h8jjKc^)>SJk`4u?{G@2S&^`*I0S9-r(PsQG^s%;ByVIu&y{7 zxA4d<$w+SvA&M9yK>QK{&XCyODxwbIpxK}Qw-;-xN}8qhibiDL@P}DM0^6wv2&A*gY8AbwEe%mV6HKb-eQdzmsE6c}I|>->Pl= zHBb0jCb(&C$=z4yQ|!nJREVel{@Ted8KAu_n7WS-H91SZ+o+z2V}02Lc@8htmdE|A zQ+I3ldBDi!(Tu#qi@1xR;~r8$_)Yq~@rb?5I-+}nL;LAT4I_u# zSfnoI)Ygq)X5pDwoMNHHm2L#bhlO?^5)+pPz1ouGa<9(Yj)SNi@E1TNEVz6yOT?v9 z;NM%WfsB!>`Ga0%$@}H2 zw}BfyB^SfY$0Kh0D|T89Ve98GW-+j_^OQ@9$Lk-{3$#2b>fMT@mSsdD>>K~S@3P^` z+%Ok(YPA^KgYcgHjtckyny@Z|A(n`6$3^DKHZ|}~zPwh|MMagnM|NTT_u0@{8Z?G%>N}Ze7Mm$MYYm z$%>C0W=-!W=>2}I1FpurLJ{ZfKm1lEXidPSlb(TRVd@&yaU|c`1SAB85cxofS6Nz~ z<<|uS0?|@dwekB&C28xCu?Ay_dRZ3M#xV_%Sogp!XLm9u2eNiRuA(h3DoZIDhu~OT zm$UpP<2$j3*N|&c^xt8=MS5nsk*#s+k!SFg9`ZEU+5si-avKXmKgoC&$KsIA38LKR z453!}s1CG?XjMKh$F!~x)*%;?{!*8ZgT8Ng%JoV>&#&Xj2KcB9Fq>#rxtKUs?xryn zK4Biip?Yz?FC=vK$L34RkNIm1Yuey$CG@yh6DwPX+D0bU{?k=5*83`3G8QyfSjj)i zzWy{-=T;ZzN0#5p-d&j$kq}D7vqB!KS=CdDEG#@ThYu_Ou}nSXQH;aJuqDBjt(nyI z=f$nYnWI*qkG;>(r%ya~wiYq1+P?rm+Q;CIeqj|y@CU{geets4+}5L5rtdhIbU$v) z<+=U$yg}#sdF0zOcDgej9sS_l3;x&btfm)JPvlii;d2_$bL#Qgj!n%I!O3rcHSa6q zIxbETRacAFCjJ*Gu!P>DdgOgNn(uA&J5${*is#`7OEqyZOC2wZZ+EhZ2#uvvFb%v3 z_>}#6(xi;M6!mD+ILXMxGI6yHdrgs7S^JrJMnpp(GH;!^-g(CDoQ(Rp1sPtcyV-=ZrkWIY!#d$Qv+Q3cY zuhD)#9FVpZ_K3M=e~b5)90b{wc!8AbVQbsyr4p}F^VG4AV~378-A{uJ315Narby?Fiz!9EBfw|)razCO zHLvIl5_E)BRAxWO@ue?9UW2o2PNC&KxqU1vz#G{_69v8KElG&coe5|Mp0MRCW57`Co-e zKq#zCWf6s;N~Zv{sAiphS!8DTzO?XlD~z283>Nb0C?lf={%$3d!?EIsz#$6kA62FCZ&*TL^LYn*&}EWk*+G_NbI;e|673_( zI#pxam_z%^d(qi>WaDj{xX4yF4k(VrZjU&PtcckFjxC<>#|(LcdCa!k<=TDRA#7jvvKz?U!VjCvyIKI;-&e-$(7?6Y}-`gaj_L8+8N$c zR~H@~&#rN?)nUcnN~Xxt&W_b66)j#Ini%Ps*`~I~C;^|EJM$}O#D`wj>zTu7w5lPS zA7>PZqp8wpa6tZtG8)=&KXWwDu^YuO+rrs6^QKuNp ze%I{W0}l4I1hDHbEs~0lM>;xU9Mw_+J~CRC-sc;7)5k5X>4)|BcU={M!mL#zgTQMl zBT@_VK}0wf2G)QrYV*(o)Hk%>zrpsCIG(-mvyNZ0f6 zPOq-Q8Ghfo^mZ@_>9#mX9^liFDw^A6W_{n0dgKmiDPYutLyIR&`r+d?{W0h67{B{~ zGeKR*{yc}-(dSXHNqI)Ps8#Uh9~t}P{Q!(0-Q!}z6{op+By|k&u%eR2$WPrj8S3rb zoe`W5ob#U6Mry2@+nA-!hd+0GS~h0;rqUPE{*28a>3lTL0XAGRro9M0AAD;0V;b5! zBt4EAuQ61e%sDi)(qoy?c_%#t_4f7~Fa`|HYEXMywaHp|hUY%t`S5a0xV424g!R81 zH&SNno9VLdNjE#Zb9fbxwSkjA%-?BaRm_>Xs-sK7!9REifc-eH>pKy%dB_QNZ>>-U zV#d*M59WIy`EaNqp;*Q7*H$TX=XOp>dE;VB?3(xh5xSh$&NpX#y4;`QTkNuAnkTDT z+D68{*%_e@uSbjw^D9{WeOVC}%2TD%wq$EkXt$6P{>>j@Dfdw{K=byFXp>)P9O>BI z(@PhKo;;|ORor8hD$Dxg{qxS%(7~1RwjZJ^yPVS5~sFt1H*q72!9iXAo zDWo+KW1NIZm%#qExp;Yvl*lZEWSzm=AnR)xJKf4_|1!#6%9azqV4lh56S1)a%PUUW z&@;7upeALtnUd$*f8M6ZwCN*$;PxuH`5j_%X4-b_<@}7nc`fkE+AAv&Yv6{qFks9w z!X*C!q7+)CKCairqQkQ~<1elTZiIFEL>Pu|<4eL5)CUrm(HU8)gqP<#1LsX_L$}>N z6bwk8h(dr5#P?TygIx$v1f}t>?%K#1tOeJC?)y2M+z(-qJN5Z(#}Wj$2Q5Bu z3JxOqVYxvjaCm3=6*NC2;%Z8`M>Rfv<5(vx@LUXnicSQ(86n zWqr#K@NovRP-W$uD#f%*?Xc0DC#i*#ks?j7-QB;`rCNQ0|C9YHyTdU!Zp3=PV9o{l zcvKP_JI~DDDbv_3B{!mrjn4xUA}B z5M7M1S@lftW$1NuRAQDg!|yGSux`u3(j1mpOLnKhIk9p#T!3C%uK=}Kb5t%$D<$pj~41ujR^kkiGa5) z{(WrRlE$FzBFX=%cb;ky>cO{txFS(fx!PJ50aFtiWtJyaZ8hxq>kejU7*p71`Js&8< z9~%&m`gYsz#+j%0^}Xg(chY{%H+kd9P+M6sSRZ&+-%%bJZAPh*=40MO5k{~j(;6no50*&Zf{-CQW7^I zf|;00(#$eDG)6UBrjbtQC#2B4_waK2ta<2#`2(FE(*gisuhr|CJ;-26EK5F)L(s8~ z0`S0{RzOuXk@9(R^`HMk^RVZ-h5Y%Vx8zxjcy>G(gQ$4|DzM8w_XyXYf*p3fY36JO ziN~J(IVk8-+Lg%?4DkFK^4PasLgNULS9KbD_mfdn)}e{z zGw{MgQd@DY{E~N;P>@@~E)uhAJdn)tkY%fxLrvBBo~Lc32rAO8)kHhyJ?ZfMQABm@ zY6|f3*7k9Z5DkyMm{`#-a*~c~daJHFRe>QQN<`4~k?YgM3AS5Wr9PgM@ zsf36``fi64;zd?eb38QH`KT&duZL3_iE~;~VF7Kd@$Qyl=gRg|4p(KqneHq(xb!TY zuVk_1$>~mOIIGJ;96F>w@WYQ;Xf^?A`u4D&smNu6tQh#!{lGp^a97oR@q>(#p+GLJ zD#8FZ7b)AyIJ9u^&6`UzTbEfT=TCS`XjDB?amjxmy;V zrD^|uGHR6l?!PXp9v9!MMR?m*f?^annV$mPuMBKz&)A;vp7_}+`l@$2!EuiYWMFeo z+{Gzaxp1BY_~ahgrFhz!n?g71g}FLFwxDai9%pUD)Yjd7ys=ZnYaF;~IbN;62rD*l zaZD9;iB5sJyx4TL-@Yqiot78;wHqc1PLw~!L0u@u%8n4>;CaySEa zzNePLo2ugkPrTgVr{P1nrouSK7`rJ?wT(9x;I;_OeHoK^rn`P~JON0pV`7J)?G3yJro7Q?e!)@-zQdQrwW{njnXp9U(-foXKe#Rf-Bor1 z0H(}9T`OXVPMvb9M-|iQ@8s0z20o{>y59DYqH#AiLsSa}xZO?vsktpmILWVL*7xoF zD&bU%T$h7&7mPuepiBmVw@bbdAY?P!+*Eq(-Swe)LCG)azx&7Da7;YxnV*y)-K&t} zoxV9MGqubwzs$Z)`gV-`B}wPzrX}&!(=l%VS0U2dI98`PGS<-*7K&cCMu{!yLdqtB zdEa??3;KJ*W*dGU)Yxx8akCEh4B(^3UyfN!;tA&GH6#jF;s%NGPdKm%y$5=Hl5EM~ z)!gt77G`JuEht5;*h^sCZ%c3KPpj#7Oby>$v-WY!o(_)2_$`Wd$qqTMf>l4#b-cjD zJMiz1H-Qgi=8SA7eSF2ASTQ&qG~*&YeD$6;089A{%;`CLX(rrtF96H3$!i zcCt_84B-XB!HejEN(;@C9v+(=&lCgp&p)v>$|SIGtBP7Wz}kk}9sIp5=2XPmO1wB3-VkZ^Tw_;2ft&bio@|@451gJkiZ$@~} z?CbUfzaMA$^ta8;PnnA(H>lvasG0ht*U5(ejgek&c@5aA3}8d;M*NN-ShmVZ%cm7i zEzNVfAAyoZjt%a#XYh5;4T{6@jpMtq?qI9vbw8)A11xE_VQpxc9bW5?D6$`%UCLQWu zXF+|>E68Kv;i*~0A3)pN^$-!+0zN_@SWr}ik~bNpk0CUBxH8X;zjj_)+?r!Dssqh6 z?c)&Of!{+&nDP9RUY4VGY7iF@8%Nt%(qnGZC36<2y%lDRi7*-8y|JV{+rr4`d^X~u zVKIV*TTxI^0T=J~y;($Sg@QZ#dXd+6e76N{3_%zxIr~r5%>3@$(6hZg9zsB0Sb7R@ zdW|$o$tfk}|E6HLd(iZ`nC4xd0T)qjs)FClu6gi2$*G5*X<~LsO$zVE)&?|&#zY1O z;ZGy$;U746uqWJNh?!!{fR>*r%OF4s6<8$zyt8HH5Pq^-WTsDeAu3S8Y}MT$BA z0a1l!-UYjGa$%|lOuC$9*zWV;$$ddZJ?1miog{iKMmvmEGLNML-Hf4mdU=^53pvHO z$(Jj(oGnz(Hd;w9zx;@+XEc6p#bEd;MBMz#9ppiiGbsuM*1iE}nnX%t!aA#>nyTN1 z^K;IN^fL1UBSn2)OLHnD623J=x7uzvl3d+U2B@}ao4k!fcUTCdSH(KtkJD%u#V;56 zH7};@@)h?|bd1qV!bVTok}-MFSe^2SIN0!)fLz4iA(^vsWQDdq(PNaEr>|#|qUV}h z@eBKOv^oT!(07bnF5)G@BAY5Ax99`C<(5?qPKWAs>sd17(&Zl?9w4;!^~_zk#?BvH za_Mpp)Iy=VoL0mPSZ-UB{k>gM&l;S<%t=;Z&QE#PMeQOX?}?ZC73^kM+uBDY=)$`? zlj64hJ8@}l*8&bHn%07s%#ST+$?j!s=wh#s)(niTWD7QJxs;fN z9Q43znXvNVt>+uPB7&qyjUg4RUJB7q{ z5cN;HwUTI``)VNQYRJr%u4?E0a%UG)0s1|&3mH0a#vXxd8Mb@SVZcH-XY;?s?6u&x zqUhS%*)_Hlso0_S3~15V5(v>Y00#*kFMuqAHRIU zYZ$}3ucFR`+4MwE5?yqGF5F|3>-5(%kUR*@(4zG zS;-C8)--#vxBr82ziq!Q$J|!S$o?f<)!@dEh^$`a1R^@=&eu!tA@_9n$E>(qv-~lB-ueiCb(Oll2%pp{U+=mMqmyc8O-B6lAUE4 zI(n4tSf)NUu`PdOV&%mq%_Ah;rA|rAbwO%+_#YnFRJBdND~gkrqNeRjyZq9}JJ?e# zNW?^l2bjU>^9gxgDe2KE8(F3|bt2FtCb|^nb~eOKI=(5l(J`XIwP&54R+(lwP=D|1 zRy#mIOQ=Uple`Piu}kt`m{ZcLEb@#c^qV}irl9&a&I}1uiOKMd9sm1jGRbQh927Nk z@Zj32s(JiA-nDAnV#IO!(8~XdnQdCfHl^f|YW}xOkXN1EnHXl?-EO~XE`2G~B8SRZ z=;Nr9afTnkfsX`38oNXZ*s}x|DX%=cvU^_zTO>z#*E;MszXB{Zw6v zC9U%T8=ld0ax5x*_?mJ~a~}V2WYLwHH(MzO0SWB;uD(1uzJZCqe`JXfP;Ca4UQ)ra zyXKs|+oqt)C3SijoZ`9$6~3miH-}8W_67sA5eS@Q;l>{~9Wr(^YSC%XLOe^p705qQ zDdsrA%GojEO&wgB6B$ha>BOC=?;GmEaKY8bXPug&YvjYGXm08ErV{l@z_;qVL6sMl zzOHXY9@bkHzDX#`K6Mz#H88%yV1l!uzHW6r4G)6`QD^N5H4lGde8LpDp(;b`MAS)2qm2Q6TuW!eU z8y6iMI^1$zBTY(q!bSshia%WzAiFVrsUW&JFL6r6TeWnzh_Iv+m&9T?Fhj|KwvZgv zBchvDABb^NGaR_GE_4!TaNwbftsF|%ZM{lRW1>jY?a>qER+R;(*JQNgX6Be2P_0WU z`}Nm1Z)Z-yxUzBzwMp!6UeR%v+FAE?J{BKh7)djXpUy>iuC($5&fI zJ7|n0wxyIVOC(FAISqe!q`+e0o;>B%jp(XQEq!D0MUa{hbU71&lwVPD!xu(lUaQ7} z4_k@Zg^@}`27c{?Q<0SB*SPx3_&ctvH@URc z8-~A?5C&w&K{om71&EWXU>sy^m8NPQI5@d@KuLx_@v zx$UF}>d30`$kWsisEmVRM|Y(!Z~J${^9<|rFQ&cwt3ds@8+C9~*4K=gW*Km25v55X z$xxej%kaySQXaXkD!y?AX&tcE$(jJHx|WVS2b94SLVGxo^HV~UM^Llnp5~XXekO_h zeSWuP>Y}EH-L0Py<&&q&rAYD;ev@O{r>Q(RU8B)6YiVXr-e)?3BJ4zt`xO0S`!adK z?LHD{k2tryB2}^SrozHC>w=J$R!D-Valkh(7A(akt1!R&!^};&RaI@HUozmbprkA* z6NOU5H)Y8$PXuKAw79r7^dJhes4w-Y*4wvE7B9-2Pe72o!~kx9#hO8yFGEz>gOFid zT3i)3Lfk=;&Py#nQMY>8HtQoR8rl zkGNHX-fplUMI^=XGZf?}xI%G)9ZLq1qovAjpbxg4gZ+ z?-hr|k{~8Bb;}v*`zS_`kjQ8W+F-MmehZ<<2W*%g`24mUI%g=UX(J54lkxU0r+w_U zHl`m-uVJvhh-%0fg)VCVWq%ve5pF)RsCJm9=1HfvdNLN2$DD(fx$<< z^pLAoA$`UM->j;C=-)!cIEF<}AT#-~T77>yjyA8AD(4;_U0|-9M9bIfmL*wKRlaTQ z9gkl^#Vh-e0oIpj97wbdrN-v?5QE&WE$8FFPhNMl)qQ3y90b|aEhQ1zggRY_N7M^; z=Op2WNx1e7>}D624uLe7nIjH$F-+j-aMivuqc6|TtG7|!yurXwF#w2~f)iy?6sgL0 z?isWjxkL3d#9PO))Z zlZz5_4p5P2w4b$P%s+aOZ1$?Mw5=?ha-d*q^8T@%@)s??p$k#h3?aZou!bF2`v0Tt zwqfI?rllRaswb)mlPX&nLh0%*w2&U*!1Cdlb!Ut2DhVwug_z(opJQ80Lzp_RD&A)F zrTXy^|r%C|e@N~Np&JztO%BLQV^ zi@aj`;VyVYe*Lj}U_+#x(+(?B;hLc(U$VA6h8t9=_52uUb%wNerH;||4~ySEY7&O& z0(#lpTzd-&MgCC#oV*CVYf|!;GP5`cC&xlR99=*Q5}BzkF?^2yd8~W32Db9tT3Yrk zNWlfr4Fl-2k^m181A(o-GOq@%J`KqmOhzn?Qb0~g`hmp#A(pJiJJ8c)&Q6+i8JX6D61Y!hs%E=Xv=!U7Ht=^Jxe?Zy=ozL$DAlpBQh+Q zERkAm>m_Npsn*7{iQ1jSi6tt|$aU{tr#|!f{cc_=G&RHXDW+_JSj+=lat2OC^LW_( zhgYNr{F=6$=ri?Cc4@Zpn2nps_=7%(;6IEqFi@|>g|0}k-m#}66a|jS$wsA%s$$v| zsP{Go*TGaquAaA;Xvp=rt1-hFIeKJnB!S0F-EN%{noXD0F?TQHRH!!Ed~P{-+}om| zvr&LQZtcBLviZ5aN#Ja*7JsT4x(zmLcs2V@V1%axp9`r>nDBh(e>rRZTh|RSZQQRv z?6@UDg456|smbnClJFpj9!LLsAI5!pb3=%fK<4zl^$Td1)*n;W7`|}rornz|U4~Tm z`KTQ81FA40B9I8E2%3Dd1&WtRl;MQQ>D2r;c5OFQzUzU51fDY_klg0~(o6K~DS5$tNZ85*CWb@L ze>67_6C6Z&YR4m(igZ%&y6LjE_`W^5vX!l~KWgLVZ?oh{6VdeuGSq7%cTxR!@g(nW zqO1mtMVAlTz*aGYwd0Y4jcA{T4FDXe=OA4j2t!Q__bokt+!I9_|iEl zh_IQ_TUlR}$@Q(!i?%{WO*We{B$336KfuM4P2sxQs!ZLLv=*d)$)Di1mKI%jagQij zhI_Jv8`U2;b~Gkfl=*J_L}-SabiG z$DwC6Xis<9Y=i)6O&^uFU6Xgv+7jg|+oPhLba!@ZoTBFbW_>R{#k_Iw(}Lnc<7~xAwFKxw*@@uwQiI&Wodl9|9+1 z9lo>%7I}&=?-?woAjy`_v~k(q-zfiE=&Ach?+tx9M|WW8RI8T$ZP-@a!jq zHYNU!xxaC!k!QFkNe*WUi*`LXo~JL!Pk%!D@K>PaXW{Sh>!Pu1pGgRIH1g?@a}0nQ zM2x~F0ir;f>+b&pF+tA0VEUawG+=NR;{V}4ewlk&w0H=VR?*QAU}<=h<*_G>RyuK8 z8Yy(=HC=TzLnbPZjJvN|=w)1gT=H9O@Ur#RhH ziqG-7DTKoV(O|>nx8d@??UM@0c${!JMpl=QttAu%tXTFOaeomypb!p)iN?|(+ps(R zc-7iK4?BYb&}!HnGL{{f7*XuaI_@)6?0{ktQEj z<6*uMAX}XHEl%EiDReX~M|eBT&Q20lvSN1zDE8%xGY8t9)q~smx9_hY%6Vf;o14P7 zemX-q7$Fu34x^nP)At8_zX<}8 z$%Z>%!yS0rhZSPcDBD{*D9D&?e*A6=rd^^GjdnZ*c06yqHFR_>M>MiSI20qN8?f8` zR23NxWmAD5O2`%$1r`@?yW@4T?1UpkB8gqTbmR9JIZ$3ol##3+{C@{uB8bRV4~16G zTlZL1GK985MB{06$$``5qrhv}M?9yaYbr`MO)|d2=JFW#hNf8!<#3lYQCC|{k!wG{ z^X?%?2FwmW#g4ZHBO19(lJ(^+Qdt$z=*8=C;kF-8hC?!7c6fP%g8SR|SvF&HoA<@L zN-od4sf>(0%$PtS~2yRDF1QQm!51+@3 zad$vd&*eP>vYMXvq{+ouUzlPk6(bUjkBFM)T&ySZ$d;AWV3GS9niw}*g7Mi4UO*io!G`0H*O8_XlR_dl^~IL22D2N^b}Ct)J|7-7rkB0lm#3ZrNh1c z_<#?^fcFMn%aF-rPy`Epj}M>MjTISL31FRDLQ_;U?d`ww0lx&YWYQ@T$sD?5#bB{w zm8CaGEXWuPR@{!fQ@omrlgwnu>hK1Cq#w5ykCBK*^9ldN4vQl$j&i!j^%rCAHQ$J_0wUEO&$^2`Dmd%h;6ck-UiEc3QSXNC_TRWZYEi~5Twe0_Qf8ptxik8igRyA~8C$T-p(_0aqMV6Ug*=8r1 z**%9cHg|xsng&|iI_TsuDs_H6=9EZ3V@U9?O z@s`wc{K82#m3z!?O>_5ZmeBeF)g^xH770C@AhNZ>^!PZln>xO#Ryt0cpry=1HGJScRHTyl$r*-576x6uqXN}7*QUu?&|uf>`U zdYX7VMLL~BG#WA4Y*-~>Z{ZEWh{p`+#PgxyCeL%JAWL&ojLmG46KxdL_s~>q!)ZFKH>yrHw#MA_G|#7kNERn0b*)qu zIX=C>r9VNupG=_ zD{rE&|0MmLHF(X2Lo1c{cIc?t7~5;J+ne8DC{H4dp)EFY&IfW{9lM^7!^0?oIDtDCy?tu^w7${20XOKjzwMH@;k)nP750 zh$`DDZs?}5*mj7gYIQQvH6|x!7?}CZe%gd}s(p)&zO--R4(*Y+VKH%Nr*Z$P~Y9WXwtTsDVDMl=`!RD5L zQ%Vxu+ySc(r_+k*Ao_hD@UubJa%7b(nXCq)glsfnlHSyLAtFjftd_idjh0Q5&E?pi z$F(4z+oO)RlI`H-)__7d=Y zLg4|m1wUYKXxS`TC5NJ^B-Z8_O$KpTEtt(t3hi#tRkG<6$#|H#=UXfY=X0g?XRdA)1mVvNp@}2lu!$u|d+{qo=Er*2Z$22H{t{==-@KVsaEx)iKC#aw-=u z-Dh-RlxuTi+%_8WBl?<(lFOm$27Hx`wDlk3WN$42r+FUHUc0c%SKEl2|?FTld;|B=}ntaN$qSf`E-Pd#UQ%3iI&zDS}I+KHt};1=vt0= zXqD;5_qaDa%VyR>RaZN`z0LRx!l6v8Yf6Un&N|O;Ug6Q`GCR71`i>4dTC4F`3_r71 z%e#Y`OA=n0=Gnss+?m)yH5by{)k#Z384md{@~)1WO%Ph1;NkUa3@=8}9VN8&c2ZyF z$9jmn5#J4Ta_Jq`riXcS{|S?uS?om(96i-bnali&Pu5|8t}7_19Tr9&@!-)2(_tN7 zSp&UC+9~xp4p4~J$i%joA9>9EN2AQ|i1_Op=;?2z$Rr+0UfCCPg=~C_smFJCI6T8z z%0y*HD{ZZ{6xd9Ml6!P5M{IkE@h1;?FtS8gb<)()NmqLv9(k|MQXM6^&cwqj{O4aD z5>ixhs*0j0=#quvswTRQ9_LtJ8&w5%jKAW9l$uKsTApV3!2|A0ZlhU>XzuEusiqkF zp6BO%LPyQU*QD(UR&q^8h~^~HxvS4r)xG4uQ}cb?1>lM5L1(lJQ$i}HUdR; zP4x7(QtbZG153+f$SMjsRVBW)%0woC!)C^8wo+K)K+rX^nKa3GjOB^PtS&9Fwh<pgGt2wfXEyf<)tMb{I|jZNY$ETO!0fbNba$^v%GVwQMtm8oZsxP5Pg z#r0Y4T)T_TfgJz}lM)Mm1Q52C4(yqRmf}&~cZ?Horm(7yN=Fs&VStW;P zucrU(C!FrA#$z)givqf)P+nO{QNW2o`-;m$E3AxOl$hx&HC z%Ytmj=RZ%4_Z=;sb&Xs$gQ~rL2wxB-WZ8i9j>q$KT?b7-wpnqyG<1`LqN*l3x;tsD zE5qk7A}R?&>kB-4aF6>#GpsI8a`Tdo)$YLI?4ZJJew#8nnv!8>W0t4)Z}RQ6XRM`U z%6m_8;%Em=WzGZG9sd2$lpKnpykepR?CNSt$OglENi67^hN>tis){b;bs!}`k|hix zpy}wEh^FW$*(|AKl4L54qS`P>Z}ue7HHBnwfsv63CYF=98aruiZ=%E|zn^4-uA{0s z6h(dQw3P6J{_uWA>NPUSFsqY~xqj&yw}w~IJ+*WkJI#gOV%#sA+wQ$nfQq7Os2T{8 zh$P8KZ;@6PMKP~2s_W?4EICbk;{=$NOA=a{Wa#+<8&Rn4ZlS5E3jYBmK7KCb@4Gi} zyeJ{bc^%camYj5jM0k~{r+2yd*ZYjEByrUq;n?6Y`Ww9alHz-}$n#TlYmwQZ>-?`T zAF&t{C}=*)iGg0)DxI&I+y0V!qbhlR(q3-~E=qF#TDao0qR~{qZ6>M>*YngPiXx$6>~z_v{6%NJ9N)zeo`?` zaA}15S1<9G%j3jM1+;b^;beb31uoMI%_cfpHpc4A2>0(kV=*REdE`8Uea%z`Ect7H z82a7b8ea;CvH@AzC+{YASebmp^~=||KC}Y9dfJbi;BDV?aWB0i9 z-7TKX1ThrV(Rbo3M_Y?@C8yhw<0X2aQ}h&c?zFTXBV~`qQ$LAc&akUINAC6gUlgdR_by z5F|5>KsCqCeMCbthpnKNy1E*wO5B)@hTR0GMtNlowGDL?IsTn5uRmjAZIq|ObyU?< zQ|2(shO8&KB#dt3*;SCuami zNyh3arnsm8kM)4Mu75W)(&0r$um6ev_fJpR%7_#;baQ_27~M@}xNQd1RD{iiaUR^f z!M*2G+`72U;zpYP>t9aOROZ6?h8@<_H0!goOinEk!b4qU9nCeq_huNSDrt5$S6ST* zk;uMWiWQKJR@?=ploq%#zcJI3@8(|_z0JihFLCY3B8sb;YIjdowout;MlSBEtOW7&B`j(w0gZn`)>lbH1kzP@P;R#`fAW8=(Z*S2C6YCc77Z zVF|@v%UhBmDr!2+`0a~)`Q1Z?W)-MpU*BhH zElx@2N1VHGmVu6P9L9IK(AP*sx7k=*BbdmczLLcdv3ZLrDlEYN7Qta%&l205;_hF+ z;OlFntRy7@?Vs{5|8$DB3g0{B-TgraJxgfr3D+-v$6v0F5>$+|o<7IN7mm|b<-`0d zoM6(_9I@?H*4DR)W?r5b5|9jLTm@y61l-t6Z@MOVp4%9^$#>seFp6PS{!&w>nL%{?BQ|03yoxC zm8pB*@o)cmi>b9Jj@l!fIR7yhj@RL_9MIF_oj@Uz+T{7w|KLx5ea6&g23P$6pMLfc z$J@$r8sBul03wRM7t9NH_3NfEoRgyNzCy!JOI$#gA8bbXRL-+sZ@H^x{?83=TI#y|h@ zB&`+RLpa%#=iT7kBd%WjjxVl_6ILy>9XrSQb4O_^^ZX>ytLqA}two;QyUUY>7>0sw zKKrzvhH^J%N#t-;0`iiWI~&WaZ-t0uUKd|la21qN5^%qz;Fgz;TpPW?*MGUp^`RxQ zj&cSE&hguGofJDwhmdzQvWacxo?PR<{&JN^lbgszZ5%uETRuP6O2JFKD_DwX>^_F* zZ$z;BDX(duzM=q^-Hbt&5YbUf%c!oerK-ro7hhiH!Q2{iqYtju+xNP1o~<09^+(Tvctfwzbn# z;{J(WqG+<=^i|Mxw3F$%4d&NoSz26TaV1D^)nRNF`GD{7p&0O9pp#1nSzcIRBW!eY_PO8Oenm`p9^_d+ash^%hL6q@VcX9f6 z|H7#z7xs5r46xuVYGClAN)$~;GFq^hO_*L>fC&<^(TdAoLB~KJ3#&oawx(HMUS@G= zjZCW#>+7aMbR8`hWqJHDH^2LiYfl!4;-X<-kU#wHEUi_3>~Bnd{QS_>G#gWox%Bm4 zdAyn;_fq0hHruJ{`It{GoW)rtzSF{tn#c#&fBt%y<((W=$9~6eFC3${sSLNxgh3L~ zRUiI9Aw|Wd6nekpo7>Y&-~X1&)#cbMZPfbrP7vl|3rtVXGrtEzN8W*%SRn`=*)3uRyWyMWbGOvmXz@`p3+m<_KBeROm+M<%|`(<>LbbbE+ra}f+B zZJavyG3N$asq`PT3r_$fBuPLNLDzINMM2Z`d|bW9$5HeIez~4eBvy@`r7@}(Q`>6 z8#COy_!WP>H^FLDps4dKpM3feN82m$*$$a}fUcn_2{z`QbMw1P+;}w2QbecrO7RMfQ_2OT- z^=z4#;HK^5X@38kQ?yoivAkp6eJeDDOmdsKr+2yZ-Ax{juaUA8(tF}F{&1m}hB7Z! z!{O_`+z(VG&iwFAzW(kGQ`;}|9GIO2w4M4RzdhBpXE8umGh~xn3}3y-cQ+pKe0~S9 zppjE&KIZ(1c4`WpKS(|t4(RB*N;0&-!>iwM<;D|67b4iIdKox-jteK+_E`wf(UmmO z%{iW4|CTSW4YRPF!&TeQiSy?<)89a`$NG+?)l|~4O`cu+H!e=Z3B86dUBz`A`{Vz^ zZ`<<|d#^%AQ_=*N$GCs>3YYIZXJ#W!Vf#5Qd~%L~?rJ<1`H)G*>1eq)>oddLzw{j! z?@bZPS*Yqe!G#NF=x-^*wGaJp(O}0{T8lGKiKgde53`vBr_auD=da&#{oxFwx4*+; zHes`zroGJh3pXt6^6tVgSHHQ$z1hesaUqCQ9r-=K{p9rC#QPn=3q64%w84t|?@bTg*JU&817Xcr?CF##T(iLG1 ziAUGDHME9qFXzOC)3lX)a2&E@Q?gNJ9$(?x>ra>oz8YUz+(opX`U9Vx>cHxK-M;6$ z$Fqq|hAw~2rCUQhpWney(#pwmpYYM~7ODcaLskgT(KUrcaGnQOFLCAO6Gj(yaMm8- z%qJH(-QP%|-S7&pNX~Madjr(8YY38z$zsK9d@&)OFIwANg*5ebv$nd-;>Hkb(QQVC zCi%Fv2iGs&RHu*(ukiHif8(2p7}3`hc-&=84E*8$=95+%jy-ud$>!V$_pV*x%H1*M zwzHJ?eZskqPBPea7z+V9S~kks%rG}Ee#@1|bA)qNYL5(Z;lgQpn~HF}G*K)FyE!TW zK&GIigh0TH;Wg`7L6orj5>L-IyLRWc+J z3Ysn;8_gIEhJ8+T2p9}TOeP}&BC>42WHBP`;WQ(NCd_6#E~^31$tB`sbGbt}Cb~B? zO(mU7vlEFDNhq&O2I$rp$&C758bSowg3W2c_U2E4C}Z=NQCbq9$Z2FVmS$&bi+C=F z$}dl>x|SoANDz%g2`7KrN+yUBhCq@`?)4HKzbHfr*<{0Idh;0s5JV%+!ZJ#Ve7G#L ztVeg)iR_TnbgVy#MfCilA-cxQ$P;c|yUoLqWs;@>+WU?(IBZdBopg#u$0o)+d)%(IezDlGE9PGz-;qS zSXoC)R|})#tE^9NGV*+y-sWnW5|C(rMz+IN@;Wl|Nf`3yE|V z^>q)IzU!Z`HpBA=ce!@+F;nYlY^BZgpFGWAe;d_BPRws^gM7EpHPmd3=;l1PuUz5o zqjBbgDuL#H22P&hNLK@8zI`OobPXjPWn*!iM|bXU^Y&Bb!U84DeGHsD#j&n>O1-xC zGTEl<8tHf{|L#iUUizy5wm7Mr{(7l6T_u;=VPj#8+gERJ|LF{?aRYV7PH^(%0DWzh z6gm%=X>dMi9Asg9h&wm#aPP@9LB&B+{{Vw0j?vpvhR1H)AFl`!vOz*Nyg1F_#piQF zI>gpigy7RvrY0ttX=|ae*p4jz()YKHn$3`i#fgM>UR#9qCDLSH>-Y9O@2)ZS=2Y8j8J)?*0Kz4)oDl<;5f)GTv3v#I_e1d-8yrHyT>(|_ku7LE^NB4UjIL&w9O~lsr3;)qbCvFtMtIF;cC_zj z|IQ86CVjXT-EdwZEE7XXGdDrYh!JR96JajW6I{ zVjW%FIQB#;sHmzW5xB?Tgu?X5aH&u&uX$fXz%q0S*&Nf;v&2e^7A_x|4j~l1sdCoWjq9cIc=fUj~F_Z#op@3pqy!K!Z zo9~Qm3|I+-q6o^8h*6kjY9htBCxlzblTD?_X#$edfxPO%|9&J0PCRZ8exDOe9W|dJ ztLe|J0bp4gs+wVHR>ibH^7-+(T`boz)9vx%^?H#+tCVZmEaqNc6tS3td@l09e9`Z& zMg-jcIITMm@Jac4a@w=jcy}O1RdW>Qs?L!mAjm%aJ}&{Uj5%$f<#VXUa%)9=A4J@N zB%6+WNN`huy!I_~iXh^RRyIWd!?o-=beMg+HnX-aj`xM3W8a4|4Kw;P z8!(c?MWnKsnrJD1?GJ`YdUAr%!4w%o#OJG`zBWNP;97J7Cpo=@%Bm=f`f-RU#`*`D zn4U#3<9MI>3|V018Fm{M#K{; zXMOuoTy%v*S`sy4Vy=kPx8ulJMMEkByv{e64DK}mM%OsoX;riLr zoIZ1%y8~IG4I9|CZy)=2Z>F)#w~7|$-wjFjP}R1LcO7xIW}nqLhucqCLmg4yxBJGz z)bot@cX08WGn_helb#ug+6_C|yRV(S+tyMQ^{lE*<6>IL8AiMBaQ@^ePF%Rploh0I z<1X3{w6kMfJ;{)3={8#yhBC`g*Gi{f+Osbo!XTIU|nd{se$`fncz^;A!*}rQO zYm(kY`$?Y}qW{r7uHGLZ=ZY{f)X9Y}rnvc((V&=CC)NL$f!RE&sxWlxOa7FO5DkZ@ zY~99|^-YuoUhgxJoqp;z?&dvz4LcT@UphQN${T8k_?~@7O)W>Nx1_sgZ}NCnrhd~d z4jwwl&W(*!Mm?*{p|7aBBVD&Rcj7cBFFs&K2vfg#4+jn(U~6kN@qqIcd@BTyJa~OR z{9YMSDq1#!q8pgJZeu`kp1SVvhsf(y3eOnk1U#W6wKXo>&!j-K&@w3=-@C@iFHUpi z-Vk|rl8yWKap=HaHZ;TuxTRI5yE^LZ2={MXIN+83#y~*Dh0*BLO^u6ktO*J5?T?LKgODE zhgh?1rQ7m+EXxE-Kv*iDwPB*`CW0s-%Ed73*Z=vKa0imC-~S=&U;DMbJC!|TNlskO;uzNRSqiGkGyAvzmX4*4(9<(Q zYFfdYsHCE@il}Efh0|Ua0uHd{XWwq0dNqBh6n`QFq|hlJIQ2LrzQx`X7RAFv@DtQG?QrsL3R_Zt|8!jPNbQs zke?l-t7n3|CK9Z#r8*wQ|KjxTuNeVPFiGo!ae(L+0FsfyrVZ8ZWc3!^Z`gDYqF`m1xC??~aQXkqW6gB)nzN^50!#cF62kqB2b zv8|$sm-*aUhDv^VfIH_;^6BU2xieTGT)&=!@4Q3%j&;<;yietdT@{!rdS-}gXTIi( zudmTLVUcLv$&q7+*tMydny6=`Tlh*4WiOS@+o)`Qxe1h|=b0Y5&-oK4IC=gaeOWiH zyZ3YC=svcz){tBxclkwK_`Jvy!?Z;`Byo-uDxlU-C$^FiFpyOPu)f6sNEC zBgWRSb>DstAKb(G+UV+Y2C)p3^azh`T;TIhPjkI{8adI#q5TJW_sA~lV%`@N+B7NT zCK>7NWngTEybz;lZ5`Fg@Nb$uhr*PMey za`?W({1PlZ$K>EW&Y$?2lNTP)pYyVA?*R@UX=ht&4YAjr4(H`D)mer+Z*uDMulW3% z4syO~w(Qx@p+kGw(p*7cne#BKWVjQ=7sarcr8S_5AP5Mu14;ZL*3lyFV3L-7KcVF% zk2DJtbl<+n*I%CI%#9%&WlikZx1YlYcF|THUVU>Ts~BnY;M#dU|Lio^d(t?Q%^W>? zltcTrQ6KZXa2+i=JHr9Za}w86-6x;bQhft98TwoMk?DZ&FWL3 z9|Z!E>?dBehBn#5(8vU{Sq05<5J)CyD6gTiEP~Iunt}j-Oo(_wVG`wK1mzUDbc()# zNeaznco*@=&~h_Ojr7wyqhJ!CtRhJ`pi!`1}F9bH8gD6lR8bc^C=p9iX|b4zFwRlnIuWBRlq(f$==L;3iR3K{()h11H`Vx-!k+ z{cD{3;uM$fjUmJuIe6$D-aWL9+L&(dTyTMi_gz+y?X{<&3g77J<5UI z>#2?VSJ)8n9kC4ZGebPMdX7&&J4eTeM%mh(95`~21H0Nt_#CTmL&{Rg&kWIV=2O1- z`YJs$GBq2vbNJX{cC4!<9$3jpnN@(PFf-c8<&$4=>cV{{tS}qe_wvDe2WhK|KgT0* zC9%NFGuC^T3#U$T>T)+Tt_pS^InL1o+i0s#5?F5i4I@jcw}Z1^77YP;Zw1@-9OU@B z`)Dc);9hOfEz80LBTN6i%bfb+6z6UYVMQC+{mwBC?b$?ARb*90)@u1lx^G|M#206| z)-{8-x{dZDM>xEHE7c*_5_)N(%%*sF0-jF<^6y5Qv#6?@#lD6nOcr~p@5>9 z2yPi!mY12nbp^0=a?^v{zjB6u{HJr=PZ?CS?c%_Z1MJ_imiVgG-9hf0`jjtET%$Mb zpl;I+jvhP2wzgX0OL!$nz9coRTRC<-foVN2b)p5ROpOfE*FDUnE)uG4V{LVia5zkD zOC=Gn@cf!eD~VBHYWNYCPkzPeiw~J1!sh+$eDK~uT5Dp2UdjCORbqjWXRPNA7fzn$ z)Ri7Go+@@9InI&&+i0sx;D2EhwgniZx;y9{N->$2376H;(o#*(B|qydWSN+SX=bLU zn967%x$wmk_*d;Z+5|mA-`z```tmdv?u;Urwb1^~I~>@vku_zZ)%T8Kq2|Wvx^&VR2`!C(JW)V_qhMKncAfP>4JlnMs|Fd{+`DS&L|)U zsBNewRc$g30*+F&0Q`G2XovBy^TGe!P z!$J^c98M>)^s1joG57j-_f1ZHb&ea4CXvfqX+QQZNA|9#GVH;*+Kd;=qL?0_|G{;> zIenRq!5pFHog8`Z9ojcHkqo#NH4rX-Dih04DX0b}0+Qsw;gDa0PM9d^G5YRaXalC=r^eQn*n~Z1q`kT9qseYPv?B)IU53->?fzP?fCe8D( z3^Ywc(~FU*^88%(6~A4EN+#9K%?sx^ceR_e9AneIV|;jgFKfy|_+5)QXe^4s?8qZ- zT|CR_OPyq#qt{+QkWg3_x1(;_~-LlzyVg+^axZHgEl6&B;d0tq%DCK@ zVrrz5M-Ly-)>O{g3Lj6BU=|B14|R6ZJ2XyOm#8c&qpU27LljwM9cr@x+ZeEd2!ey&fRXnD>qOX_TZ2NOhY9<)yus*H@J3x z5Y=)~(X^fBnk3N$c>_%)%}i>T&cPW(hlfZ-1C{XrzPTI`f|qD{4Xx|eaJBC?lf(D9 zbg`cL@*vF>5xh4(9>G;|DoVLpBn zRZ)sYG>YMfnx;}v3KYyIlPp1$aLCepsv12z!O+ksLz6ii-Y{iVb(DoYB`+!`p`aJZ zQkY4lxO?k5<(1`xoGp}xy*Op5I4M)IWG4H$eD*509}JNdTvV6Wv7xOBpSzgrboIT- zCPrxk|4G|46jh(kXKI-Sx>n5FKfkaN1O!nk-aEzczryqgJp*IR=5@T0Dk`cfNd{y< zz~OWg@Vn6SIi|;_xPIk2$#{&wmRf?IqTvNoM^kc44L{)W`CB~fokVkmsasP=eN7x$ z5Q|XK92*3C>9NsYJusIK05C_pnoERE_tbItRoo<;(RtF2Gh_P9~vQ( zSFxlJp>U9J=!dR}@cps0G((T>aPjOl9!(h3ZEj_E`*zkOeaM!MrapIsfha$<7&8jf zj13LbpUNOOJS1vbsEoLAm#itGw~94Q4K&wx(tT%??wc36Sr;SVY9JBxAPGe;#+i|a z+_-j=JCDXOTuCaMH?XbiaDhauamkxXR`0 z4;fZ`>{!2rJ-atj;g>LVjpufSAUvs|BM4v`80k@Z`bL?~>bL@N%BpHf1|16)S{8<` zVHi(qp{8n>ro~*LHBD1d3WWt58UmtR%!MkL8u{sA?wq^8<-2`M3UT&q+{T`rZ6tjX zmad^bZ{Z^dNMbQ+XVqcpWG4E#bLBcWy2i*mt2w-PFI(5u5_W;EzDReAY2M~^*VGmC z=>Z<}PEs&s{IM#kD-wh}3pNxi6J6IapZYE-rH!o8uNXR-s-h@`Ct4^LHwI-%#4-v@ z^mlUg)CDg0O%try&emN!*w|W)Uoz1(^@VL-sHv7^K9djEvQ$*vERGG!#58nNRY57p zPjV)UBC_=4JgW&y&oI{0!Nt>8xSvueYu(27-CJp{4CAm2wC4^~K#+<$SGq5wkR~-e z$UrKMB|3>#w@@ATF3=|n(=;%2V?nW7gMv~_8DL=*qbdyzRaGb$!jnL?(p*gxEcC(* z{daG2`SKke&sbEi-@x$?_EDd3eKjU511&es{fpriB56wf^|W5!&8%VT)RSbd5oy5 zmAK!HEQ^Sig`q3t(xcqIdW#3WW27wy4Q1t2R>W3Uk=8j(jZCVKJD0C>qbr5tu3=ky zJ6qan2s@Y7U0ITl7U*taqK^jy)2NoCq`UE_Q)(@$yM?086&F;PrjDj6s7e8IQQgfk z-v5v*r_OU_V1{t*j-u{1SK?c)?#eDa0T&+si&jh)STe(*V$O0w5OMh;MB@n(G1sbf ze6aKkqdgs5Jad%?;~G`#T8g?`5kfYX&|Oi&AuZJ1S;mG28BC?IWH+(u7OG<&+zWNr zD5hLpsJn`yqM0S##hlk&WnmhgIo-v=$j{Jw`vzC8+@*I`pl0JH-hIEF`nU^+rK3K7 zB8DJICC54^k#GQ6(3u?{;bF&hE>>3(cD7L+_v3QN2o#GzrziTkdFeVg?({KhI*FIn zv2AlLevfnY^{S<#X2X9lTLMW z_3|CM2WBwb3F_)=si_Dei2{~w3|O_;#sC|eMG!<6@!Dp#?cdA8p)a}F+rg**-@j$J z^ALNswNM>$pwIMi=gI{x-RPiyTEG!#Q z$%3zn=KViq_nHXKsmzKzqaO;>P)SdWks6;QtImBGO>||J(ditDrei2+#s(kLbzjF{ z$~h`XPJH1qDiT4wrA_)m|0TZo+b{T=Q$0l1Y~#a!{y*@OT~$P784xL3w}VX`z4Z1^ z(b;pIfBG+zJnq`Tfn6J@N%|4gG^39naO1*dE_d`XnKud6tYbs_F?QGc@w-;t6b3M{ zOqHpjUQ)Apl=%;`!FcZ=;~51D3qzS=sJEL3Qf7Yqip~JRNSxY=AR+>0Aw z;WIk=XQ|)!bAJAdpL2Xe01$8nV$^KdN_*3NrZT+@-a5tKP7KiXa4)+zHIfWF5DGI4 zci-jQsSDidoginqNUYt(j%}N0EpsCZU@1Aqx~_2fb}!>ugV?$?#N8H|p>7@wz2H^_ z0m&64mPk?-@vOql83SF-GS=72WZqa%&{Ly#c#_$?j%A4y(qr^?JwQ!)=kwu;?kE)% z31T5PA_DsC2=~wYk^k$r=SZb>cKrN*=AVDGm(4X^0Nn99>ep{!U(0>|;m#+Bs+NbyL523)@qp-0eI`f9Ey+{GX>8?A=TI))pde zovDHQT)%LI3)ecC)I8L0X<`4N?IfS;y=tKY7MI{FoE{JeXM`d|7tmk5*Eh@ZoYuSh_;4=PZBy|9-}$&MA`X_Vd$U|4ZK6 z5GWbR05qmY2AG&mlbg558BFvJlFDe9mW7s^X1KSThjNxVNf(?xLXjlZWdQ_bmWlq` zoVxOe!HGPP_4OoT0o0K$9*w;CUPWhsSUgF2+`sBP)=eeDXy+BK-05Q?Ym(T!mblww zW}u7N7ab@F$nGGqL>bAj2T2q#b5msQ{+WOCZ_hJUaMF74m;CyZciCF!DQ)0b=vtPs zfdQs63fclK>>C_sreI)Mkex}<*YyZ-HZZ?nkv$O-$pp!W2O~4W;|I4md3^xg5=qoI z5R??A`W`X$!ZwRYo+wr2aiT#tMdR8msi7gJv+9EOsPv6Yl2HvTQzbn)LT~3ov|y>| zqfjgWn@kqZv$}c|w8>5$-oDPcyD6+-l4NxSZgrZ0uH1_c6hvfyIkgpGg5Kg>Rh#JI z+@F5WUw_eo<_>eE>-nHSqR1<8pol%O&h!RwY$ z$L?_T`dzMfPT@*6kgQB1rN`*)oOtoAOHSlK1x-}}T#nVXOg7aFvjev{edz(+LmB*y zEtFNp5hi-*e(`M~I(!5p398G2$dZU@D5M@<;BS8SDJO4@P__LyAOGT4{KbxB=?Dv5 z&oMJLLTW0rpva~{daRF$bOGJau?mw6KJFr@OfvV$6CGZ{(IjPw08Xnw=J6RWTcwx2==2eal~a@OA^W3Lwr=I%rbi4!O6iUrt?R7=JNL8a4HZGk^SB{`!l1Sb+owfAg>T^}#x-B2RQTJ3U5fY@FG7-8IS2 zj4?c!L)9%zA7fB8G77q`A>=0+ z?CHXn8(*NiKEkmiWpO`FE6;4tSuWgo%)pdJsHKKv$W3a;< zIDApcw;bZ=)(2#=54^oqP#j&?2AbgR5Zs;M?hxGFEx5Zo!QEX01a}64yTjmagIjQS zIP;!U|J`?e_FYeP_f*%~d--~v6CbZKjp_UU>jj7klvZL9aEtWMIhA=qDupF+**V43 zZxtS|J}L4WVESvnDk9c|yLt!lNS}jk;XdhNXQzn_5zHW|F<}@_IA!7w_Mybo+zdZb zKlF@t(ZWpJJv2l)-&473%qI#_SGNeMUWlTTqKa~~!I@-|KvW5#f%{r?3lgJklFxbM zZZ~N-DpXJ~Oy3O`J~zp>y1F38oeZ4FqkpAaen^K zExtu}1fZa_)w!RQM3JGrxasU8QVFy!YuaY2GcOs@5?lj|qRP_i+#Rw5q%_b{V)1&k zoBiRCg_|9&s;puz%z3)D0tyIvL|NE#jjURb8|qc2X}ey%MN*>PL;AM zgy{c6F?#EcV0Z8a=}n^>O&oTOJbepn$U0czg&I>}Sp_y2`OAZzd9_H8QnK-OmrjJQ zuaW_{$yV9m`7qU)#CLez94^4;F_}j-)9; zTf?B@%f>dcv0e8``S0vXd}{P42hKY#d`{JKNuPf5rQs2Hc=!~i_?c>A8$8dR zZbmLlZK4d)ipe>F!$$s{F@M*t8ZY&47U$aCNrdypZx`EMk;)=k19lTO_>aV~qEA{< zgTZ8RGo989uL;D)w)R)hr)J0o%q%%e(I;PW9rSN(CYxW#<%eHiWE7?nx!n*TiE`i6 zm@_uz%9xWv7MuPC_6PcRg7MXPp-qtM=Qf0%AHg;-5wuF9Th0L82ms)=kKJ7vbUzK4 zPPOJ+6%tlj-u4w-X_45AOj*j@BeUgC6=qZK=US77d=$8u6mwuzflDxC)O#P7$o zZ*P+Wj_Kd?=|`D1nth)Zr$NS_!wBN)a}^GXA0Ljb8|-6e!4Ft$;PGIAQkCDgFYv?d zOjEW1(zZy>i=ERQv1 zm)4tS$F|Qn)3F7(B5uX{bJLFuBgaDW_I4}{wVOXLFt|Bmi7iM7@1DG`BZdzC4Q~8I z4U$~vyx?8a6t>++PJ^7fs=}xE4q0H(I^ra0IYl%w!@&Q}S89fObhM$;KD2Hz9sJ-^)dBwlmIa=-ll7CO(jOUFt@Y#XEVOEq>bD}mO z;0Fxsk;6R;2dBbgoEp-muu<%f`e@=ASw+zS1#dATy$7Nlt5+Wk!x4IU8dH_gKX@l6 zmh>rQ%A@Rlw{ihn{uVNu*pxIMYv-Mhpbo-y!!CKT2uY6{R?CkIN1jjGAz+Iex1e5b z$b)Z|Zz5NweIZ z(h+*S!)oa+>3Ck%vAD$#pPPibq@bXmwp$tK9wKY9$sJ0L=G zx-)+CnKcEFJFVSUnrplj3~=@%xCeWYT6j4RM3N0=p=#X61ykT)6{#4Nc_)#ow;zm| z7933PRbgXoa@0pb$U76O_fsPtzB!R%kzd4yORSGg#mDh>QXF+z*l0MH83g=K|2Yb+ z#X9P^QiSxMv9u_@MKLo8nsJn|XE=&zX@I4&!n$WBVXY(Sg!4G9tBv zj-d{7DQM!yrMIvtmGR`Z&qR|^*l}?acgA-|+{3pPtCxxf1wWSc^GJ#$C8b-u`!48L zmZ*c@dy9a8)`ll5a-84app*ESjn1%v%L`Lm*R!ypD0@xVzpTB(hrDn_m`Z=r<9tCw zBvrdhHT-T5DC}H$rN4C|QMi+$eQcJR8XX2Cms&Vg(A|VmUR4uwTm8P8%<{Of$oJl! zU4nUK{hjf-&i7im74J9s-2~2zX*ne{RqDlQK+?$Wi?&ww>!UC3lN?%4&NBTmf)5~= z?}%c{Dv0#YootRsUlIj`^3T3zl|vtl^%VZL@}avILl^bfLkx`^F%2dE+F4sR&1=Mj_x9_=$t3}hEe21%B`*^=AF5h%prC0td0>QEVhI+D#HFt+m0W{IP&#N8gT#&&1SVcCiq<|iEw(7qaXhc>@n(jnQqm#PuN+BXXqxL#p zD3#%pYxFpYz7ov4w(e%!R44Df1&5UprFR+pOVFONCCR(ko_ra=%pH>wmZ<>D=0yE( zscGh~17ppkJLTc4NfJRXR9S*DPcQ`<)$uJ>@i)!OD zyQnev<&cZZL0?JEl+$?&5ywQcLg*Kb2nS4`Hg3;E8v-|fdVl|q{yjvrxJgIOLag+7 zIu9Pi^7dc6p9*Nvv-CSG*O?+5`y+d3hx3Ej%$9|=^wCAh)68d%U(1BW?GzCw%bJxv z7{Fz*eNbaB2H{gM;@#N7*ipuVKN~joB#Wl8=4kSTtm4}a3+sf2d|z4BcXz#DE7A&Z z@03ZJVhAl+yPr5YI?|%d=w*NfV7&3LTaNy@KR5=C4Wx|gcv4qds*?F>2R{mp-G!xT zPDaYBA4-mHR-p3YpY|3rr~HliD>RWQ)8d%E53NRV;^$v3{;RNo7#jeosHh5Stj2QT z7ckK_)3h32SrxPNj>?ZjdBW&x^>Ip3mu+~csNo_osCvM33-^+oE2jiSfmXgy!Gzq( zLEdLa`}UTETwk$GDv0U3nLaT|k~Y>R$Jg7eTgGt8a-|X>4h8s@WhqJ_&^WVw7P zbtmf=`s#NxV;u+_Hjqf7wmy^f)=kq0ZMo7(iAY1Y0x1?bu~rn+dn=I=vtqSsviKRA98)oUQ<@O5K;eQ+W`S-#{gJ_-}{5N|KFHwVTZUCNT zqxg$)RTa;p<+b1#Ck+Pvgr_L=rOCQtDH@BheT2;5&Ka!P~V}k@9%tHuXYRTXWXBR#};LzW~?xtNsV+ zEqs_;T$s*|8<<8kt(Gb%ELIqovK0KRDs8EhUvMO88=O{6@w*^6+3DlpDNxkmnOfmS zJcQ-!1EH?T2`F`kJYB9cH*jTzFwnKHc(BXwHMPNflgm#X}}_>qkyPKV<~-v zaBSghy#D|bHHblpq4EPXA0nCBKRu~yn7R{?l_Z}$>ZT7YA42?I?j|0rb2F{8fh@Rc{}uKgI5o@cb4 zsA{p<@8p~c>fw1xB$VSk{;dDjAjFfKt2a5u7UaYI3Nt-1RQh+^_HH902X_aHzWOnZ zAa+Vp66W&|#0SWm$q{ej6;{?_OcP|38j`AaL_v~B=*)NLW?lD-QFUI!RGM@@KZ4Nh zf6o6xz2=@GdC~KF=~?TB^(rYjc-CduuxPO;Emdn44C(X&-IY7d63d_M(KJB`FR#B@0N> zH@b`U&*JhWSJ%|q^QdM@F#QriBR>H`eKI$FIk=ERbAH-YU!*+j>ZSBVyUd1syJ22d zWub%^nZFUN{6xhZK2Y$dl z4PgFp@#hajx1rAC&R?U{MVKX`*3=Xf-ol`yDO^J)e3nVQf4%i8N>kThmPe)Cy`i#R zeMQOVTpzU=vfnm0n82pgQK`nJior-*-#SVe=Q!z~po&4;G)~q?<0+vb{#P`h)abz2 zXT{sBaGI4%@4!~s{wpk!mjB8NGPKwk;~MVkmK@ghdmp+JEG9S*3o4@%yO3zxFW^=0 z$CFl7!_3(tOy3YCw?)03*s}Z4U=}>aM^Az1t~LCv)_D1~K)Hka6T?;ct7U!gT6WRJ zOS0{X&pwU#vSmISE|WKoiX?*OoGM;G6!(Oj#2y#u-5ihKJ?p0iFIin@B?wrC4!7)J zb_vT`=?PX&2t|;VP5I-Ik7I9a`U8g{Bxnu}Bgul4r+bKV#1O$bnY4)i_&!y7C-<**K#oU8jQoyLA^-Rav&PQMl}BbW+x_;`N@6}H9HR`e zj#-)qpN1H5?{T!sYhJr|2U)GnnWP|8Zw$xK&~xvAv-MCFcY=xBoxuC3jFpS%`*xIu zirR^uQ)no^@^Jh62>jnO@a%6pK@oU{CTRWFcdrW2wNQb&`DiDQ4?nTfIXMk`h!5>n z7#q!uWNfYZso#8|+0M+*B|W#OFb8b6!bV8Q(`hM);kRAu4m}qv$by?+^hq?SDvNGN zKF)h+RPy&%q%LnrP#tObg<^#<%HEehld~uFdT!eoCkFlEphN2nx_&6wGd8;;*B!iZ zF-%x3iz$BYe3E*DbuC8JvZKYsY~U~2np!L$ zlMUX`Kp>EXk5AUrlw!{2ySB}(DsFh+)fJ0kS&El{LtqC8LS4h$%q$e#%*KMNe{#6e z2|-Omla-nIyRFT;B*)|yVa7eLuTS(XKzP>b?gUOLha1IU()Fp!Bo$*Yu#`RQMIRV z!9P#u5lnGm!i|4hXK#LUgm14k)xoK(T;qGh`I&wA#wV+x;Y)mt^ZS&qw5G!m+qK>H z@o4=Qxb|LCY`^IbVC8WC_*9q|r^8BgX~VXgts2;I+IHg6Y{%QeTgSb^IBu8pT&94? z=&~vit+B-ygM2sZxg@Q}aX9MMy?G{NXJ?nb8MSQ>o|I)1Wc_6>h$om`%F4$VO)AT< zQc1$?O7InY%l_?in!{8A{s2q;_n7NzXJ1o`FcppaD4|u%SL~8R<{)K#k@adq&9TBk z7No}2Gga!Vnn4m40{f9 z!E{0;Q>v+`$e6k!b|pg+C7MNP3rIG$zjPF=G}g<A4T$Z{sZ7fyV644b(moLTZP11!-m zW&{?RsdS}iP`{jbI_DIgRoK7bZQnj$`E)UC66R=$aOFrWyXzf+Fb>HD&2^};5Xj*? z3c62#5_D_ruMc1tO%{cD(5aVPW)4Byro&r6kG*!_0BaM3$;tYO8(-9riC6yt!$zf6 z$jF|~3AG>d*=B!+NHV3#H56yFyR^&fsV){(a3Nfj_^PK+oq3ja>2s>*W7VIYI@FdC zdq>&slKn2BQ0RQwWLk7MC_B?$1e0v)loascB!2DEGd62`B7S-g(64P7K->YNT)pz5 z!L8(&G04|q<=dXlj~AWt0RVu9mR-jF#_w|{O*O8L@TJztie=7i`cM#}zH0v%Mdmr! zvSPt|552v1dYaiDEP-7Ili>XO(5n9gk9t{%TlHd6~;GMmFyx1-8EQW;&gNL ztK~5%6GCk{lEP^RU+F?B9j#g4;*bMBkH!+9I(oE{%Q*TkBCv-pVit!s9_KD%(nc;K z(kzWhR{XCYj2}?ZQlb3G66pQwLzTm0Ek{Xf;j%Kxu=!XBx< z;eRdfi6pJ|uUuS?Q0ZaTS=u<->71XYqG+;#;!rys`D=r03i7rmTmCSjgD*@YHMltG z*2cP;C%g!eMUk`tBM~iEz*62VsR=O=H0VL9*V+Y(`9TOYS^JM#qHbN<`@WP{jHJO` zuaA5haFRSW18?R>14%wVN;QqC#m;L4DXFp#ti&(wzf!XAKhr_*g&f0%2WWurfV(&C zH@x(hkD-k3_rI)-ud8u{yvsnH`Cgz~bf`iOA)}#=>vLNj#5>vFUUUt23OYBGh*K(O z3E+O2r=v-eK3v~_-G}+pwykxJ)`iM*Mdn7Pzl0jBaxzxSs^Z#?8jt+R~?*Atvbz~BT&sH-;v&L=q*J;gA zMhME^v=~&Q&dv7dCTyE2*fSU#^$VVOC`f$w`?>RUYRC17ZQjIj< z80R2cz#VVYTJ5De51yDJsn<&v=4x*T4%X)N_41HZ{6osqkQW>NgS}ob6MEB2n|dpa zwfL8wTyWaBy1y0%CiL5{gGTnA%>|`qF^dDvxgPB7Nr|19*&3Qykn?`{vCl*?#m)r;hDH37<$Rf(A^b zjg}d+;dNWT@UyhIJOlD})LD3bcINR~f-lb3J^05PGhO4qzy*I1MT;5@tMvamzVnwd z<*(hm@4aBeW#r2{y};I1N&#Q9?5~XzRN>6g?Zzev!0xDmuIq`(|4A^3 z!rn;xVG=8>pjNRgyPsmLnX$BjT;LRs?D;d(6Vxsmvlw(2;vm`K6@HXUNQ@Rw=!~V5 zB*?5%Qw3KU=y1{#Rvn_IrWbe*_qkb6 z@aCVRSJkxAB^COkTq=~+EksN~MVE926MNp`OPDsM3tzey4%f<_ zSvp{)axHGKWHoH)r5n*>CS`1WVLwD*^Uf!6@5y(YzeU4rX->@(N{NLIsF*~t-;^Lk zSBi0E*7Ids-9w-JyPF5ujL^ymgIT{8eBw-~6|H>p4$}NpvFlql_b)<>ecmUJjXeAn zN@~?dsf)!2(0|NAS!TJ)YCvlwCL&9oDRLVI2K}6ovQ0q_xkKD8i+QED!1#|+D#?!b1Fmf9i?YcBu+XR$^CU-`Ef+FAA6e2?D!bxve~P z(TrMyJo-w8V5Y-Rd85ll_hZztkVWlsv8Sj}iTaozgt(b<@N|5}@|p8R54|#)58ORa zl;{vp+8tw^EQ?TE7N271YnC{$OZ2zDqmyApqs4KymK9Fmv*?^RdHF#Fi$Zi;5L!U) zqRP+BEbuL=ri+_JqzxgXsCi?F@r&)5ZV;XJ->61_!t5-RqDaD5P)U;H4`@>f1Zc*= zi1^@U=#)~9A;D=hgXZHl<#l{6YBZLmp(<3eCku?U{6j3i5d-B3(Qbd z6gZM$nbKRV2~KrU8z*g722ebcPe*56x@Usts{Xp!EjXhG*u5m!0c{4Xfr)T#Yb%Qu z5R9%Jz6VGizU6e<4y>M$U148l=NB7w+xcp^G#I3R!&!~|qhiKzPH}ntP@}1zetOw& zb9KR6@dSNIOe1r|U) z1M9eK|8bW?a17l#l`b~GoJfftQ{NIOy~{D--7v?KaYubNh12<=*xt@(W!qqyICyE# z&T-Y8kH2bY=}pnEBhkP8Zzu1O`q=8PAME8)g+|Q2VgfHxSQH_ZjQKR3M*ej)bi{;0 z6|;!aj1*uZcqh!GDZEmBv?M+%9AyP{h-VUqcJbdaC8R}13YSr0?N6F+u5T94FSi%A zohUG!!?vAJ_{}cqD;F4uh=|{7FVGZnlNmW;;lu^0V=!Az*`Lp@Wky_J^J?yZvHzV^d7)H*{Aor>0Imq=G#UMS@s06Oc_1FgR`zni3ohfaQy5 zKe^*Hegbiqs4$vG)c~(&BM1nOY__uKm?C}d?2A`AMPYn5GTY!_tPo1#7CY--oWm?VT}y7PJ)W$cPJLT-2RObv zNp_EnoCgtZFv>hTE316{Vz}sn|0!Qv3d=f!9FVcLfgs-5CA&(bkcP>wgK@7|NXlxsIutuUCuf<``^XJAT z#@pNJ%4wBvzeN9|Qn9ZDXV1jO4gkJ5gcd*Ht=_r}jLs3@PdNl8=1}a($8H@;S|Uh6%-snPMj3cab+3u9OqCu& z0aGWMyVxWRHKUzWO0UQ9fx4N3KP>K;-@1ZT$I;gGjROL*CO6TNR_Ip!qFid?>5mi5 z#VAdZDca0+AZcKnt zo$5H%N_K&HfO*V$h}bTT4%m7&wE8$ zbf{}!;h$JI!}pc4mTk=7Zld;yXt!zzsMCA*{=GLXFy>>d>6=?Shc%x=np|^Owm}?J22)2KBTIhw_~uYo zkpD|>qm6(3XUn&;Yl7rD`h{`p2Td^Gp026=>u=}yL$IC2)<8?T_o?RkR`a3w0^`UU zV42!iYuWiKc=1m2OSUGJ%(;H7|IH-CGa>npE0ye`WvA`%h28Kb@lUHeV$TuB8L;dr z-@kwubDjO_hc@o8*j-QUBoyhQ9VBB=d?JFqz$WC%A$mG`jBP+XzOd3Nn1v;Z6?&qaKxRg|zFspQo#^-<+w?A-c9KscF zD?e@ToXbSc5f?N+adl2=Vc6f%3_+7br1>pfM}K{Hn?;dc?YFv$G6xzJ9{3Q-RVBn< z2uTi8<902^t(Qu@$hQ9b(@y{lc%UmdGsDNb;q%gg`{Cj4dK+f}dcBX!p!xY$Ju}nv zPph-Tsjs8##5H<4cp;g%YBQ=#P-HsJnEE1?b>Vc#A+cNda%oD2_#D8;J#hyluUeP- zgN-@$Gpf&*+uE@aygLh3=yEaETDLdz(4?Z+*}id!g=odD5GsHvZC)H=S%jQ(2n_63 zJ``J)W)|3JUaP(Xr&xR1C;N<(?*LFbD#KRIJJ%j_zOI?Rs26MtdqWOSg?)+3PYu_6 zxL5df*ZNlF%>tGY69UgqMo(@QIbNbgtEa_v6Jd+L#cFV*X%cvav`KN|T+o<}pQd|` zN~h!B=TH#7h78C_eZrwO^?HUwH2H+-(@)K+1luVLTeOg#)&X#BX-kl3W{GetEi!Wr zjTyi*JT<>>D#O#Qe$%PbbEalT{{%PH{3~u5xc@Ut-3g-B%KtSWW{17A;%1Po$SF&H^~bx%gTJadw$31D<0N>k~~R0$=>s}&@8cp_a?g91N6xI~kOF_zk8 zxiJ9Ncf7!Nr|2+ceE*n&+CJh9MMUZ@lxAIO&-86teAAt46ul0qKZt?5EsmSi#|_=; zD1ky&>MqU?8TnV!pL=RJ52~q9nBXG`!9)OqmwLmSWtO}*pg>)$f1wR4PFq;xTE@fORDey5;FW_~E z4_~+I$DvisiIUKET|piCI4y^#+r04F+$hF^HSGa;);@aS6^_xxc_V>PN%>oT%W#KP z170mvh_y|gpGmBI`N#o+-C@cGLZ^v@}b1h0HJcv%}@-n^=kFlyj5N(ALK@g^&?airPJgcc+^> zPeZmDRI_ABA_Z|=V~Zc~BOtR_J?n)8Wb&s2KE_Y5q{xub*`>aJFG1)qWaN}Gdi$#quT5Rk@s#GP*h^_DF2Hs_)0INw- zgqT%&-s0&jOwOi+4tqY9QCH=$RN_1~YKV~T*IE9#mp8K=ov7_fq2t7(tZoYLH~qdj z@}z4qq^m%yBX4&oD^oX38O4bV}6?Wd`dm3fimxt2P}_F z3c*V1{5GUZl*va+uxBR{q{NU@nbCQ^4I$+!b~B$U&$#_#((!$2iiI7}??Wq5p(@#> zeiIsAnK~xklJ)Tf`SCDB|5}0I6OkjL1nUvA6MTe_n>QF0!3}qL3Fz{akNOO28HVsW zGt#n8okQoc6g~?4IAEP9{GL6gSk;nJOAQMnQ{s{j2Gn!vY>}tLI%LTgP5SNeO%oWyTT91*a}L^iH~0 zLnf=G%IL9NEh+bC&X^@uS3wl{HOju93dBf0iO^rtWUpga)+htt%TO~ncuIq!N|!W! z`13O3FoJdMuP%1bJ7Px8F2i_bwUh%tsary79X0X|X%?y^Fka>SK6Xa@uFOKrWFo4X z<9bE7QL4VCB7h}_F)~t3e9_PmC|~-A^!*UU-*7$6{ksNTik#$%p@GTEgp36@rrA`C z*0w>|kC({2tm$XR&vS~uin8UBu=#(#5WRE7`h0EHB`Z+GNC?Xk<}(u}q|lhVz622s zZJE7H*$nwmN!fX3jg`6D5tmjhEPjJMsw1mBl6lDJ-Y)ojRy+KgoGQW22to;eA;L9R zmi1;ULw>)p=8!!;POStDJC5+zR&0 zaMS`{gL?eiB#*0u`&MP8l)gj^1^rR0NWg2`$y;|9`y@|hQ z6KA6!QPwiEaacTmI{1XKno@1==GKuEmH~?#plDV3gSBm7!;<8Rx!`-fzrM&{?s?+l z;%Ns-=7kC@z+kad=EzcWVE-xd&*k@A`3Pr3hq%l_doQLt*?`roUpxpC=B~# zGkZPm>e|HFnPo8xzXYKc*r72TTiyI+pE>9?!J4&^U>oC!cx50Y8R8jRntgw^mu$~r z4V(@-uzllboiZF;_KGV&&MtMzM*;}F^Ric=vsI>mqI@@c*nuLJ3@9m)x?{<3j*T4L z0~@-TGyM^MGsL|wIeJJ>XIrGR8KS+r=ax^Cns27fmn-UdyE>62%)(Tz9*RS2V=Kxu zlkt43T29l#Fiqolh4*;Gfj3n1Rp^x#s0Q5ca3^R4g_zxY@ys0v*_y?wHHF~fN^@HN z_10BS*H*$^GI3gP`G}qCZlm8oMOnqd6y_Pz^wr6Tk`8=cVdln0w{WCKYwy47s?}>H z6onE)0TcTdMB+f!5gVS64XkYoek>E;YRPG%*&p3aR1#!)_eO0Se@qJ3oe24vmaH@tC&29$$Af=$VzL;VVwpaOV374P1<| zGR)6|$=CS&F`IB((^p%vbqoFePA|}q+ztWxB6N_ortO2rS+7UQ3i}y!rFm)aR`+9i z6dL_9M~=Jt-lZI`t}YlMh+(P!vvQ+lCU%Spx2t9IcEc3%{twWbf&phsUnV6*=n`Y? zSlHVJ51qf7u9G@;eG*)3T?{On4A{*SYRZ`<8!sJ|KE3V9XkzdK1@nfNXJrBN!MA*+ zFXhnjkD5<6DKx-~d@^4D*!WmyN59A^aLg=7JA@Q9$`r%y3IwyShHE}wF%!8p_auzb zn6|sUXvV2qr9GFW$k*ik)?LTVZynfdAoJnh(7wYzuuC53a<`y4(gyKb_jF=F4?j9<5IcS_E4^=XhG?G{x8w+k&!Iii-C1JF`P=Qd3Y4hW$zcW__!;& zbvXc!e$AbGSKRuS8*H<#bYT-yhiE0?fbkb&l!~$GL@g=7zhiGI_xyo%bmliSzVZPt z;O!NGb>{%%06Og3G;Ze?;9>M}vk5cdlJK&PswhLOmQvIy$Qj;TlkD&%ES|U%1bhaF zgJWtS8NC*t&g0eEBip)tRAA|!`BXet=Gz-$zI+YFm|PQb z?5qYaIk6C>>c>aIgJp;=DW2ic$w)%h8lPx$6RQB*aNadpyT8MCm|s406EbcI2dlgm z84ogH+)w+EsABImcP+ZCMmu5}Ro3wy-@M;iM&y|yXvdlSLR#t%2darEM+29kInr!| zrVigYjO1(486%tS6I?Gpc*ME_vWcjX_`tEMlt9za+y(?YqHk{KlGlqw5K0{+SZT^& z&HUpfuL20X`(>9X6BqN3UJVirhrb@%I1bZRq&Aij64|i`H}~#Zq!yoJcl*sv)sP7b zQ7qSG%c_;9soE(C@7&T%oaL%JKf&U51tv5Q7^ugHZm@b+*=}&MQNU{yBfmFj z_MDN_SmJQW;Wl=UlzbFau9VPP!@^8{s-}j){ds7vVw&nn`T4b_@MS^Ch&_CZ3L6as zOZ4=z(kB<=g89m*+V$d%4({=vTKtSC6bsRRFwy^N;XLnNLnPe^#mobq-VE1tUz|s^ ztg4GNM~7OnUfx)hN|$(~ZChU@;pk}yNeK02VKpZ3O!z1KURq?*6I`^{9a(%VQ)df> z_}28b?;!4NlH3IPr`9l(@@vuf;aOh~u>2v3cgV^4$YO@;$=<~HCks5u|+}S7oxfzY7kW=V=RLMvS z5t5i;xa!J*YI1f;py2bIRjmr0KHMUh+y8j})h;x}&k{gfqe$fmeA&PE z3bM%Ap?YZjT0HdY`gJPpsiBZ=LAK0JAz;c(Tw(MFXZ=R_z}G4Odpp()_Dyur4L}hGt+8>y9@@T#Yua-``fd zRGw?kerp!pHi=7R${;pSyg}3@suTfRR+F@mBpByh-`0P(4?&Q`W6M78wchpQUkh_- zcvhCqZ*o|i;3WVM(_IEm!WM7zxW+gbA))|6b;n%sH_b05WHeFc22meYP?2X2Tmvru zl`KD5U;TgaAfZ*WYw|2Od)vZ8cU=D}^)yKmFx}OynM;kQ0-L=QU)L2!9V31&Fd

@_n1ytR8lyudtI z&np?3B_Y}Rhsxlux=L>7AY3D(s3Har5 z6S=a=HPT@3fik~w_AqOQrow$Whv&w~Y;Wbx1lxy@%R-66bcIA|-J~h=rS3NVIPMaG{8>U5Ndp)8wE?U3{CT*Q zI#VelXNpujQN(C6x$MWb-FNwcvZ?Iof4MwX<4V!bzJ_1+OkM^EiYAOKwK9u}-9N*5 z{591?z`6xg4<_(ztW%~2gaRafq}SCOz68Y`aB>w%*!?1-zSt@p$ThyKBf~M>@~5v@ zByaPIJRhK3ZA966G9d1HMCl>69;wbC7(fQ6#m@g!ttY7P(&QNYe5V{&p#;h};1=Az zKtqD_6Lx+X_i<>~cGz;SJPDw8#!LCTS(7w$2_h?cq5zU}VwxBE;7>4uvbD%;5l^)2E$;WuQca4E0b8rHi8JRv1wLwa0ghEiVM=z9NLsl}}0Jg*$j zt(4yRub9LI!+}YCUz%}`j(_GnFXBo}%1_62bl!sWVjsO5@TuH_gG%Y$px#=~eJb0K z3LO9NtQwf`U+Z-$B3j&H=c*22_UB9pWbyt6&GpqJ!H2(Q(=mUf&CH&7!a#B~E7IkW zV(?O?*BVY;b4aNEP9FlyzeJR)s+9^_~&_qQ$wj0o9R+Cn0#1*E-M?n|t zQ0O(643xQ#;T*uAAWT%_4N5eqiG&cV8(2Ar=m##qJ2*&+h@ zeYSM+E{Vk)*n;j~{hNFVN3(c7-T8h{|5c*Jpx~X0*>nyw?rFxbl*$1zpP@15z=4Pl zYFeabC8(d@D1GRNnmhtz$?+{-c~Fzny7?WiFMKhPUJSN&4FaWL^L}Zj-ocYF5vD|) z14t&EiYH=jsm=u$+HiAjZ-F)9$TR#_@}CLJI|WHmr(nfiXkPrn1_{J>CgM zJ&!o1T{YTFy2DnL2_iE}F$$%*6E|iI3MQ6ed4uau2I*DMkh1V7TS5KRtxGLf#lb=VxcVWSS~$mVQln zJNr%<$0v~O>-uqmRT`BVVY&)p9NJDkZ%};v*DG<%tD>esSDeM`b-x!UQs>EVa6EV- z&C&7%kp!QR17G$8*X&{LT*NL_PV?N{yjZL?8ZGgbQdGzb(Pja9P`MeXFjn{UB>+f^ ze5S^{a%0qu-6?{{W9Rg&kHCkhgC2fs360AAVuCX%C0;G0r*Imtqj%3X?(JcV1tTET zoR#C_ENCsXB>m{l?$@YH=)eGN!x>Kv%vTkf->I&-VK`4N4jEROQb%1KosX|Zt}R<3 zDi}SDW9$AzO)HbF-0{+>z@|1NIQ+L@M21g=ZFiP!%aHKWMU_eo*%FL28zK$N#5;^I$YkWJ0&Wi=Gdr)Cib>O(Yiy5x zN2jV5NUe#3PR!unVrWJnHmRBny4>&;{cOwI^58N5n8%N&M5dOw83q!k|IiN7Bui$>M(1@`fIpHaE~2Eu4{-3$%`m=tR7f>_brD$@lpCFq!+F1Mn>RK~} zDM;ExlTUsQ)#3gN^7(Fm#oLM?$aS0L=`yH{R1#w?)`AV1R%*7Gp0V8`8{x~U!axqp zKF&R?v@AwN`u6%q?V@yMJj_@X_;ydazPQ9BmZURlw0ZsyN=2cRzHn~$bIZ-ZJH_N5 zWRl-?O4U{R+<50p(&OrTNX$Q5L)!#Ld!Gbh_}86udswT)u^M>RPe|H_YPyI#FgpGe z=>hGI;Ny8_PBs3OxVjucBXD9zRKXireq*|A0n~sY{O0tm?QI9PE`BT&sgEC--D;%1 z+%Jr#>1W?oMw_|Lv3upLw?v#cxCYo72Ghz)Cl~0634X7+Z1iy(^nM84`_rE&x1U_% zg^0UGe%~%>kYfGdK4S^T_U05jTlhtBqGj3-9bRWk z)W|VtX~>?-qyjNORk``w{rNjy;R3CtYHDIbOVjN0HaZ2j&viR+Yeq^U@vN!I{bqR6 zK}egIJYy_bu^?%xqCB3Vy386bQhP&mSSsA>be6}!Uh>CKnp}%_6$3tB2(+Uo>aZq3 z0x`-w=G9Mj{}fko@v-=c&9S%u5;Z*;#rdQC8*}g{Hz%vYQRK-R!99S8J`k71qw1e%=b~%2 zupop(hE^*MY*Dt|f1N{DzCC+!J1A#1(FY1As%bv>`1kEWW3%G*TOx9oaF5h4)(tw{ zjEv;cjX5HgK_3@5Li)nRno}v$S`~{NEWyeA6h@lLj2;jlqLS1XGnbBi4j;M+XcFjS zJ0&f35#6=sOD4wA&zSuU_^2Cmi(UsbL8Y_{jn<8v$YcM0TY9BlcVOQ6oNb{nMPnpy z^!18-Bgo15P9!mQG?xno8Pwv1;SkZ7&C0!tO>nuaft5#UQdO{PDDBZ#V^LV7#pcZJ zB)Zd!y%WYY^_o#iIbRQvl2GZN-8ZlAft-G$?ifQV>E~^8#h!$;F%XkT=qOGJh{>Og zFx|kv+G7dS>p@FO{Dbo13)#eUUhkb-s%&*t>w)a8RijC3a8*07DY-nrjfZ#EclyS4 zDVrRU{+AT>63n4!liTkd4{(c@HeEn8vSzzodrhn54aC*l8b#pWC z&b{U8+9F%_Id|ik`+kCcQMXtj(JYY_Uw*VPmh#=jAU<2Q`e7~k|9Sz6!CcQOB8|Mq zM8xK9Cb14J=X#wCV4*Se_KGByq#<+dI^V2vlx3}9y9*&JK<2f9%Vwx;uT}8FuL4*o z89Lp6CTnf*4=^~IVR7qoaJ^WDYrc{wo^IXN0#+v``%tni|3?0qro);V!(Kon>HfhQ zI6SpM{~Gn3BaWRhAS#YQMR}5)o(&NR1I#D;xGLECQ?eR0Un_-WQ`cFNq)0KE z%exka{^kdHR+WDjJcA2Uoq<+h-3o3S0JOA9YOBC z*UbZS6K&0AB(YBE3eQGwZKiAD5By&vzeCluulVWt5RgO>Q4~Rtt~Wo)Cft1w`SbtU zL;76B5geeS`FYuF0-~hH-t536OX#!;ic+UmQ!gA%m%KaCKvTyEzx$7G(A4C_WjCM` zs#i*cF*XOe^S+Of->8i<$7nzjpQm{Vji9A?G0ad9k!2miH~2{qO|CE{1J7}^#Z{CT3-eAOPvtSfy48N?Xs8{kFgP?Dr zcl=%c_mO6Ld^Ys5K1U`D^)z=+@W+l3eycWyxJ&Yj`ezG>q7F$G5rhVR%CZjK z#Rnw0`ndnT0sn9o%uNLP+*k~MuSW=i4wJ=<)oMo8fudF^mDQ^`&3_^YvI(!T`$`wCU$w+hOD8FxgNOO}Dr>()eS5Xhlo?h<#KFHYnDw-xB8}u*aT|v+xN;(8V zXvnBuKzNaHTrX2STjldlW?4JP(|q$y?mxPZ?P!wSYpP2=4?2608xMZRe`&viB3beG z`EZ$^??ccVj94sY3_3X1YLqMWEAy_-;HGclecaE>z}vZ#-4Se4oT8A^h=#|VS_#U@2}egNs@%#pud(aTdx8^He>M)^M`+QGM*}8 z@&xG&I-bkB0y<0<%Y~k*p(qNqTK!7d@q$i|$<@tU|JaAa)r8w=Ko&Jhf^g}?I>}(g zcke&)e~vYHSCnL=m+`Ln?Cca9@9lzjQ7aVl2{yM9oR{i&d;94O__52N*6SBRj<4@t z&`IbG^0l=$UgPiaIvDV?K%-vE6F=Bub@Pa-CBV%I3sNn|>G3{miz3=^KV5B34A(EA z^4|dJ6wY&`QW@%k9+R~hcasVEMNQ8oGiGZGKBs}re34u#MZQp=t~p*wb%&~yIN4ic zd0~-I!9v^c5O3V+#G)6jVZQCRA()%+=s^=C^pXfy7*BO+XcujQstWbGhAfH5l0cIkA9y+My&-}sZI=kyL01Y}DyZAL&RqnC6DKgOPaY6t?N-G|>QH8K}; zI^ajBx7AeYN|o}3vsBhg=%`aFoKve-sZ=V|>LAJn3}*Re0`1q9K6!4)Lnl+jDlkJc(gXK~?b_0r`r zb9P$eXn%*;O%GmYD`xpwriO;9RLG`J2uBi}S2PTcPP#fAxU6EMeUr(FtF43frd3kO zBH^udj_$ZI$aajfgic2zxUG~(ou06bO{qxTg0d#sBHb)c9 zb_4s#3W-RRLbaQ^&VcOj;PbZPwuecaCJ1eAaB_PBhwHRnbxdelol2odxm=+x=rNe=G&x1YD;|WBtqrfG z5hRht@4Yi-Qm zF<3Afo-Y&idW}LhPg$vhWX58#V6|K=;3SB8%&vC)P7%F)xeUg?-?NCM7hi15Xd0?o zN2wLbpN3iAjFK&Cn4CTW?M=8WUw=G;WWd(kjtLRHbg`dn=n%dNM5BXdp8-ot01X{_ zlL^Cfby=o+DWseCcn#&{qTX@_wO*$JK{7dL@fonTbfVGFFZD0rU8Po~R4P-`L?qcx zi_?JqiWNyZqm!04J5E7HuNS|E-P+(?{fmX`f_D{^a+dwQ5L>&a==2s`tpR*)^H=(% zR1w_-gfr zefk34)ljLF%9P7hR6&o)Y{q7JzE1l>=w$TvR)S_7lKf0hy~KQ$Z}0k2ysOm8WK(fg z*CV9TB_z9twl**AO&6{7s%47l6QXAYDw+v*iyZ@Lw&&(qTixW~=#)&M29g1*(@j_Z z5I1l15cIjfYKiq4*Bh^c0Y3*cjasQOy*sN|2n71+^I4Iq8Qi8KlWS2D$yPi~b_|zn zL+~1}5;cm&0@+*%Ri{U9w&O6#FLc@oIs$*Y^4L^QBOVdzmRjM@wMbpr!Wpc?qray|a6N!_`6ev~e zpp!7!owT-h(l>B}zV3FM7X8;ww8oARUV3=`QXwG7W=ucwDwS&q(wLHiB zOMJR@%)wETOukIDuA!3**jz1iboJBU-$T&v#%h#a{!MEN)k>90rAobCqja7j84I(! zvC7k>7zNGBz~}_SL%n!R!dKaW*A9XXo&KBe;>Yne36cYkzmGS5HAwWMP0n^_c=8zP zrQ7uQo3R>1)LMaT@`$aa8KyUq)b&ja+wK@TpYj)pwgaQg=s9^U47a+lQhm;B`e zf%~I3==3&WH;Jg#0;%Hz))r>@a`hCw%}xL4ID^4f?1pQ4hUsJsCKRM zM(J*|V|?Kh@1GYs(SXrnczIR4R;OOg5e~;loSY+?U9_|X33{X#7}+mbPc~xsK|6l_ z{%X|dJ~fVN~=?c?keIg=n(bBS9~sMXmy23rP9y|YGsP~42kGI+p9}V?WC!j zTDUoJhoP=E9N%=h3EvS|_$5Lop*LF5zg)P`>LoI%1c%WS6;;OE(o3(;jQxr>h#=~b zMPA^@|DMnq6^F%Q8KqvQS}t&&IpuI~gT?tJ))ETMzAnbzxJy@?^Q$50f~d!6(qnw- z2d1Lb@*E!@6Fo{(m&~+yf(-g(4A-nh5b#xNKa*tmPPwVqvc#gt#Ns&wqZ4`IC?UAgS=pG(rbZiK(`6VqnRfTG`p%*Ik zD&@j6-koQ5;efNcnZA)RMsE+$YSmv;-ql@_cdHcgDc07boEH`J_BPtv+_c!mt2r8f zbl$C@)G8G7Y2t_bY^^LYy_*4RE4S|4BViSk+_yG?j^W1?-n^bjT4QXQPpHD?p}I)X3SUAn}00cRn;1$LK&s5P^}cnr%yQC z+hlHPiH&3(PiG&a_r?gizcKK*+V}=)nuefN$)D^o`}qPV@i_5Ro=UBbPLeU%T)4fR z^bPdW8*Hc9ZhApN&NaXV@0z9W)*S2A3`a-DB$DR{<|f>2?f6;@SF=e49XiQ~=||w* zYUP4=>k8#!j??1^JL@aVEriHw7Wzge7#Z%T?Sgmf)e5C_hSO5DVTaTcY|S4L-`FA) zKO-gQb#kr%6{IjaXD0}R?8Gi4F|GpG+}yP7Wr2Ykz^BAi_{o&ST0ho zR;axSAD>p`lPaW!#w!aL&k0dXnsl7np#e<@`2Fk3ZsgXN4A*6_Z{>Q_AGiDNfIF zoJ(y?{Q4n}9*xn{=HQBnrPm5ty++|Q!q(al~no6~h zBDTBAXNyt(Kla}1NscpJ^ZR9HdGETb+B>v2Fl}H70w4*JXXcpQjok=^6w-|@SO1J| z6`|0LLfTd69L<^K&wGsleoBGZk>WeJce%0*KFNBgJ9bVwue;r~so+2%0Nhf23 z4nrhzI^6Z0bX@4-QcokLF3THD+o^e(*v>Lj6VuFXB`~^bIMd$28K=Z4^u7O?(9qO8 zk@YFYrxsb-%it<$rLLi#QkUrz7?*2k*+W()#u*q|&ZmrWCoh6#n^$dZG`OP9EK z`7-C4%dnhCDjNCpK1&nh^bamRiwhI62nYKiG)pm!J#BPf?BQHP0Nc;>I5?HiROCdE zt;GrMJ>4Q9OH`d{q`sycujv%X&S?s%@CsuC<4i8@kj&-Cq!UDsc-QEwrL+A!Jw2UN z`)n9rT2n=ivA;e;|D!SH_VQF*>ZZG^jat7ANeI8EFZFiuV|+P3G0yB-1kviD;X*fc zJ~QUi5UeRlQit<=`_(YJ@iZAZODYj1bQmJ381OW9a-sVY-52U9w*Q4!6gi8W&y!PB zQo&6opWIi6*npwDTps5v$Y7)NCW27cXn9_oQfuh zNV>vk@yR?cAc{InMjav=T3#lXSAG?788x}V+~f@NYhiT0HX7R6srK7XZ}t2=K-1Jh zF(98u0aD=*yNXJns*ZD4{dgQ^^g^CYBFyH}0?QkFOb#5fe-J}K;?|XBN}b2)B7eY} zLQ@r#Y?h3wqG~G9-EFjdfQp)Cu6FrwSoDZWmUw87)rCb?w-y;X2oj9t5u{u6w3g#M zVU$FZL#)k?aOdkm_VR_hOVS&$c>>fn)zH@2MO%FtMW-TraXKIw?YPSt={&c~=JpPI zQ=81LuP~(v&t!r$O~7DwQrYaKyygt`l|HN{>6POYSDc}>WuNu+O}3{tnci7JeWqTi zp&??jdnl=^qo%Qy+A{A;W^%tRXljmRaGlA4ULHJ}VmE81w7HWnZnogJn|@|uT?0)< zmJ7PRf=*Y^ITl}MMlK>rx`Nk+rlDj~$XY@3QxHV-_5fA&jkN4;vbnX(_R<`?>$7M- zu7#$d2|DcF66)(KsB3JXve;fI{`^Lv=F$W=X6V1$%af^1QsxpmyLz~Mp&IKcA#PQU zva>wS{cro&N@vMyfFNOU6;oGHK~u+B+8e9zJATXjq>)R9*_a*S;e$cOH=~%#I_bW6 zp0+warc+RqK~u@bcbI!Rz<2kii7EvXJV|fFUR*&()fw74Ito)urr$0<{d!PIhqss+ zdc=d?F*cKW0L{6Hv^oh?)l<{h%K5Hy z)D&6Ya7suew!6sa<34(a76{^|spSG!yX$fMW@Bs(Rmqarndb4``wUEOkTm%@*V)6l zmP*{mdY`@PQ`FFMQMMK*xc^-*tBEWCqNK;_E~dJnoR+f}Xltm%?=ZafP)at;=E4|v zzwYB8uRP;jtJ}|+stTIg&(hXdMX~)i&bz4)>odbVyf?_ib{tDZH=W(*Xsq&KJPr4# znkO6IVRp2i?;gw%Q;&GpV8T&cK}S_RZ5{12Rr#>KTxHW_qI)Y$3=A>46v9|>o~s}A z&{|zoXu9}~OSK&fO(7XvV{)L6yS)?a$!1DhFL3i(^AYd9?-MNWZYH|IlOOIddzc{o zBk$T=l-4#;+t|jr^KDcYy(qD%W;4jSJULY%9SyOk2?Q#uXm9SM$ZbVWj$|~*_UZ~t zt2;~$g$PA6r1Coc!dlouPSJ2jLkKTn)WWPT)9Gb zYYoLN3kESyI=avLd^LB!{ei*RJ?4fVGgw|i!0)1==xyr~e869W55<7@0YN}#_D~$~ za}eEPV|JLtjupL_BbNygOy#f(!Uyw>_Xf3~ji+iL2nga&uZ19hC>EwTRJHK=zb<~! z0F{IJA!ZlX*~?g|XltOosbF&Xe$qNB$#9TFI)i*nr9%)TtWGaBi{Tv?D?}uNoj`RB ztr;`2{wQ(T)$0H3_S7SFD=H?T8ia2lPuFv@-m5V zkff~eYRynUXEbBAyRezwv39V$3H95(bMMyUmJ8|7N#j761PXe%L5?80IY(Bus9$N}4%J48YoOpo-V*GXLOZouy}9mzInPW~&p2&4li!_(_uqZ_Y9Hq>pR9vxexVO#L zPK3kNNuKl?k+e&kZ!E=ijA`+&4-F-kB^is7NXs0v6zB{VEH(#r%TMW7tEjmYn{&fF z>3hV3$8&_mV%jf#%*`ujsq?))QS>e$=y>JTSJNSlqA~(5u>$;nwAc(;UXc+q*F;^(J0YmlAYygh9yw)U0i6c#A7=R z9eY0?nx>FRM2W{!WRJPI1WAY4>cnm}|8!zp%MsmPU}ESockc}{v!~*3?Bx2#mpNbM z#P~)$_x2!21`M`x&R)5QFOnoBXUQbvL?Q{Y$pe-qhY+CW>*fBV2{uv|>N~G-{i80L%WUuHn?b?1Cr2uLKwMVI9}~|>dLtHx2fIo939k_q zIThhxb(+Wb@A6<^o)BJIFMhvA{Z+>L zdqK%@zP*7uzxBj;PBb_O)HHJGV~wbsBa=yyh{p&=(nR-`86VK0DLFbj8YuUekF>Yn zHZq|rX-gSb zZ{OlVLn&^{=_%G~YMyjFN<4XTd}*>ea9CgCFZk?WIl`NBjQ00(zjuVWLxHmPF0S9a zOh<+N^zg1|#AvVJ?3GItMGL%}O2mjplE|?=7AJ<#3y|$TOGCLE%hBYGAlWIdsHXM2 zo~+)6zv2wd&5hJmmEd(*(Fr+H(IDF^^Nc;|=kdrKJ8RQC=`~Z`)WF3mGq$%rmQ{#T zQ;{HXSv__iE$NL|oE{uT@h2pHROD2corQ7wA3osjlVuWyV$Sw_%#ADURC&!mz2|sG z5OfYoYMZ(Ek&e2IjGRpqk4A{6azuBR8ST@dWYctYG#u@tK~pvIxxzjKO-Apop{?@@ z*Dto=x9X368zcIn3Yr{FwA3MySU-dF+bk|Dv(nm3t=IUT@>U=4b8tGIB7bubkPHs| z6}9A4SltQ|3#Cw01wjsz%87W4M)bd#um>-*FZ6}OsZ=|ZOf$C!OdkPdZAjkIHAQMZw1XHh0tw?$^^*x`_TII!aj5*ZX zf*|TKI?HM6{)poGG@{vs&tFP;u^pXQNWcn!&F;ce?89Z1$izbI_phVi_I;xl-iC>lnF*3we6R1mA8`3 z=g1_Y9PVzgytu&B_yXgPw%7}&kW~@u#YQ~upb(;|IU?IjOpQ&j8p*v9P)d3e-s*PF zwzW{<5#FiKhn7zg+MK2DyFc^olXWED8O~n3$d&F6&XoJGnI+V0lIZ>hGh>51e)N>N z=^^&QIqYs1ms-m4T13dF2yRaE`2Is4jBO!XE9ky{jZ5cSs44YeH%lnlB*E(D-#5Y1p-M?}7av`}%9XQ~SoLor-6sG?MIeDfQeXY)Lb0kA46+Lz0ullO z0t)%`AuHogxcfsdPd8<3WsTgp^)ct0s>$-!w*UYj07*naR46U7W728lQc-qS=NRdK z#FOE9MjqZJqv){OKc=JF_YTI-HL{5yE0e=atscC>Pat3`uBN{20v%PZlM|L&9yuLh zYkq>hdw1y{-yo>DXzIDnCpUU%uk~SiCyAY(2g&HBqM?h=eT`&t*@AX;aF6Br8D?gd znIGfjU}(?+)`!Yp)D51 z26%Y?F{4XiM0YipuYShuYb}(yEyo(Oz844*Mn@T~Jyyz_QpmXs$#{hQtu>bB=a`yZ zW%S`5JE1g!@iTfFOL6{&CIr-cnuC>T#-;m|VMX(Lq~7rA-k3SG@**bMJ- zYpjvWL|7TQ%j9mB#4CIW7FP*%UAH(_ZaTqh2GA6;i6CopV+=p)<-5K)QU)(g-PgEz z;}U1nD+|@vd^KBRZ3cMTJ zTVZ-)lEwYhF^NVIU+sC$wl`B-{2EbtHA_6W$^6p+9zN*j=~4vATg#PexB2u+Gi4qN zy3@kDqJ+s=LEA+el`UzqxeTdTguSg*7U$=fnO$Lc|A3uv27~o;&earQH;O3P7<8&&g9%Gd&lsu!Q!I4sgrY!m3VC@$CsLt zVt;*sr;qM)@6jYnhbsQ2POe?Q#^v@Z?8Z~XyE-#wPXizS&PygMlgXxthY#3XU1DZ( zmc@mqe80IzB&(tSq>K816Qd*`Sxaf{x`wwlg=NY*q&zpBJB9 zL{3GyGqlOU<~;pRw`eV{!ur@7XA7@T_5nP;X^UtJwXulm|dmRy8_fS7tB1;@gR}q0pd9wE|(SaZ&_FNHw;10 zqmv96bRwXlC^_=4P2gxKih?ZX(KG>3(xcOff1NI8K8+llW@KiI-Kc`Mt(r4uYVa7O z_oVl!0Wzyk`}pqeEK8xxEAP;ooqXo*q`cVmPKyDEI`lR_wJm;XU-LFW5RgO%W%W(8 zcPuh7w#j-d!uG~CF}WEJhTll#S|J-hVDjM|zL`4YFqMDdRY8;pG+jpUcTiJoez(N{ zoe8VAinHFT*SrZtL5I=mrT*Mmn&#G6SUDuPyTkU*9%-$TW6Ls<1*gw~)A!up)GW!+ zIzwOmKm6D4##tNd=aJ1xpuB>fYU^7soN1~|Xk(uKKYvT#YV4JcA-&l_!!-lGvIffB zx)XHb-wx#H7R!^veD`pPm|&;p(rv!@>;lc@j=!9T$%4&UL{Uj8E@Ph9AD%EX`MQ6l=yd2L0ZmoO=W^uL*KKh%R7D}5SJ4Ck z(P&05ijbE{?9DUqWR%gFJ@mERbbt2m`A@g&&!7@*3e;|HwG4Dshb ze9fcz2!gYWwvRsL?{8nGvCM(-6cqvh1j&TW6Ts#PJoi_X>o+db|J6V9hp+n?n;N9g z;=~{D?_p(kux9ZvHELIE(R!RA_wbCK6${mUq57O zFOR#bg-f@-;GaJ2z-!TSx}2>9B!eAqz>fEYrO1#9F7xew`M>z4Z-J$uhukYJBj9t> zR%Sa@-{5sn^BK10$GG#Sdra=8UU}W(E}`p7Kb4i`6dl*#t|{cw5e~N&c=**H`F>!T zgPe(~w#(f5{5BtTl>en`_q0IJA(`Bi*SKH!vvwuQ+S7-8^)FxX?cfF@4}QQK2;lcP zC_PS&OU;u_2HBW@%7d@|#J3|`Xx1W{dTw$1_Q!NK6bg**_PeWOQ(@-&?()?{kiA6i zrPl>Kl}&u&ze}O8Dw#+pF7{(r*~ot#q8tkN5A8DpI)TB#)JOUWEi0k z1e&nB1K8cq-K1J4>F@^Q_rB);{nKNnrw4gtFcYY(<&!4Iu^tYB&Vs{h!Qm}=?yoA> zKfc7{ul|`oeDj2fi6``0UHAjV6xoa4fk#-L@YVtYKm3`yvj@j?l8ZFlFySq$J-Ha5 zqzUh@GV%BU-+tT2%z=WZs+G&1e!)L|(t+C~oig4nOlbQ`?D$?-iXIXNi+uB6{%^j0 zw9NdI``j(7#p|@w>=%jcE%LO#m(ispw(9eIeDe}@MK;W*?D?M0rP!Dr;fHS?Grjj} zd};NT(X9lit}H*k7@#T0=`g{~1@8ax5BxB^Mo_U*-Eoaizr4+r7C+9@AmQ~q1UEm6=gwt1o^ZA=p%h7$X!r0wE@n63hU~%#Zy-qi- zk_v7$*bxK~og@_$G6WsoA|EcNDoqHREt6K{PsXyNmFGX7%90x%}XZ7OsI&oO^gih-mlWp(z=X+Sz-SQB5;^2lij1nA@H{C@U=6_9QD?yFbW`N_zrs%-P~>%DGaoMzq^UVlp-pCodimoYe&Fd=27758JvVRj#q|qR z`)!5d$ZrB7g0Yy^i(Ra&Y_h&R#qQQ7tE)S7*L&YVF+f0XwBYo32?QYfO81*sFabYq z3RTn4RGHZBJiT9k%@4hkEJp>(n!5S;_HAxlsKskOZH0i>Kr~_YRMGWOH!EvFg0lxK zOfRw3*-TTJl~b06IT?b8$$G?dyquH*v(tymZaQ8LMpKbfA=YPyx%1z?Kgsz)k@cFIFv{t&%zw<&s0R^pmFGa-?g6&nlbomMrLC4XarshaTwpkqQ zV%w?kefU`rbeNn0+OBr9xVXXg{wxRE>&(uqakakn zXnlUpcM%cIep)Yfvb?;>#`X-`o13hz?a@{5#UQ=y)Q5oHXvOLE;SY$f#DyT@by+bT z*Zq9NyV0Fl9{%YY?(|Ku5*I0N?&0R`+gv|igWLGNq+)*oL^D=z4PDo|SY8bhTnI8V zzQA^S4R!WB%hTiB>s=&cs-Urxv0uWRd9@he@wu^?#N*>sB}X#6$;`k5zWSz*ne8-2e?1q! z_;>vNY9nQyx4-B4)gb7xdP+Ha{Sq@XYaE1D*j`^}es+T^bf&E?4FWpbMK+eokcjp9Qw;5|Xp@?;ZH!l59MXpC_1fc=9g3F{eJ zTdMK9t*633=5G^vEEWq+hZ#|o$tL4OGC33tj;+tAS+bcJ2aznQCSb5Tv70Rze(CyY zc{0f$GgE6s5@~eKc1p`i2-x1S{`(6M05j*l{2!>jo;_AG5kbP{F2-Sff3)(WoYU(( z9t1%`6s5luEi{e4*5TpZLWj*;#jXGGKhvF2j@RTiTCh9cZ$VKz5=npk8AwRt(RHn< zg#xLjp(-+|c$`d5MH3BJZ5GT%-7y>2-FTdObkQv7Sd4f&gRJqEpJxIFi{+&-G%Grt}QiBI=aL3P%n4y_A|N^Mdz#M%Ju79zjB`XQV(YRPiat} z1Q7%yPL~~<)rc0#kcvl$WeY}!$KIYwnp7%IG%lk_2CV*490nbdnjsd6lSpLIbS`Xm z2Oj&$vnHZs#$Zw_O~g@D%k_W%KXLAh6FdWq7OZyHOV^`@ zmd_I3UuNLJUGDXcF@Gpf+|bFb&p)HPt(Nkl(@+S|Q1ddGREktKhk_oP-GzQE?yp{$C3MpeN9Hk$(&{@#(SJ)nKqVaX4OLN=+r7jS*a* z6DG1!YK_BwHxBtoeau~3+lqF~D9$)!`IvpEzD z*zDHV^RC@Tk;jF@ED}w`iAAHN74_#goBSdOfPs>h%lx~tR&JljyDpqg>x+NXRPvb^ zhwBsE`TBc$M^}hwF50eKThngo7-)C;5mpga*8JQ2FD>}pF zk8g4P(pl=uJQ#jaqsgxeP0J&v(*@quBn&1CcB|sRgx{%WH=ZFG4wJ|h z8X}+nh^A>j;khUxisG|9g{Brfw%$G@Y(=$P`|tl3+OsO^vEEh%-nG8MyICUJbBsKG z$hY4Qvz^jW(%j9}TQ|9Kw(c44zF!>iZY)M7r=kjaEVh&RQjiQ79ex5{2X>Q4G?5?{ z4wF(Kr8HD$C630SQ^JG&A zlBqPAoPg16#p$x2xVhKzY0~K=@l+lp3BB2bQT#1Esstpx8JE8T*ZV$|7f?u&rIQJg z=`3dZ-qY0zQgi%nDQ-@4Gyvyu%lB}tWuB%-%R~KP9 z?xqq7#h+*KrmCT->N_d#6im}x6xmMKNBoA?iDUN;x%0zg zCRU^9iW<1~=_gz~-$b?F`O^l{?+9u>!Or3sqodPoB+OJac5vl#D}L(|Mh_hgrC3kmUExLE)ijk?-Ok7asBqE^qg&=I^e=`N~+LGF2UCP7^6?8*-BceZ0g|Z zl~#((CuzDAB1$5aA)7BuPCK2}6Q-^-G$l=<>@JD7YC z&>76Xh(Iq-t>+riw@6;RaWGLh^A!hsj%;aXAl%a&P zJzaD(l^xH!@M3~VRi3S>XfR=MdnvY>SSLy3;E-@6Mov3!`awgH6C{#pGO~isWyWMS z^VV(SKH#syhho5cf*|U!xcpR}u~3v3k#q*kW;0f+8J+lHn&$mNz~uB$R9cGHxJo2` zz{<)l$+j|VhL^ipRIUpVG2o+%EGA?|UH$^Ap|Ds+=Mf++j78B$L-u zS?t5>b^guYtjGU`D!ELQweiP19-Lw=W~KIQ7oXnlrsP;tK#g1?#KHb9J5d?IVaD!u z<1k1+bNu)N;H8A{v$fDjMR%F$f5^k9D}>b&u6%Z#ix7cGD}Vc$zsD~Fklcx^acYKvjIU( zkxR!2$7POc1Fs%N$&$;23B_{cH3759gvp>kz61UgK#`+tFO75myI#gt66pPn-2TVk zbM0ImMUFQcJwKV_1?+(m{604hagRu7mz9-$+DoiBjHVZ^QB74y9`3WVxy?aJ#pw3X z+**Ofq(@REOeO;cg9P~$sbrjRA`j-{lVn;xO*$1Ln#`ez5_+?xu*o`&YoV!RlY7jL zJmK!$K^8(fN}Id+{Xc!dg~k#bM%^2D<(za+{Cdb|lI*X}Fz{%a-Lw~DSrsJ}0ql~J{=<(OOnc} zNUl@PyNXP7cbTF4z1({;M@R~A@kW7nTPh2ZazFnO_+kUb+u+?ybf4Afr#zfIAgkY{ z=6pkecaISU*VH_jBi_v^ptD#p84OrFwX|L_@jusm^!n*+Ey3#KDE$wfvX;?P*7ZBS z=q#bwZNu%apu};!l*{{ul8dpkG{ODv?lZa&#Zc1B%`ZRaW=}K4cH=4IU4{7m8dJjq zjPDv~%o?d|smEtNZX&yo@J+@egcEr*u`t19(uoLy%=*)N^p7sG5;aiK(#_3V7btTW z(Z9S%s!Bc{C^7#$U zHG-caZ$ z^-yf{6uK2um3LC!{(zqa$yP+5qMpXmF`n!kusSi!`1v}nn2WGKw{ujp5w=(77@b%p zmJ=|QwNYOkpy)aCGA%D7XHvw{IRsI{V76m1={ZR*IG@cB**_qhl2LHt^|)|341WWO z%@d#%ZTlEI9{Vma!p6A+XfndlDVPoJ`znj>d- z;VCMjv(Ckf0t70#)IKvK6U?sckx=y1mX}gdQH(*+>L%WMUsWHo`(igG+ICk9c%;dD|`?!`18Cmz{m zVtj+nau;U%%gGsyY&6W?%p}Xv460!% zKJIFu$YyvWqjoKyC7n)@%;XEtcB=!6QF_+Jr*~CRTT@0&@hT(xo6L<4vsB~3Z8QGm zde&5O>3x>xrWv2vA}LrXEosjY@Pc@f>I* z_qW(uUS=zqN9VOrR1&~pHlE6HT_vAnb83XgeZx#{Whp(^&CM@v($i9g?M;%;nu?Z7 z6HjKy=2b+!5sSr!QU7Zu3q*`2D?XnSi9G4pCSyb6l$8VsbX8z}p$MsgmSJmlhQ-w# z!dVTw%Z;zdcj^oh3sA`>4w)Yrpl^7N?X;D1pWft?TbF68@?d_Gn?hC4a!DeIEQ%(g zGn%nj%)hd>vxL=V$L+R|&m>8v7Z@CvrmEP5qte5RHE4x=Cc^UgBrAJi(unv=O7OTG zr?y!6>mWyDdx_!u_voA6L-W?tbK?d#dRi!Po8M@HRa0cr=_IL49t{zr)q&Nh`&GM@ zMbU`M<-l&$7p55&XBZx7rZI39yH0zN=QNq{)+%%3bF3$GNKP}pfFFm&bo7jq*_$6_ zp!YFDOHu4K=eYXmO)j0S!)wu>Zcn8Xp`yqMHbx)O+c(1WZl0pXZa)9VFX?J2#ces> zi{)5o8cHtxY&uiYn=xA~nE&c&xaT1u=`2)K`_PSS6Ax}OIW|dcZ56K801o5xahgg# z8)s{Jn)$UIBC?9D)F$Y?k^lf807*naR7FWyDP~CmlLfEOj;Q2FMb>#bG)_%r2}SLt zn8g>Lf0~+RYi@?6wH?B;hQsYW#k{K=Ny!Y*H!{yo)=uZ`Px$2KC0Z)qoOhLMf@n%c z)kO403l__p7W`fZ0np)aI`DYRAqoYVnbUVG=ZI`AGIakw zk7f=Kd<|T@d4n50%>LK_e@7l~dvWb0G=4Tih zY39u5?Z@zLj>FYO<|pRaO#K*N`f-@eh)9U?A?u4X3@)WuizqltN^qVl$Mu3ivWg-{ zSe>3?Vtk3il!B$mOY6Bh>_>6x>B=1!cz1oIm)=KDncY|Lw{&y+_n&d0A@GL0tD?wh zlBq(RDjCdJ%$DOlM1C*^lid-j!2PHYO%n*g7DZ zQ*nB|_)AMLiz1?E#OCzVaki3&^Sf*Xmzf-&q^`D{E6qOsQZ7;N@!%||KEKd&d&A%xQT(#DAOIS2 zHbXQVC6mjcNiOVm3s%c%3}Al>Dsn1GDxH2#!&@O13=>busH%pl$|PeE4)*que~gX< z5uL$;({4r*1vE8B=5UeW!C^)hgBXkIXzaSd&1NTsQ9lbs)wR@?O|rPP#P0GK_x@x; ziCv(fvILLAgdUk>^pLfMaYp)w8CwY=*nCtqw9!&i^lVIA)AD3fNz&;;hjamXV!<$p zw1T3l1v!gIh{Jswsb`5F3BAdJ-D*4qT7fS^D^%;_QPM|RV|$!Q%ct7&xMnc zR*-^>J@nrzjZ&q2o*EU&XE&q(<+z=asO?zw+c=0xg+eDervKPt=p92-Q>9MEiQoc% zPFa=~{A2o;BzPw2p`CSfAm|dSY(W^4LfvKu1H~=Q)HXi6%cVpT+t5WS-iW29uO}^@ z0v5LZ)QiGUkw}Rhlc>T+P{|yvAGRyo&>kqJ%R)%&>-ncA)7u=P>8qe!Z9Xyl{aba> zcUuMI>$g8&uA}ALmT-XrKA{Lo`D*KDjKu{#xilYNFkjG1UM_ceM(FgJ)uDy7qXn9L zBPA@;ibu&w?g8~Ai3zp`**3NLUCW`0XzUPPFi(rJa1Urn4U;-a}gWV2H(* z2A(;MrlYrSeg51eD7<4#DBQP4YvJIqgV7%TodA7`5-LzkZ^7crnMgVNcYCF0W;p zT}>@v5sH>H*CZRaA{Q!(kJ9k1>zY^f#)Snj4zj7@lohn+W0n5(M9}&&*GD}pO`8E+ zm3B*3)6oaCuYF_i^^BH0aY3WHGbcoeB9Xi`2Gx& z1n-8f9+68E+HnmaGh%8?&XZP(=gakH!8<*BRNl;u*n*)O&#hEE^}x&W327&WUP{_R zM^M3pSy)M2pWi-5fywjRD|a3?6{UF;bfs(<8C=;4-*L0_>v)c&vDepM!z3(jEvg6H zL~h*HmU6KW98ut*%iJN=kV{rmWmb8_Y*zvWm461DM}01-zZ0ONAi$K1Q9(#xiLY1a zKtJ-jP27``2sO>Ergu1CzKH#JY#8;o9iBuu+nh34(t@?Hxj3|e0(LIJHa?Nn^RMac zbWU6sskHZ%wfog(`W&==C7}7RQZk=iIROjf$f69vkwdJQ|>j;NR?BTBSFgF z-JzUnfV@C9qpPC8ieEJXE)4c%Uot=b8#gByRU1^=&X|zP3uS|kZW;K zO~+IcAjv;6{Nr{A8mb$)bs+qr+b6jT4sue$1{(kVpjR7*wTxw`I3X;*K91ib4;)*GIvAA+9smN^!rMOEBwscYRF8Os|;T2d9Xfe-o1QW)n*98q%U}S54 z#o##Bj-M>1hapAg=*FjZxKYv2lh+?Qjz;9>7qj$>oSlUT@ZsAY(xn@(G=b%L z@hveA8%Z(;KI(7uO4)!WP!V84$!wB!R~wQ++%@1~9Jt+XZavnutRMhUG1!NA)r!;e zv-xuL{*2%l|I!aY#DHhK{z;a;piv9g=YoI%kyXcdV>*Q26&P^%~f>6WpZdGvb% zwsB?z=U+E<*zEXNjAVlWVK_J##wqaL_z?|ekocXF-LFx}f#NNv^4X{t{>_wmS=CXn zmliob0y$udfrO5?u@pLG2r1(j7`PXD{}EzDq3PhH!Rm!^h*+OtMghdfxJ?3kB2 z;1@7c<|y8;@tNrI1d@va*XP#}j-M=i+RCDGzD8U~^Qj}`R^8Fp zEP=S7WoEM>j*Si_0D!EHtrriqgZEU6%Et`J3w!*D$_Eqpd*Gz9p#6oC=RsA-x8u)x z(q;HL3%mXW$O>JV1KoW|OJ_}ls+zH+=awK(-=?JB#xH-KDNo4M!6{nMBW#wRQO0L_ zR$1?R{af2dRpPi=_>kH@Hg=yO$e8E$qwyhE*qzEIcZ+pnRH&!xp-0;kyW1k^tjGRv zYT_atyGgJzXUI4tq$lw1GZfs6&*#;@p9n^fs4U$tC)U?oIWpCpg#tPBnL`K~-Y56$MbM8U^6XpW8q@8RyRRK>!^-Ww4W)Wbejc#6^}yhFTafRd)N;Tp_XTA>^~A>nFclr8OX zF~i#}sX-Ao*TI95W@k_42*%;i-K z7q!Od>FT{Q9j=y~owH-j3Pg33ZCygcgiYO|+pI0lCiD1p*-uuD0{s1V9kC`WRR9mC zb5h>$M?WDSBqlR_-l#`vne8`+3MyM*EEzF1N8`#^Kn{h4e0)XCmWf$gtbQm;JIyq2Dvks=&miYc*r0>H+{Hnq?o z=I(__JC$49-12kgGe7RD8E}yX29GGm+@CTgImy(hDr)VzzEz4S>K9NhYwAkJ23|*u zln>`{m5Lbk;@Z(PCs3ScaQ!#4#I_XX@Z8XQr1e|-A z3arC2@SM$i_EcrEv z>;;EsJA~Bv_xKiZVcK0zN#w0aW8B&Q#Q@azMb@ZIlVVwC++I+ETnMQqEI5B;{mWo4 z;c=}4q|*4bT_4a08`)V%CyCbPwwP2m{lz7NbuPCQ7z1l*=>Rq@tnIR4mw40h&kGBv z9M*I)%w5cWWn5dCFV54=VxZ&*O}CqH}iM8RM zKoQ-^3eaAUaK@4daa8$At4NezPZ1XMcL0cixEGC#!q$W~pek<5tTf}~6P3`4pHdL4 z>7L1|xTKQ_-f*e<@RC;B?gbiV6~T)mN^nv@#r$n?|Z^DZo_Wh6vxIpH|3CKfnQVk zn~b)t&_$keUSX1{p2#BtXUX|wmpXO<2Yu1>kC}^k{I7hc;WSJ>@|5NkF%n=_=`AzZ zHL8bAcgX7fDa5+ryTj9cfGLx3-^t*oje$lc`(rw}z~WI7`*-)VYQ#e4w(zk~O%~GH z{>vmM;;6?Pu8lYn$8MWnbC@DG)~i1pVfccsUO*9oMtzchPge`yxO_M`K?{yU1g-B z%@MV%?4q3G3+n{3U(|{DhuUvTAwC)}fwqA5gv|`>=@^t6`|V?#u?f4?z{RcLW`+*& z>jIO+$ZB>@k*Nt)BK=6^HSf$@i#QcEEP+oJ7XfJ#*_Q5YS^39i#`Hn)^;3>7%!^@L zujlXu(WzSFvk-q-+$WF1-vCV9JAn@|HIYOC_Vh6^$jJvnYok^Po8BdzS**wFt9Nvq zdIB|O^<0~yF=yUHDla3zqx)(?uLCR@!4fo=H$pG}CZBS3>oW zQ||hz=}`)3Nklqc+M+n_CuXIUQg^aqp`|Hw2xji5B z>TZ>~)8Ty67-Z>ucvM}Sfj?ZDsx6PWugT?f@(QhMg8=8Sme!YuqnK-8>cTi#T|+OG zyKZda6!;!#jNqKh|1~uuC)?cG9(f=Q@HRUSYbg&HVW*qMWR>C)*D(V*skW3%@Exsyid8tDu-2PpOZ z42?N#;Sj;Zgr}u+-K;;~IgSnvR0Iw7!4gI<@cr4cWVwXtIDhl-V_D-a2 z>g0^>z$|26ic4Z?Y@)E#B0YDDj5)N-PI#bwUfPOo&OLTEX@P7ul1JoYg^T`$Brf#u zsN;p(2GL|8`2a%`n3y%LfE2^loc(>YdVg?8KHIvwn2au7l%9c)IED?K-lP5b$1jw_kqkNj7m;sKRZ8>dx8#<_DceZL0M)?A_ta>R&_vyki^3_;+P^DtUB8M>x+_Q5ZO-5Etja3dn5 zx@0o;UdYAV(vN4i<3tYSWUilZS3f!0%|%dqJ8W*BMldhVFEX-lET@z155I29_rh4K z?WbtYspoVG3ZtnPNH%9b50M&25Il5%(si_pZtwX}T`||3z9q+Flm1c;&u;MkpFlGQ z#?pKj%=2^5AD9OBpL8oW3u$gZ1o$8 zD;rz=pI1X#${c|fN-_qKFZpczDKT86qM(qdQY$8e9>)N5SroNR=g9HcpG6|SO)N8u zGk(}3H=CsMppb=QL{^|jnyR?9C8lD6+kNv>8qPeFtUrvLmVvtFl&OP`w(BWY9hxO8 zl4`$A)8@@JoV&>Lj!rS6dx8<|6Gx|D*W3PrW;))-DlsZKAv1WJh%?sSoQ*xk@6&_? zNL3Ms=F0Al3<<>X8r$Bd7$4sg$|YJRarqW++Vm~nQj9-_n>o9~GosOs+tdcusWv*w z>Zpo^2~(aBuOyazc5)-)qV>I)Y&4ibiOgJMRy8N+axy=6ZMg`O@ouAYRBOYfs^mv; zNSy%ZU`|GUnt#+nuJmN>wxi$Y#NTMl6$i^2(DOL$OPo`KX9!V+-3oUE+AUd5)(i~q z%JBu6*4CM^&O0|=C>r~{@qcD1n%loE((OBz|GDVf!Atbn>}dw1S# zU%8iT**0H-uW?Vvo*PGOkeyCEx!ci^bx>5+9h0L_M&8-Z{V*q3YuRT+>Ru;6hW@o%Z^Yn$K%5U@^>zE&LH+!SgCoA1wQ;3NE zkkdRO<8Rbw61Q-%O8MuBFz?2eT6(OXYmN(u)SVfjXH1)~#;%p;z9lA#ULa7@CkDQB z1eK>>TQe%>?acnmNb^^9K7CSP+E*4wPxy%{7CGa2!l{7ObfxwT0_*7I7Wp}&4Kz3b zAzq#-DpOP!xH@Le0&Jf+F65SQhhf1FXi7hf5*=`)qKNas&(=0|Gl~w|dxJy@u{t{X zwGKToH9JHL7Qf+RN)3s>L7uKfQ5kae0=*4|oi=+p>m&g$1_%vuP4`5Q)>m|J}H}+3+y%v8Ic8;rkWl}=!Qcjm~S0f1cK_6y)n*c?sGvt>22<&U3zIae% zV{h&6mtox#o_5o^FNcJuNE@3n2mYy$ac~*yRDW+J`>x3lbx+6G*o~BwM^cu;osek( z_&k9A`O7}h^x}(#uUoUtbR5=o1 zIU<)nSAq$2hT8uYOzW4#R8=+e;Tc-GHM^lq6&L!~7YX=njrt16nmAqhxTb--P>0%C&=$3MR7A&G|>gr+Q6!OoM zVBU#6wdCkW=I;3-dRfS1w%aY=l4kulaX!Aq9|;RV1A|Lr7W*Duj~IFqU%`KKN&0sL2 z{|R3ucFuDLaV|EH$n*Q<;}^uQN_dw|b^2)7&;e`;Kin_@b{6g4|M&n030hS6_k5PV zzBbV>ksc)u z+zL%~frp1&s%1aty2##_h*eJm&k*DFfwCq^5(3(iM($TH5gsT)87|}E?UL$$d5!nG zuIs|m(7v`OCm;O2(8i%qC5!5Bu+BtsCErzYxr2C4HlbIi<3PS0T7 zj%N+3!Q9_JwLlMHFK{!7<4P&jS0ZIlruqur>I(# zzVUs73onqf*Wvyb@o6Wx{j^uznSq`)Jbo1JlMIJ0SKi4pOt4H~!OfS39+%)0vT`~d zH{WYqNiI^tqSn&5{A-<5O%p0)LaGo$s;tCF-ORYAS#>>yACK55SSmCS(CF9zYue~Cm^rL`{6Ow^*P?5Si3cmj7Ru_p7| zx%VNJbkgcIW#AeP~(oTA{S~dm)R!GN}>9@?GVqD59xC zKD~j5$P^E5-S6Weq6K9g5f`PxcgO(t&V~qkc*`9+Xlf0v))uF>`pEvW`!_l%F^Q`K zWuI4u5bS^1cqd@1OSncvn~b6|9vP7sOGS|bZU9#+mrGeq`cL2ZBrC*6m&mfJN)X)e z!vc&0G-((d_((tD1EDpYIZjf&190%JVb*38^p)kp*S2+IbQ> z)Rkq49a14z=H5#IwBa1@1g#S-oJOO{ry!%#dR= zg8_aIx_C^?w4x_l^{r5&N@c%)O@C-$Pl`h(1%-o4WPJAoM|NWv+w98@(@hkkrO0|m zp$luRbOfDl`fi18W^lH?O(WUUNDTwIV39B>Eh<`%BTEQ&bJJj<&jNpj^1=PA|5|tt zSvz$K7q_6cb^09e!^2gPCS6}fQvYjxmGH8!b-JY_%ew`L37#Slqxfb7`eyvpitwzs z(jjCwcJ+los6ist|_r3RWp-tjD7^6 zOI$fnfh|)>QeW6yE}uj6r}uBW%;*aojfI)S^}-7Vg4sx5AnVyW#$Plq$gGe$JAGYA zKJ*3kU{QTv2~l60L~y`;X70%4$j_Tb5#%xr^h%eOKHm!TUeGg-6ZmFqCb>f zxe2oy#@2)cSGY$$bNU8~*k(^VVD~aQ$kfo+))a=UM_<4g0AsP^Q$F!iA1v_Vo0eAT z2Z+mQQWrlNC0htaqR$kV5p_aF)z9w^S&5^ysn7g7NNSKY8Zy>$8gJyW&D_e_nBL7f z4B_Fr@Y1#K@I%}&cW&NsKUW?w?53sS-)ind+ zUjjf()$RY$1-NNLX)!A(oiB1Db`gw(7W=M={O&wf=s2~WD3H!JNV2aB`6YPXXq;}^XXJRDmTNU>zU2NM<*OK0f*Ew)38?ld-fYK5%8DVy z*wi%m`PrKbu=X|(fCeOzr|qd%oO3nctNnKl=ls)=PsY)QHp(XJsGLvlnk)6IHCvS9 z)!(R@HlEO)4V;n)Gr_fiNq0Ru5p@l5HEgP5x5KQgQ42%JBZw8!z}Px0hecc@N91&v zlE$@7PtNFZR8?(lV@HP^1fAdQ$sIZ~F2)?(b4na0Y1Fj?H-(432}ViAW>93vpve=! zB?gLSODd-r_+dq#8fIj8l$}b^M6ORBB~?8tbBktHkoC3@bNusQ!W36Zk|WgCq_Jk4 z$Dv51%75fi2T0y_3)HXl_kRf_Q`XjQYXt{fw&6ug<`nh%h{a?1zO&8#W=*Oba&wG^ zBCMzC*dcr3`jSugSz{zyDSI^byRl2qzPy)_yP77Alb@#cM$gjiGwVd{Rh)tQRg+IF zCG!xlU0sRqOd5@vN@o~6Kf{Hcck?!)KHiX?l|@MqgApV3aQAvixYQyu#2a2ZsbC7O zK}W+*F=Ue%sWo-}!iUpBV&cXb6BAw#0tfvj_~ga0RVU`_l9X&zU%I1tjfnsa|LnKr zm4|Z3nX^X1m>a{NaV_fNUi&=ueqfj-a9z!;8rtn+hr@wbvZEaTGqt{*hnH6e2rO!8 z!I53vf;M9$o?ce;acud74|oU}MR=KQiBoi8&VlIP2$^joV7xo>ke^HDxUeNU?bbsb zcXO4Ikv|3QOMIncT`^;cwL6d24>dFCWjmBf4BYkMaUb0}PRqEhHi=MhUKbYbpd+u? znP7pI9c-~X1cR@ieD@Cy&QF&QR&k^R6qyqG>+X3hu!VDM zagvB^=a)&O0Zik=PI+t3(-*e_8{9}iAtBI^6%#H&QOmF`Jy4G{7s0$+ZqaGs5kW>a zHr?dt6V_;ARNSH+b<8*I%DW#x0{k}tv$0NPwhW1UvhZlW^;KY{pXH^prEbx}rx4K< zc2!x(ScEbbKsAKJBwwy*+1S`r)zqjO81#ZMHhC{=Iw=xaCEN$&l)OqhkBK)VlV`tg z{naO=%pk*&KeMZ0mXWcJ&mK8-Vnm(Z&r4!*cF{rp9d?_=@Saac}bjdq+ ztFgGRfh>tihKAR-PVLm8voofA2mp|seGU|V39`|{E63A|;5y8;Ez~-$2`Z+I7{V+< zB7EZR$cnT}kRkM0)DIv_T9bRuy&w?0y^g+s+=Vi{T!$4kez3>+>atFF9YW1Wd*8*O)Op4r`<<=}aUPaNSgqvQ%ZXXRj1;5@8hUwKk@cn@^rV-07 z!0My*cI1MRDrZ`t9klWUwdH@Eg-(qX5ZtxlI}sRO0HeI{DW6mok{d`*ASU^; z^KZ)oNJe@RoC@IndX^XZOOGK=`{f=#6uJs>Qen>puZR;=f*!$jz^*O-(48hcqX9-^v3!maZkZWIEmFve83e!Ecgd<)M0^J1-H z^fH1AeNK!dK#fKX?)II4g%wLw3DPO+dth^h&v0UUX_gB9N%sUN;j$G+^Jo0FoYb`t z_pCq8w}EP`=b@t0nJp}EDYkTt$Fk;L%=KY_Z09y?^g2KY`OV)=i!!;mTg-#n_ZM6{ ztb|7%CB+!SuPfB^)0a51(XxEon}8Y9`<2N-;*ClFf6(EHafX_kFIl(t(}iCn?@3m7 z{U(frP%vOUl%{?SO7a}Uc{YLcp!QZ(g{=v|NcSszLhFI!q-i8DP)C1UQXTFBcc5^|ALo?}drQ?!skK=>M>uI55&O; z|2%Dlc{UDH=O^t1_#v3?#S9nfsZ0K%XF8xiGhMe?8 z7RV(+jp7wbme;SQYTvLTKznUMO6rztI9XX);fYJ#4~QVAdZs9KhM~j5VSg2WnsZ zBMPPE5)RV7%Gs{YHg5$bx>}pwb zt{jWiU!>(cUWNu;vexGkx8~G%ji;lA(i3N*$2gOw<`j~T#Rgy%@DQDyw;}?OXDE2T z8RxMBFvZYhs1jfFQpr4BewZaQq9gM z3WYb`+Ul$CrgT%xbOv{wkap(bR8y%&U0`0-FN@qQdt4%zBM@k!(0Ubd_**i znax{&pJbEdN|#qxDFkT=Cri&g-2CTk?d^* z-b9cm)okbX334hF!xDm>2E|%sEVlrtFvy7zE)~()1a| zS5+}VK^6fh+N=a`V^gEFfBcGnSP;H;rq(2)Hf$ulHB1&{+yB$|q0cYE@Nlru{ z!OGSDZ8ES20=Yocy#8appGNvI|-K{BMU~sc2~jSp(eD zho6n9R7~xSf<7KZMa`Y)TedWA{~O63;dl7I{x<}RuoY9Uysn4}ii!E-{hYnVwqM6L zVNBfwXL|jo51yW{>i_pZ;EAD?RkQ5(K55~`Q+-}@KO)rLpXz3J-B`ao`9GUM#Xod@ zAt8Y!UUG9}N^%tlvDem4jX@-XlW7Rtomb|@2E6Y;Y7N)3Arp%)u`3|1IXUU0L3ZZE zcx-HqTS#Ji0om*JjXxKV5OQ8Q6$mvlwiCsLG>+a?Q_&#pd3XfY*q9VyP^noVjYH2$ z(-95U(ua3dBjJL0*xiWrdD)l<*PK3o78_Yu0gpF@P>eftua$<|WZ{J>3RIh1bdjP- zz^f#xXoyxY6pqZH`iRy6NvN9Fe8FKqoGN%&*M~tmORH7wYHv>hDF)nL#{2Z z1A|THIS-WK6b%KxD+nOBj7T3pQI^>9B)LHuJe1hR7t_)}GK#0y;P0QgBv;oc{i@n{ zTCC#bO4$L3^X~4hipd-TrB)0glFz>cz`M&hsrgBAr`l_8tZM4!Ri2BqSdyzDn|^`I zI3*cgq9y-)nV>&gbt;urTtZTux0hi`Y9M!+wKoT!Dl}@}6Zfofj)HW0SuE()SoJHd zj}wZIwXOB_#WMbHpC0ErT^;iRVq?RD_|q?22FF510)ir)(I zUo+2i6^JoPXZ+uK2ufnaDxdno&(mxy9-_8#B||%3`TPmW}T4VbTw7ns$`bT&e__ z#FpIVoh)=HcpXFx6zj)L!>G>Kkn&PU*vCtaBCCW7{QSj#3sj!8<`U|vyVauBx|J4R zACr5U{TS3c9Sz8)sU}>@M98QIeAo1SeDlZB`Ho?ruPD%?NMUBU+IgxMShR}@1qW@g z!Bb;rd?e73>*Wp(VZV~p_adEsFWl*9i-puH_Mc{5cG+zaE`8+U0(iM?t*Ggsq_)4k zyCTl}i?m`FPrQsr>({ny5pe`6AWsQ)Sgen)s4w=Y7=N`mEmbF90beGr-=8$$m z>c5L?U>C(%ze5H^;JE3R5ng)i3&Mtmil3BraK7XVBlbKPir98?@_$^hiOaJygW zjo=|dbcT^0T(6oMaEDn6x<@Y_GDJFmr<)VQ)y4&Jgx9jN z@n0oNpKsj7P1MzONPhQFZu+zWUA(|UoPTafC`~Xn67zh0zFOw#meEpZZI;92d zoE6)$MG~AF?tMZHm^#30me{J}IqtwQ7nmBGpxYo;IyxaXcZC$q@g$IrpZS9Bj38Go zyfAic5@uD!LL;~j7JdvAK>#id^SCa8LyynTwwVoofs?s=K75zkUWxpkn z$Lk#d94Y6hgL0BpQn#BXhvefY4IWIInlnnG$>O4l+|fO|AZycz1ae0@atlWDByn{qUuMJ0V;6KEc}k@~XnWr(!kcTwc? zKy|i&Q*z14_x{YARp=^S+ylcCr&QYK<74l!!dNjHu;#J?9$$kT1d?Evhb$ z>}L|aK|JtvY7Pl02KavfQ0qN210FZjoLvUEcvHK)jUQ%rjHz0+vx$DcSiutOiz`gk zHlQ!nLuDv)W$i`^ptKT$CG;>gsQE1;?@*p|obU+CnMv`7>@2^Y%Gyah+gX8`dSL1Otq^2!Msq%N6pmBI#Xz8ba2CwkFJ*(d( zb}8pZqH{Xi`KBxbaQ|mAgxdeyNM$#{H;797Fv3R;i*tVUWMp=umU!(+yR&$ZG#k!N zIVSHA%$?cfA6dS`$ddi4cZWVTRoZorW-*lqmN9`ITKRQ32>{Yg&Ii0Iy#{Q#a_s!Owan;Vt2yJ`q-c$AaW}Sc>kJm zL2Dn=8{EDU7k0XgSI)d>9_IDD53ke_nx3s^MwvT|?gvH5kEOLR=eQ4rtH`aENlFg! z#@QAgS$h^v!BzQ}y;4`yXvhnbB(N3jFPYa6HWxAfaJd?YAE+mx{AT|tXkgWp)+6Ay z^|ka=EyJg$SV1-_UdG1*8I8F!wJ5-R-M(K+h zYBKg{V@30pdgsN>HjRAUVs|d2g-(tv9BosF{z7#yZlhYLsp?3dMsQ{exrax-vVG3G zYq%hQFCqEB{5atK80?-!o;%djRsY1VK9Y|Z&~Naz!f%a0d1gLR_Yc{-_f63M_CQ|% z!l$F$V-?W*;U$2<8B+`s93zg}-}Yrj z|Ep&&GU8diw{uMZ1W~o~NInD+u6I2o=V!RN!a}Kt-6FQ752i{VwQ++6N8sMT0mHSd zBn4!<1Ff_>9_&e{6DZ9tFT-{MpMaG(Sd#OUA{^(!&=QUEtTX(^M+pHoc zTorYAizoD!n9j*!b`n+q`|`Zx?RBHC|34Js1wC*q|2VIq^9ho}2P%x9X^ zh+<|mNh}R>EvqkS4j%Qqix0H7f%@8eK!3-V1 z?===Uj0%H(H~qV1j=~K_g}8f8KF8SUn(RFZ7k-tG3y($!E?ocv2lX{Q@ZVvSJ|T!F z+>VC*+Q?p7Cg5aQDmrA=o@Bja=$y8&YS7hIO9HLcZK`=iH~Y7bS!{j&=jYfw@J%r$ zQN_eS?b#1b;8K4yE60p~TvqGqF^K_%8N5tGuqYNaT^nDlxV2wsP3JArgZr%89g`MI zUVga{guDOp^U`R`$&Se{C*fXiy?w1OsZWOogC?A!pkOzRGfH(_?X8Mgk$stWOMd7RNl}@jFKXmy9TU7`D?MiQGYVg?=wp`KoHi6+@C84OHK(AS zDw0At4*R9hpqZVsQ^Mf`qw$vTb;Dsb;y;rz)z-`8S~+w3N@1fB&589s62yR884iZ z+yWwC)t!Kgc+Psae^lp2k}Va0NlQZg4a&)>3d)5thiOuQje~2fxH66JujW!aGIX#^85Vg zaz{Y>SpZZ2q225Dvl0wgJC2YnlC1oZ+L1Wt?}`x#%OuCb*7UVYTD$KB8}?JaFuxZN z^e3Ek_TvhN_tJevxFs1r6oVRz+XRv`D39b;#la~uJac>t>~@Y7KUkqFsOw%n`hrt# znkYd57;A!udbM8r^6iPn{kB{l7m)xoy4pduU-y!O6#UZbKn@JvSDOXmPEaA5 z2v_lE+43~jsuf8D*Qq~Vk zdEm_o~Q(D%_x4A_X>$5eiW2bb%CB7q&zHO1loM|cpkhSfp;kWA&s|58w5W_VC5SFoiP<>0-e$!tD{7B&bJ9u~?tgM!ShL&vS=yU>r#LmVy zc4i5Csz=|ivjP+WDmbNfyvS(tPClQJ#nl81P135_!mp_F5Q9B!D2v;T)K`Wey4G2w zg|(eYo3kn%JbP3dbUUJ=^2<;0th@T73V(P@yuBRv1PnHaP02q$VK)<5RTMT*rPVRS zuj-n6yQaVYf;R_w%j!@R;E=O+#_Wc7gq^#w@WBw?4%~@&P2|ApM^D%rk`-DZ(2tw) z66z3h4x3J!*c)K8XkMp0|6JI9QyzS1m5euFNfc%=F4E|h%0}rvM@w!=Nb#ExWFDIXc)d(S6_cFn`Z{lwB?dYV648xG( zlHz_rNQz4HInIA@$!KZi9ay18+yhhVuw>?SZlyv4)wK1UI^H%kaVoSM zTN=kK=+r|gYeob(n=hKqK_R2;FwfE%+4wuMV^V1ibgxmISkmhI z8>?J3eXFLVsI>-rc^63a72{ayi?fSBB|9$?|5=J2fpN!=Pk!Q!cdc8J%IaTs*enQd zJlumjYC??Ck4l1$rVEN%QVg0E^be42&DVGLf+gy@n|UOH_)hn zEJAH12i0#xVL>>8dd{QWKf3I@@z8!hNlb#uoS@l2S8G$$T%7tE9%(wHlauqi)#v9d zWJ}v>iEl#tHKS9};I|eFiwpd!-&#kE&fS^4xK~Y7Gb-*kaKT5fETf~r-h+E$LbaHF z-ae4_;Tjd2V1{IXW5zv6WL;50M(~XsVC)x>e_bU^Wu&ek9vm`( zrR*8g27m2och9@er-nOF^C*i5%~VBb_+m(-ot0Y8C%$es ze#0PKQwgIR&kqn=qA7Igi^| zS(gs|;J+Rh6sM;4^ThGQX6|hCeIUm$Siwq24X%BFXE)YJsIPpY9tqB;{dI;6w#)_;w zv9hlz?cjn1aIF9{jZF>Hdv^G}NjCdZu$pGT+2!LtJ(zvXGsu_&u4r#7$qTJFw~fsX z3;JU4iF&H?iZXst#HYLI^mmg^7rs7u7YWe2B`@fcY5KODeRF^OY64t>^oZ4L+x;Ue z2`%lb^0`C^KsQ}HiOjU0Uwu6x`uQlmw&$bBm^*S9a+mSn2fSKRU(dfMe*t~gRt z#ofd?nJ545OZ&EY5BHp%lNj2%r-NE;O_>$gJR`?!w_5g$^gNI;*RWMwAhfPmIOf0Y z4(lmQ(2-^3lhP~ge}R$5AZfNU{Il z9S(tL$&}Vn zirSYzxW1et+%8JX$U6f&f#Jrz(<3Rtk58;D&QZQhR`oj;k*7388 zKW3S|l}L9Tw?BC==)*1njfy&xq~pReHl67!1pB5xt{6ZB;}ELXb`o@zYj*P@jGO}y zy!sEN!~%4Dd9rg90dq5Of*3TrHr80bH!sxfle87^5lOZFx;;dghB&06s{`U`IR(3 zfB7dyXCti7Ofu2bN_S@sjc)O9EwF|{HonZ*qcJ8HBBaG2BkzC6rSpSy)CO?c%m{`; zKDEo{;slO={EP>S5tb*%m}+jKr@NL~8}E>zc|_Z@ZRZe z8Y{fmEi#5uAe#)+(^kcw{_E$A??hOfm|&*An}%vHe#;?}C4z|A6{4}nO?Af`swedl zdmB?c4Np--##`OaKyNG60sGI_5HxfQCC1X!7^4qoSxxBp>QC^=Kl~j7?X^_-omgZ6 zwU{G0*um4g-|+dL@39hIWoCSm-hpyMMSy zL(q-OW=0Y~R|}-O+o*7vkpA)ww^vq}nHZ<*L_5_!C$8hHW%4h9UZR-UuY?%cS^S9hn`nww^_sfC{2hC?R<3_VXay3E5n zPZ^urCM#DnbozZh{rDVh)jph78MGq#^74tadcM$Cof&%^7%oU zE4}-BsY*VzOJ_?JH~xH+M+;HrAB{3S)ImdCkZRi@)5c1Q@Y*zYz8Pa-Cyl#qfO8*S z<-(~R>O*d;_;b3*v8<(e9rO~#>=tA99`R^wncbp| z*8a16{P&mXZ3y9WSuu+SN+CB@ z&_EDyRkt&E<~)Nff!B0<2ndp?Jim%^uu{v#*qVRFqp@Wo1rt@h=lRX2=jf=f!0#&i ziMm=Kn+UToHp=zSzU1C=l=){*nD1$!wJ}7b%);at_eba1&WhA^ zo#Mk!-)E@1v78_iH45oHdfT57`0^$Z>;cW^f6U+^@N6NaZCGa zs+W0JGej)jTDk^CxHMdY)$}^vl`)&mJTKidbabu!t?QbB#aB<)zzA1P)xF-w7G*4E z^AToA{DPkfza#^G!7n%fMj=jkW1g|uZE}K_s;;wKK7W$#8W)!5U62kOE+=L^Pb#v` z{LU=l+560|b<$EF!sa*}0qVIpiQR2B6Gdci1N9vz=xDCP@3cH8Ye}}^^wrSX-pShR z7>^dBBvZ?*?__DNK8Eg$uA#(MSy)vvFdZ zYlNT0N$zg47AY`P2c|s3jnKd_r_NvCbZ;Zh?*tf~E*HUyAeWaX*p6p-wi#t7yhS*nQtLEv7*!NQ zDU#ZpXJIWuN)f5(KE=q$2q$}MaDL|poGvFWhXrkOhNWnVmAxHy!rMd=8r2pV>A1^J z{*}=32_oxD%x}agiDnvxKji$#Y5H3HSf9V^4qP5LE}KklWtx>6OJow;Y;5n5%o+I1 z9BNpXAjz0*GH;3pDX9(On~U6iyiP&(a`NP9`a0_H*?y*rKzU|^n%H1@X_b|oG!}0y zog*Lf-suxmc`PpyUk)c8uM4@9C9<%<#?xI=u`SjkS(Fw7%OL{vhOVKcql6<-q8SB8 zYYpxFr|D@7@?EoDG}-Wk8tLh7XKP`Gy9*0s_I3!zaugLEm-*+p9=ci}7g=I_ev937 z32%D`L+37YeyAOnNqkYY=5*t9m{Iq3SXtg+XE922XPfOcK+el!|&WcVXcrPzOlgFnFx8^LUZRJBO@aWc2;7OzrR=5&5+() zVRa|L;_e#j+i`Z&8r6rarclx`wpW&!+DM=aW?BZ%bN0+IJx#tBa*cKeE|(LJLngek z&5iL0YtvIKY@DE}+C#ufS>jADQY>m9$XFd7+-?_cm*d?CR=fgga+|H?MW#1Wi1sSl zht6~M)F7R;o)?lI4hL?J2diEny1K$zY=vZWp2f`^?I91|Lvlu8ca7zxRhFZ9?7>F* zE?nizPzMb``}5$l&F;kMFe7UPcDHtTun}Qle3I46eYmYAED{)of>J7>lyoGs8Jp9K z$L->;5ggD9dql%wB6$a$=gx8N%m59Z5{tVJF^K}jBmd%03qviE-(6*LeuM43BHoq( z`p;eF{gYj|O~Q*ntkaFh>!h^1L3m@Ejj27Nk!`kO1$wGnFKJ631ih4JZ*z(1l`yfa zPQ}0pPF=Xb>D~sM-{Coj(?!5 zgtv$!6`K9WuNqk|WZ2tWU}1fijAo*y{{rXFjWF0%@q_)ujol)^)+{rT3F4_RTj5<| zDUB+Ncqn^L%_WH}PBOQdK$V?z_MhRx$S_^C?(gxX!(m6(3uMA!Hg3bV;z~y#h z6BV*+vpiW%P)LT^jU~zC4MNtVJnbI`YI2Lsm1SnOQpnDlecm0QquTvF-t~Arn6(_+ ztE;TV*U0QHvbdF}yV8s6kiKL-vcl5RDl4%fj*4dbFI?gDP&@U0`*R!PTi&IRCKitJ za68QW_#~@W`f-?KERum?DCGgiB?HlF!S4F&dH1E~k&ClE_k=%w@q~@6osN-i-02AO z$t0zJ@vr~wp(_RQyDLo0ZxK!u@wE*xaPATp20L*6fOp*MJ$aJk&rUL)sqz}=&33i+anZh+bD!09f3>&LYS;ujnZza#^G z0;u^ITkBiwDK>)DbyRuE>0iUpF?5Ca)+*b(dn9ujlGRP9x`wKd7pM8%atPmLlu}W4 z)>l~DQ!xcAXzS^uK49aAK9L|=@K)8+*4awcy#+S18!WBv5bbTD+HtswSVPy*bPZiM zkYp1!hXb>G(Do~0GF!0OtotpNDypVq7{{+Ozz_tGT-3GqGNJ{L{S6Ebw-a=lUuu06 zBpd!Mf+&==7B$V_7%s(IgMp0IRY}L-Fj6o{)!=D*nyYZUWUxvg zxoB*zCg7Pv+=!CT=g4F=^uy+@1PP0)imstkxSBOW-KXfN58`-9zgWg(b<^BZjmJ5I z5X(}?=gHRjJL1G`}}YW2Fnr4;_5LgvIWqrKJ+bomJAs0_kj# zLQx0fElx|+vV>Qrd3b+}`8}1Y{`WXN)Ja{yaqJxLw+j(NbW+pW#Tmtm;i{$gY!^X? z`Q;86(Td0Gr?$?Id3+b8R3LpMo-;t#(DX9ro2*vsE++@q_lVeRHk{6~WQJkr`~39t zT?+vT*&3jI=pS^WK^eQW3VYWBc*p3fS@3A6%=X*7qWX_#!BfOL3 zFW1K@7FDi)IYlVw;{EfT|MCa)qr!s2SHtk-_sHlLnuZ2wt@UAjsT^6tV)Ia46U6N> zBkZKeWQyeThutU)^64b8NR*^vfE1#mw}tAE`=z-}f^5SXYN78$6JyJJEbeWvv>qka z-9*4DQJxu4+?TyDW3gJ0-mxUife;-8>e@JSNkX@WIB~Lz8oz_@Z>0i=W}IF>Rn>m1 z=2eo}40}nX+$q6f0tY(DNQ7uKK~6VQ>8quuuMxk?@=_JLWc5yHhy860kuJxept+Mp4QlTIrTYa<+ z450^_@wN;z)Z2*X0G<;h2cfDE6(JWAQA));nXHC!$R$;a1@^)b;;AepT+}r;)7n~v z%E*oydiy(=THIo8beG8HGMmv;)Ol=}O#4Bpl8UZ_*fw{L z*7^?EPh_k%FD-4=IIXk9lLd0wJh{AH_C4PCI1P%~ERoesQbhx^CrE2&GgX0?ht`TF zJAvv(`UaZ$;^8u}*fMKd5hAHJ0zng?qN)n{q6P?9EEeRWR^JF9JA*V2UgqCbo5hgd8@&M;FGsHOWvBR;3)2UX|-vdu?*Ya3mi<4kR> zkPa_1vyr3OZN*~SpU0t;WrAdxSlQk5ka{D~| z4v?`RAz6L24Gkk!B=NPMVz9db*MYq2Bvct96mTHV?@=t2{oljBs%kM$JRBjO$)n(= zxwGY9`%;uKIcn+c>tK3uoB2n(gf~{%jGd&`V?~w?45Lu)$kGMO7BgnEd<6OBZ=s>- zCGvR{<2ipHN4d3M@YmvJ94$F!Fv=~+*+h)+#v-$`E9{x->9vIjxlQ}+{Y7%|6=tXB z2q%jux`AOxL=$;bqn+j&FP5KyZ*u%$kWcOr+uk9q$^=~@>gxPh4;;QIAlu#eDr;$Q zo7swF+1=SCnarWr+7IPIiB<=8rw5N!B&L)|CsO1~D#lA;9v!7vAe+mV2eO&`1iV(v z=Hpk}BnT3+r-2h^UDS5w!DPo@Wyg9zLQ4Q7NkWz+1VKO$#r=xzBWyK-glMaxd$^h& zlLNoY1nA_C=xmrA9$ZcvHd&yM&63GvC~1M0hI|@^Mkbvhn=fJrCag9Oey<7n=UH?M zfFN7&*7b1SS;vWV5nG^&fY}HW-K1(v5prrdSiTuF8*U0Dcq|*g-LB?Wr;&oXL-D&kM zLXd4ZDmuAvwUWL}3A4+OFZ7Ce6@q{$$%s< zBSFSnRYlO}!eVTbNW_W8@@S1-e%Lc^Hp~3m-=1V=H_83cB@)RT|LwDS8=w0%JXcdgFyO()I>|(wo!u--qX$d|hE||h($I9Un9Z2Y zrt*7c=xAEGa#fVe-`1{U&0pF`;5(!AMw14m7kvaaygkW(J zXd2|ArgO>$CK$OHI@ui{^NhY$Wx`@T%A?SBvvmC@{0v5ZI zP+bi{vx!7LMPw&Ve6N5JG$EjsWrB(tAeNJ-`wq}^zBKmN;FS+vz~ZW)xxa$u{x@B^ zO0k${FP=d+K(e@TIc->vsf{VSs%SZJ0e9^HnrOij3gWaJye|o&geZyS^+ZON4$Hd+ zV318^$!1F!f*GqVKqzR%d_W7fAj&v=ek!UeaLUU>^Kn+z5)|6qU=zQ?y9SaZW3l{z zceV0B>%;Kw3#erGHkf(#m`BswD85$CT|7r`OOd&SWBNfJ08zGL4|Q<VsrMMcxW zZn2bu_yR9@R|ipgJ?~-|7@E32^93ws3#MuxCl0%p{K!(M~%Ma`+o}% zL_~{=K&6X7w?&=CPYC;EoMo@wip{F?g~#J3;5kCFM3At$Le#oKZ#Ym#Rf|NoV`TCr1hX5D*N5LN9b3om zZ9tICIDC~jd~f);&{0Y`cDAAv6a(4np(5bIb=ZL>Z-kDarrDaC;OUcD!kUx16BoI9 zx}KoR{8v<EEBDuGaroRMYi- zpeT9vVo7pE6~XMMBH+gBIy^t=hOysWV}K+hiLaJF6GXAR7G@dIP>DzP$YyisxDa&( zy;Pv2>Ii~>N!Cg2ZjcLSNu<(bb0st+tTsCimm8lyNGRyRYI++Y3V%C@CI_yd16S}( zM{4AAY4&0%O1g+-t)Q;Liqm>{L(DJ?baW8Q+TfD-3SUJK5X}~>4hJ?#Kr568Z$~MW z8ZZnIT~jD3B}$r6PM8{bcGnk)?WIVkv*l`JNych-;BtHM2ZQ*%&X+sm0Kw|Pa|~rf z{%VLaCcBqPyO%d^IVhy|5+ss2bjgO(?Iq+jAKErD3Cf4uXIz z>7--ZET;1$Q)#mK5}F}mwmEP*UHAe){605!i|Gx6W`A(Knp*A_-wU%a02*YD001BW zNklGjW@A`1sf1u!CXsBv|yi%44GMNO5nHa0{+a!`{GPwdJO~7Qa z;BdI`_<{udUR)0I&%87I=YwC80Y4ISrAQ&QN2KVarn?63`XX`dJ0FQ&B$wW0aXEpl zahTTDM(P4)jF3n!^@P>ED4V+l>YR?B?k4`#phTgNBaF6HGJ98{P{+i$C5}X<8rY_{dBq(I#+pNxxGx}tKi0Y<&@FeeDI!(P(KHPBJpE(Sz zNGZF))3If?qj_wBHX56osP)OnZ~6J?YMxAdozW*N#FGUap>7%)8maLdrE=xx3th>u zx3k2Yfpw3~!eC($5{gg0J zb5S-|mzY|JVwhZnYFlWnavkA0Nyz2^?SsRdiNs0Vo+dK$75~rwn`dOOgT`tfc9Tvi z9cOKRj7N`VSV~!F?d|96xnY`vu9u`!{&m72pW0$^agB|g3>IG_b@h$Z2P|*?ulo=s z35&&yBnlW>j!d>duAuXhj^I8tRYBD>G{c}&ERf6P&|cFsZnsP>Ur>x{jvh$?eW_=ZjHR7M57rjFHMK zWk=ZNBv92rXWuX*=T6eqRE5uBe(QVNj|xLaD%e`;LC$5V zkaER0S_Y+%CY{yL9K4+KG7Jn|Lse8%qg;WWP9{+_4Fdy1QBV{G#Q?3CBC_;|zbvlv zXmXiwEK5$&Fc7dfy;L{0(?4{IGpG7#srBQq$j5I$>`wxNQf8Zlg%wsdl9=6<)HXCx zAF>^4UI6U#oXw0Zix^s#T&_T_pusD2{tZnn^Be}HQju&ni>m3M3+VYgimsz-DoT2r z*+(~+jw~{_w8>5)hh~5%n{oLoX>9N1)R|KZooJ&b;KFj)g!zjLp_p7{c5aPutbje( zMq^_WRYypK97pJCj=kM=?mk>0l~ZxmH_=pILxoE^q&-)zShhPXh(a1w$&t;KP*npC z3O?%wx~ft#%F=}SY?ge!fNp@Gsc5Bg!VW_x8=2?+jc4qwFS4)^C7oB$5RlC_yp?tI z4xZ-J$$om<>j^k5`%FGrllQLB;CwTvZ3v@SE zVt_f_upwOYUB-TXf9s%Uoe0ksAOhNht@ zDjGVfs=VM`Lw?S?s$rlNlY|!^@~7Dq9#5?hj%Ug5^RCtDqqe1+zQG~Rp6;Wm+K0m| zzm(+Bl^oHPDIVQ>#9SOII)?e}Cnud-sZlD+PD7uEKDU?!MOh3HN)2(?HR=0^H z^XLYMCJUZmHI41PoH=`%f$p+&*tf}bL)Xwt3Pr7)R4Ao3nYf=|Y-gV7r7(NhB8p}p z$R=FAD%wvBaq`pm)KSJ`Y1J zQp~1^3QgBU1mMdTm2LY?6md?{3@Tn$o^UhP|7Vh%L#Zk<1 zc?hbZYbYfJLvm8lGQi1^_xW(R5|2$L{#I`Kr+|Tyi?cd0%Kg!C=3)k+&UOZed#QF= z-^$RUqe76(cxrn&cS%POM80{n$n5T z(jKR4MbgnV79L#V)?}DH-9>xf00Spl@R`N8>ZI#xk;L{g6ZdX&Ybs1e^fNF#L|=Ck zZb>*o_0i7}23jdgY;BrHH*a!pDUIl9q<5&Fw%Q=Jw_=7z|Q7y;0t)MNsuXRv%DB4-c(JX(*A>QOG7PY*jd?NH=U!X>&T@Nic+@K z1WiLN7AWZkxm28`M>mN&>{!e)u3#k|q3m=Q@;Nf$MegrzF*7yC$G`bC=LTD-_5bjE z?+Of*Vv3!GF&^F>WhPv}S<%kO)e-95HmrwU3jtTahu7=EEX2vAwpf_orNvo|-DUaS zery;D*?5%g)h!Z*5{hO;V{3t zu<3gckWFU10Us`#1=&au-rQniGext@&-a^P4bV$OSJnvc#K~yoAhJ>_p&AATpce8J zRSiWcvNJzMHtfW1F=KN0sB`rKDx=;@)GOYA9Crvlk_(FIBe6ct`#Y! zBTRh#Iiph>?BS+sc#!@RE%>ajDe5}r(A7M9n+uHHzsuLNQ50(hgF}OKwbtMg4{L7; zSZsDe)gkPrUDCNIYb#;)x*Ko@tlzKVH8cw81UoD1>=YDAhJjitp{NQPASo(JNui)? z7`n>xliTb%Y}m{uT!BhFBIQc+T#jsHnFn7+SYKHqeB~;a&va7Zwj5kFtQXN!(|qw? zKI8tx1}RNLS2a`}%nl#T11A}I|9wt&))8`B-eH@@K*=ZAo`1@NJEP1;RovC>j9fZR zo!fQC?FE~#4B^mG|K@eqRs}rvk z)MEDKthlD3DG-Ec&2;?agOB{BT*Sm^%Hp{i~N%ExcMb(Ub4coFF`Rj}hQ52D75kWBat7FPTXb*o*qujb_@IrRL5Xvo_yl8tj z3>{4=Q7Gog7gaQy{3Fi8GSHNAh2uf@CLkcmW+X{`qa$YMDoP>6#?(D--@4C}`8cME z7Wz(}W~i(B721kF0*vxzr|Sj=<>&vc*18}HV7%z4)pZS}RHRTSP$;Q5&C;u@U5+UX zT|-qBG~GDxJrYG3Nj_Xfzpj=O0W(kT^5-v}u%0pqbq;Xm^Z;FT9!zhoB+Ecoi==i} znS6AYFYipUU683cF~Z2{UOH-B?_^L$|4#MrL69U9l607NOh+r_iLOoa_}*>4xVu1F za?w37!s&r_s(seC;t(6UN#|;Qsb20@vaO5O)0&W!)4iW2%g)o zel4WgntRCCU)|-wR0Jv1#EH`*40Y9&ou{K-o&K$K!?#+bWsPq^C=XKKw;akX+NC0e ze1Vdpq8Y|dl3@Lpz%a^A$hQHdA3_jBB-vcn*nRykp=%0-RD`w3+uZo-33J;8d@Tc< zIeU_xMnBdgI4iQnfv={H`k;rk$R_Kv6HGQ#(HtD0!ezlMi{;kpQh{uIm1j?8S=rh{ z6%0h9T$O$p`=Gm{nqPe~z<>Scha^*Zu75d2(C^^##hyc7>)V2^my;N}@$w8#VPE%H zmgPh6lYyq>NkvwfxOaoE?#&WaY}EIj;{DSd)cI{kXe}48xP63bYpC-~6V0Vrc=m+Z zMn7I_<9@|{xnjALPZHal<4N8tGdWX(%ai|WLRXT#yn}DODhMJlRLbf#`dtoLx-!R!Sij8%5%kZl(os*T)RHX z^kxoceGjM3o}srnh~0E}+gi5R$~+hHvape4Yhi|ov1S?r1JrnI`|=<jzqTNnYy^X6sd2nqdHmA7t3}e$byg$>fsBM^$GXr$jyMNSxl&-00 zYI)y1*tRZzqle?m0*UYx5viPJdYkPkW|WCW9V9WO)1+Uf*@gWIq`@lEKWD|?LG8# zx6@J=#Ay}La!JB#3rszG#+|E3un?>WaJsV^?|~9z28N-bDGJ46k)o=jl?O^- z7A0g+d|?9}Zff$|fnhxF@H?1yMMOzHJn!aHY%M(F?$@`uGro=PZs5f5SuXTfBF0sSL)Lp*#@(FX{0^X*6PM0S}9tDb{Do_GMGBpGub%lPrR+p(;6Yi47i)PP4QgM->bNUB}RL zzEw`tRRh^p=3UifCsf-?&xsz|8*2!8ETHCzZLKgnInLAZB{nx^xqH)u-Q~vX9i-YJ z?~kSsFxhRmJWdRYlZu8mdU|{4XsX8RkU`0j*jZ=h*%O{jt+Km5&+RW|oK6?6^F7qK z58rwF3x0h3k_ny1vg??~aXoWMm6P?k_Bo%IC?IN(?nO{^-d7 z_;xH0fKZOaA4cv+5D*N?I>JZT>kLC9ySv1*Z$9JCw`Ymu%mh2$hhvg_)hrb#Ips}~LL^z%%ufBYQAeso&mD|GX2MmpS z{!6+_F|*6s_-+2%XSaB^u#4(xX87XAT)l9DhJfQIYq{680+EHse0BY6zJ9!l=BS|i zLO-VmJE;pgkxrFwF#2eg&9OUt9*dF6|C--i?!aq#lf!bHpi|5y*xlM7oGKl7 zgw?XS5%Lq}7x z?5<33>-r78zCX)m)=b06kNEVXbDU@n9myzt9dxZgczJ=Dxiw;jhvB9+dfGzoxD<_n zp(`Y|m)MDC$SMaMB1rga+o=gSu)U7w42@DQ&c^s{{_@3b?v8Juy6PEz{}VpBG)Qx$ z>(yGTuedf{%d@xkly9zm#m$GyBs43nXD@MPpq0i-FE*1wDHCU7eu9UOr&w5c%C%IA zO!iYgdcT)C-@8=3Y@n8ML{}Hs$tWn=%SV`OZi02KRJx?sJj?Q$X5$;oKKPP9{P`Yp z+c_K!{apU|11_Czqrzo5QUXgfJMdJsbE?0Q<()W-TT?vvQbjMMIWycrt>1=FN)g*! zsNsdS!y{QYC9s(f^H{FnoUbqc8% zJDVHC^ZSnGcOVE7Hg5%0)z$dyuM374=vsl;+5}H;-{kk#pAsopsUJAYhaX;`za@m@ zh=l->%}-5JJEu=fF}0HCHj)ht`nce(ZDZElP%kdZ6s zJ9&|hE)UZZvLD$FGkKb5@9dzjb&2a!F%}+P=QBOU-q}HVTdQ$M3hC(nFv%ygEJYMV zSwzyr@|*$60T`3bPh5fHJ3Y}G_^=)R|hS1x3K@|1~+FT zEKH2@tfQ6s3LiGlyV5WYZwGuyuu9A&!viRg1e*f7w zOs^%d)(>$0>IYms*GZ+@e58UELAK$pY-6ymg}IFg^O1QT+<;Oh!Fy+WsqtBn)C{{D z3yhCGWORCqy}W_VB2)Noa$1m(9Ch@a8NuILz~rr>xuuQfx)5Hs9ji$KL!;E*MrV5q zb-vH}?B+8TH)j}s8l<(Shl(B#X6aS$vw@+PNN&$FcJFKcbp0W-+gU2QFL3#TOPuR# zz-#?6Q{g)K)Gm?jFtMD<%k>=sc7F}kl_C7j*W1>bnj^6_&x5b7bN%)t>q&u%6Cd!~ z-&|s#wG!7+`O@Mc*x1it*92P+R@j*z9f)Q`dn2c=d`flC9=TGUbRx>;+8S#cQRbiAW@BlA@TdR4T8QCBl-6MM-?^^MM>ZlHRUhDs2=xAz&&8a(F`{EY2pRSNKS8?j>MLxbf zOrzg+bl&wg)7jO|iRop&oQW~_@EU(2&EA=TvXqjjkO(g`J2A%S<5||C3MP|?s0%N6 z7ZH;^Ky%L!7p?UeRxcF|?euok;&(f+?024ON|CPaP8uq%apT$@ZY^vvH~xsH9qrWk zT~xWvpce_xJ?7#4$4u>tw451Y0sArXkIVD_qH7C;Gv&^cAHrmJ6R2sS+Wk7- zePLftKe)*s|9qF}%{1<&AufJ!l}o2v3A&D^oiCakc&geMJkiMf<}Sd#(FAVF%bP191r}G3^*= z9qn6h%TQ5O4FmDT6!2g0H-#XG`w~UMzJ8&$KcMc_&~>A{P67y`v|p`xIOw@eR%ae? z{j0|;r|mQhyvN^tFhYNOEncT(e<);;d`k-rH6dI#uJP5gc^-fDdukdg8Sot7J-l@o zK#`?~*SP+0iH+3D*#Oz%(M-Gdj`S25BcqHKHy|`9U+(b?HK`Dj>ys&cdy^z%LlVW3RbH7F7caRf52czH9p6? zXmA*S%Ff&p(}0}RwcoYl#Pe0BXM_r}&p;-%~TkN7vA zo};J1kMk``#i+S0mKRr9*+^ll7^Jbajhc75Z5ztfg;|zIzu?QqE3715<~h-1XZTnD znU7C5Qu`{NGgNZ%b*3JC!xuO1GPbabRN2kQ#jAXJWthg0^XNLrxCRAO4x4$0G;dMWLVrUf7 z5hlL;C%&9ZkSzSrTNCiqc5va>wY=Y9!z8`pyU9HKWV?vOzd8+BVc!k|WhTJzZY_CmoE49P)Lk|wCjG!qLav7rW5_NsOv;}uq zpIIO*l`H5EyZlb4l@G7<5{qTHH@ZkHp5g!aKX35A{x83#vchw;>;9{u5?i0;n?L@M z$6JN6PV{#m$rfr)yvNm#K4Gv?dQT3Mj&Cu$c!zj$m*wS6 z_6A$1@*Gx{;ira9F%xC#`tP{0m_DEwK)_Yi!kJ(F4}8?)!1YR=Q%Hs9dHD5L-1z1R zlgoSfJI`|E;}5uax`P_8g(C}D3KCXN6+P$Q=W;AT@%9ue>$BWVMOb?FHFm3npsN(J z8RCf&wF3jR=XcngnqfnfkmUU?LDBU8v-e(KZlr0N-!BXT-X@UV8>Tn(-kY*r-7`J2 zE6u29&T1uH$gGa`O8<#;j&yYP%)VBJe%m`@QCQP<-|5Jz7p@)<9IO*zI<#%F{BiA{K|2qAHoa zN5jm`tq=^)5L{khY8Gs9fFc!_IwN0?kmQnK?b@1H%)fzDd| zf7C=&KAsED4RQTqH}_{Z$v&qUD^j`pea@Xa^3q~}k&CfB*3Y%`7rE9q#d_9G)t;k# z{NV|@>WXl@Nr6LDaQLg)bL=RgXol+#=b0V4Lt<@$yKXyXlZc*86W>grTileicVeCB zr8l{W_zk}FQc~B+sp2LyBcC{R+AR60xF`3LuzL!rw3^s|c#65@7!T$*85^ErxvQ3j z5*wyxlNy4IXbw=<=AyDuL(_9))fDlKRi=j@aP8uC?o17HO0EV7?aUX#@K{`diL4+i|?8 z7@(_cER1mPYB!f|^fNpgp|Jfpr%oT^*xnr!zfpWCVRe_#a_|Tz!keUSjIcB}!j0%E zWA{AR%o1o>Qpq?Q8!Ba8ozy2+Sr{H=d5d=?K|l~qjN9SG001BWNklop{X} zvB)Orj0?jiW2jML@f3#W!0mGU$P+C;4j3qyWHV+(1YIYmX2|IIZn*9D>HLUTB9%io z1Z0yLv+3I&_6=golS~XfVt6@?y`qKAeS2wds>J_PVpB3%aCl3oZQIG_`XW=)D-5iS z((_=Pk`C`%``cd*o#@&!vs1H7hM!mbGg;kKZ>GuQwlAC*T8j0BVeWQ!bM@8$!;1+@ z+KzDS*bxrzZlug_f2ADL_Y0li+KojS^{#u8js`SlN=FS=K1jmd!?u3Wgv?T0hOWIt^Ok8$ki ze)cq%VKYl_?OuO;=%k`yR_5jyn~HAp{}PtQ2ubzDV?deB1qSY3r~ArndPi3g{k7~r zc#Jd0_R?69*YSUQ-;Y6bew3-1C03Irs>&;0%O4+6AWD=zP8NV^c-Vr&lhH7 zvz^k7)C+kIU1f7+lsnzsT)o-P;9QJ?hP|9PeVT*28mKCCz7fx9*$nHm;|vZ>Ft=_{ zzNd*pCl1n5Q-JtXibOKmaQUq?@7_%!8f0MbD(ef=3=GfGRU5!%`To0?-wyI}G8;=v zOi!#5N3M5W$9{L`QFgCTy(o_gdkg>bH6qZ$S?8q)!8muhdy2iqwfyr#fY%#x9 z_g{g}!LNU{hqd)6W8I=qXPnnGOGH!V~OC^jFZP5b%P z-E*%T6tjyVCRdgb6fUGPN1Sx_ zMR8b$=;|c>x2|!iyNBWVIJVM8PMkc$@%?Sol(?|SZ<<^auz1U9-hT$Oqk!_e4;Y?Y zWHGqN^1Oy(wc{%+p?=psIy!4{r02LYF@z+7-Q~HU4a(QNWj0sEzArFWCN#Y>d$SFx}@b za`XN;GaEXU2j1h<@x$zEucpXjeM5;j0m)>;UE0Lq4@6wW72N9^U~GDog~<@QXu{@l zQ&e8VfdlRA?kZsM&JC6y8kp<~7F%9QNDxF&TzCsy-{O8&JY{uMR}|tKUSKvBBODA8 z*Bh}J&-+g0k|E|t`nYoO3U>zP+0dLcojAk$XOGcdTS$RZc@4>xw*{SaJi_Y2JmX^_ z)aM?Y2&G|S=@&P0X~|Va?%&|*mD}8YG>>X4rt|o5P8`|G&cE?lPfup&A1B!RMmCS*3m#!KAA)XRwpuZp^Zp-#q+oF6m50YejuEUqlDJf~r@+6k0YQn$OAuC5y7 z@HpLL5|Su=&AUQArg3_#IA3``2{fH!bY#uf_9vKRVr!y_ZF@4YZQGgHw$VvCwkGDp zb_WyNw(Ym?_gVk?)VF==Q27rh}d_!p&X7j$D%^d60947vljI4avlB_^G_SZKpd{;-i%m&8~FTL1$-usA) zXpNR-zJJEQN*=BxI^17y_2kSjJvaEfk}>hSM%Ckdi})j%B&amfb2UY9#|f3KP%Fu=w=d@=-szs)SQ-g9IB{>5)d<>@+i&7Txi6oFF$BBhvf z=$A7+gY-yw=-CiG9X=0cYP@mxJt5g_E+w>ZuW{W@Z6@j+{jw^+)Xm#h{Y$?h$Q(no z0MA9_XFX3{`h-tAiCOH#Up4jAMadI$_;m`^WY4h>fYphUFzhg1l=7BFX*%l~t$r41p&_#C7lj0T zt{DPVYRS*^LO**x=$$H=7|`O#N2KH-2M3ced7Cb|u|&ta(BTo@pUzpMLEIJ2(F1H8 zmSN8lGl`Tth^kYbd(gjJZDss#t-g8CWh^Vz%L!~UD`Hg0BCQp^-f)0xZGM>1mH0kF z#1RPeY#gvwmNc^itIU*=NQQ{k4pve!*YI>n?dZ%Ndrb&<8pHp+7!w>2zp7J$69Kzh zJQ#zglT=VY^ID35#)}R97W%hr7+_G|0+`%=ygfZmDJ@0z8ke&*)y1e?!C%8s@M4Yo zGinfor@laHTIDA#Jw|i8n&8L(ot-I!TBq!Yf80s~itzdn<<2C}OipsgKFhHW`3|>)D zRX$P0oFV&1BRYA;zdV!I#3y8_wDYg*M1sA;9A$R!Mv$BacyfcIK>2eOX2iLH@6kz6 zYb`!0tM3gVNL+;BkB)Z(j&7IKLpG`1yE$Z}BX00EeB4J@%IXclU=S|pHG76(-^tYu z6HRG;K5{tkKvXqA6{(UFA32;X_lGwUCRW??n9wSi=YH9yg(RMyqqj@^k(>E;P=mZ% z>%S?Wft~}x!@04SCLhFr;o0{A5hkUPQnTwR?rgT;NTGZbGyDaW)Aue zNfeJzagSt-q9okZa@CG0YaFDjzRs$@=goDGZbny(l%4f9CGC9X>BqX9mCOO$_5ByR z{ByDdjwyD={ghIp?UJn?SZq1W_&_AsH~mhi3cC>`T4>mZ_ov7#7xuRiUaa$2W%aP+ zpYN0nP|e*T04_U!&(E7ma=`O@WGM|FoXFc5cdj zqvk|G3Rk#N%9iGDK$`TF{=>i~B*bBZYpP-dEQM)t-T%&Y5s$&S#(uF10eDv3thgtba8y-EODgRg}YNT{D-9mEpufiRIa?&x?+m zp@eH7NA2Sto=;Vo#S<&>e~Wl_Xq6# zgUum@`%K-y(+i7~C);sj28G4mJ8KNpr22@${BNBfinY&CWmfhDL*C(2+8JA;wE3~P zTK&N{0%MdTl=xT-?c5YzR;!eZ?91!PTq)aicEjy73pnD(ovy)j>yLPPi!{r1(IUeN z4wedRY7ndLzvs{}bwkw}dHJ7+Ztc0nmA@tphSk)@M3qa^zVi&(BLhY)BLFFo-6&#y zzHz9g`0ANZ@#`U|vmi6pA~q>j8-%+D1=h}bI6p2r6_nPDEFbwHmQ;NcW7EKiN^yH% zphWXzA;W8}cJ`bbQC`=;#AC%1t+6B4jK>psce$FBS#vzosm#RWSP~x0@*Xb&21@I- z8dvj+dBit+ZIrX!B@o8hhEmAz!}_iaXfLm}DLWV$Wq%&2kr6s_K*cgBX#Kd~Kv!JO z4oT24D=(2Gak@^kk~=$Y@la1mRF$A5OT98GB5?vRQ8d!gbGtW)nt%z5+>RAZnqNU% zoYCVT!di+svUOR-#V0<{uR^aMGaFE$9vl9#(L?Q^b)o)2II}l}aQa!`swn z`pNKdb&TazN|qM=o!jXSx-|YgpVH9Z`|+js#}`WJ3>4*=H?QciDb^ycR1c4H{@mMDNi*NJrgHko{!W zPj7TNdtds#xp%kqSfs)(q57)2pKp(QmoCpM1}#45X|DWSbSB53QBJ3qv>(StaJ!Z1 za+nU0VliouOc*bq#3*w9-e%;3(j9pTMXIjBl709Q^>495c`_uO_~{kqmDzD>%gft+rPr=#j>GkQ((#@4gNC9M@hY1-U9|2*)EHAI%MMp z$jgsqS_yLAe3%@O$WZdB5lZ|y;l9yc#M2J5bO7XBjOn&LM3hBHx(=hs=kWFBEPR*F zVwz?2KUatZ9TeA_38k!h>f!UI$4dPdd6~L^rQ|nG#OC|y#|c%UAy>*>Gq+)d+8c^; z2}KN>e~A&u>EnK_Y`!9$*LW6Ji)-Q@=f4_rrC!PcoYkiMwwS3D2=glzKHbcCpz*@H z0oeW&3`|?COMBn9uPCRpL<48#0yiU%(+BQ%OOiAMW~pH6e(Cq^W!jAWR0vNy>jphD zwY9Qgio(x1UG34t5pKvir@zA95{|Kj$8@&^@6Hp}45zk9Q?`vuPR@7auIQp`h>^i6 z_osp*Lxw)3V0S>>G$0p*`% zT;`FG^j3G&udlyP0AfP4a&j%m7z$b-RW)#S>us4BXeHsJ)`K^Te}t>ngUHKd!zz0p z1;3JK>djs7N}X3H)wpISjwwK|op%is+XTx>P*}GkJD;36KKxb3@F=qwIQ{htym(p* z{G8|1$;&@fT$G5Y3|&%mC9ep+fd@a}Oa_Wgx7hFCa|}F%ho8b@00f3Q0x8sqKS$9R zYnoYGLluG#Cy4GE7A?^sgL)$pO@x>)S(>&rkBi+zN(@zEe;e(aB?Bj}e}H?yQI2%WNkwt%mtRT1byZGT zexc3e)dd@!(&Bvw&bZ9R@K1?FB*gU*96Zrui^yAd0wEkIzyAb#;5C=E{cHUDsXQ&{ ztVeHISmIyb+6^y$Bmt$u*OZib)f6mae;lV0e{|G3?+)lF1V>2{U{@anYf(x>hWf*8U3qFe|ZHL z^${a^WlZ%k3urK2Kc^U>H=%1k67HX+_cv<5>Rb0bi~I!Kgd>ZnD9y85%lkX3>1rsc zrNor)%hkwIl3x$IeDj6E{cdfXU7X05^?3#_uxmtLEJwiYn9(rou6$D0AutImLPcm` zaxzUQ_$k8WJIi8g27U#d<7OpzX*mGe7SX7Sm*CF}cnUp3+qa zHnbE1*YC8=12?~G1J{PwZ!0owOL`U+MU4`PqwjXHtX}?2&Dzq(PCM_TcfZ!>BB=xb zJ0*CW55DQS4%XO3wGl!?gEhD4gA9JkQe`kq1j1}!wI!ai6_N-lD#f#eGV~MUl(0-4 z_e%dfg2vH>-p|Jcr>g-gd7@Q05s(foG%idVkRn?eAZ^xj)??ma-Nvski1l8-qTtV7Ke!|Ao&uF#{@9Y}J zO*2E1*cy8rs>$q~qa1N*fdh^1;pVpZoX>13m7*CdObH0Liu&06Msdal(AyJ1z9vki zSaK@nmg62i-Ao;G@1SQ8m;ic`U)h!g8Sc5tVX`-4YD@zBg{O*S>jukNVdf2rc83U) z=4TiAya&%oFA>Etv2E+G&rdiON0kf%?@ixX?+C0Z!8$S0is&>#PmEm)|I@H)bR7c| zd#6N8^?@^nlIodAvBaBC9Bnf*vlIvA0VPFAGc~wsJ3hxAMT~($BXuq|TmWHof217C z`#>ft(iEUlo_}jJl+I-{lVZ2hbn|*Pi?=JhbO&2Jb*^V<_LGrRJ%8s*FH z>(@=a{b?t713erG`P{v^d`@`6QT$_&kUudYLn%O-9JJ>`9t{<4$G6NIYsx;}_r#y? zg1xRSZB-W!84oulWf%61kqKjMJny^wiFWxlU)AbZ(J>Eeq${T}jVjW(JqmIrRw(_c z%_ipv8SRbIpMZqoRJ?`Ho+-A0g_7fTw{)3B z7%k9>)lvf(Tg4-z^Y`<0TTf(Q=gLrpJjcdzQH`{sVtkSwW7gF6!uW(PI}Hm?L?tpz zT~iCLJ`vsVCHhY#ZSQlCIh_Co84*GQ_C$c~;Es!N^AfXEG5cTFyr)8@bLz!= zO*s1k9RW-rrplh9Ay}1ov)WW5@QE7*TNBKGSsnA}xc`f5(d%&9_wRpiY?6fgwBm`U zOlScAWr<2z>5j}Pf~UKc6R>#xn^h9NL0;NUz}KWZOmNy%3ST{Hbc~wjF3)zXou^SX zZAv`ILtDgcrM6X9lVYT}Fhm`wi7X~{V4J+Cu1IiITSZ!Llpq(jycCl-VwuM8X6wcW z%zazl9gcNB+Pf-+k^)!!F9}EHa7_T9r;wn8Q4>w^#W)zAMsIn|f~ZL{Wz%GZG!{P6 zm|Nd4)m2rF@l1HTz#w4mXhN(dtYNMaC`1N1Q?o$Ow3T`iFQ5=`GD-@+2CM-sOpWY2 znL6`+g9KFmkcn>}F(t5f_k-`%q(aj(^P~_j9|)g#==c%>j6>5xssBD<_>C3W|4aLP z-|cAKB_um~KFy2$##RM>zbH8|;cJ}J%N#@o9YSqa?dgXnZksq`Dn;r3VhDL=6VI7H z&R%b)p#Os{<^2U8d~w#gRKhm?s_c z)Esy3F$AN(V@el@*=ZUXj4U2LCL>JtWJuE|BeAvAs&D0=j0D8ck8MhRw_N6y0Y}+x z`^fJq_?ly@JYFxDrO3@HC+Z3QC!wjSeLv+w(ug{SpP4S1i56%smnJ|BrQB0m;h(PX z5MgmSV}N-V7ie-&h!nQL(sRBIk1;|+rI<>Q(x1CmYHEkBRWZ;d7BA>ti)g)baNi~v z8i~rzJKp(a4`Rh8s+Mk3pOJ3TnTK5tR%vagm4VPss(0UU#~}?(10zI4_yF7FY-xLg z(#R?yHXIICLo?P4tqMC!kO{frm`WEFJP}wKM?>j$dZh3{MepgRoC!DrlO*`c7`$SC z1sE9~wNky2OR|=fK7&TULT2U{!+^-=AJ7?A_I4$$efM)NF%aUwr%_a>;92_6nWgCO zWtG+WQ)O2rV`7+Mg4~NBbNa#JF%js+0w2c@lCOfWu}BopLqWs@Fs&{j6RqC5{QgPX zgX9+{$nu^3VIq3>n631lCey#~)p^^1@ws3@buyN0{nP!uSH{RFdp}Bex^|@Elt)N4 zkXG7vp%fqrqivovwe|%i3_H>snt$GP4k!eCosp`XnDRev*7d*?MrL<UTBsf_GAM>Z_)dPT2*2k2i5vUPTjX zso2MZMRb)WXX-2qG=wJ|(ATFke^4u($jHGEP-|XXd5@ZX|JB1*L4o7+KO}feJTo&9 zDP22F)v|E*W|S6;K&p}52?S2}Ths;!L<3+p zf0viz4FxYp{C;7N^5?}fHXr6et5YB|<4U=B79L`90H*`yGc^s<5G7p1UaW3^!@KU& z+xO00l4JlSat`lAYoQ)yJ44zAP14M7gkW9D(LPNfjqbLwEoDfH33+fo0!7;06!#Rn zd;?9QndY;?guCE+$j1zv^Q!@CX~mx#sAJOv4>#&=e;1XGlyi3W`2CqCo|2f?iV@9rAyt7wPuad^{L9v=n9pyyJa^5)qLD2j9dNg1BNFvdOAI zr7g#T2ufK}+;m(zgv<~%y5L>HIp{18`WrUykhqK`a(1o>S#G%n)azCOZaa0^E99GM zack%F#8;m`M;kB-ROo*S`s{2YB-TbTH5**6PNE(=&& zei`mav2zFT7=?w13ZX3H`cc+yiUx*5q`@U6-{c=0KgQ_zHNlk{!9G_YEw|rPY~>ZA zK=U-BOk0&;OjpbneA$`YDjY@i&?Kwj)zUJiYZ6ue-Zl zl3AmtTIG=2+Xp8l$0EuK|vm!T5toSjsK#B2j>43g=cnBjAU~pd)QIe2PBT68swT> z84-7q$^6lzS+C0^R11BwHPAq8oTJ>{f;4f?jEIU2y5Sv#WF#<0L%qgKQC3%z@9qC_ zeMKPhE;5IynLzgjrW2SdjkpJu?0`o#DL@0=J!9T zIXNUHocS$f!JXc#Wysu#cl5`14J$`FODD$QEe0fbF+npnGD_UPCkL!cUa39bQ>zp2PLzhbWxPl3qjw>nD&&-p1R%XPk^^t}8Y_m+YlKHDRB(?-YWq5kaBm z0*YMR?c4Qx*m|IX1V2piG`y3-Qi}jkL||!2Y;d@{vdWG)r+%+WF7<2_A~;_tdRJ*x#(op=>^$mYPuGX1qqkfB=9B&lqJWIGNqTyy+JXsfQxGdS7fyZ8k37ykrAy zxvhSV{Cb2|WU;Hj-6aueUEEHEZ9-11g`wo~jsR2apx-&W2tcdxI|i&v`zQ2%A^3T} zNl@G}a!a`JeBLuPBO1)M_SP>(BpW)yYqQ+x%|#fy-!h({VlcG%{Ql$!p+8v?QO&^m z7nd|~+A)<=S?O%hW-^hU*WrJ)0K^7}^#coscx}GHV}-(y;P6NSRfqO!1yhv0{utNh zw(w4`b+pGAaY9?x#G7q?uA!NJJcP zB4J6>_-Vt}elyo}HUSQr*6I&k|E@8I}FEQ2EF#ce|f^g3ZnjRztO%h zd^P^Pd?&xH99Yu!3sY)fN^K|K^QC69$igEqLUE+)pWfNIbzTpo7iT|$|34j;qlS91 zOKA3#r4_{Zi~AX&I_VYdf7|b`V3k2n;ZM$_gF%1b9eGpO+nh2j``E}D44&Q)-k-dJ zM%2fo1J+mepCXUU>)ew5}XMq6rD+N{AJ=W);1I z%^exE=!u|tdT_o+Q%W4nqsLB#)3$+k)W#xL`njmedhM!i9@gUNoe&z!Uf&+l1WuN{ z$%~q1Z9vl6j5)@KX(3HGeI5{wc2K${<7_o)F@qp2d1gT1DovQ<*87NM517i(WDOwt zRcpfLUk>RUcMVF|R_AxYLL1tTFnPE0i@dI-(4y`T_pcDb$%>}WQbql@N|v$62GQ)qsFhrY~EvDmRs#4QV^}T4zF)m83%;|3TWNt zQg_^zP#H-58iEh$kGh`E6INn&9W@ih0<(o}c2Xp#q^jJQYAZ{~ zg{FJDssY^Ws-ETrPKugXo1pl@fTmk)_+XH+=qn2HLEVq$fC zMQ&7$*^*9sb@%nqa|;1F!RxAHYC#IfP~w@nx`lXayy6_W3?#l-vdA2XTwLTS=~B6Yo7Kb$&j4|>kMfs3)|{~A2wJn#+lfh z9%Y~zq;{@|GAbas#}njiYk6-Y+PSKoPkYG|EAb?j86Vt%7^s|DFM(a9IK5NOroVRi zPl$~jXrccpN6}W)+Bhx%&9(fs&M0X#_55g~1=7gTM8*L6c-sp&htCBT5Z-1~u!0{G zDuZ93L^PyAf-CJrrOb#WNOB1z-fd#B8l$h6iY1ltDA%^! zU>V(0O-Kwive!okk?#@+P05?(VW?0~rRSVD${%{5WinsWheD ze23_MJ7OnlkD-RcZDl`gc)vrEZKyBXsjMj&F%yrkW`2$GmcoYZ3i<-kjJ2J81n_;G z0vH`o!5rgfP-SpXSO4z&9cpTsn0}wCOD#R3jzSSCsLT0P7LqIKNf+e zFOT8*byAB!kXFX$d8a-<30~gma>wHBVu3(fi7Z_3h0Yp*@W+32i4?A>71hasIojX~ zj63}gDp3YdU8md}@THaxe8`vGnkZPU-`bn~!K2!c*;X#Tk}2)Dx=|u{-v0H!5Q2R? zHb==k*pXh%6%*@KX~u?rGF1QN6;qaTO<%|?l=0^82g)`dby+0rXX>E`Fr zsd0eiknOFC-o>xuNmd@W_*3gFS=ynGIBOsEY!8R9I#>bS4naxg>fQ2JM+ zs1ONovC-=xuOukPoDs+!(IVvhI3-;y1r$*7tb=h6^p_psDEZY7c zcr0DS?YhPTjnKY6x=iV+M9h-riEE@2oRvO){D7JjRu#@KF%!z3_?zstG4Z!p+&ule z=SX&-nQ8-yffS9rl$ozpT&fT}1V~9#D<6LmNMp{(IviXhxGUry4`B0N`aJdT&m}JJ zDc@TR{ozeRPoK9$=jiSg7?^30XGTh}viL6!p6M6w_?jY9v;F-vSCi~NeQ9qMoY&RS zIy*TQS>y9gmQ6hq*L!HbMUuw58$CaMP*jX8Z3py?a|}woXvHo4LQVxt=zkYEa;2yox%ScR{zAos{rc4pQvdalEcb~J z{9K_+iEj)I!~TjQD>xI1$z!Bnkv1^t6a@vCI_^HcUbl}wdoW^|`EEh_f94XQsWZ$G zzk~>VUVUS%pxAWzpdkAMn z{uVpT-BubX-R)YjMYBU)nO9Pl4uqYpjQfh$dQWjYfrahnKBKJ>Gz*z-nXsHFaku8x zGu6kdH7FrAtN+lfuDruS@{JT2#A?m!HqFXCIW$6>)S3G9csh2rx+*2(i|1Dg$AD$z zXdDraLNv|CuRuzrsJSL;qk>fIcgnYXS7<-Z%<~q}9y|svDDfE_`ezQ$@@ql<`X!~_tO-yf0{-HU=Xx%yk-Sq2kF$Ot4YrITE);ji~38tM& zhRfZN9P?2~{{(>$jH5=lc)t^iN}4g_wd{CXE05 z-N*4IyQ8NX;C9CP*G}+^oM@t2%ftG1zDS>}4yH0HKompZ0MdSwBPj@N-THTpXHTOR z>y>(b;^g}1A);c9s|)Q@Fv=PO=dZnWCk7-bObE`(du!%Ny<*sn6 zbGE?Ac8#a%hbC``y{QgnU(YpR;U4Vkk^4Y3plWFek2|oA>M)N{O)f4YdAShC`)vt! z>kI3y%YLYK)0SqCEQr{0V@=oStQU`quVX0wY znH(ZYmvVv_Ga?d45@|M;BW82mXQ4mHJ9`j1Ym;4w^^V?}w%43I$d+5Gq+#=qM>Hjq z8UyUpmWGs5cl*!FHF{qSAYSJ?-*^<9(ufQ;|AoG?Bif(!F{aNGrX{^|ss@7hLVtmp zplUNXc{vuo?on~daG>7a$8)#I(`W@>6}bh=e7n$||MO}869K%T;hw5;ByMJ+oYMxh z)crAfgFGjO`QDI)kJqyxM*dw=myh09qI|KWMg379G|tB^sRq`w6m0GpZSj2%&&R62AGPwd$jqqYHd~mbO`l_hGI)oY<=WRc zSsMLEI?DI&O6XH#nC3?Fc7{DenitK2tv=E?I>{^J5E^e#UG^}N&D4p<>ChWjGi&GN z@`Lbkk}j>8d^CpPeMyuxn3CtuG50tuadzI{wf5rvm)Vevs0Mbye`hO{ky+wS_7OE7 zj)2wNE?yRU_%p*#u)6lrua%8S#|YPQnf+Qbc|;uAom7nS^{xPwh3}o6P+;u%@3*=d znDkt{t({TmMIkm4gy&AGq|pRf3z|Qx!^bH9oQ!`H+Kc(n5$*;3P*mGK?0@9_RyC}N zB<^|TkkkFz{rjrM&-sjDZClPLA)=Cvi?>%-mx9VP-P&4+2aR(yZP|4KwGSM6lx6b$OBppRSIRuL0tM|9Fk zk>wQ`VpeK6{YLEPl2!de3YNJQTRte(n-E`q8YiulE*{|-7}a0GBZxFJ)9JL$WrUTN zKU)zuM4t#;UZ?uI#l&U&N_MC3O$+ZG>O-8}WrLp8a^V=*`n$>M`lvH963KcIXK=gu z;U(05^8W1`u2-B3>!gBK^iS5L*AhUmVM&V>SGasATy^f@!WrxPqM%9RA*8w1sC$M5 zxb{a2S_dr~cJgK;T|gCQr5kvUMowSt1Nor_eT=Y58kV1wqdQ*C69bn^UzpV>Prr7~;n zPxp;+miODXZ)uffzTU+DkL)X3Tu!v=?pZ&c_S=#zk%kL4_%Oq{VNq4%6H=C)| ziSngV#SPqaZq9FOJpTw*0yUns^<_{esBrX~k92J-@x*M^o+ z1a~Io*^T^5AziaoZIhl8S%93z5W)TDP!LOL;mTL6mT&~w@qkbt-s>UAH%(NgtZ_qY3x9 zyWi|k@cxT(s*)?A>Z96xzMJ~VDslGtVgVD3A9Jr~V*kYGuej$!UvT`#I?P2|toF%r z%{9y5Z3mYjg@|5fjV=RR{C9S6HVntUO;?RVUkg6oK5TgRDcHdAV#T6v);g^vfiMKEV9%mzk7n`h(I(`(F@KH#=UzwhXKL)|ZSOT6K z^EVy%k+#N`@R73m`Uj`cAFph9&ny7E~z>)MVx>QuSYzB z+zsK<-RGy=Y6*4Vq_Xo3`*CHITV4G176D3iC9~IIG*w51&39{FIqmtn7qG_YK;!L1 z7YFO>gS*qOT{~ep3eB7}Q*(}A{Hejq5N(S?t*^_?TkAc@ZiJrkp9iV!4r%)xhpL<+ z#&lgSw*Bqc8Uci`@y=cpvO6bV8rYz8wX?SlEZ}F7_(j81DWlu1nT98`_vZq`4m}o? zr~1m`{{g1|Iqz?fk72xLH%hCgQrq&5hUaz+mkG>s6Dcf?aYCxu zfx(vMlIEZ3I{jnxF%NZ|d;=T}G(sF@r+f8aAr5<+WpSk|@umL_(XgBP7Q4T9*<9{* z|CZhgn*Y$GM>E(fMR&iEkUM-?uP+!j9yeFd*p5wHdLB)dvx7oSb&h>{Wm(KZf)Jv# z&-qze>6h}jrX8oO`q;wJHJ5$>m}6FQ3*B7{{RjWMxr-Cn4&IeBsjfr5%XY{bK~YUl zcp}bRTSv#z?ryh!q@xn;DLkY)m^!m|rScigjzNO={+D9_Rl+{I6-T%cm>~NsCkjx) zL{QJf$`te5C>my-s^?*)Nin5;pFk6v4jIh2Tw!zKnQ5&N3bq|hP;x%f!TDAIr(uND zuHYL{QIrwbt3+u5)Y4xiM~f~bBh6&se#4q`S8FJ24Fv+l-I81DMj$T>jIVTpA#h14 z!8R>&{a+ewfu;|GtWaNqs0)hc7?5U%QN+P#Z}jR2oS6ZG9cEo`bBm?;kdzHyD>(es z7%KqY&sC_Ra4gv%8=H@i{8Pgp`I_{ae>)CbISacSlHXWF<$lQ@c5>zL!wHMB(`Z(z z+iEfk4J#=0e_>}g#caT8Uyqx&75||5yfA==(wlT|(6&_{$bxuj-s7Q>qrGLHg!6=> zYQU?Qh*~xl_vG|s8r2lQav|^~uILV0*k%!@Jbli_ehl52Et zno(4Xn6-U@6QUsd6gYvbm+G}{*#G26rFf>D`I6ii^@3;-0f1{51aQG{3SBCZNy4ie zaJ+83QkeUHMF}5DPeVeFD;}{ltY4z8EH5a}kA3*(#;a|8#h2X7NHIID4p!=~JfB~B zM-D0LzF9}yuo6?nH^2RaIfV(c&m%K#TFx0UI#5l?dO4{Gjmc2Z$J<+l`HBWI?X&)C z*o>#ygf6EbqD=5Ky83kW+h4@!w-8i6+c-n`vTTu3VjXWs@|>FD>fBIu_Bs0kaL3PH zAYw$F*p)B-I#S^0dJpQSkoO~)3GaL8|K|Gd-2GxayLHwg&FDLG|CG1VPgPV14qzHC zM(hV5%{I!ue%W-k0VLkAoGho)uuNW!pR`o_B?w)yjx>T)%!>(Zdfe>i?~kYqQ;V!? z?jb}R?>XRbDRAigul3No>+$s&D5vx2aOFTYacMU0lDqmzqXJ0B>h;!@*7srMy9H+#=Q>V@uI1<)4jO30Ucj&yDd{u1ZHob zQjnE8rtnE_pSarcDEnKVoLmBuUlvbyty)}}#vBAvctiVA`V6qC23+}u~xMBujkM|qxzai9k@wOx|D?u0%0V`E*~&=4KcA1Q=N+T9TVh>{Ld z*H95?Njpn6`5S#6htFYOu_9K>Sxx$pxL4=Qyvc=NLV z$;U%?LCV#olqsoxdbV{GqsU>xtLcotC;tU|g|C0hB`HH~WNXK%JS^UH?n+wvW=3A? z0;XOX&wpAs$g>zcBGRk)P!x4GrM;i3oWQ=%pr29Fuxv%v)cs*dMuzI6AlG?!LoGLV zyo1}o#n@ZP-w)0z?h+hHUs6lk{j3nvEMwx1_)^<*$o4O$3x?}!3I37Yk6k!5AMR`c z`{kt7@h}c_1F0;&oO0Tm4d?XFak-<$>2Uk{Io(K8(^i=`zp8E@O11Y z#~;j8C{zDg8Y!7rUGD6T3p;S*c-nielCYy+;~q0UYv)J!GY1p#bzvqiV*uL^N57J$@#(2l8@QCA0w?2pf8EdM(rJ@ zn5xXQX>xv!6osc?E8bJm?_8S5C?9h!^-i}VlM|F=TY~$A<5&bgms_;fk_BPHseam9 zL8Q|N5cMIW(BwlP;w1^&PyZ-KSybMfla|m3Y2jh@FJlUAypwfuat47AcZ7z+n20Bx zTHsP*%@44a5$)nSO5t11UQ>;HO{B5XRFEd5Lm9-XU6x&xLsJ1JrE6$c=7bid{9SdH} zmG+{}?C2o)CHx5jMf!~#%M`ktAy$tP$~zD9X#~X8(-VBi!X#sEJ$7*X4GwMuT#r91 zl3=W2Ks$|5k6ja3?bSJWsg$L0N83bcTl(T)9htn=JAQSdW}N7q{k@1-dld?g%j1h| zm15^2w&}am@6_T5i%>=_E6^5@+@CAF9g*(C?TTr{Z;FYNl<3r!t)fz7dm$qxIW8aWVFn=QHd@t*Pb;e zT*a--N<)ow&s~Sj?PI!^%Ep>D(Q`v9zA!hvwjyjnF3t~uT#67c^wUe6lc$wu&(!rX z`FwM6xNl#f)M4POZZ>Zk@KM?P3$lO2TLI~YHD9xy;0$b>;Q|(3jO__&f`+(MVDoUP zExiT&GR3^C>_kbU6K41cn0teW!GVpOnwtDG;p~m{#yP0yMc1NeyRXTv#6VHX*B5^* zXX7U~fl2SK%{Q|mX6u2U1Qr4$hPxBgc}^#`_6%81IU19WB{*z<*j*ay`nMAfsHZGj4?gnPiar)jK4j>n+XP4Ji zfn&@K?Hf{_lMC;&7?x^0kF1I_{`vOBbQW?rf`Rn+-f?=T+ncu1PQFtABW>vD@^o&# z&`PCJ9p+tjTYUEg!>9%*iOCeYsstkyi)}paxR8FCkFCnxl0DB;XM1HfSVbO2NpoSI zLTh|WYr9f9^x-AOjt^DVdMD827zJPd<~rO~Q7r?#2D}y&4BE&@eoJK(%inwUW>=!J z@MZ2SB4y>^ka}m(*aW3ZR2V8fu~>g8GoRvkTHNDRmdlGn=;#QdN9|;pD+)ta7yC`P z{EqbI&kVku%i|BHC)N=f`oYVKE^}bNSnZ#T=mQvB*0SK_Gh=CZ@3@fKx-7r?s0!T7 zjER6KBZBJR1;w4w9({dogwKS@Dm?*jvXEV~HN<;2;nd{>a@5Uf!t)$+TuorNNilA0 z*s50_V43QUGaEwWCqs?3!o;CW1)mzQin z*4=`+hAHJP2HbVG-@f{mGI}#mb=~>UhLtAiC`#`~^s}=!&n!5SPaE-EKfM)|m?flS zN(kG3i=XASz<@ABqbK@TG^Px~bAGvRmw%QDM{rmF`i%EccnC@t3_!yfA2MKt*nLP6 zqK;-ah(F+4m9thy6QP0z(N-F|*pbOqore^z?^iQX#44&IKRqvY;`m!9RA%uz)w3z+U34MH|Hc*>QW(xwk)r3w4J^i^ z;)uxQqu1^F@jS26GO8hNv*=Cl{!ZeAAQLB#V#Tv&iiu)!@TM9je@;$O8ZravAFr^? ztxL0)jA){4ja;l&$gR65Y9o=R+1I!I004X^XDdyB@XT+fac5YgNypTPBT42fXJ8U~!i(`Ngpq?Ud|ew?#~G z=f#h}82S>QyH6!{r@PmUCKfpKNN9`lvAzl$brn@z+3TJew)*#t#?tDXT%o#T;6M4H zWS~R;9H{8k8yn!%k#Vl$;no`uO5g5(STaqCF`XONsUL47erzT7rj3v(Q+luPAXf4>Uw6eD^DJcoN zxw$E-+5ADQ%TIK;)f?QhZV$fq-Ps8&Y2vqVWI|E_f$YY{M$>Sz&b<8mz?T;<7^LsX zXNpBQ1I8>5mzxSdP=8>;ml4el50Yl{KQ{Z5%wSQfasx(>H-B(ATh{lZAKjykk^a}5 zfJLzHy3YF^Vd~h1F-DVJUf2wt+3&F5lL#{+{%ct#$%v?E;C9@9b34;|Y@$L#Kk@@x zrq*v)5Xk5q95&Qs8czBD?{$bu0VVohduf3PP50Re19$r~*qn&}b4ESK-;r*6#9Q-F z?EkLd_}`_0qrG2s{qLc5GplBlubucB)p%;-U8g4YXNlL+y`rATrZ*Blvgbnv&w z#Mf#ea34y1YAlkr?p$+IIu`lV&*PA!gFge!j&mgIHR%`hBu@8lK)Y@Zy?gN1))`vu z_9#_VdT%$)V^2F4Oe9o%Rf`W~RMEq`5~oIyA+*N6di+FGiIN0WlgG>RkJ)8T8i2zm zCykdbP5LmF;ZeP@dH^B7=S$u0#h56mFgXDU0WuX!!N#rww*&91eUjH^EI*ua9ksXH zrRh6*2aYUHtn^KANcslIPjRaNC_lv?a7*@obx*TA*|`G2FH zn?O)qu*^7Dm5`876F5(G^7UPdH1P)kGV!tPOuJAF0jDehS3uhfw%eth>E?&{$J^pz zy0;bw-f@@ydMW`1a(LvR@!aBKMb;^742z4aD_W$eBsqFp$$O8^zP*eLf}Wlp2wB2Q zSVIG6+EUdu!;dska%vunl1PCXZwh6=#0Wj|qN&`0TUKs@Wfr!?oyCIo z5fY?d8W$JpU-xmYR=vJ-WXF}jphucSLy51Plx@DF1B*9gKsW0B@~N{@-o*c~A7LX! zgZ}+vl#SL9cmY(lK`G{Z1&gZc_T{Omn9ywt4m>l)nmfR_Ep{hVmmtOk9 z`aKahfqcEQGc`la7EfssGirR8)lwar_aiJ%%7H8r{Ffit@zb`eOAoCE+g6V-5h=*9 z@!<<1u*;5?d>0<%%SPF=vZQgpx9W(g5*K(+n!A$+BA~fff@NbNK;{v{7%sfFcVvRC zZ4$kBD=EoRZ6U`*ffjUDSuPeYT8ZX{qJc?=O~~ZmgSj~8jhnd?Q#K=3dcAU4!ocG< zJcs99oHX%^%)Z&DktBJ{$K_f@v5K1rlR>Tn|hG7Fl*G_j7#jV-Rg%v+9EoF}XlI?4Lls^0U zrvsCxnZh_DLv2s@;KqE*;Xa-w=mm-bYNOO@^MgzMeP{F7`p@SUK3j=5#1b1jZ(dz1 zT=!)7=AjT9-;vk^G7fTTCifPC8DJMba`Dg0yS#04AP~Bmp9?t`qh_(y=h&*-qG#bYS~C9YsFu`rX}?6^%&b4(7#>D+WJ2-tegiX794@>cT3LCnu#T8{ zXli->|55i9UQvDD+aL-eB`qz|-JQ~%(k0#9Ez&LBj0n;p-3;9!-5?Ah9YZq=@8Czj zzrW#KYZh~7ICIWDJDz9nb5DfYFMA0(2({h?!K81g^`>z-a-^i>{4UsuQj8Ldit9__ z6Irxr@VM~jz{n+~n&1ue68jM6#o65>g#)p`dmXsJjLLXv?`P8CeJ7C0- z2>h_mN=!`r!=MuH?3Np14-f5XYHKHMpom5*gN^}UB5wO73IDRBF-1_ud7g4&N{V~` zwSPx(MTPnG@oEgIknXm=$m{67g${oK!>TlR1jOH&R|qhaIb5g?&dw%I@qg&;3P$4d zI(=)}A0z8QJB6}VO7y*`Ch%%%xwtq4BmPtK?QhJqyXf_JQBRz7;kviC=eI>c zmRDYmI#Q$E>cJF^$Mh{fpJFjD@~Oa}&Ns79PZu&GmO6M;R8*q?5kOm;AY3YwUjJra zbfm;P**K*?EI5w%mj%ZW(8Gf_dcrwu=NLbCy*=~F4n@JQG3k2++nB4S2m6VB6F3xx z;Qm~IL*@_6hm+|Pa`t@f2;~^2wNDJ?cC{BlJeBtTAGLQm)^e=){}-w`f7yzvfBHDl09HSDK$cgXibx*KTqmx1Fz4^w9oums2DE+K%@Y zBrR0RfpuN|)Ju?)oBRByI7YSo^8W&mcA241lrp_7R`%ujl^u}{m2Z%zL1_K2qur*a zw59FEQI0lvh1UP8RSzcTT8lB0o70VjhB4^F{p~aWDxs*TSR?+QybZsZb?TVJbWvjU z=40yGHk?8d!@W+=EWQ1;7$&_o7km{yYZnBEJ!E+q5B017y>PRx8n8s@O#eu9N`P_X zornm4p|a`o=B5dp$MMQg`}LZIW5$ zoCMQ$sNy@R@&{HTEhf`R(`fAu8-!Nd<=+uj|Cv^{PO7=8q2YM_yrI0VE@A(hxhkUx z1Pnn@PC`WwuRk3;ho>WO(tPvn2#t8HA=Pq@^lgHUf`cZa^)dE3?ukvF!$@@bs;)FA zRaV>R+kmu`>@QD|*;bpW4j#-KHZpB1yS80m6z#PUim%<`R)Y2HPqqHp9Eu?qu?>VC5`{*Cf@OXO*KKi#y;zP zFrxGAc3M(amOLXKsChRRlpswi`!`-aC;e;u?~1nF_z8F%i17{FFav-98Om;oc){*z zWs#hJE+zEWr6kr;r}xaR4i^>DS>cPOWnsxd5EAJ}P=D+j(?pWoC(MaxLy<$I3^oT{ z-JRaIHRW8<&At5b!w$)ziVV2!ntA=FOtuhde7J2@d+HM`WM*dGEU!cRbA^19U;h{A zBP65BJX_9q-&ahh&uWf?>m88o5nmWE(hZs@G`YYjR4o5SIS_77NAkzihj3qo-Yg6V zOR1`2_P=>DbklgDei)ej%OKidT$g3P+_?XV_`0A4wuyaZYaA@If@NeA z!uO0U9XGI;k@6o9ThsmrZ|_bb&2?f3IKpnhyC9ENSdO(bDNSZRU8wjEF_pys!&Xf1 z2|-c}e0?W)4vW#w8pbE#teyl&i;Ii@g9UY%T^Q6bp5FO+wUIK8?9YlYqKwq|`nNhh zz~G5k$+AW{FZ%_0I6`<&!XfLpZ>sr*OY;wV-0C3<9XyA|*4FZrf*O0GqFl+{=RyqQ zBuYiK6Cw;#Q&UYBQ}P6SE|d-SFf$y?@m!O&wY9Ag7dWt6?%#Hy5g$fzniae_lHa0f@I!Tf2@E=HFJPCP(xivmRY{z%<&pq0^L1(O<$NDhfk75f8 zM#4B>FpaPFJX!mjb-Jvn{|5&WKC$a3yDbNmPl-7t7IK6Aa{uQSC|36Nihq4>_g~Uk zpaok^d^Q;$ki4>@AH(*(9IdBc`H%=<@0B-=8xO24Pg;Z8RoM;b;*AHTQVDy zj*d>>ZBkMpn-?=}L=tAY7=ov82lG_}Fx8zt=|^ImK@Rbcrw$S%<>rpJd4u1uo4tfX zLMQ&X(H(lYRL{^H^ygNyE&q7~2R#o@nzG*}wwZ-Rq73CijX8>Z8uRy#4&lGvkj?YI zqLn{>d=WTqLVyJioP^s?(3xSGn^#-Q@vkWU|B8;+Fb)q7H(k!@!QfINUlotVa1>?+ za*TNLe|hF1_ph{E=3xuBy(Q?{fyu16SrmgZyD%wxw{ujSUBzEt)u{&={z^oKW6s9F*kq1r&t;*gvN&jlZ|63!aH8DDp zmcH`~7^3tv*b@>F>C~7Z!!)WT_9ql7!2f5=vYrPOjqH9mPIk){Cu{AD`b}Sie6MK9 z|BD&q|B1c8wON0~3l#g|!-tPLc(95rhZ3ncxwxqQ3&#=y-v5OwKANrVZRc4HEmdvp z2(~bML$9Fk@@ZJ{1Anns22k|R?66_?sG*_pBu*GZ!ln-`)|d-k&Zz$r<;4H=LjYq3 z*(7Q<|2sEGfCwzxXVm`jX|_!3FUuteEBS5ysklTqsi$7Zb z6N(m0{7*rAFtdN^6AnH;g44~ZG4wnQ2z%e4l>Re#G{y5zM!N+tUlYD8QBKInh-3?c zg?DFz6!AZ2W|IHe2k}2mW^1Ua{edo6h*_;2qh;tFip!w+b8<4_Us0U@73FqV;oX@4 zD9g#cIyyRfia=n&D{SoNf0D}kCn<2DVpc!QKw%a?Gdp|s1UIGwac1FEPmVlg`47c* z1%c}m-_s0-w}z6c?Xw>4uU${tuhoo<0RI|){=ddyi9kk12CUBTC(3=|$caFxYfDQ@ zB5}@>qYpMK|CQ+;HVku`n$lr@ln4OCPwy4f)!{r*$$#PXxc9gj(jRMicWxL%$Q2b9 zhUh0umPDhh9qgNU$iZY4zAFobpe{|7d6TF9H5vSGPtdIp6=Uz`J)3*?;Bp-*^A_QC6)H za-WQgtIF<$184>#>vBaN+}GSj8aXd+$wfs)HJ#sA!3M%=-*z{ooot86;^N?HoGuzw z7BrVt1$d)7KN>W$HJH4Wl$0EJ&~RQQ@vN;T_a4BFp96!522?qnZ~%AXfW`TYa_yxX zKvw@1uZScLZpwMadV6j`x`adl%ha>(|L#c^>%_+5vBSUj!FWGQK$cSAt1$i2tlU@^ z!r}7#@TWqjnjStB)M_UI_i*$dj$|{9VX_yq`f$$tnFoA70?EQ#P+^bx!(Y5EY_1P( zV*8YmJ-B4F6A1)%Z4ADia*2|?rlvt>b*tl4(bHRgc*JrxseXeDD(GNJ{O>;gxvaz% zaZ-e2@oHnzU2$6X=VzbkDnW+zX9YW|!gi==&FF}@-$92MAgGXrUtkv?L(eMsh?0vV z?eoPJiFQx4@{bm3DIarTaRwwz8BOL-9~>Z;ScUWMG%X%Nk8efp&Xm2a=WoBX&m>3oVI1F3`YBV`@`?q8x5JrH4RuU&ez{ z6rTaVya1ku0ul9l4LwcCq!|t>dH&aXU^|i#^)Dg(@dQ}H&h?OY@+TpGO36*E92Yyo z?9qnMx7t#EFAOGHdVchMhFVTI@>QP;04uRxRFv_@WnfO(`$o5+!dP8VtA>KlvA)u% z>paK)Ms1ov*qAY6KY|5jOrHvovHm2;wl+7@yCP%lj$w2pLTOcgU~uyCz1MN%3&D;p zDsIx^t_@VR4}5Vt;Hr&8I&m2Rc15r0E6dwyA&hFDX^(wf>;f|!HoxKTD^5N7h?aM2 z9#ygTb2VNYCWg9TYTv7QthmMJE-rK=?5R4gJ8brL$hnOfD9aMd3-wT{T>Xy3`L%`a z4)O54n8h0o7g~CP?gE0^bRmD#Mfhv$v|G+epE*XO{v>5!XQ91svF$PCu@g4xwu+i? zGK%Gx<=o8s3w;2GhZ7y3V{hP4>83c-2jTI2m57$NPYH|U-h02p2)qpJP_X^Txqf@Z zlb#BgY(H^gVj#T}0=Dm-a9S#Ch68V2f!LR{ovt0dE;8I_DCKS!c10%KIl_MlHAwOk zUY~BN%WFd+HVudT5~g}MT5=IV!KE4O{&;EQZ^Q$ZmLCeD)Eh6UNd0fva=o_|Z3qQU z3%1qNxH5HIcR5V;`b~UK9k?X%P#{b4b5aU#(NaNm%Eaj1pFAezLIFregFtf5C0PuBa%^ zk>iY1(nTysALg=AUX~%0zbklQP=3>wcH5PoWmV>#B(54uVVJ*=Y4vZ;m)@uMzr1pprnmba%_tp=!08BO0&9C0>g?Hr z#+stS)GMXvWKnwWzF-0_Z|Yi>Tm@@~C?BV&2$>W1KS=A6ddMS^o@&}@PhYfVLF((B z(hPP@%h)Xc0CMJwF*jx$;dZE6H%l|H>hL^~n|>3Seu)v#6T>jX4G$RLB}uJj9N{H) z0HG9Qom(4mS9ww@)dIO|HyZ(5`Eo7_th0_Q%th4|6adebn0YeR#nA1Y9#6=U9Y3+~ zHr|qLW9H-SxO<_`$3j`fGlIrxV>=XtH_IEGuqL02dt02(u5(o#+VgF5XEri%cb%w&D--Xx~^U>Go@d{)nVtXb1yUqmR_5?p-%mreWK|EbQ;W#e$S+e@7PIwZg zv+uc30_>OxG)$({+N9$MOqZ2FXW!Ff+Awz>9|pw0JHbY*4y@>b4b3~Y7#W4r2E)@) z87=k`=_f0^V>sIdSvY`!CgO%_MpW&7kEWP;eAc`+@|~rsbyE)>*kLX5Xhfv!WB^@b z_G$Il`BneX)pf44v%6^p3y1H`d#xB*2pdVk3Y7d~=j#D;F$`ne)^x%k7Y`%Tk($_% zBd(IYW((L8-BEuAPr$jK`{uS0YIyN;WY z?}a54K2y8vUN`Hb#X%*AtVze(-oqe)oAbadhJjRfvUR=rnax42%Z$1hJC4n%iOd(a zHcG-HlW02)8+(XTqu&9L1f7P9z|ru+@%ikzAN-Lzn24#5fx=-e~fY#Ac3i3*?OhpgSwz!-0fb^ zfkL=7r+lDyD}iRVDa6q8`a0wIL|x9NA>%v&kY0gCQiM)dz3S(y+1%xlKFqhyz5H$f zupF`2_WRz#h7t%A{x=uEJa>qAzev6r?@f2v-lef5 zV8?6>BTU=y>j^HmgPuJeZtE;vjOtw5KHyd=B86o-rQbVLK#sHzg#=ESwoubqUtthz zyc;?-_}^H1ZGZQHD_oe&0XH55wq&9DqmcQu@X#(x={qa*)0upXYNtMG8_)7BU?4a! zxshc@B=FS8uD-PCOrFd{Au=36&(N%^M_vcm8gw)Pr7^l0uNQm($u)zGTyasE{3 znbFODJn2_qn^XQ@eXW@gvTaG&58PM-$SWm~DH;92N zt-986s|Q@Dnh7duwm?ya9>ohn53>XxPbY4~4AR#hc9utr$Av4A9J5y^gu5|1uGLe4 z9xp+ss{WH>D>svTA40Qdj(kD~9`E1+@2}D#^#xAdRDldRmjX9Ez<>lY$oc`L9Z%ov zbkpX(P7Di6KY^|JK)!Z}Z%!+rp#3#)opy_Js z(ht}(S0Gi5nQaNjPi6U4g6{!dI)B_IGQeyDHYG9iaz6w;jnmedoIFh5^!%@Nr=nulgsGmCCL5y zdxf*mH3a&4qGDBiG^OuX*P_|B`7hz~9WO9{fY<#I5S`;D+Jgl)Upqz=)}I=Up}>^~Cg?7PE$thgtat%p=Zj6Lr_VEo_%cl6~8;$q0W0KM! z=3MVha?-$kjWxdwM?WyY0B6+|zg7y*Dg>5rT*R4KQv69o$I0AxXllV|3;iHPj=rA4 zjFXkxDNf>fI$*wW+3g+^cFcUYcJ3G0B-D(Jw7{{pH7~!DjflmI1?92iCKG?^!lC((sm9(Dqk zz5p(s*l{ky_<5YThbHfvZ6WHVe6aJu+U^*S2!B@rKT~k)3}kB?5>oI!WoCG9Qy^GyCXDm7w2Baj?Ti%jM24pnYMh&>QW<*G#ng(C=7e zG-Tz|nU~sFh%M06aBb2~X+>h@(04n)wP!{RRKps#!Z130DYQ1(GP&Xn4yFFp5PLMl z(Fj>ySG3>iz2+>x4{r8zDy{yZc=bho)G>F-f9pP(HMT6!ycE(7veN2RoU_=+VZb@rqa#n}>+BWki86 z+g^~gaftL0V`n?qd0PEGmujaa4;~?Ph{UJl_GCL;smUQyduGLV`3*vP%zoLZQR>Nl zb!a0I!D}A(th6i^14HBNk8ODgI|qR}u4<^%x{j&P&FMne84W+|)O|LNEM}btvR{fg z3JWt%d@|3j)K^y%8iq`>!Ju}krI2ZX4M$7dA%sn_scnGQ2>~bFuJja^g z;StiOZh>6(G)GJh+^g4A>TfRI6csH%?6%L=>wUoURr(H7?dYbhHDkMhtzFsQWH@58 zPI$E9hdJr!_;#lBpsVFVH=1AX$1qsN*?zI!itlDV2H2d)nyUz|*yREr^(=J+=0Xa%8qkaN}4L6)5mT! zP64U2l#_r2%)J4vRRh#q?$AgLNiVyILxX`-@txmgg{DLpkLCo+`^#M#gB9zoNeBIw z0M6a|9NjU?jz=_$)aSp;bq1!2a?P*vOi@z#R}A|N-BB9-_qm~GS6S&FG$LxH9S=J{ zO^&vBAxdT#MjRRsO)(9$6K?;6_SDt8!7EW4dE+7|Rr3a=utzKhT%7n_Mthzv>Qxn$ zcFJxF0j51&%z%@M<*Nb_tpSe=JMp6@Yyi(}rg%uMNQHgxhOFg2E&#+qmLnH--@tY5=U7$8o4+tUX z$1U{#nt$#imku79ILnyuOJE7Oqc4q`_PMz8RAY6)N>d;bFPx_i@WNHDh|P8y^)(8J zl4Nlx5K4S&*^PfQp2qTS#C=nfJuEP>wc~+Y4&{}Mvs<HZtxv)4HS*v6NY=7d@HOZK%g{1^11;Y8_Q=&8eaDKLFIWk z8aVT%S*&;v`VGd5MBGV&!3gR7_&2kTfc%luaRsEZG{&txcL8LYHieek_1mkWet?_M z+nhb4TRNj`tsn}ukuny+vCK=PNHTo!M&_%Ns(ibpOTUL{Ej8lbiwMF|0)a2*S5IZ1 zMx)PDs#eEC+L8i2?xQWh6Fkb@{Xex`KaCOb09!%cJmJK)rXx!86OUKwjyLQ^ z*#eL)9)59sml6Eig%A@~WE&n9i%Ip?xYp}zw{;#wQ|aRDb8F%2p~bCir*p=dXzJ6v zX45m>pB^8Hma_;WucoSrLHvX$mCt)Dpdt=!CcJb5xHjnPuZ7(n+@?rgTU&QAH+^A& z^rYYvku;Ki&gqX}!zSRWdrk8raGD?eg3)fXzU`u$TDSF^mn+NW=ZyhPtge|Fb7iIk zt7qYjQ95Z_xi0M~ANywg9;Mf}t^}Y#@%qAHjMoV{=?3MiE6-EIKPTGs$I$ayE5a}5 z^e<%afLYe>2#s#{?e*C?vD0)NV8fPaR+(@AcoOB)f&&4MS5#f3iWd!8Go$a$r}XV? z6jcN_unN&pb1%FFn8Ldc-#Ua#YSrZ~Ng+tCR@FNM=IqX$d=<*<6uF_VZ1wsj8~Lfx z3`faqTvA*c#^71=?OnN!@>o^3V4)J+ct7&cY`GKYJfju2-EJSg+@L64He%WPVUdjP_kk`t>Q1%=| zwct<%07tmkW6939YMC(>a+eC!TP4Avli}|loHym0$UqJ={@937gKMmO|m^9?zsJ-+#++FPpDE zQ9(h(pRRg**>|iy0aWMP^$5TLgq{_tYwCm|Ma)-O?8&#b#?#a$TH|AE_L#&Nu=jSM1eHW6gRLiu_Y$i|I7~UC^JfsB-2yOY9-rys zK|HhZ4ISRSkl{Cb{IdBDB}G&GCaLqtWeZHfF=;!7EcvR|^hfO5#MbnWiAo!JzEQ)JN2ZQo9u7k zVyUgA3L_yNY2(Y6Rpz_YsYgiBcfEZX0NK*y*Uj`g`p#9Sul3$1-gQfP0@TgtN~a`r zyR~S@qC@pPBpdI(=ZKS2GJ@t;UFbLxj?4t;bF}4`<$T<=8b&em;34N_P7j~rT)~ts zNj_emki(I|w=BtV17TM!51b~yns9XMJSbSo*TuCcyS||8sCh&1`_HjaZ>sHO+>SPH zEj2l|Th7d`v~O2nfuE6wfJjrh^r_~T@~=o&?rN=$*tY8nu;0=D_VyOcFduE*17uta zPrycr2lxIy*GYU%*Y!3O0Yz!@)Oy3E@E4djh!$a3UiK`v)O!{-{L)>+^j7Mo$)PXY z<7ivdl*9Qgm4M9A9akNo5S|m$pn7Z13-zE@byOlqoG6 z9+bPx-ERJ&4jaVcEV2P9*EyJ8&hf($r^d@Hb8A+uxn>@PlsIyEwWC|{jozV!Zw$LA z2r9UaF{9T@btMda9TpSJovx3vV6#x5i}RiH`ytNGmWh6}Ijd3TWjf-44qKozN6J^J zKT~ULIASlyQ3Kc&ut_()DIYuiArq)0y8%`}HC) z^YR`Wl?-ylG@fuLez@ZKrJ=Y>2_vD{U|@fG6}8{#M~`CIz_-GO*8uYpS22FEG0yDa zu&P)Tl)S=@xceO>e5APZ@n?G8^NMim2oJSZPo#Q-Ft_!{_D6rH*f0ZF*}F=&0l_m0 zqp|0+SGM-TPg^9{^R?4LJlKLj{%za1WKMm&Uoxhms-z`B>d8MGL<|8K;pXotr3$3W zxro+3f}lMTvX)EPD9G8THt5sLIlZ3-w9YJ64WSpofm^4xX>9hxy!|nRL%%kO+bSFH zl~SE92bi}U*L6mNm?qAr9sNVmYAswg3aVkVk+RR*Fu2uV59_va{+guAoDOV~rrNWj zeI&b}?al_KPT9BVQ9aJ3)UbmV53B;`ZYERLX%*2F-P}BsUrb;03;A88N-Hn_a!|-_ z=tl@a>(x6bv2{2(p0!1YWNkGx7-R`JH)0HQC*rz9tE=Z4B!2L2X->%R=TD$qq`0Ddq%bkpG+0Q$?!I-dc%g-e_ z(^Y1y5#jSiLEU*YFYVBHw+a5&bIMMm_`;}P+{G`^F(lB^o*&x|STmSBmXf8PZWDXt z@G2`A!l!Ox*9>GOOsZ`_ez70+0fARZs#7k$g(JDD(O;QVAoo9n@UVmzA@GwpH z7Y;Rn=XHrRf-oDCAj`eEGs5 zy8gHGV%ldbkTZ?i<>BdMYx@8J8R+Na+@PB}D4 zwlqKN0~t$-=6p8y93&&u=HhA|=Rn3&`OZXVDk^kxi($PfIA5H8(-QDW{#wo>5wtU) zPKjx1lK7l2-nKSWf*Kds&pV6^!h|oVtAso`+^baXwll3Rygslg>L#bE*s+Yb@E%$u zDv?&4nMaRFnm=w}@yZ=7=zo$6H_Wf3wnCMmd(fmxiwZTE4F67FQVF`8BXpGZsAM%C;D%o5M^WKPf+)-%G$$0!23|f%zr6Q}qoGPnO^&E>?^1W<^C%Q%U}YK=LgK})i`bNC?R=yz6@ zEXTEWK>om**)V>7#N~Zpl%QtPC)GNBx6+!4p3In!<6(g2wXvP5StBx>3N>Md^&s&G z8-_ydin%3&N38CY{?TgCV(y1eOGTK<9Rj(Yq(m}b&dv!|EJn|OrZdIGAAph-Qu!UM zWy@05OrF)V^qDo6bkE8)IpP=qYC#=s&r_FL;W66z5|pLTDn3*}b&F?hW-@DbjqUDO z?=ckfC%HOwUuhs^km&fPb9gc@$A32+$a?R{Xu0NVuxh7``XUsw9$j<3+ni}Sc!xpHS7`fL)uzGZ8@~uUzAy7Y;=wWy3SYA$ zgFGIS`R%!RZ;lLw$g-m<`ewBT?hHv4`WR6AVgWBrR@m@{9HfiZ@T2g5!cy6q> z(Uk!Fqu)xZrkMIM`W&bOW+z6|@wGJhci6vWcD6Y2{z%p>F=uQwnQjwD2GgM^2}HRL zj#L>l708!x{ce9aQ-S{$0r@-?UB*f8n&84s#DiUJ+ndmwV7@#BPr~Gjx;>tC*DU)S zt`h6~6_~DGgITKJjo=yhOsqtLDry$u7`22OY!;Jd^p97T%b%}_F=e$SzAOg{HkFqU!%j9kgxFX#wI1^7A1{B!D4zHlK5%}ZJn_0j zi*`s6B-3rk&MYB2TUw)m-W@t^7*#*>z!ZftRzO{31e-5(L?&6=(gBy8oV{~e%~&dr z^fFCUe~v}6qK|_YClCXd_nbE;J!nkvH7T4HH&T3d`~KCEdR&t3;j?;tO!ot9()|t@ zWou2W0j1o$uXQet9|}d^iHV=hl!+G9vOx7y{P7w%Ju3CaN;M7^{BIcXkh~?;Qa7~NIY47-Rp>EVgAO?e>VNz#W{;wL?66ac`JE3<>w%xg*hfa7fH` zf521l%iU;PA0NaQw)8YXXBO3}VrkdA2`-B;y$3D0@|FyD)-ydmkG7on6%GhA9hn>@ zv~MXtFO@#nQAEC)40^z+1sX|uq+oiz*X^e7xV`hmE03h%Yb;nIxI8YNO?HH$!DeJf zaWC=Jo=F#03i=M^FyK1ffjH7oikxPfmk04utS57lBYGK@<*tEP2i~jl$9&ZeqiVRRPc_=AGxS&s= ziPe=hRqNdQp}I-CoJMikX%mpnAIVY#84ao{oqJw#ivF^|u>GUkE8g-x?NXUSIhcj0 z*$EEMQ)jnKS)i$QgaOLd$ z894Q+AFU0Z#@bTJWz!66PM+e3S)c?t>(*wB+wQjmrIYXa_g@?|fGhFfx-zFb}JTKuUWkN~wp0hxsfaaxu^)7mizoppskFIkW zB%|rV!4x{o7xSkpqS6P;$D3hql(WBw9_n%h1MrUC7H!oKwb&I9>kQzNwe`!h0DJG% zwZ3S$k^d+nr+gQNeq_Q*|E0wdejS1pzg?qk=sag^p?I5Mu&1Tfi!7?wh^q?Kb;{uL zhtL*bfs1)1`Y7!(CbXut)XUL2=j9Q2hh&DDF6evR_9PoqC*N?svOZfs8=Ao_Fr51+ zf9^pYz?oypXMr;zn%Q6@{^dQq`}4*Xo@AMJF>7P$G7DvM9S9#iqu6V1^z!=*0RAz> z#Jl44QZzQ>AS*b@`A>RM=v3XsU!3iTL>^e9g)ChdDn3->Qdj%TnXUPQs0{tiG%N=2 zXUf+)hQqJ??|ybT^XjG~t-7vlmo=YlwR&TsC{>w5i1NKIXI1^q$DS#f&v}R-;lg(X zJ%4`p6;8HwzJ}($<|4T^9YnNqcDy`2S+_5iuJoR_90xyxuDvcK;h7W$6Md&{va*Nj z``8g#I$dSL`U81DT!K}OcX`$&3GleMjji^_b`7|ZEWQ4Sn3n!s=4xkbdpaVzzN4~xOw)3Cr2qW5rL($({C#s6UKt~j2m}L4r5GDR(bru6FBiV zYM26MChP>0?KF?IdPA4dvKKkx=W~@zd%nJRvt15(jlpUOFxhQEE7xw#4K8v;wwX&{ zCeeHS+dFT^?S}kjY~qE~LW^%`!XI z>n7-a;dHu@aiaPQiAatkKBwi!TKwiYCM)E;u>`qR(QprddvSp1$3QY#>Zr<##?(*V!Qat#2 z6gU(k;p{p)?fT4>>-RJ~6w%HN{H!&?f7cd+UuFC%vhcc-9MW;d>%2R`dN92!BN9M_ z;M+((s;;=!EN*95n>p*echQ!I9lcZDL*1z{QuE8^yV%lH9(({#wFq;3=>S<=5M8j^C|LMjgCt9^Pru%^#n+6cv9KD@K#tyLs{+rTm* z62NeeUF5_Fer?oo`y5#>{AZ&y5@ATX6JAl$51!oZk+fRZN7?M$$vTJm45Qayk=fR+|m+Cn}0(@aG|zIz~`134|kL zX;r&ffHa{LirxcR|=zBKh&$CH7RS!SL52^HO^`z=5@@+ z^+=XQe;Xz;LGWAT9>*f1MvEI?8@3|K8dorVDx=<5WVT6N5Q&$~#dKZ8x0xAWZdu3- z7>U<~9Yg&Fj-L}*vZ_Sz?)_Mct0`b@#)q&(PHQLJy*waj0SLlUt zLxn-tKAQB8gJ7%mcKoBP6ni-Rs(AxcTQ-2~*$`tkgx(rSa}sn{$yr4fmL~g=iGJ%Q zFUL;1K9Q+433IJ_g};r4Ja;~ICmF^T1<@gYX+t(J!H&&AG#yTI#(L3cbj{quHO3%2 zDvJhjzzdl*BCDSfKSQ!|IJ{Y{Z-(X`*{EIa>kKY-!!nDAD9$bk{A((p!e^1VJE-b-M>syV!}z$3~6kU^}D?fP_=UZ&?NSLKj7@@G`0J=*!M{kGN33X zAtAk(*yoV=w4#^sM-0OE_VI%(ayaXPlfZJO;?T6fA6DKEM<(OrcE&8@ugie`hMXvD z$SNV4C**z*h~!6=FE3xc!hv?Ibr;OP6b<1dpe!sGB#*Mky|-mpp)owtQnnJMrB~Du zdG<_F^egc6iuKjw;6YzgA5mXhWPBuTu-vaj1Beg(Q9KGSM_>1la)gghis-zIU(LRL zeg0MrZWIZ49e>rN?L~2jrXyAdH0T{IulDm7h%Z?%+Ep0nHwc#G1O)=BdDAR$D_<#k zzz8(^#{5wHUH>{Q&TE?-*_#`rh)gpoBIV|vNr*!P<|_<`8B z4q+|)B}jM?zDp_X>V!GrrzkJ+^78UvVifiA@rjn27opu5ph9*%M?AavR47&@_Lco5 z@T<%uXh*AW4#(0PF!s*)((;?U*&=UAJ>tgR5d#F`7up!ET8t}68`bz5{1bmuv_+Da z#a7z7i|=eK`a$wb<)Ohekx*zA0C)<%#FNU=rHzsb>AS+m#yiBkrNUk3NSh{SS8~8S z5n2&{PQWFmY8^TRJL@zRSO)Dd?Eb2O@}fQB=pk9VhDC>$x%Dycg{kC$kKwb|IYtX= zdwhIy=Y8WwM%ebjvD*{FlzxzBk}6M{I>lb24ps?b^^uMYUw_od9%sT#Ll2$KeP_5w zNGnQ}iSDIaE>G(r@|L+(W|>1B^?;bJjy^=r^mPaRK(CQkM$Eg?5ek!`4jkiJ%V_6D zDHPG-dZ`Vf*NmBHx1!l24KK;{Hz6H--yHqp&nM8jM+UTRZf~MnJNT(WXmOFVI`AI$ z37@~|JtC{bZ0<{ISfH{?{ZPHXoF>ug~`8MEaq-XAD1UHx_FWF-4S!Vl5q)g)!}sw^Xy{ z#`%I3(?$gum87q2IxXIzuVKd8Ib0iXT*;)A&;&-ATq(e^+K;56VZzjD7&fA{>>_8o z>N4z>&VQ-E6UBs{=9I49$8xepD~KZjdY|8SJPkWddzLP0$}>_~$^&!h93U;F?6`ri z0%eBTqLCv;o(6-M=_#hrNuZIPKn@Mms}4OOsYy(5t}N*1Cly<_?w)0>=g$!%zkYp- z`Q{f(n_!GszFG)fQ>547^zG)T`N_A}V#G$b6~C8z^*%|ha0_?fP3Xe-`>ra<{PSO+ z*kj56s#Z2>#c9Q9lT2So!a!R*60go6moiW?LpZZvV_QN`lK=6-zW0HwV)Hc5J%)tq z^HprH%Hrr2K5mc}>(L$h?t``bVzoQDGMaU0nv%iBt2N__H$v_NwbZfSl*?MI>?G4s z-)#*dT($4|;qS@-7}ZoD{ub$E*WTErAW26KLO$#@xQB^m;Rk7Y{_h*zKtIHB&i zzo5Hww}}9RN569=z1>l(3)pb`?TG=hEVq2@pb`}RN-kyJH*VFg%VDvBx8rxq{;mi6we>x3?CgpwkH>2AB@Lc!-*@;Zxlmo#4IK@Ub-hWSN$-UN z#&yDhL+2_N(_JaA5@MV!T-A3MGq#IaH0#-;cT5NAr<*GKcl*pl6fY_)4IIdXGR&g` zwn_w$ezFdRtlA-_;4@VLvxY=i%y*EkrzrW8MRO2SY~pF9EJw$a6`EFyW|057DrPjZ|2yrCL(fU2=0X`?i%{mi=`%S)qt`Hp9NFSg?*^i54AFO;i2zg%Ng;oHS&72Ni&ZMmxsV1MFq#(L)vmn?6W8^s8M;KUQ-&~I1 zH&@G3v|VVvLP4pfqu%E{>8Eg1Fz@N`SMUXMe}kZ=Xuc?(*`C)bQ!Ry@+q|^*#SmdK z9Nn5f&JzcT+I{!NS$u9B+j72Q>AKK#h=N#;E?suE+l9P-I{YIps z(Mt~GELCuM7zOU}#%(GWeETF|BrU4t=t5d>MwgeuIC*o`NCp{7L;5Z^g z%y&&y`;r#kSNV%PqydxUOV4Em*~bsettr_tI4)6kRtivw zuovIvp|GtyJjya+k~yR7p2dG+6+>vdZEZbfWO~a)5&aDdzheXK%In%dqd9&e8GFjj~`HswrvZ)%U96r73Fov}-Irod+!)1DUkdC%e8$nwY zw2d#}^z~#N>Yw@_q(IT>6apW-rIhtW`HwO@-2{5_nU$|)()g=w2$h9IqUr~tn(ZMT z0shsn-Rz!zvKJVF+75}YE&yys7a?L15y{8%evb>pwMjOzAhs6 zyZ60to3J}V;63OOUv{xJ(bC~q!p@Gdv7-YgtH*si$;Nu5S0FMr_Pc+TUU~~ezhaz; zNyc>L!2tGM`(YpxK`n2y1wN*%LZB%nNhVK)SFA;jw+Fyy|39kU0w}JedmqL+1=mn_kOo-O-pmA!QUNihA$%t7!h3|JN5&_6@Rr zD;6`5gKFBd3*xvp$$`HgN7P%y>i1er5g$U;(}IA-^Llq<@9iC@^oj8)OonSAp$vh!^>@6|ITjYQ2EK*p>D^)D~<^0 zpRq3xi57~Jomd;Q70UITwx0}YySPCx_I)Rgar$KbFrdV0B!>%8_>h*Vzy#USQ2pLW zP42H@HEAlWb#P#3hI&0KdM*v#F``2K15t{Omwmis%y-DF-~6Fq4sfmy0rzhm7qU zF$7&P<#>{T%3#4RGIHH!U1nV*x(KAg*3LJCK+%uPOF^nC*oh2^nB8udi^vPOVjqX! zs>_~|{PZt{=hn)f(+dYY>NwhASQBsOc3VByLXOkW>^BXwNuGQAI-uzozE!*(?RR7$ zMTjL$6sRvW;rw*9CZknlf@!o=0x64B3gLZ3XZ};Dpgv5fEBOY?oYL%>`IS4Ynb}?Y zb77h9UI-iR`)Q`z`!Y$El{THTSgbRUvasU9WI*J^M(k7M)sxyV2!_r!0S+(C%}qf;%#;8=liqQ{h?u>H}v9t z5xMH(?0{7GFb)9>Nm}sL!ymBCY{?v)ly8>iA+e+iIx}NS=@WRfNBR&{!}eJ?8$Vh< znA>tJ7r1Whv|<&pGK;yw4S-prAtCK>!w0fQj$(npH!V6=+AQepLo?Mobi^ zJMI8NkqGit9aWJ<_#l;_DNu^H!ZQ2KYs!Pul45)v)3Xx~kq_YE=lE?qYlBZ9hopLD zA?&Ch5Z=0hu%Uxl2~ZP8mO~a+{8_F&qxkE`TvjJ&rPY;!6MPfoqJF&D3wk75>X1yK zw(zO};jsYwiZFz$Ke6;+GAALGQz>(sYh_-p{o?|hZCV@3Jj7Px~S zee}f9S3m1tVVL_1M+B~Ff2Hk04w?$e^;S6ax^{W4eum&PCrSzRKOJ&8I4Kw3)(YLs zw}?;77_2gAlc~aWW3}R(J${4TXCd&Gwjv)w)B(TdTM$eGDW{AeQ*W$qXjr-lIg9sm zeF#K+C@t8>co_!LtK^#p1&Ai3(LDN;s`_R+>6H|gf=}Zk5mQK9&iERcUVm7ek;;Sm zH$91>EZy{BB)Rt=^J3YI_Oum?cD5a{E-J(84bBE~)weOGGc}4%a#`PqkM{umgL!%- zct^4CTUpv>(o>&U!;|{mOc}=RLuY@MO*(1;ra-gx_JJ&D;8cMOIXx1W?9+dVLeWKwFTR`pc|H*arfmU5u10&REe8I_Vb31d(Ke7tXD_}61-%~ zP%lf)c*&D}p7@BRSR2Ygy|$pQc$n2v5HRN{H3>NJ(_pK)Y@geS~(ttsDqU5QDUAQO6 zJ{?=*JWj4&q1o*tGHN!r%}9+r_3EGaJ&L(&hiovTVz+LStwpSlizCkqo#r` z=v1!wa%#Y!=2DrTA@=Oo^zMvv4_CQrq1pG6VhTiaRarI3xu#- zEf8vAS*$Zyms?C_6K^W@2gVxR(MQ7IM=S{wes}hSIM1IZR=Bfp4iv{+AA2VPeuY!? z*3mS8VGCjDe?OTanG7gUzM67-ud`AdaZ*uy`J-Y@{&d3(09y*x6*X;_@`&v9J^5hy zej{RU9vqW3UeA^Y&SSRIk=))cZI3ukq?cJ64Ly(E0##^%L*THKiy=FxLrhIG%}34? zmTJr)bqsQPQ!RcdFYL!YmE6GHAZ<9SXr~Szkd zy}YK_3dDu>W6OAI;z#!!Qx{@j{2ib+Dg8Q05M6{PKCOh34}@kn5+ z!xpO*M7q_^#==qUhTpIn{+@4rs%*~WuAMkD>X*h!WAziF<~M*6qqsz^{+Wyjrlj>c z;<0jZkkR%uEwe2BpnEqOu>^Fam}ujVX?E#LZG#F6vyX~RK{c8%T+*njaq9DyT3d<7 zRG9-FQ0>bT&j=Ir1Zxou)zX1OLol%Cg88*^V&W;BzusSuXn-Ef_T;l49Wfn*Cqr}n z2h1t|-A4Q+!_zquG|;c)-vw3&63-nd>{fv*7vN8yey~2SUbC~TEI_ls$_J7sjn|l; z8cq9*$lRR`$~k-}(5u6TYR~)l!U@tCwdjAorP?RkDZi(gDt=mUMSZ5^Et$6zh1{%n zGG4$$9VnjK`r&gh*(MC|#!)a4f<(Wgh_TNe2_=&^eu)$OZsOx~zuGiYrz3C#_Q}<} z=JPm$IL4hYIjiMu9QR7uKP5ExeZo|D;ha79#WFE&busL>Ji`Z~mm3#c+c~gpmfn?2 zZ4lu{%@Zih{3-nXcA-w11wb%yR6Xig>PKJMm^E)QF>p>245JEi({x6 ziiGojH1(;G+Nl#XSmMBLy8d)G6+oUSFtl8Wly0s66;lOiqG{8H4I!}a&Sc&lOt$Dm zfo7tKN9ub*>fLA~CQ(hx5Smn9fMu)2A9TKFzkP8e>r1R23x`Ek*kLgSHOzc%1xUN0 zAyd+kF7@DS5`JW;66OtXbXX0cq#G6Njk+Xb^}3_^B1Fgz?f^AgiIQpe!{qfTx(~~4 z%`=&wIWY1zn_^Dvbx&LiZ?;}63+YBTo_MBkrGUS2@Rd1FxgVII94w_t-9D@Q*2-LL zN}xstn5|aM*n+(%uuRf9+|>L98}P&))W=V?h8I1AP5+Eb$mfv|2w$N-dYsC*HuFUE zh+Pc@+3Ip<E~;Zp)uhmWQ8?vWQUR6+sIx|4VS&tNtnu2Buz2RDS!NyRe46S zQm7+?^+1}>Ambu`kDpt=Fz>5mRM;5-ujy6$_EaOrxvLvb&FAykz5Nm!7PE$9a{Ik` z6{Am9xHhOX7d`L}$|7ZK6R1(Y-6$mgSK=S<L4+C&LkS{(Ij<4SfRHj1mY}JjyUAxjU=miL}1P;7|3Rv%Gw7;G+nq2++pJu5)x6 z&gGjFqg9-9c8?nniM547a+1+DUw}j=7dN!iGdY>)>$S@#5rpRf{G2i2Ed{hRzEB$_ zIpMXH83-TBmGY4W)HLP?B=v^@drCQd*>xcj_3tIS>;5?cKK;4C0&_qp^TJe(8BFr~ zF=RI}C=Owgfq>)Ae2dj(*o-W0qGAvG{oe#f9+8EgJrCymN^l^G{ipRLtFYosq=zB)?}0-;H|~rKQtuECePG6-;Y4KJ z9nj-k9P}d)yYrImIJThH^pQB*s~#^4YIuHP@d{Im-5=NHF1yd%a&*QacKbGN^*~HEK#*AC*KAiGfz(#7HM79%y<>HaCNo8Hh z}t)WceoS6BMoXN1YHl8y-ds|(nl+#K-@97nuoK+=X zC4F}&x&105iB5RLB#}+(|JhO$I6F@SycxMm^EL_H(FO5KID7GeDBDQdm*=I+)i+&t z9BJ5IYAJ_*tnIpPQKkN&JTLYeEewZ%fF~FNY5_M{shOF^o={9Q*XL6?Q#!e=pYvNU z2gA-h4`vrXS=nmWN4Y-bfY!?pij%H=G-`~cF}d|%c%tzCe9$9QlYxQAz05UQ(DAzH z=RV+Ma323{G?cE|(2+BiuJD{Jj$IBFW``^1**w5izb2_X0Pl4d6Y<`6AG*W@e2%eU zJ>n*-%iba&CTFx|C+tcEPyK|Dto61fi%5W{EENGlSe7!O{839UDt_uFZy_ zJWlzGD2QJYih0z_DpNSkX?IV6UF&WxwC%DFDqc?L&~5*?jl&vd?8s9CylKodZhrlp znraV(7~Y=k6N*-(5++^fhZ_Z$LTP_PU0y&FmBaw;jcv&MnL8y32*`zF!gn4)Cp3tE z@BOgNa;k#N57^KpSE20b{b2+RJIViu>IF>RXuB$|7@qJ$h-~WtLyv(9iuoeupbIPi zoOZcH`Dff<<1LX46TMAU`2~6>lU!F!M8Jg<3jT6VYYG(<1a?Dqs^SX){|>)z`C{NQ z{&b>`{&Q5${+Pw964@j$&tW%6O~3vK6lAHy#2gwORVOXWVX*6x@UN5imx_8#dUtC5 zQ%ewA$@(-tH2_+|4H@P%43xJU7>ChNWI3RVGu zq|!#Jq_ZX>+WEHk=HxS$14*|P?e>j+jD=c5;Ze?rS)G&fg!{NQajKZf;Yu3@0PY_4 zD|Us5&{M;Jba}rKhl}Sr;L4hSgJ~?<0H- zE;qsdI5;v+LCqB;(iqzAXb`gT7;U-UNG;6Iv!LP%BiTDysfyQnd+?>_qu#Cw#3a^+ zhC1o+VYR9)eTNw6dXaq_Yb_OwY~k|7O2`xiON3B%2BGT9`Pb41hzyVHfspXjg2kDVoFx-FN_0=xSzKZ31lY*BRnWplEhc9NrZJz`aD zMQ)+~j7&Y1al=lW%1_DgTwj&|WLGf!JUQoVRr)c+qU>^Ayw=Qq9Sw7~NwMlX&q()X ziEja&k5yTVI^q+a;`S|?|BkXV*3W(zNfa`siT)8Z3pS|RM8BtGOa>#Eh(z^AFanv52I~0; zYo|Cgvn*u>K@QUno$p+Gc+8(jNQR8Xi|4^!lpU_x+UgQ3u}P&%a+5PKTv(?+!|Q!? z^DQS6H^`~&=d?=2N%xPWu~$hCB}P@0RK-uzD*N>#6< zyVw@=URHdfrwNeOS*S{624&jtkc3fELd#ck*n4eIwgLTC`LnvBrFsE_=1V&ZTHGz> z_n){j=$YxDp6NbuQbI@;8eVZ4mau=zmn!BlEHUPa9I@YAEXwhGimv&znh>SOwzYj6 z?I1%JNO()8;g%F17yo(4pzdSw_cj;!w8zcsPy8F^u<^qQcR^BDS915toe`%07p3_} zr`^0My}K6I*qjV@I4s}04(ZmL7YZdq9+5aE<}7E;0_`@Tim$7Xo=YA1M~Xfl`yEaG z(xUwCd&9-6BrY){)sVh)UfWw|E{$oOFEUlb6o%L_|3$}|bMAK|oxrasM@Z(vEBq2{ zHA02LX+gY22-HS@?kJrBjU0I= zY>OJZ8Fo%>G~bstI=WBBOSBUgUe{i2uByoL_N3vCyuwOI%fIWy}xw*MhYAG_R%JfH(rzN6`vO@KlN^5V4>)Qz`Pm)u|KQai|Y|-t~B`|l6 z!z*ns9MgE5l@{PNbH1&bgWg1J`}(Lz`DJ{46?f6T343ypik4>J(Eb19-9Y+%sE@Ig z^*Wv|LSnITXeMgMoJbmtzYwdJWx1X({4sWdK(cPY4az&>Tk@xoWZO8@a%VX|$Zq4< z#Da4xtGpSXV_XDAkkG3Oe*bQ{R>TCD8~st0h8a;Yx8PEvIr8OCNj?7!zhBa4|NG1W zvh{bgQXLsCfeRa7WHN<}QIb=!71Gnf*^e#cqWc(P3!gpMN(zGv{4+uTGy_KbJ|}ZZp#@mu4$e4P7@PxTeM`I0{2s=`qo&3!V}{u2GH)mp5#@?GAW-pMRE58ma`AT` z!R1pVZME6fehT45D2^Z=;Hs{*m^1%s$8ZG0m1}l9XtN#&iW^!|W8|!ARa7x|hEo)^ zxawUP!SnEe(WpqAot03`8IjB_JpJiIFiTMqVRFsu*FQFTHbUnuvb=UdcOK&v9}}l& z91Sb@+%G?^_}ge}z(Ccbo6*%yxklu%+Ok`4?mZh$AwZk*%NWnoz=ftzn;H1QMV}NG z_;K=7oRPYdjx2Hxu>`T4NM%ivQuvP%_~@IdRxNMJ*QjHLqw^;?a2}Hq9QOW>iYeBH zJ5E^A^Dh)AuIML;&iVTs*oTqkV+@Q@I=ge z*PT87XZK1~N>j;~O#k9TPssFHL0ffQ?!&xk3=NeDa~c0)s*fX@^p#!i^ad7&oNHDm z%|gMHb-2|M3>oYfc11^Cwvb=LPIHmL?ZL)6r}@BcKzh=#62&b4ca!Cr-)lM5WZyYL zvvd^ITto>&?+Q1e1pWLFk&%8E!F33revw12!4`mk-c;GNEMK(vwX>oP0Ht~NF_yXM z_j20EU8jC@{h{o=E|Nagqm$>X$=AF|+wllsvp`}LHV86s(Uy9GD9jXg`o2@YVy%(3 z_~m5o+&~u#mE%x0JX6V|lUr2tT1HlpeEkGM&~l!i5JK|wv!*AC+xKWua$w_W&sK@> zpgm)y;Q2Zu!w-HMuI7_e4ou#RJ%C*R-8kiLFZuYsI>3qq6<$&jH#30kW1^#oAI@&X zrxVS_zyf2f$iD*l|J}}iY0ny6-jKS-TEVwi_bVunqia{5)M?%nP)*V*RthF3S+kMS43hbrag|1yXnaLK#K77&cSr|E+0Fwm5f|t z6S7~JKk?We|BrydZ;E5<1gP%ew0!tQ;C%rIQ)q8T;*Nw@qH!){Yav2d&yV>g%=<&e zWSOL%D*|S+|3r7sH;1y5QT>4)9#``&k_isKL%`_n>D-*1Qj=76K+tG?{>dU>R6ziy zrPN}n-do_EFq~wrY%X}<$Ur#bMl@iqe(*n zhpHU9deR~NDhT+U_z8(=fnVrRo9;cDZ9G^_RGR-@;CF#s)d>vv9X}%efV*YkJHFr9 zuX=>;8GLK9xD6ujA20|JfE&E6KWAfVbt0G28Q8;GLIeFkTW=VcDG(hsb6`AzcoC|wDX zBD!~0<=+5sPPEqyFjHC7hre~MI3nk14e=(M@AYm_TdViP{s^>w;8|OYJrEVTdnRdf zT%i0d%TVfyY@sN~vig9|(R5-4+T$XgaMk?{Q(&2XdGWH42RlkXkb1w0Jx@GV{_~x! zHeT~$S7&rNJx1N&A$r>D0ez_i1E38ny^IUc@*)nc6H}4_3B;yklZZQ;vi#t>g4ygc zRwU;tPTytwZ~47{nf8xa;doCn&K4j?ix$zm--fqIKIJtXY^*-JNLP~~fOfiCAhqir7y zw-BYw#=qy|nXfVu9!=_P%%XMT)%BEgEtEsvo)i9xo%ya`Z1);3`K8)%yH6%^azPy} zD}v3m(cgtwEr`u_zZ)!h(tVJ$qi7s~IP2)-5pK|r%B85)a(TQt8;wb@8R7?X1^Lik z_VzSk?iT-a@+K?yHyA#v<9=+vU^++RAKfG4aqi6=UiQklj-$^y=D*F=0H!jUqe7>z z_oOy8T_4z7%S60I*BCV9y~4*%ajpb^|Ir%#biHB|8~1$1iCS#GnMMTU@Yz6r^souc z8Im1eg5j>v@2d>P{>`9d>>Xvgl@Y|Mw+n?*A&o%7uNTT}h3kQ`CcjP|bhyHaVqwql z#LZ-S`3}&s%n9b{2;?y!4Q@J{_Lz@dYZ4iy3{_%(-FGX8qclnJjD|O*JHFq z)yu?mgiKNicz{4Q*W;@a(MLF#4UmUE#z1Abx$8Z(-$yC3&w?%1BL znKbPxuiU-2h?H|;vX(hc!Zp0kk{1ab*lpzm2K#%47WI&(vfw8dw~ypt5JQnu+HC>N z#y3Uh2?mp^JvnIRl_qz18G}4J)qFVh-dKScAKra)GNsNJT)+G(`8qh{ZBHv-)wG33*It8Xt-7_Ut*(+ z6>PCzHJW3!_lMki^!L(&WPJr)h(PY-j26|>f`J)9Ue}Pz~I$wzGpsE0u@yb!0C(cAoO((-Qr5sDVHc;2s zqnZ_{YTD5H05{9kdJf7Q|7h|GN@YFn0_(Ru!P_(No6UL0cKN4s;TZojj=KBrFbGsp ztUXdckeCzsA#vcf?dAql8r-c5(8AM zt~dBJSxB!$cK%0ey*GP5COpmaIadew0`f0^*2Zh zw4tI~fdy8t2Qp0!&9Pdq*jj)VX{XN-4cGuw3EmShIgd+j<2M)}@r;`_=JPM9hR@`fUr1iuFtpwz<0nr`h(-NYO} zhkK1ICD;I7Sm}G#40mI``u5AZiXjEjW=V*tJ=x)7hy;V)E?8gI0kL+HTrea?R8++r z*4F%n7+I6CE|twO`dpvkauO9>L&ZJfgm-Mu9%nSi*Q+BMj+<08wWY*WH$=094tX45 zuxMiP4Zikjr2B|W;`Ri)?EmDR8c0n`0OQp{e6m0hr%~KbH>6oRh%=R%?wl!zuoGKanq_?%9@(q znBDZgBUR89j*!jlWD>00gFlWx?WoS%k6ZZbVf7Ozezi7`lF#fO+78{QTpdco(-W6a z#F1@*t|m(i)T}fu(tj56{y;hrKQUihmrLx>^;zDS@C9y{-D#M&)~A0HqMP;w&Hq8} z({+k%@wg2wn+Z$;e9<=kX^NgM{*Y)To; zkBh#6M~DL=69JS58NQ!dYEvS<8-HOqMj#Y7Ib}Wy%JcVV`S<@i2mJLjd{X3%%#Q|p z%#Z8P{=nwVB@#jIrt_({xx}mKs;d3$ec?Y?yq2Zu%(xDJQSAJ6#cj(O1%$aW-W7b# zblOWx4O9DZBR3zr;$-OZgUxWXH1qI^xUuiE;>3jsQEx=<#3Y-%K##1;#m1j}0=AD? zj(T+e{0>H(KjR3#NlZt^KRDQbfBLFgK^pzv^S}DCSA6g5ze|RvnDuX}gMY@RAVU@Z zACUULUut@c{y)X>-u7@0`yY0Tf110xApOG{`A^$czJUe30Ak7NxLaiX%?2}Ib@vRP z#hFKHJkG6~1}r||-MRVe^+ZigxAb~~Ifum~J|;z{b%)wSghuvmg(sX{@lW)2)YLx2c%$ik0aVAl(SDgB&)5z=vHSYq;8tb!;<1+0(iT5NfzKl^ zMOO6Sr~!T7oU2y#uc3Oq(HaU=SI5jpj91v7_Cr!|YpNPUekbg)d+c2}tg!w2`hyG7 zMqP+w6P2+BTiHHeYpydNzfGHQfLHgV4#R58V1XfG80HnAp ztAMQkPTYgkBeei>%SmW|Gbep|q2iVCm(J$I6RP_Kz4=QszAlU(BfH%sI3dRp zL;MnotVW1hy59HgD}vNnFF@hls?Il(a|au6>&V}@=YNTU140NSZHcmru!GPW&z@gB ztiy@y^J@(myC8X#!(z|qz{luw;aAAH+Ycub1_KTGx3v+^9yZ_;eRgBYLzk-wde*&M zCfrTL{FePv0}cl6uJLaU*NX-@l$}GaeE;x(zK`_aJ~mutn3#SevraE^6?0KH*+|Pf z;M#RvKF|mq!qCWr_njw?Hw*P-_4=b^j7pfo2+!Bmt-f*;Ne=w8 zpfVV+YQ=uv>n6~ILe7skrex~z?7=ufOEvg7y)tRpo>de$u;(*+y z;%APF`b{kL;ao2G+%Ctr>uNPgbKH_9(+^Sns{kAs4R%3?EgH!EEYH=S>%$n} zgqer!vh-$%R9^87h2m}K7ETP3<=gJlVgqAN?F$ztw^z*xGsQOMLEKdAXXvLmV!TTh zS__4_haJ1+FHT+`qSrp6dQgQA9ikA%$-O0-yfHiyGA=c_-~l7Ql-zP|BIB=YPW4jX z<{I3I)^eyKc)0%Np8eW85Gicp;D)t1M9KH|y(ZY_n0~P#I?G3{q|Bj<%o!agMMi2p z5QShdwzq^bYxbkUH|mqcmW=pXBx|BJn5gLLFwOXBc6?ULkABm}PVQH&p`F%5*CLwY zZb2#aMjX8U#{70nx7a6Z{gv&KYI8gd3z!))QhTC5P!FZWBs3cE+p=Fy);f~(o`y?o zZ2O!g&{HzMte+6WncoWTxey^WD!2Lw2;AeUXl>^$5p_8SV_@Y-c%R!kJ3q#w8=Y%@ zu8!UsBfDHH6I&UAPUANtZjbM=ELj}u9}@tbGdiG$3Pc3&puolAOSx-*nh#XnE@w2K zyP82ot>4=mTJ|9X@+Uk=WrlJWzjp#&Cv5eDo6&iw2c zH`DMgx^?_FS1<_lxXZ*9yad7d8J-MPX`@bcEh0WpK~KId?Z($)*#L7=vUis$#_#ll zkwMpn^T5w(%B+*kZNAf!G+po4Qqw{SSFNTVs~&^8=>69_>?-ExfHpm9wK*;fRz+jX zuY<(AnH(1DgQx3RirV1MV@9e2@fK&>jeqO4k#qR*Gb)se>Z@A|uh(b~tp+dn5VNOJ z2kV|QBwFTD_@y9ej?sY<6M4CrNz+F!}M7`&V7{km5Yp5ez9c zW6btP6vG=?)fVv8NGg9Vi&2cfIcfgKKAW`-me|fgX-4j!247{x<$O$d3#G|^L<^-w zR<*_0cG;5{JsUE@W(aS;>HB1%rTjM20YH9pi}r+u^N{!yUP^#6Nbsk0U$?tKBU8cq zCNFDK`5o8wbycsew(%#}sENbX7%8Mmczos>x6Wxmn88{IEROnXTlGMIHD$(Jw|h<_ zb7E4Tq__mh`*^YKnMB|3)Gqn=@@U5vruC7|B@xl4%4NabsHx+b=XjbQtVSl!kJO&- zaM2-lfd9RcR$bGN%Z1Lq`aoga_kyH}_7`$5fveIIyZ2RqNs=RG{-!&g?Z>yE>n;ra zwFj-7O4RL-x4zGj?3(5cfsO~Bs@{6kZWIN111dehvnu4EcLc!rP<9qRZcx(V=hENHtK=nozKvaf5XHLmx%H_(N z`NnE(ymXFtTCB#tikiBtxDAA~Cd!bN-%yq#gU0$JrFpahbZ((9Ba6@tN492L>|`Lh z(9_y(<(n5?HJkJN>dl$RO(bjAS&ZRi!8QKOu^%put?A{opt%Bpgy(PdjsJEmFx^w=?crCb89R4Ilw| zU_~4b_-UX$Bk|~CjgWR`fB^Rt8A!)Yw5F`C-LAFXQrqP$W=}^+pA6bk+HQ{*RloLR zdH7}+3B}wL^`=0rS>p- z8Tg)mt;N(cNS@v^diiAm-fc&_9NIH(J5%ddX#Ke)?!DExOgFLKJ-l14d9y4v|66}3 zdsrHLdb^DvaL~52%G_G)?5}@3>5_OZmqFiRpQ@zPmZH%cWXa+tuduHjM*!;3WjiGP^T%r!iT5YaoxQUhoE-v zEiKLoceC_`@BZj~#$=LK@OGLa!a6;CICa=x3hpt*bDi$UrIg z*G<)T33J#hj;KP$+rY!+e|H)bS1cUPVx?=38XOe;_SLi*S|Z-l*qouLpdN=iz}>GF zL(h1~3wT8DdxghRgvj!)6U5i$8r&HZ_b6&iTnh?EcErhM6bWz{ME-Bd zOZsZ&)<;Lt1F8q=e*sMUcaay!ky6U*B_7i0E0rK+MiBA3W~m|HMS}=_a{1|$2sZ&``YYK(dlKRXu%y}MR)+_STVBhsvNZxCCac{_z)`l{Fu&f+<+ zcedHqhdVAs2?45Gb^{;G_d8gsG~CQumKw}ET6Uk~Xojr_q$QMGj;}#zrPRvzX)W$z zA|_3&?iT5X0@XPW^B!-e$@a{wyHDlv3JMLSbWE(}xPpc>7E*-O@}}n;qm<|NY!wEx zn5>1MHEs=sK~_Z~8sTHx>y0-iuBR{M@_Ow9o=3+DW|HAr*JlP}58K`ZDP!yy;oGBF z$2zE`eNCrYF3xX>cRqFZ2prxU$}YDP**rvd*cmV1xQgyXnaG6v5{6=G2|lF|a2@ZP z-*)T;p_cU7dLEN<2>!9_vVY8a7BPRVwJU0C9rqOcP*hnoeKPX2xbn1mXm04;=EQ#r z$0}|vY+i=?svR;sHX6r+%5)MM>(VDMKPctNfVFw|*{;5*s;Ytj(dr$> z9WLH6h)pKd18F)2%=T|@hFzXI849PZooTXKvi(pA+-K6}a^m?`*4FGy6?Qb9i%OrX zTNc}V*QsfStO#^wd9N4aeX)3-_r?Bmz#-lpk5nO+ajrPreo~Qc-?tj2=;DOE>?Yr= zmi;o>_X*dmu}FP@jn0a}`K@nQbRWT{iJHK5XMHVuxj!b?sr6VqqTrgkx~QvS{>a3V zQ8wNhM&3!ka+BO*=@KHe@l(9-2K zt15jOx(}wEv~B}!KMjGXKZ4Ns?D?sq@e4A@-_sPfMb!@Zk^xW zwZOv$D+KG*3k$bHCClMrCR#(9S?rqSBUOEzb(EH>CYH1SW`0P_{3&^g8zo(@Um|H9_NBK)fBy%`;CqKGnzg8Aei| z83u~FvdY}8D--e0OWA z_5Q~(MuYvN1}=OHsGk0;p`mT|1KT2MA5$_#zFjpqvwjn?!nTKD%kFereaK57VydDyQ}b-Ti26lE8tvLon9}1L zR|$1aOH72wYx_Ol-WSm!O6*nv!2)Zg^nkZ*r3{?BVC>KmhA5@iapRViC0rNiYk%l< z$_!@hAgKr8%m5ng`05ab7BgIqK#=UqOtsFB?@9)yl9KxiLV^rIS_|V8lq+j_xG4hZ ze|jD_AeITOOKq$u91SxjfYDsXUsyG7NQASUplibq9LaQgQTfA5u|m;7L*1Q|qr-h8 z^rcsZ)h_*W>lR|^`7@>N-Nx~J54Dkl5%t?kz;rX6`{~K~rFPt*S*?8zX2y!`#IMN- zCzqGFiqw$nh3OUCUXqNV8{}eipIo*> z#>MWvU)tZv9VO6yX=H{D5C2dU83OxB6r2A%sHH1i?B5eZf%B2d5@sUH;jlK^Yg zt6iPbX(~<=7k|44v;`m2F==%eBZSSxi2?OBREY{$XA0vOLd*IT1E1zMi_ux{vWqk< z4rif;U0Nzs<5hOBg}o6KNzTRwC(wXxuPOW4l3Qy4JAY19P5FyWBv~~+r#%d!p8Ua? zt0b$dE$SK1-IjoDMrTF*hht;}sG-Af36S`#y1F|XPg^u;yN_|578rE2R0|Nun;GzE zW>)kNY{7DF1w%Tblg#A&{w?uaZ)`RZyQXt)$6J@y-I)oKG_0q z6C`4Uj@4S)tc({iMQ6@YHumVBf!U%6NLLRLl2@hVeLvxD+&^8wz8Jt5bhK8S(AmK; ze%II1qN4F22I{f5@GbR9wU*ewSDi*);?y}wlSeZ_RwCA{01SIyH^pBRSmDvA(1i43RlUKl zho+zZH6*Qk?}j8%>gdQXKvL5bCXNk5?<|d-DkZ!H`oUC{ez#oTLDlwD)cP={F9LCScql>El%(>qbN-1EVi9ztb-(GdqS{ds zxd98sRA|doIRFtY=~Hq+P}?1whd(p=YK>-RN8TknF?z%7(Qx9vH8UMnqoYRh`VeS* zm(&QMoYEOXOV$w!TazWyj{5n?@LTEIV=Q`&ghM(8tr|MPOm(Pd1n!rW2NOIDYPv(;6$P zV2@`9%T6<0MPwlC>qp|}4PaG$YHK6=n(Xi4dh2tu@u zT*!3rMk$cque>~Wc=D@8clM9F?W)R>Uln5$n#Hxbm0}Xy4Jsq z4fNw|QV24jAY1;vMpwiAFQ}}ijPEFRIkmjJc3KZQ<;~O+5psw;8krrUe0X}snLS_c zCAz*!Y;)xUG8`dbj98`UeOa$&0sdiPs(=YPO<46T=Vm)UR2a}Sz#1D9 zW+f4baSw$a;kRG)?ozU`VfQxv&&B=SdEJRdJ0ccCZQ%%RR~iS5-!hvZfP zE`}PVOS*hP`l4%Q*=RFMIkHj>JQe}mTu?*XMh#B0KW(aatypc@~xTpTyV_3?m-Mo5ufwG?bZt8x#4(edrZx52`Q3mMkHMF-z?*a zhpr7F&>)o5MsymPP*7KQ_*gAO1a?i&oPEEUJ^2wT%Ho-li(o%!65bRtFG(QY!iB<2Syv&t0T|2FgU zYSjw@4;cW)77I)wX(&|TrYOlz%GG>VNPM$CMJmqE{>^*;SCHK5J*^pxDW#_7ldwRB zFg@?Sv(!uJqp+13{_-$Tgn4w|HUfX_uQ)4lyE_j>;u@>oR;J;0?s%UM+c$MA1qLe%F6WCTTVd6Z^_#a3 z7i62qTcuXN8Y&Ws!9B)d(GgunL5%^ChPl6q%^C@^&Nbe0Ago2;nPERV&~kmO~a6)(qB&P;B(2R4pLT=w>_oq`*96zqpkdtXnh*(a9Tq(=y_t2Xit~iHiIRl}CvMxv#ZtEYZpEUCq-1M+4wd5P z44#sL{Cm_fSD)~Vl{K}u8WCkJH_*o3&kuD=S_IO|c>A75BMb+#4d8)*^Rl4anpHnrr zbhlXfaiNK>6ymoFRBXWEQFV^sfD_I};5ii?pI&L_HM^XjxQm&J$Zg5F(L7se>b5ZHej+~{1scSwH*VvTgjky^THec-r|$+R3(@8guO*8W7-r!Q2>T6+MF2Mz+(yDI)I z8#kBg9fWGtT>$GSa~Ln4R##j@XzSU@&w6Lxrx=`w=?zSp*%NlFiqv8>=K4)J*q{e> z^RyNDa?9%%ON%|lW0MQ1+ZizkHyDSxv^DBZ)0e>eRkX+)_30o(&li@eZMt6D#fysG81i zRpNc)IM{nhFnLwoMOB&e5#*~HX9IZpBOQm}EhUy%j;=HTZjFi*^6KIjXk1uvBcuT2 zV$)NKS6-)gz|Bj}-WYNAM6&K7WcM+8`=AOq>8h>!;x0_=n&Xtd^bvZ!2m>+!{W9@s%)yB#iekTJ$riAek zLW7W87w}B~#GQBCa-00I`bqdWNrj=D=0L#-ujH^fO`PTJwOo_69)C#m?*7-+&K>bD z_>TdL8yc@Vyg{C6IZ}1lrf;@Y6*Y&`D6#b#!Lc5u%3+1un+RfS&$nF~P*R$lEhr>E z*W#ipf9Im>ktjU3QBPm0cx|%0FtD~;4ELj*B7~rd2|3`2KN?o{Jl%kGW-F(Q_gXThXT6 z%6&5ySZmSFT58dDapBfG8S#5V7Lg*trU`~lLbNs#e$n!|_)t57 zw+?mVsk&0|v{IjxeA5h1O*2+QBpf5Xe!&wg@2xh*`9eY`;AS_nnCRtOEiNqbHD1;a z>qJ%a@M$bF>POj|vRk#XP4JlE;wfzJA4bG-rsk{UY`tZB)DBq?yT+cJ4~|Km*@@6y zOJac)`|iGcRJ3!}_l-_v*!R)4=*35sE@LB?YP;ul4%-&T0NPm%t0WRaA$WRn=NBMA zB2PEI;jz_9r=v<*WWBfL{sBknawxuAhMS{C%RfwtYx0Qc(}K$8^cF@xIXxEmsBUVb4HOJ5<6edSZCl_ z@(kjdM*n9NayKpLG(obfe9nrV-<#3o6!v+&-eC8Bs1GaU9TuL&ayHkA=()Lb%J(Qz z4P6*z>TE`>nSL=bnl>$J=XzbE9*HM!iNiY@QoEOhV^+BIfxEVC)4ZeXd)aqon^fOb zk}9P+K%m9(j7UUt3JeMkSdUn=Ehew)!jMBLwq2Z5%a?PnpmRvvFGNxXE^}-N_ja-E z-3ym&n6o)hg3|qF1#J3-NzqMVwZ5}KNwE*I4|ZPY+NUP&cTg$3d-@r_>6W`#+xC8Z zHT7)|j4(Vea7O#+ON#nDG7?uz^42Sj@k(}|>!4{9FKb9NAq*BMWI zM;myjK^tEODM%Rd^OM{V)`&33QWi6+ZVB2YAvy->gFZuL7HZDx!cqj(QvIg>tNg zmJ&Vm+@*ppBrPNf4LZKz?e4YgNFv8~&^zu|EICpt7q@X!rE=4Cf0Sa>*JP|*2|fu!yQE~8NJCehprIK9WkrHB=hDyji~fvdAZ zNwpOBM2m|#_lwM8?~5R8)Gf9YPXmfU$aN)k`KsYT{sz6dXV1&Y!zp7+;G?GjHBJVf z>Q+HLq*?kr=Fs=t&~8e2H0Do;cH4DbQ-&xsEwJ0c?Ltsnvg1p9X&o&rSwtk)%HB)b zldK@q@TmGp_QZsdWMRS2Uk7;VYK@B$?^qs{$~|WWKb{F)tUE(>Wzkj3d&N5>@-OXi z&KlvuJ9zx6G=S|Rw?obEQH^iE&HLG1K;>;Gq!xUWG!Ym;PwqJD1L!Hrv$Gxt7{zlwtVf1!88h}P;PBy3sRY))GebDPX8&M zgK&ktm$k;=Sw_a&oczy{tmF5GSNOhUT=G5_Iq|6Rgz3h1|5L8)zjS6?2HI6FVr63o z8k#OS$K&cBy+)+OZWH7@8OFB(d#ruAupe1Aet+Y45$Cz|nerD3iI3Zcnz4)3CT4_3 za|SH)46AY%59Z>mk)9p%&eif9yQ@wnS*kE%!kt4tAtUzo5^0a6@nDI%3eyDtMF0$#gYCM0o<4dWWwx?z+=|b#||y1iVL< zox*lUm+oQbN8efe4$l552sM25@Mg0%iGzv`y!P!2qS)xM3on%YIb32b`{nryv`d^{ z&u3P9DpY=DwiU^7=6QQIQg{9XXH!2JTgDfCs?V*v;H;=K8Jz?xF^eqQ{$6v5cq^m5 z;HHfumjjeQqBWK9dbdE8B`SLrH>xS!eGlB8p;*}?Q9u#W^-{!v-zPJ4{4c=KP6YHj zngIg;mvH2r{r{c{{2#>W{~43{|I7aCHnUOmz5QUP_*W%+GnM Date: Tue, 19 Dec 2023 14:19:09 +0900 Subject: [PATCH 83/87] feat(run_out)!: ignore the collision points on crosswalk (#5862) * suppress on crosswalk Signed-off-by: Yuki Takagi --- .../config/run_out.param.yaml | 1 + .../package.xml | 1 + .../src/manager.cpp | 1 + .../src/scene.cpp | 43 ++++++++++++++++--- .../src/scene.hpp | 8 +++- .../src/utils.hpp | 1 + 6 files changed, 47 insertions(+), 8 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 ea63462b32d84..5534228c1b86f 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 use_partition_lanelet: true # [-] whether to use partition lanelet map data + suppress_on_crosswalk: true # [-] whether to suppress on crosswalk lanelet: specify_decel_jerk: false # [-] 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 diff --git a/planning/behavior_velocity_run_out_module/package.xml b/planning/behavior_velocity_run_out_module/package.xml index 7bd27fca3407c..809579b383461 100644 --- a/planning/behavior_velocity_run_out_module/package.xml +++ b/planning/behavior_velocity_run_out_module/package.xml @@ -20,6 +20,7 @@ autoware_auto_perception_msgs autoware_auto_planning_msgs + behavior_velocity_crosswalk_module behavior_velocity_planner_common eigen geometry_msgs diff --git a/planning/behavior_velocity_run_out_module/src/manager.cpp b/planning/behavior_velocity_run_out_module/src/manager.cpp index 09c87ed81cf38..3ba9bf8bf52e6 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.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"); p.passing_margin = getOrDeclareParameter(node, ns + ".passing_margin"); diff --git a/planning/behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_run_out_module/src/scene.cpp index 7a13c0c4f1052..92516e7b4424b 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_run_out_module/src/scene.cpp @@ -14,6 +14,7 @@ #include "scene.hpp" +#include "behavior_velocity_crosswalk_module/util.hpp" #include "path_utils.hpp" #include @@ -23,6 +24,10 @@ #include #include +#include + +#include +#include #include #include @@ -110,8 +115,14 @@ bool RunOutModule::modifyPathVelocity( elapsed_obstacle_creation.count() / 1000.0); // detect collision with dynamic obstacles using velocity planning of ego + const auto crosswalk_lanelets = planner_param_.run_out.suppress_on_crosswalk + ? getCrosswalksOnPath( + planner_data_->current_odometry->pose, *path, + planner_data_->route_handler_->getLaneletMapPtr(), + planner_data_->route_handler_->getOverallGraphPtr()) + : std::vector>(); const auto dynamic_obstacle = - detectCollision(partition_excluded_obstacles, extended_smoothed_path); + detectCollision(partition_excluded_obstacles, extended_smoothed_path, crosswalk_lanelets); // record time for collision check const auto t_collision_check = std::chrono::system_clock::now(); @@ -155,7 +166,8 @@ bool RunOutModule::modifyPathVelocity( } std::optional RunOutModule::detectCollision( - const std::vector & dynamic_obstacles, const PathWithLaneId & path) + const std::vector & dynamic_obstacles, const PathWithLaneId & path, + const std::vector> & crosswalk_lanelets) { if (path.points.size() < 2) { RCLCPP_WARN_STREAM(logger_, "path doesn't have enough points."); @@ -189,7 +201,7 @@ std::optional RunOutModule::detectCollision( debug_ptr_->pushTravelTimeTexts(travel_time, p2.pose, /* lateral_offset */ 3.0); auto obstacles_collision = - checkCollisionWithObstacles(dynamic_obstacles, vehicle_poly, travel_time); + checkCollisionWithObstacles(dynamic_obstacles, vehicle_poly, travel_time, crosswalk_lanelets); if (obstacles_collision.empty()) { continue; } @@ -309,7 +321,8 @@ std::vector RunOutModule::createVehiclePolygon( std::vector RunOutModule::checkCollisionWithObstacles( const std::vector & dynamic_obstacles, - std::vector poly, const float travel_time) const + std::vector poly, const float travel_time, + const std::vector> & crosswalk_lanelets) const { const auto bg_poly_vehicle = run_out_utils::createBoostPolyFromMsg(poly); @@ -338,8 +351,8 @@ std::vector RunOutModule::checkCollisionWithObstacles( *predicted_obstacle_pose_min_vel, *predicted_obstacle_pose_max_vel}; std::vector collision_points; - const bool collision_detected = - checkCollisionWithShape(bg_poly_vehicle, pose_with_range, obstacle.shape, collision_points); + const bool collision_detected = checkCollisionWithShape( + bg_poly_vehicle, pose_with_range, obstacle.shape, crosswalk_lanelets, collision_points); if (!collision_detected) { continue; @@ -398,6 +411,7 @@ std::optional RunOutModule::calcPredictedObstaclePose( bool RunOutModule::checkCollisionWithShape( const Polygon2d & vehicle_polygon, const PoseWithRange pose_with_range, const Shape & shape, + const std::vector> & crosswalk_lanelets, std::vector & collision_points) const { bool collision_detected = false; @@ -420,6 +434,23 @@ bool RunOutModule::checkCollisionWithShape( break; } + if (!collision_points.empty()) { + for (const auto & crosswalk : crosswalk_lanelets) { + const auto poly = crosswalk.second.polygon2d().basicPolygon(); + for (auto it = collision_points.begin(); it != collision_points.end();) { + if (boost::geometry::within(lanelet::BasicPoint2d(it->x, it->y), poly)) { + it = collision_points.erase(it); + } else { + ++it; + } + } + if (collision_points.empty()) { + break; + } + } + collision_detected = !collision_points.empty(); + } + return collision_detected; } diff --git a/planning/behavior_velocity_run_out_module/src/scene.hpp b/planning/behavior_velocity_run_out_module/src/scene.hpp index b1c49189267d4..def90f036c440 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/behavior_velocity_run_out_module/src/scene.hpp @@ -24,6 +24,7 @@ #include #include +#include #include namespace behavior_velocity_planner @@ -67,7 +68,8 @@ class RunOutModule : public SceneModuleInterface Polygons2d createDetectionAreaPolygon(const PathWithLaneId & smoothed_path) const; std::optional detectCollision( - const std::vector & dynamic_obstacles, const PathWithLaneId & path_points); + const std::vector & dynamic_obstacles, const PathWithLaneId & path, + const std::vector> & crosswalk_lanelets); float calcCollisionPositionOfVehicleSide( const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Pose & base_pose) const; @@ -77,7 +79,8 @@ class RunOutModule : public SceneModuleInterface std::vector checkCollisionWithObstacles( const std::vector & dynamic_obstacles, - std::vector poly, const float travel_time) const; + std::vector poly, const float travel_time, + const std::vector> & crosswalk_lanelets) const; std::optional findNearestCollisionObstacle( const PathWithLaneId & path, const geometry_msgs::msg::Pose & base_pose, @@ -89,6 +92,7 @@ class RunOutModule : public SceneModuleInterface bool checkCollisionWithShape( const Polygon2d & vehicle_polygon, const PoseWithRange pose_with_range, const Shape & shape, + const std::vector> & crosswalk_lanelets, std::vector & collision_points) const; bool checkCollisionWithCylinder( diff --git a/planning/behavior_velocity_run_out_module/src/utils.hpp b/planning/behavior_velocity_run_out_module/src/utils.hpp index 6afe451f72f73..5524c0f76049d 100644 --- a/planning/behavior_velocity_run_out_module/src/utils.hpp +++ b/planning/behavior_velocity_run_out_module/src/utils.hpp @@ -54,6 +54,7 @@ struct RunOutParam { std::string detection_method; bool use_partition_lanelet; + bool suppress_on_crosswalk; bool specify_decel_jerk; double stop_margin; double passing_margin; From 1b179590c1620c4d451a6aeeb8aa59f509aef2f5 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 19 Dec 2023 16:37:38 +0900 Subject: [PATCH 84/87] fix(dynamic_avoidance): fix drivable area generation during LC (#5902) * fix(dynamic_avoidance): fix drivable area generation during LC Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.hpp | 26 ++- .../dynamic_avoidance_module.cpp | 152 ++++++++++++++---- 2 files changed, 135 insertions(+), 43 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index e37ef27d44426..779b7c6106eb0 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -143,15 +143,18 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::optional lat_offset_to_avoid{std::nullopt}; bool is_collision_left{false}; bool should_be_avoided{false}; + std::vector ref_path_points_for_obj_poly; void update( const MinMaxValue & arg_lon_offset_to_avoid, const MinMaxValue & arg_lat_offset_to_avoid, - const bool arg_is_collision_left, const bool arg_should_be_avoided) + const bool arg_is_collision_left, const bool arg_should_be_avoided, + const std::vector & arg_ref_path_points_for_obj_poly) { lon_offset_to_avoid = arg_lon_offset_to_avoid; lat_offset_to_avoid = arg_lat_offset_to_avoid; is_collision_left = arg_is_collision_left; should_be_avoided = arg_should_be_avoided; + ref_path_points_for_obj_poly = arg_ref_path_points_for_obj_poly; } }; @@ -245,11 +248,13 @@ class DynamicAvoidanceModule : public SceneModuleInterface void updateObject( const std::string & uuid, const MinMaxValue & lon_offset_to_avoid, const MinMaxValue & lat_offset_to_avoid, const bool is_collision_left, - const bool should_be_avoided) + const bool should_be_avoided, + const std::vector & ref_path_points_for_obj_poly) { if (object_map_.count(uuid) != 0) { object_map_.at(uuid).update( - lon_offset_to_avoid, lat_offset_to_avoid, is_collision_left, should_be_avoided); + lon_offset_to_avoid, lat_offset_to_avoid, is_collision_left, should_be_avoided, + ref_path_points_for_obj_poly); } } @@ -307,12 +312,16 @@ class DynamicAvoidanceModule : public SceneModuleInterface bool isLabelTargetObstacle(const uint8_t label) const; void updateTargetObjects(); + void updateRefPathBeforeLaneChange(const std::vector & ego_ref_path_points); bool willObjectCutIn( const std::vector & ego_path, const PredictedPath & predicted_path, const double obj_tangent_vel, const LatLonOffset & lat_lon_offset) const; DecisionWithReason willObjectCutOut( const double obj_tangent_vel, const double obj_normal_vel, const bool is_object_left, const std::optional & prev_object) const; + bool willObjectBeOutsideEgoChangingPath( + const geometry_msgs::msg::Pose & obj_pose, + const autoware_auto_perception_msgs::msg::Shape & obj_shape, const double obj_vel) const; bool isObjectFarFromPath( const PredictedObject & predicted_object, const double obj_dist_to_path) const; double calcTimeToCollision( @@ -327,14 +336,14 @@ class DynamicAvoidanceModule : public SceneModuleInterface const PredictedPath & obj_path, const geometry_msgs::msg::Pose & obj_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape) const; MinMaxValue calcMinMaxLongitudinalOffsetToAvoid( - const std::vector & input_ref_path_points, + const std::vector & ref_path_points_for_obj_poly, const geometry_msgs::msg::Pose & obj_pose, const Polygon2d & obj_points, const double obj_vel, const PredictedPath & obj_path, const autoware_auto_perception_msgs::msg::Shape & obj_shape, const double time_to_collision) const; std::optional calcMinMaxLateralOffsetToAvoid( - const std::vector & input_ref_path_points, const Polygon2d & obj_points, - const double obj_vel, const bool is_collision_left, const double obj_normal_vel, - const std::optional & prev_object) const; + const std::vector & ref_path_points_for_obj_poly, + const Polygon2d & obj_points, const double obj_vel, const bool is_collision_left, + const double obj_normal_vel, const std::optional & prev_object) const; std::pair getAdjacentLanes( const double forward_distance, const double backward_distance) const; @@ -353,7 +362,8 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::vector target_objects_; // std::vector prev_target_objects_; - std::vector prev_input_ref_path_points; + std::optional> prev_input_ref_path_points_{std::nullopt}; + std::optional> ref_path_before_lane_change_{std::nullopt}; std::shared_ptr parameters_; TargetObjectsManager target_objects_manager_; diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 99d7931dff907..a3e4e0e4f3e86 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -137,7 +137,26 @@ double calcObstacleMaxLength(const autoware_auto_perception_msgs::msg::Shape & s return max_length_to_point; } - throw std::logic_error("The shape type is not supported in obstacle_cruise_planner."); + throw std::logic_error("The shape type is not supported in dynamic_avoidance."); +} + +double calcObstacleWidth(const autoware_auto_perception_msgs::msg::Shape & shape) +{ + if (shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + return shape.dimensions.y; + } else if (shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { + return shape.dimensions.x; + } else if (shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) { + double max_length_to_point = 0.0; + for (const auto rel_point : shape.footprint.points) { + const double length_to_point = std::hypot(rel_point.x, rel_point.y); + if (max_length_to_point < length_to_point) { + max_length_to_point = length_to_point; + } + } + return max_length_to_point; + } + throw std::logic_error("The shape type is not supported in dynamic_avoidance."); } double calcDiffAngleAgainstPath( @@ -404,6 +423,8 @@ void DynamicAvoidanceModule::updateTargetObjects() const auto input_ref_path_points = getPreviousModuleOutput().reference_path.points; const auto prev_objects = target_objects_manager_.getValidObjects(); + updateRefPathBeforeLaneChange(input_ref_path_points); + // 1. Rough filtering of target objects target_objects_manager_.initialize(); for (const auto & predicted_object : predicted_objects) { @@ -498,6 +519,8 @@ void DynamicAvoidanceModule::updateTargetObjects() object.predicted_paths.begin(), object.predicted_paths.end(), [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); + const auto & ref_path_points_for_obj_poly = input_path.points; + // 2.a. check if object is not to be followed by ego const double obj_angle = calcDiffAngleAgainstPath(input_path.points, object.pose); const bool is_object_aligned_to_path = @@ -535,6 +558,17 @@ void DynamicAvoidanceModule::updateTargetObjects() continue; } + // 2.e. check if the ego will change the lane and the object will be outside the ego's path + // const auto will_object_be_outside_ego_changing_path = + // willObjectBeOutsideEgoChangingPath(object.pose, object.shape, object.vel); + // if (will_object_be_outside_ego_changing_path) { + // RCLCPP_INFO_EXPRESSION( + // getLogger(), parameters_->enable_debug_info, + // "[DynamicAvoidance] Ignore obstacle (%s) since the object will be outside ego's changing + // path", obj_uuid.c_str()); + // continue; + // } + // 2.e. check time to collision const double time_to_collision = calcTimeToCollision(input_path.points, object.pose, object.vel, lat_lon_offset); @@ -590,10 +624,10 @@ void DynamicAvoidanceModule::updateTargetObjects() // "ego_path_base" const auto obj_points = tier4_autoware_utils::toPolygon2d(object.pose, object.shape); const auto lon_offset_to_avoid = calcMinMaxLongitudinalOffsetToAvoid( - input_ref_path_points, object.pose, obj_points, object.vel, obj_path, object.shape, + ref_path_points_for_obj_poly, object.pose, obj_points, object.vel, obj_path, object.shape, time_to_collision); const auto lat_offset_to_avoid = calcMinMaxLateralOffsetToAvoid( - input_ref_path_points, obj_points, object.vel, is_collision_left, object.lat_vel, + ref_path_points_for_obj_poly, obj_points, object.vel, is_collision_left, object.lat_vel, prev_object); if (!lat_offset_to_avoid) { RCLCPP_INFO_EXPRESSION( @@ -606,10 +640,37 @@ void DynamicAvoidanceModule::updateTargetObjects() const bool should_be_avoided = true; target_objects_manager_.updateObject( - obj_uuid, lon_offset_to_avoid, *lat_offset_to_avoid, is_collision_left, should_be_avoided); + obj_uuid, lon_offset_to_avoid, *lat_offset_to_avoid, is_collision_left, should_be_avoided, + ref_path_points_for_obj_poly); } - prev_input_ref_path_points = input_ref_path_points; + prev_input_ref_path_points_ = input_ref_path_points; +} + +void DynamicAvoidanceModule::updateRefPathBeforeLaneChange( + const std::vector & ego_ref_path_points) +{ + if (ref_path_before_lane_change_) { + // check if the ego is close enough to the current ref path, meaning that lane change ends. + const auto ego_pos = getEgoPose().position; + const double dist_to_ref_path = + std::abs(motion_utils::calcLateralOffset(ego_ref_path_points, ego_pos)); + + constexpr double epsilon_dist_to_ref_path = 0.5; + if (dist_to_ref_path < epsilon_dist_to_ref_path) { + ref_path_before_lane_change_ = std::nullopt; + } + } else { + // check if the ego is during lane change. + if (prev_input_ref_path_points_ && !prev_input_ref_path_points_->empty()) { + const double dist_ref_paths = std::abs(motion_utils::calcLateralOffset( + ego_ref_path_points, prev_input_ref_path_points_->front().point.pose.position)); + constexpr double epsilon_ref_paths_diff = 1.0; + if (epsilon_ref_paths_diff < dist_ref_paths) { + ref_path_before_lane_change_ = *prev_input_ref_path_points_; + } + } + } } [[maybe_unused]] std::optional> @@ -765,6 +826,25 @@ DynamicAvoidanceModule::DecisionWithReason DynamicAvoidanceModule::willObjectCut return DecisionWithReason{false}; } +[[maybe_unused]] bool DynamicAvoidanceModule::willObjectBeOutsideEgoChangingPath( + const geometry_msgs::msg::Pose & obj_pose, + const autoware_auto_perception_msgs::msg::Shape & obj_shape, const double obj_vel) const +{ + if (!ref_path_before_lane_change_ || obj_vel < 0.0) { + return false; + } + + // Check if object is in the lane before ego's lane change. + const double dist_to_ref_path_before_lane_change = + std::abs(motion_utils::calcLateralOffset(*ref_path_before_lane_change_, obj_pose.position)); + const double epsilon_dist_checking_in_lane = calcObstacleWidth(obj_shape); + if (epsilon_dist_checking_in_lane < dist_to_ref_path_before_lane_change) { + return false; + } + + return true; +} + std::pair DynamicAvoidanceModule::getAdjacentLanes( const double forward_distance, const double backward_distance) const { @@ -840,13 +920,13 @@ DynamicAvoidanceModule::LatLonOffset DynamicAvoidanceModule::getLateralLongitudi } MinMaxValue DynamicAvoidanceModule::calcMinMaxLongitudinalOffsetToAvoid( - const std::vector & input_ref_path_points, + const std::vector & ref_path_points_for_obj_poly, const geometry_msgs::msg::Pose & obj_pose, const Polygon2d & obj_points, const double obj_vel, const PredictedPath & obj_path, const autoware_auto_perception_msgs::msg::Shape & obj_shape, const double time_to_collision) const { const size_t obj_seg_idx = - motion_utils::findNearestSegmentIndex(input_ref_path_points, obj_pose.position); + motion_utils::findNearestSegmentIndex(ref_path_points_for_obj_poly, obj_pose.position); // calculate min/max longitudinal offset from object to path const auto obj_lon_offset = [&]() { @@ -854,7 +934,7 @@ MinMaxValue DynamicAvoidanceModule::calcMinMaxLongitudinalOffsetToAvoid( for (size_t i = 0; i < obj_points.outer().size(); ++i) { const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); const double lon_offset = motion_utils::calcLongitudinalOffsetToSegment( - input_ref_path_points, obj_seg_idx, geom_obj_point); + ref_path_points_for_obj_poly, obj_seg_idx, geom_obj_point); obj_lon_offset_vec.push_back(lon_offset); } @@ -930,27 +1010,29 @@ double DynamicAvoidanceModule::calcValidStartLengthToAvoid( } std::optional DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( - const std::vector & input_ref_path_points, const Polygon2d & obj_points, - const double obj_vel, const bool is_collision_left, const double obj_normal_vel, - const std::optional & prev_object) const + const std::vector & ref_path_points_for_obj_poly, + const Polygon2d & obj_points, const double obj_vel, const bool is_collision_left, + const double obj_normal_vel, const std::optional & prev_object) const { + const bool enable_lowpass_filter = true; + /* const bool enable_lowpass_filter = [&]() { - if (prev_input_ref_path_points.size() < 2) { + if (!prev_ref_path_points_for_obj_poly_ || prev_ref_path_points_for_obj_poly_->size() < 2) { return true; } const size_t prev_front_seg_idx = motion_utils::findNearestSegmentIndex( - prev_input_ref_path_points, input_ref_path_points.front().point.pose.position); - constexpr double min_lane_change_path_lat_offset = 1.0; - if ( - motion_utils::calcLateralOffset( - prev_input_ref_path_points, input_ref_path_points.front().point.pose.position, - prev_front_seg_idx) < min_lane_change_path_lat_offset) { - return true; + *prev_ref_path_points_for_obj_poly_, + ref_path_points_for_obj_poly.front().point.pose.position); constexpr double + min_lane_change_path_lat_offset = 1.0; if ( motion_utils::calcLateralOffset( + *prev_ref_path_points_for_obj_poly_, + ref_path_points_for_obj_poly.front().point.pose.position, prev_front_seg_idx) < + min_lane_change_path_lat_offset) { return true; } // NOTE: When the input reference path laterally changes, the low-pass filter is disabled not to // shift the obstacle polygon suddenly. return false; }(); + */ // calculate min/max lateral offset from object to path const auto obj_lat_abs_offset = [&]() { @@ -958,9 +1040,9 @@ std::optional DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoi for (size_t i = 0; i < obj_points.outer().size(); ++i) { const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); const size_t obj_point_seg_idx = - motion_utils::findNearestSegmentIndex(input_ref_path_points, geom_obj_point); - const double obj_point_lat_offset = - motion_utils::calcLateralOffset(input_ref_path_points, geom_obj_point, obj_point_seg_idx); + motion_utils::findNearestSegmentIndex(ref_path_points_for_obj_poly, geom_obj_point); + const double obj_point_lat_offset = motion_utils::calcLateralOffset( + ref_path_points_for_obj_poly, geom_obj_point, obj_point_seg_idx); obj_lat_abs_offset_vec.push_back(obj_point_lat_offset); } return getMinMaxValues(obj_lat_abs_offset_vec); @@ -1027,19 +1109,19 @@ DynamicAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( return std::nullopt; } - auto input_ref_path_points = getPreviousModuleOutput().reference_path.points; + auto ref_path_points_for_obj_poly = object.ref_path_points_for_obj_poly; const size_t obj_seg_idx = - motion_utils::findNearestSegmentIndex(input_ref_path_points, object.pose.position); + motion_utils::findNearestSegmentIndex(ref_path_points_for_obj_poly, object.pose.position); const auto obj_points = tier4_autoware_utils::toPolygon2d(object.pose, object.shape); const auto lon_bound_start_idx_opt = motion_utils::insertTargetPoint( - obj_seg_idx, object.lon_offset_to_avoid->min_value, input_ref_path_points); + obj_seg_idx, object.lon_offset_to_avoid->min_value, ref_path_points_for_obj_poly); const size_t updated_obj_seg_idx = (lon_bound_start_idx_opt && lon_bound_start_idx_opt.value() <= obj_seg_idx) ? obj_seg_idx + 1 : obj_seg_idx; const auto lon_bound_end_idx_opt = motion_utils::insertTargetPoint( - updated_obj_seg_idx, object.lon_offset_to_avoid->max_value, input_ref_path_points); + updated_obj_seg_idx, object.lon_offset_to_avoid->max_value, ref_path_points_for_obj_poly); if (!lon_bound_start_idx_opt && !lon_bound_end_idx_opt) { // NOTE: The obstacle is longitudinally out of the ego's trajectory. @@ -1049,20 +1131,20 @@ DynamicAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( lon_bound_start_idx_opt ? lon_bound_start_idx_opt.value() : static_cast(0); const size_t lon_bound_end_idx = lon_bound_end_idx_opt ? lon_bound_end_idx_opt.value() - : static_cast(input_ref_path_points.size() - 1); + : static_cast(ref_path_points_for_obj_poly.size() - 1); // create inner/outer bound points std::vector obj_inner_bound_points; std::vector obj_outer_bound_points; for (size_t i = lon_bound_start_idx; i <= lon_bound_end_idx; ++i) { - obj_inner_bound_points.push_back( - tier4_autoware_utils::calcOffsetPose( - input_ref_path_points.at(i).point.pose, 0.0, object.lat_offset_to_avoid->min_value, 0.0) - .position); - obj_outer_bound_points.push_back( - tier4_autoware_utils::calcOffsetPose( - input_ref_path_points.at(i).point.pose, 0.0, object.lat_offset_to_avoid->max_value, 0.0) - .position); + obj_inner_bound_points.push_back(tier4_autoware_utils::calcOffsetPose( + ref_path_points_for_obj_poly.at(i).point.pose, 0.0, + object.lat_offset_to_avoid->min_value, 0.0) + .position); + obj_outer_bound_points.push_back(tier4_autoware_utils::calcOffsetPose( + ref_path_points_for_obj_poly.at(i).point.pose, 0.0, + object.lat_offset_to_avoid->max_value, 0.0) + .position); } // create obj_polygon from inner/outer bound points From a427d2967d22c233157acdfb72b7f8fac9770094 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 19 Dec 2023 18:32:45 +0900 Subject: [PATCH 85/87] feat(dynamic_avoidance): deal with forked path of the same directional vehicles (#5901) Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.hpp | 2 +- .../dynamic_avoidance_module.cpp | 16 ++++++++++------ 2 files changed, 11 insertions(+), 7 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index 779b7c6106eb0..36106f32158b9 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -332,7 +332,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface LatLonOffset getLateralLongitudinalOffset( const std::vector & ego_path, const geometry_msgs::msg::Pose & obj_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape) const; - double calcValidStartLengthToAvoid( + double calcValidLengthToAvoid( const PredictedPath & obj_path, const geometry_msgs::msg::Pose & obj_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape) const; MinMaxValue calcMinMaxLongitudinalOffsetToAvoid( diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index a3e4e0e4f3e86..eb6724a453f1e 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -962,19 +962,23 @@ MinMaxValue DynamicAvoidanceModule::calcMinMaxLongitudinalOffsetToAvoid( std::abs(obj_vel) * (is_object_overtaking ? parameters_->end_duration_to_avoid_overtaking_object : parameters_->end_duration_to_avoid_oncoming_object); - if (obj_vel < 0) { - const double valid_start_length_to_avoid = - calcValidStartLengthToAvoid(obj_path, obj_pose, obj_shape); + const double valid_length_to_avoid = calcValidLengthToAvoid(obj_path, obj_pose, obj_shape); + if (obj_vel < -0.5) { return MinMaxValue{ - std::max(obj_lon_offset.min_value - start_length_to_avoid, valid_start_length_to_avoid), + std::max(obj_lon_offset.min_value - start_length_to_avoid, -valid_length_to_avoid), obj_lon_offset.max_value + end_length_to_avoid}; } + if (0.5 < obj_vel) { + return MinMaxValue{ + obj_lon_offset.min_value - start_length_to_avoid, + std::min(obj_lon_offset.max_value + end_length_to_avoid, valid_length_to_avoid)}; + } return MinMaxValue{ obj_lon_offset.min_value - start_length_to_avoid, obj_lon_offset.max_value + end_length_to_avoid}; } -double DynamicAvoidanceModule::calcValidStartLengthToAvoid( +double DynamicAvoidanceModule::calcValidLengthToAvoid( const PredictedPath & obj_path, const geometry_msgs::msg::Pose & obj_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape) const { @@ -1006,7 +1010,7 @@ double DynamicAvoidanceModule::calcValidStartLengthToAvoid( } return obj_path.path.size() - 1; }(); - return -motion_utils::calcSignedArcLength(obj_path.path, 0, valid_obj_path_end_idx); + return motion_utils::calcSignedArcLength(obj_path.path, 0, valid_obj_path_end_idx); } std::optional DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( From a4ef3a0bf5d7be71dd0d35ed497a571f9cfe804f Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Wed, 20 Dec 2023 00:26:33 +0900 Subject: [PATCH 86/87] chore(crosswalk, obstacle_cruise): add maintainer (#5898) * add maintainer Signed-off-by: Yuki Takagi --- planning/behavior_velocity_crosswalk_module/package.xml | 2 ++ planning/obstacle_cruise_planner/package.xml | 1 + 2 files changed, 3 insertions(+) diff --git a/planning/behavior_velocity_crosswalk_module/package.xml b/planning/behavior_velocity_crosswalk_module/package.xml index 3830aa9edddff..9eef11e72239e 100644 --- a/planning/behavior_velocity_crosswalk_module/package.xml +++ b/planning/behavior_velocity_crosswalk_module/package.xml @@ -10,6 +10,8 @@ Shumpei Wakabayashi Takayuki Murooka Kyoichi Sugahara + Mamoru Sobue + Yuki Takagi Apache License 2.0 diff --git a/planning/obstacle_cruise_planner/package.xml b/planning/obstacle_cruise_planner/package.xml index e724ddb3e6bd7..f6263521bd337 100644 --- a/planning/obstacle_cruise_planner/package.xml +++ b/planning/obstacle_cruise_planner/package.xml @@ -7,6 +7,7 @@ Takayuki Murooka Kosuke Takeuchi Satoshi Ota + Yuki Takagi Apache License 2.0 From c9b9fca4567d7fc64590153ca02d8d7eb17ab824 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 20 Dec 2023 08:11:11 +0900 Subject: [PATCH 87/87] refactor(avoidance_by_lane_change): update execution condition (#5869) * refactor(avoidance_by_lane_change): update execution condition Signed-off-by: Muhammad Zulfaqar Azmi * fix lc parameter Signed-off-by: Muhammad Zulfaqar Azmi * fix both lane change and avoidance by lane change both are running Signed-off-by: Zulfaqar Azmi * trying to set maximum_avoid_distance Signed-off-by: Muhammad Zulfaqar Azmi * fix avoidance param not properly assigned Signed-off-by: Zulfaqar Azmi * fixed avoidance not running Signed-off-by: Zulfaqar Azmi * fix root lanelet Signed-off-by: Zulfaqar Azmi * removed gdb Signed-off-by: Zulfaqar Azmi * add debug Signed-off-by: Zulfaqar Azmi * fix unnecessary changes Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Zulfaqar Azmi Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --- .../config/avoidance_by_lc.param.yaml | 8 + .../data_structs.hpp | 6 +- .../interface.hpp | 2 + .../scene.hpp | 3 + .../src/interface.cpp | 6 +- .../src/manager.cpp | 18 +- .../src/scene.cpp | 79 ++-- .../parameter_helper.hpp | 364 ++++++++++++++++++ .../src/manager.cpp | 328 +--------------- .../src/utils/utils.cpp | 8 +- .../src/planner_manager.cpp | 16 +- 11 files changed, 471 insertions(+), 367 deletions(-) create mode 100644 planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp diff --git a/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lc.param.yaml b/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lc.param.yaml index 9518185d30d63..3e8907cdccdf6 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lc.param.yaml +++ b/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lc.param.yaml @@ -85,3 +85,11 @@ bicycle: false # [-] motorcycle: false # [-] pedestrian: false # [-] + + constraints: + # lateral constraints + lateral: + velocity: [1.0, 1.38, 11.1] # [m/s] + max_accel_values: [0.5, 0.5, 0.5] # [m/ss] + min_jerk_values: [0.2, 0.2, 0.2] # [m/sss] + max_jerk_values: [1.0, 1.0, 1.0] # [m/sss] diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp index e177244930da6..8e7d1f67d3157 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp @@ -16,8 +16,6 @@ #include "behavior_path_avoidance_module/data_structs.hpp" -#include - namespace behavior_path_planner { struct AvoidanceByLCParameters : public AvoidanceParameters @@ -27,6 +25,10 @@ struct AvoidanceByLCParameters : public AvoidanceParameters // execute only when lane change end point is before the object. bool execute_only_when_lane_change_finish_before_object{false}; + + explicit AvoidanceByLCParameters(const AvoidanceParameters & param) : AvoidanceParameters(param) + { + } }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp index 016a6b2977701..897956a392008 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp @@ -40,6 +40,8 @@ class AvoidanceByLaneChangeInterface : public LaneChangeInterface bool isExecutionRequested() const override; + void processOnEntry() override; + protected: void updateRTCStatus(const double start_distance, const double finish_distance) override; }; 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 f22291c99b8e7..7a82ba60a1eaa 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 @@ -16,6 +16,7 @@ #define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_ #include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" +#include "behavior_path_avoidance_module/helper.hpp" #include "behavior_path_lane_change_module/scene.hpp" #include @@ -23,6 +24,7 @@ namespace behavior_path_planner { using AvoidanceDebugData = DebugData; +using helper::avoidance::AvoidanceHelper; class AvoidanceByLaneChange : public NormalLaneChange { @@ -46,6 +48,7 @@ class AvoidanceByLaneChange : public NormalLaneChange ObjectDataArray registered_objects_; mutable ObjectDataArray stopped_objects_; + std::shared_ptr avoidance_helper_; ObjectData createObjectData( const AvoidancePlanningData & data, const PredictedObject & object) const; diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp index 2e451461abab7..efdb302a58ac2 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp @@ -45,7 +45,11 @@ AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface( bool AvoidanceByLaneChangeInterface::isExecutionRequested() const { - return module_type_->specialRequiredCheck() && module_type_->isLaneChangeRequired(); + return module_type_->isLaneChangeRequired() && module_type_->specialRequiredCheck(); +} +void AvoidanceByLaneChangeInterface::processOnEntry() +{ + waitApproval(); } void AvoidanceByLaneChangeInterface::updateRTCStatus( diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp index 61b0a36ae0fb0..3f810710ef37b 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp @@ -14,6 +14,8 @@ #include "behavior_path_avoidance_by_lane_change_module/manager.hpp" +#include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" +#include "behavior_path_avoidance_module/parameter_helper.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" @@ -37,7 +39,9 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) // init lane change manager LaneChangeModuleManager::init(node); - AvoidanceByLCParameters p{}; + const auto avoidance_params = getParameter(node); + AvoidanceByLCParameters p(avoidance_params); + // unique parameters { const std::string ns = "avoidance_by_lane_change."; @@ -139,6 +143,18 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.behind_distance"); } + // avoidance maneuver (longitudinal) + { + const std::string ns = "avoidance.avoidance.longitudinal."; + p.min_prepare_time = getOrDeclareParameter(*node, ns + "min_prepare_time"); + p.max_prepare_time = getOrDeclareParameter(*node, ns + "max_prepare_time"); + p.min_prepare_distance = getOrDeclareParameter(*node, ns + "min_prepare_distance"); + p.min_slow_down_speed = getOrDeclareParameter(*node, ns + "min_slow_down_speed"); + p.buf_slow_down_speed = getOrDeclareParameter(*node, ns + "buf_slow_down_speed"); + p.nominal_avoidance_speed = + getOrDeclareParameter(*node, ns + "nominal_avoidance_speed"); + } + { const std::string ns = "avoidance.target_filtering.detection_area."; p.use_static_detection_area = getOrDeclareParameter(*node, ns + "static"); 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 0299e839996b0..619cbc515f816 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 @@ -20,6 +20,8 @@ #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" +#include + #include #include @@ -41,7 +43,8 @@ AvoidanceByLaneChange::AvoidanceByLaneChange( const std::shared_ptr & parameters, std::shared_ptr avoidance_parameters) : NormalLaneChange(parameters, LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE, Direction::NONE), - avoidance_parameters_(std::move(avoidance_parameters)) + avoidance_parameters_(std::move(avoidance_parameters)), + avoidance_helper_{std::make_shared(avoidance_parameters_)} { } @@ -49,48 +52,66 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const { const auto & data = avoidance_data_; - if (!status_.is_safe) { + if (data.target_objects.empty()) { return false; } const auto & object_parameters = avoidance_parameters_->object_parameters; - const auto is_more_than_threshold = - std::any_of(object_parameters.begin(), object_parameters.end(), [&](const auto & p) { - const auto & objects = avoidance_data_.target_objects; - - const size_t num = std::count_if(objects.begin(), objects.end(), [&p](const auto & object) { - const auto target_class = - utils::getHighestProbLabel(object.object.classification) == p.first; - return target_class && object.avoid_required; - }); - return num >= p.second.execute_num; - }); + const auto count_target_object = [&](const auto sum, const auto & p) { + const auto & objects = avoidance_data_.target_objects; - if (!is_more_than_threshold) { - return false; - } + const auto is_avoidance_target = [&p](const auto & object) { + const auto target_class = utils::getHighestProbLabel(object.object.classification) == p.first; + return target_class && object.avoid_required; + }; - const auto & front_object = data.target_objects.front(); + return sum + std::count_if(objects.begin(), objects.end(), is_avoidance_target); + }; + const auto num_of_avoidance_targets = + std::accumulate(object_parameters.begin(), object_parameters.end(), 0UL, count_target_object); - const auto THRESHOLD = avoidance_parameters_->execute_object_longitudinal_margin; - if (front_object.longitudinal < THRESHOLD) { + if (num_of_avoidance_targets < 1) { return false; } - const auto path = status_.lane_change_path.path; - const auto to_lc_end = motion_utils::calcSignedArcLength( - status_.lane_change_path.path.points, getEgoPose().position, - status_.lane_change_path.info.shift_line.end.position); - const auto execute_only_when_lane_change_finish_before_object = - avoidance_parameters_->execute_only_when_lane_change_finish_before_object; - const auto not_enough_distance = front_object.longitudinal < to_lc_end; - - if (execute_only_when_lane_change_finish_before_object && not_enough_distance) { + const auto current_lanes = getCurrentLanes(); + if (current_lanes.empty()) { return false; } - return true; + const auto & nearest_object = data.target_objects.front(); + + // get minimum lane change distance + const auto shift_intervals = + getRouteHandler()->getLateralIntervalsToPreferredLane(current_lanes.back(), direction_); + const double minimum_lane_change_length = utils::lane_change::calcMinimumLaneChangeLength( + *lane_change_parameters_, shift_intervals, + lane_change_parameters_->backward_length_buffer_for_end_of_lane); + + // get minimum avoid distance + + const auto ego_width = getCommonParam().vehicle_width; + const auto nearest_object_type = utils::getHighestProbLabel(nearest_object.object.classification); + const auto nearest_object_parameter = + avoidance_parameters_->object_parameters.at(nearest_object_type); + const auto avoid_margin = + nearest_object_parameter.safety_buffer_lateral * nearest_object.distance_factor + + nearest_object_parameter.avoid_margin_lateral + 0.5 * ego_width; + + avoidance_helper_->setData(planner_data_); + const auto shift_length = avoidance_helper_->getShiftLength( + nearest_object, utils::avoidance::isOnRight(nearest_object), avoid_margin); + + const auto maximum_avoid_distance = avoidance_helper_->getMaxAvoidanceDistance(shift_length); + + RCLCPP_DEBUG( + logger_, + "nearest_object.longitudinal %.3f, minimum_lane_change_length %.3f, maximum_avoid_distance " + "%.3f", + nearest_object.longitudinal, minimum_lane_change_length, maximum_avoid_distance); + + return nearest_object.longitudinal > std::max(minimum_lane_change_length, maximum_avoid_distance); } bool AvoidanceByLaneChange::specialExpiredCheck() const diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp new file mode 100644 index 0000000000000..212ed04ade6c6 --- /dev/null +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp @@ -0,0 +1,364 @@ +// 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 BEHAVIOR_PATH_AVOIDANCE_MODULE__PARAMETER_HELPER_HPP_ +#define BEHAVIOR_PATH_AVOIDANCE_MODULE__PARAMETER_HELPER_HPP_ + +#include "tier4_autoware_utils/ros/parameter.hpp" + +#include +#include + +#include + +#include +#include + +namespace behavior_path_planner +{ +using autoware_auto_perception_msgs::msg::ObjectClassification; +using tier4_autoware_utils::getOrDeclareParameter; + +AvoidanceParameters getParameter(rclcpp::Node * node) +{ + AvoidanceParameters p{}; + // general params + { + const std::string ns = "avoidance."; + p.resample_interval_for_planning = + getOrDeclareParameter(*node, ns + "resample_interval_for_planning"); + p.resample_interval_for_output = + getOrDeclareParameter(*node, ns + "resample_interval_for_output"); + p.enable_bound_clipping = getOrDeclareParameter(*node, ns + "enable_bound_clipping"); + p.enable_cancel_maneuver = getOrDeclareParameter(*node, ns + "enable_cancel_maneuver"); + p.enable_yield_maneuver = getOrDeclareParameter(*node, ns + "enable_yield_maneuver"); + p.enable_yield_maneuver_during_shifting = + getOrDeclareParameter(*node, ns + "enable_yield_maneuver_during_shifting"); + p.disable_path_update = getOrDeclareParameter(*node, ns + "disable_path_update"); + p.publish_debug_marker = getOrDeclareParameter(*node, ns + "publish_debug_marker"); + p.print_debug_info = getOrDeclareParameter(*node, ns + "print_debug_info"); + } + + // drivable area + { + const std::string ns = "avoidance."; + p.use_adjacent_lane = getOrDeclareParameter(*node, ns + "use_adjacent_lane"); + p.use_opposite_lane = getOrDeclareParameter(*node, ns + "use_opposite_lane"); + p.use_intersection_areas = getOrDeclareParameter(*node, ns + "use_intersection_areas"); + p.use_hatched_road_markings = + getOrDeclareParameter(*node, ns + "use_hatched_road_markings"); + } + + // target object + { + const auto get_object_param = [&](std::string && ns) { + ObjectParameter param{}; + param.execute_num = getOrDeclareParameter(*node, ns + "execute_num"); + param.moving_speed_threshold = + getOrDeclareParameter(*node, ns + "moving_speed_threshold"); + param.moving_time_threshold = + getOrDeclareParameter(*node, ns + "moving_time_threshold"); + param.max_expand_ratio = getOrDeclareParameter(*node, ns + "max_expand_ratio"); + param.envelope_buffer_margin = + getOrDeclareParameter(*node, ns + "envelope_buffer_margin"); + param.avoid_margin_lateral = + getOrDeclareParameter(*node, ns + "avoid_margin_lateral"); + param.safety_buffer_lateral = + getOrDeclareParameter(*node, ns + "safety_buffer_lateral"); + param.safety_buffer_longitudinal = + getOrDeclareParameter(*node, ns + "safety_buffer_longitudinal"); + param.use_conservative_buffer_longitudinal = + getOrDeclareParameter(*node, ns + "use_conservative_buffer_longitudinal"); + return param; + }; + + const std::string ns = "avoidance.target_object."; + p.object_parameters.emplace( + ObjectClassification::MOTORCYCLE, get_object_param(ns + "motorcycle.")); + p.object_parameters.emplace(ObjectClassification::CAR, get_object_param(ns + "car.")); + p.object_parameters.emplace(ObjectClassification::TRUCK, get_object_param(ns + "truck.")); + p.object_parameters.emplace(ObjectClassification::TRAILER, get_object_param(ns + "trailer.")); + p.object_parameters.emplace(ObjectClassification::BUS, get_object_param(ns + "bus.")); + p.object_parameters.emplace( + ObjectClassification::PEDESTRIAN, get_object_param(ns + "pedestrian.")); + p.object_parameters.emplace(ObjectClassification::BICYCLE, get_object_param(ns + "bicycle.")); + p.object_parameters.emplace(ObjectClassification::UNKNOWN, get_object_param(ns + "unknown.")); + + p.lower_distance_for_polygon_expansion = + getOrDeclareParameter(*node, ns + "lower_distance_for_polygon_expansion"); + p.upper_distance_for_polygon_expansion = + getOrDeclareParameter(*node, ns + "upper_distance_for_polygon_expansion"); + } + + // target filtering + { + const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) { + if (p.object_parameters.count(object_type) == 0) { + return; + } + p.object_parameters.at(object_type).is_avoidance_target = + getOrDeclareParameter(*node, ns); + }; + + const std::string ns = "avoidance.target_filtering."; + set_target_flag(ObjectClassification::CAR, ns + "target_type.car"); + set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck"); + set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer"); + set_target_flag(ObjectClassification::BUS, ns + "target_type.bus"); + set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian"); + set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle"); + set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle"); + set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown"); + + p.object_check_goal_distance = + getOrDeclareParameter(*node, ns + "object_check_goal_distance"); + p.threshold_distance_object_is_on_center = + getOrDeclareParameter(*node, ns + "threshold_distance_object_is_on_center"); + p.object_check_shiftable_ratio = + getOrDeclareParameter(*node, ns + "object_check_shiftable_ratio"); + p.object_check_min_road_shoulder_width = + getOrDeclareParameter(*node, ns + "object_check_min_road_shoulder_width"); + p.object_check_yaw_deviation = + getOrDeclareParameter(*node, ns + "intersection.yaw_deviation"); + p.object_last_seen_threshold = + getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); + } + + { + const std::string ns = "avoidance.target_filtering.force_avoidance."; + p.enable_force_avoidance_for_stopped_vehicle = + getOrDeclareParameter(*node, ns + "enable"); + p.threshold_time_force_avoidance_for_stopped_vehicle = + getOrDeclareParameter(*node, ns + "time_threshold"); + p.object_ignore_section_traffic_light_in_front_distance = + getOrDeclareParameter(*node, ns + "ignore_area.traffic_light.front_distance"); + p.object_ignore_section_crosswalk_in_front_distance = + getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.front_distance"); + p.object_ignore_section_crosswalk_behind_distance = + getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.behind_distance"); + } + + { + const std::string ns = "avoidance.target_filtering.detection_area."; + p.use_static_detection_area = getOrDeclareParameter(*node, ns + "static"); + p.object_check_min_forward_distance = + getOrDeclareParameter(*node, ns + "min_forward_distance"); + p.object_check_max_forward_distance = + getOrDeclareParameter(*node, ns + "max_forward_distance"); + p.object_check_backward_distance = + getOrDeclareParameter(*node, ns + "backward_distance"); + } + + // safety check general params + { + const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) { + if (p.object_parameters.count(object_type) == 0) { + return; + } + p.object_parameters.at(object_type).is_safety_check_target = + getOrDeclareParameter(*node, ns); + }; + + const std::string ns = "avoidance.safety_check."; + set_target_flag(ObjectClassification::CAR, ns + "target_type.car"); + set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck"); + set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer"); + set_target_flag(ObjectClassification::BUS, ns + "target_type.bus"); + set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian"); + set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle"); + set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle"); + set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown"); + + p.enable_safety_check = getOrDeclareParameter(*node, ns + "enable"); + p.check_current_lane = getOrDeclareParameter(*node, ns + "check_current_lane"); + p.check_shift_side_lane = getOrDeclareParameter(*node, ns + "check_shift_side_lane"); + p.check_other_side_lane = getOrDeclareParameter(*node, ns + "check_other_side_lane"); + p.check_unavoidable_object = + getOrDeclareParameter(*node, ns + "check_unavoidable_object"); + p.check_other_object = getOrDeclareParameter(*node, ns + "check_other_object"); + p.check_all_predicted_path = + getOrDeclareParameter(*node, ns + "check_all_predicted_path"); + p.safety_check_backward_distance = + getOrDeclareParameter(*node, ns + "safety_check_backward_distance"); + p.hysteresis_factor_expand_rate = + getOrDeclareParameter(*node, ns + "hysteresis_factor_expand_rate"); + p.hysteresis_factor_safe_count = + getOrDeclareParameter(*node, ns + "hysteresis_factor_safe_count"); + } + + // safety check predicted path params + { + const std::string ns = "avoidance.safety_check."; + p.ego_predicted_path_params.min_velocity = + getOrDeclareParameter(*node, ns + "min_velocity"); + p.ego_predicted_path_params.max_velocity = + getOrDeclareParameter(*node, ns + "max_velocity"); + p.ego_predicted_path_params.acceleration = + getOrDeclareParameter(*node, "avoidance.constraints.longitudinal.max_acceleration"); + p.ego_predicted_path_params.time_horizon_for_rear_object = + getOrDeclareParameter(*node, ns + "time_horizon_for_rear_object"); + p.ego_predicted_path_params.time_resolution = + getOrDeclareParameter(*node, ns + "time_resolution"); + p.ego_predicted_path_params.delay_until_departure = + getOrDeclareParameter(*node, ns + "delay_until_departure"); + } + + // safety check rss params + { + const std::string ns = "avoidance.safety_check."; + p.rss_params.longitudinal_distance_min_threshold = + getOrDeclareParameter(*node, ns + "longitudinal_distance_min_threshold"); + p.rss_params.longitudinal_velocity_delta_time = + getOrDeclareParameter(*node, ns + "longitudinal_velocity_delta_time"); + p.rss_params.front_vehicle_deceleration = + getOrDeclareParameter(*node, ns + "expected_front_deceleration"); + p.rss_params.rear_vehicle_deceleration = + getOrDeclareParameter(*node, ns + "expected_rear_deceleration"); + p.rss_params.rear_vehicle_reaction_time = + getOrDeclareParameter(*node, ns + "rear_vehicle_reaction_time"); + p.rss_params.rear_vehicle_safety_time_margin = + getOrDeclareParameter(*node, ns + "rear_vehicle_safety_time_margin"); + p.rss_params.lateral_distance_max_threshold = + getOrDeclareParameter(*node, ns + "lateral_distance_max_threshold"); + } + + // avoidance maneuver (lateral) + { + const std::string ns = "avoidance.avoidance.lateral."; + p.soft_road_shoulder_margin = + getOrDeclareParameter(*node, ns + "soft_road_shoulder_margin"); + p.hard_road_shoulder_margin = + getOrDeclareParameter(*node, ns + "hard_road_shoulder_margin"); + p.lateral_execution_threshold = + getOrDeclareParameter(*node, ns + "lateral_execution_threshold"); + p.lateral_small_shift_threshold = + getOrDeclareParameter(*node, ns + "lateral_small_shift_threshold"); + p.lateral_avoid_check_threshold = + getOrDeclareParameter(*node, ns + "lateral_avoid_check_threshold"); + p.max_right_shift_length = getOrDeclareParameter(*node, ns + "max_right_shift_length"); + p.max_left_shift_length = getOrDeclareParameter(*node, ns + "max_left_shift_length"); + p.max_deviation_from_lane = + getOrDeclareParameter(*node, ns + "max_deviation_from_lane"); + } + + // avoidance maneuver (longitudinal) + { + const std::string ns = "avoidance.avoidance.longitudinal."; + p.min_prepare_time = getOrDeclareParameter(*node, ns + "min_prepare_time"); + p.max_prepare_time = getOrDeclareParameter(*node, ns + "max_prepare_time"); + p.min_prepare_distance = getOrDeclareParameter(*node, ns + "min_prepare_distance"); + p.min_slow_down_speed = getOrDeclareParameter(*node, ns + "min_slow_down_speed"); + p.buf_slow_down_speed = getOrDeclareParameter(*node, ns + "buf_slow_down_speed"); + p.nominal_avoidance_speed = + getOrDeclareParameter(*node, ns + "nominal_avoidance_speed"); + } + + // avoidance maneuver (return shift dead line) + { + const std::string ns = "avoidance.avoidance.return_dead_line."; + p.enable_dead_line_for_goal = getOrDeclareParameter(*node, ns + "goal.enable"); + p.enable_dead_line_for_traffic_light = + getOrDeclareParameter(*node, ns + "traffic_light.enable"); + p.dead_line_buffer_for_goal = getOrDeclareParameter(*node, ns + "goal.buffer"); + p.dead_line_buffer_for_traffic_light = + getOrDeclareParameter(*node, ns + "traffic_light.buffer"); + } + + // yield + { + const std::string ns = "avoidance.yield."; + p.yield_velocity = getOrDeclareParameter(*node, ns + "yield_velocity"); + } + + // stop + { + const std::string ns = "avoidance.stop."; + p.stop_max_distance = getOrDeclareParameter(*node, ns + "max_distance"); + p.stop_buffer = getOrDeclareParameter(*node, ns + "stop_buffer"); + } + + // policy + { + const std::string ns = "avoidance.policy."; + p.policy_approval = getOrDeclareParameter(*node, ns + "make_approval_request"); + p.policy_deceleration = getOrDeclareParameter(*node, ns + "deceleration"); + p.policy_lateral_margin = getOrDeclareParameter(*node, ns + "lateral_margin"); + p.use_shorten_margin_immediately = + getOrDeclareParameter(*node, ns + "use_shorten_margin_immediately"); + + if (p.policy_deceleration != "best_effort" && p.policy_deceleration != "reliable") { + throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); + } + + if (p.policy_lateral_margin != "best_effort" && p.policy_lateral_margin != "reliable") { + throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); + } + } + + // constraints (longitudinal) + { + const std::string ns = "avoidance.constraints.longitudinal."; + p.nominal_deceleration = getOrDeclareParameter(*node, ns + "nominal_deceleration"); + p.nominal_jerk = getOrDeclareParameter(*node, ns + "nominal_jerk"); + p.max_deceleration = getOrDeclareParameter(*node, ns + "max_deceleration"); + p.max_jerk = getOrDeclareParameter(*node, ns + "max_jerk"); + p.max_acceleration = getOrDeclareParameter(*node, ns + "max_acceleration"); + } + + // constraints (lateral) + { + const std::string ns = "avoidance.constraints.lateral."; + p.velocity_map = getOrDeclareParameter>(*node, ns + "velocity"); + p.lateral_max_accel_map = + getOrDeclareParameter>(*node, ns + "max_accel_values"); + p.lateral_min_jerk_map = + getOrDeclareParameter>(*node, ns + "min_jerk_values"); + p.lateral_max_jerk_map = + getOrDeclareParameter>(*node, ns + "max_jerk_values"); + + if (p.velocity_map.empty()) { + throw std::domain_error("invalid velocity map."); + } + + if (p.velocity_map.size() != p.lateral_max_accel_map.size()) { + throw std::domain_error("inconsistency among the constraints map."); + } + + if (p.velocity_map.size() != p.lateral_min_jerk_map.size()) { + throw std::domain_error("inconsistency among the constraints map."); + } + + if (p.velocity_map.size() != p.lateral_max_jerk_map.size()) { + throw std::domain_error("inconsistency among the constraints map."); + } + } + + // shift line pipeline + { + const std::string ns = "avoidance.shift_line_pipeline."; + p.quantize_filter_threshold = + getOrDeclareParameter(*node, ns + "trim.quantize_filter_threshold"); + p.same_grad_filter_1_threshold = + getOrDeclareParameter(*node, ns + "trim.same_grad_filter_1_threshold"); + p.same_grad_filter_2_threshold = + getOrDeclareParameter(*node, ns + "trim.same_grad_filter_2_threshold"); + p.same_grad_filter_3_threshold = + getOrDeclareParameter(*node, ns + "trim.same_grad_filter_3_threshold"); + p.sharp_shift_filter_threshold = + getOrDeclareParameter(*node, ns + "trim.sharp_shift_filter_threshold"); + } + return p; +} +} // namespace behavior_path_planner + +#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__PARAMETER_HELPER_HPP_ diff --git a/planning/behavior_path_avoidance_module/src/manager.cpp b/planning/behavior_path_avoidance_module/src/manager.cpp index f4997d2af12f1..68cee1aa2b523 100644 --- a/planning/behavior_path_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_module/src/manager.cpp @@ -14,6 +14,7 @@ #include "behavior_path_avoidance_module/manager.hpp" +#include "behavior_path_avoidance_module/parameter_helper.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" @@ -33,332 +34,7 @@ void AvoidanceModuleManager::init(rclcpp::Node * node) // init manager interface initInterface(node, {"left", "right"}); - AvoidanceParameters p{}; - // general params - { - const std::string ns = "avoidance."; - p.resample_interval_for_planning = - getOrDeclareParameter(*node, ns + "resample_interval_for_planning"); - p.resample_interval_for_output = - getOrDeclareParameter(*node, ns + "resample_interval_for_output"); - p.enable_bound_clipping = getOrDeclareParameter(*node, ns + "enable_bound_clipping"); - p.enable_cancel_maneuver = getOrDeclareParameter(*node, ns + "enable_cancel_maneuver"); - p.enable_yield_maneuver = getOrDeclareParameter(*node, ns + "enable_yield_maneuver"); - p.enable_yield_maneuver_during_shifting = - getOrDeclareParameter(*node, ns + "enable_yield_maneuver_during_shifting"); - p.disable_path_update = getOrDeclareParameter(*node, ns + "disable_path_update"); - p.publish_debug_marker = getOrDeclareParameter(*node, ns + "publish_debug_marker"); - p.print_debug_info = getOrDeclareParameter(*node, ns + "print_debug_info"); - } - - // drivable area - { - const std::string ns = "avoidance."; - p.use_adjacent_lane = getOrDeclareParameter(*node, ns + "use_adjacent_lane"); - p.use_opposite_lane = getOrDeclareParameter(*node, ns + "use_opposite_lane"); - p.use_intersection_areas = getOrDeclareParameter(*node, ns + "use_intersection_areas"); - p.use_hatched_road_markings = - getOrDeclareParameter(*node, ns + "use_hatched_road_markings"); - } - - // target object - { - const auto get_object_param = [&](std::string && ns) { - ObjectParameter param{}; - param.execute_num = getOrDeclareParameter(*node, ns + "execute_num"); - param.moving_speed_threshold = - getOrDeclareParameter(*node, ns + "moving_speed_threshold"); - param.moving_time_threshold = - getOrDeclareParameter(*node, ns + "moving_time_threshold"); - param.max_expand_ratio = getOrDeclareParameter(*node, ns + "max_expand_ratio"); - param.envelope_buffer_margin = - getOrDeclareParameter(*node, ns + "envelope_buffer_margin"); - param.avoid_margin_lateral = - getOrDeclareParameter(*node, ns + "avoid_margin_lateral"); - param.safety_buffer_lateral = - getOrDeclareParameter(*node, ns + "safety_buffer_lateral"); - param.safety_buffer_longitudinal = - getOrDeclareParameter(*node, ns + "safety_buffer_longitudinal"); - param.use_conservative_buffer_longitudinal = - getOrDeclareParameter(*node, ns + "use_conservative_buffer_longitudinal"); - return param; - }; - - const std::string ns = "avoidance.target_object."; - p.object_parameters.emplace( - ObjectClassification::MOTORCYCLE, get_object_param(ns + "motorcycle.")); - p.object_parameters.emplace(ObjectClassification::CAR, get_object_param(ns + "car.")); - p.object_parameters.emplace(ObjectClassification::TRUCK, get_object_param(ns + "truck.")); - p.object_parameters.emplace(ObjectClassification::TRAILER, get_object_param(ns + "trailer.")); - p.object_parameters.emplace(ObjectClassification::BUS, get_object_param(ns + "bus.")); - p.object_parameters.emplace( - ObjectClassification::PEDESTRIAN, get_object_param(ns + "pedestrian.")); - p.object_parameters.emplace(ObjectClassification::BICYCLE, get_object_param(ns + "bicycle.")); - p.object_parameters.emplace(ObjectClassification::UNKNOWN, get_object_param(ns + "unknown.")); - - p.lower_distance_for_polygon_expansion = - getOrDeclareParameter(*node, ns + "lower_distance_for_polygon_expansion"); - p.upper_distance_for_polygon_expansion = - getOrDeclareParameter(*node, ns + "upper_distance_for_polygon_expansion"); - } - - // target filtering - { - const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) { - if (p.object_parameters.count(object_type) == 0) { - return; - } - p.object_parameters.at(object_type).is_avoidance_target = - getOrDeclareParameter(*node, ns); - }; - - const std::string ns = "avoidance.target_filtering."; - set_target_flag(ObjectClassification::CAR, ns + "target_type.car"); - set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck"); - set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer"); - set_target_flag(ObjectClassification::BUS, ns + "target_type.bus"); - set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian"); - set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle"); - set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle"); - set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown"); - - p.object_check_goal_distance = - getOrDeclareParameter(*node, ns + "object_check_goal_distance"); - p.threshold_distance_object_is_on_center = - getOrDeclareParameter(*node, ns + "threshold_distance_object_is_on_center"); - p.object_check_shiftable_ratio = - getOrDeclareParameter(*node, ns + "object_check_shiftable_ratio"); - p.object_check_min_road_shoulder_width = - getOrDeclareParameter(*node, ns + "object_check_min_road_shoulder_width"); - p.object_check_yaw_deviation = - getOrDeclareParameter(*node, ns + "intersection.yaw_deviation"); - p.object_last_seen_threshold = - getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); - } - - { - const std::string ns = "avoidance.target_filtering.force_avoidance."; - p.enable_force_avoidance_for_stopped_vehicle = - getOrDeclareParameter(*node, ns + "enable"); - p.threshold_time_force_avoidance_for_stopped_vehicle = - getOrDeclareParameter(*node, ns + "time_threshold"); - p.object_ignore_section_traffic_light_in_front_distance = - getOrDeclareParameter(*node, ns + "ignore_area.traffic_light.front_distance"); - p.object_ignore_section_crosswalk_in_front_distance = - getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.front_distance"); - p.object_ignore_section_crosswalk_behind_distance = - getOrDeclareParameter(*node, ns + "ignore_area.crosswalk.behind_distance"); - } - - { - const std::string ns = "avoidance.target_filtering.detection_area."; - p.use_static_detection_area = getOrDeclareParameter(*node, ns + "static"); - p.object_check_min_forward_distance = - getOrDeclareParameter(*node, ns + "min_forward_distance"); - p.object_check_max_forward_distance = - getOrDeclareParameter(*node, ns + "max_forward_distance"); - p.object_check_backward_distance = - getOrDeclareParameter(*node, ns + "backward_distance"); - } - - // safety check general params - { - const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) { - if (p.object_parameters.count(object_type) == 0) { - return; - } - p.object_parameters.at(object_type).is_safety_check_target = - getOrDeclareParameter(*node, ns); - }; - - const std::string ns = "avoidance.safety_check."; - set_target_flag(ObjectClassification::CAR, ns + "target_type.car"); - set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck"); - set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer"); - set_target_flag(ObjectClassification::BUS, ns + "target_type.bus"); - set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian"); - set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle"); - set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle"); - set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown"); - - p.enable_safety_check = getOrDeclareParameter(*node, ns + "enable"); - p.check_current_lane = getOrDeclareParameter(*node, ns + "check_current_lane"); - p.check_shift_side_lane = getOrDeclareParameter(*node, ns + "check_shift_side_lane"); - p.check_other_side_lane = getOrDeclareParameter(*node, ns + "check_other_side_lane"); - p.check_unavoidable_object = - getOrDeclareParameter(*node, ns + "check_unavoidable_object"); - p.check_other_object = getOrDeclareParameter(*node, ns + "check_other_object"); - p.check_all_predicted_path = - getOrDeclareParameter(*node, ns + "check_all_predicted_path"); - p.safety_check_backward_distance = - getOrDeclareParameter(*node, ns + "safety_check_backward_distance"); - p.hysteresis_factor_expand_rate = - getOrDeclareParameter(*node, ns + "hysteresis_factor_expand_rate"); - p.hysteresis_factor_safe_count = - getOrDeclareParameter(*node, ns + "hysteresis_factor_safe_count"); - } - - // safety check predicted path params - { - const std::string ns = "avoidance.safety_check."; - p.ego_predicted_path_params.min_velocity = - getOrDeclareParameter(*node, ns + "min_velocity"); - p.ego_predicted_path_params.max_velocity = - getOrDeclareParameter(*node, ns + "max_velocity"); - p.ego_predicted_path_params.acceleration = - getOrDeclareParameter(*node, "avoidance.constraints.longitudinal.max_acceleration"); - p.ego_predicted_path_params.time_horizon_for_rear_object = - getOrDeclareParameter(*node, ns + "time_horizon_for_rear_object"); - p.ego_predicted_path_params.time_resolution = - getOrDeclareParameter(*node, ns + "time_resolution"); - p.ego_predicted_path_params.delay_until_departure = - getOrDeclareParameter(*node, ns + "delay_until_departure"); - } - - // safety check rss params - { - const std::string ns = "avoidance.safety_check."; - p.rss_params.longitudinal_distance_min_threshold = - getOrDeclareParameter(*node, ns + "longitudinal_distance_min_threshold"); - p.rss_params.longitudinal_velocity_delta_time = - getOrDeclareParameter(*node, ns + "longitudinal_velocity_delta_time"); - p.rss_params.front_vehicle_deceleration = - getOrDeclareParameter(*node, ns + "expected_front_deceleration"); - p.rss_params.rear_vehicle_deceleration = - getOrDeclareParameter(*node, ns + "expected_rear_deceleration"); - p.rss_params.rear_vehicle_reaction_time = - getOrDeclareParameter(*node, ns + "rear_vehicle_reaction_time"); - p.rss_params.rear_vehicle_safety_time_margin = - getOrDeclareParameter(*node, ns + "rear_vehicle_safety_time_margin"); - p.rss_params.lateral_distance_max_threshold = - getOrDeclareParameter(*node, ns + "lateral_distance_max_threshold"); - } - - // avoidance maneuver (lateral) - { - const std::string ns = "avoidance.avoidance.lateral."; - p.soft_road_shoulder_margin = - getOrDeclareParameter(*node, ns + "soft_road_shoulder_margin"); - p.hard_road_shoulder_margin = - getOrDeclareParameter(*node, ns + "hard_road_shoulder_margin"); - p.lateral_execution_threshold = - getOrDeclareParameter(*node, ns + "lateral_execution_threshold"); - p.lateral_small_shift_threshold = - getOrDeclareParameter(*node, ns + "lateral_small_shift_threshold"); - p.lateral_avoid_check_threshold = - getOrDeclareParameter(*node, ns + "lateral_avoid_check_threshold"); - p.max_right_shift_length = getOrDeclareParameter(*node, ns + "max_right_shift_length"); - p.max_left_shift_length = getOrDeclareParameter(*node, ns + "max_left_shift_length"); - p.max_deviation_from_lane = - getOrDeclareParameter(*node, ns + "max_deviation_from_lane"); - } - - // avoidance maneuver (longitudinal) - { - const std::string ns = "avoidance.avoidance.longitudinal."; - p.min_prepare_time = getOrDeclareParameter(*node, ns + "min_prepare_time"); - p.max_prepare_time = getOrDeclareParameter(*node, ns + "max_prepare_time"); - p.min_prepare_distance = getOrDeclareParameter(*node, ns + "min_prepare_distance"); - p.min_slow_down_speed = getOrDeclareParameter(*node, ns + "min_slow_down_speed"); - p.buf_slow_down_speed = getOrDeclareParameter(*node, ns + "buf_slow_down_speed"); - p.nominal_avoidance_speed = - getOrDeclareParameter(*node, ns + "nominal_avoidance_speed"); - } - - // avoidance maneuver (return shift dead line) - { - const std::string ns = "avoidance.avoidance.return_dead_line."; - p.enable_dead_line_for_goal = getOrDeclareParameter(*node, ns + "goal.enable"); - p.enable_dead_line_for_traffic_light = - getOrDeclareParameter(*node, ns + "traffic_light.enable"); - p.dead_line_buffer_for_goal = getOrDeclareParameter(*node, ns + "goal.buffer"); - p.dead_line_buffer_for_traffic_light = - getOrDeclareParameter(*node, ns + "traffic_light.buffer"); - } - - // yield - { - const std::string ns = "avoidance.yield."; - p.yield_velocity = getOrDeclareParameter(*node, ns + "yield_velocity"); - } - - // stop - { - const std::string ns = "avoidance.stop."; - p.stop_max_distance = getOrDeclareParameter(*node, ns + "max_distance"); - p.stop_buffer = getOrDeclareParameter(*node, ns + "stop_buffer"); - } - - // policy - { - const std::string ns = "avoidance.policy."; - p.policy_approval = getOrDeclareParameter(*node, ns + "make_approval_request"); - p.policy_deceleration = getOrDeclareParameter(*node, ns + "deceleration"); - p.policy_lateral_margin = getOrDeclareParameter(*node, ns + "lateral_margin"); - p.use_shorten_margin_immediately = - getOrDeclareParameter(*node, ns + "use_shorten_margin_immediately"); - - if (p.policy_deceleration != "best_effort" && p.policy_deceleration != "reliable") { - throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); - } - - if (p.policy_lateral_margin != "best_effort" && p.policy_lateral_margin != "reliable") { - throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); - } - } - - // constraints (longitudinal) - { - const std::string ns = "avoidance.constraints.longitudinal."; - p.nominal_deceleration = getOrDeclareParameter(*node, ns + "nominal_deceleration"); - p.nominal_jerk = getOrDeclareParameter(*node, ns + "nominal_jerk"); - p.max_deceleration = getOrDeclareParameter(*node, ns + "max_deceleration"); - p.max_jerk = getOrDeclareParameter(*node, ns + "max_jerk"); - p.max_acceleration = getOrDeclareParameter(*node, ns + "max_acceleration"); - } - - // constraints (lateral) - { - const std::string ns = "avoidance.constraints.lateral."; - p.velocity_map = getOrDeclareParameter>(*node, ns + "velocity"); - p.lateral_max_accel_map = - getOrDeclareParameter>(*node, ns + "max_accel_values"); - p.lateral_min_jerk_map = - getOrDeclareParameter>(*node, ns + "min_jerk_values"); - p.lateral_max_jerk_map = - getOrDeclareParameter>(*node, ns + "max_jerk_values"); - - if (p.velocity_map.empty()) { - throw std::domain_error("invalid velocity map."); - } - - if (p.velocity_map.size() != p.lateral_max_accel_map.size()) { - throw std::domain_error("inconsistency among the constraints map."); - } - - if (p.velocity_map.size() != p.lateral_min_jerk_map.size()) { - throw std::domain_error("inconsistency among the constraints map."); - } - - if (p.velocity_map.size() != p.lateral_max_jerk_map.size()) { - throw std::domain_error("inconsistency among the constraints map."); - } - } - - // shift line pipeline - { - const std::string ns = "avoidance.shift_line_pipeline."; - p.quantize_filter_threshold = - getOrDeclareParameter(*node, ns + "trim.quantize_filter_threshold"); - p.same_grad_filter_1_threshold = - getOrDeclareParameter(*node, ns + "trim.same_grad_filter_1_threshold"); - p.same_grad_filter_2_threshold = - getOrDeclareParameter(*node, ns + "trim.same_grad_filter_2_threshold"); - p.same_grad_filter_3_threshold = - getOrDeclareParameter(*node, ns + "trim.same_grad_filter_3_threshold"); - p.sharp_shift_filter_threshold = - getOrDeclareParameter(*node, ns + "trim.sharp_shift_filter_threshold"); - } + auto p = getParameter(node); parameters_ = std::make_shared(p); } 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 9ff4ed95e09dd..df73990b770a3 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -244,7 +244,9 @@ lanelet::ConstLanelets getTargetNeighborLanes( for (const auto & current_lane : current_lanes) { if (route_handler.getNumLaneToPreferredLane(current_lane) != 0) { - if (type == LaneChangeModuleType::NORMAL) { + if ( + type == LaneChangeModuleType::NORMAL || + type == LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE) { neighbor_lanes.push_back(current_lane); } } else { @@ -782,7 +784,9 @@ std::optional getLaneChangeTargetLane( const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, const LaneChangeModuleType type, const Direction & direction) { - if (type == LaneChangeModuleType::NORMAL) { + if ( + type == LaneChangeModuleType::NORMAL || + type == LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE) { return route_handler.getLaneChangeTarget(current_lanes, direction); } diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 36d5c7773fd24..e4bfff8fc63b8 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -751,9 +751,11 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptrname().find("lane_change") != std::string::npos; }); + const auto success_lane_change = + std::any_of(itr, approved_module_ptrs_.end(), [](const auto & m) { + return m->name().find("lane_change") != std::string::npos || + m->name().find("avoidance_by_lc") != std::string::npos; + }); if (success_lane_change) { root_lanelet_ = updateRootLanelet(data); @@ -837,9 +839,11 @@ void PlannerManager::resetRootLanelet(const std::shared_ptr & data) // when lane change module is running, don't update root lanelet. const bool is_lane_change_running = std::invoke([&]() { - const auto lane_change_itr = std::find_if( - approved_module_ptrs_.begin(), approved_module_ptrs_.end(), - [](const auto & m) { return m->name().find("lane_change") != std::string::npos; }); + const auto lane_change_itr = + std::find_if(approved_module_ptrs_.begin(), approved_module_ptrs_.end(), [](const auto & m) { + return m->name().find("lane_change") != std::string::npos || + m->name().find("avoidance_by_lc") != std::string::npos; + }); return lane_change_itr != approved_module_ptrs_.end(); }); if (is_lane_change_running) {