From c9c58f8d58a3e67e9df8a6b181f9b6ceb46dabe6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 18 Jun 2024 12:27:27 +0300 Subject: [PATCH 001/217] ci(build-and-test): limit ccache size (#7555) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .github/workflows/build-and-test.yaml | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 00860986824e6..0c56d12800888 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -56,6 +56,12 @@ jobs: restore-keys: | ccache-main-${{ runner.arch }}-${{ matrix.rosdistro }}- + - name: Limit ccache size + run: | + rm -f "${CCACHE_DIR}/ccache.conf" + echo -e "# Set maximum cache size\nmax_size = 600MB" >> "${CCACHE_DIR}/ccache.conf" + shell: bash + - name: Show ccache stats before build run: du -sh ${CCACHE_DIR} && ccache -s shell: bash From 4094bbf96c9a873e1a3615594026811440c9f231 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Tue, 18 Jun 2024 19:41:15 +0900 Subject: [PATCH 002/217] fix(system_diagnostic_monitor): fix local mode config (#7532) Signed-off-by: Takagi, Isamu --- .../config/control.yaml | 17 ++++++----------- 1 file changed, 6 insertions(+), 11 deletions(-) diff --git a/system/system_diagnostic_monitor/config/control.yaml b/system/system_diagnostic_monitor/config/control.yaml index 57bf1b86c2bfc..5551ed4575929 100644 --- a/system/system_diagnostic_monitor/config/control.yaml +++ b/system/system_diagnostic_monitor/config/control.yaml @@ -13,14 +13,14 @@ units: - path: /autoware/control/local type: and list: - - { type: link, link: /autoware/control/topic_rate_check/selector } - - { type: link, link: /autoware/control/topic_rate_check/local } + - { type: link, link: /autoware/control/topic_rate_check/external_cmd_selector } + - { type: link, link: /autoware/control/topic_rate_check/external_cmd_converter } - path: /autoware/control/remote type: and list: - - { type: link, link: /autoware/control/topic_rate_check/selector } - - { type: link, link: /autoware/control/topic_rate_check/remote } + - { type: link, link: /autoware/control/topic_rate_check/external_cmd_selector } + - { type: link, link: /autoware/control/topic_rate_check/external_cmd_converter } - path: /autoware/control/topic_rate_check/trajectory_follower type: diag @@ -57,17 +57,12 @@ units: node: controller_node_exe name: control_state - - path: /autoware/control/topic_rate_check/selector + - path: /autoware/control/topic_rate_check/external_cmd_selector type: diag node: external_cmd_selector name: heartbeat - - path: /autoware/control/topic_rate_check/local - type: diag - node: joy_controller - name: joy_controller_connection - - - path: /autoware/control/topic_rate_check/remote + - path: /autoware/control/topic_rate_check/external_cmd_converter type: diag node: external_cmd_converter name: remote_control_topic_status From f4b14da7f5add9bc4b4b7e32d187d334056f2df3 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 18 Jun 2024 20:51:15 +0900 Subject: [PATCH 003/217] fix(autoware_behavior_velocity_occlusion_spot_module): fix redundantAssignment bug (#7559) Signed-off-by: Ryuta Kambe --- .../test/src/utils.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/utils.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/utils.hpp index 4b8a7ae3b2f3f..39a887ab16476 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/utils.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/utils.hpp @@ -86,7 +86,7 @@ inline void generatePossibleCollisions( // intersection geometry_msgs::msg::Pose intersection_pose{}; intersection_pose.position.x = x0 + x_step * i + lon; - intersection_pose.position.x = y0 + y_step * i; + intersection_pose.position.y = y0 + y_step * i; // collision path point autoware_planning_msgs::msg::PathPoint collision_with_margin{}; From 749332206050ad1fb2a952c9d44ce44baa7a65dc Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 18 Jun 2024 21:01:35 +0900 Subject: [PATCH 004/217] fix(behavior_path_planner): fix redundantAssignment warning (#7560) Signed-off-by: Ryuta Kambe --- .../test/test_turn_signal.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_turn_signal.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_turn_signal.cpp index 342ebc985a518..1f5ec84a17331 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_turn_signal.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_turn_signal.cpp @@ -355,7 +355,6 @@ TEST(BehaviorPathPlanningTurnSignal, Condition3) TurnSignalInfo behavior_signal_info; behavior_signal_info.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT; - behavior_signal_info.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT; behavior_signal_info.desired_start_point.position = createPoint(5.0, 0.0, 0.0); behavior_signal_info.desired_start_point.orientation = createQuaternionFromYaw(0.0); behavior_signal_info.desired_end_point.position = createPoint(70.0, 0.0, 0.0); From 525badbb98ac5b9363debf73a759f2d9b21159f9 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 19 Jun 2024 09:22:30 +0900 Subject: [PATCH 005/217] fix(tvm_utility): fix selfAssignment warnings (#7561) Signed-off-by: Ryuta Kambe --- common/tvm_utility/example/yolo_v2_tiny/main.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/common/tvm_utility/example/yolo_v2_tiny/main.cpp b/common/tvm_utility/example/yolo_v2_tiny/main.cpp index 8fd0cde3c306d..38b3355ca38ba 100644 --- a/common/tvm_utility/example/yolo_v2_tiny/main.cpp +++ b/common/tvm_utility/example/yolo_v2_tiny/main.cpp @@ -120,7 +120,6 @@ class PostProcessorYoloV2Tiny : public tvm_utility::pipeline::PostProcessor Date: Wed, 19 Jun 2024 09:25:36 +0900 Subject: [PATCH 006/217] refactor(yabloc_particle_filter): apply static analysis (#7519) * removed unused Signed-off-by: a-maumau * style(pre-commit): autofix * removed unused Signed-off-by: a-maumau * Update localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_core.cpp change to use get_mean_pose directly Co-authored-by: Kento Yabuuchi Signed-off-by: a-maumau * apply suggestion Signed-off-by: a-maumau --------- Signed-off-by: a-maumau Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kento Yabuuchi --- .../camera_particle_corrector.hpp | 2 +- .../camera_corrector/logit.hpp | 9 --- .../yabloc_particle_filter/common/mean.hpp | 9 +-- .../common/prediction_util.hpp | 15 ++-- .../common/visualize.hpp | 8 +- .../correction/abstract_corrector.hpp | 7 +- .../correction/correction_util.hpp | 35 --------- .../gnss_corrector/weight_manager.hpp | 42 ++++++----- .../ll2_cost_map/direct_cost_map.hpp | 3 - .../ll2_cost_map/hierarchical_cost_map.hpp | 29 +++---- .../prediction/predictor.hpp | 2 +- .../prediction/resampler.hpp | 9 ++- .../prediction/resampling_history.hpp | 2 +- .../camera_particle_corrector_core.cpp | 39 +++++----- .../camera_corrector/filter_line_segments.cpp | 30 ++++---- .../src/camera_corrector/logit.cpp | 9 +-- .../src/common/mean.cpp | 34 +++------ .../src/common/particle_visualize_node.cpp | 30 +------- .../src/common/visualize.cpp | 4 +- .../src/correction/abstract_corrector.cpp | 2 +- .../src/correction/correction_util.cpp | 38 ---------- .../gnss_corrector/gnss_corrector_core.cpp | 23 +++--- .../src/ll2_cost_map/direct_cost_map.cpp | 28 ++----- .../ll2_cost_map/hierarchical_cost_map.cpp | 75 +++++++++++-------- .../src/prediction/predictor.cpp | 42 ++++++----- .../src/prediction/resampler.cpp | 6 +- .../test/src/test_resampler.cpp | 72 +++++++++--------- 27 files changed, 237 insertions(+), 367 deletions(-) delete mode 100644 localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/correction/correction_util.hpp delete mode 100644 localization/yabloc/yabloc_particle_filter/src/correction/correction_util.cpp diff --git a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/camera_corrector/camera_particle_corrector.hpp b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/camera_corrector/camera_particle_corrector.hpp index 582abb03901a1..4ca8c01b3be64 100644 --- a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/camera_corrector/camera_particle_corrector.hpp +++ b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/camera_corrector/camera_particle_corrector.hpp @@ -33,7 +33,7 @@ namespace yabloc::modularized_particle_filter { -cv::Point2f cv2pt(const Eigen::Vector3f v); +cv::Point2f cv2pt(const Eigen::Vector3f & v); float abs_cos(const Eigen::Vector3f & t, float deg); class CameraParticleCorrector : public modularized_particle_filter::AbstractCorrector diff --git a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/camera_corrector/logit.hpp b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/camera_corrector/logit.hpp index caf93abd0028f..0b2954dd46ba5 100644 --- a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/camera_corrector/logit.hpp +++ b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/camera_corrector/logit.hpp @@ -18,15 +18,6 @@ namespace yabloc { float logit_to_prob(float logit, float gain = 1.0f); - -/** - * Convert probability to logit - * This function is much faster than logit_to_prob() because it refers to pre-computed table - * - * @param[in] prob - * @return logit - */ -float prob_to_logit(float prob); } // namespace yabloc #endif // YABLOC_PARTICLE_FILTER__CAMERA_CORRECTOR__LOGIT_HPP_ diff --git a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/common/mean.hpp b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/common/mean.hpp index e6af4f0d76d49..4e2c6cd8a842c 100644 --- a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/common/mean.hpp +++ b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/common/mean.hpp @@ -20,18 +20,13 @@ #include -namespace yabloc -{ -namespace modularized_particle_filter +namespace yabloc::modularized_particle_filter { geometry_msgs::msg::Pose get_mean_pose( const yabloc_particle_filter::msg::ParticleArray & particle_array); Eigen::Matrix3f std_of_distribution( const yabloc_particle_filter::msg::ParticleArray & particle_array); - -float std_of_weight(const yabloc_particle_filter::msg::ParticleArray & particle_array); -} // namespace modularized_particle_filter -} // namespace yabloc +} // namespace yabloc::modularized_particle_filter #endif // YABLOC_PARTICLE_FILTER__COMMON__MEAN_HPP_ diff --git a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/common/prediction_util.hpp b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/common/prediction_util.hpp index 6059f16826c98..140f1553b88ee 100644 --- a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/common/prediction_util.hpp +++ b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/common/prediction_util.hpp @@ -22,14 +22,12 @@ #include #include -namespace yabloc +namespace yabloc::modularized_particle_filter::util { -namespace modularized_particle_filter::util -{ -std::random_device seed_gen; -std::default_random_engine engine(seed_gen()); +inline std::random_device seed_gen; +inline std::default_random_engine engine(seed_gen()); -Eigen::Vector2d nrand_2d(const Eigen::Matrix2d cov) +inline Eigen::Vector2d nrand_2d(const Eigen::Matrix2d & cov) { Eigen::JacobiSVD svd; svd.compute(cov, Eigen::ComputeFullU | Eigen::ComputeFullV); @@ -50,7 +48,7 @@ T nrand(T std) return dist(engine); } -double normalize_radian(const double rad, const double min_rad = -M_PI) +inline double normalize_radian(const double rad, const double min_rad = -M_PI) { const auto max_rad = min_rad + 2 * M_PI; @@ -63,6 +61,5 @@ double normalize_radian(const double rad, const double min_rad = -M_PI) return value - std::copysign(2 * M_PI, value); } -} // namespace modularized_particle_filter::util -} // namespace yabloc +} // namespace yabloc::modularized_particle_filter::util #endif // YABLOC_PARTICLE_FILTER__COMMON__PREDICTION_UTIL_HPP_ diff --git a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/common/visualize.hpp b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/common/visualize.hpp index f1ecf35e81761..3b35d1a9a0da6 100644 --- a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/common/visualize.hpp +++ b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/common/visualize.hpp @@ -21,9 +21,7 @@ #include #include -namespace yabloc -{ -namespace modularized_particle_filter +namespace yabloc::modularized_particle_filter { class ParticleVisualizer { @@ -37,9 +35,7 @@ class ParticleVisualizer private: rclcpp::Publisher::SharedPtr pub_marker_array_; - std_msgs::msg::ColorRGBA compute_color(float value); }; -} // namespace modularized_particle_filter -} // namespace yabloc +} // namespace yabloc::modularized_particle_filter #endif // YABLOC_PARTICLE_FILTER__COMMON__VISUALIZE_HPP_ diff --git a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/correction/abstract_corrector.hpp b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/correction/abstract_corrector.hpp index 4deaeec0810ae..33802bd666440 100644 --- a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/correction/abstract_corrector.hpp +++ b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/correction/abstract_corrector.hpp @@ -26,9 +26,7 @@ #include #include -namespace yabloc -{ -namespace modularized_particle_filter +namespace yabloc::modularized_particle_filter { class AbstractCorrector : public rclcpp::Node { @@ -55,7 +53,6 @@ class AbstractCorrector : public rclcpp::Node private: void on_particle_array(const ParticleArray & particle_array); }; -} // namespace modularized_particle_filter -} // namespace yabloc +} // namespace yabloc::modularized_particle_filter #endif // YABLOC_PARTICLE_FILTER__CORRECTION__ABSTRACT_CORRECTOR_HPP_ diff --git a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/correction/correction_util.hpp b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/correction/correction_util.hpp deleted file mode 100644 index 2c2f10bf7ad2e..0000000000000 --- a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/correction/correction_util.hpp +++ /dev/null @@ -1,35 +0,0 @@ -// 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 YABLOC_PARTICLE_FILTER__CORRECTION__CORRECTION_UTIL_HPP_ -#define YABLOC_PARTICLE_FILTER__CORRECTION__CORRECTION_UTIL_HPP_ - -#include "rclcpp/rclcpp.hpp" -#include "yabloc_particle_filter/msg/particle_array.hpp" - -#include - -#include - -namespace yabloc -{ -namespace modularized_particle_filter -{ -std::optional find_synced_particles( - boost::circular_buffer circular_buffer, - rclcpp::Time time); -} -} // namespace yabloc - -#endif // YABLOC_PARTICLE_FILTER__CORRECTION__CORRECTION_UTIL_HPP_ diff --git a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/gnss_corrector/weight_manager.hpp b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/gnss_corrector/weight_manager.hpp index 791f65eb9b835..f22662a188355 100644 --- a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/gnss_corrector/weight_manager.hpp +++ b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/gnss_corrector/weight_manager.hpp @@ -35,41 +35,48 @@ struct WeightManager } }; - Parameter for_fixed_; - Parameter for_not_fixed_; + Parameter for_fixed_{}; + Parameter for_not_fixed_{}; explicit WeightManager(rclcpp::Node * node) { - for_fixed_.flat_radius_ = node->declare_parameter("for_fixed/flat_radius"); - for_fixed_.max_radius_ = node->declare_parameter("for_fixed/max_radius"); - for_fixed_.min_weight_ = node->declare_parameter("for_fixed/min_weight"); - for_fixed_.max_weight_ = node->declare_parameter("for_fixed/max_weight"); + for_fixed_.flat_radius_ = + static_cast(node->declare_parameter("for_fixed/flat_radius")); + for_fixed_.max_radius_ = + static_cast(node->declare_parameter("for_fixed/max_radius")); + for_fixed_.min_weight_ = + static_cast(node->declare_parameter("for_fixed/min_weight")); + for_fixed_.max_weight_ = + static_cast(node->declare_parameter("for_fixed/max_weight")); for_fixed_.compute_coeff(); - for_not_fixed_.flat_radius_ = node->declare_parameter("for_not_fixed/flat_radius"); - for_not_fixed_.max_radius_ = node->declare_parameter("for_not_fixed/max_radius"); - for_not_fixed_.min_weight_ = node->declare_parameter("for_not_fixed/min_weight"); - for_not_fixed_.max_weight_ = node->declare_parameter("for_not_fixed/max_weight"); + for_not_fixed_.flat_radius_ = + static_cast(node->declare_parameter("for_not_fixed/flat_radius")); + for_not_fixed_.max_radius_ = + static_cast(node->declare_parameter("for_not_fixed/max_radius")); + for_not_fixed_.min_weight_ = + static_cast(node->declare_parameter("for_not_fixed/min_weight")); + for_not_fixed_.max_weight_ = + static_cast(node->declare_parameter("for_not_fixed/max_weight")); for_not_fixed_.compute_coeff(); } - float normal_pdf(float distance, const Parameter & param) const + [[nodiscard]] static float normal_pdf(float distance, const Parameter & param) { // NOTE: This is not exact normal distribution because of no scale factor depending on sigma float d = std::clamp(std::abs(distance) - param.flat_radius_, 0.f, param.max_radius_); return param.max_weight_ * std::exp(-param.coeff_ * d * d); } - float normal_pdf(float distance, bool is_rtk_fixed) const + [[nodiscard]] float normal_pdf(float distance, bool is_rtk_fixed) const { if (is_rtk_fixed) { return normal_pdf(distance, for_fixed_); - } else { - return normal_pdf(distance, for_not_fixed_); } + return normal_pdf(distance, for_not_fixed_); } - float inverse_normal_pdf(float prob, const Parameter & param) const + [[nodiscard]] static float inverse_normal_pdf(float prob, const Parameter & param) { prob = (param.max_weight_ - param.min_weight_) * prob + param.min_weight_; @@ -78,13 +85,12 @@ struct WeightManager return param.flat_radius_ + std::sqrt(-std::log(prob / param.max_weight_) / param.coeff_); } - float inverse_normal_pdf(float prob, bool is_rtk_fixed) const + [[nodiscard]] float inverse_normal_pdf(float prob, bool is_rtk_fixed) const { if (is_rtk_fixed) { return inverse_normal_pdf(prob, for_fixed_); - } else { - return inverse_normal_pdf(prob, for_not_fixed_); } + return inverse_normal_pdf(prob, for_not_fixed_); } }; } // namespace yabloc::modularized_particle_filter diff --git a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/ll2_cost_map/direct_cost_map.hpp b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/ll2_cost_map/direct_cost_map.hpp index 5f56b8f079cd1..8169719a21f3b 100644 --- a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/ll2_cost_map/direct_cost_map.hpp +++ b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/ll2_cost_map/direct_cost_map.hpp @@ -20,9 +20,6 @@ namespace yabloc { cv::Mat direct_cost_map(const cv::Mat & cost_map, const cv::Mat & intensity); - -cv::Mat visualize_direction_map(const cv::Mat & cost_map); - } // namespace yabloc #endif // YABLOC_PARTICLE_FILTER__LL2_COST_MAP__DIRECT_COST_MAP_HPP_ diff --git a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/ll2_cost_map/hierarchical_cost_map.hpp b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/ll2_cost_map/hierarchical_cost_map.hpp index 32d579c4ab595..d6cc4553e29bc 100644 --- a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/ll2_cost_map/hierarchical_cost_map.hpp +++ b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/ll2_cost_map/hierarchical_cost_map.hpp @@ -37,34 +37,37 @@ namespace yabloc { struct Area { - Area() {} + Area() = default; explicit Area(const Eigen::Vector2f & v) { - if (unit_length_ < 0) { + if (unit_length < 0) { throw_error(); } - x = static_cast(std::floor(v.x() / unit_length_)); - y = static_cast(std::floor(v.y() / unit_length_)); + x = static_cast(std::floor(v.x() / unit_length)); + y = static_cast(std::floor(v.y() / unit_length)); } - Eigen::Vector2f real_scale() const { return {x * unit_length_, y * unit_length_}; } + [[nodiscard]] Eigen::Vector2f real_scale() const + { + return {static_cast(x) * unit_length, static_cast(y) * unit_length}; + } - std::array real_scale_boundary() const + [[nodiscard]] std::array real_scale_boundary() const { std::array boundary; boundary.at(0) = real_scale(); - boundary.at(1) = real_scale() + Eigen::Vector2f(unit_length_, unit_length_); + boundary.at(1) = real_scale() + Eigen::Vector2f(unit_length, unit_length); return boundary; }; - void throw_error() const + static void throw_error() { std::cerr << "Area::unit_length_ is not initialized" << std::endl; throw std::runtime_error("invalid Area::unit_length"); } - int x, y; - static float unit_length_; - static float image_size_; + int x{}, y{}; + static float unit_length; + static float image_size; friend bool operator==(const Area & one, const Area & other) { @@ -129,7 +132,7 @@ class HierarchicalCostMap rclcpp::Logger logger_; std::optional height_{std::nullopt}; - common::GammaConverter gamma_converter{4.0f}; + common::GammaConverter gamma_converter_{4.0f}; std::unordered_map map_accessed_; @@ -138,7 +141,7 @@ class HierarchicalCostMap std::vector bounding_boxes_; std::unordered_map cost_maps_; - cv::Point to_cv_point(const Area & are, const Eigen::Vector2f) const; + cv::Point to_cv_point(const Area & area, const Eigen::Vector2f & p) const; void build_map(const Area & area); cv::Mat create_available_area_image(const Area & area) const; diff --git a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/predictor.hpp b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/predictor.hpp index e4fb58f22e17f..b619ed524affd 100644 --- a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/predictor.hpp +++ b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/predictor.hpp @@ -106,7 +106,7 @@ class Predictor : public rclcpp::Node void initialize_particles(const PoseCovStamped & initialpose); // void update_with_dynamic_noise( - ParticleArray & particle_array, const TwistCovStamped & twist, double dt); + ParticleArray & particle_array, const TwistCovStamped & twist, double dt) const; // void publish_mean_pose(const geometry_msgs::msg::Pose & mean_pose, const rclcpp::Time & stamp); void publish_range_marker(const Eigen::Vector3f & pos, const Eigen::Vector3f & tangent); diff --git a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/resampler.hpp b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/resampler.hpp index f2a517216020a..7b3aa8553f90e 100644 --- a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/resampler.hpp +++ b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/resampler.hpp @@ -22,10 +22,10 @@ namespace yabloc::modularized_particle_filter { -class resampling_skip_exception : public std::runtime_error +class ResamplingSkipException : public std::runtime_error { public: - explicit resampling_skip_exception(const char * message) : runtime_error(message) {} + explicit ResamplingSkipException(const char * message) : runtime_error(message) {} }; class RetroactiveResampler @@ -56,9 +56,10 @@ class RetroactiveResampler int latest_resampling_generation_; // Random generator from 0 to 1 - double random_from_01_uniformly() const; + [[nodiscard]] static double random_from_01_uniformly(); // Check the sanity of the particles obtained from the particle corrector. - bool check_weighted_particles_validity(const ParticleArray & weighted_particles) const; + [[nodiscard]] bool check_weighted_particles_validity( + const ParticleArray & weighted_particles) const; }; } // namespace yabloc::modularized_particle_filter diff --git a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/resampling_history.hpp b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/resampling_history.hpp index 5b24ee96d6df5..6c1e9737c3f0d 100644 --- a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/resampling_history.hpp +++ b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/prediction/resampling_history.hpp @@ -35,7 +35,7 @@ class ResamplingHistory } } - bool check_history_validity() const + [[nodiscard]] bool check_history_validity() const { for (auto & generation : resampling_history_) { bool result = std::any_of(generation.begin(), generation.end(), [this](int x) { diff --git a/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_core.cpp b/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_core.cpp index 35113b4c5af36..861f39454d109 100644 --- a/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_core.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_core.cpp @@ -25,13 +25,15 @@ #include +#include + namespace yabloc::modularized_particle_filter { CameraParticleCorrector::CameraParticleCorrector(const rclcpp::NodeOptions & options) : AbstractCorrector("camera_particle_corrector", options), - min_prob_(declare_parameter("min_prob")), - far_weight_gain_(declare_parameter("far_weight_gain")), + min_prob_(static_cast(declare_parameter("min_prob"))), + far_weight_gain_(static_cast(declare_parameter("far_weight_gain"))), cost_map_(this) { using std::placeholders::_1; @@ -98,7 +100,8 @@ CameraParticleCorrector::split_line_segments(const PointCloud2 & msg) { LineSegments all_line_segments_cloud; pcl::fromROSMsg(msg, all_line_segments_cloud); - LineSegments reliable_cloud, iffy_cloud; + LineSegments reliable_cloud; + LineSegments iffy_cloud; { for (const auto & p : all_line_segments_cloud) { if (p.label == 0) @@ -111,7 +114,7 @@ CameraParticleCorrector::split_line_segments(const PointCloud2 & msg) auto [good_cloud, bad_cloud] = filt(iffy_cloud); { cv::Mat debug_image = cv::Mat::zeros(800, 800, CV_8UC3); - auto draw = [&debug_image](LineSegments & cloud, cv::Scalar color) -> void { + auto draw = [&debug_image](const LineSegments & cloud, const cv::Scalar & color) -> void { for (const auto & line : cloud) { const Eigen::Vector3f p1 = line.getVector3fMap(); const Eigen::Vector3f p2 = line.getNormalVector3fMap(); @@ -162,7 +165,7 @@ void CameraParticleCorrector::on_line_segments(const PointCloud2 & line_segments } } - cost_map_.set_height(mean_pose.position.z); + cost_map_.set_height(static_cast(mean_pose.position.z)); if (publish_weighted_particles) { for (auto & particle : weighted_particles.particles) { @@ -187,8 +190,7 @@ void CameraParticleCorrector::on_line_segments(const PointCloud2 & line_segments // DEBUG: just visualization { - Pose mean_pose = get_mean_pose(weighted_particles); - Sophus::SE3f transform = common::pose_to_se3(mean_pose); + Sophus::SE3f transform = common::pose_to_se3(get_mean_pose(weighted_particles)); pcl::PointCloud cloud = evaluate_cloud( common::transform_line_segments(line_segments_cloud, transform), transform.translation()); @@ -199,10 +201,9 @@ void CameraParticleCorrector::on_line_segments(const PointCloud2 & line_segments pcl::PointCloud rgb_cloud; pcl::PointCloud rgb_iffy_cloud; - float max_score = 0; - for (const auto p : cloud) { - max_score = std::max(max_score, std::abs(p.intensity)); - } + float max_score = std::accumulate( + cloud.begin(), cloud.end(), 0.0f, + [](float max_score, const auto & p) { return std::max(max_score, std::abs(p.intensity)); }); for (const auto p : cloud) { pcl::PointXYZRGB rgb; rgb.getVector3fMap() = p.getVector3fMap(); @@ -256,7 +257,7 @@ void CameraParticleCorrector::on_ll2(const PointCloud2 & ll2_msg) float abs_cos(const Eigen::Vector3f & t, float deg) { - const float radian = deg * M_PI / 180.0; + const auto radian = static_cast(deg * M_PI / 180.0); Eigen::Vector2f x(t.x(), t.y()); Eigen::Vector2f y(autoware_universe_utils::cos(radian), autoware_universe_utils::sin(radian)); x.normalize(); @@ -276,7 +277,7 @@ float CameraParticleCorrector::compute_logit( // NOTE: Close points are prioritized float squared_norm = (p - self_position).topRows(2).squaredNorm(); - float gain = exp(-far_weight_gain_ * squared_norm); // 0 < gain < 1 + float gain = std::exp(-far_weight_gain_ * squared_norm); // 0 < gain < 1 const CostMapValue v3 = cost_map_.at(p.topRows(2)); @@ -285,9 +286,10 @@ float CameraParticleCorrector::compute_logit( continue; } if (pn.label == 0) { // posteriori - logit += 0.2f * gain * (abs_cos(tangent, v3.angle) * v3.intensity - 0.5f); + logit += + 0.2f * gain * (abs_cos(tangent, static_cast(v3.angle)) * v3.intensity - 0.5f); } else { // apriori - logit += gain * (abs_cos(tangent, v3.angle) * v3.intensity - 0.5f); + logit += gain * (abs_cos(tangent, static_cast(v3.angle)) * v3.intensity - 0.5f); } } } @@ -307,11 +309,14 @@ pcl::PointCloud CameraParticleCorrector::evaluate_cloud( // NOTE: Close points are prioritized float squared_norm = (p - self_position).topRows(2).squaredNorm(); - float gain = std::exp(-far_weight_gain_ * squared_norm); CostMapValue v3 = cost_map_.at(p.topRows(2)); float logit = 0; - if (!v3.unmapped) logit = gain * (abs_cos(tangent, v3.angle) * v3.intensity - 0.5f); + if (!v3.unmapped) { + float gain = std::exp(-far_weight_gain_ * squared_norm); + + logit = gain * (abs_cos(tangent, static_cast(v3.angle)) * v3.intensity - 0.5f); + } pcl::PointXYZI xyzi(logit_to_prob(logit, 10.f)); xyzi.getVector3fMap() = p; diff --git a/localization/yabloc/yabloc_particle_filter/src/camera_corrector/filter_line_segments.cpp b/localization/yabloc/yabloc_particle_filter/src/camera_corrector/filter_line_segments.cpp index 3f782d85aec43..105f72920a6de 100644 --- a/localization/yabloc/yabloc_particle_filter/src/camera_corrector/filter_line_segments.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/camera_corrector/filter_line_segments.cpp @@ -22,33 +22,35 @@ namespace yabloc::modularized_particle_filter { -cv::Point2f cv2pt(const Eigen::Vector3f v) +cv::Point2f cv2pt(const Eigen::Vector3f & v) { - const float METRIC_PER_PIXEL = 0.05; - const float IMAGE_RADIUS = 400; - return {-v.y() / METRIC_PER_PIXEL + IMAGE_RADIUS, -v.x() / METRIC_PER_PIXEL + 2 * IMAGE_RADIUS}; + const float metric_per_pixel = 0.05; + const float image_radius = 400; + return {-v.y() / metric_per_pixel + image_radius, -v.x() / metric_per_pixel + 2 * image_radius}; } float normalized_atan2(const Eigen::Vector3f & t, float deg) { - float diff = std::atan2(t.y(), t.x()) - deg * M_PI / 180; - diff = std::fmod(diff, M_PI); + auto diff = static_cast(std::atan2(t.y(), t.x()) - deg * M_PI / 180); + diff = static_cast(std::fmod(diff, M_PI)); if (diff < 0) diff = -diff; if (diff < M_PI_2) { - return 1 - diff / M_PI_2; - } else if (diff < M_PI) { - return diff / M_PI_2 - 1; - } else { - throw std::runtime_error("invalid cos"); + return static_cast(1.0 - diff / M_PI_2); } + + if (diff < M_PI) { + return static_cast(diff / M_PI_2 - 1.0); + } + throw std::runtime_error("invalid cos"); } std::pair CameraParticleCorrector::filt(const LineSegments & iffy_lines) { - LineSegments good, bad; + LineSegments good; + LineSegments bad; if (!latest_pose_.has_value()) { throw std::runtime_error("latest_pose_ is nullopt"); } @@ -67,7 +69,7 @@ CameraParticleCorrector::filt(const LineSegments & iffy_lines) for (float distance = 0; distance < length; distance += 0.1f) { Eigen::Vector3f px = pose * (p2 + tangent * distance); CostMapValue v3 = cost_map_.at(px.topRows(2)); - float cos2 = normalized_atan2(pose.so3() * tangent, v3.angle); + float cos2 = normalized_atan2(pose.so3() * tangent, static_cast(v3.angle)); score += (cos2 * v3.intensity); count++; @@ -77,7 +79,7 @@ CameraParticleCorrector::filt(const LineSegments & iffy_lines) // rgb_cloud.push_back(rgb); } - if (score / count > 0.5f) { + if (score / static_cast(count) > 0.5f) { good.push_back(line); } else { bad.push_back(line); diff --git a/localization/yabloc/yabloc_particle_filter/src/camera_corrector/logit.cpp b/localization/yabloc/yabloc_particle_filter/src/camera_corrector/logit.cpp index d8bb5690b6fc4..65b7039e25051 100644 --- a/localization/yabloc/yabloc_particle_filter/src/camera_corrector/logit.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/camera_corrector/logit.cpp @@ -27,7 +27,7 @@ struct ProbToLogitTable ProbToLogitTable() { for (int i = 0; i < 100; ++i) { - float p = i / 100.0f; + float p = static_cast(i) / 100.0f; table_.at(i) = std::log(p / std::max(1 - p, 1e-6f)); } } @@ -37,7 +37,7 @@ struct ProbToLogitTable return table_.at(index); } - std::array table_; + std::array table_{}; } prob_to_logit_table; } // namespace @@ -47,9 +47,4 @@ float logit_to_prob(float logit, float gain) return 1.f / (1 + std::exp(-gain * logit)); } -float prob_to_logit(float prob) -{ - return prob_to_logit_table(prob); -} - } // namespace yabloc diff --git a/localization/yabloc/yabloc_particle_filter/src/common/mean.cpp b/localization/yabloc/yabloc_particle_filter/src/common/mean.cpp index 0710c8c4dca64..1a0ef05508c76 100644 --- a/localization/yabloc/yabloc_particle_filter/src/common/mean.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/common/mean.cpp @@ -70,7 +70,9 @@ geometry_msgs::msg::Pose get_mean_pose( mean_pose.position.y += particle.pose.position.y * normalized_weight; mean_pose.position.z += particle.pose.position.z * normalized_weight; - double yaw{0.0}, pitch{0.0}, roll{0.0}; + double yaw{0.0}; + double pitch{0.0}; + double roll{0.0}; tf2::getEulerYPR(particle.pose.orientation, yaw, pitch, roll); rolls.push_back(roll); @@ -93,43 +95,25 @@ Eigen::Matrix3f std_of_distribution(const yabloc_particle_filter::msg::ParticleA { using Particle = yabloc_particle_filter::msg::Particle; auto ori = get_mean_pose(array).orientation; - Eigen::Quaternionf orientation(ori.w, ori.x, ori.y, ori.z); - float invN = 1.f / array.particles.size(); + Eigen::Quaternionf orientation( + static_cast(ori.w), static_cast(ori.x), static_cast(ori.y), + static_cast(ori.z)); + float inv_n = 1.f / static_cast(array.particles.size()); Eigen::Vector3f mean = Eigen::Vector3f::Zero(); for (const Particle & p : array.particles) { Eigen::Affine3f affine = common::pose_to_affine(p.pose); mean += affine.translation(); } - mean *= invN; + mean *= inv_n; Eigen::Matrix3f sigma = Eigen::Matrix3f::Zero(); for (const Particle & p : array.particles) { Eigen::Affine3f affine = common::pose_to_affine(p.pose); Eigen::Vector3f d = affine.translation() - mean; d = orientation.conjugate() * d; - sigma += (d * d.transpose()) * invN; + sigma += (d * d.transpose()) * inv_n; } return sigma; } - -float std_of_weight(const yabloc_particle_filter::msg::ParticleArray & particle_array) -{ - using Particle = yabloc_particle_filter::msg::Particle; - - const float invN = 1.f / particle_array.particles.size(); - float mean = 0; - for (const Particle & p : particle_array.particles) { - mean += p.weight; - } - mean *= invN; - - float sigma = 0.0; - for (const Particle & p : particle_array.particles) { - sigma += (p.weight - mean) * (p.weight - mean); - } - sigma *= invN; - - return std::sqrt(sigma); -} } // namespace yabloc::modularized_particle_filter diff --git a/localization/yabloc/yabloc_particle_filter/src/common/particle_visualize_node.cpp b/localization/yabloc/yabloc_particle_filter/src/common/particle_visualize_node.cpp index b63e87b9462f1..48f2041595a77 100644 --- a/localization/yabloc/yabloc_particle_filter/src/common/particle_visualize_node.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/common/particle_visualize_node.cpp @@ -39,36 +39,12 @@ class ParticleVisualize : public rclcpp::Node "/particle_array", 10, std::bind(&ParticleVisualize::on_particles, this, _1)); // Publisher - pub_marker_array = this->create_publisher("/marker_array", 10); + pub_marker_array_ = this->create_publisher("/marker_array", 10); } private: rclcpp::Subscription::SharedPtr sub_particles_; - rclcpp::Publisher::SharedPtr pub_marker_array; - - std_msgs::msg::ColorRGBA compute_color(float value) const - { - float r = 1.0f, g = 1.0f, b = 1.0f; - // clang-format off - value = std::clamp(value, 0.0f, 1.0f); - if (value < 0.25f) { - r = 0; g = 4 * (value); - } else if (value < 0.5f) { - r = 0; b = 1 + 4 * (0.25f - value); - } else if (value < 0.75f) { - r = 4 * (value - 0.5f); b = 0; - } else { - g = 1 + 4 * (0.75f - value); b = 0; - } - // clang-format on - - std_msgs::msg::ColorRGBA rgba; - rgba.r = r; - rgba.g = g; - rgba.b = b; - rgba.a = 1.0f; - return rgba; - } + rclcpp::Publisher::SharedPtr pub_marker_array_; void on_particles(const ParticleArray & msg) { @@ -102,7 +78,7 @@ class ParticleVisualize : public rclcpp::Node marker.pose.position.z = p.pose.position.z; marker_array.markers.push_back(marker); } - pub_marker_array->publish(marker_array); + pub_marker_array_->publish(marker_array); } }; } // namespace yabloc::modularized_particle_filter diff --git a/localization/yabloc/yabloc_particle_filter/src/common/visualize.cpp b/localization/yabloc/yabloc_particle_filter/src/common/visualize.cpp index 888baf0bea0ac..17b22757b4bc5 100644 --- a/localization/yabloc/yabloc_particle_filter/src/common/visualize.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/common/visualize.cpp @@ -33,7 +33,7 @@ void ParticleVisualizer::publish(const ParticleArray & msg) float min = minmax_weight.first->weight; float max = minmax_weight.second->weight; max = std::max(max, min + 1e-7f); - auto boundWeight = [min, max](float raw) -> float { return (raw - min) / (max - min); }; + auto bound_weight = [min, max](float raw) -> float { return (raw - min) / (max - min); }; int id = 0; for (const Particle & p : msg.particles) { @@ -46,7 +46,7 @@ void ParticleVisualizer::publish(const ParticleArray & msg) marker.scale.y = 0.1; marker.scale.z = 0.1; marker.color = - static_cast(common::color_scale::rainbow(boundWeight(p.weight))); + static_cast(common::color_scale::rainbow(bound_weight(p.weight))); marker.pose.orientation = p.pose.orientation; marker.pose.position.x = p.pose.position.x; marker.pose.position.y = p.pose.position.y; diff --git a/localization/yabloc/yabloc_particle_filter/src/correction/abstract_corrector.cpp b/localization/yabloc/yabloc_particle_filter/src/correction/abstract_corrector.cpp index 5221256c9e392..1c8e2f5976a1d 100644 --- a/localization/yabloc/yabloc_particle_filter/src/correction/abstract_corrector.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/correction/abstract_corrector.cpp @@ -19,7 +19,7 @@ namespace yabloc::modularized_particle_filter AbstractCorrector::AbstractCorrector( const std::string & node_name, const rclcpp::NodeOptions & options) : Node(node_name, options), - acceptable_max_delay_(declare_parameter("acceptable_max_delay")), + acceptable_max_delay_(static_cast(declare_parameter("acceptable_max_delay"))), visualize_(declare_parameter("visualize")), logger_(rclcpp::get_logger("abstract_corrector")) { diff --git a/localization/yabloc/yabloc_particle_filter/src/correction/correction_util.cpp b/localization/yabloc/yabloc_particle_filter/src/correction/correction_util.cpp deleted file mode 100644 index 67ca4f5add947..0000000000000 --- a/localization/yabloc/yabloc_particle_filter/src/correction/correction_util.cpp +++ /dev/null @@ -1,38 +0,0 @@ -// 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 "yabloc_particle_filter/correction/correction_util.hpp" - -namespace yabloc::modularized_particle_filter -{ -std::optional find_synced_particles( - boost::circular_buffer circular_buffer, - rclcpp::Time time) -{ - for (int i{1}; i < static_cast(circular_buffer.size()); i++) { - if (rclcpp::Time(circular_buffer[i].header.stamp) < time) { - return circular_buffer[i]; - } - } - if (0 < static_cast(circular_buffer.size())) { - RCLCPP_WARN_STREAM( - rclcpp::get_logger("modularized_particle_filter.correction_util"), - "the sensor data is too old: " - << rclcpp::Time(circular_buffer[static_cast(circular_buffer.size()) - 1].header.stamp) - .seconds() - - time.seconds()); - } - return std::nullopt; -} -} // namespace yabloc::modularized_particle_filter diff --git a/localization/yabloc/yabloc_particle_filter/src/gnss_corrector/gnss_corrector_core.cpp b/localization/yabloc/yabloc_particle_filter/src/gnss_corrector/gnss_corrector_core.cpp index f1dd22426a07d..1ccb24bfbea5c 100644 --- a/localization/yabloc/yabloc_particle_filter/src/gnss_corrector/gnss_corrector_core.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/gnss_corrector/gnss_corrector_core.cpp @@ -21,7 +21,8 @@ namespace yabloc::modularized_particle_filter { GnssParticleCorrector::GnssParticleCorrector(const rclcpp::NodeOptions & options) : AbstractCorrector("gnss_particle_corrector", options), - mahalanobis_distance_threshold_(declare_parameter("mahalanobis_distance_threshold")), + mahalanobis_distance_threshold_( + static_cast(declare_parameter("mahalanobis_distance_threshold"))), weight_manager_(this) { using std::placeholders::_1; @@ -61,7 +62,8 @@ void GnssParticleCorrector::on_pose(const PoseCovStamped::ConstSharedPtr pose_ms const rclcpp::Time stamp = pose_msg->header.stamp; const auto & position = pose_msg->pose.pose.position; Eigen::Vector3f gnss_position; - gnss_position << position.x, position.y, position.z; + gnss_position << static_cast(position.x), static_cast(position.y), + static_cast(position.z); constexpr bool is_rtk_fixed = false; process(gnss_position, stamp, is_rtk_fixed); @@ -96,7 +98,6 @@ void GnssParticleCorrector::process( // Compute travel distance from last update position // If the distance is too short, skip weighting { - Eigen::Vector3f mean_position = common::pose_to_affine(mean_pose).translation(); if ((mean_position - last_mean_position_).squaredNorm() > 1) { this->set_weighted_particle_array(weighted_particles); last_mean_position_ = mean_position; @@ -113,12 +114,12 @@ void GnssParticleCorrector::publish_marker(const Eigen::Vector3f & position, boo using namespace std::literals::chrono_literals; using Point = geometry_msgs::msg::Point; - auto drawCircle = [](std::vector & points, float radius) -> void { - const int N = 10; - for (int theta = 0; theta < 2 * N + 1; theta++) { + auto draw_circle = [](std::vector & points, float radius) -> void { + const int n = 10; + for (int theta = 0; theta < 2 * n + 1; theta++) { geometry_msgs::msg::Point pt; - pt.x = radius * std::cos(theta * M_PI / N); - pt.y = radius * std::sin(theta * M_PI / N); + pt.x = radius * std::cos(theta * M_PI / n); + pt.y = radius * std::sin(theta * M_PI / n); points.push_back(pt); } }; @@ -135,11 +136,11 @@ void GnssParticleCorrector::publish_marker(const Eigen::Vector3f & position, boo marker.pose.position.y = position.y(); marker.pose.position.z = latest_height_.data; - float prob = i / 4.0f; + float prob = static_cast(i) / 4.0f; marker.color = static_cast(common::color_scale::rainbow(prob)); marker.color.a = 0.5f; marker.scale.x = 0.1; - drawCircle(marker.points, weight_manager_.inverse_normal_pdf(prob, is_rtk_fixed)); + draw_circle(marker.points, weight_manager_.inverse_normal_pdf(prob, is_rtk_fixed)); array_msg.markers.push_back(marker); } marker_pub_->publish(array_msg); @@ -151,7 +152,7 @@ GnssParticleCorrector::ParticleArray GnssParticleCorrector::weight_particles( ParticleArray weighted_particles{predicted_particles}; for (auto & particle : weighted_particles.particles) { - float distance = static_cast( + auto distance = static_cast( std::hypot(particle.pose.position.x - pose.x(), particle.pose.position.y - pose.y())); particle.weight = weight_manager_.normal_pdf(distance, is_rtk_fixed); } diff --git a/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/direct_cost_map.cpp b/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/direct_cost_map.cpp index 7da87e8050ebe..c6359a8c8f5fc 100644 --- a/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/direct_cost_map.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/direct_cost_map.cpp @@ -18,14 +18,14 @@ namespace yabloc { cv::Mat direct_cost_map(const cv::Mat & cost_map, const cv::Mat & intensity) { - constexpr int MAX_INT = std::numeric_limits::max(); + constexpr int max_int = std::numeric_limits::max(); std::vector> distances; distances.resize(cost_map.rows); for (int i = 0; i < cost_map.rows; i++) { distances.at(i).resize(cost_map.cols); - std::fill(distances.at(i).begin(), distances.at(i).end(), MAX_INT); - const uchar * intensity_ptr = intensity.ptr(i); + std::fill(distances.at(i).begin(), distances.at(i).end(), max_int); + const auto * intensity_ptr = intensity.ptr(i); for (int j = 0; j < cost_map.cols; j++) { if (intensity_ptr[j] == 0) distances.at(i).at(j) = 0; } @@ -36,7 +36,7 @@ cv::Mat direct_cost_map(const cv::Mat & cost_map, const cv::Mat & intensity) // Forward for (int r = 1; r < cost_map.rows; r++) { const uchar * upper_ptr = dst.ptr(r - 1); - uchar * current_ptr = dst.ptr(r); + auto * current_ptr = dst.ptr(r); for (int c = 1; c < cost_map.cols; c++) { int up = distances.at(r - 1).at(c); @@ -56,7 +56,7 @@ cv::Mat direct_cost_map(const cv::Mat & cost_map, const cv::Mat & intensity) // Backward for (int r = cost_map.rows - 2; r >= 0; r--) { const uchar * downer_ptr = dst.ptr(r + 1); - uchar * current_ptr = dst.ptr(r); + auto * current_ptr = dst.ptr(r); for (int c = cost_map.cols - 2; c >= 0; c--) { int down = distances.at(r + 1).at(c); @@ -76,24 +76,6 @@ cv::Mat direct_cost_map(const cv::Mat & cost_map, const cv::Mat & intensity) return dst; } -cv::Mat visualize_direction_map(const cv::Mat & cost_map) -{ - cv::Mat s = 255 * cv::Mat::ones(cost_map.size(), CV_8UC1); - cv::Mat v = 255 * cv::Mat::ones(cost_map.size(), CV_8UC1); - cv::Mat hsv, rgb; - cv::merge(std::vector{cost_map, s, v}, hsv); - cv::cvtColor(hsv, rgb, cv::COLOR_HSV2BGR); - - for (int r = 0; r < cost_map.rows; r++) { - const uchar * src_ptr = cost_map.ptr(r); - cv::Vec3b * dst_ptr = rgb.ptr(r); - for (int c = 0; c < cost_map.cols; c++) { - if (src_ptr[c] == 0) dst_ptr[c] = cv::Vec3b(0, 0, 0); - } - } - return rgb; -} - } // namespace yabloc // #include diff --git a/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/hierarchical_cost_map.cpp b/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/hierarchical_cost_map.cpp index 69f3642c8eff6..f11fe26389ecc 100644 --- a/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/hierarchical_cost_map.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/hierarchical_cost_map.cpp @@ -24,20 +24,20 @@ namespace yabloc { -float Area::unit_length_ = -1; +float Area::unit_length = -1; HierarchicalCostMap::HierarchicalCostMap(rclcpp::Node * node) -: max_range_(node->declare_parameter("max_range")), - image_size_(node->declare_parameter("image_size")), +: max_range_(static_cast(node->declare_parameter("max_range"))), + image_size_(static_cast(node->declare_parameter("image_size"))), max_map_count_(10), logger_(node->get_logger()) { - Area::unit_length_ = max_range_; - float gamma = node->declare_parameter("gamma"); - gamma_converter.reset(gamma); + Area::unit_length = max_range_; + float gamma = static_cast(node->declare_parameter("gamma")); + gamma_converter_.reset(gamma); } -cv::Point2i HierarchicalCostMap::to_cv_point(const Area & area, const Eigen::Vector2f p) const +cv::Point2i HierarchicalCostMap::to_cv_point(const Area & area, const Eigen::Vector2f & p) const { Eigen::Vector2f relative = p - area.real_scale(); float px = relative.x() / max_range_ * image_size_; @@ -59,7 +59,7 @@ CostMapValue HierarchicalCostMap::at(const Eigen::Vector2f & position) cv::Point2i tmp = to_cv_point(key, position); cv::Vec3b b3 = cost_maps_.at(key).ptr(tmp.y)[tmp.x]; - return {b3[0] / 255.f, b3[1], b3[2] == 1}; + return {static_cast(b3[0]) / 255.f, b3[1], b3[2] == 1}; } void HierarchicalCostMap::set_height(float height) @@ -103,10 +103,13 @@ void HierarchicalCostMap::build_map(const Area & area) { if (!cloud_.has_value()) return; - cv::Mat image = 255 * cv::Mat::ones(cv::Size(image_size_, image_size_), CV_8UC1); - cv::Mat orientation = cv::Mat::zeros(cv::Size(image_size_, image_size_), CV_8UC1); + cv::Mat image = + 255 * + cv::Mat::ones(cv::Size(static_cast(image_size_), static_cast(image_size_)), CV_8UC1); + cv::Mat orientation = + cv::Mat::zeros(cv::Size(static_cast(image_size_), static_cast(image_size_)), CV_8UC1); - auto cvPoint = [this, area](const Eigen::Vector3f & p) -> cv::Point { + auto cv_point = [this, area](const Eigen::Vector3f & p) -> cv::Point { return this->to_cv_point(area, p.topRows(2)); }; @@ -117,12 +120,12 @@ void HierarchicalCostMap::build_map(const Area & area) if (std::abs(pn.normal_z - *height_) > 4) continue; } - cv::Point2i from = cvPoint(pn.getVector3fMap()); - cv::Point2i to = cvPoint(pn.getNormalVector3fMap()); + cv::Point2i from = cv_point(pn.getVector3fMap()); + cv::Point2i to = cv_point(pn.getNormalVector3fMap()); - float radian = std::atan2(from.y - to.y, from.x - to.x); + auto radian = static_cast(std::atan2(from.y - to.y, from.x - to.x)); if (radian < 0) radian += M_PI; - float degree = radian * 180 / M_PI; + auto degree = static_cast(radian * 180 / M_PI); cv::line(image, from, to, cv::Scalar::all(0), 1); cv::line(orientation, from, to, cv::Scalar::all(degree), 1); @@ -142,7 +145,7 @@ void HierarchicalCostMap::build_map(const Area & area) cv::Mat directed_cost_map; cv::merge( - std::vector{gamma_converter(distance), whole_orientation, available_area}, + std::vector{gamma_converter_(distance), whole_orientation, available_area}, directed_cost_map); cost_maps_[area] = directed_cost_map; @@ -173,9 +176,10 @@ HierarchicalCostMap::MarkerArray HierarchicalCostMap::show_map_range() const marker.scale.x = 0.1; Eigen::Vector2f xy = area.real_scale(); marker.points.push_back(point_msg(xy.x(), xy.y())); - marker.points.push_back(point_msg(xy.x() + area.unit_length_, xy.y())); - marker.points.push_back(point_msg(xy.x() + area.unit_length_, xy.y() + area.unit_length_)); - marker.points.push_back(point_msg(xy.x(), xy.y() + area.unit_length_)); + marker.points.push_back(point_msg(xy.x() + yabloc::Area::unit_length, xy.y())); + marker.points.push_back( + point_msg(xy.x() + yabloc::Area::unit_length, xy.y() + yabloc::Area::unit_length)); + marker.points.push_back(point_msg(xy.x(), xy.y() + yabloc::Area::unit_length)); marker.points.push_back(point_msg(xy.x(), xy.y())); array_msg.markers.push_back(marker); } @@ -188,27 +192,33 @@ cv::Mat HierarchicalCostMap::get_map_image(const Pose & pose) // return cv::Mat::zeros(cv::Size(image_size_, image_size_), CV_8UC3); Eigen::Vector2f center; - center << pose.position.x, pose.position.y; + center << static_cast(pose.position.x), static_cast(pose.position.y); - float w = pose.orientation.w; - float z = pose.orientation.z; - Eigen::Matrix2f R = Eigen::Rotation2Df(2.f * std::atan2(z, w) - M_PI_2).toRotationMatrix(); + auto w = static_cast(pose.orientation.w); + auto z = static_cast(pose.orientation.z); + Eigen::Matrix2f r = + Eigen::Rotation2Df(static_cast(2.f * std::atan2(z, w) - M_PI_2)).toRotationMatrix(); - auto toVector2f = [this, center, R](float h, float w) -> Eigen::Vector2f { + auto to_vector2f = [this, center, r](float h, float w) -> Eigen::Vector2f { Eigen::Vector2f offset; offset.x() = (w / this->image_size_ - 0.5f) * this->max_range_ * 1.5f; offset.y() = -(h / this->image_size_ - 0.5f) * this->max_range_ * 1.5f; - return center + R * offset; + return center + r * offset; }; - cv::Mat image = cv::Mat::zeros(cv::Size(image_size_, image_size_), CV_8UC3); - for (int w = 0; w < image_size_; w++) { - for (int h = 0; h < image_size_; h++) { - CostMapValue v3 = this->at(toVector2f(h, w)); + cv::Mat image = + cv::Mat::zeros(cv::Size(static_cast(image_size_), static_cast(image_size_)), CV_8UC3); + for (int w_index = 0; static_cast(w_index) < image_size_; w_index++) { + for (int h_index = 0; static_cast(h_index) < image_size_; h_index++) { + CostMapValue v3 = + this->at(to_vector2f(static_cast(h_index), static_cast(w_index))); if (v3.unmapped) - image.at(h, w) = cv::Vec3b(v3.angle, 255 * v3.intensity, 50); + image.at(h_index, w_index) = + cv::Vec3b(v3.angle, static_cast(255 * v3.intensity), 50); else - image.at(h, w) = cv::Vec3b(v3.angle, 255 * v3.intensity, 255 * v3.intensity); + image.at(h_index, w_index) = cv::Vec3b( + v3.angle, static_cast(255 * v3.intensity), + static_cast(255 * v3.intensity)); } } @@ -235,7 +245,8 @@ void HierarchicalCostMap::erase_obsolete() cv::Mat HierarchicalCostMap::create_available_area_image(const Area & area) const { - cv::Mat available_area = cv::Mat::zeros(cv::Size(image_size_, image_size_), CV_8UC1); + cv::Mat available_area = + cv::Mat::zeros(cv::Size(static_cast(image_size_), static_cast(image_size_)), CV_8UC1); if (bounding_boxes_.empty()) return available_area; // Define current area diff --git a/localization/yabloc/yabloc_particle_filter/src/prediction/predictor.cpp b/localization/yabloc/yabloc_particle_filter/src/prediction/predictor.cpp index 8046d43dc34a3..701a2b8763fa3 100644 --- a/localization/yabloc/yabloc_particle_filter/src/prediction/predictor.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/prediction/predictor.cpp @@ -33,10 +33,13 @@ namespace yabloc::modularized_particle_filter Predictor::Predictor(const rclcpp::NodeOptions & options) : Node("predictor", options), - number_of_particles_(declare_parameter("num_of_particles")), - resampling_interval_seconds_(declare_parameter("resampling_interval_seconds")), - static_linear_covariance_(declare_parameter("static_linear_covariance")), - static_angular_covariance_(declare_parameter("static_angular_covariance")), + number_of_particles_(static_cast(declare_parameter("num_of_particles"))), + resampling_interval_seconds_( + static_cast(declare_parameter("resampling_interval_seconds"))), + static_linear_covariance_( + static_cast(declare_parameter("static_linear_covariance"))), + static_angular_covariance_( + static_cast(declare_parameter("static_angular_covariance"))), cov_xx_yy_{this->template declare_parameter>("cov_xx_yy")} { tf2_broadcaster_ = std::make_unique(*this); @@ -93,11 +96,11 @@ void Predictor::on_trigger_service( RCLCPP_INFO_STREAM(get_logger(), "yabloc particle filter is deactivated"); } - const bool before_activated_ = yabloc_activated_; + const bool before_activated = yabloc_activated_; yabloc_activated_ = request->data; response->success = true; - if (yabloc_activated_ && (!before_activated_)) { + if (yabloc_activated_ && (!before_activated)) { RCLCPP_INFO_STREAM(get_logger(), "restart particle filter"); if (latest_ekf_pose_ptr_) { on_initial_pose(latest_ekf_pose_ptr_); @@ -113,10 +116,11 @@ void Predictor::on_initial_pose(const PoseCovStamped::ConstSharedPtr initialpose // Publish initial pose marker auto position = initialpose->pose.pose.position; Eigen::Vector3f pos_vec3f; - pos_vec3f << position.x, position.y, position.z; + pos_vec3f << static_cast(position.x), static_cast(position.y), + static_cast(position.z); auto orientation = initialpose->pose.pose.orientation; - float theta = 2 * std::atan2(orientation.z, orientation.w); + auto theta = static_cast(2 * std::atan2(orientation.z, orientation.w)); Eigen::Vector3f tangent; tangent << std::cos(theta), std::sin(theta), 0; @@ -152,7 +156,7 @@ void Predictor::initialize_particles(const PoseCovStamped & initialpose) pose.position.x += noise.x(); pose.position.y += noise.y(); - float noised_yaw = util::normalize_radian(yaw + util::nrand(yaw_std)); + auto noised_yaw = static_cast(util::normalize_radian(yaw + util::nrand(yaw_std))); pose.orientation.w = std::cos(noised_yaw / 2.0); pose.orientation.x = 0.0; pose.orientation.y = 0.0; @@ -184,14 +188,14 @@ void Predictor::on_twist_cov(const TwistCovStamped::ConstSharedPtr twist_cov) } void Predictor::update_with_dynamic_noise( - ParticleArray & particle_array, const TwistCovStamped & twist, double dt) + ParticleArray & particle_array, const TwistCovStamped & twist, double dt) const { // linear & angular velocity - const float linear_x = twist.twist.twist.linear.x; - const float angular_z = twist.twist.twist.angular.z; + const auto linear_x = static_cast(twist.twist.twist.linear.x); + const auto angular_z = static_cast(twist.twist.twist.angular.z); // standard deviation of linear & angular velocity - const float std_linear_x = std::sqrt(twist.twist.covariance[6 * 0 + 0]); - const float std_angular_z = std::sqrt(twist.twist.covariance[6 * 5 + 5]); + const auto std_linear_x = static_cast(std::sqrt(twist.twist.covariance[6 * 0 + 0])); + const auto std_angular_z = static_cast(std::sqrt(twist.twist.covariance[6 * 5 + 5])); // 1[rad/s] = 60[deg/s] // 1[m/s] = 3.6[km/h] const float truncated_angular_std = @@ -272,7 +276,7 @@ void Predictor::on_weighted_particles(const ParticleArray::ConstSharedPtr weight try { particle_array = resampler_ptr_->add_weight_retroactively(particle_array, *weighted_particles_ptr); - } catch (const resampling_skip_exception & e) { + } catch (const ResamplingSkipException & e) { // Do nothing (just skipping the resample()) RCLCPP_INFO_STREAM(this->get_logger(), "skipped resampling"); } @@ -284,16 +288,16 @@ void Predictor::on_weighted_particles(const ParticleArray::ConstSharedPtr weight // Exit if previous resampling time is not valid. if (!previous_resampling_time_opt_.has_value()) { previous_resampling_time_opt_ = current_time; - throw resampling_skip_exception("previous resampling time is not valid"); + throw ResamplingSkipException("previous resampling time is not valid"); } if (current_time - previous_resampling_time_opt_.value() <= resampling_interval_seconds_) { - throw resampling_skip_exception("it is not time to resample"); + throw ResamplingSkipException("it is not time to resample"); } particle_array = resampler_ptr_->resample(particle_array); previous_resampling_time_opt_ = current_time; - } catch (const resampling_skip_exception & e) { + } catch (const ResamplingSkipException & e) { void(); // Do nothing (just skipping the resample()) } @@ -397,7 +401,7 @@ Predictor::PoseCovStamped Predictor::rectify_initial_pose( msg.pose.pose.orientation.z = std::sin(theta / 2); Eigen::Matrix2f cov; - cov << cov_xx_yy_.at(0), 0, 0, cov_xx_yy_.at(1); + cov << static_cast(cov_xx_yy_.at(0)), 0, 0, static_cast(cov_xx_yy_.at(1)); Eigen::Rotation2D r(theta); cov = r * cov * r.inverse(); diff --git a/localization/yabloc/yabloc_particle_filter/src/prediction/resampler.cpp b/localization/yabloc/yabloc_particle_filter/src/prediction/resampler.cpp index cc4cbc3730e0c..c8c3971ba85b2 100644 --- a/localization/yabloc/yabloc_particle_filter/src/prediction/resampler.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/prediction/resampler.cpp @@ -65,7 +65,7 @@ RetroactiveResampler::ParticleArray RetroactiveResampler::add_weight_retroactive { if (!check_weighted_particles_validity(weighted_particles)) { RCLCPP_ERROR_STREAM(logger_, "weighted_particles has invalid data"); - throw resampling_skip_exception("weighted_particles has invalid data"); + throw ResamplingSkipException("weighted_particles has invalid data"); } // Initialize corresponding index lookup table @@ -143,7 +143,7 @@ RetroactiveResampler::ParticleArray RetroactiveResampler::resample( // Copy particle to resampled variable resampled_particles.particles[m] = predicted_particles.particles[predicted_particle_index]; // Reset weight uniformly - resampled_particles.particles[m].weight = num_of_particles_inv; + resampled_particles.particles[m].weight = static_cast(num_of_particles_inv); // Make history resampling_history_[latest_resampling_generation_][m] = predicted_particle_index; } @@ -157,7 +157,7 @@ RetroactiveResampler::ParticleArray RetroactiveResampler::resample( return resampled_particles; } -double RetroactiveResampler::random_from_01_uniformly() const +double RetroactiveResampler::random_from_01_uniformly() { static std::default_random_engine engine(0); std::uniform_real_distribution dist(0.0, 1.0); diff --git a/localization/yabloc/yabloc_particle_filter/test/src/test_resampler.cpp b/localization/yabloc/yabloc_particle_filter/test/src/test_resampler.cpp index 124b0500e010e..915237b2b125c 100644 --- a/localization/yabloc/yabloc_particle_filter/test/src/test_resampler.cpp +++ b/localization/yabloc/yabloc_particle_filter/test/src/test_resampler.cpp @@ -22,20 +22,20 @@ namespace mpf = yabloc::modularized_particle_filter; using Particle = yabloc_particle_filter::msg::Particle; using ParticleArray = yabloc_particle_filter::msg::ParticleArray; -constexpr int PARTICLE_COUNT = 10; -constexpr int HISTORY_SIZE = 10; +constexpr int particle_count = 10; +constexpr int history_size = 10; TEST(ResamplerTestSuite, outOfHistory) { - mpf::RetroactiveResampler resampler(PARTICLE_COUNT, HISTORY_SIZE); + mpf::RetroactiveResampler resampler(particle_count, history_size); ParticleArray predicted; ParticleArray weighted; predicted.header.stamp = rclcpp::Time(0); predicted.id = 0; weighted.id = 0; - predicted.particles.resize(PARTICLE_COUNT); - weighted.particles.resize(PARTICLE_COUNT); + predicted.particles.resize(particle_count); + weighted.particles.resize(particle_count); for (auto & p : predicted.particles) p.weight = 1; for (auto & p : weighted.particles) p.weight = 1; @@ -64,7 +64,7 @@ TEST(ResamplerTestSuite, outOfHistory) } // Iterate resampling to fill all history - for (int t = 0; t < HISTORY_SIZE; ++t) { + for (int t = 0; t < history_size; ++t) { auto resampled = resampler.resample(predicted); EXPECT_EQ(resampled.id, t + 1); predicted = resampled; @@ -85,26 +85,26 @@ TEST(ResamplerTestSuite, outOfHistory) TEST(ResamplerTestSuite, simpleResampling) { - mpf::RetroactiveResampler resampler(PARTICLE_COUNT, HISTORY_SIZE); + mpf::RetroactiveResampler resampler(particle_count, history_size); ParticleArray predicted; predicted.header.stamp = rclcpp::Time(0); - predicted.particles.resize(PARTICLE_COUNT); + predicted.particles.resize(particle_count); predicted.id = 0; - for (int i = 0; i < PARTICLE_COUNT; ++i) predicted.particles.at(i).weight = 1; + for (int i = 0; i < particle_count; ++i) predicted.particles.at(i).weight = 1; ParticleArray weighted; - weighted.particles.resize(PARTICLE_COUNT); + weighted.particles.resize(particle_count); // Update by uniform distribution { // Weight weighted.id = 0; - for (int i = 0; i < PARTICLE_COUNT; ++i) weighted.particles.at(i).weight = 0.5; + for (int i = 0; i < particle_count; ++i) weighted.particles.at(i).weight = 0.5; ParticleArray array1 = resampler.add_weight_retroactively(predicted, weighted); // All weights must be equal - for (const auto & p : array1.particles) EXPECT_NEAR(p.weight, 1.0 / PARTICLE_COUNT, 1e-3); + for (const auto & p : array1.particles) EXPECT_NEAR(p.weight, 1.0 / particle_count, 1e-3); // Resample predicted = array1; @@ -117,10 +117,10 @@ TEST(ResamplerTestSuite, simpleResampling) { // Weight weighted.id = 0; - for (int i = 0; i < PARTICLE_COUNT; ++i) { + for (int i = 0; i < particle_count; ++i) { auto & p = predicted.particles.at(i); auto & q = weighted.particles.at(i); - if (i < PARTICLE_COUNT / 2) { + if (i < particle_count / 2) { p.pose.position.x = 1; q.weight = 2.0; } else { @@ -131,12 +131,12 @@ TEST(ResamplerTestSuite, simpleResampling) ParticleArray array1 = resampler.add_weight_retroactively(predicted, weighted); // All weight must match with following expectation - for (int i = 0; i < PARTICLE_COUNT; ++i) { + for (int i = 0; i < particle_count; ++i) { const auto & p = array1.particles.at(i); - if (i < PARTICLE_COUNT / 2) { - EXPECT_NEAR(p.weight, 2.0 / 1.5 / PARTICLE_COUNT, 1e-3f); + if (i < particle_count / 2) { + EXPECT_NEAR(p.weight, 2.0 / 1.5 / particle_count, 1e-3f); } else { - EXPECT_NEAR(p.weight, 1.0 / 1.5 / PARTICLE_COUNT, 1e-3f); + EXPECT_NEAR(p.weight, 1.0 / 1.5 / particle_count, 1e-3f); } } @@ -146,32 +146,33 @@ TEST(ResamplerTestSuite, simpleResampling) predicted = resampled; EXPECT_EQ(predicted.id, 2); - int centroid = 0; - for (const auto & p : predicted.particles) centroid += p.pose.position.x; + int centroid = std::accumulate( + predicted.particles.begin(), predicted.particles.end(), 0, + [](int sum, const auto & p) { return sum + static_cast(p.pose.position.x); }); EXPECT_GT(centroid, 0); } } TEST(ResamplerTestSuite, resamplingWithRetrogression) { - mpf::RetroactiveResampler resampler(PARTICLE_COUNT, HISTORY_SIZE); + mpf::RetroactiveResampler resampler(particle_count, history_size); ParticleArray predicted; predicted.header.stamp = rclcpp::Time(0); - predicted.particles.resize(PARTICLE_COUNT); + predicted.particles.resize(particle_count); predicted.id = 0; - for (int i = 0; i < PARTICLE_COUNT; ++i) { + for (int i = 0; i < particle_count; ++i) { auto & p = predicted.particles.at(i); p.weight = 1.0; - if (i < PARTICLE_COUNT / 2) + if (i < particle_count / 2) p.pose.position.x = 1; else p.pose.position.x = -1; } // Fill all history with biased weighted particles - for (int p = 0; p < HISTORY_SIZE; ++p) { + for (int p = 0; p < history_size; ++p) { auto resampled = resampler.resample(predicted); predicted = resampled; EXPECT_EQ(predicted.id, p + 1); @@ -179,18 +180,17 @@ TEST(ResamplerTestSuite, resamplingWithRetrogression) // Update by ancient measurement { - double before_centroid = 0; - for (const auto & p : predicted.particles) { - before_centroid += p.pose.position.x * p.weight; - } + double before_centroid = std::accumulate( + predicted.particles.begin(), predicted.particles.end(), 0.0, + [](double sum, const auto & p) { return sum + p.pose.position.x * p.weight; }); // Weight ParticleArray weighted; - weighted.particles.resize(PARTICLE_COUNT); + weighted.particles.resize(particle_count); weighted.id = 1; // ancient generation id - for (int i = 0; i < PARTICLE_COUNT; ++i) { + for (int i = 0; i < particle_count; ++i) { auto & q = weighted.particles.at(i); - if (i < PARTICLE_COUNT / 2) { + if (i < particle_count / 2) { q.weight = 2.0; } else { q.weight = 1.0; @@ -199,10 +199,10 @@ TEST(ResamplerTestSuite, resamplingWithRetrogression) predicted = resampler.add_weight_retroactively(predicted, weighted); - double after_centroid = 0; - for (const auto & p : predicted.particles) { - after_centroid += p.pose.position.x * p.weight; - } + double after_centroid = std::accumulate( + predicted.particles.begin(), predicted.particles.end(), 0.0, + [](double sum, const auto & p) { return sum + p.pose.position.x * p.weight; }); + EXPECT_TRUE(after_centroid > before_centroid); } } From 609df502dace1105d30fbe09140040bcc3f3f0ce Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Wed, 19 Jun 2024 09:29:29 +0900 Subject: [PATCH 007/217] feat(yabloc_pose_initializer): componentize yabloc_pose_initializer node (#7506) * change the node to component Signed-off-by: Kento Yabuuchi * remove useless node.cpp Signed-off-by: Kento Yabuuchi * add rclcpp_components as dependency Signed-off-by: Kento Yabuuchi --------- Signed-off-by: Kento Yabuuchi --- .../yabloc_pose_initializer/CMakeLists.txt | 20 ++++++++------ .../camera/camera_pose_initializer.hpp | 2 +- .../launch/yabloc_pose_initializer.launch.xml | 2 +- .../yabloc_pose_initializer/package.xml | 1 + .../camera/camera_pose_initializer_core.cpp | 8 ++++-- .../camera/camera_pose_initializer_node.cpp | 26 ------------------- 6 files changed, 21 insertions(+), 38 deletions(-) delete mode 100644 localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_node.cpp diff --git a/localization/yabloc/yabloc_pose_initializer/CMakeLists.txt b/localization/yabloc/yabloc_pose_initializer/CMakeLists.txt index 91b272b413c4c..2e6d31ae2f12b 100644 --- a/localization/yabloc/yabloc_pose_initializer/CMakeLists.txt +++ b/localization/yabloc/yabloc_pose_initializer/CMakeLists.txt @@ -20,18 +20,22 @@ find_package(OpenCV REQUIRED) # =================================================== # Executable # Camera -set(TARGET camera_pose_initializer_node) -ament_auto_add_executable(${TARGET} +ament_auto_add_library(${PROJECT_NAME} src/camera/lane_image.cpp src/camera/marker_module.cpp src/camera/projector_module.cpp src/camera/semantic_segmentation.cpp - src/camera/camera_pose_initializer_core.cpp - src/camera/camera_pose_initializer_node.cpp) -target_include_directories(${TARGET} PUBLIC include) -target_include_directories(${TARGET} SYSTEM PRIVATE ${EIGEN3_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS}) -target_link_libraries(${TARGET} ${PCL_LIBRARIES} Sophus::Sophus) -ament_target_dependencies(${TARGET} OpenCV) + src/camera/camera_pose_initializer_core.cpp) +target_include_directories(${PROJECT_NAME} PUBLIC include) +target_include_directories(${PROJECT_NAME} SYSTEM PRIVATE ${EIGEN3_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS}) +target_link_libraries(${PROJECT_NAME} ${PCL_LIBRARIES} Sophus::Sophus) +ament_target_dependencies(${PROJECT_NAME} OpenCV) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "yabloc::CameraPoseInitializer" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR MultiThreadedExecutor +) # =================================================== ament_auto_package(INSTALL_TO_SHARE config launch) diff --git a/localization/yabloc/yabloc_pose_initializer/include/yabloc_pose_initializer/camera/camera_pose_initializer.hpp b/localization/yabloc/yabloc_pose_initializer/include/yabloc_pose_initializer/camera/camera_pose_initializer.hpp index 979d1b370699e..eb2942a76e5df 100644 --- a/localization/yabloc/yabloc_pose_initializer/include/yabloc_pose_initializer/camera/camera_pose_initializer.hpp +++ b/localization/yabloc/yabloc_pose_initializer/include/yabloc_pose_initializer/camera/camera_pose_initializer.hpp @@ -43,7 +43,7 @@ class CameraPoseInitializer : public rclcpp::Node using LaneletMapBin = autoware_map_msgs::msg::LaneletMapBin; using RequestPoseAlignment = tier4_localization_msgs::srv::PoseWithCovarianceStamped; - CameraPoseInitializer(); + explicit CameraPoseInitializer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); private: const int angle_resolution_; diff --git a/localization/yabloc/yabloc_pose_initializer/launch/yabloc_pose_initializer.launch.xml b/localization/yabloc/yabloc_pose_initializer/launch/yabloc_pose_initializer.launch.xml index 83c2c8fe09287..964cc61420b9c 100644 --- a/localization/yabloc/yabloc_pose_initializer/launch/yabloc_pose_initializer.launch.xml +++ b/localization/yabloc/yabloc_pose_initializer/launch/yabloc_pose_initializer.launch.xml @@ -2,7 +2,7 @@ - + diff --git a/localization/yabloc/yabloc_pose_initializer/package.xml b/localization/yabloc/yabloc_pose_initializer/package.xml index 7ed16c9a8b82d..22e9bdd0dd553 100644 --- a/localization/yabloc/yabloc_pose_initializer/package.xml +++ b/localization/yabloc/yabloc_pose_initializer/package.xml @@ -22,6 +22,7 @@ lanelet2_extension libopencv-dev rclcpp + rclcpp_components sensor_msgs tier4_localization_msgs visualization_msgs diff --git a/localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_core.cpp b/localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_core.cpp index 083e7dd5bcd43..dd97ea2ad888f 100644 --- a/localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_core.cpp +++ b/localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_core.cpp @@ -26,8 +26,9 @@ namespace yabloc { -CameraPoseInitializer::CameraPoseInitializer() -: Node("camera_pose_initializer"), angle_resolution_(declare_parameter("angle_resolution")) +CameraPoseInitializer::CameraPoseInitializer(const rclcpp::NodeOptions & options) +: Node("camera_pose_initializer", options), + angle_resolution_(declare_parameter("angle_resolution")) { using std::placeholders::_1; using std::placeholders::_2; @@ -216,3 +217,6 @@ CameraPoseInitializer::PoseCovStamped CameraPoseInitializer::create_rectified_in } } // namespace yabloc + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(yabloc::CameraPoseInitializer) diff --git a/localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_node.cpp b/localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_node.cpp deleted file mode 100644 index 2bcfe073351f8..0000000000000 --- a/localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_node.cpp +++ /dev/null @@ -1,26 +0,0 @@ -// 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 "yabloc_pose_initializer/camera/camera_pose_initializer.hpp" - -int main(int argc, char * argv[]) -{ - rclcpp::init(argc, argv); - auto node = std::make_shared(); - rclcpp::executors::MultiThreadedExecutor executor; - executor.add_node(node); - executor.spin(); - rclcpp::shutdown(); - return 0; -} From b00373351347d91bb9ba55cd9de6a96398dceabc Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Wed, 19 Jun 2024 09:29:45 +0900 Subject: [PATCH 008/217] feat(yabloc_monitor): componentize yabloc_monitor node (#7509) * change node to component Signed-off-by: Kento Yabuuchi * fix launch file & cmake Signed-off-by: Kento Yabuuchi --------- Signed-off-by: Kento Yabuuchi --- .../yabloc/yabloc_monitor/CMakeLists.txt | 10 +++++-- .../launch/yabloc_monitor.launch.xml | 2 +- .../yabloc/yabloc_monitor/package.xml | 1 + .../src/yabloc_monitor_core.cpp | 6 +++- .../src/yabloc_monitor_core.hpp | 2 +- .../src/yabloc_monitor_node.cpp | 28 ------------------- 6 files changed, 15 insertions(+), 34 deletions(-) delete mode 100644 localization/yabloc/yabloc_monitor/src/yabloc_monitor_node.cpp diff --git a/localization/yabloc/yabloc_monitor/CMakeLists.txt b/localization/yabloc/yabloc_monitor/CMakeLists.txt index aa1515661b2f6..7267cda53714f 100644 --- a/localization/yabloc/yabloc_monitor/CMakeLists.txt +++ b/localization/yabloc/yabloc_monitor/CMakeLists.txt @@ -4,12 +4,16 @@ project(yabloc_monitor) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(yabloc_monitor - src/yabloc_monitor_node.cpp +ament_auto_add_library(${PROJECT_NAME} src/yabloc_monitor_core.cpp src/availability_module.cpp ) -ament_target_dependencies(yabloc_monitor) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "YabLocMonitor" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR SingleThreadedExecutor +) ament_auto_package( INSTALL_TO_SHARE diff --git a/localization/yabloc/yabloc_monitor/launch/yabloc_monitor.launch.xml b/localization/yabloc/yabloc_monitor/launch/yabloc_monitor.launch.xml index cf9f73977d35d..3073208e2e1a2 100644 --- a/localization/yabloc/yabloc_monitor/launch/yabloc_monitor.launch.xml +++ b/localization/yabloc/yabloc_monitor/launch/yabloc_monitor.launch.xml @@ -1,7 +1,7 @@ - + diff --git a/localization/yabloc/yabloc_monitor/package.xml b/localization/yabloc/yabloc_monitor/package.xml index 22a5d0eded6b6..a42a734dbab31 100644 --- a/localization/yabloc/yabloc_monitor/package.xml +++ b/localization/yabloc/yabloc_monitor/package.xml @@ -20,6 +20,7 @@ diagnostic_updater geometry_msgs rclcpp + rclcpp_components ament_cmake_gtest ament_lint_auto diff --git a/localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.cpp b/localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.cpp index 876b86fd2bc9e..31e6ec9c51e7a 100644 --- a/localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.cpp +++ b/localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.cpp @@ -18,7 +18,8 @@ #include -YabLocMonitor::YabLocMonitor() : Node("yabloc_monitor"), updater_(this) +YabLocMonitor::YabLocMonitor(const rclcpp::NodeOptions & options) +: Node("yabloc_monitor", options), updater_(this) { updater_.setHardwareID(get_name()); updater_.add("yabloc_status", this, &YabLocMonitor::update_diagnostics); @@ -46,3 +47,6 @@ void YabLocMonitor::update_diagnostics(diagnostic_updater::DiagnosticStatusWrapp stat.summary(diagnostic_msgs::msg::DiagnosticStatus::ERROR, "NG"); } } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(YabLocMonitor) diff --git a/localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.hpp b/localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.hpp index 8b8b937da205b..5dd46d63de6f2 100644 --- a/localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.hpp +++ b/localization/yabloc/yabloc_monitor/src/yabloc_monitor_core.hpp @@ -25,7 +25,7 @@ class YabLocMonitor : public rclcpp::Node { public: - YabLocMonitor(); + explicit YabLocMonitor(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); private: void update_diagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat); diff --git a/localization/yabloc/yabloc_monitor/src/yabloc_monitor_node.cpp b/localization/yabloc/yabloc_monitor/src/yabloc_monitor_node.cpp deleted file mode 100644 index 9b58325c852ea..0000000000000 --- a/localization/yabloc/yabloc_monitor/src/yabloc_monitor_node.cpp +++ /dev/null @@ -1,28 +0,0 @@ -// Copyright 2023 TIER IV -// -// 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 "yabloc_monitor_core.hpp" - -#include - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - rclcpp::NodeOptions node_options; - auto node = std::make_shared(); - - rclcpp::spin(node); - - return 0; -} From ee4442baf7183b2d0a66305a9443016871768662 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 19 Jun 2024 10:26:41 +0900 Subject: [PATCH 009/217] fix(multi_object_tracker): fix uselessCallsSubstr warning (#7556) Signed-off-by: Ryuta Kambe --- .../multi_object_tracker/src/debugger/debug_object.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/perception/multi_object_tracker/src/debugger/debug_object.cpp b/perception/multi_object_tracker/src/debugger/debug_object.cpp index e6a0b6242a168..fe6d3d5c75564 100644 --- a/perception/multi_object_tracker/src/debugger/debug_object.cpp +++ b/perception/multi_object_tracker/src/debugger/debug_object.cpp @@ -236,8 +236,9 @@ void TrackerObjectDebugger::draw( stream << std::fixed << std::setprecision(0) << object_data_front.existence_vector[i] * 100; existence_probability_text += channel_names_[i] + stream.str() + ":"; } - existence_probability_text = - existence_probability_text.substr(0, existence_probability_text.size() - 1); + if (!existence_probability_text.empty()) { + existence_probability_text.pop_back(); + } existence_probability_text += "\n" + object_data_front.uuid_str.substr(0, 6); text_marker.text = existence_probability_text; From 6b9d5c87306988ac2253c807e5371e9a5e50501f Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 19 Jun 2024 10:27:34 +0900 Subject: [PATCH 010/217] fix(lidar_apollo_segmentation_tvm): fix unpreciseMathCall warning (#7558) Signed-off-by: Ryuta Kambe --- perception/lidar_apollo_segmentation_tvm/src/log_table.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/lidar_apollo_segmentation_tvm/src/log_table.cpp b/perception/lidar_apollo_segmentation_tvm/src/log_table.cpp index a4b967de2e9bc..de2f1734e0733 100644 --- a/perception/lidar_apollo_segmentation_tvm/src/log_table.cpp +++ b/perception/lidar_apollo_segmentation_tvm/src/log_table.cpp @@ -46,7 +46,7 @@ float calcApproximateLog(float num) return log_table.data[integer_num]; } } - return std::log(1.0f + num); + return std::log1p(num); } } // namespace lidar_apollo_segmentation_tvm } // namespace perception From 9fbc30c2153ebb0114292f5da297bcc2d030e78a Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 19 Jun 2024 10:35:22 +0900 Subject: [PATCH 011/217] fix(mrm_handler): fix multiCondition warning (#7543) Signed-off-by: Ryuta Kambe --- system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp index 326fbb392fd35..b50bdc4f6a766 100644 --- a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp +++ b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp @@ -91,7 +91,7 @@ void MrmHandler::onOperationModeAvailability( if (!is_emergency_holding_) { if (msg->autonomous) { stamp_autonomous_become_unavailable_.reset(); - } else if (!msg->autonomous) { + } else { if (!stamp_autonomous_become_unavailable_.has_value()) { stamp_autonomous_become_unavailable_.emplace(this->now()); } else { From e668be91933b18c637287fb7ec8d73d640935789 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 19 Jun 2024 11:03:08 +0900 Subject: [PATCH 012/217] fix(.gitignore): add config to ignore directory which is made by prettier (#7567) Signed-off-by: satoshi-ota --- .gitignore | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.gitignore b/.gitignore index 5ce2c268169c8..757d2d8a09bed 100644 --- a/.gitignore +++ b/.gitignore @@ -13,3 +13,6 @@ log/ # Python *.pyc + +#prettier +node_modules/ From f4f892e94e0583720b59188ee91ceb684fdd5c2a Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 19 Jun 2024 11:28:31 +0900 Subject: [PATCH 013/217] fix(simple_planning_simulator): fix duplicateBranch warnings (#7574) * fix(simple_planning_simulator): fix duplicateBranch warnings Signed-off-by: Ryuta Kambe * style(pre-commit): autofix --------- Signed-off-by: Ryuta Kambe Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../vehicle_model/sim_model_delay_steer_acc_geared.cpp | 4 +--- .../sim_model_delay_steer_map_acc_geared.cpp | 8 +------- .../vehicle_model/sim_model_ideal_steer_acc_geared.cpp | 4 +--- 3 files changed, 3 insertions(+), 13 deletions(-) diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp index 26b252805db47..aada6687baef8 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp @@ -177,9 +177,7 @@ void SimModelDelaySteerAccGeared::updateStateWithGear( if (state(IDX::VX) > 0.0) { setStopState(); } - } else if (gear == GearCommand::PARK) { - setStopState(); - } else { + } else { // including 'gear == GearCommand::PARK' setStopState(); } } diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp index fe847cba946a1..b987f74db0436 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp @@ -159,13 +159,7 @@ void SimModelDelaySteerMapAccGeared::updateStateWithGear( state(IDX::YAW) = prev_state(IDX::YAW); state(IDX::ACCX) = (state(IDX::VX) - prev_state(IDX::VX)) / std::max(dt, 1.0e-5); } - } else if (gear == GearCommand::PARK) { - state(IDX::VX) = 0.0; - state(IDX::X) = prev_state(IDX::X); - state(IDX::Y) = prev_state(IDX::Y); - state(IDX::YAW) = prev_state(IDX::YAW); - state(IDX::ACCX) = (state(IDX::VX) - prev_state(IDX::VX)) / std::max(dt, 1.0e-5); - } else { + } else { // including 'gear == GearCommand::PARK' state(IDX::VX) = 0.0; state(IDX::X) = prev_state(IDX::X); state(IDX::Y) = prev_state(IDX::Y); diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp index c2297f1fd1d73..46538778bd1b1 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp @@ -109,9 +109,7 @@ void SimModelIdealSteerAccGeared::updateStateWithGear( if (state(IDX::VX) > 0.0) { setStopState(); } - } else if (gear == GearCommand::PARK) { - setStopState(); - } else { + } else { // including 'gear == GearCommand::PARK' setStopState(); } // calculate acc from velocity diff From 75081037faa1652e09c2acdef3a62b0d1a54fc94 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Wed, 19 Jun 2024 12:29:33 +0900 Subject: [PATCH 014/217] chore(topic_state_monitor): enrich error log message (#7236) Signed-off-by: Takamasa Horibe --- .../src/topic_state_monitor_core.cpp | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/system/topic_state_monitor/src/topic_state_monitor_core.cpp b/system/topic_state_monitor/src/topic_state_monitor_core.cpp index 68fa3764d8ecd..ff58a0c6fd584 100644 --- a/system/topic_state_monitor/src/topic_state_monitor_core.cpp +++ b/system/topic_state_monitor/src/topic_state_monitor_core.cpp @@ -154,8 +154,8 @@ void TopicStateMonitorNode::checkTopicStatus(diagnostic_updater::DiagnosticStatu const auto print_warn = [&](const std::string & msg) { RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 3000, "%s", msg.c_str()); }; - const auto print_debug = [&](const std::string & msg) { - RCLCPP_DEBUG_THROTTLE(get_logger(), *get_clock(), 3000, "%s", msg.c_str()); + const auto print_info = [&](const std::string & msg) { + RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 3000, "%s", msg.c_str()); }; // Judge level @@ -166,19 +166,21 @@ void TopicStateMonitorNode::checkTopicStatus(diagnostic_updater::DiagnosticStatu } else if (topic_status == TopicStatus::NotReceived) { level = DiagnosticStatus::ERROR; stat.add("status", "NotReceived"); - print_debug(node_param_.topic + " has not received."); + print_info(node_param_.topic + " has not received. Set ERROR in diagnostics."); } else if (topic_status == TopicStatus::WarnRate) { level = DiagnosticStatus::WARN; stat.add("status", "WarnRate"); - print_warn(node_param_.topic + " topic rate has dropped to the warning level."); + print_warn( + node_param_.topic + " topic rate has dropped to the warning level. Set WARN in diagnostics."); } else if (topic_status == TopicStatus::ErrorRate) { level = DiagnosticStatus::ERROR; stat.add("status", "ErrorRate"); - print_warn(node_param_.topic + " topic rate has dropped to the error level."); + print_warn( + node_param_.topic + " topic rate has dropped to the error level. Set ERROR in diagnostics."); } else if (topic_status == TopicStatus::Timeout) { level = DiagnosticStatus::ERROR; stat.add("status", "Timeout"); - print_warn(node_param_.topic + " topic is timeout."); + print_warn(node_param_.topic + " topic is timeout. Set ERROR in diagnostics."); } // Add key-value From f6d2c5990c9ad5c73f658110c870ec38de73134f Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 19 Jun 2024 14:04:03 +0900 Subject: [PATCH 015/217] docs(bpp_static_obstacle_avoidance): add documentation (#7554) * fix: package path Signed-off-by: satoshi-ota * docs: add explanation of lateral margin Signed-off-by: satoshi-ota * fix: typo Signed-off-by: satoshi-ota * fix: wrong description Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- planning/.pages | 28 +- .../README.md | 98 ++- .../images/avoidance_design.fig.drawio.svg | 668 ------------------ .../images/intersection_problem.drawio.svg | 179 ----- .../images/path_generation/adjust_margin.png | Bin 0 -> 79777 bytes .../images/path_generation/do_nothing.png | Bin 0 -> 67002 bytes .../images/path_generation/hard_margin.png | Bin 0 -> 148426 bytes .../insufficient_drivable_space.png | Bin 0 -> 131540 bytes .../images/path_generation/lateral.png | Bin 81586 -> 100402 bytes .../images/path_generation/margin.png | Bin 102350 -> 102313 bytes .../images/path_generation/must_avoid.png | Bin 0 -> 70762 bytes .../images/path_generation/pass_through.png | Bin 0 -> 68871 bytes .../images/path_generation/soft_hard.png | Bin 0 -> 69601 bytes .../images/target_vehicle_selection.svg | 296 -------- .../traffic_light/limit_shift_length.png | Bin 0 -> 121671 bytes .../traffic_light/return_after_stop_line.png | Bin 0 -> 118102 bytes .../traffic_light/return_before_stop_line.png | Bin 0 -> 118035 bytes .../traffic_light/shift_from_current_pos.png | Bin 0 -> 119341 bytes .../traffic_light/shift_from_stop_line.png | Bin 0 -> 111667 bytes .../images/traffic_light/traffic_light.png | Bin 0 -> 114927 bytes 20 files changed, 99 insertions(+), 1170 deletions(-) delete mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance_design.fig.drawio.svg delete mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/intersection_problem.drawio.svg create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/adjust_margin.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/do_nothing.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/hard_margin.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/insufficient_drivable_space.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/must_avoid.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/pass_through.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/soft_hard.png delete mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/target_vehicle_selection.svg create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/limit_shift_length.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/return_after_stop_line.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/return_before_stop_line.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/shift_from_current_pos.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/shift_from_stop_line.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/traffic_light.png diff --git a/planning/.pages b/planning/.pages index 67c70b928bdf8..bda94919fc352 100644 --- a/planning/.pages +++ b/planning/.pages @@ -1,22 +1,22 @@ nav: - 'Introduction': planning - 'Behavior Path Planner': - - 'About Behavior Path': planning/autoware_behavior_path_planner + - 'About Behavior Path': planning/behavior_path_planner/autoware_behavior_path_planner - 'Concept': - - 'Planner Manager': planning/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design - - 'Scene Module Interface': planning/autoware_behavior_path_planner/docs/behavior_path_planner_interface_design - - 'Path Generation': planning/autoware_behavior_path_planner_common/docs/behavior_path_planner_path_generation_design - - 'Collision Assessment/Safety Check': planning/autoware_behavior_path_planner_common/docs/behavior_path_planner_safety_check - - 'Dynamic Drivable Area': planning/autoware_behavior_path_planner_common/docs/behavior_path_planner_drivable_area_design - - 'Turn Signal': planning/autoware_behavior_path_planner_common/docs/behavior_path_planner_turn_signal_design + - 'Planner Manager': planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design + - 'Scene Module Interface': planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_interface_design + - 'Path Generation': planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_path_generation_design + - 'Collision Assessment/Safety Check': planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_safety_check + - 'Dynamic Drivable Area': planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_drivable_area_design + - 'Turn Signal': planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_turn_signal_design - 'Scene Module': - - 'Avoidance by Lane Change': planning/autoware_behavior_path_avoidance_by_lane_change_module - - 'Dynamic Obstacle Avoidance': planning/autoware_behavior_path_dynamic_obstacle_avoidance_module - - 'Goal Planner': planning/autoware_behavior_path_goal_planner_module - - 'Lane Change': planning/autoware_behavior_path_lane_change_module - - 'Side Shift': planning/autoware_behavior_path_side_shift_module - - 'Start Planner': planning/autoware_behavior_path_start_planner_module - - 'Static Obstacle Avoidance': planning/autoware_behavior_path_static_obstacle_avoidance_module + - 'Avoidance by Lane Change': planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module + - 'Dynamic Obstacle Avoidance': planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module + - 'Goal Planner': planning/behavior_path_planner/autoware_behavior_path_goal_planner_module + - 'Lane Change': planning/behavior_path_planner/autoware_behavior_path_lane_change_module + - 'Side Shift': planning/behavior_path_planner/autoware_behavior_path_side_shift_module + - 'Start Planner': planning/behavior_path_planner/autoware_behavior_path_start_planner_module + - 'Static Obstacle Avoidance': planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module - 'Behavior Velocity Planner': - 'About Behavior Velocity': planning/behavior_velocity_planner/autoware_behavior_velocity_planner - 'Template for Custom Module': planning/behavior_velocity_planner/autoware_behavior_velocity_template_module diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md index bc70c1fdd5c6a..33abc8eaf40ed 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/README.md @@ -8,7 +8,7 @@ This is a rule-based avoidance module, which is running based on perception outp ![fig](./images/purpose/avoidance.png) -This module has [RTC interface](../autoware_rtc_interface/README.md), and user can select operation mode from MANUAL/AUTO depending on the vehicle sensor performance. If user selects MANUAL mode, this module outputs avoidance path as candidate and waits operator approval. In the case where the sensor/perception performance is not enough and false positive maybe occurs, we recommend to use this module with MANUAL mode in order to prevent unnecessary avoidance maneuver. +This module has [RTC interface](../../autoware_rtc_interface/README.md), and user can select operation mode from MANUAL/AUTO depending on the vehicle sensor performance. If user selects MANUAL mode, this module outputs avoidance path as candidate and waits operator approval. In the case where the sensor/perception performance is not enough and false positive maybe occurs, we recommend to use this module with MANUAL mode in order to prevent unnecessary avoidance maneuver. On the other hand, if user selects AUTO mode, this module modifies current following path without operator approval. If the sensor/perception performance is good enough, user can use this module with AUTO mode. @@ -83,7 +83,7 @@ partition fillEgoStatus() { note right This module has following status: - RUNNING: target object is still remaining. Or, the ego hasn't returned original lane. - - CANCEL: taget obejct has gone. And, the ego hasn't initiated avoidance maneuver. + - CANCEL: target object has gone. And, the ego hasn't initiated avoidance maneuver. - SUCCEEDED: the ego finishes avoiding all objects and returns original lane. end note @@ -122,7 +122,7 @@ if (Is there object that is potentially avoidable?) then (yes) :return true; note right Sometimes, we meet the situation where there is enough space to avoid - but ego speed is to high to avoid target obejct under lateral jerk constraints. + but ego speed is to high to avoid target object under lateral jerk constraints. This module keeps running in this case in order to decelerate ego speed. end note stop @@ -747,6 +747,59 @@ The longitudinal positions depends on envelope polygon, ego vehicle specificatio ![fig](./images/path_generation/margin.png) +### Lateral margin + +As mentioned above, user can adjust lateral margin by changing following two types parameter. The `soft_margin` is a soft constraint parameter for lateral margin. The `hard_margin` and `hard_margin_for_parked_vehicle` are hard constraint parameter. + +```yaml + car: + ... + lateral_margin: + soft_margin: 0.3 # [m] + hard_margin: 0.2 # [m] + hard_margin_for_parked_vehicle: 0.7 # [m] +``` + +Basically, this module tries to generate avoidance path in order to keep lateral distance, which is sum of `soft_margin` and `hard_margin`/`hard_margin_for_parked_vehicle`, from avoidance target object. + +![fig](./images/path_generation/soft_hard.png) + +But if there isn't enough space to keep `soft_margin` distance, this module shortens soft constraint lateral margin. The parameter `soft_margin` is a maximum value of soft constraint, and actual soft margin can be a value between 0.0 and `soft_margin`. On the other hand, this module definitely keeps `hard_margin` or `hard_margin_for_parked_vehicle` depending on the situation. Thus, the minimum value of total lateral margin is `hard_margin`/`hard_margin_for_parked_vehicle`, and the maximum value is the sum of `hard_margin`/`hard_margin_for_parked_vehicle` and `soft_margin`. + +Following figure shows the situation where this module shortens lateral soft constraint in order not to drive opposite direction lane when user set a parameter `use_opposite_lane` to `false`. + +![fig](./images/path_generation/adjust_margin.png) + +This module avoids not only parked vehicle but also non-parked vehicle which stops temporarily for some reason (e.g. waiting for traffic light to change red to green.). Additionally, this module has two types hard margin parameters, `hard_margin` and `hard_margin_for_parked_vehicle` and judges if it's a parked vehicle or not for each vehicles because it takes the risk of vehicle doors opening suddenly and people getting out from parked vehicle into consideration. + +Basically, user had better make `hard_margin_for_parked_vehicle` larger than `hard_margin` to prevent collision with doors or people who suddenly get out from vehicle. + +On the other hand, this module has only one parameter `soft_margin` for soft lateral margin constraint. + +![fig](./images/path_generation/hard_margin.png) + +As the hard margin parameters the distance which the user definitely want to keep, they are used in the logic to check whether the ego can pass side of the target object without avoidance maneuver as well. + +If the lateral distance is less than `hard_margin`/`hard_margin_for_parked_vehicle` when assuming that the ego follows current lane without avoidance maneuver, this module thinks the ego can not pass the side of the object safely and the ego must avoid it. In this case, this module inserts stop point until the avoidance maneuver is allowed to execute so that the ego can avoid the object after approval. (e.g. The ego keeps stopping in front of such a object until operator approves avoidance maneuver if user uses this module in MANUAL mode.) + +![fig](./images/path_generation/must_avoid.png) + +On the other hand, if the lateral distance is larger than `hard_margin`/`hard_margin_for_parked_vehicle`, this module doesn't insert stop point even when it's waiting approval because it thinks it's possible to pass the side of the object safely. + +![fig](./images/path_generation/pass_through.png) + +### When there is not enough space + +This module inserts stop point only when the ego can potentially avoid the object. So, if it is not able to keep distance more than `hard_margin`/`hard_margin_for_parked_vehicle`, this module does nothing. Following figure shows the situation where this module is not able to keep enough lateral distance when user set a parameter `use_opposite_lane` to `false`. + +![fig](./images/path_generation/do_nothing.png) + +!!! info + + In this situation, obstacle stop feature in [obstacle_cruise_planner](../../autoware_obstacle_cruise_planner/README.md) is responsible for ego vehicle safety. + +![fig](./images/path_generation/insufficient_drivable_space.png) + ### Shift length calculation The lateral shift length is sum of `overhang_distance`, lateral margin, whose value is set in config file, and the half of ego vehicle width defined in `vehicle_info.param.yaml`. On the other hand, the module limits the shift length depending on the space which the module can use for avoidance maneuver and the parameters `soft_drivable_bound_margin` `hard_drivable_bound_margin`. Basically, the shift length is limited so that the ego doesn't get closer than `soft_drivable_bound_margin` to drivable boundary. But it allows to relax the threshold `soft_drivable_bound_margin` to `hard_drivable_bound_margin` when the road is narrow. @@ -804,6 +857,34 @@ The `prepare_length` is calculated as the product of ego speed and `max_prepare_ ![fig](./images/path_generation/shift_line.png) +## Planning at RED traffic light + +This module takes traffic light information into account so that the ego can behave properly. Sometimes, the ego straddles lane boundary but we want to prevent the ego from stopping in front of red traffic signal in such a situation. This is because the ego will block adjacent lane and it's inconvenient for other vehicles. + +![fig](./images/traffic_light/traffic_light.png) + +So, this module controls shift length and shift start/end point in order to prevent above situation. + +### Control shift length + +At first, if the ego hasn't initiated avoidance maneuver yet, this module limits maximum shift length and uses **ONLY** current lane during red traffic signal. This prevents the ego from blocking other vehicles even if this module executes avoidance maneuver and the ego is caught by red traffic signal. + +![fig](./images/traffic_light/limit_shift_length.png) + +### Control avoidance shift start point + +Additionally, if the target object is farther than stop line for traffic light, this module set avoidance shift start point on the stop line in order to prevent the ego from stopping by red traffic signal in middle of avoidance maneuver. + +![fig](./images/traffic_light/shift_from_current_pos.png) +![fig](./images/traffic_light/shift_from_stop_line.png) + +### Control return shift end point + +If the ego has already initiated avoidance maneuver, this module tries to set return shift end point on the stop line. + +![fig](./images/traffic_light/return_after_stop_line.png) +![fig](./images/traffic_light/return_before_stop_line.png) + ## Safety check This feature can be enable by setting following parameter to `true`. @@ -915,15 +996,6 @@ use_freespace_areas: true ## Future extensions / Unimplemented parts -- **Planning on the intersection** - - If it is known that the ego vehicle is going to stop in the middle of avoidance execution (for example, at a red traffic light), sometimes the avoidance should not be executed until the vehicle is ready to move. This is because it is impossible to predict how the environment will change during the stop. This is especially important at intersections. - -![fig](./images/intersection_problem.drawio.svg) - -- **Safety Check** - - - In the current implementation, it is only the jerk limit that permits the avoidance execution. It is needed to consider the collision with other vehicles when change the path shape. - - **Consideration of the speed of the avoidance target** - In the current implementation, only stopped vehicle is targeted as an avoidance target. It is needed to support the overtaking function for low-speed vehicles, such as a bicycle. (It is actually possible to overtake the low-speed objects by changing the parameter, but the logic is not supported and thus the safety cannot be guaranteed.) @@ -1146,4 +1218,4 @@ The shift points are modified by a filtering process in order to get the expecte The avoidance specific parameter configuration file can be located at `src/autoware/launcher/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml`. -{{ json_to_markdown("planning/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json") }} +{{ json_to_markdown("planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json") }} diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance_design.fig.drawio.svg b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance_design.fig.drawio.svg deleted file mode 100644 index d0563e9f2f542..0000000000000 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance_design.fig.drawio.svg +++ /dev/null @@ -1,668 +0,0 @@ - - - - - - - - - - - - - -
-
-
- Calculate avoidance shift -
- from target obstacles -
-
-
-
- Calculate avoidance shift... -
-
- - - - - - - - - - - - - - - - - -
-
-
- shift length = avoid margin -
- + ego vehicle width / 2 -
-
-
-
- shift length = avoid marg... -
-
- - - - - - -
-
-
- The shift gets sharp -
- if it is close to ego -
- up to the maximum jerk. -
-
-
-
- The shift gets sharp... -
-
- - - - - - -
-
-
- The avoidance shift is basically calculated from nominal jerk ego vehicle speed. -
-
-
-
- The avoidance shift is ba... -
-
- - - - - - - -
-
-
- This is not a target vehicle -
- since it is on the center line. -
-
-
-
- This is not a target vehi... -
-
- - - - -
-
-
- The direction of avoidance is determined by the position of obstacles, whether it is on the left or right of the center line. -
-
-
-
- The direction of avoidanc... -
-
- - - - - - -
-
-
- Merge all shifts -
-
-
-
- Merge all shifts -
-
- - - - - - - - - - - - - - -
-
-
- For multiple avoidance shifts in the same direction, take the largest one. -
-
-
-
- For multiple avoidance sh... -
-
- - - - - -
-
-
- For multiple avoidance shifts in the different direction, take the sum of both. -
-
-
-
- For multiple avoidance... -
-
- - - - - - - - - - - - -
-
-
- Pick up the shift points where the gradient of the shift changes. -
-
-
-
- Pick up the shift points... -
-
- - - - - - - - - - - - - -
-
-
- Trim shift points -
-
-
-
- Trim shift points -
-
- - - - - - -
-
-
- Start avoiding as soon as getting back to the center line. Remove these points to avoid obstacles at the same shift. -
-
-
-
- Start avoiding as soon a... -
-
- - - - - - -
-
-
- Points that do not have a large effect on the overall shift will be deleted. -
-
-
-
- Points that do not have... -
-
- - - - - - - - - - - - - - - - - - - - - -
-
-
- Generate path -
-
-
-
- Generate path -
-
- - - - -
-
-
- Each shift points are connected by a Clothoid-like curve. -
-
-
-
- Each shift points... -
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/intersection_problem.drawio.svg b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/intersection_problem.drawio.svg deleted file mode 100644 index 67d21dfd78a09..0000000000000 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/intersection_problem.drawio.svg +++ /dev/null @@ -1,179 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-
Parked vehicle
-
-
-
- Parked vehicle -
-
- - - -
-
-
- Normal avoidance will block the opposite lane -
-
-
-
- Normal avoidance will block the opposite lane -
-
- - - -
-
-
- So, it should avoid inside the ego lane -
-
-
-
- So, it should avoid inside the ego lan... -
-
- - - -
-
-
- Or, wait behind the object -
- until the traffic light turns green. -
-
-
-
- Or, wait behind the object... -
-
-
- - - - Viewer does not support full SVG 1.1 - - -
diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/adjust_margin.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/adjust_margin.png new file mode 100644 index 0000000000000000000000000000000000000000..ccb1f8c671234e87703762db04c45ddfe3685446 GIT binary patch literal 79777 zcmeFZ2|U!>|3BWUg;KXgQdF)~!kEF3Erev>*DwZSAI3V?T$dK1lvLJoqX@~?l%-O3 zCJ9-hY-1N=$=LqqJ!49x`?;Ub|NGf~pSt%^Gv|HY=e*AA^*XQZJkOk0S5?@wared* zD^_e$Jb6NM#fr6cD^{#xTh9PmR=BRS1Anh{(NvIGkzTW>Z^a6QkFIk1t`447Hujb) zxDc|mPh4=AHP*$I3vq%A4o5jT@mbiQFgTQh3!kHGw=aV|Dk$HgTG@(J<@AZXNDx}q?& zW-mn*w5x}kgQ*-$Usl15*WOtfj0e5#ig&W4^}%4V7<(`y)arspfsa(i3D8>1u{aA$ z9Ic7^DngD6CJnkm|084{H@V~xTp|cAQR&4GGP2YUa4s2<#X)Tr8L#GS z;jXW*CWA0_a&pJHtDdk>fMmwCbPoDV4xS1)l#{gz*22;rOlRRqn+yRLSzM6?evxn( z3?V`z9)qLLv^X);pk?DlU*h7M7&jXWOP9sBX>Yn>vG%SuPG2{ov5tIl0!vTGzZUdCP8(r~eI_!$4>o8ykRm*K0s1lF?TgKG}@Ld^YZfUQMb+K`!Z6I^3 zt1H$4>|%T9feZ?5hrwap94%zA_E<>wEiA22ZuWp(pGT0kx4}SL&lT$gT2U@eG`+C0 z@q~{iG_~5HBNWuIK57_Hq(5 zSFm?OdBJQ@CpBT{6Igd;gayI^FN9FR3%R2m(C#YQc0y`eqO^W^MU16_fQz}Kim0N4 zHO%6qw6HQ>6ug0Uv+z=JGe?|qRQ6KzP&py(jz$T{oWm^rn;t358@Z8Dp1k6TTL0-sE|CE)AjUu2^T|v{{&`|~YbW#;&spo00ZX;xC zep1C%Mc>sH(CeYBFJo1hC-sJfu^WjqY@HL;4ef+A=K zU0VxT8LXk6y(8)*cy3EwGXkZj2}6N(16~Ly+sb(YK0y3&Q`J($fHAGn2#CK_8t{rX zz|6>iS*fekfmV4!P(&I2nMVp}+T8Z1+zs?Jy_TO>&PMShZH-_aFJ)UD@ZAp31IYsV zj1g6|5flJ)fLY|d&_Ew(JW{by_5$mm@>a%9UF(#qincUN+1AcQ#a7x)RS)B;iWkJI z=o`4I=wT4bwu+t>w(=-*EtsdOtRPH9%fkaD3!}B$z&ueW&~7TW@^BShCs$={IWUff zr}7CItg<$(U0GWmyEvYwo&yZbrQxP}Le51+;om#Y5Bc()eE$NUfxK001U*&0m$lcT ztbs(o(E?AZR24*BEcGnh&23~n%;ENK7AJw0*n%AeB&Vh&4R)7`o2s@VMny}|L&ZiK zk}_WLgq)ko3DAb8_VHBF#sH2QeE;3c0OB-wSK3R}29lh#Cm0V7B!p3srL|FauNRuu z@AEEJ0n*g~edRpWv;<+QHqv-7uMo8_m9FnJn!ZX|QAc%K4|hYLU&;tzle`2WkAjc^ z{?8R<<46q$Ae**mfPqo9T=d4vn0RW_pZgiQO9C$55(Gc4I6Uw;iz6ZhK{Q6S>x=H4 zS432lPjty2A=+b)FP>9CPz1@h*lfMTaSFi}he9nnY|Q8BAW!mFoEqq}=o9~ZNz1s- z#o)~SPy7|t=}@Cmh`k=xHm;UhPAD|w-aJ6?1KO-zfvZ5AfFe#1^xD%M6c-#JFE1?( z)`yUBam8WnEPwoj9%2BY%3#6hHm(q7h5ls%6@>}#Ar_rCU8aJ`F=YfC*{ zygo1|>b9PChI)ox;9t6HUUc#DNJ9sE7xNQNZsu?ydo_eA4DBF_Gt|b~s@S6Oz*q`= zZqpKQMd@qWqa8e*%=PSHYPND7Y6uu)nrI;iWU3T&9nipBf$)hMw&*N|5BhL>TQL4o z*NeB*hS>l^idU0W#GoCaH5dTbhp|yqu(n6(Szs+7_irn`)GfnQq3{a4_vbEIj^>hS zuII1KqiwKs9xs)}c_7EJ7<$mc00mVS1ASF5;O1%JmX@MB;3+MfQGmi5m?v-~z_ojL z0yizBqUQlzxFSqhOHfEvLB*5m&b0)+fZGR703!g}!J4Rjgs7k47~oK>ZGnRl1nnNm zki!CDql&G8i>j8O0H6nT^5b#4NBtK7s~ba&BrT&@L*n(7b3bKqp?+#sh?9I(YE;3q9J9BmE&gE+{=A zdk|9LL3rf}#-;LA#TJq=HPrHi+SOzQy;OldSe}pr`k=T>xJ8pK6p|Zi$p}I3gD`5j zu>gPN;E?Q8fWA=YSe{Qy=>oE%hI$Z2(7suviQxG64aoya+5B@1@>^?qU8d@xUUPe-;l|I$B6W^#$Oc9kGre z3|Q*_zYZ3@^ZGEDyu1t)C(xeIy*>zY5HcYD#^LqBsGq+WKwm)2wD{}<6n%YucmiVe z7a3bxd{@r+lF|R8;ocI*4?+=Yz_(OV^fsKOJ$>R204-}@YN ziU`3Ge8S(vC_;jwd~m@pf#;(9=##r(-Ee5j#ex1>IQh4zKq6p#BEny0{5lT)8}zuM za2QM1e}EnYC`*DM_j4%z=bT*ZO)V4st)AailRz;P;?$pQ0kj*=of;8Cs{D8Fhp)8$ z$6Ex9D-WXSMJ;y$taJTl-_Z#DAJBaGx9OJfw-NV0LDBz#?e-6=H*M1)WPyNDP@YNO zzfO<|aDn9f=W4uk)6&Os@ch<*An2}z?xjAn@o#6De{BXq*k3kLf8UhU9ZloTU*W{R z&|ECm!+)BK#S;R$Q~dWiN+eQvvE)P7b0N{ivkCgX`oA|9pd=)`jCV%55_;_nV9mXy{0EWrL>2^YZrhkd^lMMb_& z$Y|X7=NSYM5VR~q#j<5$Iu-x0LHHN?yG2X-_bIRi%EkI~z`Uef47IDHTwN`3(77cr zH!#Ha$suU@I<2(yv~i^-ihMAb2o!;X@3dS|L{NC~`=>pv?5kfYfi0Yx$guemms<%uW*&0%Z=`YU#dKQ23vpgNh(we4@z3 zd44$Yf5UD9RjR+4ZGP_$er_iyLw7>`KUU#ELfh%vQz#*rFdqW;rQRa?ui0LIFB$(8 zn{6?k{pq`Y`Yt%wYyh74O*vIqP>4@hV993tr$>n*NW|Yu#ecj%{9_S3DFB@me0{J0MU($C!I-GX_ufNLc(I&KPci-pm5=4- z6@q=^rv59G_Aj7emIPy8wDbR7X_q7=pU=Obl!SKR@Z)ske?{3vV073vJ^UAf3DV(J z|2$m>(}K)H03nPN5CHWtg0M71g9BB&X z@&(QeV0I7&d5M8WEy9q|K#8F&`#XHHgN=m+goa)gO!l>T{}$c1#N30jBHg${5bA#( z+D`-~3>j7!{m(Z-7ZMf(Hz>Zu42zGKoE^jAB7B02Y4XytxS$9hJ&C2O?7tNJ2OQ?N z$>$fTTcdCm|I1QGii-ZJ)CFLC$R!8w|3y;&3kTf)&36?3aloJoUK#>jK>(`1_nrX& z5}tBL!F61zU@Sc+ca)x>FaQq6O=;FZ~ z0DPz+46yY`D{T*OcS2LhTtSD1`=>)29TgSqAq2iQjWS&;l%A?PxQPM5AMu8IsxZZq zr-UG&6@cCef)(Q}A&4PfP!NJ3q7-zU4B^%=@En5fK^*yf3xNjG0=EIazyX)Li2!aX zP;Vlfq}_Lb?roTB%YoSd0{jHHyP$1|Rk4M@e7d#}z8!!BsQ^E<6Bri&!b5=XRLUUG zpV|p)H~{>?RUA}6A4NBS^LPEKk2cf?ya!P)hk-zcUaD|#|HDQQt_JQDD1&mr5Ky9;tD}#4cZ2|aC76w3a212y)!TkYQD(G-&UlicNH}@UB2UpTLNCRG~SP2>}BE2zAN*ibV(IzXiz^;QTCLJ01~oU~hn z5PpUaf;pF`ekpwLE65)e_6Y&=pnC##bYLDHf&u;jl&7HTga-Fe02q-9Y^08+pbBZ3 z5Hve=T~tu(H^5OF2srv5g6#(hIk?{lE?>fFA>KC?0wIuO(Qmpfaq$9zP#RAU{gyg; zVFVxI-|OYSM<`&OoS=JV&>c?;8yvVL2HiLV*FI4I&PR<1{uAOm=)$WEHQrkcHWyv& zKR4Jzio(GaTEv%dj>ZsrmVrcy0&&vXmWUr5dhjihw^a83_5klMoHqY-^?&D;!k@1G zN9O;htN-ch|C?MrQWPc%u*^Sl^}-+!SjN`>C%gK;51jFzSit-a4=pbbg9*!iF7FsQMA9f%0gkpuL~(f@s6Uqk?GfIlgABEVT0J>sQP@!wG9 zhwz9HeqhPj6bkL?MyqvNV?ikq3Won9%bid-yaes{&EEJYN5)8mFi4C(|M^xSp)x2a zn$iC(K3)#iH?OiO)?`rYIgugmGLHB#1W`D5*%=9-mqTMlph?Kl6eTkZFq%v|}L zdB@d*xA&d9aN*3k^_tsHNT;0IAQ$jTOmUtlR(Uil3t{xoWu&IcuZBE$rMjl-aJ&o2 zid=xHiM1@b$cm8JfBejfm8;gQ-?HzU4>vbf9Z>dg{jQzXGaz8??|orgmU|I&fSo%7 zd$(Wa2P1=q_o2-qHeFtxX8D8rlsRt1>uvjXF;t?T z?%J{?DLg z125#+u&w>JN@>`WD9SpIR)O@QVTz_$lECsCrFV0H#8jJ@E&gHSmwvEc4ZxPF*p`4_ejaQ8l_;+n;$`+hfDuv*@3ZPw*qcTEJVVZ+p4r&+6SJ0;u!w(lA)<>K;U zeynl)dRu6gt@85pztRMxDT(UHFVE-My@F__@26 z+e1H%`Le#?r!ik{5B>Dr%enr5{~+J3p8wRljU4yrQ%A^*prFm`KORjs+l65BtBpQ= zDwSeypBwg=8ON1#MO{3sl{7vu-B>g~A<~-=NST|RCdG$~l47!|6`JGTMSHa2JDV`^ zLv@5eW=WASNlNeJpwsyRbFBlpN%Z(=El6@1f79VzRF#B7AnynEHZV;9oH z9FdJK%c6H50wFe*)KrUHv_r>NuS7kD6`XG0wF-^$dcqz}ky~W1br1*wcUVnZ36|N*MX`)$e^mbIj<+ z;3^KQux(9ZtTXanlM=eP&0m>-IBfDJa{;|l!gSmocAz6k{FE+6E#22bW1YtX%gzF_=o#hH5X2Myvy;p8yM6# z_0GdoIbO1Wx%$QVZRmitJ9jY}uMVpX3KsBRzhZGEk3rF)ZS587^^1NxAYhG&-*mUW zedf!K(NYeUBr)w^u8+eWMPhz)1E$QP${f1g=)v;m;{w7Tf|Y38alHeW!;@T}K<8`5 zhS{;GqKi`nBfh>T?a3YMS(W$c4e=L#>bT5;PO*Ft*%w$ZdJPO7-ra9dtyTR-<(LZcqeyS+4;5I47rAFWSR#3-8hQF`Fes=(Bs>d&&8&XbRA^P(shm)G=~u`r{+;i!%eJ3%j+Fl+WALCB4*C z;@x57NU$6%m}<+U^rtevRh9G`NXwhV*F0Otu}6W!*R>lHE-|U!P=yV|p$zT+)y*YTodq z>_Es1qqebYZ|$?HJHRvl5s|aaPusy#L`L$-9ghdnLt3y!1rNI`$V4d)auq_Yn;~4Z zEnnLDF*Mw2U9qcdmmITe<((($^_X+K1zw$+&@;i`>40|J3&2dHOuvrv+(%~2iiX`X zQm^~GU(IoDqS4g9Y-rQedGN3A?8mcG7kSbj9botQ_^cwXM~T0{)&9|k;K*q6^sJg= zkw>Ngqx_I%#$ZIAQZwIaN@EfGy1lOIMe(HkF7L$LuGa2dc1ksMoZ;e{)3tj&TDP9v zgF87p8t#98Pc-4I??h5;Xvxh|y$1YrcT_3Z{TUUR*SPXJ4J;#dI)DaY2lL4_0;uP| zqckj|r{}8(luFZi&A#?4YLW)`FhKLqZxVi+pgB?kN(>L$iZ_cL4HF+L+n;B^kskgl z%y9y5+wMCRx-e6;Fo3u=l-FL^VZvK9U5)L?u2UV5NGH!dnjNbwebP3O{;7*w$^ehe zO{u!C!XD0Y+Ert=U$5vw(cBO=vQrAn6isRtXJ|C>9`Y;|Yum~}d3BaSf=L8tAOQ`H42dSCY z(EdvSWR{{&FCUTOyo2A|YUP}cZlATf|ES}FO8ml;_Bp<``N_N~Z*i>T^$$J_O{~2_ zJghhl=NDTqfAGwT*l)wIkkg&WF=x&7sbbQj)w%RkLd*U8Ky@P%B>1;8>B8Ta7g{73 z`;%YDXH;)F6j;a9!tg|+dv2O1u=&|RvyXT*mj7Rkt*c7(MnnS3}o<`;xjm9^o}!i@g{e;6=JZ~YhMI=il@4U_YA zfA3>e#h4iwS;e|FRO~#2cm7qjzqvEh;CkFMcdt0-64ppY<<*g`=G`sr^X}dH9H+{U zF-wfUI%OuRUmn7X&$PP}soPI}Q@gP)L`1E7ruRBJtPfGhoBQ@QPD23ue&z$SzX;!> z_rE1+<5wOCoXRh&zW@iOSj}(jipa;Ot2=L#~HC!`xjtiiOwNKYb2bTGq zX6R!rW6pjos3%UUD7*E$&cs~Rj($uW-pVr4GBJWD%;n{R`txc^BWYuEOrUw}WT zb*zP(wwpIjdFRyYrrsaKzP!+8kIcIZyr4_4tGI8!R(#4H7S`UzYk<#$4sp`M!mgAL zOieEJ4h}ZklSnU<#N81VdsNFuyVl;Y;))&f9Z$ph+KJTb>ZX!xNzFR_mS_9q;*!UH zJ8g3EKJP&K6UQ!ZNvWVKXpZ|;k~4#mJLa)obDT9Of;Tkg9M0~exdFNnAlA{ixNBfUO(5Y}>Y}iD#mC z32-0a#Llsp`eZ)rR!WR8THkf;*HD>1X7P!<5|gbi#ESmsw&g<_armAao_%+scIRH^ z@x~Imulc2-$>pratR83@!Oe&}Uf1hPvg-HbG7&6QvLaH|5FZ`2=Yd_+%Ux%a`&?os zekHM(S*q2wGK|UFMaLmAV!x${=Usk-k%yIhY}>e1F9IiWWbD9+;D-}j#e?!KmzcPe ziG(uV{qXzw(>>8M^|36wanaXoMf>k2QjEoIveOhLkuxzaS4!1tWF4<)6vZk!&O`)I zPAb(H`BmJ~C`WUbUW)&<3|}QhelF|y@=7Vj!A9n3Ty{+w0-2Pal<$wK=0&Wk_dMZ@z24N$|~BZeBrJ z`^$)1g}IaX;>_|XwYZUfev42JDakfUL!LZ)-Sm9w!nkT~6zN6&r6`{I0VURhP44M1 zVw$zBQX$4AI%8JwL|hiRRpZ^kdzAdv+=Jl@v%g>YEMEm6U$L4ClAq-}pG{cj;9G9S zySka_48o~A;+cY@bA-|DH&IM+@WFJ`y|Fw(h!ys_lJleCdb+<`y}!85Jw820#+jy5xxyhG%qLcoca{0R_ju>l*cOj@A4{C6&?|gRBJgD7<3O~yaE|F$ zJ0OG{*ZJ>1BYppNpk`TT6mQIirc_I?ltznKs$gIwtR{X7;^t42p<1DOVeO z69ra8-ZWLnU;L}ov&->acX{!fE7BrtXW~%alXD>8c8e$V1U((`Uzp*%HEBo>hEX6c zeQvFzOpV9n)%L9pF?KLC!pWf>f2-SvT-}&#RQ-HBf8V8*pV-gn&Iyobw{?lE;Je;^h3xH;mM&9L3O`}gzOyqt?SA+_0S-XFyd z-{@4#Yu0qV9>?-a|5O$cUlDE9qhc|jlpa?7F(cO^J{5iAhKCG;eW1T?PSI(A9g%qI!f2g-s2+SuIFw6DW)V_>~EMN;hpu?3v~WmOK3_ zl4F;{1;vwI->uCRoHi*_+y5rYILO5R*}Yy^0T42kpHk%+-7rf{&Y=n%g`(L+2hFWh-WdsD{q(EwAYohVk5gAQQi% zpOB;KxBKqo6$GdA)MqL10N<4MMw^A|tE^WCSb2+$6wVB9(sR^%5`(O$N@MTO`>iaz zyYZ}7^=~hkUbx6Prr&kc#ubr`&l{PJ9X!+G_{1Te1Ibud^f8Ek+~|XmFUryT(tho^ zhV@uKa`cRY+e2Xark)6xr0Z8lHdOK#`PAKL^&Tl;OTSsQBQYmntX6^J9cCuvK5WXy zG1u!D2Qe4%s`4W;?>8IW3!Cc@+SQSda=7xyyLyuz5>Bi7dLkq0^Q&XX`c>$M8s#fQ z^RD0Hmpj`>Smgr(V(Vk3gtKmm(dT;BUT3<`7CF1-I6HsNoq4T2gojAI*&c3gTcwGE z(V_j-jCy!<9c8Mlv2ZfSZ^ng%H7UwD&UWV>61UaZbM=Wj(Hzy#R`O^*%>A_@cW5t@ z)Ek&Yo~Vth28{m?LCOhrlTQ_lW;t9VogW9Yh?4`@+Jk*pS=eor+NAbNZFn^pTtR5} z_p`m7o88gz^4!775PBY=0`ic}o2Z-MmF23?+$&}Kd)V_se=BMJfNbs*Tb0I+cj8g2D3=?zQ*-Vdy_88u*$rvtm1I5=mE(5UZ4x0Gnwj zJ6IYq(@hdS5qhddcCN5iG`HCS%U3Y|IvBa3hS#aOIm(KT1((~;Uwo_*-dq4TjaBxdx8iQ-rE<1%Ne64 z;$N4CtXTbSP>4UN=jG#O_}e0`Vxch~x**MF3cYT zDnJxoPda$Fp44MYY$YC3NrAK76 z$3LccPIAp$YANZGyBNT?<;_%b8B8KPR-UH_(OThPeKRt@Or7JpP|FzR5H`}-z{p># zp*2e!yXKgB`TKM~=AHw^*5%AYA2`QngEN1YJ83k`6 zXF`z2u8qaSJ2YH7pz_dkx-f0QRVzJd;r%+Pw^xUu>=Elf)8flcoN=2a$1m*Jkk?2* zwA{FLOA^cT6iq6-VP30J({c@qw%qoUv&(AhRv034PEFkLvkL`!3GMf?Xb)i?))n3T zA1P-7n9_f$p9O!cT79jH{-(}Ywh5Y z1(w)*kN=2wJKO7LmsnWGf>W9@T7R=jh^#5jWF6jg(q&@k__M}K4CMYRxV8T2aqN!e zYMZ+xyC%4%ekBsv?m{2EC&5-`wiLS{|6$NcC55;E1=il}f%52TQnyMF+YmvbRXBvM zf-b4i^2qKqN*5kVb_a@u-uCz3db=6Kreq6-PlRrzVY#>#{d#|Miv;(x+miC0|C)y@ zpApZ#-Ic7?FSYm81+RK~L17m-$n*WmTZv}O>gOavSfMWwklp* z+}cSquHvTVA>pxUf}H%EWG5?wrEjR?;4yVJR&#d$+0jV#0*%9PWvpxGn`h!TCE|EA z5o`81;=3*@c9p0w$UhvK5vw$v1=gh!RuA#UVmE8S?SJ9uiX~Mvg)m>H%U7 z!YG)^7^43KGBdWRkTig^OE>OIr=v`o6+sC|HR~2XwFH!~b`|G_dpCos@T*_$b$@#+ z&jUE`=KA*P;MdkVQ(*NCWjpe6?r4~`TCer?6|2?-`Ac8F35j!49UCj=oGU1T2=AGs zrekAeoHIjQ;;&r8Iiw14iFNtT_P!7ktPqH^R_SFmLvF!Fa8JkW49p-1_kCA18j2ma zc~}PXeV~T6P}sefzgXy=q*O7vb?0FvllK)YNtSgfZct(GvQZY3?rw+1ODkJJfk)`Q62iV>$bKHwI7^^-V`ST! z3H~@x%JJBqo_QIQdMO4kZ<6Ke(ms$4P zR$2qkx!^J<7j(|sIxJCYuo>0bv=Nn~jv40e$N&lFTGIsKOV1B}lDYvo^ZTvz= zzpgr={Zqg?_P1ER%FT5yQVa4QJPNtVtIpA5`CbMP%Ok693sBV{V0S=TZgWbzWW8*` zN}Dzqe04V^0{L6z@dt)LwE~Ak{Nsx1h5RNf1Fk7$VnLl~)p{cD@kU+%r5x6pcr+EE&6a_&P--b`@ zjxzDOM|{&A^kQ~gHLh|%DU0zONQDV$IwosUi)w~kxNvz-w8>&kbIUGXfZnh! zw~L~dX}ACSF*3u4t8liPe=4=W&kdj0(`f8cU2&?nIpUe>FzPg0hah7eqD*oqyY6P# z;O!8;3l6zWN$s7cGtG?$rXHvB0%rM$ubu`a1vmVva!+}&W zL;%zurx@+dK72e&l3KvqKN-rMYnJ-(`!@51xvBU*gX(<}QMy(5jmFG#pC(+u#QsNrVLN|I?b%A+tl#VhxnO^K?!&jA7iX@I0_vRf@JNA1`Gd!`+`<)`>$0!|_p?-6L5S=7_y#h% z0OYU?Vlfh`izVIO^+4wol&`2#U01*@MnOh2HMlm;Je@WT@(*vw_s{LN&F*+?aJ}&3 zbH-9oUu_vrawd=_ZeZe?GD2G^zfQ?!@B*6@@Y{2cu(XesAPX~1x8%=L1{8)#CPrgc zN%(+UxfXBz8c%z?1T|Yq(tCVXIjF)vXz!dzog!}lNu_LMt2<}$OkTl|!)nzot|;SQ zMnFxEVbg8HO!(XzEwxZk)JjD8w~Z$uCm4&aflBYmc6lCjR>U5(W9Jo~bi_sMWd1Go z@@h$xy7%fD%46Jw-B2hlH9Xw?dK~ibJHMHsnN1Q>(w9dn<+-ryZx|IHecXF{M_ub! za$#3cM5`{kIormUz1b{q6Xo>Pdy@P4f9;;_(mj^LHFcACsUTNyV;!6Cg+C^RLUWHF z`}97rvo|q(Sj&TzbWfG3&VMw-^hJXa_8m6eg(pf46ouye;*im&LD_!h^sXxIp3pc_ zG`3JO<8bq@{D*`e_g*7~4PrpeAxs)?)bi7!hgAV?ji-_G zpoTknZ~y8Gt#x97xs(VVFLF;z=;UlosQT z)Yx@x2kY;8N(=)AQxa3Hb!@IZwv<-eq^6X9ABRNA?p&@YQ$KvXF!1iAQ^Uq-r%iD? zaC4!@QiyDBTjuiq6ELWwXc zu-GEjVxKjEKNMJOyd%0~0#bXX2T_K$_fDDV8{vdJ(+jcLQa*l$ob5{W5y;_cwbNZY zg>y=+vO>hF`Ht;zd!ympd+Y2ZqQc8X>}K;=53-2RuHur#Ji!xgXNmyXhpE;$KBf1) z=b_S3Cx@|BrY60q{GhOJ7XzxEAnqf*p8Z2@Zth@;S_NY?K+Y=1H*R-`SQzfgZ-@%u zd)^iFCcj<&ns_dYvD34+E<}l$(`Q)I^GI~8=>-5TWx182N)uGYD%L+N-y53ZY z4i8@-NfKGt1m9iZ4kv^=U26^Qc~HDLWW;yGd#=CSxu^dl6T(hul8677uDI?At~}>* zoyYYO4K4#$jOAkXTcqy-R*g>+I$?Tpb~(O2P3^ zy+1yF6Sp$)X`05FcoqTp?@EE$Wyi%=w;TA?sZpsnP$H4h7u&q2+KG%p-a|Qh#{P2?o1!ZU1&>Vz zZ#yb1)jA7TCz;^KJRo}~nMMLWI;se#ur+U04 z+S!_Pb3m}cPZ1Z2nNG{8bO4oQ6^HVv;S9ft)ElB#&sts~U6gOp@7^;HLilsB9&Ln< zIC2E3$yUl`tyke$J0(efa6UIe&VnoNe#f~_>~d;@OZY-R{$O~lIJPmvf~dB>dxn?4 z^$`7F&V3s|bG2OTT}-1cA7|*AK&IcF5tnL&`;|Z?!Fv9a-JbLz!l-p9n-mqnDyr1w`Bys%R`rW>y{L;kQP1jLqgo&^&P z10HI>4XTA%f+K>I@dc@cX|>``fxIIXZ0f?zt2jrHmr7Bf;%ir<7o0sozDgwS6JOob z+W5GzYwd+uL7BvenMNY0q(?H!E`YGiE1pWTb{F1Oglr^MQp;4A#SyAIs5cW8UslG* zor9dNN(&t$Vd8z=|j?tdb}m zps<}0PT|z!fDU~lBeOzJB|a6I+CyYR2{*Gm(b&s+yl3a((A?U)l2WA+-rJEIv)17% zSBx{7ev&D!FR5=F0!7bAoqU8AysJvoI-5vwDjql1i05ftcO=vicC%%otD^S9RoC(m zkzM=m1YpGG6PIhyw+Cc}J9>`n@7T7nu0~QLFey zd$T|oaE8P97{SM%G^AL-A*!uqq?coecG1RyNkY9E-&ML)!P0LER8lY&razw=_SmmBn}0qICR+#F}+4SC8jBF7XSEEvYM3g&Y0E2 z6d0!51IolnmzJA@7>3}$y>|F#ho>rPc2Mfm1Q>ADX;^A*;hlx_Qel50s#oo}(ZE-Q zA)7FyoCPWc1%}wIqE2Dr zDT6QxvCC7rWdefDNA4D0nci?A-zlmkFm$}=P)USBp>NDjVCzzOHclsg!}Eh={;ik5s>BS|=h(7QppP-lcK$oWMX^E4Kj zR3%zQ(E|s=6~g;O*Fh&$!46kCYv!_|Bke~(o{@HuU+*NQ+}$NQ%(eRIpCb7NW9 z$5yGk`Omc0+^&_onVmk;;`F>hH>j^(phv})C^nK`!Oe}6gj*2PF5ryuN2xFZ(Q>u( zOvzp1$1v)zoHkL9BN+>1BFM)~%~dD3_6;es9seWOIFnM+ORhxP3DQ zyv3()n6#YLjZY3n6y?lWpM^=xT!}X;WBe6=vDKs9H_}XkB+x!U;MJPjbd|%a_f{FN zKTgLp?#WndM5$(thRLf+`0j&E3*rmio6^b8Elu>R7>)5v-71b`pPNRfgdS^*sfTG0 z>F|=PhxaM-YZ)2QvVEmBhI@|+o3jr05AfX*Vxk5YbUd)N76{j)RWCZyj(gm90tZAM z>}C53h_!t`7*0kfmNr}^s8*krd={**81d7TYYr-@ZlsNE_7)r~pswIoel?2gBVa0v zxz(qrRoJK2>jCgy_H^{3@1u2v-2`vezG)Pue(hBU#GO@*aiqsb)QI+}GJx!3Zq_i; z#(4`6(Bbb0NZitOUDN@YoqjC7lXm>h30>M*K~$pGe`yQh1Pj?K>Tv7_cXccQIJ)vp z!_Kc3K`*GRcZCc;XR=E2S7Ux=NrEyU{YG>14}jNU5Td**yH9ZW!M~E<=P~IYUR?%E z3X2hrr7i9&1_HSTz`?pKZS6vq#Tc$RrU^aUg{NRVQj$b!P%FU&B|9W`|KZX4bJ0br36!tRO@^fb|x50ky?C(u=z)v$y_eu14 z0vMT}W_%e-`ycJI!8K36cR7vMnv%EX3E9j|C>WpJ$gs0F8-4oxJu_qZ~4)hujicR(jB>uJ&+On}O0O-=Pn zHVotQaa>I7;ur>ITKUeo`yL!FHMnk)pS7@hCpLyx1R2#i*lL`g1uO9Er0o2?uRGd9 zE@V|SE~%DZvs;AGzQTFu+wCJzmrPi}o=*Fh1i~IWQcp+hTH%*$jCGX)H2}8q(r8A? zY_tT-b`hFwXHrzBamxi*fe$&|TEk4MMvx+x0+A(JvnskHHa0p03A&(A;7~xN)$Gyq*66sjU!1do_(s_ z-~S>&@LdCyYQH)1r;onSQrc(zy zQ@!9v2j;wqb5mjq4I8p4?eX#`F9UMRP$?)P(09p}w74P)vP?f?Ay901d!w>b0sMc0WU5VmMu8QSk+oEN^zRo*Dr2X}WE1a^ zz3cqvFO6;cxHDIz68uzz6_ajz4aZvn$4B#&B(-Q^U$0h|1z!Qb)<^n|eU=o7jH=Rh zNqnUriUQ#AyF-pXJb4sA+(*ke!^a2WOV5sIvAxX~F6u-R?nJSh%`41|J_{p0qv*{K zAe5!%#ki08DS0l0aUkE$GEaI=mnsxC8G88bwf6~>kbL{8^d(PSlIS9%C@|k%66qNU zYq3zs>^{ph`N?dKZE%9qHy=Aw4=boA>n$*_4oqN+hTKQ9;!Q=KjzrZR;D0S7< z1J(f&@jz)jiegua#gmO@uoiiFMLmXgI`eZbeteU&;zV)siw;Kq*ZYcg^%sqVEtE{F znHDW!sxZV&-72cKKru{wU3R>zV}^_vW4!dMKwcZ0%0{ zeU6X&l4$y5yE@wa=0dIHyx}{);6Cm+pNP)9_fsSA%A?yd@@L2H#upj-&W@Yh;P0Ci z(_b+49F-%r9}Cc3n9<@$5|d&f&nSZP=ZV?+BI%0z{-Ht*=KzwSK#irszNmHtBW6D} z|7n`vzjkMl>1KDofv!?LQ(w0t4wl)4z;_-kX{OhQXIm*`7Y8#$GbzK-QL5Or6gv>! z-t2#-(GZ+lekdub;NMt-O)3~WRV6TBpLo;MZES>DwtAtzc-&D^s^^*D?#|RrbuDwV z;z`fPXNh?3NTz*}=4+1)T|cCo__ld3@g>D-D2&t*nzgnRNAp0bysmYlG5aatyqaCl z*jdgV@S=PF=GPIOgqVB1Noc~J%nx}T`s{^GRfW$-#j|j-{;{3-UR_Rn5*q)jm#lXh z8gH$d=6S7?u;W7YKpAXq1lewE&&iu!P#1oFzXSQTIimh^mYjY5DXx;2Wva~^%XN}? z{4~81LpymdS@qmifnhO#G`qM_TknqE*>=a&y3*e4U9?&UEoN|lj_T^p*U}T{bWAduEp<&+mhdN2#5f4a|POk zExruOK!IteGA670$7^G_9F~*|UWI`gfqTpjUwUC>`##tkz@elxRerNyv=zU^qsL33 zQiXfJYYcr*@c@cWpV&~gRt!{uKXp(wW|v($!3w(7Q4nbuD=BVDTvAa<8w^(v(||>-#qETbe_S zgHqSt4OD(5sH{m+joq!q;eC|dzvKLM0bj4^@l!}EU9)QjR_8Zt<1Ue5%wL*#x+ka5`jKYLm`)O7IB_v10Z7FC;uO?R2C98#J5s&exip+oV z?74w??3d5*R?jRj`Y>(_192bbSETDW7jfCGm9yNVm?6hcjkmu`jxpyI2!RiYpj zPe80qr*v|3)~#dTr6x7!8ox5XGj`-+UVb+(bc?IhJcOS;gul=ev)SpOcWl70Je%X& znf@%ID0c(6Rd?flT7k)AFK74*S!Ss{dF_7Qv)#dL9T7@==UL+X3)Q&8#ryAiE=;zB zpDGRNOMITLu|&|vpdW&`wJo`Y$`^xG(5)17_&bmA){Z-dy2j2gKQ(|8Nw&6+!8N;; zL%dt6QC<@Dvdj|O*ZEIoInTK@PT+e#a)zB_9(;rjv0RrioLR~q62xNiXzT@r?b7CX zTjJ8p;_2I8KvgqsT9}F>-nBMhW~4|ex5X-2lIJz~;MLMS9>!JRFeUL-;-oF^Xi%Td zbSwWt*A>8@X*M+@#kyaJ zcFfPrOY|Pj(evp^2yDLH2|>}sr(bLv?b1?vS*Iqk1KbxnRA36>QwEFL{R)QIz22fS zL4Y6G7JkFQDV;zH3)*Q6gH)|Jr31iVZG1)_6nmLwjlWhZy%S|BdHEzg<%&_~8+alygfg zm%u)7Dz*BG{W(aI0B?B(*)E<0AZUG0%|m#1Mj3nARDn~*J06GhVipEx$(;~lP<*mC z@lKx9PPSI-&d|LY1Ca812C0{`q<6vj9dv8o=z6FdhcogbC*d_>fV6_|F>871}lW zlHd2R*$cusCWH82@NvvL9d-rcy)LwboyVhqHF{!kU{fGfylU@L z74~e!#JlOe^GTb*PrTcJCw@g#?=pDmZ(X|Y^ufM+b|ra$y6@UnVcTs}A5F!1ABpuD znQ3Dw^_?5I6W2zt5dPa1UT?_?kt(`?#nBjuKqNf zx{?C0Vmtf^qb0kf{CqwX??_@%y}#6GJ_aXoZE{y^sE7TpB&kMIN6&^ZtU z++Q5m?Uge~XfzqU5xBWu!4;g-mdwY0Ix#}@_vpKmS@p1Tr|My4{uuq$OI7VMP_>YQ zbySE@g72C*&yMr@{sj|WVy@56bC>91{k;$G6(6WVbe3iK<)|4Y`;2&J0(9BV*M1DW zGrk?$E*m|06V=E|usBNSiU`U!(!G<{?rtOw?nBSrtaSDzbzNC!e8+DJptH_;G;u-b z*tW)nu4E|?IT~lF`Qlf<&fjX2GduVjqj^rf9>34I928|0+l~(k6+KeV7=xhBKY{eI;yYVBz|Qs&Cq*?I6u} zar=5jAy@ehFtCl!4_1N8))NO+Y(K2ut;hAZ*f{)Ts_m_9C9k)b>$4!1ow;iGp}WWy ziz}W0Q{?6E+M&q(@|w_`^&NGFsusrrxA-H7<3x$3b}JbDv};QPO#4 zC~rzQ7G3c1b_j!Uz(T=@AF^;70A~x6=C5odjLq>5+^?JYbT2t}C!0gQ^M~SXe@oXA zw(Tyb7DVg#tlG+qN4M>!PI53kn1BBKcxoM{>iX8y^n6@byn&?4E9p#< ziMLK6OA_zBLcqy!(s5?02Vh(a(3Z&Sf`@UHVMkl+pE&ICtr7^jm!98o zp}>tfH%Ac_Ypw3Ac4Dspr&po(&`8Ey{sNJ~zuL@gD63MTBWVD8S3CRp5uVaMme}@$ zxj2)d2YtGu?d!Z9x6FL-oeT?Se`MM{gNgGy*!H9*xFGQuC0on>vPCePy6EBtSH(MyZX&t%O&Nvp7AgpJ}JuZ#@tr-)E*wdV&);>N= z;=%Hz2I$0wns-&>In5c*LT`FAkI&n>+mBIrB! z3pmkkcH7_;!s)Jv`lH&Sxm#<^IXBd%6zuha=_s2Wix7Adtc)0*GZioDzEv<1*~Bk? z)XE@@JKKJ{#iq1(B`(K0Ym?1$H!%-840K zn2we=s{%B3mc1`F(~K>pR@vz5j15mb%u+yyrb<$FrXu z=ePUkr5nFfZTnke`YEcE=LY>`O5Lnk@LKf-MZ;4s>d4g^k$N}XGktf%#!_vijhU_I z>+CAVle^8cI=d~!moFR3Cpy&mRr2f>3H(T~Q_dTD&p0{jB(AT*#yLm{M-0(bh4%8+ zO@drnhNj`@inp&sxIIojiyBy-?RSc3%xih<{Gnv%Y?s|rzR*vYLnbH+M?u2}CCYrd zupytt1X1EpLE|q8O=nlBX-%hY+bfjX|9ZKAK_EA7gSwl{0c|Lboo-4ra|EBx?!*F* zriL2VuXG1y-$*CSy{QnqG-2jeNIN^yG5O=;JHfpHqA+1w@#-Tp{11nLu*gu7+h6Za zoVJ^u?umP)(I!4|O>vsJnNPTh3O1g>=Imq*AE1Uct)4(lqO^kbVExTB8nI?HsjFo- zHDR)6^Z7<YdGk*iCNX8+};3ZNbvY$r_#qUwpA4w(${gQ(ftmL+?B}PDA_jHig@=c237HX4_j|O-RqUR zsIxnFOUp5f5j)9B>dHcIHeni#I2WwqXhYyT<%1BC0WzvA`rtG*z3H@o(HYi>{C|2W z0R>^WvF@l`x_!V5&M!uqeazmRzupEn9=Cd_>atO}g(+;&FwOcRI z>LSKiB_BohB^-u|H*pY)?=&JOdD`CacRk4Q=E;VMdS&R5<%h>^1}O&iV&e7e)*7E` z3a&-Qnlx+N_3y7o@^^@M|6_{pWmpDG^rL>79#6pZj>fLsLqmkzt&6+l_QHCG2-cBu zX#F9mZbTc1xRq$Prwv$Zw7)K88uF=fFMMC0o9cRuL(*eQL0mRL4DPJ|%3tC&q@uG{ zY|+zZLCh_JGmj+kKLW?O8bGCrb*23VsfAScVh)~tOxS*uS;PBJDbR;To@V_jIRIem z?a0tmjXgEZW`ht<~QAp6kx>_KS9R{icSst*Y^9 zlK`mjQgT~_ssb2tiB(8=+*J?tODk#2$p1gMKBNK4w?b%?Gh1yAoo5J@x&{ta(+;kG zCFmP-@{B4N8Uux#5}!jJp#`rRPD8HBeKmU*xjOHnyH6LrD=bJQn!Z1`u}tm75a$OQ zr@QMv`a8DWA=$mFtC{m@GiW$J0T2a`HANXZ>Y-&ytzu$fb#*69kKR`Nr$$BqfCax< zLq++_5R-8cdH9}Qq{KH(IDvJSl?!Sb&bYjKx|^Qr@*Qka?PlUZIJrqEtg-&1XPnm3 zU{ZA06Q{wklHbx%7a!Q%r($E%S{nOb9`5(yFc+%)+juNNj#+qOS=;=YjnFPyn)RxJ z^}k1#fkqx``3jrDAdL4C`qYVL?#0fj;5o-@g(+Tu(6@D66TjNh+&REzebiWf-f=!o z-7-{Kb^)tnAig?6jqT2Ulfb%n+lL?Il5f(EU`&flxC<2JAXtxbU+NBek_TRWk05~% zyF=JyctV6YD$*olk31d!KT2=wzMu&c(oT4;Bl5&Aq{IwyO}tLyczf!N#Mxth4N zi3n(hoP#NmxXWPypL2%hMRh>;uc;a=MEb6F+@PIa%mCdEjP;>M<$ zFO06b;;9oJfeF<;-q5pAx6U@kTMpBPyRy0Neeq?J!x=PI!ZGH5C!?feqdeD~7b1?f zF+OxxQP}v1{{-^ChjXa|^3B9$EwVvlA>!hSnjUQ(w*H}JZsZ0c9Lft4-tm|#`+A}Uqw%@ddH+>A3B3S9f?4r1njOEEE;aAd zdP~?{7tx`){Fdr#H^7TFSc%Dc@qpx&so|hbcE?Lb1F~a%SF1EM11;y5EBae1XA_m* zqnxc1ZvQ&r6Bx{L&-NnTMG-{;!p(rDCSX!HuE?ADKUMj!Y;QUQbuWC~>jA=`+fP8Oc}x0}<@9CC4~Qm?}(5 z-(65&%iFl|Ap4j6Zkw`R+|-R16gKLnetEir4qUOpY{q}c#KUGTJGojzq~TDmGx`O{ zfR+(s;E|U5EBo}Qrv5weHsULQwBHwab&^}@4&Uig;A*I+ugf7wj6EG9^Xl%qhV^(; zvcwXewxM18xYDoLq^R<$A&!_d&KHGG z`y>iw`+fMld93T9!&WtJ(ZuIA>-=6JEhizVp51drx~%nyhT4>;Z4-aTjoCgN>h$it ztcLa>chjhN^_}|R#;p#obup~h*~s&YN~SFY1&L7>h@{`1Cq zXP}A0dDqNKV4<<0YDD0{PIHcaYz?!AOb%4aCOa}B-?v5>YN9#=+b^|o+w@thnu2;0Ky8FJV=UNry z>|VHvGn+PDp7uH!Oc}MiFZST7H&dS>j-mTP=qF=`Z5CIZm5~}26Y~LG{1c>?QGRg= zhku{vNVcDE{cIDvXJ9j5|5*-~5dg1g$ z^e>dAl-uGm&>xEqzsy4V6&o<23`w`_fqp+c!Ijb`35ks5+FbP7kA6@yQ+$Rbe%V$5 zTE~iXFRrWtR)!!w<7-(C2^UMpuZ#Ocd}9%T}_Kqtn;BZl^n;bGbW} z%Tb3lNw)bSh%bN}hEY1cTD{6i^A(ya9~5fh6g;Vf8)rrGb9lc}5|gjiN%lU0z=@T=#gz{QA`| zDo(GiC%vIoEy~_|8cTXsGZ0rqSxzVDQDzX4UD>4RVQT@EjzTI0V~V#Ue2USo z*+b#S^Iu2jW;jAjr!!V1y=QF*V#SbrjLHCDIE=43^~0{Y_t)XaYF8DhX?Odh-P7rP zl<*)M<50QWX3zd{sL$BHRD8M@P{3L4cs_{ST6O`mOoc7+=!p-=1`PYmupVUkE67t<;4IlG*?Vp7M#C>(_-TcyDVjBgJ1^e~K zgYNrYo~O-&S(uZ8RFO?2}fR6v@)$YFv6`C&`O??lj_x@gDzk|olV(v zu=q>^Z|`=T?sH$iPNFvr-WMO@I~h-BYt9Z0z<9K>r7%|YTMjTr@y8fH1dKA%8Bz^A zxoo{LIJCazPK`>HcQMJ?A(rnxGmh*f_Wv(PNPh?{-jm*`1m*yPj`mo*o9M#{g{J0d zgYOyV)NysNwO+A!* zP{^tuWy|A*(R5MG-s~Lx0J=`b-JhGY=y^TI*B^X|^_+*#m+yxR_+!Ck_nY!RKxUuW zdx@xEjvjAU_ol&AZ~JMQb^5Z)l#{9LLW7J?Z7DMy{)Kur_Z{O|e}=#*_;sj&g+|o+ z^?zf-cN#-ob2_{AG4AJE^FhKhHwzfXfZq>hao=y4pKXZjxhD+8h1Qer8Q-U>Rf|4+ zTFPBw)QK zsfMC~r`JALUGC*p>FN<4%Wh@9Y~)UE0|^iR&8C_wfvxl!>`T}g+GV&-ENMj7cZ0-75RQ8yZ{eG=Zh5yl2P3?1F(A)BYBo6bZry6Ga z^?e-wu#97AS9WH(jRV!w#3O6w>WRyu#}V8t1{Xe6jUSp$mI^CiRHasFVhjG~V3OkO zRq_faAf8gYtM;ExwH(WU2sl~e%{7)UTo>$XjGHX*NoM2j80vPO*6oJQU4 zI1Pq^M%5bo=!YNN-0!ZILEqG-&Gr!JUc}w6w|Z)`9=5HtQ=yb5Axhrs^Ow=C?t?hdI@fqRmo)a{lg%_GDwhohH5O1yuaW$ez~ z-3n}38EhZ_y>A{V`_n~!cDvKPo(ej+n_L&)SMk$;&OQ&Xv)`PJMvnmeii1RV$vf!L zYx=Pprjc>hd@x9I*@Bfh6jEb5tERccf#@`aBj(Jmel5{z>Go2C;P7v5d>CIEuUWwxjLe()=Om+y3qO?%crlCXhJy|*A1G26y* zAuL7MOfhEiS@so04H_P@&g1h3>xXnvCQqV_nWH{_^eU|(sztAgp_^z|^#<#rHS~fk zi(fq?U{Gj1H0icZ3x9l&EYU6#+3(iZ=yB}Xtb$>~3>E#v09VYr4h)x(q7H1?A#`ml zQJ4xeZGk<(@NN;ASTRZ}OUW5tBgWszP=CX}+C`?k9EYuU7PL ztr#P8sQEOk`7}xRFy>4%sa}-R>{;+NFJmQgq9_mHiM$L=SVSxf$DAz)t9;#<%54>; z*=M%mnk7_;yjGtrM+@kDE`RD3MyhR9N|sr_y-qB}MK?L&W7o@9FA6i|AX?e`oP2jO zPAY0iXdbXU)#Zc0w-i6{pJp=HnI^$rgYoYZF~36zZ@C%_o|JN9ht6^)@P=S~VhdQV zjZhPyIuZEH{=#%p;1SUf8S2Zpmd6Ch_;>*lc;~0ncEjrz>&q00#L*s(>oQ^A7k_=Z z21&zOst-0Qm736%9(*#lS7ib_2N{ykuu5IV7WE=+QeM-CBiWDAKE4ax3^-rGghSVt zV(^E@7e4J`tjLhjC96o3gjvgoC}_(ViNMoFvu{flwi*?zsG4}EcOKEBy*Sme6AVn`a-iLF&;kwZ!*U8|^m-@kkVSc#$K#RdVkE%> z+3M)C`sx*?Cpa06nu z11#}h1?e-{=KtmHONA=K(;cKGP^{(rPrtAy@}svXX%5U=y+jqRw|@*5BoTJq;j(fr zGoH1i6msq8jwuf*GCcLS=)?S+})k8)-gQ2LN#z z-uZgXzF4stY@SMu6`+@kLm^>cH)s~wYq;}`wze$RYxs<_J8g1P?=m$Jm`LfT1?t5e;LGigIxv%ke8|jT$-k>|_w{b01_o0%*)B788C%8) zS@kJgw*DS&*ak|X<7RqPn5LK1k2aql$%~C8XQU?{lEa$MTjEie&-WG$=&rtzRGg+;CHQqOrvVxp<2s+s#h{ow$H5~ zi&{S6k-07j<%e>F+Rv6u@uUuCzmYLbAmGFSXNNWTqj#T7ib5nR(PP>}w%&YU#A~-w zxL3T=M*()kY!dTgKFNn@OUa`|V>5zITzA_g_f_lDpED>Q{L)(m|FpvjTC&oq0b@U- z#iI%|N)iWHG>Rkg;5pOK578!Z342f$n~kW}8UbSz1gCu~vA=uywZPFbCQ6s_Z{irj zpBN$jN*D<5Q!O^V`oEL>tUtsl_;FCNi4lL?UAK5E7p|2Wo&mEG8?L-r<_zT^bgE<|7SqVA&uY4Zv%0K z_6-NVa5JhG>V~T3y}O`<$Fb`ibfv$TXtqh3@5Wh2-X0>ki{y_Hm7P(<*^i;e02yKVCEtig>OM=vDU)V!E)%fo{ z@&aXmJPBu}PlM~i>vXH-%%6Jo&X@_&^=?|{rrY-T@Mvn`&tPD#N$<)Z=rsd22{U94 z=SfIV5^(uz3F;-_D^dw2K39-N=q2EzY_mD+{*;aB4%rrrnL2(}`3r0r#wVr#-U5v* zryRw>9W)%WPu*$mZTpirPee#nauh-6UA!E@YOQdQ%6ai-u_(gJ%C zISKKPy8>3>5lqQCv_hyZ|7##H5^318sHf4uhx$bJO&MFOV0mt6x%H~O)2+jZ-u?+=$q z^WYp64&NB==SN38di`$NELG46ZJyI0s>*8Icy_8vz`m8r_MrnM^~LeJ?B>X?w`af6 z4<%BBdXgt^QZ(6+mZbysTkfdfId8&;DaW-g5f!i{gyh}4RmoyON%QlogN6a^_y+qM zpP5TfpqtGM*2}kkZJ1`Lm!`?pZx{%NELLgnB&QXAK!^fL>9~x~?G=)_p6(o}w?Q#0 zEl06Rns0?_7nITyI}j3I#%sY5?_r397oFpI1!5_>{_MI5Y4z#Bxh$NIY}LJf$ijpr zgCa#^jp6LI#ayUe)w?1;jWgwTUZB_Lj<46?9BLHVQ?|`-?mw>YM=9vUaC7NKIP5{P zd1cal$vWU40Wb7$vd5pSm2yFo7EX!R_r?eA+@Y&y*9?}jJ(ll$QU1Zb+RJUdn$_B#@B%J-g3x+`3J+TB?2VmJ`_64bJv^l!cz>#$G5w&7&?hmE_VzVvh|oX9o-R2Qsm2VP%|g%sps zw~0CROqAwCL4r+qPITGyVter0zD`D;E)9bW-HW5Aq3?`6Unv%ty{2rXFYJ7MobKO@ z#^``LE;=n3Qk@@CC?hqVnfZc;8A}@YXI6+V@=bi2Ul$OOC~?>QD2J2zf~ZP|A$%s) zT)f%|HoF3FNGvQGd5=}0BgWnJ>~V}8B1Y=}19$}III?f4#nFWxMt7Bbww6&Xi6~tA zqH_9`$^k9|-uRS8xytcFaumz;VUEEi`hH7vnMs$xQvh)uEi)=e{1Dzdz!Xr=!lit^ zlHGi~3X29tJzXLIlCFkD?P_T@nA$l=Dcp|=(PtCb=qk?k3C598jV?Lan48_PtBOhy z%9!ut?4DTdiX>-J$tOJT=kx3*bs~Ae#0OBgK!L*wf^l%!j4m;aE83>?Y?N=#@il%* z^k0mA2!WCFIg{GG6@BFi@lryPcIJOO5_r-m8@icVF%k!seoNo#lDOA_b%&FPl122w zGpBS9Z=&L9pvd?)|H69kix?;Y@95=)f=}WF$fh|y1yMV#4N5Q4N_&6wrxogS9`AxA z0C1lvH<~Z@gj+df=2LkPxtAi%&I>u*vvx7G3H|KPY>w}ag zXK$5?ByJ4nlxkP3kGcO>vjKn#H(MzwvrZ!vEdjKss1gUhzVEL z8+{K{N?}(7W;ggV-DkR5F&Y8rMWcxj{9K)yVx=zZYQ-OZ4SY8Cr#o6^<|^5Wku_xV zqkHtyVT2R49^4~8UoX!X7<-lulrKS1P8Y7?r!HZ3YqxmXi)Ck8UC-gOfu3RFVO#hzNtkiyNplQkrCwLjc@7KvdgWiL)Rpv zqDQDFwPYl;yCZcK$Ga0t4IKz1Mblbb9~_MreoosjkW<7fwyt@KKT}d+Z4izy=N5$e z-@DR@WPi2TK{Gz}Uj;&zN@de4fDk3kE$C4_4fYX;;rxHy^K?d85T|J%bK7gHv^;<`JXbyrY= zhVO9~baXpWw$N^QsHa-%eet}OiCy&XWKYCSAp>;Q@0d7_E~SmA=A)qWal4VS#onKv z@R3#N88oqfm-z_;c|6~lm0m3e-P+NEHd)NalUpnemL^VJs>yS|TnzV@hJ?3mG&_(M zrM%8(cslm5=*k5v!7pfanW-0E>OUU~{UgdD{^Fg8-*(NR7H`#tE#SY}OUU^@s?#=` z!(8`qIGlTByy90`)oGm8`kP66iG9SB8~AXj1PqPY_3C-nd~aNm9cnCxApr96?z?Tx zJmEaqUY}7nu4m5{76=si+$RwB>Y8MGvT7=MI=7CIMxKQ7$-UCyWuh2s{L-<=2YXDw z@!uXx&|+A3ShoC2nTDC~y_0HpE-kSzg(@Q~W6NOzk>#hr} z$ba+nrbB7OZXcjOY>hYYHmWYtZxUiqOl5*YO*1-liZDeqctu@It&&db#tQ7g z+d;QgCM8xnC5V^-hx3oFy^N92Rohh0&sW6l`6;h}i{bi+1(>@}D5}3wKXC)wn-+um?Rjz_H(*qa?x`47iS-C7_F*X`gv zt~E@}@^d>&G$G$!oZwpnAS`6jtj&H{QC!jBV=zm2zaqXU$;h)>>RkZhfqWP~fE=p* z(pfAJn%yU0hR*Ky@TLQyj>hl~q&r9PDnpX>=J{A(B^=Q9D%dAP8)S!LT&x>?2wYy5jLNPnQWm0*3{o6*S+x|%R zL93iyHw;Q0HICoC&EH~nviue)ROnfy6BmAN5QU7CUG&GJ8SL!Pw`}+Cv%m_e$(O6? zQgf*itV1INt^|r4x+R8Yy}U=CJ?(x(=-G;KF0Wuv=SZKrH#PcWeXU66 z3!ja4+KQ-i51vA3IRhpdG^OkzHQ&SW5`z}z`D;|Hg;5QI&Ic}A=bwVCayZYngFT$q z6XTbbk3ckY?tST8p$DQtE{k45GyZ&qXx=w}xaQXha*$spNno#Vt8=`G5w0XqbG=_B z4FrmbNPQHczxgCK)W#o2O>|mahd$B210hAHiVi-0At#aP8KbCx)c!SrO5&Vssv6~* zKAZDqPZ+T?-2TVnDvI*e7uq1D+B$VZbZrG{ZciSu>xDp_wLj8gbrU(9NjXGU`3h&5 z&-IM!IdLb4b{jB8vY?L3uL&hw-eb>7#s0XrTp|8m|KJPs4sXskax_QzSG(a-NPf7F z--zSaI&VI%Jzz>Ara2*Senba$Rs-^Q^d?L=7yVlT)n9nl!pHCa9nSM_`g@6351eak zp=eAX=yhD}4Qjc)#J)P)cWaJkctggfRZr+~v~s8=@fa>DyInRA-r)?(_vG zc3~bNVoK!tZ^+0+KV(G4TbnE`OkhPWOdu_FWBU@aXmGS6$YU7(&_Cn;*&?W z`s{hkmsJg4OG+4fj@YYmE=o%n*W0aKfo6#p!LGZ>DR;G|j~v(fJ>Z7nB}DFDY{IW(yue~EbO9}u99tbhE3tnp1Nb7r_rxUke(oN%MM<1JX{{ZN@)5H}6>+*7 zxJs+v$TikDW=0O(6zeP){KugfQYsqJM;Q@CEu&L(3wD%M2S+--%Y|aTQW(d73YjB_ zN!SzRRyx&e^5m^|-ddS)2E@UjON8#(ozW>02{kg5MtXSfL05O#XOoJHqtN+`aXVq-}>&@_*%-yS`Om0F{pVjY5D1& zLX4zoUiz2v{#Og2{n6BXj{f=SB z>#$|8f3ooGH#U86cq_HvwF9_q`av)b<;zqN50Tk7)1eZ|__bl=ibk`KCu)|hl{<3{ zkwQ0xu%ueOfZ#Nltqo8qxov-rWmTVXj4z(8UknoSv8~fH<^%F8D0&~UmCwdW$ILM& zsz|KU#k1*H^G9P%$e?`YMAiO|Zrk8NwD$}~OW1*EH}j8He^A1U^o~KvQR?aR;;o8A zJS-r156N?^(k#&?2ML~eeVbkVVCuZMtu596nxv{AAr)BIA<5b4I6_*)!D9PxrZn~p z$eqvOq`jYJl%@*BGzFYXu0{z}Zyb9#n7^Fidvm!)+X=KhltR!k9gyBYBhAlNXG(PI z9vgTcqH2Em#Q@28xjV<43xMz1tm4S1+f&a zS?=zT{6KWHiuDq)yFD$j@?($4AaqlI5o<0|o+dDlr$)-@mLenUcp-&Ln%ENsCk6Sa z35(4W&0M+b>>}u6!fj_s>$h+I;rkE^m*9wf+(a6(#Xo;qNysUX-`L@bXfcO;#4b_( z_(H)<`njE%UZpuc8IL($DJDi`!Yyc_&QwYhlM(UTDeF$Aumv4$JXT{52~$Sz10baZ zrDXohOU2|!&o$V(Jw^O(nr@644OFy;@zo+KJ$Q@TA92#yB*t?yb?2b()M0N%Q00{a ztm!QCLxH+jm8-*mV(exrtP1!mEmZHmzprq@*63rPTR+5wr4aqEo*bML0xQoOaM6N{ z>qiT{QAhuMLf$&MEwM$|itXforv9lW!S{kJhD9)jZL+8*XzVIl3B}afc?I!7cA*R_ zBQ`Cv9Dod;+v^MW^TptAstPS2JbCv^F6h1fwGArp>LTu3`e4E=DTQL1m`#3_f#>G0 zbP_m#BlnCiEg-V_F0qw!Y4Jo*qG+Fgu2l^1q2^dX;#edsMo~)Vi;^;~k7QKJK#%Zm z=|HFzsAo*8C7?l#|4XC-0igaqK$I-rsmKKyfr+ z-4c@b4k=O`(mYG$lt%3(oL|J+@(7WS8sW*acC};I^VolSRzu`cRB8FB^7+kzh5sox zcFlupK_AP7sK(agssP!&Fsk^}O~N|71tnT#B2wYp1BHDg=LD=|x4c%lFBG*xQ)Ses zYhU^(`DnbN1V5dXUr@v`L~BIsT~(y{=QJb5oglfJwd(Zwi$_5OxgnAJD4+RJpU*F$ z6b`&MyhK|-Ot}h zvp}m%!rBpnP&~m}>A^^@$7sCf<+3YS7FgDlOhoddbXpN?As<>%?1qw0gQCmjwuaUr z`qu9*t$yqNZIk{v`%V;r`XOOrcgJ>u$O%<{p#2&t{&8+s-me}lr22DqA`E;lQ0JAoK~4VHz;7&6@cA5L3|UEH86rh^Ph%J7%F zBHQoDKCAKK49zm*?4w457T@$L9P$>n=ZfQ9oYe5F=3LE^Z?je3^tH#P1+yQdLw zITO`3xS3P&?aJLwDTJCz(ehn^m{C#_K^%kHn#NO=m#Kd=|w-C<81Bgr%g+*87?vK4h z^nL9GD59I%kH%~;dClD@$ak&(#|a}la9ax^#YW;BWJWhg9L6mkQ5VNg-RUd9K z2>T?v)g+#K3~x7EPgJB`X^+ zWD_M#Q0KnH=@kIr_Rd|)=hj(Nf3g}uDP_A3XS<~%DTN#X-)=kr!dokN{omD5(y|B5 z8{DCqI!6#gnX^@_2V(JiVli{oAOeoWqzzcL&ZrZ&EXvR01F^3P5Y>{-*{yFJZedxi z32IT}aVIEy(e)CB9wu(NSjzrpEd#xRzPIx=t=Ts?P~JCk=@wcGU60ZayQ8p4b_)bJ zc$A%UN}F9dxeD`^KcbU+sKnUn4}wlBRg#_*%ygfJ%eFeG2_t;Bbd|@>hHacUhd0IE zIN_-SR{>&90oPjoazXwxKPZz0(wfYKIlf+BWlOG@9h=T!HRG%dEE)DL|J1}ux1*$y zv`in=T)3K*Xn&4FjF4G(P;22iSS=ZL6RjnH7m4)n$!iCr3$8nDxV0YXwVsbj3f$YfWa4ayNBz=+DrWz$pDV{n+{22)7SFhcW^=Ju_8S8g$-w7wc&<{cpgua{Rao zGZ+q54YluihL-cUkNdN3^B~J*nQ)_-AvJH0RklN?QLGCp0y%AanVcrc`oskOtTC5}LivZ0QnI zTKC6_lImVb{7z^)oUAY_1GNL(V$LUCfBy5_795g)E6L{Dp96Zy9 zyi*PK!*9bMIO$ZFM&i#V@!Q#+a;juMl#65AJk@+EssG9xAYlCU2Dkkvl^n$<_(_>U zX@8=1nYJpXe7d73*IbRCn;bjO)v_=D;Im1rqxl_92%_TWt~?0uoDG=BUhOi@@*Tid zj$rIgm#+PSSpT2$qEPm19S<(Eu+4~Xg`0U|t~;9CdxY^=x&GIS=F0dOFCpU&?abvW znrzFlh|(&*STMIy>Ri zdbt_n1@$)%Q29WH!OJTv4O#YQU(athlZXzSnO>5_Z4>C~_ zo>A${g6PWq)xu*TU9WDYGrBQWU3hDX zT2Wwj`Pr|L0NxbZM*#Ji6-(a|Ze>03&v=u$SbB8zMakb%nqo7csD6bKCD9V@JZgV<^DLgI8D#$ssnD0IcKm7F?<5aau^tC# zrk|*xVb;c>?iSmjh+_vObVxCZ!YBR_JTWs^3_fSG_mi(vqiLLng||-1{!U zwdlx{NC4Gt4c2SPrv&y?PUWF~`TNkk%4#xcSFG-cZ7}=fw}Icyhx}4z)#J<;z29-< z#jv*2)oQE;_pJ464NkU3O+sJ}luU$q%sk(wPj{zNh|UU?b7B-^^NDKr+>Q99*ekxi@Z*bev;vTgGYnkX(#n zAd%lK{QXdCz&WT2AMg@U0#yn>Onl=9r$P!K5i{0^fpuPWu zFIn8`yB8CFtt;i)74j|=jSYp^*-4e9LK^Yl`7h+tCVXxab>@9x%&yW5qbMG0hDr)xON!h+?k;v6hDHRD&dJ;HIkCP^~m3ux6%i7EB)v-kH{?qa9jf zBY>lMEo{HV9*p`%cOcBp0ylkccUY%M0N342kgF;st9RORtP_epOCbl%s;NW_c?}k*fbO1m4g8_laaFE)w z=Erao$)9O_)Pn>i->{n~&D z$6vDGZO49S{hB^oh1ASI-GoSF_brnz{AH(Q;X6))=El0*-{ItY+TO=wzvM~4%(XdH zxH!0KVsO^)a+6UdV6XvG?Dl+_boPk$lM9r#xYt=8L`0V%nl&U9iGGJmo!Lub@^NfN zCpG!+rD=vxXdPxjFPowGI&Ee5^$i)v0!yvWOtckMOZ;~ac?Bi8#4T3cd#lL^Lp#|r z+MjERI<7=}#04^xX-37mWtoEL@2$q0MK5KEh|jHCY4+WphZ}yzagnLBZT~D_bCSA0 zORmcmTcm$;NxJMv18Ov(mCLMQX_AO!1#?9C`ZQa=1 zG~LJ_&Yt4>tQ;Jgnb7-Y348O$c}B&9tmR-3oynD}*GHJ1G{3awRM`+`avVn?mzzzK z=LtmGg3rxZh+Q-lTo&UV4ExUfEl=4rD`BwLOg*#Pwvdz>#JK9kx)#+&*2R(G&&oWf z;Jwb5EdUx!dQTRp=6yZ1_dEEF?f`1i1PWl2;_QZ+n>XO*SJFOm5MPPkk#ag=T@nUQ zew9RBL1r??L`jqlr z0y^vOqBQtZ!4a9Jy-iq@*o21Tdl|VL|I|l$-UsW&9QX91^upz%;1o2U!Oi6XEHe(x zKd4+5dM~kY7^e zbg6i|(&Rj9l(95r9KKm&Y&@B+89NuJ`G!1hnqsbNa7|Hx^FYXcqf*i^vS7F&MSofS z!)1;Vl3u3LQNQh6*k;*sMF(O6yQ7O3-jq^PD^QcVb5I`5zQrBSPa=H1DvA%Eb-*{Q!_#?K;qun=}E3Hg|ug zw<>))U-?)#TdvE?RE@II6^wqQt`M=PhTxMF$uXf-d`!Z2E2oc5xZTW2`}neE6ePk< zmwxSmAYg6aG2Ei_<*oYid7&J5gJYk|zi@(i0;s4f)moOGu_ui<2T%3?$a2!hOsnPU z;U%4js+Q}Ir@K>v%q_x}-?gy2NZ6}K<*7pB=+u)tdI$v6T;S=VMF(c(49y~_%pyM=d?Q@CWgNOQ$0d9=l zEL1QJa`Yb1f!_S`Xr1mumM=VE;OJV+OV}ghCV9JR{C!znICWYLnL*a0(}N{@J}gx2 zhawD-&jIM2u+3lS4-hEgd^3yTR0h~+(AjB^@bHSx-SK#TEL0QISvL-@qpP9E@XZHG z;_lV^si;(Jzio>5A{Z8unL4IxG?==k&SJUd!|lXPe*h>ubCRV>7D$4B$W zV7}{KAF=sAi;-7YUrOJduHhFkcUqomzE~sYu^5pu_VmA<<1PGW!vRp02kBX%{TM6F zmS(NxpvX>APz{a4{O;Uz_II_-lp!d#RD51v6AHzz{^H^a{mu3aXn`UM$eYtA_(ikSp)tcDy!_{c_e4(etzB64a;> z0EzOU5_CklI9la~2>SFE1&Pn9nX5>c{UR!u*en|Szf;M<^+^$OnbF6{NV^)!kfhH> zUn$WG1Y-J6V(kp&nmL=h-mc{W%}1A`s|D)LrCk+vqBnKLGqd-*0eia2V!5z0VqxWxK?z<|>2%YAW zt^isiKAhdpZd`Y=yUQ;?&QAD9k9ZYI4Sd9E(r*36rUrRHH-pUC7q+ct`YE{m+u?cK z2Mzje6L1vC5A`+2#3W`MalO~tYDj=DxNZ2kpnK-i-ByzEEctlbxEGu zH%$(CV1fkrMYZSedkl$d-k*exy0;CYKGU*U*@C~Zv(YXEqz(E&BCnIJ0mzM;WV}rJ z3R(z+406x~MO*9qnMokL)J6^yjhfZ;h)LV2%Dl^?YND?oQpT zOfk|03{&J=mpgC)@sohma34pJHLXT>2f8JvX>gsGkW=Z7oVnLaR*HK+eZvG?t}&Yh z(_r^FTgl<4sYZ8UJBQFs#O#V5CXg9^-;2!=LE-?0G%$P-exA~|MxX9?N~U|C!T~=b z3=4M9l+n#MS#4frVhlWpEv`K<0;#qB$3`lV#-XAb6=8D zZ~lW*IwaOEX0)?>R37&K$JkpyRkd|t!-@d{N{1jV(y4&N0VJhCx<8r>6c#AupQ=SwJo}c|iT1PaU<~Bc{zE7M<^) zjEr0ibDS(Z4sn~o0(!I8NrzyMca2NwhSjTU1n#RU@!^3PyjsmubJBd4P7RGehgmF4 zn@KaBflMvu+Y!dwi`U-I9OP&dOty!FDsdmTEjf~i>($ueAuW7^5h6{5;bLx3#aorFK{+1nLin_~5Ky7kw2~d7uaLxl1UiU9PY+(a5)0CQY)ly96aHasT|D zEc5Nh(|LFg1gNEa`($m{Uj`{O@c#j)(h@tbvdELkq&O^p&*_-=R(e$Ty2;?@m;QNg z#q9@4cy~YhxNU;0x!t`PY00XaP9e{Fu$7J@qG~^=z_EQM9`5PSt}e&+x>aAJUGTTZ zwOQVIvm2rNQj0!u9A+&up^*7e zh;zt;gXtb7khx5GXLo-kMNrmKwYkj^+2KEH$>W%J-aT#7~ey`L^DLK1P<@?=mmu5e2>< zAfft$L>>Re&!$Xw&+jyzHC5d2c3o6G43ZEe?5``L+@N#j%$B{Dl?1crCPH8pHbQRf z8$@^^dRV3TX+B%YFvCj7Nyi2y*^$#1|ExtrXOJYs)#%RSY>YRPPx|*zL~n5jzhpm8 zIT|LFe+1CF3~Bmi%|Bm$4R6y0#+z)L@p^>-WF>zeZHVbK33%WPu5yrj&FD3s5nRjI z5h9V=@?V-AvEnH{L4VJe=OsLaG`Y>DGi&8xkMgEjo-s!45!$Bd-N`QTZ?1@5G3#q} z?d`EAt9)}$8I4HVyrmpj3{>QGelkuD-ugB^y&IWT$JU#Ou2<83wK5_9p zQ>VuEbWeSI%MuoKwiWQydb@D~3M8T#*#g~_@>RYK*UD07z2?ztLweO6*`-iu*q1m) z&nmtW;pc}W?>ScYX{MK~q3=Yc*-W*pUu3RgNJ|j(rp43GU_w7#KNzmtHydaNx329a{abJ-$)vYKP%gulSmKu&H*r1{tjjh7h@ z!C}M|w2GyH{G3QzR<$`Bz_1BIkb4<-T49*M>o$I)_3q73xPauo!T3`|0AyidVe`|s zm=cR&jjy`G=hts&p^}m`bfVlhjYsPZv-RcIaD1cAz)zq+LIUSU18pQlMN-JoxNj(( z#2yP9u%cw|&XLd5`8?U&8?E}B#cf(>vsYOAiG9?_17G_QIoXBBeUL-btPbwmj-r%( zY0(Ut0XGoujbb-Y1r{~**K*)8YAlXci9s_RjzDYAE-03>W{Ah`XjX=8)cg7pJAIa} z<_S^MtLe-xPq}n?ZhC+OcM~GtHNqoK+5^E9MUp$mr9)v|eXbzQCO}4~K0isD3Eg;) z5}xbtQH0d5mIa8t4q&EZ0xqP1K;q=eP$NA|yoPsku7=jM-f6$%@mMWYgFKq^;@+q= zsBM;5o2YdLyX2l%d&wUDTa5H~4bFK%prU|Gi7_vEqCPJEpm1m55q8VDb!G!U;n3lCgT|Vb^4Qv`K zYZmN<9C+KqIxeG@>AE;-I|$0K4HY>r$(*506iEo$7Pp8$p}dy8{nYtRO!*I8uN^Jx zWP7utIc(*&-O;l>?ao?4Ed*Lz)Pzyf4_%Lu9*4Dbo=d74Op7B21wNB-%z4`718Kxod^w$G?e%&ufbRNGkp{g1-KNPcUKdUOeBg%Tmec zlZQjlPoN>;jr-S+fRhxdD$AQgAZ#1Zr6H6kd<}7IIPKw}%IPAN_UUm)Z!vJ$v*oMI zk5lH!Z>o0$-7f(Yk46%@Q=Kjr&@>WQ z-hpw>ctQ6(K+>o|KvhR}slYf`c=#T*DdEr~k&Wo|cgpv5;_Ig48=qgx^Ci3Z4G#^! z2?6b6Zw5>;x6?sap!w+2)sc#xgLyDsvwln4aSkV4I$`9ID)o6g5S)E%fuNCHstMS_ zNE;yp`nVDM_G!;0O4u7Za+fdx#~VfXm}sV`@ibs%s4!MH5SPveRQ3Px&6O^UqK{vg6+PwOrEKpQp_9Ds*AGY1at4IZtTu6pA|6E*hKOX2VVLEkN_q zRa$*M*_(3jh@jH!#FKk_geCC3pDO4VkW34|U>2SKOu}#gUc{y@8>5<7-x_~~`|q_@ zFcI0rRHd@Ll>Cl@WC}YYbg?lZetrQOd1%{=s`^Dw@0Q6ysld`g6 z?vc2lgRHNe-B!nB^XtJ}MS)t$(v#N`rH(rWWzQc8+o?tMTRlYo+RF}F_R59)F*_bD ztZ&af3$>LQNfGqzpYNiwY-*QxTSX+9Y(^y6eP#d4oPuSnQa%fGKVBg0=R4mC?%L$v zE-xZ@-2ZFhrrp_sgW1puf0xF$4Uj@ZRYO93eG}UsY5V3HNg`l^ubsiRqsc z3@;vKiiFNirqpX_4V%OI>k49s^IJ4FL{H?oo*B?4G{2D2>XUMq7V7hapfC`c^Rg44 zcjZg$CtoK}VqAWle+)-@IM~bHd{l6YOWN9R`UatJ;4ZqhCn6DaFBsYq3Y<6MXoF4db@$;ysNcv^lX?gb+i-!|r=zY5GujkgF(Ho_T( zq^qJc9kIgm1)#H*P4XivCH=h{{!6+nU&XIvjv$o$`I=5rD_;bZASS(!OD&p6zW$NjEP%^) zW#ma&n=jF_9&EhcnZ@w8>6b(Zw+I_o7a+dhOOlH50IYmU;`F;tfNtd__QLP-Sm>xD zDB0GSAkakIP%f&K5mQ`pOE8A_3l=nAN(u<8>Gw@s1`WRj=lzh!XfU&dt^`7wRAhG3 zq+;JY!#^KG8n9&&pXwfOgKqN$yE4S(@6ENq#+4gEot}4}#)(N*ojstvaX}KpKr%-t z99*gjP*7Z|B9Bbp0GZnt@yn9`C}YdpCQ#1b8vh)201jO%xi+QaV^82^*f_(C$~XGS zRyRSoSWBbaa=C*^LxlBQ=$LnMu1%8EmmK-5VxX_^uAUBjkaq>`WI`b94P!G=N@~vv zxm3h+9at6B0riI%(DL*nUn>}kDm9;IE!v0t_gntC?x^5|z8M)F45h)vLO(#kvut`T zf4Kqh_%S!rxil4*?z~(1X^uS*K`G&L{l@L5!g~j8HUW!Xx9_%q3`A2BoU!xIKT<}7 zUzKL9Aw=Apo$F%NGaobhZQE|!7Ige_ zm!ORgy&4dJa|a+PG1+F+enW+tzjmMLCZxhZ-DyL^;|XY}sCL@R#ptC;RY!mY;Lw@p zzLrrS9RXCgf3E}HQVZC8QdH8q7X(5-k2Rz=<%Ggqn?^}0VK}FTvvYdm!)tgw^Lw@& zg$Rxlh)xxw)}v#;k^WiD#V>ZGfU|e6EFJ&qfMX-IDV|^IYoUp44V70e?HHE$$c2CP zXBDIxa7Jr%tWx6T<uuKGT7QziY1TS1+L)K(6=3+VOR|atpcnYMI6>H2g6+HjJ`15SW zfj^-5@p=AW{P9{ClTg8m+eAC+jz6-)IwW^wNM zA1&3NKbsruYy>KQ%bU~>us_kJyX0P9Z8rR-N`jW#)8a#Y#|*?bZ)bAB5}mG52@765 zk1KDG4e+_1K_JM|msb>sY#PVn5A#Ep>LoU6KbN!fm!woc1pk*M!Pw-3)4&W1G5*nY zQfee1NpKfg$-s-w$AA6;=>?$tdD-Y;fA~kf2Os%Ymu-O9KUTxeTa*9!dhuh=n}JJU z$TT86OoUTOK&hzO-*X&~gop%o)W6`xOR{(N?2P1P66xYG=|L}A{<4iy2B`RCaWz5@ z3wk&9PDCa)c2AThHeO=%A4+T{G*(N8&5Q0(oX|MzQE>;(Tec_au(*PbCTiuv2kSK} zjDTl9mwCF^aIkpLKjF(uvU`|)h6X#sKf3vB0kPTMO-C`Sj21#pF0f$F)i`)q-!QRw zl+ZA-eB?@xz~z3YVFz!BX5jd>TRPvZqEkSN_HJqq#4E90kWQC~zLy~$RpTH0|F?XV z1w<<8c+l5rYjcVo$e-Msbo<@|Bwhrz2JdGxE5~vRp z1+JHWPnrS<+frvOlYha24+`C0<(gPOe%X8_Z) zGgUaSKlz!LM`y(M>u;n>4Za3|UcpDUL(4LM%eqMvJo+P~{F*=h3;@0XK$Hpcyn(3K z{PtGNW5bZ<$H0X@-tJ+F;c+a*Qf5}na;6pNWE%o}J4&nB&z?25E4O#wY(7B)NE4Sy zmE?j67(7j2u-bCtGq&)5fCLWI{HXw_Ww3eIt{yEpI^Oj>+A+*;H2Gx^!1j@5as9pe z^YwTgXElSjUBGg)Lc)3u5)q!)FN;PZV0u~s3HXLnvcpH;wp|bDh}-{>Jdzb0z+B#9 zCtlunIO zpoyOhB*V0(z?J|99CXKYf=Dim%XazcPI2JZK&np;Y^ozyx_otrUc-@nBu7r?N~1pB zoCXY%AejU%{p0i-W2654qLT&{f{j;Cd9)B+YURn2Bt7+)rIJ>Kwkc z@mtnv)jP3R!2rcRSP{*&5s>xJ#=V;kT@UA?gNNz{;io)b$nlvp@VsX%fZyl_So zBpfAA>n8bEk^s{y6*!VUP(WxjPqdheJq7oh%E?M>0ZD{nvtR5%#1H~RkY+16-f%w? z1RyRI1o)7|rziW`k41|bV6>p^8jAu?WYMes8Y86v2p-QNb}*3 zWMxTt`|^=Yx+4H5@HDjh#IHnn@h%}d{uB>6IRcO(TMGvsRfbBBw<66ocrvR_#IhRH zjXOFr&3;viJY-ZYeF)rlZ`j@nVM>(iY{) zb0($s$D6HBT@H$u;t)=OnQ#Z)YcpE{f@vbb??LOA&Bi!U9lqcNqb+(A zG{PIaI|7}$lSA6>Y?42D5|qsewHfPl1g@WjaIf=&7k|9Jpt0QsB-5gIZM|+h&{KF|JxU{=d9x?UXZqis2fAnRLx6$wS(;*(t_=Sq(y*$eVfz+5 zD_}az{5@Y4dS~m3D77f&85FdrP#VAw}2uh`f9Iz%c?0^;9r|sN=)C!I{F~R3k7bOR}BI`!)MW zrR=DIcSYVwVC@|PeJ(<8BPAOsYkR5MmXai&<@CEP=c*C#ex_Hsc{JHj#&*q@gB;fQ zTsG9VQSm(h5fk4TvyxG>M(6loE13Z`Z@8c%5VKCU$=gs>bA7}?*Aow)2M0EM0 zCBQ9R5Rc4Lg3K=i_c_bNkWxNVG7}*-SdWV?PSu~dc5S?#5FUSZN6~#{5BgdGUM(}A zO0*UXm@D#{c_TlmAm5GrTa0a#rpj1E0*0{bKD}85@v&YIpZ&T9{4E;uY!V(?jcyQ- zQJftO!NZ}pfeI$*)tjVka0%;U*R(>_XUg~1O%5249prrjRpKVH|x=|MsTzKrKo zq1;szWeVSZ6>ZQ)?FO&>Pf3{_@S?#uZ>B$NiHQ6byMlf@2>xqNJ%(K|mISRijV}Wg zTlPxT(A(ZoUv@1QrX$O*!Pyc)_KpJWHuf{^xKJ8i`Q!OpH(<%u(nglyUWy3Omm%q96oj|4ZD1~K}EGmT5+$qg?7Nw2U)3& zt=Pwg9r#HoNu_#YSS(|hnPZBXP}T*&I^O#PuYPn;W?EbJ18{vg`#B7}Fb+?T`EWkY z;tN7vqCzHUW!{tF2U7w5Ifgoha9@?j`A^2~ZOpZkgaToF&DLEZ$xst*_pBA;&=z5q zPt{a;?`W`V+131u5nxJyq@ly4UP%vz6q({q1dY9(X-2llYX@w&@(hQb086E8^g%r92vD){@$fB!fZIyfo!Uz=L{5sBk^>3od>#fatc;|r~#+}TA*OEB(I$% zO;m*^zPKRGQVYe?!Cgq_zYOR-5<*E&j4+Y$7)^1@QGIaL-(|k3*J(zeP?JXj9uYV1 z;Vjn7k(4DToL0f>Qmtwl9vD$79v?MdexjquZ6-%eTDJU=on=-)BwuAgFQ)FGDZqBU z6E`}hLAUib#rFusv(uAcBq=g(0MH_UlbHa!!{2hJg?`}crnf4TRV&p_`h`J|EZ zmAE_)?#Rlfdn3kC=31ACArF|syHP-Q%QK8I<8t&nKDjm>z`h&Wvb28(bKE|*^U*2g zzh2c`l$TE01h`EK2Ux3wqkDwxsG!m2gKA8~TUKv7c2Mej?W?C+_T+Vc6B6_mGWMHN zKS1iay{m0V0>%TeyoKa79Ug%}Il+7!?OL#q$A#&Ik_!iM>}IU=2VaC$Xnf?K_eC?2 z0H%WhzT9WSTW%V9Tt{S3;Kjaen6A4fS7T$;&+eP*w9uOXcU~i8G(ew=5#aYTV3u9W zfy*aALNYWc=m{Q&gQfT2As8+A1f^|T0GWwk6QZ?P9KvuawL1C>`8memUYQ za=oxIZ@oakIT?c}Om>L`WMWOZ()Ln}in$8aR&xQrT)c89mH&dVeQM!vuVS+Yer_@a&!#^@t$9Pj9-8fj;tPtgvr?S_8)b@yng!fFnGlim$%$Q?mwoWma35GX697!dt~A zLyR+deYXsf9H#HoZFkdksB4{9#4imoaH*Rb0Mz`lU&sD*6<+x?6~L2T=5aX+$$y~| z+@Gn0`!j3b=`1gWvB~6l0RQ&-#HaqN3>f&{)xXP@=(Ve-K>q$3f~6u@CFDADMd06o zBs`X%0RH{uw6^n0Oi46p!jqz{`wp`6f3AA9V=6eXKT!`jp8yKBWGYQ+2miJiZwj*Z zU*`sV*y0B?g88Fq##OSRnZKz5p5|?4rufe(gG;9g3tSwMl5X}#RN+BQ!0(W&wKL16 zg>=2oy>jXP^-TCcvSuCeGr^y94e29K5Sx19EW2d?}g6`6kg5_x`iaVJajZK9%Y>WMHaD>JDN8-_kJ)E*Mg?a;&=0 z$L0Rxu&g)9_B4OT(0-v0c9wjGW_NO?gXlRLhmS>>X}|L0Zj#G3oQ(YvK+ImI<-b#H z_*Q2mj6~0>3N<&ozFTZ=al7_cn9anUo$V3j?6-HicZwFOv4lKJa9=u>SkUG=8#s*a zZ4_8PM)5dpTsn)p{PA<=ERI8;J^2|M~6_3H%)|r32ikViMpalp69_qhUE=V zE8+(`$hRA4jb6OJ`1@z@ zaSZ*E!Ya4P|B4MSRUGLiBDj4s3tGU%p=e@+$YXr)1d)G_k@CRhsxO2Ocmr^Y_~wgO>cztWvvz>&V{`h0MNitK2h&FE)!FcT{L~JH zX+C<*N?*d4hjW0!`9t~Va2B?KbZK3@@PNl;;L23*KK`!ZQ_;HO0$f(!|18P#AsGm$ z#h7!k&SmUbOoo1qBmD+U$`UI3JysiMApHPaIFa`g0Wuk*vcm?Ig(3}4VoE%*Ws8`7CORd=S z@gQm2EmA%Ww$C(e5EC-=J~X>kmi)XylKKPRV{^L5TU64bdVQzR;j%N-(_wq$Gh)sK zDfVnxTB`M;_jvjeuQ*%*VHDTsMHg)co!{xG3K%76WJ3QRrNi)pEA>4v4&+>T;I3%x zyPxTXHe0w&ie1J|@iB0i-rv8GRQR^rezrzGJ(^Lwb=@_~+$sJkmSc}=!ClsL32y?N z?NsBRqtx>B2)C>ZpSZ1-25jM{Y_LbhtaDc`{~v`k^YdF`{Bz4tFk&=|X)1?9X>z|& znk%gWRv(Gg{ezMt$ zX3C^9YR1rFax;hUsZ~JV(AU1sUZKt@F+E{xDpCKsE;(jr*4fYTsQ00d1OsLhS98qj zDAA9qxrt(NdroV<{xUDG|NCTsgnL4hpcKIjn0S1`YyRS13^fac=7ya1rMiHk2Pdmm zYs6q5x$E)@wfZJ2qlUE4#Hm!oWIvOJbO_TAQ82tGZJWoDb+UQDP?jfap_2X%F;56l zk*16f7T$}=w!_G$Zj2d+v3(0n&V}!@q#bVvlQU9i|LFM~yG6^IQ6KVzridc!)^D+d z+%=d)66|(2Zctl$Pgn8Y#1rtBw=&P-yX+jP|6AqTr0CBuQLY<3!%?SVWEuMb&6>RM z_>QGWbJ}+uP1C?% z*+U((hHPa}^EQ8}kW6!V#m8Sw5@?dG(0}eW90g8sZEyVaWqkq^x1ZCpoOImPfz=?z ze~N4odQm^@II6iRfRH9WGIlS~N}*d+ODd#iD4b0GqsjdK>ir^eDe*pRE950ACL!gb zIOE^eG?t75)_M3!%XnRG_YX@oSn%$H$8me4^Icg7nAc_$YWq*%dV$lE@Osfnry9jo zWmOg(EW`Czv(3R&XwV}nwIuMC8KEX2J*5vDJmI$yWimQEsmUOW!`M(7Q}t=P5LD$b zrWKsf1)mShor|r+ip}PVW$KAri8gH|DBoxw?clUB3VvL99y|ItY$D>+%MlD9YUbe% z_>Z$o$_tl~%avV?!2oT735rV*?p^m7dApSwC3SEgWV~tE8Yj)d-E2yGxR+|&Wv`xmmP(m>(cu$ zYjY;MLE6kZwvaFa&jv&F_H1^xW;bCU^+Eg`?J;X4Xr6lf3H+w#cLqP2Xs@@}-pBbO0+^Uew^05MwWwW`u4d=*$wMCs(3!Lv<~J&PnAd5x-j;f z4`rX#BmWponw2CWDqg@NFoC8TXJf6Lj#CaudXL(QlRP!fR17kXvvy;$!zs<%9Q!Pr zwW-)dd|!?9u3{ek8TnT27qxcuOu|nQU!MK7PC58G>*zGFF4u`%O_-V2`KqBTHKn1Y z=2V!qRDG}9L5{5Er8?eTe?PCKsCB^}VqALXu$ zTR!2hB-$IA+C3CZSPlW4`Fzo#9=yH%ToFf;7>Pkzk%R_5$Bw++hqdN7@&x74eAqwk zhrr0mQl+1%=EVryxl28ewVP0HVQ8CBFCDWk={JP&FP)pT!pUaSg$4FClKOMoX%y~z zt_Yk|ZHba~Zp8)CIH5Rh<*GhIm44S^ zn%Q!qM9zQ$>f$N`WP0qE^-vhdiR3-UjOeR$u&iSzVG4_RBV+XKv%H#!gZL}g zmu59YgJeER!E3CI`FpwP&_&JtF?;fHMy zm|ldng^Zgs)V^u!^2xN3XYYqG#C_zQmX+(mBcGv<2@bT}+OYAnsO%(T)TJ?jN09Gh zrm^A+Nn8m`fo?pc6UR3EKg=WwY_#4ahuWCoF(ynCiksSGmxmySJ-X|~7;`ofq^%FD zTZ2tdL2N3(B{a?o3;8VFYgYT+Ss!xl*+d;_t_qAiL5nz;*ByAm^Sq`awErk?A~jffu%pbySd;;ln zDkjGAxBg(x#j_R%z{5*=vGo{?H{i9jo4@;54Y#!FXSVl!pQph*4eU7B?3WGIUoEdP zI7zuk#<(0hxy!G7m6V3WQk?C-45!y{LX4bZKkYC~E`5u~(!5-+ab3EbTDeHW5 z6ct)@|FN=kVs`|WCvU0wJoB&7UcRV?S0g&|R3&4dim_rpr8YcKsbo}*-rCvTQ1a9Sn4QU^J8P}B z)rA7~k6-qsNdBy*km5bDtGaj8eA4)M&BD7?-WVFh5QA9OI|VaT3=}KkfuCz?&}x?Zh-Wt_ zo?Rb*!2$YwcLIbGB9+ewNg#uh*-Tm&x0b;K4JV;UU^CXQSs^R_U6Q1{ESyJUjC76S) zt%47d1`E|1Bwd%e#9ou=I>p`U*@$W5iibFp@P3DnE52F2vdK+mym5B-=9M~>%gbd!?liC?va~pO{lR9tGNTB`tO|l zY$v~L4&k$A5u(Hx~F|nm?_s|U*j)y`7 zOoB1yqXDshD{4DXR9vqY_s$j72L&kV#MywAYRQz}ZP*-?`(e|>FWh`S84VhVAH+W@ z78-wO1Eea`PwEbED+e2i@;(d=Z4f_YE)O<4BH{T+iFI19^j%PN5PzgrIHUfnt84wk z{E(#YC|eP?Q?7IIpcUciERHDj?R~@gu!yxY_j0%CsUvK>*XIYfH0(|DJ;%K??Onc{ z$|n{V%?@u+Vr41K!)te zFEGz#cpIe}KXYLoN4#??$s|Tg^J8~ypN0iWIPy2em_m_rWUbk9n^V&4FQ#gYV5pT@ zwCWirOqKEY#TF1Ck$$q4v|LFOyo}flka@U5QFtsT$t*0VtV-edBm(a!W566O3q!#6kNVyJdtp-Wg*Csxy?D6DU|}SZUEveKn%Q#ewFL=0 zT-)O69tyP)-})H8Rrv0jlSL3OoA>Z4;;cC=n09?-3h(D~E1i${Wjdx^p?QD%`BJM= z(aLv~ap%gaf}5r$N^kM~0$yNG*1VeY(E!8>#BmU@F@&awKBWgdPA z@CJ)s{{nBaJpy%MrM4Mpi3%^b(;%;!Y`;}r(_HoqU6Y^}a;P2cd+ zy$02_d{?24KqB*Q;qFvcl;(G+{Ltq*$_&WxUDqyw7%j8?=-_`x1=l=xZXrPrB`-o2 z9g(JXW=-!xT9>`u&G!Y?zAH&~L2_8QJvC-IjJ~z&S`jb#wiZa9zvn)xu!66H#KG|s zy|%khUo6MrBcorbi3LXq+M`=ND9R(t`Q!2A_Ghj+j3(L9yt+;m1cKxs4d;q^Q z&!0PcGuNl53yqAza>g@kZL(eVI=&j%Jz?W;Tcn3HN+*Zr$8mo7u15DLPkw3HriP&G z(Kt15cGTo52M9PutN26G^;d?f+*mZ~>LF%h8^_ZjXfBEn=+Nnco%~TAVs>S1!ETxE zYlv|Sw`Op%5Hbz zT8n;%#P8p9jl-0=ZcDiqH3Tb$_aY|wN$|$~ODJQrb~1itb2?e&8IYAO7F_SZRpVLd z!&2@Jukf`U%#qoPY#1Y#T1#G!t+6*g-u_91Ik}*D=+t5(Un%)FmgmE<{6&P?xu&pb zH+eHdfXjwTvr=#}oE@^=ss3wZy8K|FmDPMeT+{gy#VS|jRlkiMlP`heb7EEIr*k+p zrfxdse)3!4{^1wB`p&OIB0VOdd&Rbm-2r{tH8LGCs%hGG8G}8LK87g8xEH&y3@D;R zgwM06Mzoe)39Hbb*zmLa$I8fp1MPC};y;)vfS4L|4&4q{;_~(wp^tXMSGYM?%F?Dj zg`9MEPC&&vPy;yXegycd+al4ZjM8vY~s+k**nD%wv%Z5&w=au3e`CI#lpI z9Ty&z@qfj8Lne84RBNLD+uphSYw5nv^O@V8l}|Z+mXhj*MKMQ2hf8Jjg%=oq()CH6 zs5Txqt*y;6Q52Tjo-Je*M94HU+)bGvo{)z(Fn`^fv+VXytK+{i&1+YAKHxN41 z^Ton$i7j4|L%8$Rza_(;tOgd67ZvyQTsm$$2#oKRyhsk!>>la+`TBnT{mFhQ$qu!1 zd@Pz=GHJJ2!obQIGo|kjw!Wa1>NoCInvE6ZPNzMh z|6u#;#UAz^`inhgxwM(n=np*scSU!1gOkR|JWqEeIgC4b{$2_fd@1sA^%qMyf-hw* z>%)pKtVf1q+&IqjWpXX>Q;i6;gg49x3tLL|_ggqDJ`88e654U9v+B-1kYiAKi%_TE zn$K-I)}v}E>RhJ%3f1M{>{Va0WPN*xqjZC5%Gba$_2!ko0pAShN9DH{_~(Exf?SQB z*@>2rK{Kr zVvS|Ce1`2rYl?j~gWO|_)!QLI!K?gY^~+%K;M%|i4CHQj#^4o&cvn#xJbi_pdfaohsQ0VbDYJ(8s#ye&UY;>P=H#jRMSpyK zFmLMAzGCrZ^x;PD&&;z^clq1mJ)dh7izp>IOnZd>QpYA^VDs{Xb9~Q3r?Oib;9aw) zM=w^4}D;nps((v?2BfdvIU2$0MpXXPyPk!Xl}D6 zKVu^={UxQLz8@#Kv=`=Xmk^R+Qu`)$>xFjf&~}zTo&M5DtJA5EYU@MlrmW?PcS}BI zv3`F&C=~|a3RF<jV^J7#t{`wnt!#eIFjL|61sSWxzjIAY!iHZ3OeMgJL*+45XW1{e0U>c*E$;$sG z-#Pa4S;yTComa7m(0$LM+07Ct%wBL!7YTaz7c0hJxLT~{!8~Rxw|uVC-%YRMwSYVJ z4P}HozaeQfN%S zaZ&(WBTl;Y;XJo#uQC0_yA1IR--;Gyak~{8&os^w`x!NOS*%hMn8)5TL|g#*6})rb zM1ro#g5k~QNQwiHR2jd1L!DF_DE(hc5sqTl4(|d|FEfB$x&mj7Cgn8YmMM74OFOh+*Y1sQk7;}n}~NeK&;BU zi&1A|q)GH6IV*WO%D3w5LN=6vvvj(ZHm-N+ER|Su$MVc5I~IMh8W2?Oc|ZQuY^+ap zi+7(1eUH+Iz(=hj66g5X7qVUDUNq=_H2H~e_9Go3=P&Vh%wwN09{(+&I3OXjw;A;3 z61s~6yf+z%zA(a0#>mk+fxA1QjT#hH8YC}K269$imaHcby13+%SK^Ey)7`h~AFnoqUGWAabfyLGful9i8vGqKo!9 z>e>T03Zi4RHwJd1>p4^iIG8v2kbnvu{Vx@2wE?fKIbPc?l5rd4o!UcqH9mVfK>B?G zm#K4n$@m60i3n_y?~HDufGc~VGhf*}Qre7QWIM4tkSp=##CH3et*zhXwvD*~@C1bj zU#*bLQUp4UMd*gnfm+A0ng4O!Tufr);m*|b%F9V`NC{@Ti;=EkIwmnzsT4Ogxs(pCS&O4Cl z7&GU*M^g3tH&xPr?aBTeAxHIdkq%%JD z%%zfjV)$&L(h0poWHrdpyLVe`1SKUevW{1d%qlwYt^}h#p0Afp8AQsODXWs*@43%l z3A6KfMrrW4iCadSiJ16DL=Nu5G%EVAwsad!ja$n_Jj0rW4denKkuWQ%m152v5uyB$ z^OJXYgth|Ae$QF!=fqAg__wwA-X9or7mhVA=>50NzffCH`lstn&=PU1k7dU_cpZ0~yn=fKYRA#6Xc zDEPw=@rv$iA_z2?g$3nr6cGd{a!=8i9R3i#Yh34OwYilBb3I#%ih7~(A~nIu&X_!c zWJR~fe|_hMZLNhQbd%I*yu7eY*cX5|x)BZzc|n>$+eF{5@B%)NYvSQEODNpi)KvaF zth>gLvto?V`Qb4LEO7TugM-datrSi-TUa4`hb4Ec7B*0S$1c38!O;4v0CEkX5*{nJ zh|68rAv&FBF@>hQ$Fy= zVuki`T9S<)o5RE%=-2T_^M9Mh55P34i-?ikB*Yqzymk!@MNH_K0yyZNYGgWcF@^aG z)W_RLghG2Slm)$ePYOfAMMbq}&Auv&}FOX)9vtF|dzwXa8oU#PZ9Qwy^ujoFB;MiK#EVwm$iwW40BhbgY_ zY|MYj7MhMVvG!M}hjvBwRVp}%YwjtAS`cTFD2!w}X7kF8S7=t}oS>0#Gx&?$FJ0mH zSshMdZkY|8$)yb7DjDOVE#Eb?$$o;0@+MZryNQHp6rLnvR}kDo zP;Rz!>>p3pU785Kx2GeIQ|#UdOLi$Hm1El3-hQ8&I?%Ay>$Ci6yihpCbT}+CE0+o1 zpb^Gx*kkIfd6>hjc~`&02By>MoTGK9JkFwyj2vhiYCC8$wh0_O$@c%ddt-_O?P*rX zi|l&L-lg2Lugnu)PAfS`AOu;IzqK-Vy%sjs*V*$OqH?^W>)N80K+f??Su-I~*|Qi1 zEpUC;aL=};zI5wnRqfoTQba%AgCn|E{kGq5vWBao6ZDkpKPTK}l0jSgK_=j2V@ls@ zZmK$$*lYZ0yJjY57o?4%Q#i_*H4H8tR;SZ!Ps{Bf|KH34G3LXu{{Mz&5063MtSbe+ zK!amQvH{94er9y*93FO$XPRma$3a!zz3x7Badm(E`-#NF1Nm~r_bO)eTGDMJxxNuU z`bz%RRt6Lzy_aeGrALzrZ`kcEJpZ`kQCnxHSfHmB)1YPGS|%ZrusyUg+p+$Yu{!%KmhLiC~;b351Ff^HM7Wj)CT1Emt8HzZGgm4&svT zbyJ+diW+=4h#Qs6mofB@osgix>MU4)!=4I&Jw4g(3+L&Lr!f+=509P(^O+BH2T&R~XXJTXxYnqio*XJ^&aBYf*z?l9i`HV(svs$JWrNOLi+o&gTGb+* zE>5fZB<8!NC{J9R=;y%7aYlw`kQjV2=wUguoWYQzstpd=bh=(66}0S5Oqik8@oq7B zZ1HJSLXk{y(bz{?U->dh&b{&_C6>AR;T}*9hK?`q=lXD!G%OEcA6gx{$)WK;+@F}^ zKRkO(Ep5K>>&07yAa`Ba!9?2U?oQnVavQ3_miBh{f@Y(&5LTKuK{$x^L`@(`t14Gf z@~~B=wi2aL$KBT0eXQ~&ydreywnx_Wm2dxgp{1t7O z*~Gj3AD15KWSWkKJ)+|v4ojy{^|APfoVj;HCasruQ{e>C)YfH8r`G=DF4~88zo%eN z>bcqr-EvdLCsLyjZHgQ8`~0oPqmc_m@A*a4B6h|(spP-}bfysrg%ZS>NNArcGZ^PO z^&9JF_xzxQXTukxrTAPF7|10#jvfDpv(z}ne4@vZS)C7R)lsFIRVH!;dLc^Xtd@3< z2L+`lTD@%Z@H-<`zez3oIpODq>5AsX)V(EFttJ=4rJr!`r93!t?D0D-v6?Vjd-!m; zYM@7+4EFt}x=_M%`v-zfRqw^nY&o_o8Mzi@fXN-G$Y?$m?VBJSD|-E^5chwJP`0&Y zw|ia1?O93umoHH#qS9TsgR}rbJI1(`)aFaOPlV519@0uN#q&;VSFU1CYpn_rkmMf0<ne*Q+V-b z(N%$M>6aqn9MjoxQDUle29vwH-_4JUY}#^h%wucL&;Ei!{w75bH7U=jT*TVkKqz-7 z_TRP)D6xo%mc3e8k0>?XkyEXp5f<;YQ_m??lJy8J54lIP)=5m1+4}n+Mpo|3+$P2d zCyn?;?py1;tuZmr|Jwzj zhr1xx!Z6Q4t>QUA=e4+mh%B}C+0WyxvD*^Uma3n&{6P6bx7vKh=NTp*@H=0M-}qgf zEo(%qs{H+qeVSlGs*E(GAdBNJS|$BcKKHW%XX*cMr|#CrD*?;rFW%)}`={=|d;RK* z)HsWNgS(~HVc;e&yz`L<%<;Q9PZU9Nyc)2xf0|ccPjlj$H%xc6($a%6foU=R&lAn$ zwMkc+ZKB<#*?zdPP`&!_28QT$*F6GDx$57X)>Z+|&iRKQ{C}tZuFAc*W4{l_Z{Sbd zC0K>Of$K0MZteE4tzDk>Q`OmnH>I4OH+fSPu*Nu9J&>#k zN$J30;{7^#z*RPrr_EEY=ASz$zFcm)e7&X8?e9yacbWO~^JiYu*s(=?cb0H)*`&RZ zi>)3d?g>7_TD|hY|8Dtjr@rjGt@8B9%&zOzrI}j!c9m;Q8SN5xEv!DH0t!5M;yS@ zxB5lqiY=LfYNgFJbJzU`b+petkAC{%<7UNOQD5x0A2}UdUS728-Uk-Kl_PNdjd^)J zcXyYnvUWV5%-Kn~)&8emoz>iw6T9i*_l3XKtqy(z>MzJVP+m2U>+IE+pOshMEP4^~ zve`%09as)MdH=n9qIR^o!Jhtwoxo9{88ceoomEhe>4qXOp|oq6LMDjTF(g*??%ck! z(sk0biORqE=L16)=uh|5)9-}y_U@lHu{8C~hHpk2(tDyywPJl{ z{R=#XkZ1Z~>EQ{6}F3vn~^iauuwjBxqwM^-gT=q1(9@^FM!@XmR zOmuDaX6V{6XgfTh8<>xPn|YtF1vglBC=}Gqc<019P2s^dV5r<~5kbm;z}Pqg3VzXK zJ8;H-D^|dB`SYc$?X2(rUE*RnT440|(mlp9cSM#2_Gf`5U)q5r;ekQL}i*f&a{BZ_Yc`b!Tb_0}yz+`njxgN@xNAjGzd- literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/do_nothing.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/do_nothing.png new file mode 100644 index 0000000000000000000000000000000000000000..9301382dcd093cf663cc18c89fb5fe0e57a3f438 GIT binary patch literal 67002 zcmeEu2UwHYwl<)Mq6iA;SSXGSQCjFAy(^)IDj=N%LXd=#AWcQY-mnZ^q=lwpD50rf zL!?OWA|M@1eAPF)%P!GcYhtu3raA6!O_0fM1MQBP~^i%*x#Z3=A>{aT?}0w4XE5-HBnpxEl4- zewe5$28-J-uD%}zv-9*6c0}5_c-f(`!X8dIPz0W%F^))Qq?04H4onm#AtWj#Bqn1b zD!yM_MH~ixNXiJyNQ+xi>)W|FdC(e!V+crhcf0*CO-W%<(3F6=nAm=CRq#m{>EZ1M ze*4Kt*-A+q0-sboJ>8wmoa~PyLBE=k;?lz6QqU{MwN2o<`(bL}vpdqw3H;J>a&W^y zuc*0tVbGvNQ%p=uSQPpX6dKz(+j${ZH37}R$H@ze#CXuAAR#OvEGAAJtrO19g<9;6 zv(R*r@jI^W$qSrF7BX5s7Wc4RuOYr)Mtr}l3hjfc8s!6Qzp4zaQ6x?97-w%= zO;;avO$Q?vUt3YJW8Sugzwd+I6WUM9%g)mkj&XEy2i-aPQ9Bcd$xwy`O7OISi;9ZN zPzUegMem8$F;rlTB+#cwd(*`m>F9)|y-j@+hrzhxke)vlI$%6JoE&KTfYzd&mlwwO z$7;?PciQ}Dbv(iL`Jr{F!1xcMhDyzljyP9pT^X1(bu3W1wiD9DmENDV`aY#-^=eTiNtdS=1_Rn#wV10P(<`C<)STQQant2U>j!MbfBfAQX?U$1 zrvFNFV82q1ft|ZIedAI0Fb+@O!$2IAU5-RkRzMXT85|PGUDwXu$=v{hMdGLj$R2~k zVbI_dyF(9D?Ht@(yfEG#j%pZp47B$hot*8w-GR7PT2OIExWE;PSRa@DFjYS^kg=M9wjRt9uPR}0=I8A|@RYFE za`(0)h$8K@jYJ*PF+RHDj^d7ZNpUz{(#HYq-~%^tlhiksrPjmixHxHvVeLKOvN~v2 zQAceRDP6oQc*DWlkpTC$7eD5qOVII!tE>1ph+BH-AXQ;@W~SnXXjusZV;x@|brl!5 ziH4*u$`GcbZs-f1ds?cCB2Bb3B`wX5Im3}UV4Mb8M(&m#aOjh^o~V1nU!E2Trw zA;8Tn@Nn?VKuwn5sO^rmG?9=2?RYw9QpVz9XJ!awqKCCJSM{|pH^S(kBxD@WrYJ`> zRg9&XyN8`Nc#fjXS=`RdNYoC@8^}UT7p36`1+?kvAP&iwG6uX35~vwf z&?{w@2xyk-5;D556&YzcQ2Ta2=3`-IMELW5HIO>m)H#BF2)ZZ)`0fVA1FZ%0*+o_d zDIo^N0eaCSIDq{?l@T1NO91nr$X3lQEE9-)Xz@c!5fa!guzWcak?fNpdCX$U3FEA zt_ihV*F+OTYtPRNEeiTF^wv|?z{0iuwf+25E`M0xzeCPoz2Qg+KlmTlnm}7?u%f@) z1%8xO)sn?JnK}B{BUOFvVea0J+F+NUz=;AYr*EtRP8Zx;&qT)sZY<#oN2)-pjMq`u z@P?~{GCZY@AKb(RNYvtw-w76wq`|u?1U)3Qaw>kHJs4Oa7q}X=jB|`|R~+ahf&^qy#8rX)!`UG{ zC~yGMX*2~4l&TZW8vlukrxg8dJM-PzXgLA!gY&`zi$iNsR#cQ`BxvScNJd&pSa#Jv zN$N0szgtc*2^nc&TCwXY!zoE`%8q8RT~@k-EXm(v)Ic4YP5j$ag0SfCOeYO^`TPxg zMKL-QR0@gL*Asy-aZODX6)-<>RV>a6 zVUu}BvP9~yA zph)rhYC0|s9?%>tfa!BV>S(#T+nG6H93k_MQdw=5MfD(f1>XDHCRu}OlBuTW@9W3J zVs$?RIISPZaL}L!6$WVOVJ*z{2*Au!;g+$E50EJp&S*jKM$``&5@6bW{eYR4gq!&S z6RsnwYb+tDrv>+;m~&$Z0xLH#-qz&P=GNM8WU5P0zU`*=(sL;BP4VC~E#-2tS+19;^J z+NH=9j)K;h0=4|0a(y)kf*#lpPU;$9Kj{1k+@h{61j#LpRVAVK0gU>ywt##!V9?sZ z!G59i@#k_{Jua|T6sQM{5f4|BfKm4WG!_l8E|h1`I9Hzi0fbPYs1`UOXav})I;-D= zS|xy1DJRs)1ZoumZ#odTgj!vB_LEj=Z~$@}3@C903K;Oh;OuDblh}Ws?U05E%hC)f z-F8UG%KnH4{sa(!$cq?Fd9Su6bPMw@!2`5m{w+M<l-Gns zA@tw`zEWS576pMJ%J=VYf`>o6XyD|91mNy>=+VjXcd-#H#@ma6cz~^?p#)F6?-7Il zESy{gECAG@fREKXfnMh2h)C`LwHSn3ZT zNJYQdxZy^DkfMG6`%lgHqbn>6HW2N+{?HzDxW6|@`39}% z%5nZX590s2Qzt75Lh66m;xudW&pc%k;-bQ`(zN6J{c!!R=YNOeM2krOb)5b>PQY}4 z0+Ieuty}|NBX@f7&nI zeWM@4e~0}KA~pYrKlFX4|BpWa|NAz(6rIJg;xWk5R*$~p{s}u>3Pj3eVB%8JVq(%# z64EpzM<0Q-sI;)O&LmWYo1k%hMxX(tzGTB9RE+RwWQ=9 z*IE(;Bc)db9{-Kjnr8b~t@R%c@V_$&>_4B8h2vGAtQM4^`bUXeAX9tH#}0g;LD`t;2{7%*~rjxaf{T-QHQCimb*mq)=nV6@emMI?e0kXS>Qh>Z9?QG%; z$Z1BB_F4!kv5KBM_R!IChbT@a)RCDw+nMS40ID05U&dRS>51xSACrVKSs=G50cMPM zf^xWc2?;32Yo}%EX$f-`1<#?}C?t^;nin+-2IyAb^R0hI^#U|73e`)SN+^SfarPz} zpf^CVQ3vEO6H5#n1!YT3Q4oO$WML^8RDE?9EXZ<-gYT4)L0MIObypb3sKVfAIH;rJ z4Tw~@AL^Jub-;Vj=rvrRtS&(h1_*XY379@0ZRrBy708N0-@*Edg3KWxcTvh5VY=X5 zJru~Us)>Ruq=h84eL&Dsqhxhg*R=yu_#L6_kJ)Rw1gTka%D8^al0%tSkmX-RV58+2 zDbfejCn%!|KAQjv(;rDybgBNBwFIMdqtNcCIa)wG)OMrgXjk&HpwB-a{p$Se4>?sz zULDGOLPRV#dgc=kpjw!8a=|Q_p66&2YFA8hmcbR!4l$rk@ zLY@*6g%UiXfZh(H;WPq0`6$Yk`74!xyVjJ23%4Q{~kG_3SIq*U|RlU$*}D?5n?QJ>63MW$XX4_20Qu|EFxdtb~;8 z-!S!3lA=J@12Q%3-yeOvf4$YGFg<>9FNw|>`F;m%H5Y{PlztbD`hfNVbTyEARcRzj z^%VmHKLa4ZoA}ubx3k>ia>{x2b+5p^>#j_kDg1(GQi9JgzC3sFr0Ik8nHyd{J-JqW ztyuhp2X0Iiara7@%I(d|b~El>|BC^KfwFbTd?BedAkB@KT;M_^7NjkA2AnRGH(o^4 zkEJ19I^+USMczXV8RF}h*7FB5{P~ZE>(jM@E4f2{@|ZtZ*@BS?m&v-8Lz#i`Pk)?V zyS_UA$WI@0@GJN2{Mox4%KY+-g4Nkr`@?_QHfS|uD<{9Q$YbU{+?JoU@&weVstnKg z=@^db1~U|uZHuba_{khN-slB0D99hoQTU1E@HL`u^A^q*C%uf9b1Cgb;$ z(-0@hyuNxP)>=mJClwe%j&9_L>%%iPDg3!^1Io*el_PHZXR@csPc+}NxjKdPG2*L%fY;lLR#y~N>)t{^M2n$KYoh4&U_4}EYic=)%4SOajZXf zl43$OqF|p@ezvO0{K8CY`%hWuRId54i|;S+8vyO8EPH>`Pb>V@#ENMC66dOo^Vh!k zYhSEL;IDo0T>{@f{iQGdlErrkeE;;%a!L4!n_hBzL%MU;5xuG!rX0K2Aq2zO?AJ*vWGZP+t zE?JsOLqC4GZF+vJM4oeb1QV3~*x_|j`vyiiM#3XA{_K^JhVBOrkNME^nw7{?G1H~( zA~}dO)5OzRgsH)tsRpZLZu#!Z;={%BqkENoH)NPUesM?G+VYkA{77ytczi9bs^Wm| zy^{)rNo`9<*6NbQX)CJ&AM{1*_rFPI_>8pdAA9>g^k&Ig23lk&kn36CYy4~iDoN^U%d~55yAA&<6=D=rs?PVc* zh}MXJcZf@DK!cq3;O!U68}AyG2*P4Zh!eRjsKd2v_sZUwgv8(*KD3`dY4T$0*JJeR zaRwk3w9#q5%w}o{(>4R<0r9G%4#vrPq@d;b>%JN^(W9(runW-Xe#&^@OYNsTt*%${S#^O-^?@~RusEgV|i zv#;5lJ!&}NQT*+5 zPL<-k`TX?A$ZYpD{TP=V`B`v^+&`6tPd8X$nxkZ~Q9gocW?4CKspc}gc0#2Y`?uR} zMTDvHXsO7s3ps9$l^uTFSKQgF%G0!$hq6j`-@R)a*z8;xHDE4cl~Xa`W?d2(@Ve*W zExjjF=oZJKk`vNVl5Tg}gO(Sk2h*}zd^-dBCIvcuTG42*kFdP%Ab{a7YaA0W-R#8c z)f}g?rf=uu)$hl(k=*Z6s_@iDPHU!GZgH|!zw++q%4oN{);{;&-xDj%m#V*|`1K>a z1Y19qD4PtAbhZtcioj+dQ|k3o*P0^*HId8)s78kNz3@8jv4y(3~f zT9MuE)7lL7{ZK{0^3wc#B_yzxM|P!8I+CRgvUIg~PtMoL_C-1PcHmvg^P@apY`E%g zUpV{elFwMt%z-So#iLU0P1SNf!>&LN6;EXEs7pz?lKDD0Hn1hee^hq<<5~8oAzOCe zdjE{f=XZpxTDEBIwzDqqc|Tixo1JqpS9y8yTVu(R)1_@fUYS!@q&u4O8?16Y(9!a~ zIS$tp8i*#TTe&1BRt|4GP&{Fp@5-nFjvjsGJrnh2w&;n^@81pb*GP1=y0R;| zeF+@5WS+p;E~nxwmi2+~ zn{l7@w+m?Oh#SfiA@~0}KmJZcoVS?ib1SB#J-?Zw&cIKk4=APbS*^VTx=vu5|odbG*(B^lw>MvOJD z?Cd=;)V%3E{w24W%pRwt_+3ZH&+8xR+`0{);EoIXs+bs?0QRC{@4{x;9*#cE2fQy@ zi~N24$KM{TH5y1d`@*NaiPhd@pK{Rf5ZMJg6$Tj;DrOF~KdgPPHq+!k zRs>g?n0tDqQlU1*G~+kpx1H%0*}9R=3xS!8efkNf2NLf_MH+7Uu0f#yqPLTbFttRGKaSX5lb|(UY{dQ13R6T{1kLElZ!d|T zWZgQa8WXpl`maz-dt(a+WyyiyLxC>)XkL%nQG)Je$8QNX+7ceo~ zk9+W&&7MR{;S?S?IbP5>v@Nh3Yy}_7poeLWjb9Jfed`M2`;gOZ@GNc6q9p#Lk@T)Y zwFwWPdrY&P;Z~3BLkC`+J!3v*5IoXozb}%(+AZFPomD_-;Y%qDJM{UC<)eMCyc@0W zdX<)CIfduci@Bk3i>^F%Or@$e8CxT)Xe^WsdWNOs0mi;N>&OKFy7+#?-VfB+vWGVUClyB&7kQUKp*8Y^sY_+FWTHc|ihKF!QMr|yjz z2MVLE)s_SWC6DOmbO*25EPy?`ueFh!`|hQtk`ke0qN9*#Ng|TatqnN%P+!&jA)XQa zv2Zdz`66!Y!VC3z)BX7^6?tKS&h;;j#}cajb2{X=3SHmYn!5i=W>CP*@Rh6-*8>Jd z!k$dl*XJmQLYaAO9mZ6_sYuQ4H&u(!Vpa@RTdgKUacfp5wKbG`6L7IICTvc+>y&p%A?VZB+40@rP#P>8>Pvj3OoEYV91 z9>%0w2J7*y=-fp2EPbXo6|L9gBN-ILZp^XGlS~d}_2tiHAC8*tFgIXGzau=#J3@|+ z*B3lJ@m~7S>&yug{m&OSGcS|h#syY&#G8seIkxs3YZxLvL$M}s?*#^H#5>mf#mtDZ zE4=p)?XDvbTTVO=wC|rQ{QR4nkxizXazMNPWdDr?vZ@DK+VRcx+i2frr|t8=(!%#V z^zUzJ@J=#?jmArUc%NQIO4=oXdjGKdOU_lpckJ!!zick)<8UNga24KjstGKq!l?KA zH`YpK4gtrc}In`6??k!UHv!ziw0t?2U_x_q%z3AaYdamnuy1K9tfPbufFD=@8Tvy4@(J{(VW%LN{MT{AUt9LayuzkZODlOpFRt zYgh#y8X!{rQ@jk(2TY3kd01~veK}UbVg3AZE{`&vk$lDr!;Tu!?}}|X=$BT*y?H49 zHb6YuvgtTRvImpEWCt=ix;!dO)xAX2CLlhmXu9S0$do}v_f`4KiruW7+{16*$v?G4 z?C~!>#(YIiX~y7LmS-iji2B~-8Y1GbKfs*Pn8QbE*T{J*dSS0UT7zpp`eiz~QEuS* zT>?kCZwjkvNUVSVJ%jzu7wF5`5D%uKNaX>2>oM-Ro(uDGALIt)ri*=1{)3bN*{jl|C@K^zzb*fF;1TKCzR!%gdCXWg*V#9ar#Pe4#OOXntzg z^vy$4-qD6F157vs%QYO5&IRzkGxJOfQB6!d=evpbXcJPXi+6x&G9TM#+5PHDZRTyk z*dnw=-GsH>&83X^;!4(UMb90iimpz19-TTcy%{k@_E$+B>dcT5-ENJ$VSM96%@*h2 z%#JeDau=I9Ca-H-0d zt!|&&5vTQ4F+%vrw10`t$+sHPOhvIU!?Z0V1!Bb;Ddj3}zJW?(>F&aj*cVbY?~jco zpW<4$JM+x6UAdl3ZsyHo=gkvWnpP53>yH7rBcMaeH}PL%B34Grd85j=2s|_<5p7>4 z`j>7L&WqFK^9ZmNV*5=R6VoPP9h@0nTGk3h$;TY(xdNo zu?`g~M3io-&Q8^xc6%H@%|*~t#;dVkN4V{rseaFhm_(%r-B7&I#e=GU7^xD$v$7|P zVz+&j8*rHb23!Bzlfcg=(Kh!Dn;EQQH-CU{4_z4Dbz*S)sISm~g6%x+nkXE1VlICw z@S+Z4B01W}(vtjbqOUc@Fu|xes}FN}y4fY7Yn7%IfHdtR*de;69nNX>a5}?+=|z$E zet6wKb&4?dCFi~N_P7$@UnH@3ChcMkFkv2Li>M!y{mTEU%niFCynTL`94-ZO?;+7j zLBc?7(Qk_X*w~vKd&__(ZoT}lmRx~*SoWzSz@sV1CNtn1RM<7@Po);=;hN6Zm#R(khyG7TOcVGZl0wHUTKF>M<8}X^;uEF$ZZO_doIN5-}h5u<|r$ySOFF$rXZ*K$u8mfP=IdDNh-Glf(Ty}tS_3^G1JI8)~`M`UcRnB@D=M- zMKGDp+Cbp;xC1-jL|Ah-w+zI7ym?KDVI>4Du+(yq7f)Oz7Mc!4od|p3T*4p&FmON% zhCGmT+xq;DIG4G)(9LCIgtztk9v3lTNk>0a!-W>z31J?iu3)aAJL6pD6(f#gJaZAn zYbHUkO>X3-NsaY=FvZbE5d|~O_J>o`HCYv3hZgE1V^n4OGGuFL6Lqn3x3#uZa z9L?v%2AB>`y;SVEu69%Fwy^R{4&iHzDtVhQ%KFoY)yVd(^9Z8<%&GU1jkodqsX2zn z&#SYK>D)Sy*v6q|5c;vBMP;X-DhNt|R&MvIU$`mF8{R+sR0t zll8~!bDU4TK3*wleTg3-GFCWI*=%sP01iaRHD>&BXI%2UV~B_Spe!3%EV0jGU(3!5j;)k%)Luu1CB3i*p+e+0JYX&mQRQDDcHV!Hajp-S0$7 zp7Qv%)qEqra6=UNhw-+^c=f#T%8JMBxk0#l_;jVy5%WjSHcTUUvW|UndUq!Rk6&I| zgrkvd;1mP^kE@|LU>^2b%(>#1+BM<{I|oBDZTd%Vz>ohzD#B0In;F~O9b;IGJG&XC z&{V5XcedaO+Io_~P(iy+zAZK{9J`MCdEVbq zgy;z@aIbj~YW#JWmla!gtA(fS;l^rin@-@YBC9?F_>@x_Er0jh(wDAMcu`t=smQ*D z8SWRDf{`5L%wrJcYhmF#eSJJ2RF3u5R_@54g|A`tL`0gdawMGl8;B7(0aSG;d%4x4 z;QidxkXcuRiC?DTJJy+Yhvmf?U%>|P=BFO*Eg;fm;k=x$sE+$K-fLRmGXi5jT({;h znC~=etZk--vjO>3DVwwm`%Z6mM45jq4~KIw@5^};v331~tLHkx3cEpA!IxOIc%BJW zqVKE@8flttaT5U(pE25O%zk+h1aM&1m8bdWDOv$mK=gQEeqi%fYOrFQ`2({kh~kZB zROnSq*J$xsKp`XDQ8SBZVdX5dteE$)N=hSVJL^gb3$tIHrsH!C3}Qwh@H776c~;3% zi%$zO8P@2iJ11Mt4|a=Wd0g65SEzYc}mxOGrpcp?B3Q7mPkk#y!5 zsm|bJ&@)Ds+Xa3iB@0h@PL*xhQJTyzSUr~C#|s6VPhU&6$aZ#O%Hr{9dfqc+#+asq zyNaqwC`U1W8OV7z-6!3Ca6=n=&17YwpxI2R2WMxMZ*V5dl^76)bJDYpy>T zHu@LVTFIG0{KU&j`Pi=;L!CwM}p;%x07 zVl^q+Yu%rD%q-O5_?;uCY@PtqFCRY!G)mWe_*r*hm-dI%?^(wTc5M&M+U5R8r978w z8*vWts^i8OgLV8A2(fmbJ2x6n#2}jIr~Dg}VUyXne<93fDq6=+ON_dSx3fj#q<3Z( zjLH>!x_G$!7o-j8w^P>?rkfHf&SJbbb+9_jxIJO3p8D-kXYz~9m$LJ(Vo5b{h4!|I ztGo(?ro2<#M#bqfMgb3A&o5jk($+NAg$oc5g*{XuKq-C5t;j@^x| z5R)QI_B$#Cv_}oJ=4Ju>^v>5zZd-|)$X!vfcFC+r!47@4S)Ow(f~n|m-;~b6%wBcx z%sDNkFVEKKmEgzTCxK91eWlX!!tFzKIa*3AmTEKARWUIxanrnHP49N%MSOLfiW9+P zzWrg%34&g5ZsPUgO#IYI?ZxyV7q$6gmrpQFf`#?6u+5FOOzA&x#lPQWCciHx?M-6T ztt%bk3zjBGwy}aSMfs^ZV;v!DMel&E+DaI*Md=DJnH3JuWVPwJZYozUZYvY(%OdtzUEO2@;|xBo+j9ze zMy-d+3=>lYi@_q^OL?YX$d+1d`aJQoel9!nA=b;eZC>wS^8i#K0@8^d%%6A4Ng>7r zcTeR!*4FKBRQ&a;!uv#~GC3%y*JE7yh)2xcr0a{i_FEcEWfIO7gze^R%`1sHe$N~@ zD6fE>5uCWp$aAeS5x}9!uR$OZQrwu(!ZEPtX5fg>AulVi(X(t z9}OCh@Q@G1>+{UAO(k@Cma;`hs_+FZobtMLf(ch7P%)EwqMNntY?GB9i7T#TZ zPz0A)@F!)-5JE}NFyKDB##WS z!t9$V_dy$9;C{*1leu@WN`dfsKrNQ78X=o?Y(O1t5mpR&&Lk{VyiU4 z=Q34deoUMPbUn}5OqITuFxis9a$Hab(SOh5;YQB-*QNm}+-C~M%MT-Mv+}u*+}(a| zKC}#lh(}p4kD+#bGAp{*luGPE+(;d4)m7`tC-Ne^qv5WJVTXyI8ngJwzP7|c)7DK> zzgGDOJT*xJ3R~2Rt-8KNWlw5>QIr3XKt^)TeF@}Ehgu&m0xpArfrsnI^>!P)!q)6StfQ(}c z>aCZ?Pt-Sn@M-3uTDSHwNwN>gbbxpGp5GN!3({>JX~A7_2S2lQ2MFGs@{YAFUW4Pg z)H0WHL%4qsBj8G5*0FE#h2^yl>{1kp@6U{FCXd(PwRU@sFtt-r7pGNN%u= z2w*s6Fs4v(mLfjzV-}>*u-4S98iz4ssHnce)a{8lsi_51`HhG{A`^oBp2_+oQBCf% zs7p7HK(Mxif&H~>y0|tGBQB}(hvuO8;>%4!y$5YGmfoVS8FfIa!f54u71GT)6=x)IYRY;|8|aZDJ>|McP@q1f+TDBj+@zyxT#+D^Vabc zR^$2};t?pv87*oVpTjGhDp|b%kCgJZJnhQ%8%UyNU#YZOd{oOeg6Vm4qw-toR!d;{ zH*U@se5f~hd!{meNK1v>Ff)?dne+0}cKH!2ljbbNUewtH!N5i14mBfjYqQ<}Tkag< zBhxIu5nE}^ryx^N4UbhXA&`h)3dHuhjXmz&`e+?@+`&pi_TQpqPCb~|upuMtj5le| z2mFAg3@`=Jk~PUHUOOyZcJ#YgvkM>!_L4RjO_2k0>ao_+c~702H!)`oCPvR%+)3~V zKJ>JH_uRSQtKwo_8OpwVYSm-L`RQ5nGOT-)8^8A7VkIAX;MN0jh2Af483}<6^D~<>U*pvN*bPy>eo zYXNLlHD|ucNC(nXo5Ft#lnaoWX<$wR@XT$>F1?Q5`y-3oL>t&0RrkX6)UH23H)e_? z`!3U?lGI|O?Vxz-aPS0`qQHL~w0$JL>35uLeklM|9$OsKTT6Y*6GV(lr<{C#H-Q&W zABB=#7pPvPfHr9C%!zHAe|P(ZUmcWloVvf0+L#R3|F4mfvfF>xnmcsw#n67&kHwUC zs4w1xy360+caAotI1^@&)pjPK>ILg-`wD-YXcQPS_CPoD3i|rGLEtE4$$_m3rG>>eo!4kTekm#8yCfwxv)eCp%_MMVo25EW zV*x=T20EusM`slkPw*|A{<8FJe(!R?$C7Iuwj8sI{7NN!`-oMXLxv#7cu?0Rz=%0d zaRM7~z?3m);oE#j3E%AZABz$;C9!u-2N&Z8jNE|tSf6R#+5zYiFy7OAe3|Tlihe;K z7jG;pe(BU26Is6y$gw!aGCDX>MsNo)nrV>h9G{QW3LX-l8>%f@JKJ5=$-c1oZ1s;+ zrk6|ehHqK=PceQx`aSxv(J!rvv+tP5q)e7v-+8)fgp{Jn29vzd;|46xj?$NofvIc# zEF$*c^h1_#L3NiEJ_7amL$IU!23O#hz2NoCxud7ZCh@OvU9v)}*K0kv0j3~&?7#~5 ziB&7E5X{BUDAYz~=;e*o4gc}dh;rgu7#PHXWY!|1io##M?@PwD_QHUoHNpIOk~Y7% z$+b^X74=gLLTw0*EG|^TNt)=EuUI<)um`rKQ<~ktgqjD^2HShMTj|9fkNLG^dIjqW^>@{RPU% ze|H6t{{RzF5d#7uQ-k&IHdMOR6MLhY+w!ru7zwuyz}+jOWZ#PGtsR(~nH;Ef`1Lt* zwQL!fo`c{MOZS^2^d6Kun7Pgzme60@7rsVNL|Nbc)+hf#=yI)hW9+-yXp^uxZcS(B;KgHSoIHL8A z&=nx}vTZ9vGKAzdHGb*~y#x}&buCCue9CsCFB3m&h)D753ln_iHGRt8hyCMlcisNfXJ6zS@2$^8$4_ zaiJ=cu0%rw))vnV9yadHU&q~Vcp;meK4EA{E?fe0IAMBoV&&9*Sf96M655I;H*D^U zxm50UYk8U)ed^T?pDKkJ6K7&!aSlgi_s!$Nk2i20Xey65JOYRjIUs(}TfgsObgWnT zp=ppkY@X>1!dRh62(ALh)iX9R2d3=>u8@Pi69hJgsBWqTsYJVjQJ$(#V2XS^MN@-yu{wKz950^(0k_gl)_;WL16+(mnIpEvZK>r; zAbn-?g>eoX{}B)-dxEMbI-x7iui7eHku!tjhof3Ldsr$E%@%96hIlCTp}>K{hJZYaK|Y|3(7*yKgNZ?&s2Y0(+$h z1ZZ;XU$VA>R6fl-P!pSU+sSK6 zOL-vR*SVp7>PsEAN}&;~O~j^VkfZ4gn6UXG1 z#9{9N6pCFs7>&D`ttn?i`ec#o5$zBNT<+Evp&QX4wwt}QI4>`R@&OFJg8m1WhLa*a zyrzdnLPizY1LRa1tGC;pwga*Md~8w5)}ZY7Qt!SJU9hW;(iyPb*k9eSSTT%exWP$g z+a)D|cxdK4%UlH_{Z~2f95z=3DfH+^R_uon!3AGm?UJ|iYA1Wc?M9&Z*ijkdJ!60{ zhGg0889YG_S{$;~!J`6aWPl4m!47gC3k=9&a;=@?KPaBL4vOI0#a{=FA4yf7Db3Lph%hS0fveN6g zwjMsRG}UN30=Pu_9dUWXPu@j6Gm~CR_8l8t`woyi)3LQ50nzL!aKxTB=N2b52oXG8 zU#Rp=zuJY7QJFvWny0TYu+iF=1o(pU!gn`$PsBOAzN*I`R4Lon^u+01)JIDd@{*8J zzQ7wZ#5^!eaOpLUNjFBwNGqPIv+RofZRe`5gac6a1}T}qJIXre%?nl|vbL(|ScD*; zcjn4U@0i>fZTw*W6=`MtsIW>4M)FnThQS+(gh^MI62NoIs@VT-g%SbuO3EW}R6+;* z_Ry7q!EPqQwf(HO`20RH?ovFR$K&@gMCTqvE(8JkzP0gv(Y`Sg-pr}2zZEG|BMgfH z3Wdlv#)4O434@0YrXV=d1zp&taAt@pKsp{ZNj~@r#OXhut71)PuWutxo4(036(Pno zfaJKD##5$`cU^1a^5|Ruz-moR(c8p4#Cpm51mI)(c<83ISav=2;DXqSl}W5Mob|1v z*lD+}2aO{IW5tI;u;et|=TBcakzMU5#;4xM28`Nz&mHjRwcJDQrSSG>kR~2kH`) z8x6k9mmkiOL39JMJhFjt4rI6?4yA6Y%}nbx%fu8!IB~Q}ZYcdW97I1pof|{#O^9UO zsRCG>rIKd$DJ|9+`dof#3dihIb`}AKY2}qo?bTm)^=4SbDh3R9_>XxLKLh`}uIF9n z=?Qr9hZC_oAy%bPQvH>%GPVmi?*4ElU&uA+p8YY}K4o{C~u;#8L%FJv=oM+zwD@)Rk9d%D|z+STr{Pr^SW@QeO^#ob%gguG4mWOdhBB72^AgflFH`aYmEVreifQ=cVeXQ#qe_RB(9 zp~rt!<^xc(_WUaaljddMc*w`@Gzjuv4Rj!^q$O0jw4%l?Fh5vd%^C4(a500`WlA6m zusA0?-_`0XwZoYE!&!8Q$+-pOW_aSAJ>lB~S*z=pPZYgrS6jA<7zW;r4*_}jO~V?2 z`larLiK<+P=YGd6IP=?GVe7%k$%eB!^-1b#LPqO0@9uwkyvE={x~PT1E2|v$`(7td zY7ZF9BU%WvNty{D*M;vvg##7z$n}JRKQfU z*|m9hCfpdle`;<2mJ*9c@+XJYyPXbH6L2&Gb5;Q=<>^ zn`%e)=Vt`yMoPVx!}VVmqfmWy+3z07D!MR#4^WB+!!n6(Bpt&7t{H=SnP14iGLrpy z5x3IreuGQ5_e>6(+IqI{GicpL60IpU;NIzPyVoC)HALD8Pz}~P7tq^yzcgpN=)YDI za&PMfaqDb{tFq@AieO5fh1=+dPMJRo3>V+)(zi0;StdXy3lFW<)5iQhbwvk8G_k&y_ZjXtNlP;$>{;8NpJ@dWMFG9+fCJqb$v0RP*zVo9 zB`$2)p^}%rEda>b3hdp6JIEE7sk&voJU9clDU5&RUH~rc9z~PnYSj2iLB5^nsd7{Q zh=Z}GKag<)H`^eK;oXvu!u&Rbh4JIhR+J7=}lIWGttUPMvfCxEWEILs*|W ztpx5q96So}%osW?Bd46qLbfdL&x5EUw+H8-5LJ93Z&T{xz)|0}Q(6b}8gl^53mo6Q zHAB1ZgF4#d16VYX4nPV_Zoka*ZCvw#ub+lhUJuy=(6*)$8g0H?Ofo^Qr$9pohw8NudBq}Z!Ryx)d$(j}$ zFl})##dLNN;2t^ly3>GD9bN7=wXv~O4Wy{d{lE3z9XZFT=XvJSEj_un1IC%lwi)`9 z*WsjK!$hCb^K8+)gM^QXmSrh0>ktx1*)Ib6->J_=1-C&`zO7E$I^eBzho8g2k9<<@ z_lyr^1oi?2_B06|*|NhW%5Ly^jK{t+gCG@Fs;BtPF?p*^*Ozk}IHLgV!T7;0=AGf& zV5qJKC@5&h>X@)J3VE8NfB|~^*V~PXb(<3n6Ev?zbf&lmXUbwNq%+=vRO3)ob^#0d zbB&rVNpEhgN|sHLJIMJ|syR$OLXb#%l(Q=IcYlZ29B-0=?Nyv=mZsZYju2%oMl$g- z_ai-U5eXmMXX8K8`_#iwCNpjpWTSI;N}^=A2f^R9@#f_s<{a=ItUD!`aZP?yMoYD` zamXY!+O^=pwnGpAL<7*JlK~Epl!21>`>!CBBWssSNE-@T{!+@Wr{ux>3_!HUoDW<$ zBfV+iE~X-fbFwE_&{4&`+#zXFZ#&AVxkm-X%I%R9QyEfWJVA0CEJjkdRL80Ahm zc-}TRbBv8ou?+&!6mrXE;x2ZGunV+J?M|>SmuI`#`_6}Y+)F7hIo18DGIdb_Se3>E! z<~pf92)O}(Dcc-)@Y%rqRe`sVYT(hS9du@)H>e!Q+{QQuXkTtbZ5MuyhruoHPXjAF zT_Ij2Gvc*XO<@#Klr=4n8hf$g)d8#41cGvx&@W|d=t_|v@_=_gZ#wG2I3?e>#%87s ztDoFB4=(?l6e;|2X5!jh$KfAhGzOP}R(hF-+AU6B-Rozc0r(6Diga*qrgC(May1kC z(J#U6-~xn{@92qS_F`V9G@BXdmJJZ7P=C7^AN^I}q1^zn1FaVodUT}{vH;?VeN{0E zKlrn!An$!)(i2tGZ=gSL(tJT^ zMeq+m$V6nYxBDYqn?sfea5aGuDsyRE5j+Bxo@JD?RvLb+{E;wk|VJMPZev#bARNyx9j0Es+!`N@DX=8IM*d&?uH0m^9Il~v-A z_5Pk+nrVjMDCejCcigUkwgWk!@=qMJS^=|soHzyDw#%@R;2J$_@cS_2kMScDOXcU^ zrb@$FKfSzkSYbOS*InfZLB#NFV|~)nb{p47bdH71<`@PAk>O!3`n;i8+Vg`*;#rLz zE{c#@&6EKXq`3cAe{f}wb%tN|iS}9$vp`FC;BJx7jlwq<^Lm?HwTRGsks{f zw4~^Nu&5zX%*C?{Sb30s8U`UA{ov9HL5mab6KWxY*+xJ-OkWTi9lj zODz6Cua(Q>fWzIT#jzVghZzZub;H!W22EJ@AScP2&D@Kl$Z1?8uKFo9S?^FpUqA(0=Btq_9)O8(_a#<0h(7mQ`>P5 z<08Pll|m1i%r{OBOao)rJ8hpMY^J<8)H+g9Lc(-*Y({k|CNvn|I@tP*am~%vXhI88 z%Js{~%UNl|>(=&1aQ95D?%jY0&SoNcJc?qOl?9j-$iBH2n4*ZNd6IO8r=@d`gKp3i z0&TYNq$Q`N8&9e3yNVF)DdUJ*A9^@N!obJBDpX`)*gt=0&Z+Agl z(DG9&5x_CrtTbr=t_Wvj!)JIEhA$q@s_>e=h}I0Y5tFtF{XwGx<MGDl*`kFD+m`nB^G%sQ}++DA~ z7=f&H?|Km`rw#msmVsDgTxQC55UJsCG!L@bWNCI6v~?X(|Lpe7@`nYjTc6 zn>v$0?7eiGkY!KQkUXYjMtOm*hjP7{QM!}^OKJO^He5V64TMf8!00ecRxGw^Ju~7 z6T{rLo9XTiX*nGPw_Su0l3whn==qlV%Y4$6NqW&cUrpj;v(>^jHzc^|12y5@;$XP{ z+gT8`1#v_7k}R9(woHIxrf18-bGkHlMc^}dVQFFS54=jNO_rCIda)C*x5P*uHPxm1 z+$rL8TR}UvFkqEkr0h3R!NilTu0ho*(~G{HvaLRVoSeB+LLjY?`EiXkxV0%H-5CX| zA1Ly-S_U^J2kX;V9$&gGYjR3)fjs0seoKFyqVFEP6o!D=3tN)H&L`~x@yq^{)eZU++7<|9}5)+%dR{df3mi_g;IgIp>=Dv!R(OnyeMqPrWtt z|9L$6WD+@=50nhF@@2@|4xpiADHYM*fwStMWZr>JXOrQMsc5%)u6iih?U(mHtW)nan`sVd!ADD&Y# z9kDJ`FY-!0h0;S5^APp&wB3WnDAS$F92)ZTQF}dvN(h%M21$;bss=9KSLW?g;HVJ* zj$^9dRq7-C*%|u#N72V;)LgRf0~ny1sQ>cW`lOlqht9#6l>3UP6G&V88Qqo<9Xl9; z?(1qn*_5Adb`r6r@iiLAv_Q$Ng_;GYv%~bScdL=+ge$7bBE5t0{A^O67E+%;p&`D% zq%bn)9Yu$~JKDJ#s@ir;OA2v~TzpIJhub4py@nm`Q+o~z6BYaOgmim@OVxfK30KAf zMVlo+mOK7xe|5_1ru0XZ!cS`H+DyXxWrY@2O$HV>`wfy5-97hD+&x+xNFOK0SD1Bw z)uU_?l7v1cN`u&)wG&*GM*h_NclHnjD|xmRg0glK5q)lUe4o*eVRzFb=%#2a^M8LQiCJ&o{O0;DsIx9|Yb{ncu&<9fv3GZn}5$@UZj);FI7iC zt8F~muK;IQgMdFE58_vCeQDxyq#Vi##C?w#3bJx;ep0ZF)1>ELMTz{VN`+c@RghHH*#* zok+hf+W30m6HO)p0|~s>y4vF`oimcGfM4#r4SVC)d!lE2Brsl>;dRxn3|aD+&FZP2 z_Om^0*7W?Z@hW4B83toq5COL@?o{5JxKPD?Ns+I%?*zWQKO^Ve*=FfYpWWJUXtbDsSWcLF7K>&(R!11#h zKG!jm)G9|l%+fAiV=A>AmWtUK4{2T}6B@=V-;Q?+?w9E$j61%fQvSF>a!ADu(Ofq} zktmy@6lTcROoSd0T^4+}QA>nwy8z!k7!5DJ>q_(I9^8aA{5Y5}_ygR8JvfJ+$*OG8 zciZ*)NcULboVd^f@|L@Auj_ojWv8ZY$%Vz!0!vTtvQ?nvoP zd;eUW@8h;=A{@ruIxU@=CUJX+IWLAzs_uoOXjHjFez9qjt)r|reXPiQ(^suQ$p%d1L(d4uPyDo z8U2x9MR3Tu#x=py)%J8v=5ek9JUy7N-PKP!f}Ku*K=$?ZRd+wPwQ(a{v1<{oOI3`U znYBnz&$9gc8Tl5r_!L`fSFzr?=@&xIhyW9{J9Cx7)M^AP?zsJuqU23~_)c)k1-Eu! z>e__L*KZziU73_AKNwBGe~pF}Oe0o-;FBX*2_=5%yOY~~S7X9etvmk{X5UNFv3gF8 zDd&{lKAEjE;Yz=3punywJO0+|b8NV6MTEYgPxW0`1769LVVD`kDSz;y`M+E*r1-AR z$guTCsS|UoZ`FBWtz~7onc(6WXCVai2de8(YyDq+?qT3K_*}KH)eP-(8i4RxXce1e zshaN%6>+L5o|}1wSY-ccw>&16ngvg$m_Z2V;WZmdg1I^?V5!{jmCof zgCoZjn^g7u-gXuc&`Inw3z+PDVY^8oyLr%+IQC9N_~j)mG4Dd*Vuj{MG73^b&RGQF z`7oFI0?3?qN^I(LhW5V@vZ`Ui#GkIO>RO7ozWG29w?6q(|3hzO6`Z5_sw9qV*%J@N z8)E!1!tNH?Qw#nIi-(i)cOh*Y?1&L6az7O%ar z+2NN!v)(TrjLzfr$brNJSM>=SAi6$<`ICRvu8JgF!9nZ)3(fg~>$hb~J#J;+6m)5A zL7JS&z-{BStY%=mI8F+XOFrl|1SGNrgV)OarR^GD@?wBOs%~!ooRs-~J~2nPwA~z) ze8W4w>3IG>TF3*WZNUKN98PrjSOhrq|5&?eG!A}0HwmhUrjn4|z9N2cP5#Ck-t?)Q zcK^Uu2W9AsE1*>oviN!^%{p5OiF(NiA&YKy(fL?A%kQtxnLBj?i&(xJAZiJcbMn=P zuZ5+Cz#>TT-1Ps-qd{!=_*3WY6O^0<+$pmChwRcT# z-f&166g~+9Oz;_=c+5GIf6EhxtD!*FB{{5_i5O3*c}qa`ExI0S7c472wcJ7|@+`08 zB<=Mt@mmI(mC70F0++rK+fCY@!NFI+lQ+6tFaaVz3z*4wAbv8eu-dScxs^`Bz?kN)88X za{sPvr5@mK0ZVM5r!3Cz(#fmug(~WK{KmWavO}~bTb6XM3%+t+CHPXgb+b<$BcE>l zT03ClH{V7^&-a7gWBl}#8ywa}ixkX^#cz0|a2{p=Lw|0&O%wG$^iERh1ow}iq1!9} z3YjRo%UxxO)zG;zOtu!CVKz-E;mT1`>Yf4(gC>X9n%47Vtt}X2%Szx7BxDmyb}Ih@ zB5uNaW-923y@uP*QYE;Lb$w})QMs-Z-}n-2eL!fE1a%)vLP5h(vb)V$czQQnS;=$u zjUx=K#obn~MdNuulN+ci{#Qx*@|qO#E3N$({Iwc#NujzA3%ZwFFI>jyA>=;U1TNwZoSBcO5*Wz2VrcdUy1*be`>P=biz6^kY2D;z{j=i|4i5)~GHvSsJW zQ?M{|&zG+2TNLl_B@Mf>4W5f1cTgH1R{*d+xBFSj0l;|mF|=f_d{BspzEz?jE z*B%j}`@Rl;eP;C|=#rARgjwswsUa+0B>;rY``!1RW?QWytTK>1|Aou!8F=HxWgP0x zeY}a1$yyzHoQ51CQ0^Uy^}P2qMWA<(P$VUVdWWL!$;#qb zZSP!)EK7e8`Ww!3hGu{G*+l$2y5BmVyLc$xzTMxKj85dex9_>cjN=}-<7A>CLUg-> z-v%7D82jt4N_hdn8S=HXC|xT*wJAn0aAvvH(>C&75$!b?U{z{r1dJU>B(Dnjh{p&D zt}-KEF5QT6{rG|2I_d&&@r4;jNsoV*&AQtxK1B=REHiXd&42Kdg9Qs?_E6%DHuVn~ zeY%x{U3n%mp{%Lr+7^oa{(=rud)P@Tb>`i%lk&x+3o`KJipyvk;NxVEBQDI z@%J^gPdy;EQ>~I&b$PgQ_aEj47iPIZoF3Twm#xUbYTTp{S_zW2{QB3CW_(>hExXeY zLvmy$-lSBe9Y_!uPqa2wf}Z61G+`F3w40O_Ro@hV&iXj~$ogOw&MmT)bmk@6FWWE#GKY zh}-LbbW*L7oK~ncy(eJ#o{UGe=Wb?$OOn(?_|A5o}ZjnKMk+J?dl%Sf$ z9ZCwGyVKAa%B&bo^ixy+T$!8fg9PHA%|?Ij(NnyzM-d* zsmdn7V&stXmG);^OUo_Y#R!A#*$!pZwT$j-ED5%+aSFs~2fCF=C>fO+D2~j0$_!|@ z_q|lR-RO98TJ_c^l*p3@Kc#OQKV40{;i!$wuA&9h--}P6=OLlnJUq7-v2b4c&9p5s zIh)CUWZL88L(yw*Gi?r)_hEX7`UxuOJpJZ{7K!Dz{#A1V+iU%Z<+_3;kQM9t&CTSV45`fdd6d!*Rz@ z!IUPX9d_(M^>d3~v|ZjWJX(*$--E|m%bD(&O9_<7LsaecO?qu-O@B>!J8%RJkw>_0 z$GL%$&vS#BQFOLHE;Wmo@^Y4L?Dv$Dqf>th28@xXNcFm@3WPHKxGHVTCLNS?@#h)Z ztA7oj@2pO|d+yx`-u>{GiQdOXAD3%hb_@J#mee?OSF%OtOh>y-$YiSdmPgA7UQ^}# z#(-3Z!Jyc>%(Aa<$|`2apiE*dGE7xmg1JZ!Ju9&u8A9-B6iNG%g%y!YMBX*QZt_W9;J#T~ z-YEjDCq;K-#d?>?P(r+uoc4|h|Y5gn~FPgD-3=(Zre<&C5iGnL3(a)=X&VEn@eMva7w_Z!b1FTGcs%EyX zaJo)TJkgOOo69R!G5saVl3}13i{7K*w`QL?EoU`9Seg96{c#b&krO|`r18Dk=f@HT z+1Q&oDj#0M_EO^emiA|i1U`rnM{MVwmiVypi8Kvf(2u=<-T1u=u#RAA% z$oD)J_6heTmv%3$%?E6i?+3)Q@$pv_RU7mz7d$WDgMJ;YYMYc$4xMnMa)syk zs@+L^PtV~g;y=G!GzrE^{uybLu%e>@VBBCev#x;#>cF;2UWg1lP6}?&z zk`R;JSpT|DzO(;h-S2s|BzEAl^d4wYdMjM=(Fw&?{gYh?tbMpW!I9%(_9n?4B%8=LPE5)6+8G5r3I$iy?qUedo;Fi!`63zC>d^3AVb zzn-C{cJ0q}re%m{*x4T5C*JcK-zFSlFszb#S|K3>zPX^Ee~BdLCUV~WhGEf{T-XK}5te{%{o911_bAPE9cQvo);FR&Q4FV6q< z`SEb1xLvDr`StCfL~jh%uI}sXP30he!arjxtn!^(-gqcwPNI%O&Beu2M;>D(oHF0( zp?#bSwI~k9_v?dBIm1)>I4NqKKK!=lrBfgUuKU*W0!tb3QvPri|08o@1Vur!>R}%r zK9S|=mlo@#hSwdF`u|o+`>z4(LlesSWoEr!+e0c;%GtT(ESJ8RegI@XKcM@bkm_F} zfgj?@CgqJSj_`eT_>Y3zkI=i#az}}|*#30_r=CZD=KI$k!9DAJcvgm-<93G!@I|T< znh;_%^*=xUZUmdR-nsBD-7miI*IT+61VM~&b0$yV*StzytU^uQxN*Z4PE@n}$CR#T zbQyjB)Ih+$&t;VIwtn^M*{{#|@>;49H3fe^#2Qs5+)xn8rlF+oGI5UT`a|#8{^Az< zdQN+`JlcP{bbkedv+%CvlbRzBUlq|uZ^QM{qf^wuV1{8(gc#yXN=h>Mj&rjCE2Jn% zjG>t6~vMOK?b7GD_6{A(RZ9fxJ0>_ZvHbXZCbEBNeguPd}A%QOYaygqw+SCsVk zGaW8gJfCq`WAU`vXY3BA0A`d{%=zANN={4ldmryz5{4biqfe^(-@8>F9)@-LNxu5; zSse!R9F^RMH+XG*2#$j`Yn$dI3?t|@^QQ+VJP;UAVR;b zdfTp}6latJEZ#&*$K9va>c}KPXaBcvSKcTeJxR?cHwa4aO%VBg0D_hzo4b@Q5qS$y zfHSii7jT&Tr&R{>=huL^DSwWLfAQ;8(D+cWD9Oc(ximfmU%qf?BiJ^1NG|)CTCA>X z7c}Bl-Mu9?hUBKhaUGf2&+t&9gX*p>AhKfu+dQ1duaHScR}E&<;LQI)&oJ%MI#T2+fiLvTh@`s#vImq>}3D6rr{o-8eYtLze3Ho!>2iR(&y#N zWA)Me8CrKCTN{T)K+nqDp1-Efv8n$6;E4@XRcAQlQ|bnw;b#d-1v%L4jjqsW>fr*V zUrLrDgV&h9U?Z|STMy@ERD=UjYNZe#KRHwpgEju%tQi;{g@712Y7fSBxxW}8=rC5u z-Ux-{1n5meqIgYzf_>E8kJR~F4dYhgmX-;KYx;_9C`glJXi#4l{`(d>?@E5DBsvxDZ_4a zXn&6d%yIbaU{2rffNlOHHLiQAJzX`;%;K}H-sZrkNaMLWgXKnBFj55MQn<)CTF zUk8r632^ZW0-K;n8^dlXCq2JGON|6W$T9es0<{aw9t}RX+38=zc=6pO`_HcQ!2@L; z`S6>D_QUB}AjT)vqWk)!_AQkndZvZLWC40esVTyz8lzO>p;?8(5kq>LKe21o44uLB zWW|E|SoPLSMmuQVrUy#%NqieZS+BrDLMK~v3 zA=+OYx|NhzApnsS6*@YCJr%CMp5Mpe*-_HQ04&%o)x+GH{OwYSpO#Vzg4yuDdX>C>A5jDt9K*l;A+o(Bn=ig@9f<5_5lSo z|H}h>bqzSIRMSWu*46(Bz<(c zH$QFD=-E*u^?S_xOolata=}Nt(DgL|`Z$5qzD#`$ae=BrbPOYPpT@^~H=wDB6J{zL zT%#M{W(VW$oEBnP;e<&1GDEs8_clDesdPl*-2@5L2BrjOk2&SV+4x6@^znv$Nxq@b zNN|`-$Z6w~K6>`-Sra4QY$vK|Z{YFKma=?jP)qTEJ$gDcciYWCFI3oIrCUs*sYm_ut=vKAot0TF>-R-!rp}>Vr*?_TZ=1gteCy_1dc- zndCP^#tj6dmbdd8Ayv4t1xusn@_ru%)d# zsr)DZ59F#^re+&0u9v9+*S}1WO!M#2Dly(9G$($7O zp>~b2LznkZo1bAb^-T*iXsvPOO>I`3`Y1Z%z)~jQlx?AFao??yerwYA=t_W!%$BdW zNUWF(&mbP^a{y?8W8$W^=A~n>Pq?5S7B+Cgl=dp#cW)uLFaS+2gGH%%>J(Gko}ZH7^Lf^6sf95qd5Z$*6@(`?1zH`+6o&?-W^D_q+VQ~qSv zQFa?zAe%U!khT?`y<@59cFV;JI*~x0l$=i5vfI%2+PFdOY~gZNwgZJ$`}BYtVUMPv|6I6% zdr3AIrqhl?PaI{I4$37PA@{AA5Oq2c)4V)V<0mUR^jX2csT)&CX!iTW_Ld}>g|vR9 zFvxmG$YJSytb~Vlwq7+>S=ES>{}gE}bMmZL0Wpm24%Ll$fcrI$bS5ZH6n zEyA@8wdF?0z6E%LWF{yZ`uw?`&(hG5a}}4m)S(A-WA=tedydR0d1nhsI-n}EJ)S7q zb2ufJH#-zp3ZO`{dm==Byx0RXgJZQAsEd{viRHh z6P>KIW%ZsJW#Df?6Dd2+CoTVkLtDFmwu(#~tzrYlOneDEx*{#oo8mCkNbQvnJZ%k> zLqwI~-7Kb@3G+-Mw070)hSm}RhgfiGDdp7OkN?MVVB^`BDGKIDWvX~Fo4*-SYiQjW zTQgnkTqe3SCZDFA&%#gz#QGOnq4uq@1pb{&X^9eI1#UQ*Hk3WIUbdE4WL; zI{%rLMJPtewbI2HToM_R@K81>awx00GKzi&)XZ3kR@zat_S$WP+;rc{d|8N|LM%GK zIIAIBF!DhM7z8$VUS8*u3bd+#z@jfmTCu7~kY$nW&{OFCs){wayq@1EkV6XD&RE7Q z+d<<#lWm_Rs}B*<%%ZbZr=eSuv{e%NVktUBqv0BrN|y|Y^E%$xW(Nl%G&eGN41-;c zyipa9?l2AQtro0Ofu&^P33#ZXJ=2F0himD*rOzs+TYlejw~>X(oK+)Hd8lgX?puEb z)*C>4G3gq2zdVpmN}Yk_GIOkX)yXS+dX_rTA~(}m(VjThH#b0q?`OJTqvb$}&0qLi z(1rFMRD_G+CZ>=s`#ZxmvW!yZh<1Xzm_+RF-M6@IIRerdBYOp}6xX;~N^ z>h$fpB0{}}5wLe6E+R%_^^qmu2KChxs4nAgFHbLll=K#Fl%!Wxsr;ufIy5BbI}B%Q zevuwh6$IMM^WUcu0+%EIdU0HS&wZ1zDN8vn^{f)=l!zT-S5*ddMNOfo_RNn%R zQcKd-!sm+XSd?NZwO+nOM_hN=Sl=D*Y=_}OeOF8V*23^@oT%N+8;f=DXOlvfErTTB z^=i}Utd{J;5t7#3MFZhqwG$qG27zkY-FII(*JIn3SN7PISJ9827-BF3p?#m!(?{9o zg^bYm%;6>wd>Nb34I7*%kUOtk>gL%`799z)65Bg=%ddJuTLB{aTg}A(a3wH)_Qno$ z$Gm#d5%cm1$yqNe&}N4#)Q7T$l)5wn{2iw{Smuy{R-|8_>!-}hF6!PUJ8^=SNey>V zh8QSjmXfE?oLHcWgsXA-8P$9p#LcapEIn~p1p&cVv?;ftd+WM~nG0CX?!5auI0 z4&6u2B&NM=XuSOUDEEP7E@EIg{U-Y)6%XUw^HC~slZDJjtGMphds!pvlT9(k;Axo} zP<-?!E`xnk;~PbDdxrG3gJ22vDl(Y9%uP=r-pnksJY&`WIb^VR7DvA;k~&l-eF%Tq z7B}r0UsOV{0;=`Mr&VTc$?b5@0)?1`b5;@c0y%hu&pz*t(FViG4h()7_9?Q|+-wI3 zBsn>`muNCe4&xNTHp`)^N^$ z4po}%+9a{RWA{pnP;a{}CUVB1Q~83Km2;(eHnzPQ=P?gEn+WZ>%@y~n+V_@nC(y21 zNGh^ws)X6pm>*28HoH&2$|{9io$*a%NpQYtZ(5cj-klXw(Vb)PMUn~1_`NgvQojm5 z{fmI=kqlen-dwdjK_C}Mi)4*%DtAgZSmNvg?nG7ZX%(>wF17WdNBbkG^ z6S_5N3Ht4#V=SJ$%p55b@X&4PP+RcF5(%jH5+Ul?aczK;BdVY(QfbY+n@~TVI}OcIdJ=tKprU@Uc~p zZ-w+6>V-k-T`Ic}4UgqpLswhtR+>nyTov<7TR8iRta!ZwE$Fr`2%cU=?q7=hp^h zm0a)c+KyJu80^FDFHycy7f+aJ#X+JOWh)r4B<540-~IcH^tp1~Yf#K(`a5OZiT1uh z?J?2xzS!RUiS1ImCYB54Ya|aoYPMBaSAu$Pl+FlB)Fm@NvSv5kX%_A@r5KZ;Z##*m z1oo08$L{`O7^Ns%d6-O_W4RkThgNH)`G^Q^NGYtM$xoMA=r>FYMPq;L!~EWLq2EpV z>-QjVXdQ*@emhiZ^iQ-EN_yRv}&m+RI3>DEBvCoW`GEXwf(D~nS5 zQR2KeE?VPfIc1AFV4P|} z{o>{dF*!9O#N}6Z1DU;f^4YP%id4Z5(p9(JJw+bca*o(eEEx+wT}X@-v$?D;S}EBv z1&LPP^UwUd_BN>UdB?%2nZa#r2)AJ!bG^gD16$wS-&%n0xGB76@=M#IQX&O@J&Gs` zt1UOIvm@{Or`N(0P9A|WjS;S@d6iz5?y$7V{29yzUxHnKOXutVAm8;eUmQ$7Tc6Y{ zw~lLZN?3Qn3U6+vB_zL_77x`fuw=#YEKIj6Jd~L@cuSqzF5^y)Ozlz?GJ3H{T~4jc zW%dUjgGyWOjk(Q-`TA483h#WIC8J+vGwec-K)9ExIc&t)RQ2VsSDim_?aBM_K0CGHVD+Ll3uM z#bB|dLrzQx`hv#*|@6N%bn&OmGlA=_)P=OvZ{<1O|Wa1+>4*POBXkdN!|M#~cX3t}5KAjr}#;!F6{v39p5 zzC8_Lkf4~mp5O8ld|75_xukthE{&kuRN!_poypv%BR8k_`z(?#x!y6O_O*DK{m4~! z4yvH!1iX#i;-Of-&}(|yCZ5ZR1>3vmXJy=Fkd;nxwBV5y(!ZoXhbB*N^%yeC z1?H^I^mfF~o1w~_A~X!#IQm!x5rd&iNlD4o7Bu{>1?aRR1fNeQ5|64GD;_2k8&OgK ztr$afYN8I@LP${1Dan{i9sgpKT6v6Pk5wJNWf)G-wl$eQ)%Y&?`|DoY8+<}YJXB%V zu@fPX2PkMZMHjt|dJy+Se4X2{_Q#A`MzZ1!rzCPZ0rqBdbKy9@{=yIdT7&|%fEX+e z8_m?qPlb}Gk9MpH4II>O+0|22i+Su#;U)s(GQ{vHbX zJ^mXe|AL`MF?ix8tYI44t2pes*OsZs8g)$%OhLNET7sG0oTQV`r53cdY;fM|PS37Z zNK-m<`t(R_Uue4O7|LN@`zMoPG+&-0N<=` z+1uj&0-oV4{e{{dCS69<9?Wa}3*q zcFhLOy}@bN2WEi6Sud!Ogw*8%0ZSy*B*Sl2rd!a z%P1hgLb(j~ib@lN?QX+~9By)>;KduZ)_ay8@DeWfDkf_=2Q~$)iidfmWDojH8*V=$Bjxf@=@HiVeaQ zV{o&dfdjpQcRV|%V90Nx!t0DPT#fJ^vX*wRf;Z~`5H=Wa!+LisXt7uM{8(mc465lc zA41}v;1yU}`cYEv?&RT>1-McyXq3pEDpAm){ni>5W$`wK&+1yr?ZBcY(M(qd)4Ao) zitPb>+U3;bjPA@=%cL&`0T#tw-6^~Z*lNV-E3#)2``7M%F#I*u$DDn@0VpbF?<|}8 zUAT_)q8`GdA_rDx9-OWDp1UBi#GaCUnq7^tapn92-U7B(2^L5hM$@tTN}yJijFS!~ z8xuMJ2gOx?YQCpuzD-FEXBCfQraPKG1K%0`Dujh1k$5Y_)caPK!RqbuX-AgDgb`0K z8|5#O+pnX;yqcTJm&-ijUg6&SHpKkd#2I8C%7DZem^2+Nc|N zEVwc`VC}kSP%bz%vAJqr*SJjO<~cdHtPovg{Zr$6wEVZK8k3t^ug`_f5XQgrPf4wR zfq4fp7_+?8wA@YMft*hm)cWk?`bzuF z{FW_(aXmn3qs%#9a((;t_DT5Sl{Glawdk>nlpfvAn=gzOoH}2b^KCV@BtK+pJ8rdC zN0Mj6YpQBjk|TTb{W!8{(A^k=npa+v6cqDfcJoXX%_+~?-G1c~S_oHlUbR>*5J)bp z67#U8F9Qj8baDnOn{s-hEx?H|H6`?^{F?H!9s|t};q!z~joC>Kx4Yz-$O5_dI&T9F zQpwMhy7RBeJ6c`kNe^V;@J|1OHw@xA@-y6}zVs;+=~?Mng@trh^?AlBiBkAFt$Ktj z)Q=wVtb&@GsxD4RIbMwQgy+UrcM-wS0pa=(!5s9!pbGNxw__d3;uE@!Wu!EWaI_Y&TmKmT$}^$fd)n(*s{>~ZNF~7J zZ=h)K=8F>zfE{y^((vbf|GTgQsqdjy6~kNS&MFa6OiUJ11N(_}ETY!I4TAB$lSOJlX9=J8{ z<vMayv$kj&jQU3YnGFMJ509xjR; z(1^Olb@o1rXpS@P`We<-T`l?ed4XAP`{sIJZ9o`z%6@r7Cxx;ED_7-Co)yJqsbVDs zZ)?=+E5AbK7d@X1$E5u20X@ZlKNzVm>Oj=FIS0}UUtXQ*c5vJqRp6=*;p88tBNrPg z&e=(A}7rRq-J(ZkOwYe;p1uAhhQiykzoupa3|P?dP$xI|-{8CLy7XqOajxI?T%Ao9~w~5J}&` zO_Y6bjgmbEP{lvSDt7v1>4`YhRQy$2vOlJ-2;ObKbcGv|v$Wd9&UESu>}&AcK?(Gf z*Z4J1f_Y_CJRE*nrLKkI6v@xu=wuV2t!-?s{~jyja2f7X=}+4pNcavAI6MMJ+^4d* z8;sTFdF^}hO4SE5O}vp0VKk_6Z^p;jjkr|k2u=;bVaGb}f8kO8^By1TxNtmF**V!? z)}Y>L1OW%qqz6IEf1J9xdO*!fjN+2#ps&y32*K%DTD#c%%8?W2LxCQx&qP%F3v6_n zcf1F%r%3T79!eyuAAbwb4x_og!uDjD6Y1(%eO6aCx5v^aD_Qd#i{;)>U+%gy$jOi3 z4;-sme&)r1Q+Wisd%a{G_MZ=I@u!@2sQ&RLYq78?BrYz~1huMx<5n!WO4imk%{xE9*SHn}g>yt`t&`bjNy z{#T6p95-5R6@nhG^WBfW^bfd;MxEkWvGO|8|xjxmOCZ$w}d2)t#etUibcSK1) z;_!Vt9OfVfP)9xI$uh6+egE+2ad_ zP@iF8>tY#RPN1{LS?`=cUBVSySJesL#&;CMfx9q#JFrA6ntv>DTs69n+>u>++an)RII%h%=?8ebXt{KsT|L?ZPMaI z9c;sk+G3)}Xe7kCd&!(JS^alPgvc1B*2hl7My8)mWVsz^_eZk$O9X*W1c|Z+{ucOP zez^bas8TJ}koy(5a=Yk77jQrLMRPrm8ieYzIs~$`>w#-*DsWrHT6uo&KGrI8btHHo z9`%dX`VWhH_$wORm}PI@em&^j-gcCfo}C=bersOeQqR(5h4kBTP23c#%c_wb%VEeA zp=4O)!wudG<{d>=nH>y5554d1&#*0P!sav{&9W7moQK4KGh(39C65p#&K2-4PXAYk zm7~I)v1<9#9_#X;|M9_<)^DlB`vk_RyFSU^y7hdzS^=5ezQ2mJqG1!Z&lEgGCt~!{ z?$fW}SSzwRwY?U`K*@eR5QTjI>McEQtqUy>cO`xFjW&sv>%*Bn%JLKUm2DCxw7dpm zV^AJ4S=SekR1+6|=X{=emAw}$X7+L0>z?K*fEge%!yVoA);jasBFS*Cr><*1o z_PXSx_3U{t@3;qNoW9KBNl|JeGd?Quu5((3$9H3K-&~MFu=ry~3O_=h5V1C~JC*ff z>e+W`6?yic^DX|4J*#ZNGoynar}R=EU%sIwv$V5rqoG{3GReQN=HxWr(nN8|X`i%2 z&;l|)=e@z%mffmR$(r50QT?3#)rmRNYQLeBQJ2>}rr{g$6hk#$C)TYDu>O;SZHxPE z%3D>lURIduA*8Cy>Xhcbo~f>6j@#bs^3GkSYD$)!-S*XE7Rz~#50=W~7j?w-QUjKM zr+lS;nA)})Ke7YzjhC-N4~~ZScZ^Xe|D^HWcyZ&lzh5+eKF_I7Yx;0jsk(l#2RdI~ zg(KSZ(0z~=Oq9=82imd5i8_Wt#THWs4sB-E=V#17dbCLOCH8RH=1N~&`uGE@d@Eb; zlyIdsqoT>X*si$?uOv>F=zUqNP>9iDly!J_a`V<5iDzg3*hl)5$2e4Ld(%+(TR+dS zy|;kFcTr+vLE3zyu{Zk1E&%cS%b&5Ih%NTSO zQh$@3Aidp2uF9F`Uy@Qb*N9#H$17W&dAI>jk8-nSXLD)v1eXwUdoA%sdzFWqPIt8f zMt!>s)1_D(I$%g@MX$_U3mO>#6=lpXu6Xz@I3#I74(M67bGD0H@y;NPV^R9 zL};0S_s2K}sI&qFRw_icSMzLd`+OlX*&$u11T2;Hj>h`-I{_3H+JA>NO`&8==}pH4(UsPbc&ryGDGX(Nh3*$okWBC`Jnu zqMo26_vQScjXfZQ&B;0noLkM{l$3HSYUqN>P`e z5tG__3d;u2E^U5$rBdbYqO)Vz|1OL09PmHS(OYgn1T@Xpr<=Q+=jZ}Rg^2BcPBRCyTV`ZMfwBo@3Y*7vsCw%X-N-OWA|@LS;9LaiQiz#Sr+NMSDhZG6pS?8GT0n{!z;9qQ*xs z`1W~_$@8~aQGE*(X#$|ftQ2Va{#xM-oLFgIzjC}qa_=d93WBjQo>w-{q~ZLW7>EW$ zTj@BGTxUFQjjTO@>1G}~XukA0%MwI{zmN)yWspoZ?EJUZ= zr`wsPS7-B=z*Jb4CKY%;=Ej`U=OoKZ66H)CPl>*Qh-tJNWr~9K$Ji zyDH=So9uEAGAv=REjhm>l4^gjG8xw=sGCG@#r>gLq;pu z{PsVv$wgdw2;E@RBq;nUlR0hqklNw|XS#)Mou$>4>0&*9Pz))+4PN8%uB(iEd=HkU zTILJcQg4(U{lTV@9SS`;^+}p{5}d8BGuS`Ky?3dt3=4vs@Z0`0byTqyrSS<~o8O%g zkh=9X+ShHFQZNswuMgO?wqBBMq#^I)F>PjN)5uxdwEIpRYI2Og-awxBpkR<%I=67c zTf%8t-^J@^S^r;lD0%%)assUC*WZL*4OP4I!YD-5l&b+tXllIfW0z+)M76n&b}6>Z z@SS|;_UU}koey?V5_ZNd7pI@OZzuO;k)*9WBWYFL;`Ltr#g5|9W zGk9KwPOJ6ajQ}6M$S!Yzs?_ong$ULwH*U!1%cG$T3a3Hl#IT;{x_{Gls(H?iMVYw5 zb~BGw$oZa9ywGV2N}w}&`Oykt*Un+aK(i56<}}2C%LxOAhLT^f7E^o#0R3JLJLUkW zUWoVh$KRUBKu)|^-w%?>AiEWVsQ+8b_)Etlm6V%0sU zCMAy8+hM#9Om&3&(qi3`^cnvI#y4xvZuCp;hck}k|D zMMKBCov@M?1Z#2o@nJt2knGPWIf7(n)Yz`7HB7wYxzx*Kko`88RVZs>S-ABC=w0=t z-v4qx!ezl31cr5QPw!5cxsJ(aCB;3k+OP6hf1XC!Be5DxS3yOR9(%C4!g&W8E&)PnSB>-*Eq8|Cxt7sDFH&y)7r z88=*<{!692i2EORz{ftgQiFlE1CfpMnzeFpp$Ud6cOM0NNb;dT5>Wa z5J5DK2;Og9AUVJWMG)wcXJIjO169b!UCL}k^RU6z|knd6*Zn_t} zk0gZLNZN6iM(wD{c2$0!omXcZ*!V zmfXC>skeoArUsX?8MTM9*00Qz3R;0=xxSqYS6kIXr=hbkQ>+*Q(S@zWn%OFPREsb*`Uh;SV1 zcnm&+%c1|&Kd0m_`}{%<5HywY9jQxS2+8GAYW+jZOyngk6N%BF_u_#T^C*4`^#Z-A zYX+sZ#!(C3DTBes@qP6viAa3>GV&m*10%?bQ74>PrK&y0Qu(HZmC0zu5mNdyDl+kA zs)JllX+=jJ>Ri6PU{kq@FyYO~`<@rW!>%6fJLN_e`{sNmV#rIKjG_ABguUHc><`4f zlpr&I2M@!fhx8nT6pZO-T%^?+C>H7naZ;L3*AF`W4kqvWF&riZ*c2ib)3w#RxjYfV zXRg|vb~nV1bY&yH0_b<1)%li$z^zh#6N{dY@7%B3zBhtK+wVIxpcChgh<O0hV zb&-P>mSb1(!N;a-y8=6AH$EOEC%rt<;KWj|D9z8Fz~fcUuIqBKEkdpa^iA~Yi`A%6 zY-ozG>r(P;kC#ASz$%Kk`SoCH=ber-LQWd27agumMI2|clW!x4f99tin=uB6YxbW^$uy!IqN~sT&fj|eF>}EX_lm%N_KQ;~z zey-scczR9`i)YHeWU4tOa9!yCI}Ov_&MsZ8$!2$cUjFHT{f%@PCwJ51WIX&$bQ5}K z#1^~psgp4Q4x~L6>W!v9bI}P|d>$#6cJAF;*_zpI{^4UdC4>0#m|lVGrT56A!=7NztMCvWeSgs{HJe&Ajt;u#mDyYB*P5Q_ z(wnOE-DRduE-&gPy(8BlB4adBo5EwU7_X`D>A6}XOP~N7$ArQ-U(%Z6Lx#V9YXOQX z(~L2L9mz}&i(VuYRrr1j_jy&}K39aA5lK*;%B++_E>zsCk5wstawA=Zxj6J{tlHA} zvGA4Yc1?ZhU^+SPc%zk*zk90=!wl?a+Qa>P@e*!f=nd+QXY%hg)NwGq_eNmVvqhV? z{k3d#o(`5ve=sZmo6De*Q<8m%#bCEUT41hhHzkrF17FLPs0>`Vd%$zF8PqkawUM;VVV%4>` z68UVE;q=c44)>{Ny>x^ph9)XiK8~+&+Axk6R=q+!_kSWI{K}gH4%edG_Ja%VrKCt0 zd8Dd=X9%?rMFm0XpmpAJ%Uju*PsoX*H(79xc1?GVs3G05$3>-T%O-7SV_Tx_A*#?k zR~NDkbFJdY0gdvPtjlNer^`@SqN%BiT}EULmmW`DTQcfj zD%vvBI>$jZX0}_V5thv%O~F5j*rz?8HCAQc^i^}aK8Vx*K~4~IfbRj^;d);r;=|%3 z2YEz&e8ktR++BbBy%-_H?}Z68e-tX$Ny*m7DQYfxDJWQhC&lVsf#`!>xp1JOC7CCHz^P;Oq% zoK+AtUxJF2u=9+=9)6Lau&#LOB>qC-ee@`9dDDu2!|aJsl^@^Gw7Xt3?RZG!f`E(1 zgbZt{cSD59FJN;Axuewf$U{euQA{7G91L&Vvl$Ym+l*p#=P1o&1zbg3d2Yz2SNhAO zcby0x1JNKKNO7F8V$(bAn6aSY53r#H-(pz%EQC8mx(KT(ahE^AT75ppv=8d|e-3gPvhcD{!1dJ0qyeOSHV6&2Rq8iNW}hq`X2ewv8|FT%9wcipG^I#8YY36mF%MjG8jU7w}!N|%01kKjrkK^i6Iq>VHz5nE!h6$YCrT`fua;{(z|~p7X0fA^o7qWOZB^+oqtb+EZ5l zT6`(LOu!aLD@Xb9)Yg4P;1!p^JZzH3Pn=9tN{B{o%isMdm2*>mJf7=Izfa}*;JehS zs#YYc)tS~1D8zT*G}zMqs^2xY83j8x8>fEPuE9L`@Hcvt+EP}M0Ham((WfQx=qUpy zdF?>nrele^#g-aE5iy0qq-Qwe?dKSwxrv4JaL-Y`tg|Rs=TMTj-s(3_|z4sa?U&fi-qDSkK{| zN=`Q@Yit71W>S!ibj-U#Jm3A}ivox#hp={IH11V-C;mr2B|4GoE_m&|$&y+%@u_pS zac2W~P|dSjdel~$bK%eS_;#%fSbX`b?7(<#+KNhVhg>naY-Y0GwwZhJ3P&-DB2O3g{bXqWLIXp^Vg7731wr8!7wwQwtB zYfRESIM&3!A8sW{FjycQMB3|jVOmn$pU2;jv7GI&Y3m? z0tl%hH~~`AW=|AwUp8ZnooGE}Z{uj7ScBmRZfWySn(lg?x8z?PpSftv9Dl_<_fX1G z*lHv)ag`87rxxO_3f#b>taQ6eOx=J>Kai%9LKSp?01&i%X{+An>+Z4=+{4XMF-01~ zFAmi9m$!QMlsk`1{UE;+fni_c$G^=xVPnvD8T(~|=+?x;xz^iaFKoqcq>dG_-}FA8 zi@RAE4y?0tvUI7tSZDtvsXXT9mhfUsP(pV<-cW0ZsNZeC24t9cWp|>e=o(m(4(OnF zmZbAE%zKwWke#6t6n7xqk9>WBI8C+>==^H57vYfh$)(YqFCWLVf_>6ovru9`=-Gup zjg??6vr)#gYat0*^J&B^eig7-!-!9?Zifjo?lU+J*v!k2wz}J%*%1SmJKK}$&K&k` zxm(;~w9pshk8QTaNh;#xC3Pe>hybHO29a1Y){)a=a7vgzkkx zHP7sKV$%r3+Gg=XPr^rqR#P4)V+|9MS9bnrrCY)Knsh<55X7#=Z8NZEMov}S2z~Ap zP`TsUJd$+{1N0rfZoWIT4eBNhlt0ge0eB1F*~dTN$v(M59ST2OYF?(4^(|d>(t!(e zMari|$axLAT9pcA{vpTSL&!+kUejBvUQbw6X&8r%wF>15m18{Gc`mpn`AB&OOIzMc z>F+}OIU6>>XMKRL+co|)2S3+;BE;_a#9_73c%AKcA{NW9bK<9vL-$TYSNg~>-hV|J z;1_S!9vYc;hMl&flwrc9-rb7>;AT^nK3B_}TWOn<=&Rm@Fi*}&K{t&8@_V|gT!PFH z;pi{oqw?Ft_o^^ryyAFlA78x6>QQM2E(yzt0;hW(T9Olmhm|r041?8CNZV1?)b*t` z$&)`p?41?iD^ zW>${W(9P<)Qc1dwTkh@f&a}1WzFk#}F!`80-kdhd*77c)mdFdLmdg>zC?=O0n_Mi^ zluS@`bj^oc%l~fH1OM2y3J3(NF24u_KVL;1Ffp8LyQn;KsM$deU}FRG#HLO}t>h1i zcI~Zs+#s%;&JAykyL@ge`px5+dF*lW0QO9R=a#0!m&qwmQQW>!VCN)}P$ zU$y=yZrbQvF_i7ZD9OtrDn$)k>z8Df%g|jFmiJLNJM6M>8UqTZsF<%yHltTTrIDE7 z?gHX{)j(ND>gsD$cn~ndnQ50Cyl<;c8)4 zFuf9rbquL?F@7s2_fgJ>-_&xI+)ZcC<==`l?;?_)TD}~2XNzVwsm5UEN2Yw*M&!Gk zS`IE23Bioe%=bk73ltu-nab5hA8UycCb)v)u9|1OIB%mA74GupFgL53jDzNkW-;5ru?qj=t6nxlwi~Dh44!g$=X|&$ySiKX!?|&) zkdn%*QPo%7GCh9~gU%@rhekVa`2#cpcw0GNSJVAmGc{wqGqtOwE7`f~BAx~7smBbA z%T4Lx=3bieb^8t8Z@W*2Hbijlj$VG~0CSu@c!&FY6SgZ{TQWs$_0lF{k9=3&Fogu3m8roBfa6-x3) zKjAzlASarqS{qtUd+}-3oX+XRns;dFFRz@2|L7;q3YZ_TO*JeVy|QbZ>SI8>SKDJL zN@)!kqX>ocB`HzF`@pLC1H%FAEc=K!J5J>wAtW1Fez@deK0$uR1mOcUx27fYx>2tQ z+LHUTqwDHyou=nuh&f3iiSMcX2TThb(BizbkE8b7yr3cOL1cZWb_t3_mhGI zc$^7DW`{EU%g_&k-GAJbg3Wi_@T^A(H0U$EGaLDdAd;o{qq$jEEfNx@)o(P^>guuM zmhkGAw~hR7ls*YA*ChvIzF#eKFwAz7^TS%Me#MY2UqX^|1d~V-cGDgVt_4-!T=lA@ z09|;0-CPvg&5iqQ9OMOjSB8f2h9clzAcQ?QcfzZm>QJN(bW+MdhDv3iKMCvz0tae9 z`){Zwe(4l!9}ol(ksX>u^@ZdD@GT~ZPo}>}xV|}ayHt4Y(~#5LRAz*K^9JGDctF$K zrO5c>i+wUC*OO$Mmn@o2^5f6{1x*(Qe@hxvY1yJDnkb8Fp zC^WkgtF*W4AMdFFO9TNd6)!*ODb7WMSkvCwIiIlrQspE&~x_z=9Tz~^aDEj6iM3p}X4C)n~3 zSmvm7@QQNX1(BAt8twxA8X28pmw4%{`R-v%K>9>$ideKC02=Huzk%4mhCM=2?3tK~ z|BgKqqD)=1qP{A^`VCW6yq$0~0KpoICT#mI>y-NCB4SU2_(pYElnDFuiq3&cdziNa za($Ef&R^o7Rm!k=vM( z7_YA762Wvc-&OXI+&9UfiHDL8res!UkOUw<)#(GD zfbyh)2^1@`_W7xlD(s%4>y<^E@j_jgUR<5;h19g3H;D>qX*a-GjZ!1@yA7-$P@Dua zBK3Gd-bWN~E({p7m8%zTpOG-VcyewzpO3jm#FDY4l2I?CQyVTYGIF=OP8RluTwI6J zMXBc4LP)$eog9}SSNyAm3=YhMoV-Vzs4={QQ^EU&HYKG;fY~%br?)}SZ@5hOSu^<43$Gsl!#8vyQ-Ny!>sf(gr}vBjUf#H_ zjXf1rE&Uj_{LC^^*870rOC!6q={;^kcS_s6>oD#9B*^p++r}ELG9zw7?AT_L|fiiq-%bL~9Ejki(Cx{h+Tp~L4(9%nEX7ctQyFtwaJ z<gi@OmkT(g1d7dQRU_Xk2%?H91LQn_J$=sQCm&{9+&^;t;Xx%g9py zY&rvb4igZ_51(}CI z5uF_1I(~OKw9D?Afg{q71%^fT)QOLJTr8X|#6+VA^resvF<(A|T?LJ}S{R~S_w?t&1}(hnCu7IfR_6$SK)U}Z}p$0~ zwp42ki*cOWxG_3PLJ8X@07Z@e^*0xVI`l2J^XH%X{6;q+a0+d1JfWHIWAa8ptu9pMCv}b zyk`5VIa6~n05T(VJ3%l#s{@3E-kgMBv=m;TfS`e}a*GR}(X3-@758-6=iT!5{oI)6 z0Ic)vUgTOw{}8*S><99np0BqY%ZRPFF6(R)3O5%%4LXdMUb4|@B2R0&er2@<*wFRo zoC_=1(eXRJ+V?+yUq33-THerm8{j9l?>u}&Fy=P1>&>%PjlFgdwN^xal4IqORKu*1 z|7?7VPD9;!ZBD&9qK(6>sIJI3ooDAsMQ(N^xZ1{&=zGcS#K&C~gxZG$nvy63_uwi+ zA!GL@JNmpjTacI=PpkSeYHPY(s(oM(&0syJL<&c)9CIb<4!hW)(AX2VbBLj{@zD!S z#&-`YS9z;`mbJX@>$y+?cC<*VvAdNJC?M)yvR*G;S-0W?_n9~WBe+6T>gZ|EFe|2= zx`$sjuo`g7NDi87RA-i6j)r3|f({#<3$XzBs`m7Hw!#XgIYbk7J+BnN1GgeJ;?%>9 z%kMD>v%Z$a!IdL?;?zT2MbsZ74!=Xq$~#fkfKKG-!zFOWd#D_e}1fPu6 zn~U(aJ6`Fa!p2wF1Tc9E?;of1t7a?mzC6^?NDeU>5gfk-mPBNM7)AwHp?uK`nhh1$ zNO$*@N~Vobo^`_Nia!MY<9lXRCeipbc0%#@Qj4G8B0(YWoq9#0u7cMtkYGnzK zPlH9;PS`iDpSJtljQsTH3pr(7n=mWBCxN`gDM%lNVjmoWOeFBAGlNy8Qg*Xl` zsT|EO3mgZKf)A&8@%h7cUtA`HN!Y76R;Am+ygcoL7Hjv;XFaX-%q84>P8G0)t=uo{#h*gm=O**+nHON{z)?UyE)!$}Z z@xbkEVLw8RiL;8AE-cBt>d?#da&-Ekm!v7ILIVzA1(};G6s!muD{}FW&kKp1D|pD)m#Wqv=bW%X}Yzhcc$=09fKXVh1e3h z1afQmeg__S>QDbV(G**$#?|wsIB2vUc()l|4Nf1}+e&NlbV zXC_;xR{_GWASJ+V+PSq(JGyQfCloksE%*wm4OdKCl)Bp7!xOiPyYlbm7(zIEAvA%0 z^QcJ@T&erJ5vKhw_mZB9J281z&$b`Zx8!zPKk(Y?C=Hr0A+p1w{CDz%N-}krSDl17 zMhA3Co;6exJ|VUj{zX5FKaDX5A}E#!DG}Z~iZ-vYelPkOa;dCq=Imbh>Xd67O4Mjv z9M9o!@KjfJbZDyzMw?kT+&-@RleGNdwuZJZXVHs;Wo17h*yiE~@>vrdgkq1oIwuuu z%oN|aD*3Ifoq@Wy2dD22<|HWlcOHo<*qLNHy!Aj&3%Y>880+a%?(?2Z1Q4^z);<4w z6z6dDwWV^*O_dYR(f8k&H+TW8aP)A#xf>}&^1Q)|@r}&fti+I7{jb*S846vcrE-1c z)nhI3Lq7V7i;4{rjWeIT9U0rm^M3f;c&+ovo^2MW(y9@7$LIJ;=~8iuUq)+?8%{V0^e_p&jI{tC$l@ zeBJ??pczoaskhT@WPs$UqIsvUxjews|CMN;CKosMb)M0=;F@arA@2gWKOs`;^xuf@ zF&4!5$Kyp4vbsoa5X4Nr8sHK7zsMmyrJH*0ydE9{BS z!v$T>2^;VR_vM@XZD=cw-}6pCq}I|T1srf=Lu7Q(i&fElzS_rrYw)@y-#K^qGtyO4 znY1zsM7mpb2{@kYhAE@WZa7?yvOA$p=uTymRw$SW1Up}{fzGMe?;np8+e`?r!av?$ zg>N3ITs0Ml_E>KQ{wnN+W$@cVlS@GiUlfC3Y@6ubaX?I{>C6cv01WAvp(^uM5=*Y?Ge1rmw3TDx?z1I5D7g#9X9(&U!Yp5bm-4)}K1ST` zRIF<8dcFRt)c}Kj?Q%FEJ$`nn+rMBDS$w)LL+xG8of>;(H(`@2xsw`hx$5p19yzxm zP7^?MDtt<~&@fy&{R-i27jeU=+Lqg^RNrQGSo?CG#^UlQNH(KJ)pmKtyb+YA?i)i; zqa;A(d*q1uqtxNNEsW$lS*^}dEm2t@%Q`$B)aEbdlcUn)yxf&IsZrI={Y$Gt-TW;Ro&h&_OXP*0;Zc47>0pbS1c zMjKO~c-38hndfvD>2z2u*R-x7AWEyrlU+W+mEWAvB$!S*!%kLUDH8PJYnL&;}WOO($|-!*gOQ2n^& z|2a)Y*#Z}*?WDo(JpY1IrT}Kv);Me! zM#<|@I8~}}tT7QSTZ2$uHiU?`iW5}E!a>|8;IY+W>fR)D5z_RHb$kDWSC={SlV&^o zTS1Rn!e06gF>PnwT_MHS{{rOz_`1r@Yj*9hG^_I;%Uq%1tyQ<1OgTauBYWw@3Kgew zrX9&$r~CNf55ukf*yb}O3 zjvj1m03L%9W$ ziDb#bs=B=RJ$TcCeT%DN`WK^l@_)r_@y83yhmA61(deX$7+sgc$iVu~* zRW7m69UYAWViaCPuVdZ<_8~##JoC@HsNE|EP_BM|U1C9PrQrVfeWMQxDGSm6)9e1V zJ@D>vbWZwNrg{jw)`K(0-q$SCUn_UYE_fQ}Kwo>UEH^n5WzDljTYlE2Q;P3}vZRnf z>DwNKmieLXP3&R{ynWTLDn*_ipazfj(9rIqXPLYM4H&vVsUZj&0s?3cE(MrfP04*k z>syc*2sQ7&b)HPQStz#dY&0(V1$Ko3lc?vj*- zL&xrB}E^6$IA55;}QCKXG4z~L!0w7v&7@}Z{ph}|E0UH8@2ioh<3 z!-$T;!MT}vbG>~ZbHQ8w{UVcUUsLw4Sy*Lr&hTu!cXl#Qzj$T>BuO7Z=V(!Ewb68T zPR$=COY_9IR@%O8sn7~#r@JgUSNh24i%Nu%boxJ({N7tdb^Z9VZk$?n%(miVQzr2a zj_UU+)Ejtp%wQYoY9xPgh*M%TVP1dIFp%}i?XR2jIX)owS?%GHf8~sg-)RmxAZj%(iDoiWGi;(4I0(I|4Wkq;|YR{?@+){`=Kg#NfuExK|x1;tEZO!IOd*y%b`v2pDx29<~SG%nU)xge_3z)j^EFVn zfY#Z3$v6$|6lVvigjOw6GtYlXZPypG@TNkUp_e27dnc5Z1t7vjt4Z2_{%3lYJE?T3 z?Egmmt3b_HFCu7u8?WD+TmgV#2&0D2( zSWa`^ycM1E=CN@sT?|@^#|EpwKl2HiiZb)!%C@%6n|Ch4QU0hS&cy<2i%&9N3(jQQjLqQN)E03mMso7cg!a5k{w22H|z>P$WeS zVLbvuK}lByt7)giPyBog=14dfMF+IK6$)>Tu?54KyG#xShlxx~3$&0J6X)lLi%d@5 z(t$Y=V_>L33+u{UBIBEuPFQmcf${ChZ#v@fwvJf)>5XQ1J3EXSgAW)zq8%LY#OaS& z;B6V}V?1LI*k@YrP=nSCQbVnJSaV0K$!A4ih{?G??T0Z~ODpEc0>a42PjG1F!;F;> ztkC9o;^g-ynpk&hl9Eh%I^gl3KbFm8{h0X>&P5hu3z3^iN5(jS761HqKT*TslQ8}N zbO-o#LJZKhPE5v|O##Aw;0&7jALfSEv>l_Sm;yn`f| z;OKz2!N}rm@esS);qAaS)5sU~v-~PzIPRM=a2LDri%Ttva57 zb(}O{rg%q3JPyc_E%bp5+RVmsLUfsuXO6KzJJ|wt^{EGGTdXBy`W*3)6r&0DlX}?# z>jH_p%*24w%vMN38B>rmM?0c{b)S3-Qy@57a>Ha?fD(YosvlN`8IWWIP4!%y%v|jS zO%-jO(60Pg^kGeYGdaAo3fvrSP7;EnNJ7qLI5TIIwvCXQ7IN}Al9DAxQGj4-he9gh ztoY3jOAD)zkl-6;PUfyCCsX(lI~7+YB1%r$*$i%Ar-YS(q4jj(8aSk&x|R}ANlw}l zr7bU{VyyvFlG7l9&+QH5__5lG3PJ`)k656vN?@Mqikh|tb|~o8VO4&No{OzIR><1) zFv<~i)X^Hum#A`7#>!mLQrP_H5rVR;>O`BFq5?l!)&^mr#dy}v5r@`uA*kVmoK0~$ zQ|(xylRnJFRYhABVFuSEnZg`xRgRk58ywcet69qsF>;Pb6`U%;jKuGXff?AFDiVd2 zT$Nl=dio?3_)J|E>1ux1mSCVQC<6MiH&d9HizQl51JFd3fIcci)IX|;SF#oqF~jLv zo6E}J4fJg7(1*e2))Q-nqxCfT(O}(x76K~P@-Bc55Ph6fwUjJDpH^mYh`tkZASq#i znU?{hPOMS~TBV$zhzjfzjTFr$$F@D;uiFp7e!8Q_OW8lkW%u3#M#w3V?@*E-^e(w62|v9=+gtfie)^(-A#NrEKQ zQGG|0o+VtxTFJ%SS^;gU#qXjjE69)1A`;QE{FCiieiyWynG?!d0fy4GcT~}q2mNTc zsL09SRkSDDRkRiGjQ(8oaQt8_4JTDOc>+rDKReDJ(q+c}egmDsextC0E~uG%?aJ6| zu%n-Gfy>0MDk2FOJ#%MMtPIfE4+DeuvEkPm*D-G>3 zNl8xL2_*;GNE6SvptLOkMfGRCch!d|4ZbVws)~hnPTB?Z2Ln4~iISacn~+{tv&rW^ zNihoSt_FBk-bGDIkY5!mO#uNfT8T%|11PTiX5YykL61rBtQt02&HK!*YU z(-Doen{dbfDX#+TwA1Gy3|E7%aww{?Gi4 z8NQ*kG+5u~j^u>bIPDXrj}La0#g7#F$95DrlDu$+_sl#qG0z&Tn<&iKEY=+q_>b-& z!@2#^4t~!r#}`};YiS}1GOsu@V3G{%4UU@2n!HlC>9fQtDO%a0^~~|+komWkW;M(Fs*rmHzV~I5EI(#6x@Lx%JZ=R-j2 z3E2XdiUiy%7trqnT~XH19#6PhE>OFgte~qZ;0KJHJm3eVS=_D3y@gzI11%XL==;Ep znyoKDUwIg`cPPLw6JyLyC)Rm^y_#_KpgEFIvVyQlK7i&T5B6o^GiaWlKAYi$OuC|q zKtgajfK!!NzX|o~3VNN8P>eRzE9AT>LCz)A>!;8DpjU=F0393DCvd$9XTSmPh-Mt0 z1pYbGApqk=GS2Nx(;)~U5L15yXK@Dr@F~DJF0vXErh)m7cmoXN<4d*#V`nZ6!FyA1 z5DQ#19b1|X9s!%r&##~$GX*O#Z9V{1;4%RIav&WAy?%P554`~%6XP>E2=e*#p&Uf% zsV&Bs&p;EW0JXo0F|pWv;D}6s3amTDY;(Za0;Y4Gj%LobeP0HHCSk5AuuC0}1@QVO zq)S8y2Im!??x6_s1L%a6%NT6N9Grl6axlX%I{G&7>T9z=!1;Magr{8HNwP55{%iAb zL_1hw9RI?6;2K=08k-T{?qa>jqCqd zL_og^0B2=zIRTK)@iV!bB>n#Y=fmL0&pDq5oTa9i5Q$`-xBf=X{|oZ>m-(Hk1;CD@ zA+(#hEPF^N5TK3!GGDVwF|#k6%jX&eE;I{WMP{Yz*HQ0p8&Z(}o0Zs~8*)PCC&~3K zr1=LG3In~KQz(oO9@A|8=S(RAF&pCx&&v2r$@{-Ir2s?{`dqCELcy#r81#R)LP3Ds zfX`R-M~eE-N%tS>FoclsHxu#C4f*d?DBxr>;fsDrqx@;Fgc()(ikJSs;&c2vRD{T1 z@O=KViueajB1jJUDhK~>VwNb9G=%#=7|x#!bpkB&h%*|d<2Zo_>DfD@^#p|hekovz z)0hfpYB9r^N4^2;*B~RQZ(-9}$AE9)SJ{f)$f65Xwms6ogPvw4$!P z0nCaYd=8<95Jf%(LML$|5RjZgBxehTf%n`iS20^}= zVMiuar{j8HmNpZC=}8n5gys+1Fi^}-2qqYF_Sv%{nA1?l3FH~V2BA=;4HFwAK}h5u z;DU;(_GTay4)D+kY;~eHMOBE)grLzU)-{2ve}-LSA?*6!5?(}tXd;w<2@?=N2n!+@ z+L8gX@CXPXzX~owDKsz`0}f*Kw1wfkaAv*~)3^Oc6PyGX5Z0gbUd+)1t51*%3*ZQ~ ztD_wqF%D4T3m_Cf9AGk&sLCgx1++{DCNVBp#|fwr&`|`!aKQUXv{6J*nDKrJZUi5G zLK~qc)iDlOkcRdt;yi_1@*)91$ABxR^#@^_QyoscgLd;1n)!K`|1)luppXDBbD}nJto!c|NdQp;wI$PoaXdl*i4vF!N{BG*+TUu& zAUAK)Szws4ug&7S5H*J1`i(B4nJtlsBP2 zaWMKzNfeXR2j2&K#Ki3W``o6l@!!g-?K+BR|P*;1wT>##7sc>EG1*E3LdKJpPB5zpvznpyxf096+9GIoYd>g*u!^Q z1rPZvpLsGfEY@^@=_~gpeWzvczzLZNOacUJk{B#rh=7m?uP_4!Vs$-`j7R??xD@Og zvLU`_zhkZxey$XLt`vT*6rOR{6EhL_tEKS&)L|AWh?r3c5AF{Ynil6^W+1T|lYe6= zJTv(Hr9&)BRF`ozB1<@Hy1($pg}&314kn^gQ(;_yR!qEsg1B?F@XT8u!G${jHu;Yi z!wc}kkpJb?@XTb~FG;~%IXuJZ{bw$MK#DN^amKNWSy0RLx&QC;75 zhB<-yZxyH+Q7Xu){j-IRka*3gbo|;hz6V(YKi=}yVCbBzO_1n+z+dDSm|5v40-NSS z{{5AXkgUxtb^OXSz6)9VhEzEgS^GO{$NpzdKti8oS@JM{EbZ@e#gIaum+1;H;Ya46 z-vzgRLz>J##H~{yvZ))Qp&;4hmAqfLZspU}FB1il%!^;3I2&}&%cnc0p*N7nJQX{g zq3b7c_Q~ooGFE-lR8Q)Ke(|9!Lp2n)ELMF1|0nDzQ2Nb57tG|WkS7s4|$ zJ87zF?ti^j66`rBg#g-mVrX9beb3GH7|DKVw# z{@$`!a98(?)7!+IW>aM_NN@q#q&xCGZ1y+YR`I`?bvSpKCG#rAxyvl)F0-8a`JDf$ z%Pc38q`tWTa%RDsz`wTu68hnC$bPeAN2#i5gNE<14D!>D^ZWXT(wd6$z&${Lf0a~c7=r)o zl~~hnNtpC&{?_}kMBq#eoUz~FS9!kEJCNWr(-X8%(kd!*dkq2VfYFiQR^Ul~XM%eI zkaV*^KL0v&Zz5gH0gnf_)X8)6OM|VP`pZlub3of$q44Gy@H2fZ&rE!3jzwEKpmB^3 z7+(No!QlQn=+VLW_{w?nw$B5u_H zc^>{C^4x0+tcn3DBw4@Y#cxXOeKtuqtO6pHxJoVVpL-De@b^Q{_r_`baKhMr{-O=@ zt4VP^7wc9pfD_6c%2yJ|Ih9R!;DoZ4(0Ft^H-~YfSN+m5CYOoB?>VGC1Qm^L2W1QQ= zo;rRgnQc}p>UdpBZ-goX`W?RMYHd+>==SaV7nNrhFT;dfAIZL}?n8tY+eZiZ2LqOa zZz?wp?3&epdB=UEEb{hfxiR~OMDsq|NR!EKKYZMAo;Q^@<3WJ@Y@>QR|IoUeZ2UtN z-siOG(pi`ADg!KG#h^jslYls56Y?F0vDqy@w9r$zIRus2#+lEi!``~w>z0wzZ@i)> zb3NJXj~4HoZCz4gOC8TN@-6L5dm=5ca8_}%J|1yk{ETaC4_djBFQHKrNu7PGz*C;m zCXLA5vyC&)J9>rV8M1o3s3!Y1DHF1<-F?ig>x$U6FynC#`@*5xw-G;{nw8ioleDfF zPPo&-UWLCG>N$(S1#^71(UZJAp=ay*Sv@DI*NZY98{gI2cF%Y9_Jl@xL`CAP>w31D z?fBc_6>O9)d-avlvk}|dV3O7yZdES^S9GRnt4hwgvy81LUYgynif9J|@x6+<^h$oo z4^=(Ca@gq4x-P3Fle|cE7TJ4t_NB#6(t7ZaZQIzQA;bMqT(j=%#MWzXt-@Pn_T+TL zWzn;}ngsvA=ks1XL9W_{)Qul0XHo~XFV4C*$2A}}xb@nb8u#!)h1_i9ntdwFVGRy| z%`lLr&Q7B*^_Oe0aN*Fl6|<9mRyr|OpuT9nH+6r+ex)z}1fH%LqoLO0FZopZ| zGO0J_NII+3Z=YkDIi{JNGiJ57lWJ*>Y37(_j%jAt^*OPa6N@>qm=g=;q2mkE@adyD zzjStq`DR@zyzZz3pT0Q9a__Po{CywG1lA<6p30ma-A6f-MvZAbWiA7F21knbr@fo~MTEs7;e|tbd??*4&7_r^8XmDx3zl^f zKW_RlZ0fYpfQv zdhA|XMO?>9i)UyyHp(^yyvbMAc6T$FdT@2SYMQz?RW*%!H_O3Z3J0iNS>b8O!#X|I zQ5gQIS3tP2)N=jY1ARlg7={xW;Gs(oW)D@}sXH4-vb;so%ylM67A&q9L)S)EgUE229xn zB4=W5xI3&H&pHZ&v7Tu_E9S-@^Y*ZuriQoe2k^(O@x^<-;M9YUyn_J|bYKPs>w3ot4m;oU7acZ>t-35rC%vUuye%gStk~KhGID01s(YGafD8Z0m~YvMzWRx zNZ#($bS+*@6S9__uM!KQr!EFon37bfdt}=BroPN%fNk7h#TtG28>@(mnQhQh-_8`? ztCx3@bIdX4y&8^Yz?2)0>8yWc_;@D;|N6iJ%5Yi5f(p9UYef@sbk=!RC@^9l;HJo* z$G^79rOCPxH`yo$^kPe6hjXsj&_1fzWe(@vKbjJm0w5E~`--OC_WritAMmK+;Fo4&xA^NQH#y?^0QxJTQ?@h&~P zLINM(zRN~+MV^meogh^{s{;)m3Od#UaYi!Cf7g{quU6-`B1*E{-;bQe7?DL$VS@OtwV&dmW0)nbM% zzpN~$z=RjPB>0K0X&&tKuQkXcIjw%$yZLqW7FG}H;UKCyy= zEkKnhHo}n$#s;nX+YVGou=xhwFInR$bU>2YWv2hY8ijrKj{AbIq*zK5p9!#U<;|PV zu#y@wpJH2PE{3(`?heQx`2IjUjTArh5|^~jfALU!S@Eb(Ny$t7ir-qV3>2{^5+trJ zeQXD`Pr|pPjRcb5@&QxKooopd1I@t*{XXoPTYIM@e_@5HI>^RHW zVPg1#y9fM4khcl?Lpj3x7XVY`Eb z_z(?;(grTK;JkNck?GepkSA(Z@1tc3mG^Co=_j_-hl$b09qy@=bJi2uDkCj>lva6d z$+sw2UxhCfZe7=8-FzK|*W(J4Xbb7SX`>ZTt{gUQl<100Yz_OZ;G}tLPHFIaAXM({oC$A|1~ie9NS?tJJ~aZl^Wd|HKg_{e3+<{GiE1O9vM z`pA781;RbMy}YRvA3Ofqx}6qKiHv=`WkG0zqyo#dY z%Acqm+#5?QKlh~nrI%QuV~4AoI6JlP?J?KE(7s}}!Gb!AqvQ))Gjw)e;y9Ku-?QW? zO(&${1wyaMtfj#yS`ytE;oeq4jTY9`7`Ym?sp(dMajEQOzLGi;2iaDW_{P)2&7!*R zbx29m(*^m>p=-Kdn)=Rnisb_bGn|1TQEsXz6e^LA5 zq2ZE>pzHI~5At1)tld@LXR^Bd`pP=1F+d)^60OmKl7nfDyoOD0w}!=XEPD}On4wa- zEgin1m`WpGD2spL@-ZV|0fkI`k~A8HuhZz;|M;VxC$(zjmV~yb9m#{~2kc%;_7n`a z6orIa>$b&?4V83@tt!60OjenXy)&8m=0dIWd&2Acr<}Gx_H^|~$AKe_)gCSA^zl<> z1_suCo_WRd)|8QihD$xU*NBf)tllx5(yv&mL*E7;?o7SbJYMy^i!_vmR7gJoGAZ@Lb| za3>fC`RPtmS|E+d)8E9On<@9Ks^XIdl(O7#m!qmt*n^H7phn}w8@A6+H=-Y%GCnh;BSN-$saLT)yZf4KvdDAvpp-Z zwRBx2UzwPw8){3#ZzpUxHlV5S92YGM$?Utwq94{%`?+eOHf$x+pX(iYJLG1OolQqw zOz#-kv02i&qcgd_q8dwyg+C$_kfbql-8L=jc!j^ zwDi@gPWH4n*i^+8YSZu9u=*#-YuM^L4XdajX8Qgq z)uNRF#vAt5)P+Au)JwHff1ta7(n!mb9qn%Fkj#7YEL)+)hYpKv-xIqul#A3%j~p33 z8}%Sz6o}MQYF_LB!H9?I_M~`GX^<5?))mtlA+cHFH@xeRmB=qSuBA0Ex`y+#2KE`T zS#|0sSscf1yWmb@g}YjJuscd^em zSYJcW4YVr@=X6aM^hu&y506ugRk5xTY!nm+mNkOwy&u>ay|sGSFP}Rcg`txjt?eo| zlD9Z9(y^FUcc1*oLuSlUH}X!oVOl+6LzQt*N}HdJu)(|b&?}s6y3Z4%J_M8$aWtip zi@lM;yEr-xeZ8qp9oML8l<*fkUGw%+ASa{k`@!1c4eHE+L!>Rwk z0i_((U_y>vGEkOF%YK=uH~eBG4{l*jS84RJJ-enmL3wQ*(=Kto|x;IlB#{2l^L{u0_VB4ehRGmXr}sU z-7;ayUvCSQ{Gf(k)Vd_nlCyZg)=y&9;vqfDETq6R#(PCd4J2#@#HW zp9r1YQ%k(8BTu!!;#M#*I236m!^0Ow8D^Ir_8^6}rru+Puz2jb*<<;wj(}E!Dg) z>yBsXi?*!jZ1k&ikh0@j@{zu~wuzjicd6uN`o8#pO~S|paQMq2->p|W`mA*W$T@sI zm>%2upB@+8FO3-IJ&>4M=d2rvsa$EBfCs!$E=nJ&a~ZC?Rv1rve>_P1*16hOA=mL) zj|SlJMJxIP1Ge1kf0RwgU*>0^|Ddfq1&CdiBj)@wns5AlghWs00>X>6??V)#U%o59 zoE@wsNsw(5+nDVL+`ogy7g>+>&nmzX3C9!7$!ex&E>!e^l$kfxw8jz~27+6Z53~lD zD?~OQARW|eX?ii-zGO(PucazR4&le?X$_9=_Ffa}>Gz(2?7A zw0n8EG&c#S;}#MR5*ETJl|9O7XGy_=_-N_+klNu8ahT+2%~g~W)-Svg9HZyOQ1&f0 zQy3~oNxBe|w(7+ih19F2-+yHZ92-LQs3M{PocQ!}wy=t6MC>AvFJqv6h?R9`YI;Xg z??^TZABN;yR;qvP^&Oq9p|`5{Q3-{HJ7{CxRC-a;Xzh4<);o0D@eFUTkO8bZ8drg_ z?tZ#WpG%G}j9e<#7hZi^Bi&$SC%JzCxhy80r~Hk#hePF^J$i%YU0yXC_t~A~3sWYG z9-^pi)_L74ydgd%*YiR5E(r&n7`y7mVJh8^yI2=9@X<59$!CvnjvC0Sak#WfhL!Km zLP-^?zPyrGSERJOsi)r6iHDV2I_qQH$C~aPJm7I$GJ(9)1}=eU&O6AL*2s6dzjo`5 zwQbqwI)m>Q>ytzp%i&GogGYwNL!ZC}7Hp|MXRx9(UO$OfOLbJfB360#g>BaxJzGYi zZ@%K_2@6RoBWG)q58*5M@?-LHJ&*UaQ7)I}wW#1K8aVrjdM(v~4SPM_J>EsOe&+}B zl|nEv0<7#*V*vDNto-ZQ)5(}mO6}Qn_ooE1xJ{C>T^SsIW}t&N%F~2AQvI5Q>?yl& zKjx+VVb`XfMA=JEKWf_3FWxUZMBU5eF(s~%KWG9llf zZ6paqeP}@GCZ^|lK5u<2?yqK{TVc1M7Qf|P$%W$KM7Io~dOlK}9lKs(H;2?%& zw;Owu2`TaA&cES;Us;>bd&)BpAxdu;%4D@BX%RlmH#@L+V^#c(BeJX$b9@LvR(Nk# zDWAn(jG!*u4_qC%=)`Hh%E|#cf+2 z{k_XN(}p&*P1EsZP_h+iIKO13?wi&U5wrAQc%b-bw)x--^XG?@F3&G~=D~5i{@tAe zNp!5<^%|Ax6IO8}!|e-)Iu;kGg$hfwc#Y>e>#$d;MfOMvvxmb|Oo@n2J(W8? z7!Z*sX}MpvuG^&|idWd~02ZoYpkWh5H^!Tq!DlWw?6(Riy>}n(P4no6)&i@=WqEt1 z_M6rs#RJahh=-JvEmeF{yKfHkU-QlN1_ge ziA9+NOm<`Lb@E2Lerizu!neT@Wux{$??aRoVeyrdOb&^R;X#bt%vMf!)pQ>o(wEB{b_33{G%d4c5GP80vyd7~df@-SJig+#?zn{S~x+o_87; zjYE7D;Ms8Mz^|bLg*M8(6clGrxO>;r^Yq_C$IB}*6@Dv}yLv{e_ie6<*L&g-DB*X| zZFd`jw@s3F^9dJN-^cR>(>2sWgFS#oqLSHP;|r;mY=(zT$mx%IBiS1qeZgtD{05RQ z%BweW-Ltj=wUQQzWVM$^@hKoK@z-?oNvS~g*5AFUdCK7I`7&-V&O6tWa`ShlDHeRA zAJrX@)R1YIcN$uOr!ZomsA`~e{^n~hla8-0PEerSe_CVf z*U@jFi+g2f5s7hFEL<~8Zyt5uzD6*e`_M}s!zexHBXpJ01b6;gOVh=+FXCxi6z`}R zl?kk>@Zvr|kn4V0lBHoskUQJbzV(V{o5onf!*Pl7=F;6Q57QTu%cYU9T}LFXZDTp= ze16k&F3sI~eFsv=>_`Xh`O9+)D0!}sCVG*$c(CW@W=Rh<-+-zYswu8dXz7v}d;pt^ z`rWx~$#B``Ju1;R)J@2y`&Y5<*|WDmZnxzunmzrR$)HlP%eB{4HHMZJZoa9UL`3Eq zkxQF^m2Pf8Wq68;HJ|FN*-O0RO&yazKabv$M92v}$3eY|^rnvLU)|+kY4Lhl2iMKD zqo|>BUHq9r-*;VWs~Wdzu6^f4OfAf-K2#ft@4tlGv!;_yC8f1QZYC((WDLZ-Oagdn zsiE-!gGy@?udyJ#rZc0;$_@zXn|c5Y_XSEX95Oud#*r1^krIPIRQSWUvq%$*_DqnD z0F(WdZfqWM%%6(zB^~Q7>w(1&BuTV|z00S*+w7M^;#IukcD{AAIXqzT5JFo_GP4<8 z{oq*Ei(Fb(+T*dyufU1|HAZ!Y4#eK-eyQP2T}AjYpdo$tk`K8n?~U`PZBHN%lug1rhPhB$uT8m($A&3?TQx zLF^FgKC>E^$z6T6-+K%_^tSD$8_el;uyW#VHFIoENK`*1EAe@`UD>0cfVUhT@k?_q zm#)&k>2#;ZOF*n8hIGHK`Rvx~w_(3NB2}*GX0(63c@GqVGD?8WyCNmDY<}SB1Z9X1kJAnG5a(+5h$|+%l7NQW2*Y?q8OKzhSU;ljKff zGl=k%53LWnf;aC|NTMr*l}KWA+uRPljNK3x9xRslws~yW($+ILo8#CC>JOBAoBfJk ze8hFgS9w;}h05#e#Ep`xCHI(zyr@LQ_TD*Io?I7%bb37I6@=?g>eLFRH-~|9RyA^` zA1tCevnn*DA#4$H->^AaH=qCsf)(;ZF}8J^77s;HyYPK4Vv1kHSPqMiOQIGg9SBi6 z9ZMTqfoKlX?^l+T?08l0P~nE~(75d{Yn$p8yJ)B*XRF4^x`ER~O8{(dd>LmL*y-9= zt~H+7syBciSX&ier8~`G)|LfUXG^s8m#t0&n|I{n&Ov2&F|{TxSkicxA54@S$Npm@ zJgvE0|ClwwQQ^bb*6Ut{x0?(>EaPKK(~Xrb9gD}u%mnxRo^z|GH(iWen&oh>2Q%z0 z`2L77A~m1Aad}5&_ARo@tvA;?{W(|tJm?#|ZEY1_el~AE!M1yUe3Hw}H_x|Ty?KD7 zA8`g0^0>EWl(?Isu_cgB)WK(eGJa+o(>jbtFPepH{3-s;Q+%otAcG{OE3+@eFl@hm zs0hxzj6ULB`m5nX7x~o^@Ad9TxOIw)le6Bm=1&}L^#01xX8EFEjw-rtSkWHf>^25I z7}dX7+s9S(uJfv4@ooBEx8~E;5=ngukskv3hUsE%P58um3(M+jxwPk_TAty0!iMBq zLS>~PcR~ikpT2M)o2ur8W+K*A@NFS#n~;B`JR2AADjA#S(R=L1zEPKaMD}~0m7QL1 z-(?c=E~*8z(?^OGKfF0q;pHHm5|)APJMR3W=JGB*$~_Rs^+!nh6LOMhcP@KVU7I55 z?!+YH#}BDA_WrB!add)byMS1;v1EqVd&8d+jJtN-mtfii$N}8~&>o`HmzC`^X|~d3 zo$<=BL&WBQEQ7GFK)8T$(eHhg^y~Vg3Kc$?Zc%Q)7H+;~bSECT(`)Pa!k)mz(>}Z@ zjmt;}Cz@56O%(?V+a0of;5^`jIWX8<;i489@OVtEVp)gRPd!hElN8r$PzPmSt?6tG zmWA!02G`|1YD;;(XN4d!Hg8@_OK+%Ob<>0MY70lOHv@NX36)#1fKpjMdW_cFNI$xt zLNgr=j@6x$u$W4M$U>wVQw2mEV$;6hd6!&i$Ux#e)>)hE)O}d{A+m zn|N9sMdn^@;mZObI`j22Q$>1l{R6Gfc@|Ix%T9V`C%P1#52d`PD4$tVYgs!^*|XZt z*(B#qQZ!}RV)=^%iHF285wvDfF}0Xz`Jt~-Qlp*t+%l>eM2UorWKGD``J${UD1ryV zYBaTYSTz;v1Cvg)plk%-nZ)~rX8PAw^vUrSkEs)S9hLizMp_mO@OfnK?tlp+J~Z9m z>*3+9(A2(F-Hx6j9>CZ9+@aCZK|8fvH>4!h^Ox+q{Wm*Pl`_xh`&0T2Xgrq#Wkxx| zWZ?(XTCVg}4pxfrAA;}9?$^F4A^#q4?f?S68{1y5>C}6*uMh#}rXOt)9uHVJ6#vv0 z$vqt4Bffu^gY0T+*X4jE*}aDr(8kW+Hw?V+W1ubC`3X8@^ zAL#Xe=#OtHO!w`7RhLIH?e2gg9|tU}Q|pIAMZ_Ul1kshSLjc5nzN>hbXzb z@wdG?t1J87n8i1HD}wN&yt-HSy9(7ivSVvF>JV;fTdwYWYW(wvFWs(9>uA{UdrC2y zs`UQs2SlTIs(ceji3l3+NAw&VtS44p9c?3Tt9IN5Qd}-3PdmkJ1PmDSON=0^_|Fvl zE$i0+xeg%?oWx^c?8?S={+vO9W}0;t#>3T!w3eJK-LZ*%cq^b>7$nlx#uux44F}tT zK>RimAI{lE)`@rYqFCWI@ogb7eGdqDJ`XPtL>he&L=h5gZWrn}f*yS#sjS<45fgKS z&Pz>l#2C3_uzq}-R<<{a`E;hERyPt=BD=G3XIHkr{2=OE1BK1cygwVYw8MBTr45xc zl92umWEqsM}z$yRvn-j3|h_3}6S`Z_`e*(ZEeHmOpmqD^A`GDd6eu z%oN}0q51PW-vnCn%Er5$029JFcm!DDl5%}R-uiO9>yY4C))^jtyg#V(Vf6zPAlqvE+*}Uy-b=GoY2SCwBLpu; z<9#2D8g4I>O#-=b>cgc} zW6wtdvC(>to?RC=rdw8wi>qh3@KgN7MOwPx>FMwCL|22D=<0eKM=WYE{GGgya(tLp zjt+TbbbwmWoOKyN-M45JPqQL9=%yF>gZGQe#BGv4k!h}H(gr{!=9v3lR-ezi0v!3% z6x58rtb3DXB0O(+$ho%MQmMUbdgAifm4PGig6_A+yqc>+gCr4dySa)Vx+602ui~%$ zK*7WL3R=1y$dB6mgMtDC+A<5bw#T2)9{bRgwJiap? z`5b{=Kv8_CyQbKuK$4Lx3L7;^#n-V#q& z4ORN%iyUW$KzOY4?))HewAD~u`qJh##dcz=c}mlG!mSq$ArNFYt{~&(J&m4pWstmb zE9xPRytMl=P|;8ft>gyM>vn|a^Pc-!#A5xP`q;dcdBqF4XqASErmurFFB%)!J2p`O zcw|c4#>$P)Hi4rh?$+JKUsf3g+n;IQ$bNCHr-X~3xJkDrt1ixEZN$>@;kbU76gN1g z2l#d*7^nLO zuo|1YrvOm2QQiM1R-T(dGAV90|DUTvqWjGQEDG+EN!c!|%bwK*$ZqKzY7@VPZ!YXB zkALb3jswNUdI0GO-&oC^2AvQnG!eJv1%q}W@s1Y*Ka7r}IQLez2VA$S=CiAfr#s4- z&{GdSU6w9}H}|m0aFGZ;F=~{pw%6*1oK|*Vok< zkd!2Q`nZL;#_FeBMUr%1Tfdk@uhEVp;5_X!hD%e8FDZGuIV84dFgPhcso$Qr=w(yR zf){YFqFX`Nyg6b)+=O1S_1dzwNzDDo zmagyT)D*taW}L9P_}LM=Nw?VpF5rn3{uO}#PKO=k`^W>c5W$wkaJB&Kdl!y%*HTb$<6a7QOFSGIU^&w+2;~TT+s&88~JW zo2VQR73HZ-?CBY}6ND&qWueWGCR$rU6 z-KXhN-{nY*3xG3Fs&7L}%0@|9b={9u3Jc&l15N}0o~;@H$BV2Wp(fW!eah!iUni6k zx)Fp_nm{J6y2O$@iW&Ynl~=u~W^hgG7E)BlsY6uCZ zc0agymfq^NyCwPkZi|sO`NlPOt;)8f#N>{j!8gAExw7Oqck|mPAoEu?`lf*=9GrHF zy9QY0UWx-UHS>R6$EqM$-LT13TAh<3Jn0-P7*Xdex!iwjw6?Ll8wr0O99ndmbjYnK z)gjXZCNgYc-PX|zQYR$nUSUry`<$P;bPNZ4Ma5s0@`~+3kU-jaUwjVxf}aA2oA^p15h%6&Vdf z*_o@W%^aOQ3*L0{TbMZi2;WTO_I9baD8Sgb3+@baSIth@ZJrTkJ_Y&y$3*`LILP%IQym3L)Yt8~`Y?1f$M@f6uw$?^juD$_-`E(*h3)Hp+-a0*&TwekX zZDpF=ta>h43NY~^tBje4x9Kh37R!>sIgsWK6mJqAPhs7tGK|=8Ei2KAR1s@fc^_+2 zH^f$-;Z*#~4v(bzyYn}TSxYqtxSD`SUSijh8g&g5vTN%8Y4LtGu-N5S1b57$Aeb?j ziH~B}wE~kA(;P#n1aYw*Q8z3%3qRUk1!mpwLu$}hjsi<H;iC1wg9R6hx96X2u4=UF_h=Uu0n<|n5 zby-pnayRV*n6JEDh!QK!XPH*+CQ!OSmdEJ@2H(&146IT0W!VsuVo*2K*f&&i0b=UVBwbz*%g?Ku0B?rPug-B=rLP#cjpQ&Ybo3GieUBFiM4t`xmU} ztQ=oEkA?N53ZTlF`{d^nD_y+EE~hQhokj>R{#D-B+I}z~OWLIF;feH*VvU8rpId)x zx^yttBgF$0X60jEVwn)&u`&;V11vmdtpG&LBDF?lVg&fo@o`JZVm;cRF+$8gd#FLo zEdN4bYOP&JL$(|7Y+GvW*0}M(`2NQ$_^#*I;)d%9RcN1-+N#%Et*R3-cbpE<>jwo89#T?yF#CYs%vuo{%Kr1$8u@TgQ2Bv^um z=$#Wpdc7#etv7FU=nT7Ea>)a;f@WXiG0nhbchel#(8rQrI+S17e5bp|i%wDAeY{IQ z!x0;oIaG7Z{?Q`+@v#mLo*prFy#pU3CE15xi{Mlu^4 z>Iy05C5!v*MzxQJV9x#l55NFZ1*EsVb_M@da7454z&vkV$l$T5=}nBUel9l@NpNW2 z7iB)$*L0`(^pZ7Y2)-=-CEFa;x$A9yMe%^F3foo;c|<ic)qDIxnNtgu?3WoujQc9@!<`D;a(CT{^g4Oow2=BtV%Q$FYqiy* zIXwshA(PPKuFUq6)YRWgM^2vdQ0&srm!D{hSjGl~RsJGhPVOD$z~3ahyStAjy9k`$ zz!Q9zwoS}=Wu|lY?+ZCybnd)tdh`Jv8gjiL9KHSRfJ zep3sVsJIfqXLwe6!ICWk%LFmp2yFJ~)+E1g_;_~b%IS(A>6*w(rSx1Tq9pI&nN z#QXen@4Sv$?Tu6mzr?K^u>C`!pIq;wpbNV3M%$=MR-XK!zd(CzxWh+>Ot-tAh$~oa zUU)4pNL@hpOS80J&DMO%qve-i4eN9B7Euh^SB=R`Q5B-_8@YvhtBAjrS=^nZcl&y) z`sj^A-POBRSr!MZ3Zaj!h>MGh7V9f$fBhrEZtJO@M!ot}ILE-i!0)-zr`6Mp4#oT^ z7p{F@eg50GZxdBBhq`)kmpRKWTzud+Z`qaUe?``Mllq(A)}+`hUAgk-@Nnbgr=(DK z5s4AnoAKPy=eH!d8kP;U#EM?9LD=p1=qvuQ`1;PVmc}vVht8DEmkV-RUY+r2tw`8D zS`G6|mB>#ixVN_I#L{@O3$?HV4`<7wzo9Pak#wOyqO57~5_v@}$Sg;C=JfWX%ER%O zlC@PI9nsxp<#=-5*kA`wP3cWBL?WjA zl4IM8N0pWAfWw>z)qZ*Y#5m{o;*a)qYgVV$43X(H->4ls`drSg+^VMGxRHyR>$5Q&W=ZO2gE+y_oh!EfGf_Ss~R|+G2N$$_%xt=2I-uqS>XVE?k zB6=iCmVTu94jX6D-%;6n$S(9I^4iI$Pk$ewZpHU1>|G9-2FsQgKuiP*>1Q4uHK zW0d`y8ZR%ei2J}^%}AAd!I#muZnak3S}@ep$dzZ2e_`|UNSvX2bI;}b`bjnQ;ZJ;4 zqX*kx|3E%{>QrZgr>W4H2~d{XiI z4^Mg@4KHa~Qg(Uu;ONIOi65NT_S5RTZPL1TBq+=qhuyhM8;u%%-{JhG2G{hC^4s9N zPO(wGeCIWC@w-#DUJf^)(w+E>yn4s{DjO{pGFa*(?es8L7Tx|Xt3H)vtos;A3o<%5ZvGrOS`rSj;5lHaed+MXxv zk>k1%_{%R#ukY1edF$4#zGs)s3VyYSZ8e68!1VGJrb{&>*gu0{@qA8k;^W-SFs2}$ zj9nPlka;FFHm2w$^@U}=e{~2BcfRH7bTI`|Yjsgd6A@uOKbC}H_u5;Pwn9OesW_f5 zbFa-76Sk`YDH*n}mdc)8t+Pt2<TEYeO{yJEJX9EGVB46!zVI5iufq|*)FO@_BiwlsNQ8loM&q`RRT9ko zVcCbDc)>E)2TH~=)ac2wrJdp)3+FE|Q0T28+bebcD4=M0_1W>6>faY=^p@ODw(A!@ z?+mB*H{nT^P1v1=8Bc@b9M_)es}Zui+{gC zGFoe?ZKW-qV)EgawGTILFi+mZ{+z}Kw|p1X`~G6fKv(6OQp4n5-ks>sjZGkybB-F+ zyAJX@yxO~Q=da6V&S>3XIkpX*dv>}9GtDA(?Z=)*w#+iQ-A7dpzGxlulq*0m3rd(CIdGFbe|Y!TCB=}lZqaPa|mx&3lq;D+t4Xi{1hEJlgJ8S zX9)bC7XJIylg1s<51o4gUf1YZ;LjS5m7K6e-LyWjF~hLmqAl#=Mx3E*nq>;Rb-{U=Os|ay<8dpO>ab^4!QPTbm zPXkss73<0sw6A)5^{0E!uifzKmhdzgr{{;pK5h5gaefcJAxApWV*bP754U;;DZb9d zqc5|@-QL5NJ4a*O({ZoIZd79v@}90tJtK)GbNLF5oi%eas}4gYHh4eq)!0p^n;t62 zdYm4jrygO3dS6U}VG8nsI&P;BnrpZ>bZZujxZdg{*;^D*dSX#(H&W62L`#1}ySJqo znLTTL+5WsnFb!uUZ7WqA{(8--A|3g(Ef=pIyr-BfEa$~rGrC8&tMUB$!1A|`UKV^* zY4=vadT8v&qXlEs7i^^Ii58I}ontl~@IlF1Jbe!r=2i4*d-9>tE-r4wt#AK^k^r%y z^d;r=i;3AB#gzdAw6&{>y*TmB;@%T_O6oKa+e(wDXWR_=c_uPHWf6tPFgcgzLHTK; zq@<*6Rr3F%?5)G1T)Xz+EgjM^bW2DK4ICcT1PF zba(eK-#vS8-{0Qv^Spn2$Kk<&gN)qQbzbK>*SXfZzy-uugq9$vKr=WxP+<7@64-x- z8m|r7zX5I=(p>N4Fl4cGE^tMrpGCRm!B|8M4`xLHz+J*G6s-MOT`7|AMpSz_!hsGr z)%Ie;;<&b%&AA@1VW;s8D#T5$xqu_BH0`5b@!fCM0ueuUuX2t-QP~xx$k|5;*F|;- z6NR{E*WlzZZEhRd?N5*5@VqE@gr|j^6!8P0i-Vg#3JzaHpFdh?cVN})YxNI~kKF5I zn?zpJvA=p3l;xwnq;vDY*1p0wOryl*jr@;#MvL|Cnu8-%YoE)ehhka|5WVyUU#?DR z$~3l56^#CD&UzVITac$jcfB~uVYaw@5lIq#Oe?OyNE!*FnIwjDskmO@nx z!4oA+iMH>M4%e%Ux{l|=Uq zX@|Q-vjp$gI^tOk^}cW*MZ?yVM9)i-7V|H(?HuXPOkKfSCn@JbzQ!Ud);=H)#ZtCO zzw0yJSCwDb;o~D8jVTHztCYq~e)+N3Cw(F2J!z-hp@gg@V&X zI~_Gj{4NJHR-9>5Jm!eY>(XeQ`)BT$?dNMU@lyyZ_j;mIFQzzLtrB=Qz3lOCrd2?*$2-$2 zHVpQKUO#?3H#aB#dL_)FT{)U60P}dg_e|%LdbrGZ(f3qcQvnX)u@Ww##qq@)mAL!5 z_hAgTH^9{k4_J=`e1q{poe}eXV&ggHW(paP_5M~F|B&-z%mC6P((QhW{MYK{-S6$F zYT4|SO&k_q7Yt*NO`i;_S9}QClQ-rJ%9F3BqC29Z9=-VJ(_%q2o{N7oV)LOf#z=~& zVLdvAH1v!4@r569DKu}i^c+t1lr4qp8~7^)cPR7xYsF8(jh)AW!ic+=Wvi{#9~y>s z)^ElAj_>dB&EmqJ*%9Av-Rmq$g{{67Tb@SD5R=|Yrj+OCoGROzmOdxf_VdBGE}mCh zSZPn(5V4^fXP65ZI&j^5N9>y#!4n+cv^(v;Nt^VDWaGF5)Ey@+v;{S$hHh8MM_8G5 ziZ|YtCXtWh-PzN#eDh*ormM7i-F6JDr__o3RSz%OYJM(B01XJ7dbN06JiQ2~MJ`?| z#amMB49*=roK~l1!EClEGHY-D4s+dJgs!N5>-S*Xib;ft~r8!Gxq`Y-iQZPyy)RMKObi-c4b=bM7> z)+5%wjxv>6y-dTb;>Uk~c z4K4KbcSYI80ojx1`?!~7_gZc<%exNknq<9=twQ$?w_}Kpza*9tyFoR zi*t?8FU%Nsb#&pGDStHnkl$0FX9a0ixSp)XPf<*3LAi99Bf~57oMQiwr=PnA*}I0s zS;9ph$GC3$(BJ;CLnl@;g=0VyN#^^lpqoHbXZloyqnv|6pKKuQs(Q8E_ZdB1jkoMY zmBX0ijroB~oWZrytdZ}9l5-zFZ+49I=BWBW&QG<3t|1qRA8n<$XC3V2#?)o< zRtMm8R`3&bV_Y#kJ#QeA95Pt^6|_#|0C5C8A!}g!J2B%W(b56#&Vjz&nQSx(F{^n@ zp`IzIBtTAqj>aU|3(E$ilgqr)4P~5P15)P5A0l<-upeXakfXBF851+hS(buz|4vS5 z&YNG;)|D(y#pz8r@yd~L9?+4`T@ejNQH^JIKN(ccc9M{K1$wj%$^_q+T*kzgNWC0O z4J;^T9%#oHS<*I5d^^v`!X`kxyqfWqF+U6P96jgS+;NS->c85!E^I1$6J=V@4DvMr7^abPt8uq_+Ety!N|nU%Ef&lTQS5JM#|kA9cMN`9#%S5J(-GlT77vL zOE~%32W+2kr1EX#PW3S-mCgh>F%6><3FUm=(pbVFDui=rTgJw)q2IvFAVVZ~K4s~; z-2#1G{1fAIQF_uW%Upenm%CqUlNfk;aF`lO^BuzLtJ zv-L@Ls?sFLn;cEK#2#bz&x8zf`*i>+#OlM?IymLK zX+lcc^N)xM#ud8cdnQ;9unoy}Xhns>cCLD_BUKXRoDL^`pg(;E7Nto3P>pl8FXfF> zO07;VfXx6eF}}@cYD=mneywqfIA75n5mQs@%fTvbScEtRLaE(9w-6&ZdcYZ2IT}B& zj$H80EZ<@uilZdN1`3Q4yW+JPK(-%?!E!(eKEx`XLs0sqA(4+8DGk6!$)`xxn1+^n zk}8A{>bypQaAq==1o8})0nMn)U3|44?kJP(?oq#Yl^10>C80N5 zsWzmLi%VsZZY2NdyRv>>tF@aFLv)j?wDXd)gT-=t`oWF;Ek=xcRW82fRzh=z00D39 za>Ek8AYqtsHDq};0LGz0wf)jb1pmi*dW>U^>7!ZdQxA&}#TmAbG7oyy(E1IT+ zRat_s<75~*n+O7Zk0+F%l>aN`OawChVp7}Gznng%J5W;o{vvQ$F@8%Wu`Z0KFT0|6 z{11jllKgJJSSE5)38ouM&0guwHuP~%I_yT zUcAilg$qwvpcf)pNb4>qRszDH96gp0| znRK9;@I**?0SNBq$3rRFOZhUjp|j$yZ;tGJl38O4XY5Cq`lf1WbYY2YfSg^}B26(c zkj(q|y4Yo9n-*JBOqyb$=NA+C)-yHdoxc;%_ALmpJcKzLgoZ5Fx#h2XabOTOSB$7t zvYw<=x?uMq*St%da;6ln*<=V)DmiyL`ZBA2xL@(TQ-i|-y)`srdjZIK1n|xX+^kN2 z_``(8)$WvWvN-q+i2giaS`m={Kp%Ouf}v6WXd`Hpm{@+7=;6eNsWByz>`RH4_m|=W zJG9Q;#l#9JP{MfbW_uq#gR$-HCD)x2)x>R{`^xlQErs8+aF3tF&?--m!QzWnx3}S& z1RbZ^ZV#6erx=)8C4HSd*s-1yThj-@T!ByxY3;~e)>!y3EUL7 zr^`5fhc;$6(fwPpN>zr0m3E2W$`WfDni{p^yT+$swXU%#^}`AV2C;~Gu1c>%i4(>$ z5h!wF3Z@desBvHOZCYuKR8ol^BuyP!>U2fo5NmzQuz3!9TH|J^jSUmfDsge2I8wxB zUm(=0@1*TlI6FgFX^55}3-8fW|!1@_wrdY-r~A7)LUWHkdG`PMkA z&n&91e_!CV;Jg0a$aWnvMRvPUmiF$a33Lh}(04#8HqJPDGsC$~n<;+)*$l9yZvTED zokcXDAZyj;!e5K6SP4C5DeHo9*qr23JlLm=kQ1JtMB;Oe6^m^d)s)_Y3^UXSDE09! zA%srSp169rmENB;gPPNBMQ`z?QA{BS(mq9aAn`c(khHr$7(#0H_m;6=wLO{K@3Pp< z|80I`cAJ9BCcCPVBPMJ-7|;avVV|w2G9_6=jW31yz+(ElG$KSYJQ>cqCG$?>wwDQn zhivbzVQ1a*L~v=j5No(x-{qR7j=*=`OkWELj)*Jd>;(}ZkM*3HNR=dUl`dY^9x{J) z<#J>^bVw*6pe^k)DBP1F`QH01Hch^4pB)E-`7Y>C-MX+TLaU(l+6M9s*N@-{&WkxH z-kHcxjyGP)ye*B}FxM4c!R9b-TSI)wf@i8EK3tWVav!4OVo1qXZ-U(-Cc`yzew>^7 zpGPPhOncpNX3m0a$6|WzqVlVg!|34h1&} z)HwNFfcWf$ol-sKCDU#PMpcHq*HpRQ3sV>rY*u~Yb!%Y<+;@1QUNl)5 z#-CU3&AE3SWiYqQItfbopizDd6V)`84$b~WOI25-TCK5Iqb5lWn@2DPmThO1tENFBxCxEY2Bs;eM?rH!@ZRraqvuU}lAe_%>Ti=KK z@N_)!*k{>^zijxh4{nmBbD)atS&X2`H#760CAZzqI}+~XpNmamm)sOc+$Z<6kG0q) zu#fKPwA_L-LYhAxavW_^J2b%~1utdZcXhnga(s5RydYW-2z_U3Y-IyVOTMeQMSL8T z3~onGtltFlY>v=EAMM<|mM?)n)De9~HH5e4>|9;tS~aV6&w@l#wWi#hoSz0nB8L%=~TanKuSEuFh8ymi3=nFO!wOz+gaiV>hJn)aZx(67C;M;e6R) zQN$JsL3X7{<}#X}c8-L!d???rpEd_mZ@V40m?Z4}(oZ!SxmFS8Vcf*V|I^O#9{_BH z;$yotUeoj(UL0!48h%rXGQ#bD&I15+a z;{&Z;mGR;5rYew(d}@9Df~geq`cuj-FXm0f;}^3G=TS=r=gU1EZ&zPf?KBzJUa{9; z^JP-Kc>U0!z(BQez5WLIsNsFJ&=#V#geBvL@*`PRjQ4HygCdpT;4Itsts;+=Z+%pw zM^st;W*6TNt$F{u*dR^_lo{whgQ;=ci$y7 zRKH;W63Jk3ldv%*(Mx5xA>}>1VY|d^MzyLSbD14oap!?wlpXzPEnbJ(Rc~+zh}yhP z4YPe(mQ+_0>Ewf^PLs67UH8ZxDRzv?P>Nv5Fpk2=@i8&fXn(oqsn6EhR>_rV_Oq$`SC;<6nA({; zzyc8(UFY&R$ClimXtS1BCPA7a;)1?h(tUAVlP9A?>j!{Nv2Fy>GW5x~J7dhZ#IFxp zK}#29t!_d08mZ5eWPrGTLvP>R=(vQuSNqd3@Vyj^7?*Ylqmj$;U-?5ADu3AGsRdkN zb1}4N&Yl?DCvPAN44BuRv@(u3T52V5whfY3nDroEGoxXO7mN*NB^5Si?Yha%nrY+H z5gLUq;`;`&cQE=RjZ5^twkN{QBig#f7c$J}d(lCfPfLoQ!AndK#HzSnk{kK3;K?KcyXz7nd&``XveU)KS}hKI$C%>;hpB!v1(y=bjkN@BDIyfW6WH&ks2jU zj)UyNbTdW~2#%_4Mh9EKG{GtY9Fio1eGRqC#(>G|K{qALYb*gD#4FvB?7<7pGvJ7^ zC{+RCkhXpQgW%42x)7xdqEyzc#nZ%yP0MX(FTeby@^NY~4jxLr(=|RL`2RrXCp1L@Zuguvh!n(~z+pvJSdzb2EVo$4OkATscz7R&I{4 zu~%VV;#M*sG9r%~$PTX;5J?_S@IwOr*+wFc4L~F#2TpzOZ?>9Ll?^*U80rReM>}$| zur?4wBbHX~#oGx`jn)RM7U2{H~Fx z5a3b}E8uBc0fmI6gNu8^=?%!0xV~pDoB&SbsrWFKNem*JeGxgnzW$xD2w0^SmY6a7G%k5EG(p`$kP&oEb9c%uY}H_yc}oTe3LOQO@Ji; zD;%Y0a&dAK>ICcrejs%L@P2(}<#3-YU!ZT@Rfuz1d7b z(6ikgfg`T_*^~DtK@%8D$GqYzBzWuHu+a&=o-@FIztqrh|5E|70b7`u+gk~k@nh^v zg6sG%8ZSs#pv>b$N(p(K)I-IV##aqVHN8H$vp$A2khC#+v9<3C zw&Cf@@Al5+V|iV%-rss@Hl7K71{XO-H&VR-6LC#efgV*ZM`8qtOHm2Pgp5s9uPDFD z37d}%pP!=QH~lB&aG(tN_}9X1zx~S@+}CgsEV2pS2px38o+2=vD8)`_<6V^_tb5vQ z>)7Jb%z|pAoXENA$iYz0SeBojKWWUByX1~eSwVvzpA9N+80HADS8h5Kf-&Nk(lc1s zm&%FMsLbY}XH;lcRqfRuqz;|Fb>H0ukQK7i?$8JiO3g#F`c>sJpZ%+XvE(5u1 zrFV>JErgWeZ+HbH4vZ|}VNqP`pHw0uzjZK2|NKk;#iE(H-*HNx(=Sv+^JL<`9Go8l z!gyJpFxS&8m2cLZ8Aw0X%s!onWFG7&xBo) zliK4YebRg)0I$aCG-OpK$vu|~zx0Q!qbRXbUmiqwIFPR~wpr43kQp~$^N_EcWXiHb7DO?x=}0|+%3>q^i&T-seLutkDP@Y> zx?I;|oIO+C)Y61)O_t-Teb6Cba^jpPa+2?G%OyHV;NOv6WOtTAUi(@syc9mRUn0()ocUzciRHAgwRImeljZt# zoH3($`w`$1oU`9C%YNO6oH7BzWrp{(Zc<8VFqL$jCVSZ3jz_($X(NNBl(WK-N!l3K0vV%UUzzmn365D%s0Bi`wfkV)XHIeJ zJo`cnK(|7ipHWW<@-IWaICAl-*pInDGsL#?uBIaib}H6bbD)b#CqU00w2_-!VxHk6 z#l8-aj^q84l^69zBK7#Ujc=Hht>kyWqO1vs1y+MW%9h5-SlxVgUSphE>k6e7Uq{x& zE>sa!Rt1GjZJS|TQrA~#dI$2>eKF+gDtISwrl(^)q(TAesv$EFLpUJpw2p~ODH}NEXcc>Y%5Bap7CpSSg zBKZb(MU5lUzd!54yk=2*b3T=Wa^itJL*-BsQ=rfdlmLFFj;9e^BAjRQDkZ?os*3UZ zD^cGYDB-N}uc6wQ7#e)>?En4R}&ba+<%!EyvM%Zue4wjy@K z>tlDuNR9=vyrXg7fuscmk9wrDeen(Z+PRlEuRBD z7hh(L1+wj|JRJlolV6yr?R#F4>Y=fyT?g)NGl>%Z@`W&xxUei_Nap$MM`(!2`-3|x zvw%9t{2K_7fzh+~npl?(lRPyqRLIo=fyT%$+~svJ@3pz?Uk7K8Ukv~B)CpZm>gQf9 zHOX099F^}7xi<--rEjF3P;nl|Gp)zwdauOpDG1tuXcwhOaU~Y>6GmP4+fS_Q zALNnO!zzKgbny1MOAcVHmo;`*g9Z1~K!@!|dU~b5djalftMq9D%{1cto~5%^R-DBw zrk2CeGNl&t)(@IwaJ=to##nWykAqh6$d&p>Zu7NA%$(Wz$&E0smy8crhz~JH6ae40 zXkUJu6;-XICkFblu`?7wkD4Fh;t1S|Vp!7dS&A_%-IY&IP;71cWX`{McS`;l;8$@A zvCPWL$8{-&F$#Zwkg4n2L~LG?`e$mSXst)QdgYQqY}k5~gH5)@g?Wv8ulqP7MfN#l ziCsQ}S}xE+6W5DtuJ{kei#BZUI7zwPL#uyk5K^r~0KQ+BJ_-E&>JWFpWZ8~`KwYD$ z!KlkF3Gq~+((`S&;b~{p_f)$eX%I zB^hNY*%XL{ZeHZ|QIACZ;b>}rJ0vTf&x#uOU-QC!Rl+3H9D zbC{~l0|$9|sXWxF^==d*J9q~wS_&3oEpga+8K;bQuCxX{oIx-0bb?3yJ6Mse?KJUq{mu*2eDUVGCH#L9{mHK&NU2-H#ZWLer8fJ-{&<0fEuV}`%*Z% zAKh$p+j5fP535}aRVtRh1wP85_7?&uWS;tMhCsZ3B@SIHE7!<;#Pwu=xzmGnra3Dm z!P#8%dAT<_v@d{QWh|4+*g$Bvwj)S`v-cE}sP>t_?S8`%zu=jf^9|Db@}~OIf%YHS z$BO(b<4$*uuxAKjp;mM_D|(}{^)sb6r}Q6{{7=owzbOmt>E;3#32q`STCB@ zgC3q}j7*pViz(%nTD-SFXbI_#ERMs>i&GY<6aM#Upv0xCV>a_WUL$axZ6E;p6|DMW zxeRsx(J#NUjxNL4f!SK`!98SQtGWDLz9HhLKvtKzsm#Gu_(TlQ?2YK#wlS4CzDk)G ztoL0z6)J}JgJU7k=52Hn6GrmEwOITuK4AU?x*Z!Qz)3oU8!!QZ<>9=SF>+-rK2YY! ze3+RwwHUtLSF#VGPYWXfo=@_Id#< zzaNeOgyZY$TkW}(%>b(|C zlDHnS7mTa2-5{j{_LqXX=>VTn^a(G0#JCN8c0tQbNRuJmdf%U1dC?bedqPJ~-v3Pt zC~4cAg(K;6LEI5Rp^z$U=epD$Zd-aNe(CCSfM~f4IA)b$ytuTjmQ5COVKA()4G1Bi zU1|u}Sp)J_X70)#D0yfw<&)n=G{n8(q`S&Kh-k#8T zKPD0-ttuw2E;GcGvd5z>* zC(7@N<{$5!wx@i*{{W2ids@u47kOpqLbU+~tdozN^=@dIjuJ^6Q%SO<)!9HAd3X!z zHlOdDqWK5W{Z(7|{c$p&xx#LA=!*_Vp-~l~neSyDy`dG^-$MK^IsVtjkCLdA+D09p z&HpWqSi}j@0!g@Sg6tE>A|9$+g&ta)_raXeWu66zJui1dxq7AJza_jTT=vJiv?pT}Qm(n$)w>FVoH- z?aynq=D|Uti6WDCO-(YMJCj*6;v0XujsNBacM^cnYp&9UzpBfI9VfA<-r@{P!zyuC z0zrH_CB?f>MpC@K;-1}ExrK1fzJouOKgSwt&1pW07y@L3naL>nBBmg>g_>rR^`tapg<_^>tH3uMmfsYvQK;hD^gG6qW=}FelIfcV~JyIjy;+3F_(#b^^Pb=8%lu zvh@sz@8?~G8J4%TSstU6BkSANuTQ;^wKz_DF4o*5o@MvmEbF#c@MZW8DK8Qs-huIgl6o8T3SG%|AAWW8ruGUm0v%fv+qd*{Qei>lk(h;O_O%lpix%oMXE0acxhZc;CI{f;d|-h@n;F`>mAkY@i5+#zetaqP~vT#JN^Y{B67EDvTE2|?8Omrs6D>2d>*ohao#bNt2U^s?tYW`U=pfTcZj zmNuG``RYmGl-=o9UEp_J6c68Qi8yF|l)VGnQ_mE}1?F<%x{g-*VKNiNV&e{f56mHp zjfxqRqiGWLnTPps#mNIW_JgkD&~DG=ecg81F%TgW8c51wsSbzGCG!~b_F3MtU9TWU zJmx&9R4dy5a;*P4+{7Gc!04BvtgLKBt^4|b((zjV@)#EPe*v?s1#qZjO1npk6iA5W z5s#`P)%pe)ihU{My_p-ua1Njg%)uA?X2<*w*iFx61*%veVAK0$}!3rwH_3ud7;YOSQt#4oT{~{ z57a0f=S$nZ&b-4SY(IJ#M}5}&ffrVDyiN=BK^KS4eTo@SWFjZ2jszWTK8%xz^P@F& zU+Y6;y2fWiW*#%-w$)!hf@hY#`9_ z184G)oSMSr>C{NkMG`YSco<=Oh%ey#1kyredQ`Q@K`S{Qek2u3`KUVzgD%xSH4vd! zY?=iO0OH`|$E!O`6h#fo+~!lw2sutFB@i-=qYy1gB9LJzkxnsvDr`~rHd1AUpdh}_=q+$aHS9lFwOJL2yM$PzB>~OKvu#$!As4%S_qZie?}cR-w4e*kx3X}5oPP7B;| zz%AjmWBVFhxpOs9Y@(3ZlNfbs)1Mi21oySS0jgZz&V&&x0T*OAooXpjNQ}${9EN3n zhUL5ROY^Z$2D&l9k&1VGqIe_@lb!#rh5v&}|Jsg?aR2YXj0{!sOEb-eM`nKwy#Bx4 zZGHgc3H#}YfqW-6Cc#Zu|3Ps5vBvvjPcL9~?0QFP(4 zvFB*Ur7z_8OP*s9(FDCzOX_KJc6Jtb+aiC@u3=vYjDu>p2xTgw)iN`c?J;&)(m^>E zK=QtEdGm3PiB>+eLW!y+p6W;bU-)Dq!EOIwGQU7mzQbX`F)aKaJ1koW#EcjU67JYP zTyX~laFg=%=i}6J#pkaxWM!V_!il)(9#{dRdl95sMkV0DOS>D$jiCD{fg*djUoYz#06pwBN*!g8A6p{jBUi#xyqN3Jc`nk$*72AP#-)70H%uD%dw5&e4VNy-SZ;T zh6sDzuT(K&wnKlkDMyAqg#%MXdnVHycTRDQJMq(-E$O<*E?L`eSROWI_HwAgv^jAO z)Bdj~^v585{LyoFTAwVG<3_O8SN_ql&%g4PKZnfjp*%u1lge*z(TEP8Mx1ag;~F}ydF|3V>M+}F5vqFxCf7#-7e(`%DgU~XRkfsOg6?SVPSHzzw^!gl?T z2oTHY?YEB~Id}EGK6`{W$^HCmZkWk;S^_-0_nKtH^3c)3tJWCnfPf7dbAR0=c_sK* zaf})WOtZZ+U5-sHXchMA$?x&H-L%dq0ow!f?`^qKKx(YWP8?9Be0VD@*-SaxWuho8 zqNJ&01vFBeDRurw|KR_7#*##T)sT20n*njSG~~b>m~LbnI5mj-k5dZNGElWL!(2NR zFASF8tE88nP!-Nw)vmtF=%KhsIX#S^Sd*}NrOPs9f=F5!Qwn6USyOcFcZcPvavSBh zX3$d#Un*&1lIstGyR>)n9w*{4l5>6po}C6tLyA@^(DF2#x4cojOW3{fVt#rp3M`GJ zLn6-M!lN~6pvyME`C6F8$Yez`awYOxY`hts@z|W`2D&6`7FK8Je{B5kBltUhJF*Pb zd%O3+W#%D!HgIT&-|Z##`Tl%TaX5yuQKe%`Jcs5A@{7*r&O~m#6_@|rW{Fy+AyPnl zejlSfQ6j@QTV}>uqN`-pC%c{8QhZgNg*TEzDVQxP*h>4z@vkw{NmcWq<^cUh#}vuy z8H~Fp16tA-3+O4j zP0uz*p0`0yHb|zc971(CG-=qLPM&(jtUoE)(nuFx>UhX)IcpHDXk$AuSU$XR{OeSlLn`}J+l844Un4h0Fvz`TY zDGG!gbEqf(amX5U-B-q_*IM}R89r1D|Huxk$Io01qf`!lLgWjkTP3PF+c`Zo!nGjK z{Z^1j+#Qiv?IeLAJ5pCRG#CinS(2sjQWY3Fne;ngnw_0}hVO>D7vN_Oc57>E_9QvA zO)4f93&41u=l3`{apE~N-fL1qu1>!En$g_B3f7VVrbx%W7>OzCQGyNG#K1Vijaj)z zXPsLzx3V92hLs9_le|X~uUT|V1o@*KS35Z1;I?59F2#}W!S3F?J=AK;RIVLIugP)KS(wm^BS1%9;2updD*kkV=xR3LM@$f$ehTnP0dT)e% zB^9xJj#(IRjS3-dE8TJE2IbaDm5x&ji;FMB&VljyknM?L){9#x26orY7^ybu#~$$n zGSFCN1+2QuxSnzJ9Gq#!N5;vsMy!eKne;?mN4tqBi5>2+(5+M%g6Yma>8@7X8%jXS3_q4j1< zCFg2%st7>=`N;VGm`rxL!2+(h{hGJwTQg6?m!~N04D7cwwe6YI9dv-q6!DEEGtPj!7miL*p>SVZ9VUK0HTt8(;AvcP!U$ z?a95+w7zV!JJR`g&B%kKZ^k8z1wMGo<@tb3YTqb%v(l6kFYL$6R5?E?mgdtVbYC0L z9aC^{FE6O0H8x54sjq$UoCXxLj_??uv#N|WFiR(8V2B2U8|1)QM`5)mQNVj^tld@D zUG#xi!RWmKaj^o0vxdY+WbEc6LE&GM33xMT2kn!ZN2l){j0=6aFS=~mju>anMLOe3 zo@d4k+PQtLgKU!edNXo7#Vtta0^79GEKHS>62mqvB+EI~WczCjrc^6_NvvD1UaRor zgZQ+xycImlhJc$7PB!NUpL{E&mLgd=$A7cM>*3>(un!u`dRa$dYBW8-CvEeJfLpr4 zvA9=+XJ)G7RK20EU(6YEakW5Cu+TB3oXPGzn;U^P*=eoken`=;I)_$}if5pExkN*6 z4X~-kZBH{xOPWP^Jj8)5SbcEJpyl1!iUw?nxV!W7Ora(-t<2IIOn`)J_V_7J%WN$P zF191*Ad|=Vl1^HNAm~$cYHgyFg9jt5Qaed^j6f{~3v3{#Xa0AasX7N!(Tldgq=q)fLZo(``2fM22^66g@FHQ=GVco z+FP)k+xgAa`T6H}>2A)?LwDYChnLzO_YA5;oWXzc;T~3fh)~;5%iS->;2LMBDljsx zDCK@q5alLk0z8b{yB0AO(wx6aW5y@|WD(Y%iSxIw^0sTOFTH<;-)jXJ! zG4YJYl|U^+dhr||K(f@wqsU7{pv0da(ovtKYkUKwjI?`bX?~Itty(i2s;wAtYPR~g zc=J~E%_iXy0`UiI%d=hOV7#LEjaM{GbnE1!5Z`pz&L&EmcEvENbvHIP>YsKo9#xUv z<8v=3-l?mOVAP8^-<`z;;;3@Xt5vPr@qHH@1rpuTC8diXn$f z`t?E79t1<;Vl&?UhIRwgz`k}jR=rQg-(uxD@*DX0|-WYu4oEqnrgg+dbW1sfjJg3%A$_{wpjnGmX3={p-JP+|+cu~9s85uDvM=TuONBbd`sTdLUIo4;HD<#}$mac?T z%^xP(b0ku+R|pe@fp}X>7=8KW`SkON*9OwCU0kkR+Dq-6J?|JVWDhWvSab*`37A+h6dEQ84yYgOTQ>eDU; zz9|eNH4ZrU$5p2Kj8!2h*7d`HUTt63C&^sZZQfhih+ z=&Aq2BlfSFsFDL$TsE~%b=9@3VvcyBw#Fk%1JueA+Wg6(0CFRPF^gV&X-ffMIhb

hH`wmj{h?=-bX$@@7gy?N7dW!zedqis8SYKi%J@r~TZNvdKvMnMG@-%dIuxc>Gc;WY&2LsXD zg)9I|K8(cQ>Jj>cc@31^=B4TAzfd$3z1aLl1abQEB*qPeF%+?to32>{Rwg5Uw0QuE z@w)#{#xuOx)62;JS=9>si!~HHJJ%=yCmmkXra#u39red;$y*W0t=pQl$vSCYl9We& zqmLlF5;ns!rs`itos28AL(7H0)2Pd#zB`P!@6J?3l{D1X6HnGZF#PTuMb7nfGLP&; zSS$@|hbItG=e2J!(jIn|0N6>c&|v=-@pz{B zJn{Ko3k0 zN;>f6a}Op{?x3bgu3cZ}K0m1q$*YoH_?{;r)rsPIcLFuF25Sy4VCcYvbl#u z9;km%_ZIi8h#d-&^?cotl?EX7$@!mW7wE+k0tiwfGMK`*>7%5>9QysicA^y^M$Aev4@1-wfVmJoHlD zo{8yAY)kl}!z}7rqIeJB<_wa>9rtpYgzt?X84UU0*Y zQ)vHAB8u^V$Rz|o_5musQl}XK zb&WqMjtC}tuHq9M+qo*-HVdc)$lyHszIWXs>Fxa|zK0g~pCpqShr>kwpQg%I*jBp!C9g>MT9VOSt;j-ym-90!udBzY;&&%Hiv<`I+ zk^hf|_;1V)XpY~(v~M4jVB_c<0Mvt09!4r@fTyc#7xpwY4hlVSH4Z$X417vgbH`q7 zyQZr3K1&_X>RqRdQ(&T^Ik1Uv2cQ1hEz4BcdXZnwlRNR#Hpq+rhkBNts zgGy--*78jZzWkXWUQ>=k27UlCMTMVhrq-B5T>m7Yfd5TG8h%X+vLC$x5&~4&|8Eld zPuW!m*l>T4@cGxJ)pe+jNtouFGZ)U+b43uj08_3}v|?6RGr+A_%EvKX%Y$7$!^+=o zqnvzd-h6KUwaI&!?Q?sMxLG4`UB0uhhGumdE-g(VnQ1>P4H=xloN$*DZIEg27;BxU zbicWObNkJxK=etbWZcHFp5wC7epm5ab<5>MWHXSflr9d+lp>q&ND`FRXRZI-o>*F@ z*xUOcW9Dtl=ySB%8#*X`eHV_2@licR@Dg3W6Qed}wrPzCX zKKBkA0xbkea$gg<1?*beZQ%ii4DhUb?u*(Pq&NuSrmcxVv}c{7U&8wpv3yW95ueQaG*9STRy^qN}5RZE&u+I$V zh0L_pZyb@AQ$BJg+s9^Ul}^K-{bWw{TI>Xd0donyVe;_-_6ZB#Pr7P|gkq^OaA5Q^ zvbAViI*x@S#Lbd>E+@Eaj2#@^k+aMTkJ!H67t~t zgZla(IiJxF0Oj!i2)sbm3#FawaL-tQ?fOYOvADK{*W@^rqm;dN_%-pq3fT@eHg+3u zADpzbbhRJSR~QMAy!BBBInA9H)83T5gk>QUrS`V=2&?dg4(@+;dBzy1@W=cof6e;~ zx2+rd!kE#Y^}UR(e`5riZCBSGJA)7u_0B39M5|{UrMTj^qQ_h!j;zfZ4X0~+5?P;qn((_PK7IAU% z^>`fMjwkbfCPhkFD1pU^ryD8+M8?0Qe=sHxwq4gy{DP{UIy$#F2SQVrx6gRF@_SOb z+$&VaBu$59m{QG=i*2Et&kLzWav!}T<9MR@*XeydtlWS5U7~SszGM3)B_N(GyD6SQ z8a=`Tdn6a*$xY#gTXFbquGYN6wLwls&;hX1@t-wTFLW;uX;N=J>wQn}53d)uXUZg2 zGEy=O04LYKLB_8SG)5+f#L-KXM9#f4zsP-5kg^?m5$UIZMfdg`eo5OtHRGaH#c-=% z^_*-X>5!T+#P`_|!gBC@J(SV6d)qR2pU4mcOPOqE`=w9Vb)7oq@zM)84UV1u8A3R( z^Ym2Z*Mb|EZD7I%II08Ee)p-HfKxhp@pJjcq(WbS?tyRQHV6;6`J>*Kfashpyw*3b z>yUc>yy-Hq_Wg1EhPsX8{A)R>Mug=pme!TeiNw_QBs2V5f?bE7$ zQrlNj`~>trL05HSA3p=R8936ZNps_AgwS%%YC&%m31nZ|wSm*KZ zd~~}ha1ibdo8N)L!VF;EE=!G*x0og|_=CJprTb`ZR!Mk0uI^R+LdU%0vg8g~QqlR( zdOvhVz-sUEZ92*78XTAUgl1E^@KvTs$MQPW+~|{8NFF}USQUKy-oS?h&H0-V|H5~Z z`8=?Jz7)29ygEOk5Ij;J8HmM7v$?Bi|C4QgMfNu}^vv(tv%JIL()RTzt7c6<{%u?w zb%zb(SEb)=GN;0n*C@(Cg}+?*y9&P`GstBWe{7c-N1JC=`_(XMiR&HPIX&e6VuJfq zJ&oOu2A1w?r!gvgsxexEB||S?{WBBGuXE@AWcE2JJjoseqa)pq$Ekd(k1o8GO6z6Z zCNan(IKC`5aPf`G=HY{}mXvpYYFUlt@;G?4S1+U;UtzuaRHW_@$v}TT+VuCfZ8aem zXUh+^D7^8}O_bk9IJQzJZ~Eh{r*@CFW0>CubMUhP;mhi=G?^;FJ+}KFn%)-L=df&IF34(A(Ouh4 zs?lioTDrUk_Lo;sUs`t}7x||-Xi|3MOt5@0e+Fk3yOYl>9#o{FGu=*7Tk$9tZ!s0F zJHJ=!{XfrQ`>}9l9!rC_Ou*vv{#D#)b3${n3P;Ybj{M(esD3XLCi8|Dx9_B?z;fNh z8n*iaQ?4jux({7weeT9R@}6Z4m%a%Hi`^3ZRFUv_%g-mtF+tdIDK+!+Op3J|PqxWx=E`5#oSzR=*FfmL7p1$z=DzRrId~OIE{2B@AJCOEl)E1UyrN+5 z3RHQ*@{uw3?cIMykRS3vo}9^tCtUkQol=|>*CjxZn>sHa{HL<;ht`072=Rt>4`?v# z8*$7HX~UNM-`?x&Q?F;=NnT&R348C^xOi{f4vTkT_uCct39rytDYpl*U2#?^Q%|-E z&V-vvjc>*TXd+BRix9JkB)(OXqOg0t z&=-mxokku{zbM~!;TZB}^JX#-K~S_#uA$NBx!JrE>WRKtSy>mK@EM9yZQuSC^tR`x zO(};PWB83NpLtsz;CdJeyRDfPvWHhd!h--^3dyd!!HhOBJOA@JgRot1%x3#taq`I? zi{sR@Qa`$=e;4535ZWl1MLj$h_aa`vNd67UM_e-i%M~VfB2le|=@D7E^A!Yp^x~!W zUR-U=sGvhsYjE22)=-RgR$a-L<%TG+C|X9d%|n9&kDlJC-As!*$%MP;buZKF>a%NJ z-KYO$cf(J$x{qy?+IR@I!YdIauJ~R5uZPQ`RyJX`JI?NXyJ(1#=aAsj6Lvw{$cqx& zO+(XMetcV81s7>MJv+9xR*q!zA=|#;@~cQuXX{PbmMj^fC@+QWP4kE&PldY8 zjY(NJ!D(BI&!=1a9Pv>v8e46Q1Re3`8|Nfl&pI|PuRlIx6_S>kea5XtD(aB$7D^h< zzkazBj0Fv>E#F34I1Zqs&XUAV3MvNaEq{JNJ1}!*b4<$}KhR+BSCE?TGw1bPd+ZD` zUSFIekYe+r@pRQkvx5(if4FqZ9+3>k65Sy2QvZ&3JZW4!5qV8IJOA-}IeoFzl=hXx z0#VoLNp{p|T;N%+6^F3D{APFt8czyJf+_0W(@rYa(IRWBkaOc4D$G6!w?{pZ^G-WN z<;V|uPnYwyi4;&#Irtl!? z$xZR0?%!sJ(_uG^L78~fWs?UkDKDP6OU6i)C>4iw%-`C-IZd1vXm7&O3Co68)ABr% z^E@)}-KP;)oM>uf{*?(QkwFB1)+xQzgB19PUAupu*`ISc^)3ddick~yeQgtk5KJiz= zdA{o7O>zEkHOGO1`Led^DpR&#iKXY0*B*gmp_Xl4Y`W;HdaLq6W1&^EEL@<_0((E4 zd<<$OJJWCLT>3UF;g~*S3ez0Yv|a*wt-rOqECsWep1JUA4He}{f5ZB~1p(%`*3Gwm z8X>JuOkZBK#4>wF%-KBPp)NBPz4*5=A^(+z9vv)2(s9Lk7e*?=!NOyq^H zt&b)Wvimz96G2fmXHM-}J$vx?rFg^+X5l_z<>>uxRA#?*N=d z?fP^yl9hK76R*9Hk@cU}(k+)pQ@#|kd1hBSRq!N3FmB??Xf@7bf_HJUyOnwYs+ei~ zbQ&h}b`}Mq;Ku;|T04KlkNb`Il!g>oIjOtc3RVeFNOwPc%KP>PY1SO|S! zzKwQgNpH_VA?tljSklK(?(kzu2a~RZ9BQzmHI#d`{ek(r2qO>qMu}yEeSvU0MoHSd ziumlsuI)=uIAB_nRZiOW}?)U%-CQG?t8bh3H+!@y3HK*58+)l~ z8{7(*$dK{h_VT==MOZX5pFxUsds=a=&)OJw`AijJZMqciG}^@Vy)g!d9KyFI2NQZa z=Z5Ps>Pc6}9tjVqMxL|HGkv!Wyg2%xQ?}gS%e}BRk!3UY?c*AFbqwxRUcA3&yd^29 zr@(fCezBH2yV7g*cKKZ0NjqE5rO8_({%KknvJe~rVXN)%|1P*x3D+${LG4Y3aifK}4k2~Aa^YXjr?D|sriXBTkgZgi9Dm*)7N|?u1|60l94K)qRAe3;D^Ug#} zhD2Hdhj`@M?{%?bY3X!zR@jW5ys%U06gzeab>{f;+b8m*_|t9w zuP~BpYcU>ZY=fM^PPrazRYaY z_(CxG6ssg8&PNd#Y@cc2b0#8R^y$Jjf1sRgmF9wuJBZ*aiL%d@u#5qySv+D7i?59QwNn7T$?+VqZZ%V=M5 z?k-l5LBBbszQV>~OFow&U*r^QiSo%WTLp8OI=@=<_IMprd_KtMk&WQ8ZcB-K|A+-+ zP<(qjeur2zyoMTKX)64T`PH55;$4PqCWNk+pKJ6Muod=f1r~_OUh#SlC_E2>W01ua zE=Ky#>Ag51g>g)a!{@7dO1zNKOL8(LmehTf-*9?Bp5PfA^`Y%cx#pja5u!IYGNgRF zCRtuBlMQ24{o=)ZJH?8Wbk=`{tSj-9;Nx!PE$sWEWyv*P>^O3F>Z%!CiN2fnWY?SV z&a4=_idBn^zQA2#oD)zn!WJ}ainMbw47U3RXF+2gAf7L4=3>=J417;U-K6w+97 zOo>Smbz{bZ()=$qL8WQ4DpJHeOa;rj~vCB(ElF?wh3VT~>rBdp?)~l~QES9yoS~3A;$3e5m=@&vPPEDrD#jN=I@eni_=|(K zACj^l^t*k1q((XYrkvpvjlHRhqkgGN#zq5$)(u?M8k0w%NqJUUrD2{)`;4stCeNN% zvNq#F;4VNmd8H{;(_2jAylgCN23+3UF=Q|q`H&7vT>+AQJ6s;cf3RygBSAGzHZ!Nf z&}-1~q+VW1FK)WP#Pw<{*YCM}g_fa~8%6T)b2K=`_AcP3*0c|Mut zT+7Bf$@FVw$ZPoS+~fhbuRA*(712Z_Mr-V)O{N;C?S_o&AL=Rb+Q#1bm@<1)ADg3B z!RRm-iGc5f@~_X3La*TF7>-E5SGtBTOl8vGD+qRBc2lz3an$s0kX_5vOBp#NOjgA~ zb5!Zcw-LrZW7Dipglsypi7!m9{f1DFSi%r~TpbOxnsUsO%U|@jOc2(fQ0j1wUR0^w z{2cAxY+(e9&9rD-l~2{FZWeNEq@xUU)?++tTsdJS9Wfu9+0@I!(Ih#x|!uIHZ;AH@!j^T5M3*|VxHJQ8$nKVpLuyIR9 zqCNRazI}cnSbB8=u3oce?8}JvS+EGl!?wo&A6aU9(=H^E(IjVH1a3XUE)ifXkg4iN zZM$9{L8h6$8|f=ghD^e=Y2fdH~vTB-h^> zuM0#q^R5|5SyyuVk7$V2Baz`P=Ftl(KPm`XGLUt+;6aA*Pha{nyAIZ+Xact9iBpt+ z6twuq&-?8sYhh)Z0BpKU6gsRtJ*rUEap-kyY1UJZeCu`t>Sag;1~*z?w*$6o%QO@- zuBQF+F%>Vr)sYzJuz*l$u0ri8W%)^<;SO& zfGSXh-Y;|J%hkf!_FE@=3snGEbpT_K??dzuwg9{6Vw;9aDsX+%o`?(xcK~40blzMG zbD!!j?WAtV*h2&WJra%3G}$O$9taH>^R8#^Le17NFHYt*u5kpP$mWRoI*gdK?<;Cv zCA@rO-@ce&EMn3~m}WKoYLHgtv*6rCqFQ>l6hm?BH*Do=?2DD;zZ**@{yN`7BT}5j z@lK|i9OG;{O7t>0SX?Or*k95AthFL}GsqmVr@&;|BbQ*0arQcvsPm7GOS{M$|2dq0 z{)ubf3akkt7v3hTTuX|$ph08lI2)I+eTi4Z-j%aJx+I{gHA!IvKNx9Wp$2p`-+``} zvp1eXTjNj_>B8L|#ov0&5R=Pet+mK-4q&#xUb-iV1A*7qAyrZ>9d^CmK4)3~GD#Tc zrNLyxL5`ruhu&`IXe-56V5kvHDF6}G-Y+4$3dh$Avhr28FMajwyM~wyW)W6i?stuu z2M$p#%ozaFh;>)C=_{Veyi|2gb4j%S1!WJSAwyxjR_E+ypsu;m zo`#HjafKBw-0H%Wx#vD$JUN^erxJON_bNSbE@kO0ge0Cx{i8nmt~XtoyK*gqZ;v!g z;l&CdB-HXsS6r*1)4qZ0+?CbKrt-@Rz#*9qCDKF;iX`t~g6kXsQW*)ITDml-;m{Dd5mZaz~7HW*Oroq)f0|IxnScCCp0Ly`f$LD>FvlzFg>i5O1{m@BuQIh5BR0 zvF6yH6HIeN3x?!jx zJi@s2j-VqTMuvUQDTDHjg{@4nfvoAbJuY6_I>68NZ~P0Du?cZ)k;kwkkEIBzUA;m( z!x`?~wYy;*fkg8fg!)w306Mkl9VRwu+F8-0m9O;9<8AWzviZj>Lx2)H_o|4;fx|Ej zE|Mdu*%AvHVNjgs>xBs%WTc49wNNUbea|vJP+saOUVtTqsz|1G8hI+kcrU$x;(1r$ z6o8Pv6;K6knG!)H;4!Z7dQkDW>lrS`TtPSseA05oo>*fP@jD--RZ}dQrLjY|%9FPItIZL?F&aKr-&i&& zdms7@I&cB~#8|-MB(vSPuT1(T8%=Q+rl;v(SvzI*LbFAYKz;Jf?wp(;-pQf`JPs#e z=c=A9#SQ|?w!&vW` zx7+KU3nY}r4t|d?b_pNU&$s^mfWNzDH=C$a(}$45X5W{n>!x z#O-;W+HW0OL&4z_PfBLu+5caaei0>9y``82yL!LzCGVnw=ad93ihjy|fFRG1b{n`2 z(g;tP{(hX_SXRYa+8N7+NuHUJ&o4Bz@_jneb;(6J<_IoPes7_H=fG0#)rCNM4i^ey zuU%<9@&Ui*C{ETDf4NnsHfvgy(?`x`GjtEHBmP}nL8#+xJ3(t6XUa% zdKch1gtrN3O|J{(4%Yt)WpZX35_9>yCQ}{9xtq^RyRd15-hll;@VGM5>GJtObfvu#&J&)VR-Sdnd!h3JCsc|s+&dt0$B5jjGUPO6w(2t6ky$o()s>mLbP($` zdA?Mq>L7%cMea!V-;nSOj*4b-Ls)p}K?3#|F+qQ^oYeG2WO{dHeckcg;j{;H#|_tA zuG?%5`V-oVyC%tr`VV?H2Kz`ag(F`omUA&o&Uo~$?~?q#uK%~pT_w&K44wVd+$a7B zZLOH&EDrpy?@AVL~e7> zUSXw#`sQ|_O8#XNsavdq7Wbj1qS7#V;-f8`LA&xK*EzxZge#Vibb$!p2-sDTQb_Jxv7#yc+aW?fG>3Irnd1 zi>CSlpe^z2uCqRr@A7pG^F)2bYRo3&kcwN8=h!{7H+f=d5%Nk7Ou({ku3AR$h4Li3 zujzAd75#Xw!~j3h^PfY;xH6Gd876FRBy1He?w;qlJUyuF+stsq7Yhr+>R$Or(S09)TQSA0SE_Z zj|^i;{FUqRz~-cqYpwIQ6J4*cFSG8NaGQKndlupW5ejrNuj*XO=IT~9-sFmlzl4Aq zTpk*XHKC_cR*K8QS9(7}JiYzk>w1cqAxb3D`TGvHN~e4O#!|8Vq?_+8yWalxA+FqW zd7GulWf@LsO0(L>?EsK7cCwrs1)YZnN;s%UQsFMl6SjJD^c2@#v-~!tRmw06U2IRQ zrQ-TU<1XvP*Yx1KuN|8Z71E$+TuV0F{3xCZDsAY)J4KLulP68pPgurhK>$kwN{UP0 zg|j2%$wy%A^dTpz0e95~k~^9AFr=9U(&2=5rUC3qE!h(KUhk-3;UUJm}LQy z*q1Lp1L1j$at)&RvX}v68|%KJH>bLk$@^t|e7kps1Vy0R1@ktIn*YKPZu|}lqiR5a zeB2oZ+>k4?_FrgYay}aZg+i(?SoKh(@%D@+E8E4J9Y@3D5t>Nquz_5G(M=u}tB?N1 z+676Y_bul>@B8bv=j?`oRw)RSoI(6xU(t9G_293XY8l86tpcN) zOba}E;{L7;paK_rY_e`Zqskf-f1n0P_B*vIc|a-QT*Ig>(zI>oK`TIrY7YNOlwL1f zsE?7V#8lxxe_zhe`d%NY4I!k3#l9@=oNbR4sJ=bro`ryEzbh-2k=7<&io55KQ5o|W zezo{J0OI2dYBO|B&r|!(VqwA^bT=$=<*2vo%j%BCn&hdm#CfkXEP1 zFPX!QpW%Eqs@pu`V};5o-v6LU?Fzr<&v?KsvgSiGz*O3R&c&zcGnL<&2Gx^YCAo~U z>o4J(wDpEkRSw+kZDRPcuhE64D+7u$41HF=+dYJ$w^Z`fzKt%k;9~tP!Zsa>fR&pK zUHg-uWG>;EiSe4dKUuYDC+IZ!>4+c>W^4 zh+Vk1V_49%ipsUw-;hQv;qp#U_H=*=c4Rj1nmwiQ`e9F@JzkmN|HhQw|6c3werWJM zwpB07huv_WxH@B-On}4-;eSZ{2@JqEirwUIi;3deKW|t6@X@ zHg*$n!k;N6?ZJtJ2J|URG~Px_U;~O@y>budum|I0yoR`|Khu|1q<_+=tO#>(W1&^0 zbevFOk;$}PFyr~ndQr<6C%fnpX@X&}=gmZWV^-|Y^ME7kkPnxI5Oew>{lm_{o{xhm z#o>O zX$NX#3s9k^-iUJj>;YH(>!nt2(}sGBfHKwddaMsn=&Z+rm8)8Sq1&L?s#(FXEwe%w zHAQ!hxuZA!|HzL%F`(8Of5Kx`!TqUH_CP;we?a)#P}11nqUa`;!m?0!;yVZC3oP)h zkVrcs(W8ui4Ypg*TgVhE!}Z%!!!}cDhQz_uIl0k;&YHU$YfZQO$ja1D^-QEno+B6E z&|~)7hj#%$P8A+-duK}~>Y&&!8GdQg_Qp(3n_B92E|$=)Z9K(;*ME-FyT9isg!yCI z@&i0m#_75N-Zo5UW5irDF%RsS<*S9Vr5pyOo$&(_SDi`E-?N-H@%3039h&Bu8T6;W z+KNrAch(vA*F#;(Gd^2P5qTJ@Ene&zTQp&lXz>*o{c7?|Kp7+!| z?gdsm3zmOzDP`Wx?v_ddOe3CWtk-b&00>6M`+EX*RUp`}VY2avNquu76mCLwBo}Qz zz*H^$=Q(XU(g!w7&QMaCo@!G3boP>%_=};fJn^p1kN!i^_7$eox>)mIP=_!QgX-(I z`)6#+CC4^NQB%pn7-v<+eC)jLIc*v5#0_`JU0XK`PbxXiRO%((QDTD_-s`wL4~A;r>EZ}MCJ?PNt&540>6LFfwc7*9=Z%g`5IE)VG7EdvyO8=0;n zP*=7z-9JG&qII7HJfCADHBa`&fG7TA)j|c3pOq_Lf;<2T5QA&?bp>zI&v2db=(>0P z`@-?HW`5S}5i+P5Z^zUEU+T?PAcZClu6tG=zb`lFlhJhCcJX?Zd6=#SQeJ!fjLKTF z#$Si@M}dW<1Ae`=+|{;zz`r5nu$;;ESmD2aj*=X}v9TZHN;O0=d28aw71%aeF8?!3 z{y$eR)=tH<+kAK2l~P+<#qclwf}tzHd&{pUB~!Ead9C z!Lbm{)A4tknKw`(%ih2xkToC__=7$oK1tv-^wBB zZ0hus&t!7!Za;uRnBKjUCr-2fwMf`PIlBia4}QLL1F?ro^c?*uZ~gF-n4j9V>9L`S zmR6^mge9R1$KpA*Hzg}YGEvV0w;X}=sMHMb##9?;8k`5TBoFm$@t`!w#B#8KmZaFB zp78t1#A*EIS^y>wZv&);7HNIed>U9B!dl*5PHMV+4qWTdiDumtE0fvdqZmHSn@Bbo zEU)`gY&Bqx+cjCcTm-xmIRe|2FLvzbFK`=vVYyIuG7B=mfE4e;upLxu*8Xc&{+1^* z;tXCU^ZX$J{cW?McOTcuj)jxohD3WSyh}YRU;akJZ;qR^2m*fSNWxwV$H-V)>x>w` zGnllxIMB{nHH&sU5Z+ulZ}(lfiY7uKSzJn`nW8EK#5#WCFi^NzWJ?4XZB!vnEkIlp z`2t>VLojaKd956k1}ZS2TOopvx7QLzU=tz)qX<)lX}YO$P zzlKgIMc2MtfxSy0_uH+X(0E;xP5R*;lDt%@A$_y95`;-RBRHz#@$Ka;7=!D~6lblP zu#YS!P63K2RmB!4MTzEDDwIBdTcBIy5C?_kFgwT;l}=;o$V>xWFmyRHZ!t($dVX3a zL%*;Cz&tmimGE-)MTFt;*-cTSu#_Y0lx_>^)R#@>9z=i-{f2LqcfrS%;ZPd~vzID> z0?e89yKar)Dl0wvrV~wEHD}lYyE;sJ*ZR`wS^Qy)Z?`XI)KwsRm(%()%hn7!J=-OS z|H?E=W2eWhUGL;u;8h?>h-@iu`G?7E022Rl!#VlIJ|&y8S1PxgD^Z6T8BbgeR~wFf zSj+h%U^2oCd57jYtUo*;Xt2MpY6*_eYQMMp@B(!5mDJ6-*cc&h3R|~bAuG%;&)JUq zjgh@kb|quSmKXh~5t=}8Ge0Q2x&W5{aO6N?EDEx^;dgJu2mK&kxU-}COlL$?irfD} zfF?mJ9Vmx?Si>d|SmxtUY?VP%!ZZ(2f4?{2{GOs)36dM@j;^MD`I6piDR6LSno)U4 zdQasez;Dli1GQZM;gnE&|3o&vlm`1AAY)*uBU-nnZO_53VEnCIvoj#!6Lu|8@c33=*E$g>eN=Ups-(ld|bJ z_5DN0JLFUQmc;w|6%zIY-J@%e+Dm;&z(@@9)G+gCeo)y5q2*lm_*6$=RBZNODblGB z?>g0!1m|&$9~;2_sYF6x6W%>E~{%3As_ zy;Wv-5iDWJte}%n<#TOS-ZFZK&mq#MO`CngyG1!bNRP29%5U{Iiu4b4RUJFvNrJ+x zzeo6H*Wf@z(%(PC&;atlyVcPHafdvS3}?~R ztX=d6_iR1tfrglo0_V(lOk@f*|+lXLw(4>Ijr{ouj_=`&14 z#wX8S)t6x2pZvhOp1LMlOz>|Dbn`Vi&^DRH@5}jZY@uExOF~{Qmim7O0e)mYY4qEW z)Sy^TeBi#>ZF1Q?o5)xx`>q))`O|0yGC#&8d11SO$siV;=|{@%G{OLlava#l&6-y( z;qoH`s~8AlXl5PEyR`TK(Zp6XUR*EOc z#^2v^(w(0uo9ns0y=@bshoLQGBl)J@>v0*j(6^gJlq|OcXxONub09c(So!9zVbOA0hd-*9H^rB`OGx@n9T!Yx~Bk`A|1d zw9t#4OMJ~Y#j{&SR=Hke%QZ2#Nm(Ai9|bvgoT zOFxz;OBv{(avysLf4Jl^oq%c6*ADpO5i+m<^~2$yC}CQH*MgN5$#|b0_2tdYN|T5s ztZCRTI&zklT{pgfR5sLHc-s4h;_nC$CJ2k#yI;&DeY$L38Gr@v)$Kr8Hv^RGHv{~b zZ{3+Wg(3l+Ll&+xi-!*u^8ZB+fPn+L8Xk9-9M?TZopd5NP}ej|{Y0$W;XsMIMbW0Ecp{Hq|0;Nz{L8^~Ofwk>XQOZ3Tw`>7sYlmN zePHIs#T$5BFn7wxIfm5g2>9m$yQ7F*WxuEU%L^d8hFYHuWWh1_0b_!(`22i`JrX!< zsHHF+A`*w%C?~DY zt4#HlYJ+0YIVNaXWorGI3rz{RSgV2cd>FUA5fb2Scvhtm2<8eVS(A_dd`sy*YA@u{ zVZ2(AgDI5Z?Gj%qeJ5m{iAD1{M}M0;F2=!i*(<9OY_H}K%yWCXmKTmP z_cREPacHZd!VV3j(;#za>b#Ip&mh|O?Pn(M1I~w3%CAJ?7RFjj4|IENa4rb2)Uprg;fzvmSQ;oN0WpPJ) zse|{5zGmhjS<2fi06CxRpgyGCUD-C5nu$8W75!Uo1Kaj1V;Z6WP0fy{gjH$?F>dYd z;=?zhT6=rGRIQ0Q_kC^V8}K$YZ!$ot-7=>e6W_l{@N;^RwV;eM3CO-5W*tt3D`?z8 z@YV51X_o_86))3#5z~&%x68V^K+D(@f~{jbx!{y#1gBSN9C|6Fu`>^w&|fkZ*ATU} zpO^R>0&qY}D3M+|v;`3aSN^YB4qeX@;AW%gUfC|f@y zwdoL3g+%w=+08F`@sfEvD^krRiFVcC`R4meuaLFF7_+yEtiz1ShGE;60YUxWU_XNt1)<;ZtsgaW z{|&4!#W^JdnQ~y0fn!;b^WPrzaCwhvy2M*(6WH0c`tf`(0d&sDp+vz z-IQK+|5$!Mpr5ZuB?BP{X7S_5IwhKTaXom5j?Ib7n;?>+VVe6?izjh5ZU4D>(?gq! zcIc=Bm}H?RuR*C!l0(WzyzJPAo0}`)X&9D6^!3TJV&7~^G*%59Dj(dwe51MxZ{2B|0Fj9Zay59S&4W}CHHOQ^M^H2P)PyWNUzN5=;NuBB-X>$w-E;Ci)D6pNPwX_JpEL&0 zk_YM*;|jQ4+w$Z?k2Cj5u75b3L$7y7`nJb~{*F>`?m3rj_~?H3Hn!=_jEWv_4~n4r zwY}m0M$=Ynna7N;MTfNho=9l-46autt%_7~9*vksP%ZHj=NZoFD|Yf}E1_Px+^v7* zwO2kl%;Qp0+l3l9msfE!eZzdh-Uf_?*~=}<5xs+-%YwYRI0pl;>`_g;Yce)YAA+X8 z_FF1_f68BGk5VCPiD(BVtFBn|Ino*i^`Jc3M{habmZjwc$NAeA5yOq0P^{#kaFT2y zZmNOwY%MQxEiatOf+mHD$rplllkqhV$oeqXi(1rywrQ_tf|kmz$#<^R1Wk14+dpbG z-0L#k6?g0riw!h&kW9IK7D6&JK12y`e7a@A@kfjR99peO9s{TrPyX>;3MxNd>}r5Q zkfRS*)$#MMj5)JWV=;kG>;+_c4K5Mw7hFG#>}jP+I}x~+nl~xfsVAh@8@7)>HZ_BlrwjdkLsmLr5 z*o-2lN4R&|gy&_YA1>b?tMJGb*g&*j6!OI2eU>iBnMf%bcbs&-BABNTb0gx}nDp}o z_00GRWJmI$>s{=JHtm;pqOf2}yB@xnp=K&Ixr=@;c`ZII!|smKQsC_z>0#5dsZVbs z4f-JY?(V{vy}QnErGXMU*wp%a@&S09t9^3P)vi8L%J@c0BCY5rh<=N*xC*^e3#F!7 z<%X>TdYETMZbQ`H%RaDe9q^b}dgQijDAjr|}F&f5WA zNw9}Z|M^dl1|=aE-3!)g>3asLlU*C^kPCXa^aQ>{sSBk-a-LOI7R<^?&(D;^`ZzM~ zm~cOHelrCAw42>IK+Yl`l?LxLlr)jfPVM-Vgp2dyE5j*LSKanegbu8y!Pt0wg+}1g z6cI7qT9~Dmck_UgZ-lXj{MXt?LC$@rbaQzuAG6j$BZqpT;(>+LZr}T>&+@rdUNsd= z_2w_*pW~-rNTGZl9TdC_>|jvy66ly|Mj0>ROw-}$EW_l-cXzNIeEJm|`)9=Xc)?nCJR;u9-U`NXS%pP?(5&=|n2Kiw|R+_X%+s4|w$ z{go<512Lvgu4R9g4_{6Ku(S_94@bNn!0~mlZ^mLY72;L<`TS10@+_&neG%Gh2FW+m zFyd($eI>f*%Maf5fx$-W01{9x#Py@}-W(cjU*rI4+}L~7JnXy$w4Llccuq5%2dO#r zI`TShdk)yzt~ge%UIyN+<7rJ$K6ExpyKpR2&@r7#Av;{Org}=gcj$*7Rd}|4#9_Tl zz;);?FnEh^@6f6h6i?=SS{V2cQc`fOX8*D`soPS>eeU|Q0U4#bjkUyPg;M-E`Ox48 zX6AlBVD2N!m>R7A{1=8RRIn-r*ZuJ3b*lj=lnL!*;2;M-;=A0gF?}m3fjpit z;k}dX%#lIwK#jmhk!RJil4BkV71=u)mRdZDc3Zy%cA}3`&WJVC8QYh9mFsheXY=*1 z&X2bg=Wfid;(W+P+^j}U^*g|PTAzcRBnIO31uSXmC)kg6tb z1Ow?B`ixIE9_}8wM6OQGB&uYoCn*@uY-kfCJfUN;?m5?mcvQvcs+e?=O3XlILt>t! zm=CzX9hj?o`l}}!w5jQsG$Eg@67Saf4$-9 zC4~rHM9)U$7Y`q+p@Yg($Lz>iaS-w1$ioWyIA4bA7Z#uT*q^!?s=Q>0pR) zI}>=`ad>nrIr?e9Qs{-;neu=o-ZBn-veI|mRb<6(NOt4c(W}qez6DEZy?>~NFDnKM zVS9>Ee`SB-$53ab0J@Lpr$Wc1O@2zG;J$LtFesk$i*{q@FydJEn!#_~keu5H4BFVZ z1?zrw|=z!3lT#SO)^#;>sM zgT-%;TO)GLtp;eOYS>JbILml$@UN{>v#dnzKFkNWC?zI1$Gom6=yhoCYQUGHSF6`Z znNh}8xXdW6Or6~mtJE~b4~Tb3X#poJWW8Voo9BJ#Y(^UCB!8us3{I;&2S^nj z&6Fn)4@M>TXoxwjWc%n=4n!TvM(lC9iSv28fVb)GpkC(hV4v>mp2FKq^%Qo7sz@-J zM?gO#BrCrN#lvu@dwb~IP%`XQtCRzyUl?iy%^GpJ@F0Zo)r?p5#4g>c=cbuNszOF)x2I6qDX!FdqW1f4W$m>zfP*gtNi5)0nv;S`m(&$M~bE$za5sh z_)61-@s4s&)q#y5A0I9tVaMmI5GBN=UI~bz@db`Mnj@o(SHQrU47zxUBLccq`l)+g ziMXpnvjnmv?*_8SVJO>Upn*T#D8H`0kwog7?=)uqj33a-Xp1#{7gSN%I}2gsR7+IY z;TYo?BH=o9~6naV0oNmh{IP6xDWed zs;xGsYnJgIYnKXW8p=_kjDG}pibg7*HXr7mLb1f7@3oNUHT8>~qjFN8=9~y_Ir`rG zv?Xvfd(jx+XQe_-sIx0y2+A3Xx-JDrp3pd^6m?GNQf5)rUPi>Y97?cU{d=9qw-7na z)wKzU1A>}Se7a>i&XI_Lz)^p){2(I zCSJB zfCg)3iY8JN8|k*~0?_*CK%(zS#^)PbGOAtT5h&boHAzlW(-5gh9WE)rA5gpr-R{JZ zbAkAAMOt!(9Hc}K^u#jfajAVu)S^Q<;3(IbhWRrU?|UdILJIXe$*{U}5$(TitiWSY zJj$0^)q21yS85>&yx)%wh-r1=9Q?VzDo2VU%j1y`3a#h0oFz{bZsgcus+>mHTvv2o zp0jx!5#JvUCm?JT50pDY>^x?Ex#JJ*?asx)*;@A2hhwb?4-G+J&bP%GLAq6k-~wn^ zmA+)G5a;AcTqE81{QSHIWYryud6c3gaE9c0b)SLq@+#_P_nsuY7>lshhPLs}QMcb) zm!)N?075X7&-4S-rxiN~JrqNQmjf5Su9}bzO|@o;?g=j6Tl;z$a}O~Qq5Z5{z|>-s zAz&z=+`fxd74k2*HHF(#)ZR%og30p(&xC#uSOlPjK?o$4M{HtRAb=ry7X<`1VOJvm zO#V`lHNhp$Mg4|0PiUrwOMl8_+H2Od*mQaG8|hmqsKgm)mRQEM#s+u>2tA?Y9;u+i zv8OANW%p^Dem%1BnAmH3i%`Cn27>?hk8VR9sTq|@7%fq7X`-yZz7MV(HKc~vp$l8} zR&Vmv@T*c8I&n^8r1DS%a7AKupMMo@PhUzahA*aOvfl~|yf z`%+D*p>Vs!i#DUB^k1I`v>8I@;KLQdUL>LzIghv{{lI)LCE*QrvV%6G(^Ok%!*eQ> zdVzkl4HdC#ULx{%C1Si&HS=`LiPj&!X+=u!wFNbBcNm&fy5a|>9dClkYP`2#skQ)?)qG#WDs@oYKqz8t1ph)b)!AvZBD`paAKPLNiXL4PsJixzDj=u|vOqS<93x zFp^>`B%TS`Xh9=j!1x+ka{t06W&ebeqV%3;%DIWdwkoPp_f1Ejx#vsW5rVy{Hs&h=p!lj@a;vQ^(d=KH5%~s;EfKKjbzG@JzlC zxFf`SrKbioR`lq+0@wcnSK*H14o7NEw406@NnM1n}T%b%3L^H z7bTXckP~EENm{e9?JYrW-^K1ULIJ+dct~H=-bPDe{)3T+x-LhU!knvAqd1J zUJ3c)CyY1Fl&7|zkB)s1KZ&z)tf`9 zz+aI24xs zjT<_o6uWb{bnD=BgR?H5_cON{Los<}_=&-`43LGR-NsLZA6NSluK;e${FnXC5va&r z;2W!raXVCe`i=4*wG;X@nQMK{{(Or{&^%&xtI`=X@ttS}n`mZ~=rsLz0?)8L@?typ zOHI|Wc4Uo#j+B4d`LX+gKWLK>>Uf|;pYLj4bf4N>?nju=v^~Rq1cf}QH;Uc!?yt4z zv_mTIojG3E0{OM1vA7ZSc-{LP&!VS~`2H83kvf)Fu zB;on7xQ+qKOdRu#g=|t~n_sHb$jqsmCZ!a21Alen*~zU0f^%KKjO%#y zYUA#>bvCsMskp-r+(P}Ba(x5lc@xR@$f=*_hS0pm)}&3!MQ?9k^mo_Xzu8^H$w0}} z!;x0MhLodhHq042{7BvCY?Hmr2J6)Xr>m)XSI0JP8gCFnswC{Zff~ZHpiL^`*xl28 zhy={7&|}f3tUrFKv2HENue8S;vqydpbtIcq>@sv)RU8C1B+ES~67KKqF8~W;!uzs~ z3X~MN{~1~Ri$=hnL>GelEf&3%*pDi-Qfu<>BAZi30@CLbhH}R|M8o8=NDzv$CA?dyeYhlqVeLpQB`J_sw(k&+1#u_4iQj;?-1*atf$BxjN7z zwpu}{L-sQ^f42Kk-e# z`uxdqmkBq&_tz|`olGm(5wi3wt2jtvkduRoE!{$7^S+Kzi-Yrq##L8DJ_BWH=RxveCu!>W*4U9eU@UnJb1rIS zG*>9oWoTvSr6EfT?1~pVbo`g0xo-Vy@Jj*jl8pwfihO2%BZGw6$4KZ*Hv4AP`}&a& zxE7w2Ydx(JxV96prL_7!5$>^v4Igv7lASv?7Au3Jf`;B83g>O@W4t*!EESE7t$ROs zUnGiN%e+M>a_Du;X>Wn?GXOxuz$aHlaEDAk{r=XjNnHA+kqav!TUVH>D`z|r-&$o) zs>*j8sNy8)RMn*Nw);14G7qn?NokWBhB3@PM3`&LUFiuq4+wA$hH%=Ap`)r74=e;e z4(LpTV+~CC9NNQ!S1m`)e|T+6Z)j}j%rl)*1>hvne4n)|OS3rVy~^{!k0P^UPEfb3 zT^m+}GE*IBQ1xkX_v?-}Z7FJACGt%L8T$FR(Z_9E&)KDu;9LMR6x46kpBw%F*Jad) zjQ6chIyR;v6H71El;*lkn}qM_&9gpAU@evakW(VQp3TiTX`61OBH`R@O`0{h++`bm zRDmhK7%#bOYFyg^0VKgP#z#+!;bZ63uv4jEn>g-$cL($2IXL{PyeBKhQ`~jBPp`;I ztt%snc9T#uBok^?`C5G)k{qRjgnPBY(J1k2k@uz^Pdt2V{KZkRR~K!lR|Vm5*}xGp|yVRF|LB8UAHfz=i76QEa8PD8)?cs?>gv=Quq+>-!MQx5q&j z0E!;ZV-TO2X%*;XgV5;3a@^g+Z9NT#)i$((wsfbBx#G0G&-HuDmd(`y1NQ!3s-_e!pjssBEiNCAa-8gYZ zETIbKQ@AR0r9Mk~9(_YSU7*2Y8CDD?q-gnUlENtO)5h>-xDCSMwU4gGOFkblM5XGy z@Lh)*mx^k)je=>Fukfj=F;G3ZOa>dJv;%I<2=t!5n+a{+?KHX%I)HV`>{3yMi>PPj z$|#d%+z>7pn#}*OCaL`R;v(znAyWfVE=M1C?iA5zm=<-Aq#2cSM;U~x+kH#z1u~pX z=U6br!^Zh~$8HY?kw?S)_ z$ci-lL%BXdxsaoh1YTc)(C~-(M`lky6JTx;9#0th7RoU~#v4CZY>jzQ-V4=xDgg$R zngg&c&!EPMVo~-))ahUx4e@^J&Z~gxSr0#aIG);T!!UHLU4a&Rc=m0Qj5_U^MpE!)Hea03v>pwEygzKeahB#EH1LYuX-x#)O)2E`?r|=RW6N zhi~Q=YZXpbXhMx1oyJm6fvJrdef$EGt0)UMPU!K`)|??=`9fVR!L}@o@YSEkV3G-5 z!9`z!AiZdGR9_q-qzmuh;BMlb>!#Y1G1l|W|mLyWHG zMDB77dwB}qP+Chdlz$K$78(=_xZgT)>J-Dh(Xsqlylt;LbnhTr?9n>k{0O$D=vMyn zy!oHaRdB zw81XD71nw>GzJRWImNI0wHmx;Xy(L?eZtp8IT(d&y%ao>=n#X6>gYD!If$BbZ7vF@<5bJaK=BfkvJ&^g;raOHs=cQsKyZd1Sev8iFK1#MR{c(B?J6bv-L6r}^q`A>5Y7-$*D2N8bG z%jwDQ5;HE7|4)(4;+jVF;1+X}E+f{uFQ2ay@jbgK^9CaWc(K3Zd9&3xB)lqsHw%5wUY@Z)-IHH(+H6m3uS_QYw)=^ zV}dle+0Qt^>aSoxy+HD68MP&ZOD~~U4COujn4_D}(NyG~k8PSIE~YvFi2lP_#mg)x z(?vZ1E?IV5V~!3tAi(*C+=|zCODq0rC^cJm^G15^;9vbnDhg1_0oAs;7r*`SeOXh- zqpPLZ44byp?!TI!BNHN~2m(PQBCNxa+ zn{5tx@A? z--b$g9Y>y6M4hbT?3`M}El=FH|Hk(BIOsO<4#RC>petDU6pYsSUaZA)g1)gJ0zsr} zGrIV%l1$|Oot}iQJUh<;+-7p2Y{#hlHJTx`r{1zZ0u--C^Gx51Yg9sTmwPGb?uz#issXTnMjJub|QWJg& z&w)eE96))Y=R-+L{SX%z5=@qN8@d1zJTLOMi*;+YlxT%cxGfifCfj5f#mp&aZ9>TN zOJd$&b>lGoM!6D$Yv`3~1@pIp+$Ig;6Hu{QL6_R1m|d@kJ9=(>OW@_st$KBXJ(SfeE8ePBA{&{I zkhE^3`;o0W`{MVw(r~Q7yDR6>8dt@(igQbX*dVF`5_h`^0-ouL#kI5<7NE_dd<-b* zeoAlapPwc{p1FlIY4r6J^yk?er|)eYo1At_`wUtANNw)EJN+>JzP^rmpDd;c&UN~4 zo@>ZTd3ht`^!Y$v*HyTMnq41oItZO1Az%>G<#~-bswWhfgE#-6C=o9yewI zkL)jrgTn?A$Z&_rELY4{CO44LZA86k_U(+gfc#D#L!kszSiwVyF5MLH)#rFA_37v= z&}sFY+UJ0?o?tz3&Ry0t*-bO|y|xvY-Jv=|36K1(Eqb8pSp%47=ks$oS3ZiHYn)(obB1_5`tj1aRHIPj!t!cdh390^Klp@DBJj~biv7#U^UO!qL6Ud&@X@$Q+nP$d##e zy@G-9q#`Ct?vo#L5Z@l}3A4$1>%_S>s`2PuCUGco`mi64sI;4qHj;b++hiMb#NB2a z#ONp|73PlNQ}~9QWA+t6(Cw+v&DUaPss4D3r6x(|j#${T4tzQ_2SJSntyVxNa?5;xNHE%0wTu&!w@bazQ z+}w)8*7K|vCJU_t?q8MA>8eVhT8|PghCiIB)OJ0 zN#XM~CnRqa#eP@}Moy!biRU46FxPrR+;TJy83pBw^6q;b-{tYh7EwDH`u6&4I(fQozmS$f5O^UBBi505gH0sPtrSY3pcVzj=LM;9FAO7V=-+f2#+UdHYf*NkExkfB|KO}N>jqK7pC{1N!{_x>X;^F6C6#}R1 z>_pBlH^(?MV{Uo5X50M)BMnF-v$v7&SqN$9!TB_+oLp}b5Grv3q7c6dz1&dyY5|?! zR+K8*`XWa$mA1-$ZZx#riNWsw#!oj zljgM5`#Q20h_^!t_n{RPBQJxg$D<$GPNTyibAGklXk{9HE=3`QwEJ7GUuaY}^Y50< zc}4T(@@JY29FTfnUS2w!&Wa~}{Mb_SO~8JB>T{GO8Yjyq@Cd+?*UbhecvNW% zI7r0$bOk?H0BEMWh_NYoKV46^+P9@4+Dq9*7njgjZD|i-)E*zsjrH5I8UB2CA*1S7dmR-=a}EMN*NU=<{oMP; zpBXfgyT5K9;fh2E&!3sHk*s1IbG52AI@q7!g^=WJ}lRq+Y}y# z?K}8n;p0qD-XqFEdu}@3b2fL6d5`YNWj(c=oqk05!K{F;iAARJ{+xR?Z6d=&l$l(W z+!mkZn3YYfgRGsoHWX8k@QiU;!R)O9Sq(3=`0%5`Bq0wpt$Z!IKIa-%1{G8a-`yz? zvHqp{aRk;4K4_Y8kH@RjI=PekJlaphBp$N1BO-Q!zKa&h(k9Bi5h^ay+_$qS8`mO* zO@(t_&l2|}_=@xjd^Pu$BuVsEgGNP=+lSKqS*=$TR#(WanWWcyn_8M%UxD?<?s3qv-h?t_Bt7d&Ji~vJZl6#UCjHg{T)hEOp zGQF^cq|n;nOMeqPXrW(1WJ5syEJhjpA?DsEbGR7rC%(8Oe(2cT;KnzrIKCz3xe26Y zpGC6_4Q9THKofkp=L{oBjnw9cA_u;3NeB;*ywn}gqQ4Plv*gBti0aW1B82w&SAEcF zDb{PS$Pe4X=5@g%8;9v*z=DO|D}nQp6fM#*Cz;4aFbeCko1CCZaH4tgO^I^aTUcAJ-BWI?fDco3^c(>bEA@aI^mnm28 z{k!02qAa6|*-~6o4Drw3K4kuD$J+%`@_e0p4KG6H+W4+j4f(WU97>&ie8*}dcLOSb zeL_Z(tV9zbC5?5`Uu`He=Q2cIMORkY{2<$ovNLI+jxo7!H_`Ua2|oP7IXz;slDw}d zuV?Ma3ZL02?WK=Fg^5a=^qrCt$>XrrxrJUK5K!2b5R9e>vbn*~35CfL*-jA@O zgBZ{+hGga|lDIoX#GXK=l8PLjQ2g;Asi=&|LL(*rR3s_wJDu6{FRWerCOy|ugHKF1 zTPRM*7CVjT{#-(TD7f&4A?Z@vST{JJsI>EFXGV8pK2o>J$jXWqPSjx(O*52Z`XMuO zdT_LlNI6-k!-%_e?$vN->_L|Qy53jC&k>DPHnCG+GM$u8$X4BfL-U&vx%Qr!5fUD^ zwx@z-Jr~zq_|2Z(W(luB;96+fyHp&yt+Q?~v}!ldSXoigp% zl7eV4HSw67+biPasnMnaS0WuR(Z9F6;q~uZo|G{erhr)Ia1^eW~ z8otkT?9KE6HN+vA+&+ZZ}!}9})kM;X5gf{H=VPPR$cSle~wxzi%>+I+{xoQYO#H zTahAyI9HmPG2hOZ3H}xLDLDWtWPz!Xtd1y?!EqomAJulq3oUK2(=`JpMFyNamV>xB zS=n7+G<-~g4-dDp3bWKL&&XI`SC+{UOnuU+mGl^+wW)V_(V&&Yh?#@c!Ca~bY);2@cwrahC4!}g4$gA@Mr&*|~t`>$(_ zY2R{)_sJBd7nc8H+c*Ax%U^T?E;s#<9WXRxG3ytSDF__$Ts-I?<)Y#jwI?5xNrv6- z2^t~F#Nn)4{iPj4r+LhZ_3H7^>Me)VpMg8$%6t1rjxCsa1#kNU*q5@(_tI@q$eoVf z`mOk)8bznKfgit*79lqtFa_JCBo>d{*Tj1^eE6dYqMo!V3o|u=bi}L&nBxF<%_K1b zxcBSBM>t&oY*zCZJq+zVBuS=le$04XI)bj^ps> zr@zt3k;2GGvgqyf95pI3a@%Z;6^4Vs3x!qB<1N$u_jg2YRUuZW&d$y{FKV54!gx(P zHVX=~R7;lHBaU^ z7|JY_(D|g1u4JLNu@pi|*(l~h_WsV$&kTADq23leA*$@cB~$Ikw5nqhe#coR_Kn;Y zB}VK&IN%vC);e+4z7VkN=&!9T&0n1P9vnw$(i(a9%;wqBjE{Yw8G+gTSQW)aFyeX1 z0Y{Ol1$SJGZxH}V#2F<*&G2hHn^DDHjQ67MRj>P-S6QR&1(ZyWzOHm+%y3C~c7qg% zy_D#;FNG*JVRkXw-F;w}m-eA&?SUbDUwGSkb4_3?Y}Zi({_T{|w|KWddhI5hY9?|+ znh{CM)fj}x=G zGJcj1T$Xn^6j1lLxVdsl0#P9CCDz0`(v1G#Kj*vEWsh0==+6!Lg@I<9zmqM+IA6wBuTo>oAJIcR^UGxgv(4wx+82u#U&EAFn^$7#Y6{K< z5_pSC8@D@M?}^svJAR(%W4v!;ZRJ8tNEkR%-Pb*Whdp8+edW?%sFURHlS-c-qy@6R zAi+#}Vk~wN17-~MMKW|e8Gm;&;L5Y?w=`arz(h)kXEMZ)%fE2FIg{?RxPAhiz$3PM zZw@in#H+k&uvZd$!H2x za!E^(qz&3wTO(C*b24Y2inm_BjF8PSLtQ{|N+_4Q>_%!420W2lUwVv7AL88zwIHPx zwE0HHkl2$rknLoiZD(p=<~uQ%O(Nv-@u4-PPWk12{rgqSP8d~pqIQuokHwzR5fhKp z#5;dPC(#&zieI#$^BbNr_1|s+AnWyK%$J)N9%ai-?T?0jIe)_NzSKZ|7UprpTHV%( z=C{*c?l*}?Y=yhA7$(pM1vU@-wLS_jsxpV--3GDw_5*Ul*Aq(&t97sGDX%nMPPf5)mXJ&|V=1z$9ysx~vyt{h z#eI#N1yNS*RP>+~ zWdTF0KVwh8+Bxg>Uqz`07oS|VR10+kR?M+aZe^Mp84?q@x%&T!L@^IA1wW66?}m3g z!aQcHVDhu8_|z4ZW3P=j3&^*n{wb~&7A2jOh8_G8+D6=6x5A0*bT}%{Xainx|3liS z9Ko?6E-#=iyoziFvt?0SqhsOR~ujxy!$ea1BU z0Fp8dku7ozxJag18wzr>P>|%0uE~9pw_lud`;#T_IsN{|;$l!=$si({3}@Hwa!ZS$ zuRr@;BtF$o&&&*DKW8(ma3>%j=uHwJ0J~X7pL$(r=ZiNe)vGP%^?dm z3yt%dLao=7zt`vH-qkBMc-$Q)dDRCV-idqs&|>=zNx0140Hy1{Xzef58K7TcWHh@&&<%?Jb@wePlAQIJ3QF_?})a;HBXZJ7$So0 z4do3EhhLAMbSRSdCCIT&d+Di|995bbZ!!+m;nZl@7JN84%2u~sVw@?!snH7eo`%)e ztNK_mVFqLN7!RYK?;0W`?``apV>8bQV*J~m{Hotdosl$(j3cp{RcGF|Ov9}_`fwhd z`PrX^*dKfjM1T4eyeC-?bf0DxgDc?r`91vNmP)Oeybn^ToUmSJ5KH3t+2dM$JwXuj zxICv5fphw~qLJMW5E#rL>5ZkbjKO)`Nx;ASh}I*GBKIlkrSd};xgo#a)bPTr(Q>KX z{Y=$mvGDu%hn2Q-Q7wrisX$(_eNQ7TKwa8+=Cj zt=E^k;*{8I`yC9TmCR3rbEjC%ArW??;@u;wE`u}-+M5TRggsH07>>m+KmAFC)GB9v z5sE1_OL;bBKaE+tmpLy?(==GWiIs?oiHol|0s84l?a7Xd7>kw)2pIu>uiXt97ODE{ z<*v;_8tVt#ZLYJ@XI|mIV7XIA@~x5KRsZ`G@W$7qmBuj|bP8J04eCL%DoRv`;@tV` z3G0&MMm)?xp74;D4i%|2nD481&evCm8Z{6OwqS28`;cY{{8Dpzfw~q)hEn{{M)$58 z!}*4WYpD&62$9JO+x+qmUETP)Rkkvp#cE!XTeKf-j4!WKzt$5J6eK}A`KFaT_V67M zt;2V38ZgZkP(60{v0R1aVI}<*SVUy8)11foME!%7=0SUD3U7fx6$W&*Y@Qn-TC4MGPQf=kks;G+cu8@)xLG6t>G?WWiH|%(WF^?z=UI;qAh5tUPQaBef z@mE}znvE*KH%Y6{jSe@#kWpM*^|&^^YLgUZdEnVxOWFbiq1eftJMVEY7j$P8&(vqI(n{bHft6%{D$Co3CQG0_V{U4|JZ3Tsqi*PKEgbv!H!4>{QEFKbnMF!u% zoajxaRi>&GnRe$5!dI{8vHu+!%8Rbcr8nE)h?{(YmO($bxO4mS77z($K)%v#$>M}l{r0!V1T zZvfTXJv{$|laKj19SpO6*5KXnV-t!EN{9ivq1ke=mK$mh2mM$k_MDMCsgWXIo1If# zq*OTj#%$2kYa8F!!`D@*nCLgHb}auA>#zk}+}Ej$aIOZTKmGyr;#?`n66zRXN8{7a;!t@e!CS0F)0|r4+Eg-E z5PyFk(=);a>c3As*it=G!Xa_t{l5MJx^j;%yC>aT{FU4PhCM0&zMhWe<9+09*%^=- zW^L_Z%Iw2eiQ$n>4p+00Jhlnks*0b*jC7&yb*GODjwf4M zdd1XR$?Uk2+?t*~G?uZk_&j;N_9`XZ`=gWWIP7vscm2Ef`-98o)?l@CDS!90TUzoc zG+2W5<4%5kL-6UyO~}u*$LVv#&1YdTu+wG~=(UufV(}$m8fQ z=KKO_^lustx*}GpJbTNFDTVhwqrt_#eXTqF`vL_(Y<_?2QTK6%t07tb{V~P;gQeS{ zZl<4_^K~@~mv8}k}_ zAmqPs+VS}zQVZ)qvx@wU*Kt1!v|sw~i_ZG%yQy4tO-*;==4gKKoo9)x)NyHP zOxrj_KhB-jTFPI7IYN&Ezrs}gKW6J1AdR9EqIGsKEXcEm&0ix3?<|&eT|9H_O%~M# zW;04oPBtC;EZ&*OZHVc`t0L}oS$zX~)3>py2~vmLERp_)!86D@r*k&MlVab1Et--Y~7U z`2bLX)O+%?6Y+T%(}KY}xXe7a%+)5`$ij{)gaq@Z#u8XGX|!^_H}y{XSm%fB2;8EP z_`D&_6A3+idP9;?6cp^lOiDTK#>Ds|oP+IHI+)qwy-QzJySYWxjXmxXd_y+~`_7Vo zWu;BREqFTinEz>B-|{SkT@O+>xJIRn*sqX&RA~C^v5}$pP*=L=(b5_$7<0Jzo$vk9 zwKiADO?+KLn=N(Q;zE_!V}Z*5HfHIoPmg?$`(wqa5S1~CRtd&$YDRwY?PBEJBfH!ttBogIkX#n zu6-(gaLw7-)XSrXfm7%B`K;oT)C-)1hh>3>A@}s?YL{SNdR*>pzA7#kIGI!GwAEj) z_1*3u8QJ%7U(&MqSfXlay%SHygKQ8n{o(hf7orV$(Jnq+cttoO5%djG1y=^u@}xkT zppgx&-5IJ4@(y_i=(L!xKRUFuG;E_Nv|*;o?^@l_UQ-7#Q~AjqP@4Y@891^okY;B$ zsHsD&8n5uVxiy1&e>EBc;66b7()EuYup4=!zZ69VxuuD(fOW;Gj}ne(B8mNPef=Lm z<_CIxgWshuo^herLoXd+UB+#?26i=1#NG};fmkIO$R(BHP9iG?1Sz&mR1vP7S?6fB$SmZ7Js9zN$nw?Cn67bLVT1oKTI2bH z@~G)V?2dwA#{-x@mnI#X&Rm+WdnCqK|H2Ojs_J_8I12>Na?qh!pFeF|Po`-+c4s`V zb)1aP#yO=eW%RqX(~;xHeu|h~FHrvTH~CrQ0^!nUU`m-mWFAD4(xv!(jphqNx94<-E{jZSTiZe;mlz9-kg_-Iq;QpdvTYQl>do^{v5m7ZW)0qYFY z9OX{Xb{c0&fea>P%k}ciqx2RCLelY}$|jOHe^Ns7Un>6F`quN2iJNcaiy2gICYud@ zPx$}|E7ksM$=_e=SEQ7bD)Z(~YCoYgO}6PUzHArY^4u44LWJ!ZqtOy+4oee0VjeL6 zHKy75>@`tLY@D`?ptGr?ztIT)(7X#TpIs{}x>0K>hn0Ze$>SK)ku$lN{mqNlQEF|) zl0H&7fNotlSDt`u9ISkM&bA*NNloZS_cv$*^NLe}-q zmk?2#Eb|h25>1;u{5Mkt`QnCGHWRIVg5X!81|F*VPROf;9R~t?(b_&k;uogg& z^gn?AwE=LM2o+{#=4;2B!_BA}>t>aYf`mXw;;C~)G?TRFg&eK-H-Qry<`r&ED_847d6y}0r(p$_(` zuLOlV!Ca!dvv7SoMI3L!y~N`_3-joNN`a+%LZ7_7*)8++5>LJ#Psuh14^HQJO;;6t zHd*0+;S=h~DVLJQIhkwpjRxIc&2xswut^{fWC8-72>&o(LLQWw!wkm9$JYzQeF}sx z!!l2Zh)AkByARBIpw3-4&P#FItGydp-kza|z!c+?(BBW)Z~vcfKi*m&F1hvgE#zJ$ z*-WEXq*9^YN4~R*<9zzcvj~0fQM=9+u;6rkpk5U90Zs1Baq~d!JLLpBp8SP(&;3(o ztQO62Apa%)(bC8LlV zo+C<^zMVN12DB>#@lDwty6;)M;(WCFyG9qBeic~-xYMQO^qV^yiZSNc)iMW$;_Vhr zNB3^rUn+!Xf!y%#ftYYQ%wN2`K2yijYc~=e-_gmczY=!PZV+(?3S&AW1T~u0yrtUt zQzeS!8`&nY>f_bEIVDWk^pgLjXCd0ZiKD*$PY=oHgltsX7cOCq(8|iFF~?j^QIKG4 z<6KwWq(pO;V`Iz2+X-&$mI8}Xn6<{Jh$a<40JIt_z$>|t%?`%RTP_17ucF&Q0hZ{w z*5C9H72HUO(Q!^-9lvhMvjzHm%SNVd`;}Y8nyum3s->b8iOD@^ zNm_$%;7m~tv}Z*YtWs!Oj_-SpxwXx9OaIXDx(V0c!Y1n5r*or+l8&Dq97spbL7r<( zP%V7i5p|WNWr@z$Jfm2B{KDrbi5Har%=Gd{rx5k^^}J5)*F%~bUWe}DV@y@rwPk@q zhyJMjxF2YeV3!1ZVb$}#sQ(Ky_}2jU5(1h5pL$RZ|36i0tRwpnG*!`35DecKhIk5sV zU)}Q)DgOI#{?+*OHI9tFB0roZ2WdmdH=>8P_)NeU0oHi^a5QG4zp!!iZiYh98I&cjEl1|Vbp6t zyJCJ}f%NqYe)FGU2e$*)`qMHsdlE>Debu@XID-qPDg$$6Y@Tc1S}vcOpaBw2{I?~d z0{<_1FozP*i@1}3IwJiBJD4F2wRu_Aa{F=EZHd8g7bFk|!o?#>5CtPX*R-^>O7f*t zs!k4$et>X2zqOTL5iDRm((*Qtz}U(vFXvVW(vBC(g#20%`}gPjTVTF9{T7hOG}~Ed zP#_tkr#0bhMLCr2^(vM6U`+4cbnRUO4EWU?x(UNo^oB6#d}8|GnDu|*#95@@u~3ZF zG}M}occ$^=%s|-j@J$Aj6Ymap)j!_2sT$Kx+}AGGIAbgvZEibgR>G8*HWP;>!7w@g>^{7_HdtBBD;odqyK z-+i?uWG4$Wi(7}?mM&b%t*5j+c8`3KH+2PPAgAx+*53L2Z74#;K6!dH$2%o~higkf zbue@Yt@6`4I#?ekI|o7hs?e>Hg*}sY1BCQDN^`G&uz*>mU&MXifMVSDYK(WeuV9Ke zvI1)c1HI9BcbD*NZJJcf3rX8`jl4S+2ZOFsu1e=;%)O89*z!~DM244$xR?A-Khr2=b0gXF>MKL3Ga z%9~D}&!!FXbOhE1>vfaLyu|f(=h|^#DxI$_1M}Ltjjh;lmV4gI% zQJkp6cQcd-iVwU)J9QQGQXi)kRB5tjfj^k6_PGdq@6a1~H6#{?Ix1R>F=>V;hVKg# z89WT%*G*XTc+gF!oV>GaqkRhu`1hJI>8pb8(2af?>S`<6zS-~C z3;MN+cM2GV(HbCzycRq6QfhX>;#lvhX2vljoYIBg+u-N$iP)%nBE+_Myg;|Q)F`UG zQleTG$3S^P8|s*xXwl(XL5o1T68Uc?pLXW<|lQF|k@H>H# z4jaz!eY%ry@}E_hj`uWZXL(y{e^_@sKd5#;*`;8$)%VXF<6cCVt7HkO1S^bY^A;&F zjZ@ss-L5+L<$C?aLqfJ3WS~A(RO|i^1Lwk#>pd4y3!)_d=a)igiE?&8YG1f-t`SYe za6}>cUeJ9b-E?ZJ_yRxI_|4`AW_e5jW=3;Rw$GXW+@Dzu6JR5?QulqPwDUrpK!8D6 z<-t*3{sQZQ_V*TKvc*d#SAb5X>Nf}D)Fb2m-I*j_9}&>D>a5<_pvfVYSo{KwF1fQ< z;y!uKjUI=qNdo4|?-uAqU9S^i;BfTMIl2XhhC1q>E6%MZp@_-$G6U|LQuNA5zoU7`EVbdvP_6sR9WjZ9 zR==Pfqf|~wF&|0Op9>7`S676}in_s@cWg5mIy_Fd&TO59XqcG>3&L$+>yhE^@C^*E znfkytSmBT9#<|CH{I4(O2s{gDIM!(u(MGco^}^*OvXco{sMwny;Xf)Ey0Jn)(NRK2 zwGxW^lVjNLaQsg9KG~2*q?IyYKHvWI`+Be(3OSxi*Ly^#SM4R!r{BE&-SMI_zx1FU zY%}(xf1Rte@0C3{2t$~2U!ITAyL)?wi}svk$oJLhM0

!BPO(jZD#1=eG#ob=#q zMY|5Z9eUtf8Q<|y*fnhJ?(OLKJMhZR4+>E#`Z*~^`(q_D>lMx!V&}_?GszYRYw>YP zF0N>O%KzTDbON+0s_6NvO+3arNK^;RfQ6Y|mFg$750kPpwi!RLZ0*s&_PJ_)7|#U~P#PWQX&#)TW8u%wFSL5@H1+-W{sWvUb$@sAARUP6hKF^iF zrFwL5;v{FJ28*R0&iYVltLgyNyE(ISE>kz{pck}b=`y4I__HCxaH5- z)N%Kgm)MuSoN5NS<`e#f4ll$pp20zXV&=)g`8f7T+vbH^g6J)|_Iq!9dASCni_xym z>UJ{p9vT#^OT1Y^e^983Ap^#1Cf&SFNbWG`bdu5jP}t9q6^IJ@0AKnw;#AFJUZ%IN zuMctr4!Hgo`CJg57qhTQv&QraC4_HdPSj|0;MjBD+ZI3%NOslQq(pe_Z9Z(+c8KTP z?|5yHN!t^_V9h&fiTBzCL3Ya*_NAQdGg)zHh6H6f*2%~cN&W=!rG%SF8evE3fN7U| z?~Vj{tB$OXW%1;aSJ#L852C-@g||2FFB@#rlu`fWyn6BU8791k&@S>IP=UQ&Ip^d{ zPYZ9S-A9_Lgx&Yr+D88qw9@_hFhTi{=04{?vZtvUi#38N+84-3-~yP`YG=NNiA9Qb z;g5i~j*JLM*8*)S*%b~=)$ec2#>qLc2?)a7w~{SRf9x*-p=7=v9EU|*T>DyX(%QGt zFGd9g-`qif&W6?^=|K6~z3x_wzP`Tk3a1?Us@GjXDb)rqXu!hbpetwX`02>rYQ4a=;FwH>*b5-`&yOw0C7L9$2;>8NSYZR~yfLAf@O}Sv@s%L4`*otPQ*4=0hKkkU_;mAMm4yOs2_ujZI zVe>FwFOXTx?$sgfNXoZJgNL8v{M}skuQmztqclmW>B%#j8eo!KJVFS^AZYc0bel25 z%2S-h<$!MrXH5-BR6Qs0H??+rEB3R*CZx+WXa-&yU`eG|u(X_Sno8+a7#~YPcr%BD zsI~rw_Pxdf?a%x_c5GdC{#SFrnbV$8wjJp>RWsrpSEgKK%jcQeOq)>-r`O9p$y8nM z*;LkdoBR8T?W*iKcM{lN@;xn_T}Pbr8#H==`gmd7eQl!rv4YT}tPmim_XQ|@br%7> zNtx6d7cy_gapr$v?jOSY*J=JYIliHnE(NT zTq6}3yJw)wEmfe(9ah-{8MunPxfznz3*)7i`Q)bdb~mzHyY&jMr*)fUlH!qf$;AcI zKlE1VMpiEPZ;HYd4a!zOQYxoQcAR?yAQS6#O>T+H&P#aT6{;pIl5~w0gu-^# z!rhc5iw2oDzwe)Mbrad$*PfwrBGbfU8mB^Z4OFmNCFJ>$4UIk?*DRRkj`|YrRF!Tr zpsrvf$(nyIH$mEfs@^h!zKgN$51A%UHsPz0RHs|g><7dZ1>C6Z2H4YfnZf; zU9Qw9N$+3!?<$@VUob$>uBi9Dh&Aq?5ZoI~>e1{$zThXLg3Zc0`}>fp`tF>g;jjh~ z&RY{@$wzs=vDtKR@7RoldUO`>m@<5Kyt%q<5N#M99{}QeXX?XbJ^k682^m1XaP@MW zmk@3jSERi&aPcJ`GB|6x^5;Z;>C*68uIvs{EA-5e{oKL>zk1a0qGE>C%^%kvvA5*D zw@DLrWF5ikIO4`K8I|1J(5 z3)F5$2US?Kv>x4_u$aww{I>gRB0PV)Z6KmQCjSB3{{n6wssaCF48=dkBGL7i_MuxG*rIw<6`W6; zVRSNGQpln;6-->CGFgNEp{gh@KP7ymPv9BAm1e?XHBAiwmsP_L@IX{Up-I_^w9b|V zlVgt_B26Q+*heA&$13Em{rK5Kl3&na7Kli~Jb6rg6){CIZBT=A=YUdulK48&Tgx6p zRX)Q7@XBuPTk0Ac79`mZRGLI+k4HZXJDee<(#F5A(6$`D=@}4A%sAf`PIY#9&JWgHVHz45>I>yoKvYyz zF6&o1-tw}ne+F}|vKu}94?eLf(Z1@9!+XhR{v`DMolL@w{Hbd1jT<$t8yOEQ;~(<( zrAi|C_2(u2#ln9EPd7zPP+afb{MXDE!p^LPPsJG&eqeNrM&A8dE=O?z1FlaM+4l7V zvYXj+P9-cNvXmaDc1r1*~yh^@W2l$h6Xp&-08gU@KdZ&aYSHjZIk6qVLgP zEf?a*3fFnGeH!O~?U*FOYV$HEcS?Ip44PJDuJ7)99KSSj&xFFGRr{M;oukNAx&k|B- zsrV@pKC}oR#5gIRDk4C6Pmf*O*c^>f+&kn6Asq)foQPg(p(T*;)9Uy@CiTJpW9_ZO zqT1U3VMRhvKt(`7LXj3xX-N|$mF|>|p?eq+0R;&~q&uX$V+KJ$TIn7H>8>G$8QwLh z&rzRq&h>qM*Za?0*X)_S_geS5<8#Ma_e}iplPBL!o{c|$P@;bfv_G)?JUKo72a8`; z1}_PnZ!184r@YtYE00oi4MkkGWP--AnHaVhraU=G3a|mxZt`~9U=6){6W1-pDw@Kj z&z~P{YF{T1?qu*eJ`(WAfnS<)S0kDIn9XX7`gz|{8Hr3x@zIbvLojmxI>XN{ZyFbbL9w^SA+m%4pynoY9jbl zNFx|^PlyM7`ph3c7Tj^-J`)S)VnD)n7?JZ6L2Xff+lkvXFQK*@&7wGsR>is9oR&mV z(SL6E*n3FT#K@v-x`Cp~oQ9t(Q^6L(n;0~3Y_Go0_wI4fiRgUh5bib|d2vN2v+q`UAf@RwNQce}i)2zGyBVyIF6-?fY0XS{o8fkr4fP+!l70=~%%)MCT@ zob?2XMM3B(=z5Mj6KLx;V7GUqD~11FBwk+xwv%Q+z&u!vkES)D;<%#!qtxRx@3>3@ zmrFEiTP_`=k*8zx-Y=0-4awUj@~lUikV#~7h?gXbHkK@LHl0%zte)c~TC^A9^4>*+ zu>}L()o*`Ix8pu=fj6dyL7j_7UnN}pOSS>2rC13AMpe$IJ0x;esm3;?>47C4`b3O? z{_I{w`r|G#(S_oVRh#OmqN2+F%NV{l9(kliu*udZVT}!*rrjm7$w%2J1`;f^_wZ zeE>QMLFPj_4S4c|c#H!bu1vHLF)v0lU1K}$9p!ZUWwp;Ye>C;-m;}gN+cqvqCE=rV zUEz0j#fLu(cT&Un7oHhZoETq=4p-Y;F|L?L2&yM3!7p{a@Pc}Ko{%m6(7>Dz+uS2? zy%b_>tDR2@LJPsy;s)?%hOhXe~cX4(qJF{m^O;@ zAKjZ4WZyH&34Xrf$h!Ff#3aJrUpleK%7^%bhc-xkTIt+xa*WPjuK=w!1ZJ5uQ_|$!-+8^*RaIu;+tc?eI*D7^7t1&H z6Hg`uP;PA)H+w;Dc}1)&vfY^kc*RdWvxn_n6$rD`)I-FtB50NM4nRcZq>g|zAwLEW zZ&ft%E8-AOO49NSieE~H-2xCFwnTG~64 z9C$<1!ns~hM+So%d6@aKmv&bs@V!pcQjhOVR$Y^~^4&uyeb}e3p9(wiQ42b3Psc8+ zaCw#lZQ#KzR{h~4B7AbScf)06>E$c4?$#_35QrrQu}-#ZkTYGUYj9ZzlGZ~2FWTm2 z3HcPs(D(+m?(P`pm<81q{rRIxJc8URb&w4UQKM*XtmpdOBoG*4ye9ZS4CWa`!J!%c zI=F$7HS^Wt$pc6xHx~%X-mS{q0&X6y2vn?fyQC%@*ucyecE;29l{j(Pg#RzR03_K>_*BY3YE|azDnHQGu=N z+fW}S5M4j{0O*%vQ8Hxz(L7LUwQAGT;8gj3DSdn=Mys4%Hl}5thrlc4j}el6Wbh_r)}S7|_7ivh1Sub7 zK#V>@$d>b`<1z8L)>uMu1iE{-Zx%kGt2WcZ5L{BkK{6|s@Em&LeAGepQjl~*i=IPaWo;+)6488V{-l^BMJ-^C$Ra4QhEv+G< z!amkRDklF%MZLss`Sd`XpyTj8F{-cIsnGjO>gC+;4}_fYN2!BDFCN4>YPN8uyf_o; zWO$P)%JC%y9=6I}IS!v6c=f6NRwm?$n32=#PiSrH-U=p4XzGb)pfiG_Zx3#K3LUs7xe`Srd|%2uEsP}k8LB43#fOtVa3dya@s~K&m@!}M@z1`{8aFwH{+{1c z;+#XOFTax4^>}1-*JO9&>%*)^d0JuD0vj(2a^K#znn|x)!D&STQNPKOe)n&)8j51! z?Oi0D*qi=J>|k8B=%l80;g9CEz)fAM2wZ zWmf&#PcRr22JK6_M-$7W9)qVy=13rm%C-*+HmrlJ( zoGX6Zb8TG-w_htf?#of{Z=QoShaKFjC~**wn&x^{JI?rIS&cFtvDZTJG)k_>Pw*v< z0onJ=bk5&`jyPltp4B$zy|=VhlhQD)gGZ9DNIm=whOeW52kQI9z?r z0IW}-%es)m_w|u5Aby(<2@>v9_JWofb+EKN`=in;e>Bk%cSz02fGLRd;N zCNj@Et>{z<4ee{lyDnKg6$cqCUn3&yJ4cO_hXL;wf@*K%5cJWF`T$VbY{lw)jt!>E z7XUnno!Jfcx_wuxny0`~NEozM3e~y^dpx36&C@a|QIt!RMV>JA>O(nZ@o1VuannvI zbjn?Nloi4*xj>$^BJhc+h-OKjj3M}_y%49I7C zJ|;jlP&!Eo6~CP#lQh82V$K@mNY#*4ZCD)JU2{8})+6}w8A)ZDusmN3#XHXE zkC*dxIdo6QM8WCLcc-eNgl(q8dE;(8!e;BVYZr}HamRmB-n|!Dv%qaBR--G{S6T-* z9^W@%5!)w0gY@NNCmRd(Ue2b_bdhR`IJi5rY78|r@Jc@9IM6ir?dA4zBA)g7IfGi7 zm(^VzpAply+jPIg?Aka_!Q(H^e0Q8f2EZb+qE6;Re_gWwUdT-~U?@f7F8tW@&!(4- zmwK>6R~9!GUSC!5g!=C4o9`xcQ9V*&h6tK zdN!w84hB_r(Y8<4&3m{s)iVyf%cu(-u%wBJiTN@XUepW0z|E7fKzsLhG)_RHr!0t1 z4{*N~B`4X;4Q7RiUIW%lX5U>1?4zr#YCpgwk8`}Bch&&6!nOw~eD-*s2P3I@3$nR*x4Ydp z0jia|AZ8Hw$mRu$O=+M6b5?^PHYr~gEKgKUif0}u>Md$4m zIMmwo8t|M&F8K(fN-Q}s=`HIlOB>BnA}X^kjxGL}5eC29xKQx`%27I^&ZiI8zv&Nc zt#7^KT+;=aIkEUhUYNv%83V5kmOJb1clE(w{u1~WRr%IEvssSV?Ruk&iSS}90Z z%S=+s)sJ(LH3uA-_YRj9IERZ2Nc{J@{>I*355RE>Gar8J9ZryVcH-^%9uk3g0G#@% zSMHt%$ur!%voh*e0Hw?9J!9DH^||SS>B|(D7doC zbwq^@*3f?hrgTMvgnGvMb?-gO0qVSfkb@*x?6=aId2CP#D)g;&xv2XKlKP?6oA*vb z=d_ZE*PnC*b?SQ9%#CqXys1(f)P5TiSvdZ6-us$t*iD(LQ40adXx)W-H}9XW%(K*H z>FVceS_R>q7nG<@%nD6r(0t}%k$EltW)4yVo6VIU{}#iW_v)0oo^BiLwP)b!dc9@? z*vdPARk3r&F}~YnAjtHxgjN4#NPp99PvOMCmOyyw{;Cg508W1S+D`6;xvhJ`kJ6r& zoPKrltDnpE6ve_t}0kjO#vOh&oG!?|3f6#y=2VURgT$QSwc!5-nT8@r(5VHDtslD%q z?iu^H+E!}tOb^IeR_Yf?=L>_aUrpRSV(Sy}2_yvIGn*kmq_Lq~Aay(q zTdl%K%fgp#ft(hl?dd*US5sjeh^eBN$KjvzZCoJ&(oQ{WW`0h}wBzBo8|vCZz<%+h z0(dK{AxMsbh!E9`F$6?b83qmv+uJTLQFqsRnwqlVqNWzXN(U@pYgO$Suiyo+7p@$* zmIArE)22TIkbl{WUzzDe7*It86BCU;FMjl^<%ap&j2%2tR;9LCv@!#;ldH% z2OlH@IJYBU6!`PcfM*FAamGjHlHWg2`$ux)X)YK~f7q3uN7X%IR5)4?wcP8M2|_0X z!%W$BGL_}T9w$idN`;;+pIJN0e=I7=B=()!%rznFutvQVvtd=k{dY!!yk^Yv;oa~k zr<0kx8L~fOYlbe9(T#;%f3;Q3jhWAlhWl^BgAbFDkVd#*hlm0}TMzJ)fE_R0eHK<7H;m|&P z!i`LF?21s`$?+8)q5@DzQ=x#RKFC|&LUQ(h0EHc|`*;Hjt@=6;A6T4^wk=#gsZAC1 z0XUXxeRI5GF0d||0ffT}m3h$8(FH968{=uh6ds;%$0b47*?@!5SJCpz7uhbKBPg7{ z4PeN%iEaAA`1uLIK1}>qYr$^wuan!909V(R^F!AV)WO%RH@etBj(cnFAo~Nd-Z&Xr z;(M9}Y!ho--Pxgn#CCkT?jK4%Ei7!Xk%4j9oc39iY_9eJ8sgZHvQ@%j9@!$~953nl zw(f_>DsG1Qmbx>6R#AI;$r^6PP??yg|VYl#%8u4T2N^G>GDEkjfLoap{sWR2K-WJXLbIS zxaZ`V(s!5zTs-)!m)P@11$11g02g8Z$YMP zo?9%xLS#*ECY?b4DFk?Bh2EOU^$^kmqghMf+a#^^c-@ddmKgKwYh+)5Et#a%7y1(0NEiym>(IzV2x zdWw>G-Kd>?#u%}1eh}68q5B&gBq9pt4EO0|vwtbl2Ihzbh<2Rp@v6U)k-r)0pQ0^> zGe`18AK*U>`>VSNb@^n#8P*I!tyd%TRZ~(v1Z&Zqp-$Y6mUe1Zp6E3KML}%?1ylx( zJGf&J-V^0U1z7}R{g^^kIXUYCW;EMrF5Q_e3tzs4ix-v>pm}QpwjtNjWFg?hJc$g| z(X`_UdG-+}<>Nckd6SsLU~3INLeY;wap@z4#H={%hZ4nbbq)H4&X^}b^bMEu^!vZp{ulI(0#y#QvM#7q~h-^F)4Uu1UO zcv;KOn?e=m!5a(@-Z2$-#s`64-LlN+T0g@_?MbWONyU1f4rit}h;SXe2I{P`EhRI!TH^+YJc zZb@(PPeKyEsHjPB<_^+jCJq-O`a8n^xXP#j)LSz11mRDu{IN^|S6V*>Y#oo%~CT7(SY z;yw1B_ZM*yN7W$KDJk@P()j`1G02s9nb|;~f+pKuk+Lb)Y7AO8!@15CJG~Rpm&i`b zQ@_gw@7Nj3|L)4X_HsL&O`X*npuE5*{k=%yNwF7n%N%Rq11;!+SK^RbJYuKTaPncw zwd=Q9BfSe|CWuG0E6C@%Q%Jk}qL_qJy(`H;=I_z~Hy$=Bb@{oNpwr|fF{>)Jg)dYC zodby^U6GNKgSwLSi=4R+Ru?gxuFrhJe2kt`;s{zJ%=Sy+GB8jd!*Na^bFKcDI%_jN z=AK$X8xAMMd<2krvy(a{tK- zoA`P`zj`$MDz{(^(gP#+fgm33PVdgwf12)vShmI;_bmCU+$i)uQJ;MQ>*QvgYG}@p z{oFg~w{PA>Wd&zE7thy(ELgDQ!>&!gn1E}S417E^~_7pVvpUwCUs5D`n1!BZTbu_XW%mG}xINq|0MK zS4dCK{j3EL*?+Uu6Giv><~DYLZ@%TC+lF|srmlrp5~6e&T~_N@b93>usNiZ}HzkUd z45qNHWowu#c1-s|Y9x&7^Vd#l%|vvy7smUGq>{ZU_m)+^EJ76Qa@?58$zSCPA^6DtaE%s*6#GjV>){%&~W8pc8buD=xNyQV&j6&mlBdO757e#iE&-W;>*F z+k4^pwb;^QRlN>7lr5F)i3vrWv;)ph0vj+<1|t7ywsjPLp<$2D9( z?49u2$2J9H{)(qbo&WdWR$Y!#+}Ax*(Ks{{&kal4&@A5G5jF9dA#y~>bkpx5w9upW z-xB6YtJK0{+~J9N#OKZPyxs8BXZNjzwSlQ37peIhXqkSX8W|;jJ+eG&yt==C*{E zw<16xv1`(SF}x~8adGL`SZ;-)Ds*eB^w9e9Vt04h{)(~+-#(KfOf}43pCET(!>7ox z)k6MLWUZ%)4@SqT$`l*GKqV+YRtsmc*xaEOqP_bcBCsI9JOtHgb?;y#!Ux zEe#jr(L!KrKC0*)tge~%R_28JqUaOc(a03kw)XoO-&Z}|-oEkl8wc~yKgIs4Wfs9 z%~x5!5W@G196q`Ph$#I$?A9;+pMT>nK*w4hd~jZWqfp_A??i2RE3w_=HyX#|yD6)T5z4}Tp6U$xeC(KY zuZ6RSUFB$xkNEspvtdsDUU+bI_J>ildM97Sf*tb@LFMAI=*X^xyRM^+HXOGG&<Ff1XnND_-NF)mSUOyh`EyBWti5fLG!P=354p^$d_ZR>r6B;V4u&>lK4uNVF} zfCmp9l>H^LpA`Cwkg`$WnDpcIf(QS?q&9&-{q>jgaDG>jQyK|PlXtez8MWAnHN~Eq z3k0b4cH-#m#m_HVi83B<-PFkUtPs<@CT+DK&^s>xFXd=#Vr5BhUTvjxzaf`QM5~ zd^8~>;!QR;6~?svU_a#byWk3c4SnQD@#i%!+Org}+s-<6IW%{B3a#ZLY7Aa)$>B}Y z5wwMs)d3xFrT^edk?UWy?4$z9Z*Zn{`4^i1$-fB?z#0U6l*F|N!f6ki`{PNh*4-0< zS=qS(jnE|e9O0WhGLiG4%1dL^OXdsp6n zs;;U9R)z8#LxPGU?Lr)L2T815`LX*`QeR zyXN=0bYj!ZE`rKhO+TpJbx}ZtZq(_{(Vg@oez5 zlNxZ)u1Oo&cMWJG>@@~#;j^tsFU&5tXF9M!<%iG%u#o24wO`q+)(Ysws`khEr+$6s zA8)V`2Yq3domsMve>dL2)U!N$WbL|TBSSOQ)M832_8p+S?_>NUHJf|E1z;%GC7bX6 z`WD7Kpd554{uw+mKCM;9HBy=Q@n)|x6y-~SU*;XF4fxI1{^hmfFTvu8t|<*td}kW# zOZhe!k}Ws$2q3#%5z$!po8`#uxdYR&A)`JHm^&7VgNo|6F!IywJ@>3`ntdGz9(_W6 z1+*>xb-oD_;MLU!@A(j~iTpOuabqyh(M1V0vfnQMj;PB+0k1gUB<*|l9Y_0-d{Z?NN92G3 z-qAf`dDu(zCox4dfozz>b5|X9SN?-*e-ior-Y25PgX^BJ~rN7>n z;Bg#Kgkh%b>hCZ4ZQ8Z$V4`vbUk+QK0~*9oe#*m5G`2T|;n#UGjuYY*b^MeX-fx%x zSkx@sqKcmH!?j`q{uEf$9MHrON-kK*g}p0e;pG4K6g#988IEibugHFo z?U53WN1an02L&yZ7o$}B|Y>f7hI zZqSmCG7sPW?f)$=k9cA1>^@sk{4Vmp{V4{wT(4+;f~bT~cxf$ID=6W7sn{`p5vpUq zOWE=AM}Un_tVPoN%Ogj$Yu9SAi4+wm-i3Z4jT-B~J>4#Ox=u4#qvv6#p8f3)2Mjw0 zOh|?uY{WJZ{>H|KeI)hV^a9bw#xZg6wGBi1qn@7AGbX=(%L|VxZZMv4%w!B=TA{4+eW2ZnL%+6jY{5~`o2;Mc0J?fWgguzGMKYWr zH`~#6HeWX>;+qTebLi*7bnaufSF=Qd<>zX|F1by+k*;r0i^JCb^Wi$usrzOJ+qf+N zN33B2S0F|kXw8g+#%SVy;npKZ1t{3;^k9A2>KdT?^WOGKJcNMx*TF>S`qbROU@oqO z7(;iSsz8SFu%gjfhFMW29`5laHk_T4iZ}Cu$(B+Zne1u^TQ_04Z`8!a#n(5Oetfu% zbOw9CCegwO@yTt!sh#cj)+n^iJMVwt)8lU|B|wMVRJZ}lck5l-i}%tmWobn!V@;t; zUp3Enx3x&Z<`{ea-gz&~x=h{JzfSQFCU!mpm`v{d2aQA7Zt<1qsP)|RFDx)tnRCU1 zUsP~m1x?+Y3m1PF?LY4R+pi)I03#C7v1lIp>TJwj)n3r}Q|t-m?6Mua#~<9RkOn83 zNgw?eHvLu4;6%d49Y~io?CzCQxSML1@Yhc)sxE(XYJGBxo+E^YJJQ(+%p#Gf?Kche zn=t+PNQv4|oGt4zE2PFv!mA4io9@kywl@eI$T(e$UBA{}3&$tvI zSZK80MW^HxeWCr~CPRWf~nz}tsvWz>%_bAbV* z_?!o=B>(oYf4AOj{9u?3_nRdSX)<-cmcR?cY(YLBo?2C6Gv!Hl)2&cqKH-S2_Gh?n zhwyt}4FS-iitqMWmFp5>V>(mQFGSpu0Z`p@8NBd+=Si1$fS)^W$~ztEs7Ew-sb>e| zAIS9j@d#M#aSuBP-c0-?%oDbQcFIZ);$rHlz7=7vl#viZ;(3og{HT;VST1&N9=iYg z3mM0&!5e3mW?$l1?2!(E)Wv*p`>%2}>vK^&&-T(3JVPrJ%^zhY(e&n~ux#CSTy%L; zx+0pprRP8q49qHrm^#AV? zdBkf1xM{lkX|E0=#N%^#%x4G0-9#QAxLSMhFTD`sQsWYNkZdg?*^jci49QFKnF?;a zY~Gr|cpzRCtm%b?p)RNzC}b{CWa$-%>+_)piQBx{}Y4$^LU7w_jynPg{Llv$@1DHwkb*VfA7-#&Jxx9kf)!A@G{q>o4ZdnU!zmtriB#KkCYkky!!?#WeguQs?VO8WoCc~i<(WQON{l8uBAw{kAC_1Mc*{|H~sXs zvX)X6)h~O;_w8P_%&gl{EPQ;AM~~nSK6=wRRWE$vI;(2r{e-t2Lo9}D!I3U5E zH`f$+NZhQWQN}7EIqAXcXx4B8!Oj00hsJT+%xF8$t+B?h?gtju^Wb+-4fv7#qdxJf z!x#CwasnT9Lf9zodkBFsSi+VFh0vu)!!%*C)$uT0y@(~-drC5n($4mZUc}1`e7CUR zeCUAf0*8Jaluh9jF4hffV`_kQo@kw?{D<+ek>ka!ZW92L`8BMC{!kwLl@kO(K`}Xjx%Crc zM+ZgqgG#b5nKTn|`j}^@v}RsQivkW%TQJkyAi6c_bTd|C7onqrkB)aBZr>DNh`F9X8Hh6C{g}0fv-@ zgXe0)q+kU<#0FPfd11}*O_HAEGxi*8Ntm)vd{`)=7Eau0LNJ>}_&!rb&40;I`r$^` z>+(gZeRbvCP=%$Y)%KAsz_#~O&$eC_WYmU_p{y_G*E|xidZ34tCHFP@Rjo=Sf)zcn zbz9(}w+AjNQ}<7*@1Fu`E=`$M--qJokws1}})D{iDt87tF~%?~rnQsc{g zr!=3&5`(bT4RN9;W?LUg+k>XoI`ooAtMrcZX3@Zj`-W>KLaU9GzXo^awlF}uB+cef z&-TZ36h>E{^b*Uf+-*?uAxv#nnibI9P6?=mv&OQx|B_Kk@E~@nJK7g;{cD7`>F z--SBxcBmG-6mzQ7wBp!#pLHwjNiT`)!G{hehwpSY({o?NT1zYk@HsXZH1gunAd{3bT7BRyu8b>U|$tZ z+%|J^U6oW$IVb;Y)o57Ma;hOqHH2fm$w+ld{z0=x6P|E*MxAb+U16rGRDpHWwGW=U zkZtmHih(lw%Hm(v<;YRzv#ZZ_)2os#)YT}wFoiZ!*{AqsL|B}o=vnC+f0CQIZ8oQ~$I2l=iy~s5 z{}_48gTfl3&GR_Nf?4g>c6RGx^YiU?1Qe*sQ!u+Y+G8X`-Wk;lv(br_;HaPLy&9p! zsNotp7Wah+;m-!(#M%)Z6hjB}`EWCT9i_tX8D_1j( ztq=-&QP#_D*-C6OkC6DNqN|Eu;PM+370>o|xjy2f`d3bLmDV4u<@J_tq-;RckT5I~IOv=>~dki3=SrIz;24ZzC9-Yh7WqxS9-15PUg!n-yBF`do4Xh;8lJ~cuvjEUfU?tC+MXHni;-&mX zg6}MABm83}%iPrq7!Oy{nVQX94~ah@zF(AC(r$eE;r#H8(vM};PLL4n2)&&fy`nNg zK7fL(-J-8%S0aR;{`gzs+L;;|$2~&j8};ZdPS#eDtFt$hcjSq7Cwa2gDOWHYKWhP^ zo1F5FAWvrP!FNrRC&=Z(Du_QU8(D+ej4sxqOE4`bWlxZ@>@c!cN!PjFkoifsMj^BA zSy#3*Et@6Msqtz$sTU@Rr0X|8uf=@0mSNiJ@!=qaAbzXwcUQl)Y9!Ij}C6oxN98IEiyuXVh!yFkcZ?qYW;@%ej&>b4w5LqIqE8MgohC~Hfp?kCl`Y~(cDlT=c;=p ztKMFjk5g~IERc;U)uDKwSJnvm!l;ErjOBft_P_ZqfdPh0RS!7mO`~ffiDec1BriMf zn`u^)4b$J#Yh>Y4cmF((Ug8YTaGZRGtf+lHEBiv6vkgKox$J+{VL6*H>=`EK6oPmo zdKJEFYJJ7#+fXr+#_%@1INi4c;q^~*w3qFI>}|^`-JZ-=WU4ZKeEqf45^QHQ_1yd; z+47GF0r!K{W1K5#z;nn&PyLRcy`B%leug++;eSZUxntJQvmkwv8RCd>4J8y*dJJbf zAq>2t>Bi>-oGA7Bo!wnFX6E+9i;(j2mr(*I6}y2CImW1!coAEQ=0@5)0EP*RDft>g zIV)~^qrnMAF}5;Xl3Q8)G9PcBWnkq~i4`~kam+(a7rP(qc;{9h<+<^!@cWM4sWbid zPs&HEh!=$+lJdV|wtt<>DT#!)I9K$BVD}-yaCs_m8V{XeHfL@>%6lSFG3z)KYk)j+ ztXW+frk8i0Mm$sVWqTO1w!X1VT$>Bl7p=<1%r}||tm!ypkdjF;QcUcF=L@)9>Jh#y zhO|bt))^PjhK6sWXR(wbY{<Uc@BpTn$Av5rM`Ogs+)_G0BtcbIog{l>quK;FA!N_ z^Zq^p6TW4AY`StK&7OB+k3T5zjvn$lx5n@JivQLQzpB)$X8|m{?UD8!FC^pLJH7~8 zzmw7ks~#HKp`N^|;z!jhg|FX|{U8v{W*_(3d&vCTcq#LZ&Ot)$LR5lpU?fCTG{NLf zjRVs4UL345QP64_szvL3p$HE%ynUfR2wHHDzW?MS;Y$OV9lAy41ijf**&52;IeE%? zXHq`H++P=l<~3NnWHfqgwSz*mr%IX*U4Lqz402EUf8n|Y z9M^dqkvX)lj|d6;PYp0&>uz&tlpu#Tk-B3E2@=RNN6Sq{4B9o}{WR{47MPwweV3PQ z_NBMPBPlc1-dmq@+3B-)oayC~w#1GS$(e2nx0ZO+U$h9ya_1|oL+xr~v0@~7=Mq{H zk7m+PJt5d+;vgE-(6sa@w5Aj7%-oN6934Vb#8oFJ=U|0sp(6H0I(y$B3(^-U_cy_! zX8_@Jp9C|Txy$*#%#0M5Q2cN)A0Ky<*A13OAZQwpg~;c($gJp$7fJZYKQ=WDd4e}R z?H^;S__E!;)GIz}CmbGIHtOcK-Ywdjd?)9OcD?fUK}ya+qniDdSi79MC0}H$TJI!; zt9$!|Q_Ql^@|bmHr8ASCq}$FGb5xB>c<;(y0PVu=fm4Y9p%>I$uK4!^)^~*VPbzLi z0%QPaFW^ZZ{(;R9PY!Hv3RUR!TvhEec6Z9m*#>s`F2D7&J(he(E){9r7G?n>^(5{Y zVGZ_+ZZS4KStXQUg}j(!FuW)1U0fo6KQ!aj$&CA9BpN#(YTrc7Z=)f2p}6TXW!$cP5tGVl^fVg%j}Ql&mLWH|?N5Byir&D41{$ zLDa!rE$oG<3pD+i+5dN${{Cw@NGd`FgpR)hH_>A7f+=+FWTK%G7C{o< z-x5k`gvzZFq5ef5I-mvf0(PZ*Pr~_6?``hF8-(`H8)EWJ!|9=hFSoXY2}^sJ?sRf} z*|j6Hwmy4J;H02MY}C8l+%k`>o#$r>_Ryw-CjIIRC#r#k9ooHd`hP%DkCZ@+{T^kC zIJhT-S&ub8KEAJHDODcQOqM@mwb5&C_PNOf6wPY83g!uE?`-C_Vussh3M>EAy}5zUfI;a_ck}OThzr?9!lTRT z=M5L`li{JscDv5~gX{cv;%t)&m`Zh?M*sx#-aRb>hgRAsYnn}K@49QP#ce7Yf6_b( zf0I!T$sN+~TAl#`=OW>ov;&^8KfsFjW)G%2F@9gF3CKtPPd2> zw5nl|(}j?3ERJgP&UW1%yO;EWVhl5Jn@g(#Ni$WY%B`4nKP*5n$#B$ujPZKDDpMds zZ+qg=ce%pp!|{=jt+~OB(lPh>q-SV~0q0NQjsF*+`hl;X{>;UlmZ&YlU-uo%@_oQb z-(1sFe%WkTe=Zi8io9emE&zMmlV!G?7dh@8`$fUrZMr`mF5`xsS>#8IF=>xXEC#tA zLt};?P~?gifmn&zsOMZNG9@SS7GxoFoSV+$apt**-2pkh1HJ5?1upjWM<~H#ov+i# zL-(N_F~Sf%*jK2+WF|_7w)b`+v zzZ1X0mu&#i0r}hW=g*tFwukraw9os^`3bC7yL;6{T9ugFZc(dL`BUx}8<>mDSXrE% zp^cp1OKX8wz|T1s+$>I?-q+)IL%}W5Pz*t38o38<`TK3cci&D>0$=K?0L-vmjeS73 zRUFZgIN06A)3Z0!*6*8x#YfStr(XXbMD9OHJp5CuSB?tnqq6Cu^UE_N5T=@?ACA?e z^yfBPtq*z3C7zGe<+=FH+c1?L@zny9* zgmSfVpNke=Y+tymCvK8n1q&v0oATONYM;`}f<9iG=kZAE%>uq56m?sdNRrKM!;{Ix zVg{~ekr1Ysr}}^ZkwotH?sQNSbJhY^r2a08;~hS94yTl5?lVI858PpXV{MIoez+v) z&cZbl-3tHT>E=~ex9IAO?z=PxZ%Zg})E<@FTkaUi843>X zTW;MSV&+QGU4D(-HgpPuDjq%ftj2zs5hg8pdr_Tf6DGfBYlw1LA$zk7zqVm}%Y6hU zQdH>KL4uj~ea2q)K#V|1#QB~ca&c-#RsrE$v^_V)d@tx-)V;IVN{37N3>7@UzQq^@ zVm@;%ZN*z?P>Kapa7|-NRGFH%OWnqPU?PfSK_v5aA=xD&*)qa(P0_oE8t1SL@4?v$ zJH@xwp60o|>+2^L7E1iC=6}iBiEfKP+>w`2GbR=JDaQ{1^vnb4P7Ua^Jbi*j@3YRa z_*(d#Qr`c?iTs(t2HE2{=5bTKgFu3=V@M;~kskJ-ZjP57Z>N--G(fhqUAm ztQw7Bn91nW;mT>qoQ&SVn=&Bi8w>}Q?jy9J=lhUOf>rVAq3T6tsvl++Gi%}M%G&}d z;-w~eEA0y@kEtmSDTK>jilU|!EEXRo1N9SBLK5HflIjP7$%&IcxsZ^kT54l(cBU%( zU?x2mwn=UAbWD4GHkQ>*P&^_qPPc7WvQt(^zohy*@K;FHAwV!<;5ou5MX zWJ0K(5IW>ov`uyK2;GL0w}T z87@%JQb4&Z#J?TtY4eCd(yNNR0o3xmT-B*f{a}UkjZE)eT`t%<N7KQIh8vY%1{^43}4)Elww$}0mK^?Cm zo)aFLH8eHnahJ4xs##WHnaQ&y&G>gwO0D}E8kI^jW^;O$)00@M6!rR|VZ>^{=H_Bs zQ`$J^vGX^<-M_^eB{-}Re`Eu&-^}rEq(#DoMQArEh*tFIYbA{3C*KAp2Iwb&Th zuBjE{yaG+{Hc@IPq0<0PSCQ=<1p}b zbD_Ppw^%2Fr+#3$8#r2Lf$)XmwOARNX>CF#q#OG4hw!jQp3rRegK>~El|HIk&^d-xmgY)ih>N>MQ9ke+h$tlRUuBQ3V#X8W#U zc=Vd~Lv}M`qon)71{x@;=H%Q*~~MHsy%!T$gi-t7aj(G$T^IKVV?4flx;rQ;0yD_3hn-xKB0W5N`JBXWwS*QBZlTB8^zPZTRWY zRA=i?qn&auFin992it{cAA*O#Qf*YQ`4z81`wZ0%Z}UChJ51{7KINO}lz zs-@O*fjU)|s7Q6|>nSs}vbrU@lZ(+utH#y?aTrJ81>zmdN&Bn4;Gn@o@m7=|w5Hd6 zVp6oH%z}ShRRY^RwIA$%6-eXHX3mF}(l`h?xr@A_Ee3AO#>-9_j1EPHNS6xlQ1(LH= z#%0oWUl+RKBPqM+D%%2&u!yY0PZ}Q)_JZ;>2gX0>Rxy%ycD0yms_Kjx>!4R%d41JI zbXyo-q+6cG-W5A+tE>l`mztYqAGEl!aw>mjx6N6cZPD&hKJozm|CM$n;83=0J6d^d zB`HgiEK#8_mDd`PJ^Q{yyqRoSqcMs0@J3}{vc?#Lv2P=?M0R5^FH>Y4Ot!I%G5prjZIrY3Ab0WJH5)eg8-9)~WEky&wn`!xSo+WggA_JumN)LrPGTx9RhGiYj#VMlH=KrT z+!>CdXiBh*TBU-1$?dA3#KjmN{N$kH*EAugG-dUcx;?yGZn||fgY(KDqJpA2J*;v+ z$zWm$>^UBA=h|2KZFv*4#`34w*XpuC-WLX1jRPPrN7_x~kDD)vuzGs#noLkyA=_>E z&HF*`zE2Oz)o8ZtV0TWRyt_BJ=ar4LX`8T7zR9>2gIwTCo#=M?bl;Uw@4UD2Wf5I2 zlFKCu-SFnq{hQ-KNHU_f-1eqPay1RTYQBZ)TX{J%sM!BB103;uH9>< zor3(crw5&KF36e^W?XTv=62G)S&X7DQY0xi&0V}Rfq7Zjm-UW)#BqOhtA@@1WQwI6 zi)2pDt?;0Rbj%;aN*YMi=>T}Dt7*yf^t+j!UXY1Z-e_%UF<24jDxL}r(R*fi$Hw^s z;kBs9DfAvbK>A;1bB6|fsr9F&);t`|BR@aqE?zD0i+s~Z%~%D@oU@Z=c*;vZ=RL{e zbHZ~lm0XJ)`^3wRMU>bblv?f#SHU*-U)fx7WWWi3DMfmtW{fH^J`Te5xy-C;EVhn@TGgEFE5$eDFjFo_6hMIVPDyXd z1FpE&N)NEOUINI{K-O8T=9tF#?d)B9o6-1c>c?qN8Za_%+;N(+Y*{s&=<4FGDFqRU zMNleaSGH(@7i9IkeE-ERK>nsetuBe40NrZ5n4%%S8~m^J=Zq(SFsJR+<)3jZd7z~8 ze`sXSy6@P>Ba9JYgG=~@QMVp-4`-!bM2-yH_>-Le=CN?v>8jxb+?8}alW~8U0u1$0 zpI@F+Znuk#0Ne8iNz8ZTE1N?L4Vz;!smF}TD^Kc7l^@jD8xUJN8;vOHOq>W--);{zqOzQHa4()%d_sj{?mQNM+ z8B{>$v6Y5Sk{>FikLNX3Ew>Q0^HA)(1BQ`o3T6A!xoU`~(Aw=Bs#B;v^$uUy8U8=y~A{*W=t3m&tVm5^8NGbem=?8-fYPbad>V#tF$ zx?Aqive$Y89pYCe#yi?Q(s2XqW;yjcDtGKS^7|Dv731mN!8p<@`}#2vHQOj0N_+K> zzBY`N5lcmNT=JHFc2uGsD!BAADW!-{Y36s}Zv|?T5;r})L&GYr)?3q;Q{MXYBxb`c zVQaPH7I8ttF_5_FC(BF%RZmYL%l{LAz7xmYj{{wlF5A89+yC@JkU?}O%qPW;ixOJ=7CM3sk~GZ*Ngw z#&7hRBB=LP_r7s9;U$FugGwb?e=4n{x7w^QNzqBwyUK%{p5UZIxsA8abOXnGW&4vs z9R(bzMagkBw|{(C=j$?7R3JaYZRA{U_;MhQSWBZ^!kij(3#T>?fSu%e$$>agXjdZF z91gBv9$Y&je9=xNlwQRxQ&i}5?a9{Wuc4~3q%uF)Lk~38V>cI2YbCvn?9kSGFTMdj5$58j9(5$$pD5 zT+Y$73X+YDp_ahyLc4F>)xq;xZ#I1 zGUq0)zj0)m@oHuvF11PKp>Rhl>r9pQ|9ai*9bhKrK(%q1Q26v^@^c5bT8)R6fh(_n z)5wq_Gi?}p*;gGL%Y$Pwi4J`2YAR_Q!cg0Ib|prMmhK{oENJ5K9lNkW zVs(3R-P&dEG#~}Z>Wx;zAg~@o!{u=TaDlF*&eH|)it=es_t^Bj(}Muhn}4q4$4`%q z4JQls(1T}4k+11Yg+Y=^m%GbC4Xd)^r2Cp!P%`~>Lt$-ADM1gqWs-lSx3ffi6W zyb5J1wF|UW07W!;EW)C2z^y5`Tq~txBnoQH8H=)z9boQ)fC4{O!py+_Zsa{i7}sY~ zI^t#>(iP9J3C1O6%wafZH-Q(bT zNBkY3T4lhZxg7YNWyQ&*rck?)3d1Z6BLB#e|I}lqw!CSNIfAwRNOw2ckS-ajwJYd# z#rU+AFryCIqa=U5@Yx7X`I5J*T6ttb-O|*#cIHtsKQu=>VP<9^H-1PKVR=)t4Z_zG zc7xby3FLYO7)u!zGi{<>tjQ4!V45FJ5Q4yHfULhQI1GSygRcR%ZR7aIy&QS>0 zdi%wTrB4i+Ut#lPeJaLz8$tb3H5FwF2$)Mm@%bhY4E39Ots_h+n2FaHfF@^XrfM3` zJD%igrsnVzoR1pI(fKpVfxp{!?%n^o6&(q=#x|P(YfjSX1{q493%X3~r0^UIv(avh zSCTr(s7{p-Pb0$Hw~RP@kssp~H+tYiS&WaZcwv9Gj#$--gF5_?tvUvnTDNJnWX zZGU2V+;dZifPiFX=Jf%d<5G2INZ$KU>_mep#jid0j}7gZp&6?K;m^P+wh3+KA5wm= zBg;&K+J=9FPi96|TX{!<69xq$ykFKYMR;M3flk%)d`YQhN>&JgL-Q|~e7XJZn=u1b1PeL~RKh03BJYA<#Tl9bzokrc1(l3fc3%7Nl%DpO&)HgK;o#>rDYQldPc^YWGc z#-RB0Z-hY!CKK+h;H#m5hcV6Kv(tosWeXENJkVLMsdoj30V;>_EHP@eQ`wd!yrnd{ zEGA~Ae_!FfrFPyhgoT1poRYOK;$cf$+lZ7%xrge~bNO_j^ja^Yd43Yy$m`a%S3(?s zw>@yk<=;ENvJlo`!MJVQ~XpoUs-N7eD09%S!t65KfYd&%vti^HgD_a@97?U zy!%Y>mrPyR<<<#T^Qx#C-9xXj0D}SCWtF#|51H?=@nPM&>}bF^JA%f`Zuh3`%o`WD zEQm$FC=1aNEJ!hHJcy6f*X#}f5d*9%DliIj2A>W#ol*u}EQ~YF!*%ysLtmOo`AYe< z-AZ`JSn*AfmK3g0NXQnasL{<;2+)s;WQcF5MPVoBL<8UG$6PGkprPe2YvcHP0PTVF zXOKF&ZZkY&iUSk?!ff(lsfR&9$z7xH4^{i0@nP0{Vjf4X8W8fygI`f?f48O&xjO z_QB2ls8q;SzFV%939)^0w@udKR+Q}C6>5FbP>|UCvn*M}ZepoK0wqk{v6^Sn-NWs0A zP}_ZJ_LMpuu3)2Zpsh!XFOrn_JgVTC_Hc=J9`&0*0;uTc&hK>@zBIp6Lhfh}#Jh}$ z%M5xEoA?T$o5=x3jBa&FSe;*XXS^*MFAaZ~99uBE9Mf*881x!7M|G0b(bO@?7PM>o z>!!oVusskY^7Dq))jHZ1|5Sxa4B+egYdYKgjRu!@w<_DyZWb*toxB*ZoUt_svqnG! z`bV*p5-5!czt^FjBvMVtvvs};6qy2_mG1`_S&ZyjN2_j%biqfRp3KR{ehHp?#Nm5` z)8YP_u59p9x3x1I%}s;eU&VRI$3t~EBQSu5tAr{47MH*6tGOiMDpNR+gTP;a$5+wSH~GIE#BS>LW{2F z$iJL3h&3xJ7$DMvF@L5dQLbHg*K4WN@uW4i#m^|=iVXoR)*sVu?Yv2vAe|R_>mniZ}yWXMR6^iIDFv(&^u13L;oQs|5l6m_XNJ~KAmlT z)Y-Q^(btVr6L*n2{Vs}f8u?C5U7?~U%eR0k_Nf^ON3JO>Wk+k7r^Y9MwgB-(NDi+E zT#545cj?Ry5$pdApD00(h9T^|64YH@hKqp4Te~`Gfu%gXHB22n4wM|7Jfk6kb26Ki z{SoXM_5`nUfj^TjpP{$29}mddZtE3mU>pZ;4kNseYh3{zm3?U$pyV6fxzr~Yo;wj! zVbwLp7-w|^4}59QCs)%>;|X?uv11++khj!v-n3$fxGkVfocgc6K!5F2L}BAdUo_@*27ae%-@%Mb+uCI8t33HsQ1ccSY8c@F6~AUy0!o)F@m=~*HU4g>WUIF8Ueo%?5?1S80X z&nUZSZ6_vY&ww80mc6lmzR10#!C4F=d4auDjqVGe1NLU5722{O9`~CGdQY6-*2GGE zUxA)*oEFtj5`b5eH97^HF;KsLdy-Hv7wZmpPS#7*DNL@+u`{BQ@;m%uZad2}QabS6 z-#a4X-#wM?y<*paeVHsBKHJl9lzt?W8k@9&&?V7PqdeC&D?fE8pt69M={H}CzS%xG zNklgJsv>v5oz=Ibh)V#emTttT2`#xZ3fWp`WW11p2B4EY>?(9>6-PSsfji!o58UqZ z|3RP3JOwOx@ivZ)uDGh(3FbRyMldTQOX8y3l`8h+t_`>5VxKt`#Bt29gv>iTI_kRK z;3=EK>w16PN`}PZo+l6#Avh=kAQe9>ai3-_-Cy-;cE-Ml}c z=Mqz=KcPqM#$TThon1Q3c2@AD2_Th z%LAuMVUbs_+S-;rXeoPMQSp&TD1|PT@%nz5df)372xOfQftrEd)m@=xt<;}w*j#DoE4o@PzMH~5L_-it zr-xB;Q+3a0Q){Pv@Fu61*XH<{=RB$arotQlXD8BsiGtRkL!W>Zt=s$>`Sd}3HclSh zSM1Z6sM$|P&SPXp%gXuGLwN%(K?2zN(7YY+-oV$)OpDP+I(IGUa#5*ZkMaf>snAk3 zH_zpPzhRZLiCd>5Lh#qQ9B|}7|81^kur|o}sXpgW9r@pC_-Aod? zW1V~kPEP4PzveI9w_0L0k&Z6gU!{b55ZI9oKQxOQo5|U=kK>r~-5m^!-~Zu_igJP7 z&RmTH;KOwgZjMpt)q5Lqz3c=&3Exu!j=Z6-$$t5jQbkQSGp7e zf7j8kRik*18VFNJ`mf`BwZ%^C*Z@scC-OM3EQD!4$E<$KWen{@bN0M;3mit_ppgX9 z2V8xxFlOw#VB==};~L6L5RyGtuu4{LRsoeZgqH5)#|DtE~SqotK;) zGsST@sjmI1nxot`uXAZ7eBJZU+)JvCc59*x;E7tJIHVz%Z^H9dluHB1m( zk<+KbPt*cd$H0HwF8^unn+_kJ>4yT~`-QIRMy~pfhh5zdI@=Jo#~qK^tZ}h+wy`UWKldDh}Zdzxz&&YMVv&}(QJICWo_Sqe?fgcjYTDi6Bo1Z?G+xR0gKwja;^|&SS z>werkwO+nC;N1Fktc0tgw{wRGVhN$Cwr!tBWLv#_pta$x(yz7aDo!4YG(9n}{@me% z#(SSRhlXyl-dLk8yhyk<;f9WGnu~} ziPp7u*lTJSdfj>G#Td{1^&nhJC4cycauj#U!;4wbxnddW<-Yrhh?Y!0vij{VMttFUmm2XwDR33{?BHq6CQ4aZZ zbb+jS-jS_S2>OhX;nviq2*(1utz2MjJ*_J)!2tn!7pKoAEGwNW;5$97Fg=sXNz9-b zW0UBC8>1?hiGSmy>uOxaeX(FmvAyYMI+|4H`TysCOJ7d7aa@7 zp7im+&W;LAtsR|2&<}Hu6U4E+g#(2{9y~<9`cGcM^kGV?i4H+nemi&2>6I8k94VP^ zOwga440(1kq^x0d12MQ)ten*&W)cF|4k|}!sJ*DKH)~n}wy3VPptavpAqXee+{+9rCydx|DM{Y(QbEzY4+VjSKtsDpZ1x&x%Ggly#c$!s@@aw7lLxBM8xB zg2P}VVXX?qk`qBD4iERQz5z;}PUQU>FsmI)>zhu{t#4Mc z(&~>}=hi>L;CjJRG`C3Zg?poKE&9Z1s-9MNwV_3E*>%~bp&r&mL>yuEwbo*kU{C}# z3GscM9ZjgIz0l|x8a-dL4BXQEDZ>`lkD%-m0H7TPP&$F#h(S52xR;6=XI8@!M@`XA zqN^v*Ep*sQ5X>7nDf~lRM3-cd96FiKd(|cQgm6sFqNHlA>?s7JvTZW^gs@n{l9>z} zXLN#4&ybS%e*jj7w+niBaBd3NvP%dJt0A>QODdT~I2{tp5{0cuXMB?07@RUOU z?($8IkMBUx?|v&&VIp&VGPu8?Os0d@qa8z-&Jo18>TbSnQIgf@SLX$M%in~6?h3+%i?Aw62y94tqTzm z5fF3*1%3hJlWr*EiZceqtHC{0Fv#Vw;dPRJ*>(m6?Tt`S@$#| z`f2?Jc9@>e@UH~0YotFFII%-MkRGVOIZOpk*E*@V^Rpi0COrW2tvVUC_L@sD1gB)& z;CCtDPRtu`y|@X+-8cVozyqOkONR?WItxZfL^98Ok6acf5GPQpJBhe)raoeyMZQ1RdQlf zvlsl!dKfk@vqq@&og0nL-}lZ(nSB@e!Z)Il#m9HT-M!Xh20`e{A!h^q5Hfo)lzH#+ z6NKq4v!51Pc6r?NO;2HLz)Ue2oH9CEQVRmr)zm0fB?KJ=2Q4ftayxjP{!>1V@jo{u zCFNUjpkT5s1lJ^T?MnY}r0VE~e)oDYrfW6~8<~uG1Kh&D1hNUeEZs<2JZ|}K__A;U zi05?*Cr96IbT=C)MNaCs15=;Ooe!Jtia2*LU}R(@yRgs^$eU1j6s9-&m6sM^;-Ewu zS28d3tM`Ib8X0TifN+!#ZYruJgrhJy!TzK%WirYRl~!a%VoAjbG%4&zHuw$(6|)o^3~BlaEW(Edj=TmT!pG&+)Sjhn)hF#We)Ukc0w2?{s`7&yfbqjtc7(Swf}qu*yInxk=abte%?gs4#Bhby7w6A9XdWB^|O9z0gBC zM4+ts{d|1%l!?QaFJIJNScrviJ+dh5%;^Y8)*y(sqN)TPNIoSebIB~qzkz2v5LBb@ zfLW^)AV(A^lb1HQ{e#KB>4$j_zOT|zxg=XK_zf~(e-Wg7_{dyzfUP)*I#0zwsYMp?1BvvkA3G*%OpXL$Um??^zAkP25M6(-W@!x3K{X(Xz5Yj`K zUegAmY8i}L@w~eF8g6)W73_%Etxt)Tq}9<7J=@~KjAX7OaLCDKFQK4SO+8bZ!Go?KZD51UTnq3N4rD^4(&-Bd7J{@O2w5p5PKpxi}+*q z%Sd?$rnW_R+2>oGKNws?2|EbNX6B-5PP0?=BA8Tw}P|{dFN&}THiQk=EEK%s|F`4l9#+8a}rE$ z5UNS31sAW&TI`UD>l23MsI@6Kw*~_0U)2)VUxT?V({oY+%MVxKj1osksz?CI(WFoU zvJwS|3fQyRc_C`9tUFw9!_Ws0Cmi;YjB0H~)=sHn=cleWfxHI|GHamp!34#;hsDLK zmK>RmjtJE2^BigS`~{@`{S3__3ks6NgqD6@}})+jH(v?~H2WuCl0DPVeO)A0zd(1In#Oj=4Is4`7Z3qF_4Vy~~enjHm&FD##bffn|v3D`9$IxciyP zYMWqj=k@;J-02B5_ThEt_Q4rA!{bmr*qb_RhoSqIXCqfYpvx(m)uPZq>mWwyfnopd zGv;q7Gd`ih2wfXhi35#-9N^{ zpB~?V*=PJ3F~`knJPEWtDL)%(Fo(FX`9Kus0t0--9Vh7_Y!>xTD=qSR-4=xIURZdU+fI$hL~N;8#N7Pq{A z+DcR>yGwkO1+gyR_ifCAMG=BaS;C4e;5W|tnaTFakjGw(Ghz|4nxBqtL^GpuZhyV7aKuCQfa)=M0WN$3d`=EMQ!K*yDG=7RV3dv{`R@pe1}= zaTbQ3hr`b>G&BTtPD%qc)HTF;OrJzWeaBFRRoam}Ze}~e;}BvffL!I>HgQ43h*O7_ zl&-`45iSWdQe+;efUK-6l840M5#kXI(wTj-I1QrI3Kpv`0fvBba;+M9k^H${yA{^8 zJEb!3aCPy6MVQ~s%*={08-pR>!8URqy9`MdX;Qd2<{yf^kCm7tRLN@nk*w4TTn>Ys zl!=#nMp9bGKcfClrE1HwFdg9HAMRzuLhT@2I?)$FYNLmCLAS-Duf+h%NtF^dv4$fa zm$$*P2xj-mD{SDjWLVVbrFt7S_IMy0$wY!z6zsr?SZ^^gbGG@T513iiCQUzntVC@b zEd{1_`i(|WBORnnCvO=8C7Px}lA?k!l#<6CDUHSr5(M}Fv&M~BoCxEG=+tcEeT=OO z7(A9_!frB$QkjA9ID>Kl93H#}-SIFfDGA#TU`Kihr8aBUf%Tmmf&lM?M;?WsCe+{( z4_b3bu9%ej(gHEisev)~$O1_CBYGcc_0QtScp1Zgi8aOhg@0gKPx+jSm^Qt+jcx(4$q&*^`mbiBROgTZ1EPe`|fk3 z$+8=Q#`Lv7M%nJ<+%?hGSoB$aoMacrI2ZR2f2mPH?v`n>Upku)p^ zQGNu8!tBibX)2H05uvdhoq37$K^Fc?>?xD! zuY?RYIdTTNS`V^fU0od-{K);z5wtDkGGdQ@@&+IaBWY;(RnR%hdN<(P>)Uw`uroT7 zG??A$I0%@0%n=eGgjaDAU^E|I9nFc%KwDT&2EtLstQQJ-99xPw-4UUwumWQARHO@q zHA`{0?L6t`nAV(+Kuxv;@iqWQ@ViNlbL(UpyTen2F+$E~y)h#54)E-D4%tbNSdcrG z%W?rY_#(mKe9&vigw(3a<=d#yI6xYHF~V^k$zYKm#XNY>67#?kSSW!-FOk4W0AJf@ z+HZxbhrV_02v=t-*%lP{;~CpTbw}2(<=O7jQ@#n->GT!F?m@@?vBqzzMRh}CH_u6p z(MG`{@B#p|X2g?#O<%FX?* zB9RQpth}=|u(Oa|&=(fU^d7VD%yZtnr@1pU94A@?>}&dzViw6@*9 zMxJ4Z0J@9NqF5~J|LZer)>8f9@$Pv2p}Qm2yZZ)&=|vvHy>?0<9nAAQ-eFsVmz2)@Gu6*FMf?ujODNrOKR8}pI9gWtqL4jOSn8v!^186HF+Wc>{ zNpTuDc-G_GHrf7Z<29w&z47_|N}}6>-Dg4Oh(mbCpu=~#7qY5zI?A>g-kH#I)B&+V zO2oow@a0VUf27ELs0E?`>oRyur(3=fHruZ7EqgNfpX6@z-8=f zXGDDOWCnY@lf8rExvycKlSb3Ee|dkdSTSnWBjjhHFrOvR??4dL~oNR+KsxqVK~u1@-o78Q&Sw+{Y@a75)wUrDOZ7$^u491`MKO=HE=D#e&Fhz%oqU^Ay9h|jvZ z1Mk)ljI#^REfp6BXJbR#$w!eDFdbb$sDwhn#IF{*(oUbKwxuZuUXZH= zm^KtPlQ%n()eOi!ycxWsx~^x)6sX}e`FVhaohy%4(a*m|=(b<%N>;7Cz3$`@@))H0^Dj3~o)u@U7YfY>1Vx3%$J*Th*fNK_Ea zm(Z((J}W(tBxTE}7voNzxGnySPgwlXXH^aOlKmih#&x}m6iw3eSH&qQvA8Ru5UlrF zH^ZhGXMg>jY%i(o!^>>2;wK{SLO$(3KMPwV!N--OuoWt^w{ZZ|yHgD$Plsg4KCs4k zEh((v^uUFakQ7&9a~FD2!Z%?ay32JqB)N$6NL3Dr>031MhE&cUoDTn~ja%2h$= zO2a`3h6Cdn92wy;51tDV*+ecYIwEN= zd1&((=(J80%^EcW`8Y*nT%=2Em>PUVHb}#+eiW;~sKs?HI=2n5z%c%NRv@W55!>X1 z%t!moc_T#&F6M~J@&;&?C%}-5(=)qQApl@QH z!l4r<4QYr<5&{O}B%- zD!Z|ORk)baiWU_t!OF0r7&@$a7vbjwUGo9yYA77bl~yWZ19n(4B7Xl=Nl*Qht>;;+%1^$r`5Wd{Y9=+o!Rfy zOgxQ&z6%t}CxnZ~sc~7D1gay#SoZdP5R*+NwLoC_TvEs{V=nB`{XMzQwgw&Zd zehz(lf5@i;)H`DeIr|1EU9h^rrXWGwl8k$y5Nt(LAU(mH2y}l8u-)1fiuTF6T6WZ( z{{UbyL@s=M9svbDN2J7C3(Asg$}Ig@ShI+VZ#LrdG#-j_@Hwq!z;|L}xABYsMJqwy zgc`afT_til$|@)D2fb$#&uIr-!hhIW#3N491EKm_o*o@Mk5`~wIl(sN=ZG?OP_-O- zTUQZYdFl|pRbBLxuuR4?*FSx#IS)HWCP>NAM0$a)7FvX09DuldYMRr+dkIzy&kru) zc=Z*Owp3%7=!^!xf>2(MWy+kx|M(P<;Pe{8(`5k)M20sMIGjOBF)s4xNdIvlrYn+IjSt9NPZ=)qCkKfrKTI|#RK;P}d)~>&Pm2y;YYRxdHju8YZc^g%mz#xK_?(%z)c!_qZbUeS6 z;`y!$vY#FHJ<>YU1nUpD7Y;r+FKbN15}XfxX#{x*H^Nbak+dmkGk$1( zK{~FaXCU{$)TAa@h*LPtbgqD=28s9?pSBuWAV)Eb5x(Bb;9&(vI9~J0CnfSM$nliM zz{A8LuZpML^KK|Zcs|+$hx6zO(9v8%=bmAkbI*Sjil{L_-auypx|baBAZJG*ui*li zlU{T3`h>>_M=ELZVl4Il6H74SQjSnEePkxQ7mvDN(7`pCHP9G?p3T-ND|ewGv?-=s zx1OSj_1E;gkcNRUiaI>=%Er4CU}{TQ&UpeChT&VXAx*@?xgPQ_B*akCiT7G_vh(w? zDMRPNV|04>Uo&x6bBG~?(*rQ<^A#f-eQ!%TzC~fKBjS@NWaUYqc?2^)J;cMMInjTp z#_6te1)>8ELE^%oNeYcwfg4ysJ`x05!h0QPxVBGnJcz-!FJ%6tsJ3ksJrr%BQfOBo zNZSCCZd_3(;aM5M4EkUa6ZX3+Pt0QrjM??*t{l%CwC@E=#XK}sO*KUBdD17C+Mic5b21l`29my!X@R8 z)zt=^RQ@rhpwpUaQZuG#NwO%v~Qg#2v@WiL^*rG|_K z9mH|F1kwo@q7sv+!UF30lV;~%i7KO$(S+On>Ji)oHra%WJFF;Dkbymm|JTM#!+`X; zoYD$(NZ4W{l9Bd3Qq24fWHdaNX#To{=vs!u9WkrLt^?!FU;dX-tx$xsK1>$`9?y*V ziy?VwwEpQu!G)D8<9aETq4uJva)xQ&dAtcOK*Mw*^cgqttqy3LL$`?8ppi z1c&flRe(1h+>f`V%L|2-9 zGH;rSDK?b58X&Yd2SVP^1K}tcg>_OZ$VjB;e;o691}j6lBR?N=C3NnPxtN|Wg*q$Q zmhld?^8g%zan{YagRN;s0h}9<#U#ATf&o2`lu!yYIrE~YA}Toq8$TRwa9pHt18bAw z@yM+(A3${qZ~@A?{*^3YsC4jt`ns&#mMFB=90Ysb^}kY~AGnU}u`W|&!TUI5pbO)v zS9MedqOV~WhppcY`r(oZKd~ z{AIC>SG?jHlW57+!G{)ECk$T>y_Uh7p5(m8TqD?zUvYVYso8^z`Cp0!o%i5dBnknsVI z3Sn<^^e}l6diN7oy-pAMbToYP%!jvuZk+6E02AkIl%oz{6g`KF@pb|jg!D^WHcK3= zj#{b*7b*^An#2Wz-4=cKyt5gq3$BBtz}oriXWkhD+PNK&RunQ{9lDCw9ImpSV%C(| zjc@)DKPM-R^IRe4G7c}U^y|;~AWyAHvP=)2gFDW|+lfCxF8Ke&n57{>=s z7L3Q?UJn!uF#^oEfIz*`9wc;_UUx(^ny>?+H%t+O)$?ZGQWZp8Qf zdTljuj@K@9&bvcvFFZM>4>n<*`mGdFY;^@k-5N_;xL4P}VE@>!H4qU@HREu6o`;Se zVCja(;s3)lnpQc=brtCh|LC8JvPmc(XFhW~jN?32venq_^mZ;bJP+-`uUI0q)dB zcPa#?OUERxB8gD7bAvX&fk82^U)Sjmy37w~S=-m?(txt4I4}ldO0#DQc!O~>%x0mR z8QKSG+64v%>be5*5#@Rs{`$IPpbAYwI;i+|q`c7X)(2gQfDOq48J>&BxnA2 zV5GitN8OVL*3h!p2E91gH+`MrD$>|Iuig#K0Sow(7J#Y)O;e)^mZw)yp?B_0qKfZb zSPB5#$@30^&B>nJKI1a%fe-AfOieS8->E(^4c-tLPP$xfD%`?Fx&W;(d`vlNHKazT zRW`=d8e*Itx1_e|Tt|zQzD~#Jvs^+NY|RS9zoj(b$_++jr2WN}U>NHudRSs}&i!O^ zbwTP?>tBz%-Xi_ZpyOyxi)4;qY*@SQ>y09D&X0z+)?OLPi3=G^&T8)c^$kPPxGy1z zywS!uoMeV*bcJRx<#lUUSMwK%DrOk7O4ndxbiWMpdKk(+0v4-H-N=RU#K^$Vg2vT) z%2*4~5;Kg$G5CKzh4V{zB@12i_MjFbj9|Z<7a&;N#0B)q~o5q=u;)$fu~)g=H9 zo5@)wvL}2@=aH}_bZo1mQue}t!8R~UbRj$son8!?pG!z*(L-T@vp5UHHPf4@{YL_h z%+QWL+Tk`x-d^~Q`}nwDix5G$UM8W!__aaXx;iQrZJ+uoU3!0#0bT|EzJ=}tNSPZL z=n4R@Uge0EdnfN=8DNE&}+2U9TkrQwd=Dj(%6 z^mVOp@(?B@m?tXU?%{AKIW<1Y^Wo@5F_sGatuw^Xh~^IF{6z4G0YV`%ZnP&ApwLsG&%j545Y z)C5-!>V?}pSO(jlgZ>*_MLk~z9@9p56qLY2s%)I4%YZWf_0mL@2r4_m^0+8`ISoA= z&X@r=sH&+Q;_M%-=tKdR`P;b9mW?PH}$K^@mrW>gpi|WIV zm;qGK|9}`%*EQ;6y{ER?djo&Yr$q*q6#RTG?vsyC{^o8@J_eh)IBmoF*s=$4QyGUl z5f>LPOGgEwFf9+V2@6%c;Z75Lwe4tdR53Iig=qe_~ zf%4>xYBv#e-Pqt~3|!h3o136C=%Sck!3tID(X0d!WMW{@k@NC1uJX!XZ%>1*(z{oc zt$m&Tm`uo*jjGn`)@G)wIK%a-+f?7h}!IWb@Lri@Gp;*6l0l>&P8;6r}P7y5>6iTf%%fMhh%AReN_)}C+ zV0$cJub@OwMEM9$uUkfmQKOMe45 z{qIDD`#8(h!R3N7+IfeC?!T;R91ePhBD~0F@0?B>&?>fr{dT;89yXQozc(jdj z^H}xzOK=a`c!x9vSim!X_FOdbTMIWc4P61S+;-A(oZMakLJ*PtF*@dIAr(S?_P18H zQMyGlh;6Bm zf6EW=m%v#AZs}+M#qdt+k>S@tq|o{P$2#X{6~b6Vk#4OU35~6PXhX!sb+J3fAzXcn zB6qCWQ%vCkt|JViXdGU-A#rn0a^?ye+(q|)koek6SaAcaO6Y-f8HopyKuYdTEY;tR zT51ALv+M~6G+`Xj%%H~kYJUsFIe81%gbVCQG#z}08Nf0dECy&Ojh=>>iTxKdUGpKh zF5Y`YT2gMWc9oi0ZHcG?mJ$FGULyz>p=q26lCZAXEpj>-qLqH-H3gRt5|`VJ!*N2O z&00zj-$4$B{LzFuqhuSI?JSjU#RK!K11K@3lafLZHcftn!gEq$BrkrD|0#!dxJ%gq zE{R%`bKp&S%pLf#jGi#zX*A)PbZJykZEVmd<#&`;Y1*2%*e$>H1)JFO;CCo+t=N#RLx; zN|H2u&3bK0Z@BIRxf5>FBIJsU6|_6t2666%tZkY7?_}G_$pDSZIP2MoA{uUSU3?N( z6KqiH2Jfi=76{xIALgVn6!mgPwX0%DiKjYkf<~v|Y6A{Y(if7F`9Hkmx)(B!07SGa z)>%Ps>@&4Qps3PEu*>Z}o{Kz)Z*H9wok4kA26rYD549ng6uNeE&~zD7bI{8_Ji_Fr zQW#@}RN2~=oIOx}f^FsipFKtrwcOwVydTDTPW=FBA~L zuxdn3v;^LMEf1docB+GrOHbRh}ht5{{af+<{?yvm;J4r zH*C%+_o`ZdArvQmE9hoM^EAKEO#+XTC&9DH_ayI4B%GgD$Qt{D{7%$1J0`jjGyYbx z4u?IFPv{vy!sJfXI6K7$EN@^|g)AiMX14f>kQDmv0;gL6j?ps?*CH7rau)|D%gKED z9z-1I)kp?{yUWNFhhU21=>FU=y5(|!E{Qif_XJHbp2E&yl2D^ zw3OqwM+ea|lc^wHGJBT;j7>b;4vA(Nc?rG~!5)jH$Dg6kQbS)8T8QiSmoBryrVL2} zF?!)~WL_W~AoYdW+}u2MF^Y4rE+0Z2KlB8ti{ftF8?l(!VY&7u1y>@5VllcK5cx#* zT1=8TYFOMpC({}6uOJz*CYghPjifJ@l&yv3(C?tCf$U3uL<|7h(~oilj>dPg1ecpj zt;8rR-tHcyMq(aKLMu2?Rjj7SlVgT&`Aou6sI$I44L4F=hh4*2uF2b)D>!TS>#nIi5{e~Hd=c%N-B#knG zR|URpOAu1~3~b)f$PydBWlp97^|Dsg`UPXtFdIxgN;BAW7RZEieTo!tNTz<_Eqr~(!d#LpHTi$f|W3is|G+o3bLdAZ;vPuazYa`6R@3)Y@J)iP47qAl|Ec}|y7O4-~3QNqkMV;r>2Rqs)& z-mi`Yi}?7C`7Bcx9=x?wq_W#JW^>KfBlpG}Y4a+@dhU)Cc2|BIFOOIp@?qLV{rVps zEp0pcTsnpG*a^+H9YaG6ae;ZPqb2TZRCc_cco%@(UZ^E8*CczyF*n^@FS6oYn$;Be0pCE1Rm(tsIH^1#^9e& zNYJ>G7#}bWKenWL$W^iK%Bw@pUn`-G11%{ro<~LJ3>?~{H9thJlquw{qP$b&;F^M= zcc(w_)mTYdgvfVgo~p_%%)h>Qvf!hP4E`Qol?ycAK|zNhp8_%Z^isW$Ej|NsKg0^= zyN3*YtjMkX*6}rUqsW7-yh>H~(XqZQ50=TvZC7NwUo8-o=-V*xQDOh*hpa;O*atqZ zRwbK(dy?M<;8oS8uCA_m^G+;W8A_HP#buR_r4~=f_I1!(BOUXozI(4%8>W=57R#Sk zI8erR(Y&Bs+nlO#J!2BX=C|laNB5}0`R8c^h7Kc}hy4hT_g_oTr}g|C`>6QCdP_*d zKt>OblHuE>oowwEZbGRf?ftnv%bUJCI~ohc+&ddCVUJ2T8zkJ%N7}+Wm68I!WxcxF z*e_}pm@77>bZ2C+346&U>6_ne+H;&SgI${?18M~#qf6mZX*(Oy1xa=mdN^b zlbu2ZuGL3yC5-r^NHV6Ps7CAiE4FlEYG*8LYioNkHZp)ce*h|feIZSyqalAW_DN%W ze%*E-aq;c#sxQCvB)_L&OZR*E5G+WberD{F%@@VzTWp|WLd$7#){U#N!%bTB{EqC0#Ox%k7qdV)p@+Em1ji;|t`A3xd_O)TD zO_sr1MK|zmn)9ve25d^{|(cBMwGUZzqOP`4n6ndjad-MXT$Y2d=Z zR$^z_iCJd9lY_&*o}7tH_Yf z)V|+7?^l=^xzH09zOF1YG|v{L^?mB;F8w4ot_1CIr-7OwL#iyRuy4H-(WrUbUsRtk zDZCrDpZ?g~&u_~d<=lm|^d3D97^XMoxovH@->6N>bYf3?c@+E|4f8@lmGLUEgy83j zN5?+(u$Q}G4~4EfR5GisyT)6LJlI(H#kc!uHapOQBLRb6RDYm^9ueKz0VG4K$-7R` zN91Sc%pjk&+9Ic2K5Id(WK{U6yqy#vGSwADg}X%V)*kmBr%xIj>d4yIZ{+T17P46E zOV@Z0&-ulpUW^txHa4HT4%22Hv(-?sXRFZn+j^@p-%B@3AQ!8%qT*H|!0* ze$H9uDC;X55{BCO+|>AB)ua74PD-Yx-aYUzT>kcM>!&91!Os_B&Q{GID+|Hi9#hKP z^Q+frZLw_BaJP(w(yx{ob;_npg`^baTH@{e)RL&w+gBCvxDsv_oV!6+=Z;?q-7>!_FiX? z>xl*1rR7t1iCOGof8%A_C=Kec<^7hq!5@mjkLBBj(N_^CI{Uo&c1U~K?lQh0kYn=v zr}K&Uq{>fkv*)usc*ZvL-FBpzFZBLJW4FhtgxAiNSUB8@g@;hVuk|6#&g7{Yqi{MydA;AiLt@@DcM)$^!%37EL}SNuBv2mNi(--*X&u=ij&H$2Jad#GKDP$VA7kssk@Fx3N+;~1*a`^#>u z8W}h@aZ#yciVohjWCcpB8~OG53Lb-U$kD;_uhNf*JtmDZbLh|_$MNswR3FpwSa_NG z_o*^oSd_q=+tas9sCd;y=&C9uH=aF|@P+H5>u&!@Gg`yp^Fya0=+}B3k<o{ddX9B{8H_O>#b6&OwLF$^%D$i`^O~#5JN`P$*r8Yz74yA zYN!B?dQIP=c(*+Ir9Qn5!$9@lFj$!zIuV%s*^l6N3Lq7po$zGL^?!|e$yi44N^X^n z?f(RO&>Kv2Xz7HB#o!>&CBhEOq)&DAfv3;&lCKINzV=f+{7Sih(R=AN5CESCo^Fz# z9kPF8D?mZ4=GcV$$*apA8?CXnuPzLwN+tm42EnxmRC)?d>Ho2={?h65(X;iRB5&BaYE!^FMKGA$5{zriibCzD$pY?< z_`e8zrJz#7ITGhgyetz8ySZGylqvr|27kL0hnwr2>wTiD>mbRV0Gr}O>ID#~e}m@o zn+a%g8pDuhOk^yfAcc2fs2&oK!~HdD$b2E^jJ&o(e)FFLDRL#0SuHtxgj)7C2&q}9 zN8y*s%9_QU1IKS;Pl*ebvxGFmKcouMgyYXHo&$zi-|A8e7Bm)&n2dI`7V_tAnfeF} zl8%fu-RBR^3F3Co=X%HD)UEEz=J4`1y_1M~A=~IJt31j){UHskfBDN$y7vU!U_oKE z9e%6#m)W#^X}BO=_ARs4Jn(k?Z4b5~+KoZBd$AKuh- znpZhswE23|SwZuFx-D7O-rif32fK~m5db*kTsws=ENf?Gb!4;Kz?M0 zz>xIuFWG#xsVai#8*kQ0)7+D57L=*C;3?hWiM-7?g63AW%^Q54oSl&?=vd93Tbp7Q z=un$d($I1I=rOZE_eSqc`%9oCW$LYgRJN$}XHfEl{v(KzZyA-!@P`(XlWMITytjyp zi~9c7R8up3Iy_|F1b@n_spZ=06U{Bv*}sd~?tPy#`Bet41>m1-Dja3$sEkO9ZuRPY zK^yp4rP2LLFyzzxO?PtnQuBwCkBBJ+2wM2aKgj|uSka#C+}y+Zp33fboF@TL{z#op zz)p79ZoXOa99ldMy+1=Wx_`cl8EmVnwDNXXonrcQUfqGZ6YVg$S6|Q7@maEYa}85X zFSORCme$nlKk9g_^Z<>`{#N3$$=adS1nrYzp1Y_L9F5K$%v@Z!pstoQ{qY7LcF4$|`eiq1 z*^cBLi|%?B%@Q(ybl>x=YF8;E>ELC$=d_(iUd)O;Jav(M&V!WroTT{lmFt#WpFYs# zG|=k4CFy4Ox5(V5-qJU3-@I~r$Y*(occ&ujbDA~FW8bP4+mQJmGUF0g$w=@=x)?b~ zC0&&+dl?v+E`6dxuiCAuz=hlYnfLVP#Ai*O%uLDTjS}_W@^aJG$W3xA@C%V(v3SmJ zhqICO!t#rPi5sTchvtheJu~;e=}QZ^6A~o8C~gjCkB?ux99;-M>)!CFFsoG7Z>XcJ z;~d^|Ci_Ph^YS`lJ#+Ya?zh#yD&EP%Q?j{>ae%3biQ*q7#Wc)i3CDcBEO+$OppEWY z(GaPNr(RXhH-565XZw$yDO%eimn#UX-_+lqID>tjuf`;0rD68nB7t&l;=qAZCnx(m z^7o#A-)3j4n7KS0D9?i5`Ry?8gx}}7m*NoVvU?@}=K47vI&;q%vF^W~87EM0&dZWk z*S&0`IP-qb%wy{V)z57_mnc2s`CMxrU4d`@i4UFHV~M!+Cad!te=PB^TraeD{)X49 z!vlkS(w5gOE&CMt+N;64i(Z^=?w0Loz|>`m9E^5fIp4_P!o7&qOSqq9>{s90_3)qo z?tbpK#mw*BQk|nETe_-LXrIjZcD}X1pOY8={_{F{=g%T9p2tS{rxjy=5}s1(A6{C@FYd@;wc9Aa?PN3=WMc<2U`(A z@0M#i$B6mMA4z_Cr>8LP^7!T@V&@Kyyi27$elJx2kS98`yO zv;+Qor@1A}M)M9!K>fm+)$ir*J_*iAxwX1C>DtW6iOz0U5yW}uckeUmFqUw zAMY{FOp=s*Yf^PbNI;=3$VTYcw=E4>rCF=R&*%=mvDKwa*xk2c8|{CL*|@XVygNO& z>)Jev7qsS$1#jfn6rLOCbZ;sJ`?Odda24g&r4T#u+qGm9aUKG`D47& zS;wMRN%nm|tIsFT#V@UANMgiWXKTMk<-*Xq(Jq%o34(nUL&fV-zqTG4ac70`BQq*aeR_6-)abI9$K9X3s==vG(K&#EufY0`jJQch=&*VN;= zjdj)o;sZk)J;Pn{-t4T3c-DW;%YGzkApfJX#=F)STA$%73)<;tPHMhx>YHz>8uv&B zPnVTVtI=!x#eY|*-)nijfd2k7js+FHqe}y&V+u|0tyMQO?AsL>Haggq^K#;tyCv`T&PiGeJIwbTY1d59Z~6Q!vRP^R-o%@G z-|cPZCd%w?Jxn!@FrbN4YzaHHgy+?@$#Go`)|0ol7_Q#r(GXcaNvLK+XYkav#?2#5 zpUivR2f^3nsd4Ar;{`2m?J{N`8Ps%l%&>aiSDQT0xv#x3>D`)Amok=Zd)?>$If9!) zJWaO9{vMywKNkBrH&dnaj9_J3>#So3ZpUPgb>_KWWqrv#@Of0zFC*FgYM`LWuWz?| z)9scmR$()3BRg-hKIX(H_zpa+9edb#x-#9-VWg^KifF?HnUi%M4I{SsUV|4J>pqPK z7aDaQU}rm|*3z>3$7lTx{jT4@8vQlUb^D=j#d|?og>vc>^WM!*M%a5!4m}tdZuDu* z)NvcN?RFa-5a|BZOH=gtWH$FdpP4Nd?9+ukQ`nW6BxfI?b-B}`RL0-2%ZG|>N2a+f zePP(Rg>_vvch-MOwYFm_$BS)y)X)C(8!VHRv+TLYp4`1Kd?))|mWuC64Kn}hiJxwEMy&7H5rpe|?0J)_M5qm{D8q+I_Y=^T> z7hcS(YyLi>!t8aYUH5ovt9(@0n z(+>Lrc^OMb&<+e`T&|XR^Us zzf``#`-kpMfwMo43vP(IB3Yb1dmI*Y&B{vTir!%2^OJfzJonhY8CHnrwO!&*UeRY>dC=C!{#InjL&S)1f_wS76HRABVsB^PIKo zOp_`*EYAJNNi=zb_d&W|x!T2^qZj1QIm^Y;JT+CO8|~oJ6y`s(wB(3*>7y46&XKW=-z4LzTJoG%b0}4 z=$U!lwT*@B&T;S2EcTd+*Qffqs$J?+xC%Pf72ZodaW*n_B){%tT@TyfzF)7QZ$W|P zz}y0_YqjPj>v|0qb9FZlea+o94h>|%u9k>VTlP7mOt&6(1?kT$$EJ=3>JQSC z;g`6`pU$nVFKpx$E%3E% zCjDzM|0&6%vueEeYWt;!#xF0`=$*s+%XRb5jCCJ0#Pnr<-1zixMr_uzwrh6AYj?h1 z8Cwy5b?c)PCa>jZ`>rHyd3wzeCI11-_4^%sjCB{C-gqpa(C)IqX)UQR`BtrA?Y#}{ zXBsbU6teCT4SFY(adYn5jTfKXS|XP`mi&MV7RxP&+Gb1&8M zPt+>WJQdQ^_w++eacaY~ZHynT+BbaNQp#)GrV)+7hFhLgWL@j7UE`SlBuVUzZA7PF zE}PvptTglGTHqt5xe18V<#5eJl1bwP?kwiklIe?0Xc0ohnj0^E0(SDp$JX z4Sf83wRz#-$~Ft*^Rmu~Nm4cjy5AQ*-58r;m%HfHf3gdH9zWk<^=ul8H99LUd-2)j zn!BTCXAZmx`}SCRujITb2d~6rE-fww*2S0E0)^b`cL3q(0_}I6y|j6o_Rkr zdA^o|y};)qlMif2+N4l+Pg?hh8duEAM@Db9`BxnNGFv2Uq34|#*7Y;h^KMse+iv>i z=d`zJ3n?AtBQk}hqU8O_7i4C0#Dc4WQ7WG2UR>8)>G_Y~>NZ?bJqmtSD$*$II}pq6 zrafO4cSGj-p_PmX`j*p6U%irgA{lUVga4sp)1S{3nR4uB9hbI;^5!qr><+WdPgW{; z|2N2dwpl2puRL0b?h+ice#MIz-6KohJbC^m@e)%*B^21HpAMBe_K*|!`bdm`p@?F)6WFmMmK7w=rCH`AI&OX|JCO3kZ>xj*~a z#npcGuHJvAGV|cvvqt<*VQUs{IUjO7g}Y0sRzl^dPC&L>qQ8C0r!D90Q%gN{EO{!1 z+#>wUPK(`2uhmf*2z=kp?O)ds{wkyIPMxD|kMP3~$BP# zj+A8j;h;>byNp;Vtxc;}-A^{=X*F2zA+fRiNa3c+2M)8g1=MaI|8gp>^3>!y#n>lv z9Df82^mh%xdzp7-gkonTn*KJKnX+oge0+xEVLhMiq+>?=7UZ?f`Nv0p6rImC>4Fin zi|oac!})AJq*@lMSinoL;pY!i55(7Cliac{wlPle9s6{gFnuoZ`! zLUc=1a~78uh%Oj7rrtj$Ir&!JlXr_+>|3K(9@R11bZyXBdkw*=Pj25_yDvVZ&ey=; z?&np%M;i32H;76;pBv+*uS;7U9io?a!s$`U5;5+jMPKjNXZqr*ZD&~)){FU$)CHA#FW2O0WKTM*WTkBJ zXj9aQp`T}72!&HP9%wez!Yz4V^B{R6Dt6ah|k2vTSpE`6nt(|pGI@@%&@&0hvLJdA%goc65`}>l_|B>5N;04rt z%WZ5LWB*i%eH<>VZRl`yeQ{^I?wcR33G3R9&QTRo=RT-^wjuM`p-z#G!5c^9mPorK zmWG^Qu?UaRo+QTVvkfzo7AMQ^=nQ{oJO4=I>`d>^_M_`__upk3#0|S05u1LBUTo#B zcX69U+{UQ_-%SoWv?qO`tS3D=5pc)N^ZO`zo%B?a`x|j8XlLy8aiZ+Px1X{K`37*YT7s5IW^a zrOTL)&KCCYqR-mn;Wm@^Wms<&V~qS5`XEMAbNU@nQJ=eeuUfrK|F=lVi$6=`XBJ1t zylh$2*s8nw?Ak^3t@jS=AKjSnJVpS@y&3DZ93Gn+{B|ro@Sxv3*>)Mzcgxr3j{Em@ zRWwDG4jooMb-(@p(e;&KQLx>*bPGx=tw>9Eiiil3D&5`PIY>$)AxMYPp>z-3Dbn4| zFbu;0!_1s{-}gKFd}n`q|KWm*A8^g8d)@0^>nSztY%8gD|9<%43vWL9Y6oG*PGcvg zkHp@NE6O?Oo9FF%K6t%@jR3o0-mBf1^yJ;P_Ib zlKe+E4htK>JSL!HXh;B=F2$<#+RI;FxK%IuG~Y$czEztZ010@p3-oY&8N@wZoo*kt zvTW&`&`A1&(pujlR}mBHG->^%Ue89{vAp^RPptQfw{dMalB^zmMjQ)p6Q{n_*5<-0oJAb_i7s?+Q+#?~E;Uf#yf%M}rRE~5)*WaQ+DJ+nA^#F9%|4co zD95v9AcZ;cs6xB-4jOKT4wQVzXif8UPodMD(>26XmbA+#>7=zx?fMT zjuFhNgt9E_dOqFHr%$+whpzCpi(b3auamWS1h9krZ(Na*~BUC0+Byd(avT>4-6 zb(_u=yaw{PG)3zEk?-cKk2f*-eG5(+Vb}F5n8u5=-DF@R;QxeqAi4zyf8N~0sHQwB z*5LQ2AitjC$dI;Im{hwrJo~r`)UvyMGYp{c!uud#Y02f0Yh_3DZ+apv|59Ylng!? z8;e*zX7`gW;dtvxeC66I`%9j)W!QrpwEXV6GUr}$3SdGlX4v`-ir>UW#i3ch^Z^du zoHud4^RmpxQv6UDLXTsI3q{KI@fQh4{Ry<0eJoUP>~;9@`2h_L&LIDvEb&BrJWOqU zi+JyX-_MB_XMCh~`?f;x*3 zFPmo-of&;&>k2sH_FJ_lJPp74LrAD4{I#}o9d%O6R4Rrw7rg1t@efuUwTUc+fW#m^ICR0ikxPK8U{+pqd49B3*4FkrD0g1d;ll?pd?IvPe-!oT zlK`#dTPcP=W-lot|1>^Nd^TF~bnQ6RH?OY34I-g_0%gUt<3YtwjnvsC#OvjMZ5JFUIy6xp1|$&8rn1ClvFvbg4MXxD)EBLp2=()*tC= zQ(R3+FYCt&vMW=NG(A|5(j+RaG1fCgUq@V^#=(?-XqNlKB_BBVQ^WSdy;rQ~*N)+l z%baoHN|}$|%37ieA9gY$MH(9^71b#fbC>`bb|Lfe8@rUw#6`1YS_XyJri#8wIFm*D z#6hw{0aI2WUYjqEl1R(&m3SsKTIlKPOhwF5?(WwO_(}vUvh_@|MzSbobT>}ECLy_h z1wI-(9~8^`ySMqT6!1^kCIBaRgB^i`atOr6L24y;m)H}}i>+vJikEbu*OOaS1A!Yj zhv94vg%^JYAFfHf@onqRpy}7mIPvMk&$WFWhx@KZX^2k6x#EVdct%C+(_TeUg=0ls zzeKb{vlNKm06Ugd`K{V3$~Ua`6#ZmyQ_Y2d#<`=jyj&^#GY1k3h~Zrs zrBQB9RWm2sg`LE zB@wH{jEIk7$npHsNo$yNG{_RS7dBuaul3bx>^X1#2kKaESK9bQP5ExKj-glFzgcZ& zKYn(faII^|ISGNg9DOK;IVUblZ1Admh*L)o6YcywZAF}-;ywi{{@2S zq6dh;r#-mMMTQ32mfl-GtOs~U0>y_6qD#xA8F5(5DVx$4W%>nX9Ba)R*t$BHvy7_V z^#_u1jS(=)JoQi$&vVp9oV4wW6VMJl($A~s;L?2lMywFYOz;^GJD`(MIqOwQQKJj{ zlLq?>$2oAu*$84j=?wa7jdW6S-}=}3`D(={?L~S5`q`0)hneFC5&n~V9`clm1(ZzK zF2Bsq={pBfc7*rRx6n*^IDZ7cmCiz0N5RUO=7Pw2;BVpQiI~!BZ6)(hIu1Da%haRm z2f|2SE}I|It2hdi9@xFwMA{eL8$LxWRNTUICsweV7HU;GA`bE)v)Ya+U9YUmUT?Pm=7@U%URP&-`*$od3pV6vOMQt25H@-sZ3Sg zZ~1x2C7kjP-!sq)b5s2J`b6*i>`^qP-a8kP&bsej)Wsq-mmISZcMMPFN??sz9JL(A zxKA3^47}ybZ94umVrmvNtgDig#X=(pje2yZO?w4}~W|ycA z4ruxd3u$O2*U}V|FXzovw;VhuQmiG+>E&DdVb|!;*&M;HvwC^)rAIP)WRkN4eJ6@j z#c|uIf3wkauk(H3IkK{4L?J{RK@k9n{#SKT{Aa%NAJs*`MytQiBuOI#1akvIS0b1? zrc54Q?pyRotJAU*23^S;YMFfU=BOqp{#-KIQF`tZlbFQ+hQie7p&GC6q&Y92Kt{H6 zPqEU+9f1#^;kx+Spv16^7Czi1(2MlDtgSrDAUW6(K7N~U%5N5!;@YDJyI<~KW4M{TyZ9%25L91(U71y$wQu>hZDAfg={yzJU&voS(9@Kabfq@JIHct_tZPlTz)@C^%~svBK1Wf ze#B<^XuI+P zU50cUouv+bPFhqC_(xZm$r4Yi2+@v3Wzv6$}arfqi^!{qf)JLof%zDW8A9Ji%pIswNPnr1RUfBRnd`Ex~(HRY7yi_=* z>+454oHcj~ewVZ-(v$PTh3<;0M@1JLCvJV1BQuYP4yA)WkJRUSW@<1NL2{Pocl{?D zDl%2s(3INbkma^8OYGA&`_bGTDYZSM=pWa3HkUpSw-`~=#{T2IgG&B>>7B~dk%$?K zo^_9rqrK-`Q(D@QKBQ!?C%3B=IU^g@2s)ZX=I8%3*+}LJ=Bi^3n9BNxy^rndQ+SDv zowq3wCbjL8O|XE8@8P!=>a{D@U3$}JUf^|#=K}WhLg%ouSscd~wP&Du9CbEbuf}~Z z(dScwQS-klOlmI-y`c!n8z5tIX~ccLke4*n(0M2O7%|ZwOF6YF`9{88h9EpQTP*%5 zwKk$7)kF#wM-Oj6-r2-qfmYPvXPukrSbOdUB61b}P!)k{htJ#9zgEXN_y->yZ1oN}#!~FHJl%fUu~WXx`i^5B`h?WoZyzF& z?#TlQ>vS1Mn#4Y3pW>QM6m+w44Nkh;4SqAG@wSgwqX_$SiL-}e*LPyd4+Ul)Ck6Il zw-1%Mb?D>=#loNea^@TCR>sY)_F+JC&Y_q>E-{w%{fa#V0Nm7P*C zv7Qtp)9Ptg{W$RreZrfY1rtMnt@aXf_D1-ZE5@wJhI5U&y7;hQRioNrd-XQRc-EIp z{J?#(I1ODKJ*jP1xQ^$Wavivjxg%e>2Lvp~o5E+0gtbvxv7KPrP?P4k_pu=>K&4df z^FtO$+`G0lUh@`%neN$Y$3b@zj>Nm*Fy_s^fv_Tu&((YAf9{uOe+?lDc%vuNh=+Uu zsttxTX=5+X5x;T&fGbz!K+seyG2wt6q8*01{U9znA-6ZZ7UEPQRW;cx8;#ZRiW5k; z44dfxd>gc0rCUhlj0mP)r*LVcj>2S98<|b}F>iOm-^4bea;a^NlrEjt)UozNcN2Eu z$Z^rq+{xw1+V+!}qR&M<$|;%ri5#P0;)yeZ)9)y#$Da3XCD(Dq>|~<%s4CC{|FVh{ zc?;TWii)<~%S-Y~>^dH7T=ZK)jMd(rFSOp$M&W!aoITUjc}`=kuB}5-MBps!8y~6u z_WCZn-w2Fz4bbm;u_V8Jdu{&s824kK0 znQCpcTwwgATDqUK9YrYghV?awi2?@4(SPG{Nf26BkyWv&t)~A~+!id~EnluINodc$ zm(IM)6Z>=0oe_s*8QJkx3r0f(l`CceID3aW#|?xboP0&XmYkYMZvyRp@2&5wq_w(k zNP(24(5UM~wyb(V`$yp1*Z1h_Bj}UEY44>aq%61S(d8mb8*4kW&m}|m%`=QU#CjWG z&4orY&04W}r6=(1vg4f&EmmGzjlVM>={Y|q5p^6cf_bx;UE_20bN#icTulTU20-Qs z>M6^8_OtVa!2Ko{HgOD5A}wu2+K5W?HgN8QnCoRbVAVkgbJGAg*Eq-Al%?mq(P{f6 z@>O%CUIAqctc;mimAsDCW*Jmm^~^1im5(3}%hIuz8N>NyJ+!_YS*rtrR&a+1QO80d zIy%o)b`Ty<3G{FS$^pAiVIX${XFn8xk1XRcJ_HS4T(wnl>c;})mP=L zi(NjXSeoR)#bNU9HYP+DiAQ#hpj$;<07`}6H{~$ZzoEltn*TndM`wx&50vcv3{&Un zU#gHBa>Ug|a*+7;#UU+xCfY4vv=WG<^IB;DTL_mN$h1}OlbNZ$e2DW=`PJpIF_z`q zTHdXzw74ab18K!C9~MN=O>^V^#RaMS!(?9S%(1at+1*Y?d&3E&sK&$za5z4+)K6y` zsQXo{3B5VI7Aj|^YmO`#P&*G|D8O%AKL@K622niIt*B-IYOgUdYsc2t*F&4$QNr=z z9L#54Z)eli=T&eJAxZYyg>hjn&0`j=-&f8=DIPA%l7QnOSR(ZA7esvV6g+;k3=72; z6;ulQe-WzYx|C+uuf^y-e~r<&d~qd?nhOJiR{dW}LV%lFcYX*8zoQeFBq!0sLlaL%CLyfm4~B&&hnQ`G zcS>G$;uk*4mkqR5Ykd^>f@rW|OqKtV%qY-)PA7`r4bw2uHMo1$i26gH;O z_j4|W4v>I=fLIG57IdpHedLuXHPqRsfM-r%PQY<@#u|Ftb}To3@D3gSk`2HBnM0p4 z$GG?CmO@(_O$7-#jzDr=IbKSamOhwmD_1u)Q5#Ojlh)6(thV%w4z5?}p67R}QTTPi zX!}C`VQ3gfyy#9Dl>v9oY}N6iSSxhp*{yT^jrJ1!Ai$>qb$v}m6#3v;Q1d%UM)SMi zH}iF+Q~@4};@Re-DI7#I2E~n-Kls-RJMkQ|9T22ghVo+0=e}RU@t8`!6M6h77+#FC zRH=?hFXeG8+xNqD=X+zXsI@B&T6S~|N2qK`aavO)OAz#i3LZUTf22E>;~~+f#91== zHkSN%gi5q(T?zrQUl><$M_ABhgu0j_XM#q+cl%c{Jz9-I zb?8Z=zUy7@lWi@as2HXFyLT^*Q-lj=kNEF*HT?ZRu$!Cn4OZhEa_xGWR`%Oj?<$via21^3r@usce?H&D-2RKSftDT)|*w`5q55u3S zHjiEHB+W2&;d30f70n*G`T4y~`HpeI1?8?xg08h6#=SfI{xNB)pvILR!ox>-3{Y3_ zrY&+^LiXS@UCi4x)V~0B7~vy)Q{mZ+61JuVzAIaR#`@}|t~DP+jV>7{p~o);awpLz zO$sRG`DNnfWi6V6;L~AK!Ro+s)c8@r^;;2k%pqmDg~s%{9$Rpw*t;AZmJCl2;#$S~B3P7Dra@$%cWxr5K-Ys9Ru|(ANEP|KgF|#9-Iwdv z^q%O42+{o9iD{Zf3f;=p-d;ko+)vUx!*;@)=Ey%wHC;eBvQ@@z#f0Hx83XQfkuN&k zDKP~-Myc3aREtYUIKv#%bi96-90T8@UGek#(~nSmO#`7^^~a=9+0H73-a@!fV|#P` zAJ_*}yS}VlaMf||uJ@(=u+Uz3KSxByJ+RKm%4r^Gn##&TfF-&1!9?xDF^7{*A_107 z{ZYVpCG(>FY-pD_IXO^J!J{k z5fv_CE0jO}!afXeiBnC95HHc3h#)K$L7#nJvHi_g4;6n;sYxaNV6<$)uYoTFI)3Wn z!o&|;D$p77J7z`)6n}kFt45r}r^bRTW*`^wQ_#;zbLWH_Zj4ihx={zg$oH?c8XmLb zn$tGH5$x1*=vnT**lHCjbDN3qMXas8*mWsI~ zr(NIe9Mxi0A;d}rTvi<=d%^g_OxDy0?vov6+SoXIQEh7o6zXJ*S(o8ZCXdZWUJW*P zz&haP?Pw)wgQyfdr_s*Rhnh_9U{sgRm0Nh@eBJ1iDZoFq&(zt`@^G{{6)S5Qd}7pe zSq8PjjC@c1gHm^oDs=?s$L35iMT5>29085^j22opuMF4)TNd@6cYZu^Uu;up8v4+j z`U0cq@a|W;>Cp?Jd%?b)Z0~1P#Z4miv_;FKV2sAbtD&80keG8#7;5Ff&y3;mv|%t! zi>2dx&;kWkmcU9CDDe%)jZ#i}v?S*1g9o2HF%>dB+4%^nrpED%`B&`^iAB zFSSv1gln#H@nX^5urtZU4fS2U2{!wUK#*23_Faut3eBIm$1#_hVdXE@=T8ns4cd{3 zo{7u^T134ZPr+39YdERbZ_}TbeNAJt(V0(^@4d9Z^HWLX=gt;Qui-bKpb@al7E&!P z=>pz2xN{p^T(&2Fcdg3L_0E~) zb|ukK))_%qk&98VJl*PB$%P=TMw^@p{a6$RttEPT%};U!gR4m?hj9_@PtMF{wR&Dn zIMBNgqnh&@41Bkn;NCJfK*%p1eU1FjMbLe_;M4k{ofsI-`Pb$*Dv$elAX*5unv} zfOHloo=)VHNx%uXj+ljwk+>)ajX zl5|_u*A7C46$VH4g-d0g;&>iJ-`q|SHazEGJCxixo!Ho!GrcF9>Hz)&0~FcGFHkD~ z3j*-D6gzjHIU(nz$#lu!i2cUIMDc@Ax4UTeU?g>DJTdVw5q8LXa2knOJoA}9R`X@G z2-g@U`n^4pisNqw9gi^pAz`RlUh?UaYKOKBb8pMo^z|T{j6FI$&2g- zN3vCi4Ubk{}{Vm&tSIFJxZV5^2H!`Lcx!531 z?XX5F|Fc7hW~tpus^>cFu&&(x8C5*HJnkWVyxDuA3;LvJ4%}thDm0OM2n`HE;md8N zlF9ADYlD&icLhU*K0Ljc*d+yK^y0jDwVFc;VVB2`#f<;y|5pB8XYjY>Uj=!t0#S8= z%xJ3MT~V~cuoNZ_`$Gr&iKKuuI|+}Ov3Fe*zB!`7fyqK{ahL| zOquTcHEABj6;L0H@&s0CSWE4anX#oBCK+nqxK@!vvtzF{a=R~zSWvk>V$M}7+Q)CC zRuqr3;ajzP3v=q;cP05Dwk}~XwPYC=-H&eWt2)(W^R?dzP3(JF2QWD|mqF~61&De5 zo$E#u=+i0X=0xy%ah#3EFq9C3Ys%G$dn^UL|35FEHzOrs@3Skx#7?*){G*DCi`k$S zui)qW`?Tk6v-Z4Km*n2=pEg#)!8ZnfP?RWB!;T@65jo`$w{^9bp5_%>pkwT6^?(#Aekr;fKVH~ zrSb`hX_p)djD~II^!dk$scq;Uw0qYK%nP;1$oKnelw+*}1hIdJGeX_xi_%=!u*Ku% zv)0`{PqEXVo~7y@@bqE+;8xb2Kn_g#dED0uNZpX`M5FHYeP91$GsAzk*>>Dtq|Lu+ zLtG$#34HO0lL9@AVkwm$_6^w)+eF>T>EmG1(9o#;xMtltM`Ge57?ri<#L|Ej zr>MCLEbyHue`gUNUw*)$g@CE<>c)lP%14S(B)w7XI?&#`G!3OLSL1qZQut?LXMSbD z)V{V*&F|zXJK~1ID5VNpNLEdgge1g8Gl5ncidI4KOQn#D$FsT2e-| z%+NOKz0^;MW*N8X-;sHn>Qj|rAl<5Jahpd1$Wih9x#t!|JGJnR2DXPKN$ z|3h@Dm+J!5St@ntq7A{f{wO7nJw1IQ0?*dQZF+^QsJ^RZp2f76>KXKJ&SMS@Yj4{f zFW=9@@pWhnKXQv)_r`BZ@BQjjhoG)Pi>R*Bnm;WWL zenk)c#P6Gtyh}SnImRY}5HwkApCz~|XBOo5`J1|FSv9iJ0h#~e2Dz7h13PlT2>xaC z8?gLK>=m+EOH9_q72FqVXnqQmBdKZH(mN-S0MV_q@k z6~-tQo0@xoW<18^WT;wq34as^iT+$2-&l$pzn-a*@ruu@my1_Vl@}`U)2s>odVAc0 zk;?`-jj!EF)_0PUzR3ji>pu)_>`4FK5e$-*3%LmGsL=c4?P>H-P*!#@Vd(yHC&~ZE zLg~hdCnk<-XQK!!;PxBjRd>8Bik}b9u5E;u$BJAK1yr(UN5%K>q;a&}$_I`^2_?c0z^* zTu{9Tnr^}}{4Ihhst(px&wY_S#}wLcr*jlsYu4!!fe#3dB$%?XkPk$ylt2B$wwqd+ zqu%^Zj#Q5q-Pb9*^1tL9D4xA@=b+=jLgrqJ>rarn|Gyed8w6b}f^I81c zB^T;iHucvyp6@7J^qR*pJ+r%ham{$STWXGI)WL{g6*XZDFzHqFL6HN&JY^gZxQ!sgYQ_4hgF$l;GsvUiS$y8 z0>V)ywb5tiVYst$-)U~@oPlzjlpM{~n1+36d0;fn<8*Rv6^SvGTDiKhZq?DQy!n3H zOm)>M{L^?6dMOX4(ETMq>lcXqpx9Fomh0KFD$pcL*B&jbdr-D;aus0Q79B18%SpX*R4y2GI?1w-~3$r z!gQIp^stGOh-|bthyFf4xJf^;#H24*&_lP@vTcn*0l9Z#>#nGDm#XS&~1&a+Z*cg^*so-HM_BM>`kwM7d~ncwnRnP z%bz2iUqU`QRqynkev_+?3zM0fBK}Q;mTc zAl<*=FMf0gx+T97Qyd1aoG}vKFQ|0`t{&*;eetFKRm>aS^U%@SB|a?kjh(xHs0cM5 zLpWyk*GOJLK8E+-F-a{+^dFjY0A4Y^ZYc=!OqNp0J2>@HqECE}m9gzFdu!L9VHz^> z`#1RmxdRv1Y$?*300FpYX}WJYEB-D5J1TwPgYF-+9nj`E7JhQ2`|pPO$7FvrRCfBv zZrTCnZ{3zX4mPoOr_GZx&%jv3PaT&)714J!r#` zf7xh|iwA%3$Dy$}7x5{a@su^OV~s^}RkDt}e|uT+`h4&sULdVuP+|hTqd2WwOz;k!Gkuf6fn z%HhHeGu5JYY@0A&0`3)7$ca_D=(-yyqP_I5uz>DB>^#GhWN!#$;fPAcQAf3KA z?M`__$`dDp_lrRsLt&qBB=#K#cEk)t$BED1vGYKoMfnl^OHfsMpqF zfY3X?pksJIr^%zb3<}YDR8~dT9~ltnQiaG>t_L~e(+`|47Gs1gzGWS=xxcL}^< zAVfHvPjv|}rsw1Mxpuy^@S~%ll+rwhZB&TXCUp||1@n!<2=5AT2&?)#71iN@+T(O3K+W(G6 zZpHfJ-yaMSyaK=A|Ia9YJ1X?)+Ncm04ezu=qh38V>bG_8yNsXn7Z+O!mjMrI*Losn zVpcMYyT|$imd@^nPuM+j#HfOgc}+rv3D|%jnIOOYK-imSC6>IsNJY(%>sFevt<@`o z^gWE(WaL$_k`At)g|yO;&G<|*u<~HEYzIKis>srPOo=NYL1OHiy zF?{K>iTy=2ag+!MC(4IIh>h4f7*nZLF!I?kk7~$}#Oinucbvf}6>C+ao+G&G$NQM_ zegSuSilImD^dHJ~%JIJr@8WcknWrnY!<7bS?SxzWz)z7aO6-%5{k`!xTi%{Sw(U}b z4J~UCgRN6q|K!%`#Q(u@Od@S43|{CNMa+rVi54uR4&_Q+(k7TdIp)TwhXlzaJ%2V4 zRaXANQ!uKX z?0FG|ACI7QJB=sd{VZ^F<%xbPP5*772gcfXaX!lIQ=Dpff zsP|1i3Zk9#iW7I*rLWNuJ@L(yLlL(G5i&Y=_eHm$z;b4e@4}I_;VQViCJ}UER*d%p zrqhc{Y=I4!KzQ!>CtH#`IlJa^j$!(mhCe3 zE$sVUV=AE^Hmy;0>j~YCtnV3t#A`P zmc=tt@gIpk_TZT_#euJRX?>aQv^ zr^d82`ZyHd_9xZ24eGymgFLADJ83B_F0Ptc+uv%F?KGDDM}bF&qg;o0lnqDu$aA!kNplCmAZYezaCQcX9IIUL`)k!sx5u`nq{Xv+pHo-jF9~ zf8=D2CvVgdT52-EWSD_q>OH+h78oN;L)Fdf$bYR&yzL_jc~2cRqQ5&w>Vw+aMY!yr zj)Q-&vcIW6zHvaUnFr0;7;iVgfb3C@_jNk z9jg4exV~ZQEnEaD$Ya~>nsO8F6~bFMQ?Ki^-fteh8HG&c{sKUQ*No{kB=1(%)=InN zlv7GO`cx;m42+6Gpj_$cR7C^0zmcK28^|VtJEnx#d@6deP^s$dJ5F`7LJgSUgzLNZ zYXdC~k31@ZE{$Q-+y<0prwZbBATv^`^D)O$?m*&?ABK1i%`k;fs#U#|*@I`W^~`!Q z>H4tOGu=S(P>IW6vso5>+HgoLQ{l2 zAye?{#yM8Hq?kLIUjF{MlT2pjanG>sXt3X9$UzAUDmBv*)BJ-EMt<-`8Z#IijQpIk zRs6;4m00OV@$p2FQ?D|hd%}D)6F+Puf97^+>T^cMcg{N@ljziS?`>y(Tc93epy;kC z(l`pH20IOV@}b6|z$C9!HLlbBdc57~^-QW1ujB>ac%!>{y#F?Z^q#-9(yQBV*V7JL3nz=) zv`SLPQ+W3pqzC!K>8KX=$-NkvG~;>pPe>2oP@Yhfff^R_nv(%BHi?o;W4iML5UHY; zbhUprk?ej@?JX7(t@XB9m&yI8)DF%5RsfWCdUPjucb}>#v-T~W`Cb}xlOIwhEY*iYH z;?53LnZzH8L4Z(V1==JGf~sgJPyCxyev~Q%#PkIu$1FrE4Hr$tiY_+36u>*t@8Dpw zYr1e0QGIlUCR{YmAvZ{yoG(Xm-p$sJUioj>fVRFXNJYK*1-s|$378GOPQJ}=vz0lR z)e-X3V#-x%yc=Knhz%szqsw8h^wGRe5V#tuH@>%JdkcomxFBb1kb_wxA!Ah7s#K&DnsLiTgaLq~aA7W@R+%@m7AW$zx zoqYNqQez!0wmHEB+c@9L>T65Ybd(j3Nmp1SUQQn=-YL_mWn6Ep`&Y}~uT%D{_hC1r ziEDI$9oZ<)=Q)5ycrM;2dT2vBfz4HbOt)I^b?V^Vke*=#Vut`Y(_N{pL3$_WFK-)? z!+4!9Qzm8p(B^k}Z~(Zp+2Oj?elMyqs>7#i@^;xA1^>4CiRq?t;+>M-$w)9v;b?NI zVY=ABmEIrNc>Q(=V0miQCH?qD?oRx!kdNr?eR99596sCQWb4){qD_CCydGH4{p(nl z4tKH)TapuQK1dzMUp`%)pFBHS`F95Rw-k71uWuT?(rgOlNV@|I;T64QOu%a}AXiVa zBzShg+5=cqSTs0Ci zs24zr5NXcupDpbgX;Gy>Ry$!ZdY9L%ds_;$*|_|@@rilon3V&ux;>S1$6VM__Cz=^0`ctv!L$`85b9A!pbV;Alz8%7fGe}N~*V4!9BHjB# zA8Zos88v#$C0`$7TDh%VDZK6%Ua-`S$FeISUo4MEIQg#V>vzDsv|-!PuJHRTg)whc zWc@}~l;C2Upw^(TR_B*_D4{|;lz*N&UoLvg)9CBg?=&ZIRyxuVeC*#QNlwCe89O;r zPc{dqNflH(6EhBewtOz1Gm{=nc*9S>86acy)trmUKLWjJxF@=h1Q89BBqQusRn+^(I|GTKjMI$)#I4du95XsCAhgP~FB=@%!GxMX>@ryLW_N;G$`9u47PtP~c z*P`LD&G{GpR{>Mh9DI+7yU40VJ0PM)?NP06m^wPlHE)Ndr&y~x02oP3JLenWa`*C# zYc)8_Q<6Tk%9uToaToIs^nkJYdZCe#_M02DZmkjG(F%t!b5DxqR?OzENLQEM{Stat z(M+bHixXfE8bI=zM!n0}+*Ty~VaRR2NG97o?rmilx+b&gieyA0L0j!0b+S9LCmyaf zCgEbWmO8q7k|NofF?)AuiVqQt^z>+1;CcIs8(iwZZFVfTJT0gAmhQ8gix{dOp>FEliDTJy-ewu%NfX$DWu}6NvL^6zr9c5@3&*&iK$-~H^ShO!q3-UkB#PW)bVSz zhD-vnU7Ztx0Qo__G|jE@*PECm(TkCa9X}LRDz9q?M*orH9(o1Aa?~G3W5}2(8u~ZGwYadTMTEaZB_my#nAV@R(^WMmg%w4lZNT zn?ENHPKzH5n&8sRnX_&@H<84V3;0**e_zY~;EwxWMgIReW|oh0tchnvr+$CHUg{sTvDUXzi{t*AkBI(4Ryxut%39MoSfQs4hv6; z`c_QhxE8&(aZi-2bddPj9V*xmfd7fo5gi#JCi+7iFh=wry68(TGZ^p`%!n898^lT; zqB81KHz`kOg3bL_V%Hd|X$G)hFxZj~&aj=wPI2|SO@qY|($D|md z9cN9JJ5tTJPPT19Vl13kR4WBbhjrWj{3V}fZKeDagnh4*?dKhNJn-%huW@e#izvbO zoi0y5ch!!D*NaE0QD3hEu0ZPp#A4sR7soM)rkwS)N^p&Ff8?#w>I{lJ{t<_hfEUuq z0*3_?>d~y-L%^9%!cW(iEm~UTr|m2d7!)|H`0uN)sRU2dV^#=?M`+y<2 zL4ny-?^*Cy{o?6J!8*ENY8n9uB-4h1LNSv$`2;W7dUuVtW+i>0N~sHx8RSZ~02=e% zs1ktbwgwS61mQl(L}$6PW;Ya)>4FcK&K&gkLiXLG zuObT@-2;zoLNIHLQ~71JI);hz>skzCn;EIL4mkle(dA8M7?nokxKzIwND;yErIzI%O z7>%tWx){kfm%V)*i%-4ZLuOSK9sRSNI}*=Y;0?V(Bc84Uxt}Qzi+ijET}b+vw&LV^ zudk0_#U>dNZioltd?AE#@NbkHJUqiE_D@$bdJrCppL~d)cprN4D+)xyCtS@mDH*Q< zHsom6?1rHoNVfe9U?`bv#DL;`tAx|TWZTELZlCE$_X2KYTO0lGj%YVr%pJAwb>bT4 z*jCn_FD<8F_&!?AvkJBC>mCa4spYtFl_uM!l@g2gwPpZqD>@Z_DqnCn=UDI+XVv)d zEu6F)z4Chh66-|k^$P-UmKs+^?N8W}?XLYBkDnT%w41-vz>}omaI)@CV}eDu{zZ|v zst-4FQhDLobn%QD2U_SuD}(LrR(zJBfb1BW5g@a-W$20da7?`<7>f zz9o%wMxDp^<*}4plC#L3l(TROR%j8&aR0BWOwGy>kk;ojFDsGIm5mfvr_Gez)39&( z;+~^S2gnGTmDA^stChQvkB7{dVX@k@MiK3{75~7oWo37Qces;g*4#3?}UJ#wC zkMJ5-tcBU#Mw8ETvnd?m?c_fUYk|kQ1l7;VYo#F)|IBw5Qt=S~9k`-9RUI})ZYshQ z)akQvQxw(xoogw>0Ss2ku;lAw?yH2gZ%*(o&h1FBVTC-DuYJhGPy7m9QEZDmg93HV5@|2q?xT!*y&!QzEMP^BH_Xm-|(;BA1D1?b(_XK z3GYhFtDMYU*odd>=vE5udpwVrcyV(tw77`V4Q+FSi=LkK9qLWXCH^4TL6GqSp!u8V zBQCqGJmH-(eituwD8;2i!xacub-8{v@W9+cOo$#}?Cq#Lpp{W2d^t} z7iug*ki<7Dz(`YsLz_d-&X7mK^>qn1`}ovY@$9D`iIfQ)keVvI>9dhrXXlaN5y(Mi z)xe^vKoiuP^X+Xr3LAMk)h&Uw!9FEul#-0T8iNQn+Ek#VVew^>OB9%UV)AhFH)ZV- ztFticViz!)^B^w!=nY^}8U-fZ;!{I!@rj(?Vj9&7kL~= z7+%MXq?i+qOeOw5Y`texlU>&}3ZfLLBE5sz<|6xR{%bE(`AGi> zXFu6TP^)8_V&>(o>@2}CH*i@rbh&J8OYt!%)SvGmP*U+`f#S& za1(|~Hpp1ob2$4eF>m8E5E$R_{U#aHnOUWg&4p6+z{wN4?CNvib!=Mf-`(rRKxAS` z3WXe?Pw08G!*2PyN0^-Xsvz^7umxT=n&K`@)i5m?b0x{Lf{A#tI%XVO$D|ezw`HPXk zADFa(8ITsE#3LeJI6SXzpwWG)<6W6pRN%&xn7~Uj1|J$ySZpPq&ZJLTD;FpSQhz-3 zr?<0tc2<@C{sB4@<^J`sfbYI4Wb67Y% z?Dvgr>=p_(w$v3x$;dA^8+s4;GimyV?aNQvWN*4RP}>=M+SHiC!1OTN961>&b2}%u zpH1-n-@5wT+}Uv-+9ZVoCUw}Z>&;pl#o?YL0expvqrY9jnnw~h-D_4R``^D|aUOpT ztgY)LBwi3A`7LWeHrD>-a=3DXW^Iz5NzBZ|QT4&{Ex|#dXwK!5osqjz;@yPj=YNk! zHa5TU$Pb0ymyZrv^8j@|7i4~D{+Obmz)k_ZvL&5G-jbJ%Ryhf$$i!G{y-|4zcet?K zRvEMYhn;KpRoJZgU(CgSv3pJZjhJu>Ya2QKNNO1I&b>F6zwv7(pe{7_oQPL^7ZW0| zLXmc0xT5}|P1Q=ZV_zzKqM>6UHwN3_mA{)2P%g*Ar>U`t+Pm8zynIx|OOs84kYpl> zEeV+9XPa{a0p--#19-lA-Z*h0D<~ZHg7auV1VE^J^KWiw-FNApyD|*dDxoAWGA?h- zG@}R%#I2I$CXyt+WLMcK>7E4Z{1}9RAHZY-BDJ+Q(701%eivC&9nFQowPTX?sEgNi zbXa~#lq6nU?OZFInskbpn1ZQSDCEoxg1F_yVq`He8HW=I))qG`rpGT@aFuv2A!e0- z`F#qLS4F(tlf(?o-d@(`Xa{Rypr5vD5^95xI(PyVH~IC(-MiN%_J>TD#z=H=W|s&~ zk+FC`61{J<)Y06UE;m_~~I@CfSYC_sbPE9R=U79I^Pmx;IJb^ul z`4~v{<4zO0L5fermjKYSHYH{D8O=FGbC2#1gN*wT4i|pDS&J~IwYM2n)6R6@XugQ$ zOYIM?1Pb2R3Ij~e(AF)AyHLt{}`MO{c^)~&5x_hjPMq0k!>T$su9_9Rfu z38q>_Jl*Rm(h}W=47HTpiI-1Qb5htn+Oe8|4B^crJBKL4k0|XB@vz^}kdiJ!#F}AT zK_sQ*bbY9KLfTC>;)=~#1J@KS`~G(Dhd#Z(HZ@uFw@S6bFPf>(xw-n|0u6l2Ufrbm zo1y<>u4@@sFo5|*B%lW3%{1eyl^YwDaI@jOi@cz3kK7e&wPUKL){nBE|KNge^tWJ& zB=%-1pSLdXk31&xTpQy(g+E+9&(4R*aZt6e-{oLW!yDsHSq7FF^hxd3;FF}ev{-n? z^3hlTAi9w@@|rk$&taaQ7~|2@8F|BnG|FS&p45U%yZl7Mv>P_9QzcGL z(AP~@;u$1j=HJxrEiP`&d_(0)pQnF7;_seDVWjt_m1?1am_U<$HLd}oLAhaG0Af}< ztJ~inyre<*tZ-M+N@DV8^Tbszrl#X!L)~#jya@0q9~T8GGCl?LkY%v&Z;;SFtXZ^=Cyg>F zA~O{T`OD@IOk}l@22BsuCB7H~Vl_y6Y78^eFU486Tv3?i7s=%rUKMK|gU;h3e@}j$ zp5AX%tSe5|QcA9xsy$I9cB|u@Z}bUguWBM?Gw9Fp-jS+f*}g|P;=&0KN?- zQ?xbIoqv4|k6*&`Fc`R&%as@TBykteDJgOK`5EQ&`#;ey7IIycTMWHd{MkUWXLNmS z^(;GrW;rm=t-kL$L{@xMiu2*7Z2B10w7r+w_luogoS0gKxhLHj#v4|dnizrM@q>|~l zRVbdkz1_jq&3i9NSD%s3zqYQ+->qN?snQR`p<@|2G@>8Q$)MjC1Z`;5>7&1X^+`Ta z|InfWl)P(FlFmJukqS@S>U)-!DS+|hNeFx$U+Wtr?53V;{AZ?JaMI2iAYS={_oVVwV>}Zt*O78d8S^7)IAvtwlWnA4U&G`S^6_ zIdvCdmiCu+upv-pu%Ds}I`7by$B3+TA#3j-XE5jvS)Ok0kSV&8vD7i%n)|OjMq|2# zCv)7dNrLxe(yBTeZCnyzTh>`Wn6e!Z`Vty;-Li(&!#o*(As_0`&%j`U(j5AX#9%Z$Kw+Q9Xz-yJe_UMakJ8sq0@Y6IpdoakCmc_$MeJKuvMm{`l) zx8$JnXXJa}^6TjMM3GVzK<<^bt>Rd5&Y=f%sKpO3$X$-h!@;VOc+C@oj9-n7{Z4FXOxIEq?kg4sVVX^%Q^_+Js25T$Ec3$0Ph(4x%2iEUURs{gsuD zI}%AmPrfy;fx8E0yUKR@dS@}5emIK$)#UE z2iw@!EK@ht8xhass%^lB$s%^Y)$EIx!yOK#;vF2{OsRkGyZ2@|M;W00_I?fW{!O;X zxHK$U5VWflqj0RmLB$d8DjRx)4ok;`1x*&Z z?3s`1$ZQ4P4_f)3lf(OO&XVw=J~@C0%gqz|v&*xCF%0e4`3&JRyaa_Zr!OM2J1ZNQ zZ`N1|y+rvA;Z11wL|z4zp^$ldM-dTvq8D^MZ-Vk<)DG1|V*SUmJ0bOA8NN2%ZSiG0 zO*44`3I+Sq00v~r6S8nMqr{Gh%POnCok@Emmz%-vp&SFx5RnjWh7cU&C_jFA8i9|* z4+OSkw09)Hin3WRbu-2758RDtXOO6z*wsoG`U0y@frgms5D_$82di)+=H_5ptP@G% zVngZ0?j+0JLR4eeogt1ECogu_lUJfyI>~TkGafsTCU6|JQTeE!pcz)LEojVy*(y+2K$@z=+xYeNh|zUdvzkef0~^GU8* z<^kx(yAN;5p^!sogmdTqf#Pbr#*c%?tzQB7NOw@ldZ8cRhD!b|R;j0)EK%*SxV_Tq zfYW@rG6^q1H!o+-tIYe$wkxhSdxRsNUB7xxdTY%p+g~{Qgr5QzdOw$) zvb3uJ?JU{eG)j4>yZio=&`y%P0dB`Eq#USbD>Dz$?d*73ef=g zlaC|Ts4Kk_28RFIkbRX?WsdOa?Ipajmq)cjr;k=YJ*5Sc8TeGjT0s=^X6W|B@=M7f ze`&aip(1x+x4LS)1WE2;{lvO-YF~{t4SGXp(@zTF-W%#?+KOXL`oW0p<*R_OLO%Bh zAVMF$@W1bvfJ=GE|dAL_Be+6yF<|9tk1+(nojeulfng~qqRo38 zVEE$sFVf5TWqbYN&uatuk?PVLZCz)Yj<@Y})H+Rs^)U9hH=jCg(heqDAt;kFYmN9}aBPCDSQA8{+dm4xMA zCyHWSU*G(;@TOeF(ljR{d4$K}?cQdl5!zLt7sDdhC+-tH~* zTD##*a?)?JXsr6aWH0NN89)toEK~2PbM_0w%4}?ZAhpQTrMyzL5%>W6J`* z0pv%E&@=q!AY##2A_b+4mOTFzl}nl8+Kk=@8iBkOB%0*_Az0%M-c`%dro5Vq~&*W(JPl5Zf=&KUuZExZ!0-I8s}f*DbO27 z9lb6kC5Q4ycJlB%DJqRR`MVY(ui_Tydht2ZSCPY4N_f96ELy19=j>X-1ugS2iVRd6 z7+BkO$>n9*P49-Qw6x6!95a~JR)={aA8rvCV9JPuFg7(Av_ezrz~MeI+2LNf=01Cr*ts7bv4}(tUv-~?Gbci%zSClJPmV=tBVda9x^?MO$+yR;b<$>;FR6_Wp%r_x4e+TGT|bi zkm*oH@%_h(jA*6dXw~%SG)>&sf%@;W3mNNny8rM&1hIc}7POCgU%Ls2e1>Wwj&LDP^2^xk-2^RrmFBjBy1A{V9;K{#X!8DLc+sBd6SKMq|~ zs?SvTKcOtYhFj#@YC^5(3qGv875IsHl}aF#?RwI<_tQ8s%gSX{-ks8n?UPq|xsUA~ zpEtMn>>q%D=}x*3uz#55fFbwb*Pz9)C>_8SLDLtp__MZC#Xff^tZ-ExG(1dQs15+H z!*>`CuUkQW8I*etEXE|!*28QKv?tGKteW*&_IkcTA6>FHBjxZ&bce}YUzjyh{_jeq z&FODHCLS==wl$pWtP-y~pF4;xh3)Yc5-q~JA(rzGLm(lMcJerMFWMM)^mY~Z42bGB5n!`^8}nn(jPpl4SM`ulL3jM`Pkz)}qeOU(=WvX^d7=@2g*-Y~BhO ziUEhszhEUte_VxRb-I;w#Zxt(1aD=MrjZlBAyE#k2&Dq%RHr9NLOBFsnqxdb!*!fr zCGM;2O_~ZAyWWap=cNOV&3a8$mlNsE28L)7H-B{W!eq2-S-{)(!8IKiV|+)dlA$YL zVv-QE@3@pFqYV}8BGnI55{4Mgp4~lv1U@R^wQEuBa=)Cx4^mX*7#_K1{qz@a^$f@@ z@VeI6fvV3#`-B=es6{amvGuqgeB{V(Gurc{{~>o2%ri{dVGDcuOCNMNV!U&B+ulLM zuMwah8Xc2GyZhy;ZTnnz2MYZSbwIM6$hi+8c*W!<-vIw3;njGG!+=X`OM^#Jn3f2l z`{BcJ{!W$Tp`!uNH}3}G$HP|BZbX=L-=$GQw^pm{WG#}iW{wd zjjE*pmrj1j18t(^=9YYHM0{IH3OlL1!;qH?bexU>It*vut=)VBvm2r@5xY*Kc*JW4 z$IpO8&;F=VjfT4>)BQ7tf(p2x&eYf||U3C~5+6Ii` zPPc3>R}Dp|a{LMgy50G|Ts^q3R5`lF##x|FJS?_+;@B-MJ+Ki^{uxCzIQhQV6c+*Z zzq^Q8&06c-IxDBfvtxk?%w~liy5tu%m5=nPsDPOu$4Zbm5LO^SEvroiSiN)r$Y3LG zCBd4C0j*F|t$B2ZMid-$#j-F*nm$7ZdURo)R~JQU#DhaW& z)P`hs_G2#+sX=RMBWBTKBMcVNDtwrb<{xuwoRt5J3w`=?^!r~-TkWHVJU?!7ID$J$ zb~lOYuZFW#yDQ!WX^Dj){*M=+LrY@EugV*=ThHG__rbJL3+xMDZwUgU7IURB*gfrr z*Ok+yh#39rY#S~fH1$6&ReAxlAx1;BZFCY67Sv{yF5P4{Upp&GI%Z2r^E_=N%?)-~ zVYPyPsOSP7f>oO*5uN)#oyuZN-_Aot2q|%)jlOxC9IeW*NVcYXZ`?rHEGqEyd+@#EJj-NswLSNwe;$^TT~^X$@p z#Y5{Ymlq7mJ@S!Qfn4dOLcwNLm%+QuBFJ2Al6tbM_WBr^PB}dJNqpm$nquo*3_0r&T7Y;(y$7_SkjFc$(}Wpy#uz$ z)2)>4odr*qYNzCo#W&q?qH$D=OQ$~b6(!wT7ZmetVpz<_r%4v?yB8OK4v{85z8g+< zwI3#z&;s-kgPI?ekoP9mE;p#x905_iCwXn^s_+m%yhi)qy%S<3A-DQtHL8ZHpkTIm z9&RS-frpNe|IWyhvtY! zmunXbInx0h>rxj*7J=}TG^TnZaE&U)$nx+v$0{zgukdzs4E?3=7~T;azt@rz*eQ?J zSFYbh!_@lbeiUv;EqTb|@PH$4JzLC^G9IKW(NW%peq8kQPy##ppF@5fKq% zdHaoD4oMAcUh0K`3h2Cn@Z>+OP_6Mzo_6yG#cr<^D6(iF*{lkw}Y1cJ{q11KHJwl+jKLl={bMILAR_GEdzSD`6P?ste&7ZbtB=Oem9)TUq z5aHF$mYIh4EP5BDodpEgbtVdp!)RI-=9AqcyHECRIQAX0*n^*xtyOG!L+$o94huDA zdDD7LCznoc9zNRod`{n5)9O$O^^~$1$aS?9zV*gX_?_TwIkiV@CCwNj5#*$9A+k%EyuQ>v$ynefX)36`V#@gM6=N;eH?uEh2?g&ey z%G#DwQar4@0);9M4IRf{8aTYYUZ5oA(Eh-z#@zfhVB%1Axwfv%5!H=9xo4Sp9cOpf z>sa*W)`?kl3ioB@>J&T4m7E8P-?dufsP*g}1OiUEPL$ zS~GgASC^<($MQi7C+t<*uJvTijd!)5)!T7^g!@F$Vjom0bOe6t9z>B@6|x?lo!WmD zDq9KrGr@9)qqIa|6EgSxl3NYk0pyIa7l~A!z1wDJdH=edH%LL)_*H|xSf8_U>6_11 z;;e&}!Dm{e$$AW)Mf_F2oc*836*95E|! zbyF^Ulb%JZG8}y(Lp-^W5E`(?`+ozL+awS9$NHL+-A4Mrydfqw^C1Z{aila39fne72qg-wm5fnmUU7K@W2|bV?;C~j z(*xtw!8DJky8_6A!On{VsyKWs{ikHb8z~k{@Grzp%IVY!J2j1$2d~p;^BDWQEG=d!@w88?WT1J_VHJ9H^_^>j^zgkIq^;rTQq*Fmu?HwyKKZkry67a=xP;^b=vv&@5?lkWFB_)y{8CW0mXs*JmW&da=! z2+I!Y-h%a;k7|qbzadA_#$g(Lxc09l1oo|rjg+TbSe z*uGiUYtIVR@uHy)525r$jr3ur?fmcsC@&oBUSkFDQkFH^O(3;r@QMUP&n3y4&i-3g zi)FT65!?)NySemL&~yjzvp&kjM{N7M;N|`CQAK~Y^0KJ}D(tc|3Y@1TTrkqv$8yz7 zd`>PyU%o^IZc;W#^wrv(SG~IKnn)A&Ma@{Y{2K59#yqz3UMtd(Mp^%Ce2(%l`eaD8 zy(Rb1uVO}Tcdv8$vxbv4nU~l89{q3+)lv(ZT3@0W%o=?xXh&W4mR=jx0&)|aMb_60 zd7#~kB}nPKUD?F1o8)B$aYONeGN$ZVPqs5M~Km_He31%i!QpP z{NGFq+hq|N98#*)_33z(5-moQF6-4VPk*z`xb}$yxc-yBJ$i>ABnS8r?pJ(lFW&7h zX6+Ik>yf(LoEQ@%`|FVC*~sxUQr$9Rgq_bdbsD$?J%p%29dbw*rxG2FwGGY842ODH zWXI9dPKlg-YisJi!Sgq2$?-x0ybSj#qgEW*c@47TN^r}q(*0O-7xLG7R&u?)azd8! z?86y-0cI}bB6MXO&l7Jyx9@fR@Y40`>x20KYLb;(8|K8b$no1(wiNh_S<%iTS(p0< zqc%G;UVk2#qDDx1{toQ$fcsgOs~V&>e?9jOaL7|IhA&_yzZXEtG83=X*eAoWZjCcG z41Ktx7wOpS!D^^F*e_M!(s{gQ^wKJh&-@#l6zI7Y3Pu>FL<>J+aUPD_=7}HRd-VMD zKo52&nZ`)OIKQ;>NL{U14_>hmUA*!0+2~`^Y)8p6yRrSS(+5QPr4JvzPx3+D?;0;C zjkUJdpT2qWSR~Zq0O0|8N9-t(p39GBRIl(mf-FW&!L3`cJoQyCo8ZKwD#!50(Q>Q6 zX=YwLvc^)^{VHJUHy#||<_1SkEhfxZsu%e~4j{9wn;$pVl$$V8|8p&vR-R_UCPxiM z-~5w{$W$}qPfdldt*5ZFQ~VBX^VXenszUA)!p=1R*!aNlTcsrD%n^?9A4Rj1K?mny zbm=`@XLh&u6xD@hU zr`{uP0hzqq>Dv>$`~6a4=ichigKqDN<4Ja&5N3XMVWC%2qc1_Dg}bGX69DUVQOFMN z>&$MW$zO2sHW={Ee2LeE?hU@CKX-zWH)s{MM{8zxPI-NSU}2qbeq`WV;e9M5jjfO~zc=A2 z2NZHbu~fQ0&)e0dP(EL?&I5{xuJO_E&VxWzPD^mui#Ba#%7^bWk6TkuvDDVqvZ{SR z?#rKTmg(t(*PjNG*fPL{F2O^$x=(_yHgK7gk@c6Z<_F0N?VcF6Iy?+|G0qRyzCzBT zV^#O^s;=GLtit`41Py=Iq%WUtSv~$a^Fs6b{r7WT&t#Qx^}C$&>Z)s&SL_Px>fLTZ zMVr!|(*l}>jCYCYF6qpaC05ALkd}PTJ=}fp)6LO-;X(7&o7dpxU)*1=HZOex36Rit zI;MX}G=Zb>KGANUgrd?*j{X{@=cU)Yk37g9{!c!#hB^blaW4!^t^T4Dht zYgR58+DO(NP-c-hVyvv3K)6mc7^`(x%Rq&)N1wTU;U~;?Xcnc@-%T!Cur{lOFSXWh zD{(a*5kJub;-dA8H})a~l^EhTTav+#94EMIBk|!2Y?P6h2rwdKk#npz2CZG=H-??O zP07G0=M?SXCK`%~!rT7w+#h}P$K4g$CPH%-J2Fk#6?&pz{L0dJAUI&~Sz8Vlv7d6$ zlefuMk1_d+<5)4{oszxw$5t(=^(~2(mE@Ek^8WmjXsFvLGjo4%P9szV;t#8%GB^6TE}pK2TRPo|{?ZE99>hBlR-2ZjDx z8UX312?lwiyf!|Lz5DL0&zho~H!Vlt3y1K_zdoeUXly%F|8sbIbee5+@ao{v&YfvY zIa11QKd^YL@giRwJ+#$!w0W&v^k!SQ&wN94rce+Uz4Y#0ZM1dQ2&Yw3#9p0b5Gv`U zeJ6=RZ-%&5fILM9_56rz#;s0*wnD^mOME21I@OjyEx)Cgak98KA?XZs?bkD%9(@Wr z{n zf&#mT=sYeVj3;?l8YxOfA2~FK(Wa++J44LJQNcd`ZH`S{+a*!n@eA6{Jxfl}iMYc? z`o$7?>LE27b1nQV7_o?I!Y3or5f2biGoFfO#B%SzK3<4g91hZBU8;8%V@MF72m6c|qr5#5O!&uE)II|uc5cm)X3e5|qlXwjBLxRPCv=Ybc z3<$#5+MYdjWSCk9-|s``Z_k()rEBCF8SRg%HMjF=m))&FRV?9YdluJq$SI@dJ#&^0 z*}D3L7Z0zBQ=3^jkle>>NrQYpgJnVfz}QI!|1{JZ_Ip(=YGRXYy}AX*~;1O!2d)$V%RD>ejqk{lW2g z>%@V9kwGli=yFWWs^q30`lXpj5&YuBil+dsE0#0zw9M>*x!HfRAvY+;Pw!Ul?cAO_ zIMA=6#pC|dnNbT!GyF?-Z7MXsnPGwcmh3CMs$MtAUGHm?Ft>Vpo5k4`fb8bF+M-b{odi7!|bTp_*G zqE6s^*{W2LZns10VjO$~3!9|uSmgkNmrNmXP^`Dog?eX!km8rrSkEc&`iz(-WGtzh zUn@z(^ato6C%ippFz%piVQi$JaWblfF1~C5wcxk3)R}}jlKcCIaz0u2r9Rjj7iMP{ z&!|~DbQ*qocKA$<7avi>Xv)`9o~)SZRMmanD&@V2E!Bz%_qi7<$^AqW9R&z@a0q)ll>FBjCOO8yuxAl$%9V5Q6!-gHk$7krp?<(!wQ>9NrK{D<=e?EPeliRDa%*W=~a z!WC|MhKw6NnAme(N$48APKiW{!n*+PfajgTnd27+qxF><1C?Jz#a zPpLN5X1GzQ2SDAHkpcY__EgveENSRbn^XqIo%{-u95FWZsDmf;0JQU++RH27kx|Ly zM!Jt&{D2$E-@GH^o0Y$kQh>CB&Li5OYWTgn7vc`ZafABxE>r4i9Dj9q0>r&;Ix|9o68JBt>YfD(%1$zhbC26tUZI&a z5Z0!PgPp@R;nc>wNMCPodPDjv5sazin?Or?MCa7#kaSLZ|7b8~&ZK-}Pz7g_`x zygX)5%UG;mY*46fXa|FoK6`*L3u|XcPR=K2;M)`xUqV}7+d3tC%`8JviAH(eFI!Oc zAi@G>X$YzKv)B)q`ta*WBAud^4YU&YBi-RZs5t%K4XN3%OKQ-3N560Ku-#4LmV|H8 zT{#k`jSbJ@u~bz12)BF`ahme5f&ymvH2!E|r|<;dC=V%frWGWjfsZ!s>B2=ni)_$i zcZzh$^SJ|{g;(FEyuT3t-f3>T;^OX9F(Ng*SM8u^SZbl4BLVidvjfvDNJpN3m1=u= zUCpv*s#0->vHwPaKfp2>a1C$rn09S`#_7 zec~V}nX})W33OOj<8SCj44>+5gH}Y*BluMHx$y z+1I5R&wL@5+In65sZTf~UnavLLhUWR8C>qG9B^~C{1ehaJpUQudrVxSXtQ|raYk?} z_|<#k5Bk}^yEFsPij?u`H&dsN`87V^lE=o)@2yWuU3g9r?Vq?bLx=p`l7U~~rIXcP zJ=65%VE$u613V-J1qs{Rz&D8aNZP!%;I}sc2wPbuZs6$*y$YGvvhBqhGWz9%tn=KM z75ll)j5`R1j6dgln`x&$o6e-d|YLY&^d=z;He z`VT(w6ZqE$LDG14cb}=_>=NiMu9$vwW?ON#y#W}0D?7!OP9=edzzZ@7io;R3AG@d3 zZ>4xVjSCmBvuAx#n!?uEi8(e}g_SrnIa*UBo{-A2VdL z<9(^`13h2^Zj>Mt)hsdoM@ClM1TvZ8$>*WTV#Mo%SQj7O#V{)0#UEwZazSNPod&gW z4>t!w9lZ6Ys~->}VMK6t?%6MizFKlozZ<8;dpxGL8=`u8v9~vOQ2l*Y8kh5W*B9kp zdJ0}1*=Ky6u;TTwq{6U=GSZC+&@$%|GK|MGlqtn8vzu;6X z2061_sn&Q`*Xz$ZkUWds^`^G7JFV*?E9Yqrnc>srK_X8TFScP%d8i&q&LJ)jK2y8i zHB||YEMoXJQ$JMmefCn^3&i5jMtK$>WwIpdDruL0C%|}Yc>m|hEL)s<Qo_O9@x39t+Xw`a3+# zV!Fe1%&%EWz@d+u_}?&4I`1GS$y5!^zcy+U^(ksBx@xTaX|D__`IFfNnLkSd=~6uA42~_ScA`vwJX!ujwoG$4bUXxdHIBWP9Iuc&*4+md zF?7#~i&A}J0UjYr)8g^=h`dEY1aM7sIO8p@+UMme+S~g7eaHhkk9w%^Lr*t7-m<2= zu~Bw`p>>j%o%V|kdBacFF(0Pccl?0g0+ykvs)N}r!=8E{3~+CHJZEj*q@&EaCtpvo zhILRNxIhj|ZI2PziG-TfIyf#oZ5!V4Su#N8!??RQIDo(ccK~f@dqN8U>KgCzFn0#5u}! z(z?^mFj;(;cQQsOc0mJq@%x6t+QNfEEM zuUnp&yZZL^_*m)(eV|lg7yFBq|knenLJ-fH}tS{ck2=FyL5E~|8 zNu%ii;(_OQ4!b9WAI^feVK1(9GewT2!)&k6g=&TtJNQ9Rqh|X{u~EjFgge~(2cabI?(i{`i_P;J41(yib!5JMJqAoUn2^Bwa({uTlv z^WM{|DS~9jY+w3Qg7WFFYi)y*bdP_VPcJ)xRC%qeUw%+${KNxrCgMpCKV^x`1ia5u z;G(mW0u+5ZEO;xLaHk!QeN{joROq^DCHj!1;dL3}EH@CD`OnS{=p$cF^$__eR(P zpvLo_a}VW7xp}BfE&jBrGiXyk09FyI6naO5U`9q{(v{ zj*Lpb4D`VDSwz>xviunVvs~ck>;^B6PjpyH(=aHBO5&t53%FDXOuo75p1QbGkZh6T z9g5kz$KhaDPZ>RTh}su^(kz?Jcc-|V_fp|6LD1plvi1e2mmBBV3N0`e%iS8{5V7dn z;pIl@&jZDLxACXHh4lyxU`wE;dhf#ArA`Oi z?#r=Kq5Dy45!xM&EZRJvaEF!W*^5f3aojmWQ4Q=rgvaJSb++)TFL8S9h5=OVr)E7e zAfBuVcop*eQ}o_$udrQBWnkFRG;XYZdhuSQNYSH7ciuyO4*4k*M?Qs#&ih+sce%0> zsK^05OmOV(os!R+qFhuL5sZA}P)Nxl0Uv}}c-9Q_i$9%Aq>EWCJniOqSfTp@%lCPq zyFHx#XBQBakej!=!>TPS*7@pY5G=#vjv>FgP?SIaf_ta4^H@cw?}+j<+)f|cP(=}k zygX*;XLG`J`h33`Ot?v7ezz;@C2016-Sdo$D?h_$wT&LP39vazJ&AEXIDY+rytdb7)XZ7 zZ1NZ}#dpQqxiuQxXB!j5=(WIg&8k{fP$U(O>BqP_sSQ7pETaAuD z?KYbC5IvS7r`QPz&2Qh}s&Aq?QT6mdu!)3r(CfkFgycRWe)h3tH0|zOqQZ}3q%;kH z)aq!u>XcWYKMT-fRi9(?_--2~#LalU&+uvQIefZ~M(Ev{0RM@%6N`NPM`kWB8FYhK z%7DkTLU(Sf6i@_V8GDT5uXYEkH!iIR)0y`yugDcjtoe;XmnP-=!S66&^EtMU?p42y zjP9A=yXIXMzv?PDP`$3um3nifT+lWI2B2o6pwRmh+b$C<{s-djMpu1mQ*Qy8|7VAS598YiIR?))|&zJu4y%atoi;0(K$y)qu z{kHgifc+Td*M|O&G+WMhZ*$yMRTolKb^Xsj*)?%&^8OHaROFfXyT3RYh<%4q8OAN5 z4048;E{l%UBPS@cXV*FC#tjTk<((C>Oo%dO0-Qy4y#syP3uRJ`W**)(0ncS9LS{dy zaV(|so2PQ)-AWE{>%J!KF~fCb929vop7KWYZC5=`&1XCto(zHuL-k(w2r@7259l_U zAhQ2UM63J@NKVL??FVP^r+F`t3jDk`7mj4By(ktQ80#E+c={PW?b$bXok?4rRBPhr zn@Cfw$BvK-a85K=2tW3K@fse!TPZ%!t|a9${?C2zH3dNBOQSJGGNrz6BA|%j+ z0&N+ip`FxN(o&Y+^Vc*S zuOM{n)}pq?BlgMQV>PP-ZgJ@#06ZqLT9QLJ{3wfh8<(ESItK;a$8L9yURrAX;>|`T zzxcVmBRFgJWQBtl{?R=3J#9?oR#D+#F@-!=85a9{WFz#H>aD!pLMBY>p|#m{I2xa- z;xU#pC|`y3v6jp=d39Ja;yUwcP?|j^ARHAybALeV6I`asLIixQ1<=EGWW%8)3+4|H zA^l#68b+#YDa&IX9g$ly>=TZ$gU%$CbnBPsOo#3Nl)KQt|GjSZzXgz5p!d7_7Y&}d zQLKzEpN^If9>?LBbiskvJ&}o@&R*RGmqZh`ZpOIfuF>vMK@ zdQ#EA4e~!>@h|mty(wntC_iHNR{G>R(93$)2<5tQ?)RA40w(`}_s6=4WDiF4`_kkZ zX$foBo?E{8%bIXe@|2AXbi>elL;bZsrLMxbyTao!w?5_Ay_1&(#uEy9UOv!yH@uR* zapFYQkp|L#kiiTs?cUx7#)@{o0h_T2H3N zw|`c&;xa@k!x~+l%{=cg%1ISvv5qwq$X;c?i$vK~33H!Z@>Iaho6eiPnEvPcTbVDc zXa8qI#s5bp0;Kx02T0^S1B15`tnWSkAGY2CD$4F%8>hQNMp6_BLAs1tNS}>j74psSxoHa& zeJ^JqKaR<7MNU2Ox&Dy5LM<$~NmCQ`=+8yJWX^89C2$r`%W9Tyk|az+YU+=$OJ{U@ zbHAn9wrx3@WhKa05ICdvA=^ls^>tJ;!lBQDPuhR`N?Kj_n4edeUa9jF#u7!yWIzTO z#>Rh_v;jVtR>`J!q07G(l2ggfqmoOND!i$iv=$c`x8Ph9oc~t%ZP{Yj^K`o?&W~Qm zNP6t1xW(}_dMt9y>{ZTH8`lST;_8p~>3j#p>)@q3K}%hM*WTUEa}s6gbv!RcI-FKM zLyUE5kIpjbgYzm&&ND|lsrHO)&S+rkT*t@6%OOgl8J=ix-}+adcZ%aT9uE3peaDZh zNgwQp7cRorWp&PSG7~TcGj3L-C&2rsQHnl2Hbvt6gDd}^$NG8}{1Ul`M*ng4`4q z(yTRQ8P|?)_n49y2{z+0;jGvN(D==iub-daHVEdGG(97kQ_t3s4S@Ov-ezM50ozN~ zj<*>`LcYh~FhE!GUmty@+U1GAXQuXLe(k)dgl)J98B@mO5H0oQjjYG=4G)F6F_RRt zTlc=xbv*c7`IAZIMUi%wdEk|+@xtSw21MPVaFGGuPq>!|REMAU+dDKAv@UKvC4Uvf z_s<6%{0{}V!H9eBfp$XdN3xFc&80xuE~9+gMab#ttULj*PZPU4J0#19hK`QW*G(~d z=RZ@)RPNoKxVPs$sjKqEAk>CF1Jyi|yg8hNb)}kU(EXSvX`p4~(q!<~C(wzkBo1B; zHnqG)%2n2I+bZ`3`a@WwBtt~?)pw1`h|ih6$zos;L{|fTN8m*R(?+)^_{f&LFFD@U zosXbG4ILVbeOam$2};FR%8!+eXS=aa ziYI-!-w*PyQ@_S(j1rM*mz{Xm`tOl@$n_tk$a?Ch!O51{Y(|_wFTn*rUHz7g>YKfn zPS_im{-~)&&((PiFoH9c2+j*oQE&~XaVj@uxt0wk7u<6o{M-|uR;*&dXfL@?*SIQLPq1>Tg z#Ugr!U{xrzEO-KB2jv^(sq%X*16dk_)E^q~kr63B&XStWclr^sFGCK^nJ^Xcim&+Y zan+oPSHh5ezBNB~t-4eY2YV1FBEV>@G+fY>D}V3&xxmAk9DkXA4?qU@f9#S{H0;8e z%y5F|OSk5*&2}(5aw-ubdA@iWfj)g4e4ea*xyIDvTkV{?b!vv8Gj{+tu%$)NtUJ@O zu>+WG(z{G=aUfQHVP*R>>mZ$we7>KjGT?k%!5!Mkr2dNf%uQppY0Cj||eMmE>7-ZE?XtNBJ;+48*#NY7QnhJkFCDTUOL zaqk)Zz3JPOgR#g;F+KvL$?sDRC1i1V48C!vS410(PyN~O@YR#nS`Q7zSAQ@>Y!c#6 zsS1fvBxfq5JY+T`3rxmIu0s}wzZyyj{pejb_GE_^&}=S`O{e&2`u<|&LX7R}KW^Gr z_K~g7zg?*Rav3WMQ@P#qYcM)-WAWHJA1=A<)pI(jHqlhIy9n#K zx&K>Rq44@UkJvqU;2AAIOErRrr8{C$>g>vS66UpfZ+Y?lGrH;RTe$(qxm`~?Ils_Z z__~ZB_mL6J?feX?j(q-u9`m7>7T1n@g~yF6cyyjZny2kN*KZBRy5CgxFn=-Y1%)N67`<9G zb-ijTxQ1Ix3PfXeh!3Tuqt1tLsJqNihi|h)qay7jY=^_>aHf^TZZ+RwieS z3%HHV-3=ST98@Fv5>A0DwDve}C~yiZtU?*ZBiP+kuhcNVS&6v1+Q^7 zcSC#F0z_=eIBHGionI~Po||o&YstxKdpR2jLRs-E7K1FT{AeL;X;1U*WpgdUMF4~@ zSt+@5j*GW2iFPXW0Td(~p!R~H*FZPqHWL}nNI_gyXX|`^{{nwO3iB$_mm)cd+ltI7 ziaZoVq}}+8Jc{wxT&5q~d{tH{-J_~t()#~8Am@8*=!pLr?+0&};$v4`08_9;xdvmF z79a8b#9j$u4>Mc*wq9b7e*|^M-6aGf?Nnv6taO6qbS{u3C#arGZ-RZiWoeB>42C*p(QGas>G|%yq9HjwgKQHKvHyqF#M}UZ2S9 zr5@N}d=OFYd-P5#nr32e5nJO6Y)0My6uQ07-v37Xe<_%+vu<~wdNKh=4Aw($CX1!} z8JXIsVFG7xfL&MwutJA~ft^$Er0-euyRL+nyal88{kz!J0H}5c`LmnYO`ukxhW=8l zr>EN-JB9G^^V?#5{w2Z;?y#3%TmA-HbgY5V$_TH4r73I(|Ij#s1b38SDMd+d91R*G zTqM+~sMRr-YEQ67)Pp@&l*c_7{@t#C3>W0t`%Z#AiG$O{3M*EYv)PODaiP|m3iW{8 z%&p%=&r;N{A$`Ps$K(=T_$Q9FufG(mt6Rh$D-+c{vG_Upaa}K-OC9H^-VL(H$QPfb z9Z;?$C+pQ81ep6e-@yUA`;fEqcjv4;@Dcxqc^sE!P@~LpsGu6JMF#1Cke|noeMIGX_++aPAgQjueEHFP+ zD=Ia0;m0*JV_xUzImrdfDJ$EN_Oh_=3KyAW|Izdic?6y?wo2hjlTWxjGjQi%j}Ja@N*=8A>ew-*?&|3=&tw|iETJ8aw7IpyI8i1WCp_;& zrA4RxOql{isN15NF+t=$@&SCD=_Gq)`(A_y&gj-q7R&#&_p@xzactaOWm>zYtjZL! z@C3zu2BCNn=tlx;vVeRrqVWH8IHUhN%JOgCqCcV>g@{XJzfj?H~v6SdfrzR z9S7PmBnrVLC`P5|Sb+HEY9+{@B^{vp%39{N+`X2-n=Jt}T^Ps)BSLb!f^t$BmjFFu z5iXL@p+)l8pMEP^2et(3W_Kh&mNCg8J*3LhZmn)ct4JmV1^Nr{MNVG^AsZ%f3z2_; z!0&k9*=p|XML6wbz=&Gw(vl4dPV5Rydw{H(KHl%k&XY|D%KPuqQ$5D|Qq zvx(3%93o}#vsZc_D6xsz=dePEL^rrgD>(63KH~MI!vdrNYV|7r0o{pm+(uyvAQY`9 z^tj~UqqjItaq8C{-?MjGk^fl7*kWh}l#tD%RO&hF}KAuFQ4ZZvJti4GY6 z^cfAx4&+<4hfa_98TUX`=#bQB5x%a8PkJWYN+M-^2N`Fr?fpn`hTVr3-^g%sfgP^{ zj?eeJJ5tI3Ez~>G$Dor0%!`Yl;Od(5w%VSNgh0VSSDU0uhx(;6(=r>%Z}=GRH#QFn za?v@=Igcz#36o1Y3}AiUyomhP%h@ z@;p&PLQeBqc#e9`US;2D1f#hC{E8#NQEy#k8D`iw`A{!?-S_# zXX5S4oQ6~{M+6<-)+h??ian^(={U_dTe$jXFMMxH3OOHP|DGs|&fouA>o0G>(+6n% znvZrRxMBAn@B+Dfiy@HSEFo9IZ0Mz!>sEJbH~o0c@5Stfb2=*GPB~4&sX=~%KIo8= zsKv_tl+;w~Y0pvrEw^rA2)mN4H~M9{-j^SN_tHnL?OK=w13HU)ULVCPprYj^zl9;m ztdf6;aY7pIEV-OuZT~#_5d&1+K4cP%7aXqm67;_mnrWS)JLK~*!QV|GABL~SkY6Ab zAF-MIIdxM^!fmR1jCSnvE|>=&zST&DK|vtNi|;iDTv|3nxjyGUtUmAJ6KX~e{PmN! zPLbgkc;7-XedPlssSl%_amRl0d;GjzkVCiZ5_NIMB2~~~`u=fjc$o5Q)6Cs^=70Un z_<-Ls{(srfzrVS*UmaqY=DGshHlX~A%YTa=a>}cG+c%OQaw!Hba_Nc*2tXu{-K*844yG>R0edZVZ(hDh5*d-Z` zr%bMX$9c~I9Zs>0E7S4B=UAQ6`2qQWLcTM% z97rJ2#@cc=*YEq0(2tT-yXPo|fsg({ zsk=mIzn7?a?Zu6Jz_0pnlrRigW}Fk|qoEWbmNW64dV=}>8mant`(ni)ierbS%;Cf4 z*Gmsr5j^Y!eQ)P@f`hWHd=jOs!B`|lLm0Bnn%77v>lmWD7r5%8Pu^B7dw7Gm@E^{T zN+oO8%ghON@v(V76+@skw{`jc%Oe^n(z7Ixv%9eD`3pfj+n*8dCNb|460pzs8Yk_n zj?{vn5qIbIM|UMl+fVX!C@mAPqOt*lOY3i0Z>sH5n~6 z4rP}GQ=Ww=3X#Ak^7UB`!15oQV{vU}>z1#_eDhCh(go8S3cu>Nc+3QwGW>=M%5l^@ zuX`0((Zh_O?6V7#-Lsx`SeaiHmR=Yht!8XmE0O#1)cQLABjd^3EzDp<$#Gb9!mF+e z+%p!jH^-KI!3smP|3Dv|!7S;LrbrqBx-+JK^3(r% z2rYTefw6z3rhS_vuY&}gU8hL#0ESi$FBpG!E1Ix`TA`ql;kRkjO36cwy6`DPVp#uf zAMQOXUMCm5>m4DT09o-Cj!B0mJIQQ;heEUjglS)&>jyNf1`r89z_RBA0`MaK9MyHg z1|2X`21*F~mWS9tVSJxoB=o!Id^v)+I+$HqEn6kFrILMted7B5!zy0b z&#Q>yCL)TCjuCG)Dd?dYUt~hRm+`ZN^)5s(QwEg=i?Bmq3)*-eW0jceV{Q6@yD*R5*~5&U}~;v1fWw#wv6s-Bb;b!BO8Ou9A4|m?A0d zp$M7yyn)X6VuQH~5MHg;i^~_ELVma1|Auwd(^xN<>%0~mH~z*^Ao8n`h!)&hKl0kn zZ9%qmmj=vMZ#HLMg1St>|7WPBHN*SD+YCvw;{X5ncKSZkA4TjRLeMfx9msaIV}rkL z2=6G{EPt8O8z>{jQ_awO*3{}GoGT=du8sk$*Z!^GnkXy`qIK2MW7YC|dwWEb|Mk@E zGu?g19Td`;Mj9c!>O{vE(bkyYgXYe*__k)AZ}U~PWlD8l5^fXwtVF5AxQ{wC^YOd= zot?PuqqOh%!{k4}#(=pF|Mo2zA?<@to{&{bv5@k0Nqv@_bpWf=8P66kyG+@)ltHaQ zsu zQi>4mm3ZwmbX8UBe(c|;FKqi)C%)&l=l5$A63!Vha&P3z-(EINyu*Kn<7V8^WXkFx z408Kw3U2P)WB}hEbsIjGcezMquTT!FZ^Ik6i zk9U4QHq%3um2TvWH}!8Z!+@rf5YaTDom9fSe9EykXwsj z?4!RwVDzPJO#m+tLKY&r*bzY&d|_M`zPogRNZH22K+Uhlmh;Fj-V0}v&2A42fr*ky zqACefn#UcQm5*y`EF^1aB2}vm5}c4IgDJSTw1cFyv|Pb!lOmc(0RV4NQ>)~V&;cEK z1rRi)HW2&AG-TxoiE^9}|7>DrWn&AF%OrPU$sm=_p6YHt?I-cN1~K~0o~a+Nu7AXO z&Y5WviB~(VPo->I19zJXs$we)=<3z8!Fsky;J6vIYt%J_$=WIWuKUMX zlHmS7&fzlQ;o;x<>rKsyLmdP~t|NT8-^0D@?HA}dcmgHjmnoS-6wl18^@SaLefEiq zG`KKi??TvJ>78|~MGz&!X3+W9-w(P>6aTpNx=DYY-JfhjQSyJ`7GNk(d1eeu>jhEk z^WyMCZ7+YR-kYF1$WQm~X!TgeqywC{;>^SC*Ry1V*ZQb&Z*#yFI<@`>Pu7E;D0nRJdytQ_zn`b_}PaoFXzt6$F=1B?>dxUba@#o5s7wP3c+5RnXO{X-scD3 z9PhJ-0@sH@FNyK1sfgrUTH5d_FnbV7H@98{HPzMe!h_#hu`Aow25q5-$Uacxq{<`- zn75!PdZ+JR(&(GodLrKbZCdE#Hsexb!42scfB}!L>ce{Uh1)kKViZ7Wzcm>h%-RsR zH4-aZ?(TCkBscNqQnRD{E2Qc5n4~?oB6ingYhujVt@N}z>)IRKY$aw2%`~;OdE>XX zdOK?I_vP^y7i>b2o}g8TUft6#ZzqCYItp4xPy&oeV{wN0^iDxTCMed z)bDqM6Q@s6_!lgiRH^GPK=l&L^M3|K8ef0(f>Go851ZaWeSKd-_;M&cAEKy3(i^hh zZZMUSHxn0fzsml}r0=}jJEg>z#nNP3bNR~DZuMGMk9X#_yb8^QLJuYs8Ru(*I)1

w9lj_=iEgiQ8F97@hX;Qio{RT|F6ey2JjY?^o)mzA9^EYHDicl zBT2nnQRal5^8nrwP<-SWF+S@sr=H--2$5Ftdsv%iGl%;Y563z?`&v7dqE5l$K0x{Q zb^7Qx8R5bHdZW`Fm!81*$F~Jl=|0l`lPgU;`QPXjV-^((*3+W|%wPU3(xY3(w_KQl zPgyXKi^GS|`h#u+%BLzw7L}uqtgblB%j1u_M|GbPZXq{~6UngH7_IXDz1*O82n`-9 zC-u5=UJ6cVDie7yXQ-U+cl@n8+nv0jv|Mfoxtkp5=Yge70HpD81XjY%f?4 z)&7G0LZM8{@TJe}nWvA}?2SU$o=kesjA;O3%EY!Eg2i4JRDy1P_l#6~-0bwLnzB;O zvryH2;mN08UHhW33taMB9fe6u04Z$v~+ZeXZtGP}f@ z!0Y0wcX&WUMciq2>&MvGB-}fD{7+Sf*H!+xd&f=oafT=b>A*nU#}2Ran*FS>xBjxw zALEX&40u0y@jV2%xuY?y4O_Z-*Q13_j$rsvSYujaBnx!tCgG(az{`reO`OPQU?yD{ z^m8BCJK$y&wsLi<3F?#&YZyC61g|9K!RILxZ}GAQRrUErA*&yXXLv$f6DA&kPExf&t0II{5A-vr1iOOm=iVhlm<^fCAjdf5Gm5rQ>jU-4Zhcye9+jNWAkq=}= zCBMr5yj?e(Qb3&*m-bXwgN6X75>GwJJg%?#D?5Q=h)CogH(y~L9LZXc;~kthTWMx? zDn!eB?Dr3+-g%a_1J?_-Ws4M%VX~o^*}%aUKL?um$$cH&XXpqyo4$e=CBECGGxLrn z$viC|c-t-$lK)Tz*BGP?$&ca_5C|iu7yd~q`)aY8L8M`1V4}wRl@^Zc_xd<$@J)1) zzz)*?K!vky-bRPgXvdd~OwT;<(0W^P^&SYp+I9Dz#Zy$!6aC+ooDH#JpFZLcLezD< zEp&9eUU2trK06aJz98mL&!$>-iys1U1CWu&3-j|=IyniyHXS+(`00I)d~A|7cL%s} z{K+HZ>q~bg!H+^!<{_<=D4{aG^Ivp*7m^krx=31eqq@fS7>|V9Hig1ECue6M){kCX zP@#hp#o@o;rJge1>rR7y<|lEFlBB041dTs@DAF2~ZOYPoh(v)Lsb$8si8D#htf&aj zsiQ6yGnuI(F2{bDPt9h8)p6Iry#qk_%P#3IEsF%msk3n_hk@g;z7W%z2{-B9fE{E2 z#a>pMFc2@B`9&Ywdd0VU!`06W3?oFmWxmu`mU_tU?SzsV8fqr)yT$kaVd{uwqRJZ; z4Se&{qNRoO>)tq<1Wy6!Y8hYLFpgYDt4f}2R1EF4x`v7DNhdJ0{tS|WohtB;eRp{2>G0&y*LeL+V)#Ceq?d9A}klT(>>m>A#a4%Ja%AHmr8t@d1- z`%wkU*iCs+J_-?{DTJQSRO#d1-jThLz6WGP-VZK!e@=NYR(nr-Y0|2;Zh4Hc?q?mE z6LT2tt>Bdk@G;GND;*LKmYM1Mk|Bt4)A9M)%|pFMM==9(qB*)boj5g4X+gLTRK02O zJ#2&ROq{p9^N0=d_;9MIF3Mg%F3I)``c+6j`=eI#G6DL0QbPq;>>;6;e{JO7=euV% z9Vq?-2-p>Z4B%NgjF(ys9BiPa^=t1s3FA0g2Ve2r^sQdMx!JY*mOeAPn+T1Y$Q=m0 zmyIL-Q%a*_0ivvOM8 z4WdK1^k3ex>U|xCyd^ue703+DgYSU7q#0H{cUgeTW%Djv4k~UE-fKQ`J+ZLsjEie&zuU_4)=iyy@! zc9-!WR3L+D_;`a9vm`&AXLc>vZzgWKntiQ{C#Gn(4L5q>arg01q?f;y10TfPO#-YL&R{scsxRyx6I750?>u!|U* z0ZcOL-86O2v22+<~LH-hzWd3)V z#;D66#-8}4;$3^9XbgxdN=0{2D@{Lz&?w+$ye-UeKC+!2_J}0FW3yPz!`5^2ld|7M z=5-Mdg+5S#4y#Vupt=%sKIsXDGtc+KzWBJB zCk5&0Ya;clfHVdg;9EA)47iRH&(~()30cU+xV`pwwDj_+l(TCIbGi$uxcELp#)}Mew+Bkn-SelRe2h}) zo!%cpI%$N~M!E+FI(>GzsJq_B0Re;R{c9tPok*^6&4DH8V-S(F?JHyBJ0!{!KjG)S$}QPR-W?z+ z8DNm`Rqw>j)BJEG@c`~6x3IilWrCI7Y-cm?yLD+xId-Y#D|rL2p*iI|7=uOcHhjzm zGj0LB*BO=IGj$O7GdPVTqX(u-T}+jbM|Y#d=kAMW16SmXyuDgw|T*CXJcV5ZaFP5^7G;oEa5j} zy`+&V#oJt}{nJwhLsf`Nf}IQ1FNW1!^9_=h3|#7=#4@>5MrpcfW8ab)*+T~SRU2hT zM_KWN3+=-&tbvW$;h4pcn=^O(4pe}F;rAIkjRpAn@#p0fic!LMGwUB0J7k>_$>-W* zc+6WO=a`dv=^}Ag0vr&vlD)4Jo1Aq+k)WkMiB79biYXP$B3}4+M9H06Pl3S0Uoy)y zb{xnRD@}a@04?WGk{iwsatjlZla1n|9-r{tvVM|k;ohoVe~SB0SfYORKMl%Hsk{Tb z+%rpg>Vo4OLC^&W(!D5<2RC>rS2d*vt+@Ym9SHn>(T70o*l-!vWf?L%4o4AdtlFrUN*9qsz7b zMobZ7L~MI%H@VgY)?Si5gJ{g2HX)2L{|(VcGiAxiS?}B{1ByN&(gxo(7lSK zq#)1DNT0ct`8>4rX`yv|-<#NBtJ9?85%SNnFALb|ZDa*9IjbWBA=z@TZ7~bT#I`5@ zSP4(re`L9e>{dS5vL9c~P+lvTL!?#!^WD3)zZS4)ZNPi%qECeMU0g&n@~spSc6x4Z z*B2Ev__1s_8qa$YQ}=T_9Lil*Y3BG`dcfuacEvoKTXqf(el|4kR!k`Na@d59i-BR4 zO+J-FmKsyKV09TT^^SO4n4GGv&Mc#sNwW2$`HOM!LD#s#WbbHz+axrkaf(xmP83G6 zaF@_AdwfGv?MB3c=HraSa=WF7dUPj`hlDlgWPZz9W?VOlbLO?oSJ>P`vTMcOU?Wiw z#jAWX9H1fb6Mm8P7?OoIX1uXepbUO&Xc)J!u~hTm*J8{3++4xJ;=m)dGD>JvFDQB; zq;rESi=pL_r&8jZT^nvaaJCULs%BC=2jY9FE(__5%I!U}Y$5O7-35#ObT&)cdbHAJ zKZn&h?$ubkIijHUL4m*5U2ouBOilOXFAZGU{1~?j?+A*ec3thSto~DJQPT2Ml$Gws z#Kza8US$*61G{Lp#A6_W;DqA_%eix14tcx zeK-P;dMTDJvEr0Un=_ni$CKjwTC2IXf>Ue~THhfS<0O&fI zh9FlVmm3O7;2S6+$1eM2&qdR)FbnOc2G~0G9P$p`278J*F|!nBJ=s`xu3yadOb&Oj z{&0?#FK6u*bocG&f-*mcJKU@Y8cIT|ss?_E5{1pr%X@=m{U%r1PhpG8!F!pKl<**W zg@g@IvXh#@zmye@Ec*7vQSA{(RN!56MLWEgO8u9;%tjfXZ{n^e&Qtv7WdeLL zNk>nm{5yvOW^7_m}+}YE;cZ{AdAoSA+SEPnWP^bWS&X{7sYQUZ}=O}p+SKo}p zit_AZOA04f-NVDARvR;yW)%99*jp`zoV?Bzjfv&1mb~S+@A9a9p!ssP+^M+9A>Hp` z{y{cT(IaH50L{c`!s7S7G35xth6KN(9c9cR4?vHDRcwK*nrf>Vym-6#21ujMi_G0E zJ{_*pafuwesk|~&@sl)B4V@$@%0zziosP4&*zA+;eI#Q~{41sM8|i)#-${mZ37D@s z<6+K`&Q(k+`&!7)$BfWTcj`AbTVYuycxYTM!!7W7x!68A|4bosjApV zwTW|9LRC&_+gcbb`U^b6w=&S3mf6u6S+?V2rw4isNs)ELv#fWJX}QbtD**_3g@)kw zKEr(b&-wC_)-M?S|F9c^K0Y+I^bubFy^K8ccmA9H=G~HVS&@eG1@7_f2>n|b{rl7| zpRdJkVw8_k2yeg%=-Gb)P-H()Ls8#ZTDCragUwI`i5knQrEIm{`OFUVkvQj91bvlh z2z(KwF&VYV;zo{E!hY|Aut7^BWF7o4kPw1?wbSor{E+qqnDrvxWVf`-I;*xP-#a?0 zmk2~L9w3wJc`YYQxtngSZfLmar&!l9z#I3ixrKC(`Q>bi^&|9mmSK_NrMB+vz z-T1@>U(OtKQ@uMHZr%aUc$!Y3)LQKFq_&SvlaU`i#*m(Jr6c5_ZI9N62rppQ(kveX zv_(NQ!y=PzPj~i|zZz)7t7*!BLj+iq6^QUtB`!bX-*WoI_JdEIv?6EWQIeKY9xO@* z&{7rUsU!oqbFWA?*xn;sTa{^Vhu$H!D&Hg1-xMEW8+%4>t*gU82yGrVz6JLh-5C<$ zCd=6OzNEO{g~2P88a{N5zua=LF4>?v_rOIY47~i&IQQ{Yc}jsZrD%l;~+7(O0Jbfiti+}Xo~at zY8DWs2T?6NltaP=SG`{&p%!t@PzfSO9^7qiH!$gI?a;}Y*8*!f1COM{*g;mio_aYR z;TGYfcxgcOG@8_2%@>o?=l0a_1%s-hDMO02qEXrb{802;ws6yPx)~&LP9oCUaemAr z^p5$%(RnS3Sm)>-@{cf|N8PfrbGA^LNKREg& zVD)btKR6pAU$!rYeX18}&9Skvo08llc$QNP4+I1RaKyh-H)Xk6~{>1@Ixj?)Y+K;*k!w)$xIH~rtzrHzLW z{nrNmF7^oimurCJXUD2MJo7J%mP6aHj0WdgV1aP3-wCi=#AM>!#LfyqekSW>OPOeV9{ddvN)64S% zr~>x6w=W)s-f4BL418ti3nM8mCp`%uS#-I^B|5aCD-?X_mC(+Fq}6KL5^W(LD__Lbgu+JcI+MDp0VxK zq)@B=ilWtBow7W%3-#izPAOYbRaGV@TQ`v#L$VCL$B{M8!4J6d1fmh?^Gcy5^ebDn zfZNI+*3BUj7^|wTFmoc`S2`FQhs=bVXZGwYEGq%4sz?+0*62yg;znSWD0AX&jY$rB zx@Lf9WzR+ylWIfH^0G~zil4~Qsl=Il}#sr z=ffO>gyeUDZQZkg7QF0q6m^Q5(QxJZTh z{2Wbh6Dc;B=!(<3Ld0jBUt;aoz@u4p{k6L>hw|eAogQ&etG$Z5RTaCAl}*!L@uxr4 z^^>GIDFD%$PU#+Dd2L5$G=OB!?u!rsWk{|TakBLkpVvsek^3E2c9savLZpFVd{d;m zq3-zD)cyo5MHH8M98#l2hG{e$T4c-Czq&b<1toc6qMji!5I9 zii&L5#rHB7#-kiHTUcV2kV*y-^WPw?6CQsm0ZuRxx)<`}2N(oHp(W4#AA%SFXkh>P1E>?)>|=DxL8W zM9H=X)8}j+-xh+JAELA2@qLkfg;W?e1od)@q@Cc}r(xS=BP};pG5P}}F<>o4VZ=9V zQdzRevqp|0@VY3)kfz873AGKyw`0kbYtsZ`%9Fz*1cp;iF7+(`?<~L~!?NHwh>jwc zt1r@EA_Ns>;uvNcp4ix1f`G*(^0creTkK_;MuKRRnk}Z;~xAbwnA}j zS6H+{Y#4I4DzA8I*SyMl|Hg6cVY(nBJK}mdf!JI8COCa09Wt||Ewt`VeZQ4|w^c)r<>lB&daQ$t}u_2!UL~);l-VAOzc|MYF z*+-p7cC*=62odNSci(w2BYv{;qFYZkX{)wOHWGhS*hd<1H2w*8#rFO@LT+QGDm&aF zx~ci0o}JRVB8^5*WNx@_Ss3Di*Ja6k^0yCV&&0F$jZ>N9u@@IZ7pOD$kVZbER)X64 zU*5<0^HE5F#IcgjmS;Gg?=2P$gNvvKbvI^pR9j^p+>#iyhv+ zBIxMkL=VNRTqaQKTsZW0Tp3oY*sEp2@nEfdc@xvu$&FGV8Q?I&?Nz4HB2zh(tFf`6 z2w7<}O!M)MPR`&;APxQaAg1+&Ve4^*aDwnSeQVYrNWC4sYjh^0WrBYCf6p~1hYz{hC zbaY$EeZW;^f5f&;C@ZX8jjooqKn%~*{uT`cdQAE ze}2MjWcFyilgxYz+xC7t^tVKCJtgsbKbQ&X_bt3>&5!LBd)`Z7r2dF6j!_;%g=jo! zSlQyHV(<8g==Tdr!bpp}x*dmp;jCLE8CEg0Hb{?O!)0RPk;>W=31E3}a^OW@q`cJ~ zIl8aMdEd>ugASKA+jxr_dbF3|c+NLhi+gZw z9BFOZQ7kqtEVa&{o;I93=@ zwqe;c-AG|pN|6~+R*E|4M>vB1eB0;{Y9P6;#A9v15Et3;cEz&YBxXhK-1q4P0xK~D z=a1VKT92hY-QtdojRlfRnkSqB@&hABWazOTJEed6XSRb^O@9l5Musyc;EVk~>yO*V zy{Us~tuPt05gyUSWh?<=9guQ0yS{(Pgk7hd*#F~q?$|TFxQbp0YC-*x3Xb|0U$_SV znUzSLv>P=R7N<9(7=UCH*7|#2Wanaz68}ZJd`v9UZCuqP^Bk+M0^d$SFgbvf7Pzh7 z|C#S)@&=Zz}d?&H1`s9y*79{d&@XPey< zZS@SHe!|*W*iQq8pFRW8gs1f~hyJwG5PnEd3#EB7*;n@?Cw2q>q|pK!21kE}^oU3U zen>l(N6Vo(di{ugOvq;27?N{*n1lTeE?o7}_qbW+jUyR|7N$^70y$=%vIc0sdI^uA zXr@FFhbunT@_2~9NN^_4F3UbeE#Sq2ORmVkdN>E>lMxp4x|Mu{{qb2YPb;e#QPNxt zfoB==El8#Fk;h3me^Lw|jZ85dnsL*RSSWtxzqE3@whhb`f6tP&iS((!^a^ctj%^Oi zcmiLJ7GE}s96GrC(b6UUx)?lc0^tC!6oU?FePBC>-P)|fDQJ&_s;(c%QFfS;?=}x) zWMcl!;8r&V@&qUm#&cMtB((y_LjOnGOmt)VgzrJ4@8_&Li}n-iy4jQ{?ZftZ-P)?q(WMkDN9R5 zeHT5_>BzDR&hwXZIUE*oasOnxWYPDVA{n$!VnwNHWI6miuEuzP`pJ}A%aBzSr!bMD zZ2*F$h_^pLn<9WX`<_nV>;C9bpufFL)}%yH4-Tir``b zs$RPZaiF}0;Q`y;3=!~`;z8ioj`JLbAGyp0R+!@`g%uy$P|ViHNs|~Icu^DWUF;0e zR;Py&+ETq>0Lr6zSHng{$dva^O&RRh>#!>RBI(jNnG{3y7jf<@`V99MWjh9;Vk?V) zKw(V1c}{%x-4M}xEAd}`DFA46)dTO-nEL8EKUG`6}& zsrNq+gUvWui+q&W+MROWTZz{|uOjy^Xb>$|&{h;Orn$X<0z>*|t-IL$SU0v|$LuG; z`FGVx@M0Tqxnn>Ng>*mj8D`-L8yf?+mDqWv)itc~i`s2o8G6QqcJdx|lb*ngp8VW3 zKgl_^n`6Lh$zxwx0nk9O;VDq^{*e<(h&1l@i{%}i+u^Dtl_oLka}ys<{RD>!t6KD%BEqh|kb8@@rjwRyN%n(`SboDac2u>YC#{ ze>F4R5s>0M8FQL9Y4;6-Q8+E+bkmuYFn^j9UQt1Ur(Kq;V|aTW&h}L1ErxKt-Q1Yv z$Dw9uJD2xZ1-+LE?F?bDCut0AGw4@``)wH8xa>Ob-PiKk?VVaSR{e9rg6|G|dtu1c z4W{C(E2QMpnD==9`2CY_|1G$e1HoMm<#cND*A&=`=MOQqJO@44>wTUDt>qh4mGOje zx2Lw!a-B-O_{=4IiZnW0q%*H$T$qI4cCl~peinG1;{i;s$W3JWB(zqzy{uWwwc6o) zK<-@(v}J;*iuBsIabLxDxrgni3w~mFq*$g* zMS=2Yy~8E+?4*j#r3=eh*E02+G{;9kMWi8MFOyrv1r-FG)nAnni7*Z36*hr!>z{W!PDIeb5t7hP7gs zigL|v9t}pHf)h3ADk>uRUw+%S!FEX#QK*`To#c)9k-_FBJbp>r7)%owL6g3MD2X$K z?FKMF^DTN~$2`B;$R4-%57moY5@ih<^WqE{k`GpDaL)S3Uw*$Tiqg5mz50ZO!~LFY z;Z;(S!#iRJO981zIl13F_vThBE_xy3#NQSP~lmj;4a*_Z{y2`;CVl@A}DE) zR(>NoIl6q#V*GXcd`4jF#Fg;9Dm5SZs=L~`4d*@2fOO6_?SHuVyYGm`{^A6-ok#r} zx#LzR(CnU&U$%GezRNlEr2xo&aDK{;eaAs`FeAnCtuQkWuhHy_)~e_O4{5|7U`hwG zwko!=icb|>Zz7R)hhpxOh&nF5urUqJ7Arx7=-Zfg>X?SuQ8Y&2`LRT5`72ySuv^=C^sCbDnd~_kHIxe+W4Deb0{TTGv`@@BKIh(!Dku<_RWLOPFbe<6Eif z+ZMj{t9HA!u`y8;Z^hoBYQ@rB8dt?v9f+fjK{mTv$c|~Hq=(7U8h}-36+#t4JbYB* zi9YYXW6Zhhr!%0*Z)5pRYB+9wdHRv>8mEd9M&;u21HU|;Lemgx`}ZRTE}Uo{g*JUG z<2i+gg=9epmUb9N4k0%)Hkejuk-K_j4|&B8t^BgPMVrHZ1`T)%whx};>RT305f=zQ zBO<3hc_oodyGC0Hs61(Hw_EQ0n@M0_LHY2%dJjh#*}Gzr+1q&!xNRm0=wyXFBKOYg z{>E>cnSxGzX?|B@QZtvw4_f)IIr?s49!?u9F%OPp8un)`(PJ29mXt*U3aUxihlRL65z8sc3CgQ6nv>?e$(sh7c-r5LWSTh~7qx4dh|5uQ^B z61J^d59K*AZq%ktFI>skEMz@Z%X2QRcqH#-j5u%Hb$Ue}BM@%jOKQ03z>-GU|# zzuhwip8hWb?>G9EtpqFQ$fs&Tx}G8@>Qv*s5_%tiw_4C^Y?87T)NwBkG9dqyK!8N+7O0l zVCk%xZacqTDY`*UBKZLKGf2%vHSg!X>miw(_LO=XnC8Okkwv!2TiSGzE~)+fyJ2q= zN@G0>N`L4BZf`pw+g++Tm%3x`ByaPV#c}qRk~qck<0~q@p?bn%UNT&ya-t7bP6$WE6?bqN<2$^Su14h&BJwdLf)2MJSf(NNTtj>Z{2Yx z2n`0kRyH2bf3}d{=KYY+GKtnsW6@Gd$LsvpXjl(+&o~R0lQ8#0dcJs#+&6-CS6+N; zT2D`@3yXF>UmYgC7pT$Fv92db59etS<VQZod(YuI>-lb*;nf z5mLf*sM%+7t48xXYYPjH3YY%%`HRC1hF(F!iffJOS|`l$8=Z!J!VZ@+&1?4Hd5p+Q z*M-Hn-iYO^WGxN<_`-$rgY0$pq4SyBwL`1c9bH-M zx-BP%+|R{ijX(8ZQA*>q^M(yi9~ZR*np+Q@srfvEc|+oS$!vOE1yKhcA7P2|cyH2T z@h$JyhWQ4!odz-+53Y@7UMY0S$5X<06K61f)5Tzu^v&DJ_2PrGw!J2|_zw5gwVt!x z@oAG?`}#F^gA~1m-7YGGr*jjoj{A|7*i(ARg~^us2sY65y;IeN;3k2K+i|WYmp?PB zXIAI?OTmXfDu+qdm)|++x%NO`Z<0G|T`zZVZzY+ooo89h3v@W@v2*^OC8(U<*ZQ%4 z2S>B$w?nh=&<`(RvzIyJb#%#bIdDd+BB@NJ)Q_8i*7MZv4l;xswwEujpPaS%of!6& z4+`L!FwV`^4RhQW9!~eqcr;q5^Kj2$mtMo+i-Wh4_~(X=_*fS2vv_=%(g&`k2)&L? zwr`qx@%}qxI!)Z%vN_?;ah!L-b@ntp4&%8IJr*5fY;Gy;I=)Gm0Y28(~MQ7D;Ee(ru)F4vn7k zHk8(O6uDa3bNW0AYUzN>JTOw^Ide-E3f-Ezl_{$44#isAubp+#x?|lutK~kvop&TX zj%DwCd3&yT_kQk%uCedj{Z-*k6Vp5#WoXxd$g$3a0A>X}4Vk`kha$q;>F!wW+7Z{R zFTX>N^588{M$M~7bRO$5G6w-!^Bp{JhtqEI`7GXPK7)|zwe#z;O$@E&&_iCASiN4t zasSXooxW4OZecz5N%dtPy<`_d1Am9l(fd4qDEn^1{CGlZgU)5|B%MF4@BCU0Sy;M6 zLZ0DWSLz=Qz0U6~il}es;Ujv2#=17VBF2&VEUu%&tyio9dQ-0^Rg2vGY7()%YFcDV z@6p(~-5ESad2jigu>CC?QTtn{WnyS;@uUP)TPus5Z%UIGT-)Gr2CDSJwYwJHqsi7bbiBy!`-uOmpJUcpWOC#T&#wS z2U!NT&-IF3wl%l3CVUq}ad-_+ZyUQt z>D-f6Ve`6|M`~!ya~(XqstNP zD%B0O*R_y78q3QggU{eN*TOIE=E>zYc{6oxU>i2_zammjaYIF)Z_OniLvtW}KVvxg zJ4iwTEDlo`>`#(nxO(axZumy-sxNWi->x4&F(#ZC%w$2c>gp6R+pG6u8#}3i`j}jK zJI9W1i=7xfx26pHmqP$bbn}qS+`Ra7NNLh}Gw%T!{+UO_jUiuS^FFjdNE}p$3c$j{ zNEp0veueBOFb7{ih@f~!m)!8>!~Jss3&D4uUBr75`JWfJIh#3io+CudJus&6_%#^L z_gAhvU$rPZ9rCd2F5}u^^SG|8x@nS;`MtY}=HAVBTh=SW4G5%gkrt=^Ic?}_hQZj_ z7>CCqx98_z^m}5;$+WMiKn6Z1DGmJ#${PMz8zZBJ!N4T{H*po7)!yEVmtO>h&Uvg| zH#UJ8`tUcw9W=ifE>;g(|K0)oDqLpgmYV1w9eVS_;jX3Dbk`Kj;``DEU@f2jfaK7D zt?JRg%3hGl298!MQGITU+z+>dVl=r{Roqva5Hs95K8y2Mv12L2s|7zQNLXphyK{Ro4*<3Tl%L_T&VuK#Qi6I z&1UMXrWC^d4}K>W!Qb73lY0N7_6ibafT%YkI{^3pi^}f=lu>zG_ffZzjKE(HxgsfE z36x+;FltCjt&X2=ci5gnl^brb`d#5{-^h00b1{v*j+^BjEcJSSHCD}k+^|mE{~-vS zyv=7D+Wu-B-}@ftPO-h#(7fwY%AEbHfwIPC;o}Wg=h6m^|9pwFf}(=5RP#F-%>T&K z_YbuKtV}$dSN*CDH)G5@jbI4Myx%D@|BtsHO8DX`@Lsw8tD`~h{rw8h>JG-c?`Xcm zGg!?0((1me4|s|S%`2*Xx6A2JngckS`(aVi*V_4;-T5UYIJA!>Ir!h>Gm&L|e5~3^ zZ~1rDJEp(B7zYAtC9BNeef8Hv%OpM12)K#chqvqP@4=T4YcJtbN^rvE3_9+m$$wwx zM`wEGe_#+vg|qqT@2q4zV#N+ ze2!N7%WimoYw(gu3Qk~ChCkN0C65MozfVmmh}Vr^9y4h=?_z{TBVD#mCf;zrx)8ZA&x_QZe_j6-h3=oDY#I3P*vw56&zM(!9Q-E# ztEcWC{D{=$EKVXnS?zrQvH46*7dX@m7x~%ndN9L@GmqwNoRWWYSWO|Is&7`ZVsH)h z>dw#c`H%%@HC%l>tZJsMoqDCCw6am)6-#ztsopOD?OO!0r!8pdNm#Y;s7Lm`B+i zap>5i&8}?%4o#xV)^PiZZ$e{*e;kL+*V25$trC5Ry?^`T5Y(`Hg6pe8ZHCG`mEsYk zGj(>6YLymcd=t>*NJConm1;vM*PybL}DH>ax1}*&7>r zeCy*eDb_D{5zad9p6gJThJ442)G%r^+noo?hp}o2 zmDOM=zf-tOhui9^lCq{MAY`cnG)Q+s<%jq%6JSlIL|%!Lts=;bN9 zV`z20lx=(Hhd#?FM0HW)D(whXfuz#Wru6sftXXdtKKn-MNxC@INTfzudS@N2$nm)* zLI2XVNdg8>PrJf18d_5 zQ`W%DA`gq&MB3ck+^s-tE(qJafJ^yA`A- zX(bec%9v8aVPRqV{&x-TUY>tyw&ODW3%56Fq!+gws?=#ESYy%V?uX();l8@jvfH!|%_pki6bL|Mz=FU{Lv|Xz$ZSp+$`S5)s1XP4Z-7uzo4j z3Go7i^E)c3AO772mm^s?C4t@0;zR>p3QZZ+Pf@vA1V=?9LU+ zeeqm|?+~+`<(2!F=R!bd4*ZorjsT>CC zF*to{e_&+55q4()Yc7T4e|*Rk`60AzKv;w_iAP}bI~qk2pB7?t!dm>Ib(cB$NkXI8 z0^WSx*`oQ)xfDdPt@8_gbTp+_jo@7`8)Xu^XGK-<8n3#`*~_~Y_(Ks3IvD6m-Kbo?=Nouzzt-WbTq zT(x&3?#6RR=N`ULbjx`*_W9(}sg&;md#Il;l#{#eu&|h`Ma4svk##t6ZHHtM( zKt9|`6$8T5$)pO1eRACHi8pE%x@3`+zUM_|=VxJI~3Dg5AEjhcA^BKFam)5_Lv(S76H%sJn;`g8;} zGn$Bgzh9loxxR5-2U@SKgJh&F_m-S!)oVl<<67y1@%9l^bY%!`HnF+>TtUB`?kmg= zP-02^Vxnv(Cues%Ltdv%CU<6e*)VBnrzJzw&wV(uWwUq7M09X9ZE?^(ZDD?CNm1(6 zzn-36ki=7KKRi7vp`eH14n@mq@i$Vzd;tQ$YjCM5c1QosI3r+`jrfJv4iQ6F1e4^N z4Zdr9IF*D+s8Qz{K0farIWaO{JadJDp42agyqoE~VE6j0ii&6t_%uAEMs(Ng+^%3@r;@i9- z51a4$$%DcmG4Z^5B)MsZ(rg{dOH=va9! z4(fy?aW~C0<5wqm?TycA%wMz>9sfza_HR$S>4M%;#`rxIGaRFBtvQ?Fvt4+p1>YJ! zxU5qre6w=RcR@~zqDhvu9`+tFp|_pRt(&I<}9-y%x`TO3722B~A;Q&UzvG{PDvo%2YFK zqrUTIqDvu^M-1fLCjJL1pDCgPAhdKK1eZdV?Q3&hJOwMY2Pfy6nr@#t9w$|@+g;t_ zaZbX2uUc~iWGuxeIgO*skct{I;DgAb+>ikO(#1bCs1 z%MASQ|HO5D`TX4@;dNj~C-%`cp@K?uPT`9Zla9jCkAYmeikxpc(5>)MJL0bqFA&)A zQS3wy_T*XuuhhW(PKwAJXy#QT(I{GNH&@@?%bJ118O8_Nvv9xt7j*;xa79BEcYg*E_YPq=Wl7Z4i0wD ztq4e>(j1o_7rI>+JJ>04!d>cP+jKL&F4&VIcC9uKYN%khq@3Jc$9A>)=1m%#9CF`1 zwtoA~0H@QPFS#W&++&qIn}nqD@$zg$QnCDI$bLyR{VuD1wRM4Vyzi@E-Dq*kS(bN` zyP~w@rQ?3-SGERHc|`oAXMV=I1t5WYPj)js=fF`9wGLk?NO?KV>{oG z271yw@!%!?@iqL%mjC*uRAY0pMlHv0_{+D4cX7k`JXZNbuib-}D5Qp|gv8i<7K&c` zfxW>{nfV=9NZpU;kB;(+ER8l82bFCVmd(t}Q;V{Sta%}UQ=;Cxx3?ff}+Iis=HsvQ|Gp#A>H5+F?m@nwQoWLzzX-x9|7*` z5vB`QO=&1k3zx{e!9n*zjS!Nrjyl2d*q4t#$k71=3bGp;v`f;bs^)C*Y8}BQCo?>AUhWZISLk0h-=cv2etag5`uOgXu zkI#{))?rULf|M+iEH*Ko)R`qV8;`S;blH|OCkJ(SaPEVQ5*ts_Y<6xy;db5Cnn~25 z8*-8+9g4;mM_X@6dmGPw&`J<2HMUr2*B8g@&f3;x2JzM2Uj8ugEP$ydPhyM6CD4O| zrDi-9UZTyMKPc#>`PMpeLV6q+NUDJNLg~AkwBL9Bx1t)qqWeOmbxC0Gx$Ebi_uU39gX5C0zP_J5P{lo@K7!w zqa5J^k3sT#_@NvCe_-AopC(F^`w=<+T+95zEVVkcV9-w9(WP&Jf}3X?x4O|C{V`hY zbzqz0`i9Fdd9kbL^c~4xRH>?d1e4nWh(5(EEQ=f4ErYY)>oZ<=t&*M(!7xJ!n?y;+ z_Q#5hFy|Z*?DTO+Y_`|IDDT?+i2AgIg?VYJ5=~8yq_hz|R_3-%D+LwR97j9m{WDY# zgos`rgV^kKT5ZzE3F22f1qJLCX6fAQKg#`0gi5(APfm0#j0DEaHX;$zA`O-n>v86Y zYYNjgg^)D_nm@9l%xFGCapST&IoDe~+Mu@jRq8WK&@@~9OfRQ1!dM{2jQIM9$&o-8F%VI^Hb>*so!`AbLa>G+iAHd0`=UU~wp-b< zHzE#fUsy%%$cs{>r1V;sV>854{Z=efJ}DmVdAjXv5Tz7WgnXM1&CRVl*`f{#3eE?Z zr(e?MY6dqVXJqSExhq+zCd!3}FxN}*Noa=@DL#m3QCBt2Z??Al$(tgarJ=~0E0a{J<#w$;PoP8~KA)49KBpaQ2QvNw1B~-j?bkHDG`4oOLz8o$sKW7W z5@!ymX#2zSZPuK80S#0&Xx8x5Yec{1dt@@vwX9xeYt?(+$5QQ@OwtirjINQYOl9T_ zjg$19yqvTPwPKA~t=AJ#_7|dz63;si@BPxUYP)oN38FP9`%+UIlBYx;`?Y+af4MTU zdETYZlsCVcHb~JSP1v!1Tw?s@OK>pz>?z3#8^jQai%q-`O}*@WahbTYfxmzRz2s(Dd@~fs+@ePU z8alCQky=o1a8wpbD)t!R1LrhX)&9aedz78DjGQ=fA{Q@7GJz6heMj4s5G2~}RYu_Q z`-T)l7a^Xp*S*dp`CYfQYR9CGl4pKi1YH0ewUTu{5tx2Mcgd!y{p8HhJ32JG=V@OKJ0}IMu!($qQ_9qRk zOt(AW$6A?=JM338_` zxsp+ZOCu5&5|p`R$G@`(!XQm=0G9n+TrDthdpc47O1~B_>>-8%UHa}^5gZjB1pSzB8l+uh>h z;_H~+uWy;T;r4YhVffavm_nu8rWcC8)^tsnQj`@VLg*N~IQT01b2Qt{-LiG<#@5EK zhC)=Saa<@))+efxg36*Hv&JH*!sU#az^Qpm!dfO-vil8X#i_Y~oPIl5JBRxg`#PKxp&1$b{s+ni-{*q`pc>qi1COSn}x?m?5&o z0f6w4-#h_=j|2=>XLG`{hPB4Z9h#a;_4Mi)`^`W){)EG~xjjwmOKx&Lb|Ju+$?N#^ zeo;%xSUV619U2+v1m%}S-7OiI;PqyPHLmaa{m*5r4fGv{g#r@7Ve9ONcVfci?VWR< zzNU0WdHJ1Hu-flVw9RR_Y;10=4cvWqAT$y8ni6w(vGgx3hcR zGIM@}U>RJYBH{gar1F*_e075TAL8jlRfpgoxE7kmc$`|SAt1wA(0IBFJ(EZyy0}oU zVDcH%7A6wZfS>y{M5*a?ORoN=PLMH5-6lz$*P;B_I->7P+Sr8HJNKh)g#)9b!H-1u z{qKiRthNF32WR$UM}PP+0G9k3-(I3X?zlM`6PJ|GMjwRd6&-B=;#alhB{ASuNrwWq8W zC`~mF)vd6XH?3%eUem_=vEw_~G^P&5QkL@7dXa>a7ECDHD=}c~{i?|I|85ZZM-W|s z_2FiF|MrWe5Yv`5L_J(8VGh5XnDEzJ0mGrxGr>zQwAn{Yf-j3AimN|XJ<^~+CCb!n zr!XwGeciPtXmw>ZZZ2T&NZHmgAdzEd=ys6}!Y}|gb_Xv@VM2?&Y+`(HB~Z#Kn|P-c zSjP!6HU$>dd8bkQuB=$LWj8YY3gFGzSPGo1qac^6#4#ww{fLpZO&E04LyvFCedd{l znQS+NE9aLS#rqEcDYA6P4wx@6?_T-~e$BVgo=>g^3?XTfv<17b@72>}rzIojnwrC^ zS>(`=gQWf2_e^C>`Zg+(!*z?*c}8y{ha(}hG>i-^{?ogeS!D@@ebUM9OO&)I8mdei z9+lOR*cTtqWE^uB6O_H3%&Nl`d}u$Nc9_t5)H-yuo{)On-8h7i`eTbUb@vo=ZMWLp1pM@73~FZF}TE6(wzRwPU1P zg0pL8_M5rURcSj;3vk#->4xj?P=m7mxS7 zb>3h~MCty?*)*cntmy=j=QaR)L-VyLel1NqGms2<#M>>dto&$PLV`sAJT5QW$w2YS zPmGKGH=6htQCyK zXusumR`Hl8qCN{q)5am|`V;~7AosWUqJm|tVqotcvd;~Nr*^&oq%SDe#8-!AFJj@w zoq$Mxh+xKYVmGdX^Av=zwn-a96?JvN;omIdWe_Bd@hxXvWJ;pGDR~Z zCU(z8aUbv^lB#@ER1AS~hqUZ1G$1^~ov26x;Zl5+vE*V`U4#dDrv`lqWtyL8}HUA*es&>8v%B z8@&<{T6$8kBPV!t9`u;{HgoMSIc@0d>=Lj$I~P}$>yj>2+B!5Q?;I|f?zSyvi&$67 zo-)suzhPf4KU{TydwIq!k4)A-&Qo=oVpREo8m^#!<8eT=fx`2Hkfx+mw?h=mh!WCL z2t^?I78kd;@)K!t)3B0s5w$$^ebxXhF7KT+qF>`H4wDa&L8BXF<}}trn@gWk!i`y4 z8g5>E$Rbk8PO?t%$3DA7cT}sQOA--Vecnrx0?`uYJd)8b3&h+d{IY$;el=hrmm8q{ zUL1!N3AWd;$1h%G;#}g?jFZ8f(aOGhGP4!CGxvrYrPk_VdywFXZ148xD63IZfoS!O zOPsa~9945%NFJlaH#V;#Bci@stRQPF1!~=`^R-E8jwDfDqKKA-m*7J(G-o6S{_vLD><$fp}^$AKe)0^QkrW3n!`Pccx=>GY&g%B7> zgI6wEr4_hirj~iYIW+VR`z)vhynW2R}S%}zo-95 zhVF)`@gz!1KgEOVwET2uwjNt*+=Ak_va;&JQPc-Qj}wNi?XAtNjeBy5`<2%D)PJYj zm+tmIQX21d9#`>J3@hha7v4Rce{q@3jm80KvJkAe*!Y#1HXClsjfYdJsvI{1B%peP z{S?o@t7)7MF;I!kte)~$mcum8HHp9eB|xlv@yg>%ZJQ~nyI)8VFUcdr{rC&SaJsw9J+XMaIXPt-uUQp;f6>ZG3%{Qmgi`_>F&Ikmti6|6$}7a}Q$q57%S$Bwfcb*sew zm)vr_QaSkpcm%#VMjKmyObbbrZEaLeBj{Q5+dP>@d`nz$VT{GqdBxRUQ6ZN)XwlgD z+f(c7lHW6Wm|rP9PGI7voM^oa5vi78oWM%pw|ZRiLS-jM3>@nHJeD()R3RoVqq{TR z{Sf|iwpILV_THMwvsbljUQ5W@ah$6s_{LujYqaZpG=HRLW`_SXH*I(ze`YKfipVPR zx^%UT>NO>K*5EPFFldJP`#UJev#fllO0JCuB`AA#L>hU=^y9U0qCC{FO8LGOG!T*y z&Ra$!w$R5WLG`SR{7Y5mhFpx67h_kfIncXEqm3319j$6-w`qxx9~*%JwV^OsH>b0C zi1-)@2^7OOOOGbiqvN;ecMHt&1!Gh+Ra9)aMpKRB6XLUr@;XW(fEwa(S;Vha->cZ? zg_VkCF(uYoCfA4(m=%~M@;XG9s?I3q{_q814u(sR|tZ{+)<7s@LP;IH}kSTj|okvs)v=UOSIgpj&4 zxr_a7CQyaG@qHWK6pS9fqvjnhrN9dO8c+7|&Y{ytVS>=Jcs|$&=NF@qaEFM0JL~*q zjWUFhk+s_azUK57A4uLIS6*H#@1YLv8~qx&WnpOHy)=|7uyA{4x<2Nv!R+GJ(`9b* z%Fs(kd(9eCCh22BqTt!J)jr=hbk#<^%Sn&kIf9MWl|sah~F zCNov}VM1W9co9XCc*WcO|CM%gMc_QUpcX;#tQem2awj5fIvR4xX3UA5i^_&J#vBO=X7$m>5Rd#2^aK z_$wq`+n8&~LSGgyi4t<1eSB4!@c@0C^GqTDA^j&nr=Q0)W{V8cR?}jgUrnxkpu&l2 zip64ec`5dJAP^Cm#m`_4C%aM-fu-z+K{iFNg#rnI@zP zV)rC>pC)_92ahs6>LY5`_fg|_Cu03)~iY#R2j5A6fv1nYvQ0*Di?TQJYKpD=+MZkHn z+b`in4lA7N*PTZg#r=dC2zPYECg;o`%_hxy3#8)Bb%Bbkca`1akQ+R#=&$G`1TITX z0;1)O|EV5pg&yDj_b>KJqQ3qVm0DRQ^gU3pq;bsH=3I_kMn**|sroHSq1@*740UjJ zv^-;1<=$2T2v9~A9-ryu#ecA>gAS;Yg}N zBW#@;da=zzu8*sxff2HXYRM%RlhvjErrLmEc!Yiw5^a!H*4r&{;>m3u+{sCC_7ynX$ zcCFQQyn0R<6i3S{1e`{>{AYdD$Ws-$xju}?OW4@o z7Wu3Xs0JW$sN7Dj^k9OBN)ga}W;P9KJaq@I#VuoimT)q=K(Ou7N7ws~ivl1%DX1rS zk~BUk`E;(7BBN-fDnlN~@*LKW7JHN)t3fQ_8Ua&d^E|Y*l3-^_p%OXT7)nee6Z_+5 z&;43Jgu@Q)XxX{JZ_!K7<5N@DTsm4Xu$9UxOONb33vrQuuy*QfWSrmAw_xQ$fr-@9 z(vi{ELX)YchQ@6N&tn~eifKCHf8nsd|K7YNru;eM z`yN0;Bi<%oEzItc^*Pgy;~Yz$i&9ik7v;+cG|BrJT}yRSATtPH_&Ii^iK$0$m%VH z1bxLMNqDFtY|R<&rU~kIle}?X(swT06pL?m2nZaZ&gkP!2+B1fynHfFU!S`f9k$=< z=~nB@vZ7Ap>gi=G`IfwRvLgH3#gH7>JAQX{sYREwvFccu3)wsVVW#L0iX?)5t7r3Y z#26kZ#zf4`Eh)FxajI)A<5)6^%pG|_Q^L@REvnA`-Oc`uk`i|CsI+R{d(0Su;gK-X zCm<_OtcRJ=>Q8DKiLHE+-5LGuc1(SPJ%`n>61IWw7!*P`w$z_JaYU%<#p0TiD%rPY z;LPl^y+d&s_kQFfVgl*A*%S4s_XsRJGrB0Xh?=ejQ&SNdU{X{n$~= z&sJPsx#+T_lJAP^vhYeWCggq5Eu@lMo#H)imioNqbzCX!$pE*o9bz`nuLeVC_S%^*J#GQ;+vrQ+G-nw+C z79C0Iul-h3PXNQNyc{!7C^IulrOw>=;45?Y&J6OVWPGl6Si7&VG0Cg6k_no9nb3~F z@#Qu~sfZlX%a3;=2w`60ri(d%Ib*`3zYEAYtUmYQ}4tzg+%Q@u8(?W;+7mXWjD8Uwj{nRukkW)Yg ziXMw|pWQznR-WgVuwnAmp>L%35LgtVO47Cd67NVXO@WzKk{S*uju zn_M-0d5=Ea^{zJxZY`c<&bw?%`cji9vAb`zMxR%POR@^k#t40EHm_W^uU0bTsuEUI zT*F@PS}Ubs^^sNl0p60VHq*q2|D~aLo4AkRk-4h+|ED}cY#v<pwfA}NODv$AxLSJwcF>FxhmDIZkQgQ!(fX%icSOh-@#%MF7G|BY$<9?9P-cBj zqXy28vZ~*mAd3K^3M4I4+UpYgR0|WMWk68;8p@HP0g^Asu*Atfig16OICBH{h!~J@ zmz)hhai+ zi@QYa=~CUes%7j`yB19Mn{!ywAgel5fdUnar*V=KG*~MyYZ?=j^>CS@QmJ_T)p{34 z0;+--X*ajZ1gbydyd$AT<^L#;|F%mx)3^M?ho1&p+PK=PDQXm{^x|sdI9MSXI?rpz zX==irVklET!Q_$BF?hZwH!$C$Pm#pwgPz|knq|2=6)dk7m|pp8e2(XB*9Hu>aeT~7 zOLOF{s;^@e4#ZAinFIo9P2s#8J>j3s2}^bYP?`Yi#>Vz831)s8z~4Mf1Hbe8%V`&`aMpFa!?f&l+do@>qf>N57;FE%VlN}(!N#^urdMDiK`|N z0HZy0v|*C(l{_@5qJFfeNlHqU4sWN^%1dZD5XG6ERm>YUkLmzfL_*DEn`Yk@5wR^3 zq)br%WmVStHSB4AQq=qE_`?RfuRsN29o({)Qk$0$QUNw6cR8ry*{BK8!P%%Onfpav zxoTfKS#E=!sbjvyjQ}aim!*o?a~^2?L?u^4n{QDG7}A}e7YEm&h1au?zrf@?D8{FZ?;58Q_KDs#WHk z&k1<1dkpVI4dB4k`MS~_?G=@21bE)Ao*77oH2!_!1xD4B$~-^W>^FdJlu$q_peg7q z^#b+P5G7ze;wwYzU;_s)FJ12lJ*G~1?l$ze&pH>S==j*VTSK*+{PnUzB4MlMmrlRP znt@}jnkINLLrH5b*kNv|IRhy{ODv+e>n#jD(;#hgioj22AI#%>l^F8{PWx`H7y@a8 z7iUWF}o9sKg9#ljb#?W=RH zg6FdZ1uYuPNpsLAqDYG&km1Kt>D=6sccaj-n|?TMo@~`ILp<44Gq+E=$a7|3&e&|P zHesud(Q2@QM0ne1KMRTe+_{+@iIII=7Imn8dZXv@=NuKz`{13xGTSaSK5EY6BtqX( z>HIDu!gy|BeW&LMg{5CVC9|v|t(TnP{}~?YbL&Niy+eyO@cQ+(3s}I#?hYop7(Z7_ zx;uv;8j?`De7jnCVV8qD(}gbn@uNL^$q=pT^z6vEa{kxRy7?=co8^Xe`eixJ&$Po_ z9?`pjS({qb-tW7j0+LL!MC1$i6bf$|4d$H93k`9j!ip3*GCw!`h!gcpO_wn!))hBk z^BB=SXb5;tx|gUrbk?4o?h-(n6PaE^SB^y3~@3y7VKMu=@r_CIo?zbK1Gm zYHbGB-2D+{saHOQ@~21r=SR4TR52h82r8E2g|=}*kU;9tx0%Gdo7uI;C`3)Ccmdqz zww(2g*YDZSi36^lzx)_M3JQ3+pK4z4Qpj=RZ7AH|!)fyg>W;U-=?79oz^Vp?gfg)3 zl&`r1ksa`YABS0<`uQoVYStK3>z4ef4qP`fHvL70{{`e(^#;bOHJ2-AP?my2l!|a` zVhVYXsyX!nbYv+oaqx&%$t~)-fuGEx$_zRVW0K(xhHd8e1cmhjrf9NU4;vUCF58^C zSC68L5T(Ycnr`K-hM%|t%lSyJkcNY&&KtHMt!M-N%P|MQBkD8aT32)1*Ctuo;l#jD z&W|oh{u=?$*!*9c<+&_z_`+=ZeyN)p-+ki_kG23KT(#rnP;~S717DqD^k8ei-1KSH zeCycF%%u`^`xWi$D;)pkjgf^Ji8?_h(1~xK?WY42f{`VC&=TYBoohrSAzCX-A^RDY zfC|ePHUd_I=xY0oL3(8COZ*!1PhKqvVX*Z|=DYBn%CWNUBNT0Yd3MlXE8NINM)I``&H773&1F zIIQ|gGAEp0?y|5AkQr_VrG7OOPXRhet6O2%SCPN^Doo$q>xel_vfGYhJ(M3ac@ z5^l;$UsX7;*s>h(_zPp#4jP$M*}pJ=rU3C>@ixqMVfLTxWj_v`u2ykGj| z+k)f=S~-dzST6cxdDd@V(f;NOYWb8iRO(7jI;b%D@a^nNs;7ld2QK)RVdhkLF@8Hle=_fzP} zQ6_iKFee1HEdJR)CV?@w>4v)=p84=Zs8F^aIM@HKtSq|b1#_DKX#PK{zB(?-u6Z95C6$y`>FzESknW{RI+yNRQ2_w~0qF*5rCA!3 zlrG5yR=T@$e}~8Sectbnf7ILc)B@ri^3}`ir5S&Q9GS_fB2d` zOIs*6#Er5XpGR%r=K7I``KmgtM*&K`bw%he~MU2C5rGv83*hu42ZCzUy8VPTG> z6D~D-*uzyqgs!8doY(srS4=j#Wc0yX7US4Zz)i4t9>6CQ6le5PH?OGvdshen$B+y2 zlP({R62pOEw{Lbt2kRA@ph44U_&f9E7nu)M(&#%oNC_8p%*Gi}z_0;A0f4zZOYQ+| zuBK&o=4aPTuB|mWY%P@vu8P?z41l@c)4PcUh>4(WukS)fQqn1J>4WZ8D*Z{k!SaWnV?QUJ+N+79g0 z>L=7L5rlQZZcfk;`uS>>4M%|+8edt{t>%G9`zPd6u+PV1aJ|`|(KG-iwX(BnTXR&S zz!;gFeaV#ioHVRhcsVfVMr$C)72B{h1B^baC_6@)()UUIj1u6!f#Nb}DMyiTCAOOu zh)R9|((aQ6E*YU1(1?i$-iCeb0GtJZ%TpWUKf38K(WK%Ez(+ppJ;WZL>ih|4;YXeU z-5zh9Yb&?QK=AsFN^ca#j$RPK6+sR3)|G4*Htpa`^AE0e$bLq9srHp&y_`0jMh|Z0 z(@~L@=+?X4UwqYGj}zE9JM%GhA|YgAug%lKQq;I_LRiSIE6(ln^M{|&oQ%S=hgL7d zHkz1Au2i13(Y<}W@btxtft@?=SG#?Y^vK@sZ~5M{E39h_h3`5S&SdBt!OhzLToL?e zey!Xyc&D{(fgZVg^H4bofK?hauXx-YG+qY&{R|Za0?w%zb3ijRn~U9p z8gX&Nj0B<6YR|p0p{7U~N0!nCH6;@*g244c8~D*79tblI(CnPrK)?E94sKxsrNe3{ zmPE4-r~WOTzJNkIkrAU2aseJ}GBShl@$X~eJR)raIL&SdjGrd}2XQ%U@H6<=bsRd4c9SfNAKoZbysosU8}d{dqhK)o*lgCW1N>#*(kR z4-^y)qUQQEJQiRgnO}_Sk};HZG<_oYnNJ&ok7KHdN(_Z~gIFyL`&x}L%GGnFOJwyn zYi4r;PJn%{%GZ9BEGE+)va1C_&rmbW`omYxG!^a>7}%F>Bzv!WJR?!&4ILf_SIgyS zkFSS&O8+sAp}^_wfERD4)=9mqk2$J2V4aev*ik~zG5BRxQT;8;M285Rt*&%^hnp;a zIXSasQ@-X>_pbb|ARm}YSujh+d*p)+^-lyKQtjm|Os}4~AMKc!ySXXuyV1owOYO=i z#NZv}{qXJ?M5D2U&<+R;0R|o1^Zuk^rxD;#!MT|XZ*-S~v>F2TnLzV|bcDy@f+duG zzQJQ%z_O@5A?>4@=SH}21V|1tOFYP`czIu(`ECPD*(cSfK8xW=Zb0XPg`P6I%Yn-V z-8p*+%fW2dLT~@TELUdcbAl`f1Pb`-~*<7h>rvrv>;ag0LW< zNq}f9%`9~8Ufhvvc?>_XGqv_g1kJ{?Fdd)_!aunz4uw1}#xm6*T60YTOt{XCb{<8R zp1TC(Nq5{DFOvT{&&^G~*hf`vETUhL4sEUUA=m%A=05U;qFdhr&P$Qka3~;KcMewB z+O1Ew0myxVyEM#Gq(AY%vTR(jp#G#uGrK5-s^J9<`OhWq#Pca{pmubs@79P=9HEKn zi!0(*S28@FHC@t*?0nz3@DmQ@n%oR3dMqyM+G@grQ&5LDgG~rx`y-4XfD$S%?aeCj z5Se(*lUyWnf`$?pw6)nxJ-=$pvF zJ72te7DMj@uUeR_kN>096k68sNsQA883PmRWg__1d_uXsW6K zED_$jY{yD6&$6-~OnF04dL%+eIId>3K-p;Nr=pd88=E*DP?WWa>9I<<=#=;rKP1S}*9eOass!{%W0& zVvrPm%C+J7J+5w`5s28LOCNA>HKSxt#%^9Al*&|LD6OfH$yBK^Z8`iy~pT-9l+c8|@%IAzI zC`7nyw+J3@&w^u|zNB%VG1t=a7cqv%43b9?ko5w|5V~>ghrK-X%IP$JP7Vs?BM;iCSq$CKnDuFUem7n>u%&?0+Ec{L!pfS3q?PT1 zL$M6#iNd1T2^K-ej~WXR$cBNQfUB89d6|uHpI4)G<>YYz7RYvi z=1>BlU_*-n=M5$?bAh3Gj>90J*n1tVXmhpL#r5tS-?oSA1So3RXIBE-Rtyyo{ z;Y}N}5MbD|zpQ9@7pkL>UHdLyiK?(QJZHt8M0j-WrBh9h?1U0w3Mu?{T$Dr^lqVin z%H;>tzO!&7EUT75nTf#!LDhF5S;Sa!ch1VbB_X{tA+gr{=pzDT_;zf79|b4|`)#b% z7ySqXQIK)Q#{K0x4J+?|J_VFx5Vf)jNa+Vs=D$-rs58ZmrEV?{@)&xpnHvf?eguTk zB+?{MFg)|3p7R2tR)8e}HDspXO?SM+Lm1%ila5F3QmURy?aG70zvW!i@$&}K=%N&+ zPs(P)t#wv|BA^JMsw7uh2|8g_F0Z@zih*XEI_@V%b>wyg)SPopJ~ggKT*#~I6EHYn zV>{29ss7x90a7yhUoOCY&HyZGU4}OtTM;5v2;f;Vu^?PZd6B3;mcdBCc~6`DE(-3# zuBd>$#e7e!ZCHC@xw=miQw5DsR{A66{|T%?Xi8{xV+Kqpm={K(*qF)mS^qe>2$4e| zkn#dsd_`=f?0oJNg|__MnW+y|ay|bYKES~y_dj{?n$B;0 zQA|o>@8SyZ;}m)TgKs)T;SGW>7g}CgBLn)F1XyL?^WwYKWaG57#=b9Z?0HViR)p70 z>7oI;5*XZIR<3N6)oiWXR?fjI*5;e~T3v#=9^L(MSf>mPUfcWzy(jYvKLb(W3v|!D zGh!Kp;*w{+X>(B<`i*>&HCze+-@Q2AY@KtQE=xKbdF>VHE@y|^)kkmt3CTD|mbyT+MS-``(_s};qbRFZ7M_`T0P@9jU&qS4PAiExBe(XyQ-Y>3{!l`xU z4Zj<1<>Dw|gLleRdW)L4b*)6oC0Hd@>{q7)i4gd5>$`9CXzi-+7v5%i@|rYnOX46% zm4dQ&KA2vbQQ&HnAqlhS3$ya`(~ogYj&81heAZ~Eh22$1DW07iBf#=Y`$aGPl=3js z2O_f=fFa36KHaO$EN-a#gxs+NE)zBMn9Y!~VZ%>Sl|WZdcXe`DLQkFf z95CYo8XayfJ~?S0^i+z}&6%p;$upg-vM22(PBX{v1D;Yqw?s~QT_9Q-nbtTWl(^Fu zCKO~At3tKmmt|4{U9`?2#313r_PPZGN;%dBZmf0k4By zJ>T^u<>9fZ4xm^7+*QZGDRTFqRYg`U1|2o0d38iUE<2ME;m20INqG@12xbG z=GK}Sdx+as?Fa-rvQq-=LO;bFa_?;~(DW)OC}>~U6LIR=%e9W~GZ*xjBOebcnRBWa zbp7)b%KF{PqXs7(BlLDs5b1+IcDAh^yH7KXP(r#;)(%jXS6DJ&;h5y8oy-Ipu&CAf zr}iSR(M-+njW73|8hSspltwQczi^Cbh2G} zknKD~SRmRMO~#43Sco&ZJ~mb3ijv=Y!A?7LL;%0ncChLd`!iQmpbt-YxqmP&t#t(> zqmEfdK$N^-V?o-_XozQyKxW;gz?Fv8HrmqHRj$#sRzkZMZr+?nSa&PQ*cqPW+>O(bbP0AmE$qR+ zH=CDl#U@^?f?v4Y@=J;{Y%SP@(m|rAsI|g}IAGk6`ZSRJkKZ<0M9_UmdPzge&tOK3 zq}<1#JO%>J#wu*Z5$$lP9bs9YYyzpw#;VlqVtX*_#?AyFUG3O2xFG-VcZwQ^2n*^I2g7LIrtK32HEzVoPEnlL3P*J}fj8qfV&a zb1SA~sJ<%ryzai8U7@{xHdU-i0TA%CRVw%zvfpZkNnAk90^h;T<6AF>Mk%jXZ3ZZ+ zRS5!v>b%drs{ud@1Uu&57JxOkJrxW^w9RuC8`jHZY6HU#?3+n;IGZk2{iiWn%i$RX z{A-X0z5c#?ncD%;^SNEWs)wIt+Pn^a>D|;XJVZHlg`vvL=cIm(h==ziPG+{HWmO44 z(5T|AI<#M#<1T4>Z7Ojm#Oz(>oGqY=MeDC5f(&lg+fO@AiYc~kgNFEDXZ?7>Dl3JG z{GNBJ_2hpKBO^hX3RuzFItE_TnIAh@V!9mndl})-t(;>o#g@E8QdTw_vl!E>A&EvS(v7rm4|1!WdUFQAQx{O`r>D@QKrUa89WHKZ^D zcQrp=WtieOm9c1PgRYTC^r_Qw(s8H-@2X2l#Z! ziR4~)>bj}P9c7=41EM>L$H(@h@2&${2Z$q*%a<{ZmqKV#dGR?acU+EyKWaH-9~OPI{<1-u#g~z9^7f{SQfaM%bra{VU{Y`lRUrsJ zSBvmFd!iU(eYm+VowRDy;2JVLM}2DO`B++lI$!{X!%Fb{Y8;vEdL?A>yv)L9bS(oI zNgAm1PB(ACkL+6KTscIXQ=`hFB3YCel!#BIxE(|>!!Ust?9cxs z1{p0NnBB`8@j4K!YPb>7?hMa>8>Y8_WI5nwHp{BeO#7NkUM-hvtR$CHMQDAlH4iUe zndKW|ANTECOIuu};Fyt>fzr~_7fh)w@U06a!{%gwXV~zBS|G?k`4+b_w6T7i6Re9#IJ_@sw^k@>WUAR=c)&J!i}zb*;N5K023Y8IEhaD zY*Kkgcr5Z=VIfF2z4;uL5*r6fEm!PGH^?|xV?YqN+@%+9@G_XSMyW7Jay)t(tMoWr zicuspo&P@&Ca5o0LDysExSDQn@7e#wS6+#{0&%HlNdWNQ=ejut#63Pc3Vf2NKPsv- zDf6{>~RS*9|5j82(XVa?vhZ} z_Lt%BaDw;cn^~HB1)5atKf~_&`r}Y|rcEW0-uwbc74sniU-9=nh+HuJ!!Ck zN_k;`v*dhu%K5spBker2tUbE_Xo#`tiXXW&7_c%~XN}3)*H@z-JW+0q2^fQ58ksR^ zje-58KZrUUpbP@FE>Rqj*UqAoQkr1b<@{w36BjaMd||HrJ^NrqPH;}E4X=mi#nwAkY0oH91CuRa)6)2Q7-RlTY6B&iHvL&OJ z%I2LuEjiPAOAQS|sMgJH(N>3=J{F0vaE0Nh42lq*lAez#i2P#3Rh8>AeVzS;n>%4h zgCG)JTH>C26`84b((vh%j&2MBH;kdj4Qy0t-8N!TI?u9gzPS5_oRM0UUui$%&r3z-z^tgPGyrQHY5HwbbugCtjaNfy#l|o3?U!ApmnNI&PI}+8M zzPlZV3i(zLb@1WiggyB~OvLTh$_KUj`a*|#5Mm=^BkRZU-12RDUxh0Zy+_}0?wHs9 zkk;|n`warGPy=_)ohCPhg`qgFnQ zXGJoRW!;(6cP}j1T6eud%N~Bi2+YdbkKqj5>8qY!zfx>)e`uG}u!)Yre~tcD%rv%m znpP-QmAt=kqVOI(P>fsR9D(c@J3?==n6+eMj}muESxiR>HYxk#fdF!?Wz;@78BkUV zE=Vw4ah}KxnRj3KR=k|&`BjAEH9wZg-V<@}tIjq&CwJVGA*h;8hsE-@CtB1Mu!|j(44cg?MGE#%aC71O7;l075 zAR}|dMPi0XE8|^(F3QI|P&k{roaA;=1pWQkJRA7Ro{K`DZFXokDJMYwdZbbh&aD^& z5$Xft0WeNSpH12T%BrEE0WhsM2o6<)3>uQiDKw;*fR+ z#e5#D_XUa8uB|^ha_cLS>!yUx;m}SvRAHnA&dQ@GF~Sqt{(MjJUFOEPfY&)ee6gYb zdeNE0neX@4T7pjJG`ZGzk)3PXo6q%0axHr_L4)Q-V-_-^dfi>6%>*Vs0FY&F>c|#g z1QY;_CJ4oib6s(+eKIiw$Y9!I9rRce6JQuxe~P#dGUOT#tthSh0n}!zh%sqUO&XS* zgeV9k^WdCZF<9dWJ@Q}^X}Q6(+oKDnry)&VXAd}l6%9n!$_3a`Kf>=+lk}5 zQt0NZfXkumn(E^}pmqms#wLkiFz1d#Q>zCbgW#Ujkjg%hnH+-@86kh@GE?U_p+Wth zyoyCh_$sAfEKv^aVS%;&mO*|1TCT+nKw#=lBy3cC{>@U0GgtYub4^zv>9d|6Yb8HM z7GG^WD1Wr?Vxqq!nNQR=_>cf^GoiT`Q@zv6{Tyq1QDE`~p%RR>uoXKfJW)?7ovfvn z`;(#74++t5!}s|mNnf@)jFVj2TVCH2mR4EW3=yGg&>)%5JSZ{CLN~z)-3uEWzE80(0rJ~oG z<~dhzzwc(l5Y;`QKr~IxE0l1^|E7+7(`Too)P!5$N^wz-G?>qAF z&23Zt;4Z~SaFm9%J7+bIgdn%*HupYvnd|85n%Gz*E#xVI$p_^Y8qvN>5y3$-7{}v4La`uy~{T?R<|y)Cwe7h)liRgFxEdLKq8>;2%{R! zaS486>|pj(3&$rPpRp;vGRaRMIM4C{nC+y(V?1r2`|{3szucF1p+I zcIz+hc%2ujy!M)P)lfS`o6nlSaiYaMx}ns-vaH@M5$}kSlr!$8YsA11@8Elrgw?wC zM8Z^Yu^kJZrMZ%$`=pombno2vNtHUDpw3V9!W+*^6zA<-v`Nt}yIXjN@Z*K80MhBR z)p$>X8cDVxrimq#C``#8zBxBhp4^WSgWO`?pFGA3wSI5yVxzMnZZIxT{$~LZ@V&B- zls7j5nq-ErBiD{6796vZjCH*tn&bQ!)^mS^3Du0vz?Y9Rn3BQ7AFNRZg_IC~Nk?rN zmks}e@sg7KoEZ;3`Eg4Gap725nIZK&-(Q>o!@W#~k#fPCt*34AE@*6V@Q46(qi)Mb ztNLjybEYmWM&Ru@b7L3O&S-IjQiCBoraUG9BV_23n^r~@xf1^w0s7>@JSg_9Y@5x= zMtEwSx0vupVp7C>l0d>>x4xZQkQovh8oCb}kss;tK@7QZgxJh~da`RBe!UBOAkp`z zP(;ANcsKqX5~X1L718TD3k0A2$<&2=0R$xDAEuIYU;TUpd?z6-k?tx$mUyQE^gsCI zg;Lql!|FfHzz5G|FF+?6q!u6p0+_5BFKOe-K_;1yRtdJMx`70stLpJVU#n{~caEkuG#rBXRTS!y~Hw z`2+UShVqtCTP-RNhIvX2slxmRfuMXejOV=)^0AE7qj+^TNbyN_&5{ zpJ)k}_B_1eXUft`WYMGxkL{Zk?4o+1>IjEtNfnl|;+tCBXHM;y{ZmyU_1sEBBR}9N zJkzxJ+ZX&jhr@!PR|2GDs-l#=uB6PQ?G1{ftB9aw*R1>R1=crIrztnp9-CS}WR7hy zq<;q4^9Eg=Oz*~og5S^!J9o&udQV7^D!2Ua-r3;@UDW`h0+VlkxJc`Z=fTN_8L<5) z&8YXNxTHFa-zuxi@Sa&+|A}Lg>ya^J2CHZvRoWGDBBcf=P7(9g7n6t1f|^+eZJ4q( zPR%TWA`LSq=GP0%NSZH^dnL1HRQb-U`SA7)){@=Ee)h8Y?{l$}{AZT&D6FMBT|fCS z#BKc(QRQn|zpTWXPG{5ia~4oUqo9GX!hCrVfLyZq8a$wMm4K{0N7-5R!umV9%^1VO z20#-)mf^{B0*p*1Fj_PsusslAUsSmC zP!+(uk)19s?a3$U@wwJuo^7B>fUlVJ&7|>fm*FLT@6(&kgg`eApejJ!3Hl1vTejK2 zwkljI_%HTqMC~?aI^tnx@&I%-Ht~*z9azG;C)!SvoHSMJXRA|`&{2#0sO01rys?8( z{DD8=Mqh!^BKLL8rD&rZ!N6WwOD@2sccZ^I8&O#J;ngz`*#O|IR`v_XIpI*igtfA< zdo=>#nq(;&8r}cejIA#Y^w)$1Er2FFNWL1>KRi7AeSoc*YKBAG(2&mP7t)RPmg2~R z(>tK+`3DRkX9)vLG_Ked9z}qP1G#ncfQRzJt}#%w3G+*rK^g>=fYF{d%(|Uau#oj| zF~+)Lw2RdGUU$$m9Ca$F5&+51=?ZGm1F+5)x(5lHuC8`KF}PJcVD>ESZg6qrkbiQs z(Kig2GN%3f*1u5))M@<=zFTCM?M8kZPQlN{o)O+uZ~sZRC;`hjw%&n8EbgC??}rg3 z2>06Z&DGNh(dyKJ6`=Pfn;L^dT@C1?6h6z$x@eKvh{yK;_=!?ZuT1-sHp}s&=gc7D zuT3Tfk5Rs0i#KKBcN@4^3yMe^a?o=-Gc>ONA|bt)Eb(7(=rZv#RZR(^N|;~VW8i`$ z=x6tOci(#VNlPUQ$bWXcnu7}`L7OZDdNy5kVG-Vc^I2E+Q-#&gd#lBkwmU*tj`kB?LK#Ew}Cj2-AS~4Sg z3}bgSXx`vH^ZTdQ;6N9QEW%Zq7;#GtDd@Veu@nW;50FWN>~ssd1$2L4T%@c>l(x$! zK0cr^+Us(9i%q+T3KPG=+4NtID2W%Bx3h~LOa*O)=TT3clDl4mbbDxT2(jtr0a|Gd zKEJc}4@e0Hw!+|Jv7w(|c;=iWY~b zeK0L+|Ay`@?(RE*G*uziSbbe~8pO20=z6MScIvL)I)!%k?2@ufJr6}5k4i7Tj&3$b zR4dTPoEMVV3IEXcquT0`Ag|l^`;GhUG|JVPN!vZ3DKb$6{Z$znDOV3lWeWy zcXy|X;~57Jy;AlEz2@q|mHDp9%1W6l=}U<`>!g3q@J}4PqEbJo-gF*|=_c!`j3Q9J zC;OT4V#5h-F;W^DH{D`n)17AIz~UjnxU@7FcS)w(C;M-C(mb(lyHWG^(4P*3{6kAf zdp;Db&8q&-XGDAfX;0svnV}pw*`8!KLP(X{ry>g$yKFgDQ#I@%P|-U!S;5mrmk{Q< zHxE0YNl5`MDlbdC`*1HUHGdBptl5DY>n9#IZ}k z71~eVci{TaETKksLab3PRXa@i(Lvr5Xyi}pI7bpG7AfkLhtc~%1#;|aj^`Xa#7X9# z4>g?35X6avThG>*iS-^3;PFUHPjY!gG2NIx>aj|Vu8j$XUeJGQ&sv`kD) zH&~SA@un%5q6Od;`+{kzjZ2}jeq}V=n*EQSHsA&bxcyX1)67L_fV!m;r{~h}0*?H@ zyYxy#GJ2K$zZKnsy$7J$QqfaCxM??kq*sC&iGw?d;;Cv?FM;jt!H=S9V)7H) zbFA)a;EIh(Rb=nSnZY8{Oh;PoiNVfMOWFe~z&pJxis}lK*fS=GWMRBvvCz8*PHFYW z67Jztxl-e*zxM}7fHPM++fFH*7uF0qeQfX6yiYf4d@^B7fH163lwy0G@tI}|o11ve z>|{c(x-ESV61}T+=M5t%i36?1np9}NvlOb5y(KVWg~Vo3zQrg!Q>d%E>2eNg<24M)9s>xss7|IQ!SS?mR+DVpARBI>+ET!n0YfjUu+ON6U8S$fvwmvpVviJvg%E?Sj9sR;u^6|*@9v!Bbo*2mBsPoKCy8Uy+x_DFR`KVObd>^JnaXnKx2*2I zppC{(pP%?N(T}QS(N8>Bj~Hmcs->XL%W=>oE$MuD1*b-9VlCa13Wr6vb^H;2qXAE* zCpNRKjwAL2c6L&ki@RtU!ukww#i6-pTiEK2u7Ru-mV3lK_~^^jsh>tq_S}*2vZqB4 zmly2P#9@d%)%Pze(Nj(>H>%SmpHc#7fEIWcrL0liKjQ)BJR((eRAr%x*cT^at<%%w z^qZF2))%~J4SO$}CWY_1ibU76b%IpEZhN-vx^dvq!(fu+Co8){)PUWQ*>m;s-wh&z zfbPsjkNgb>f_T5@2C&@w0!Ty_xqQtA}-K1cp}Co zz9#=J{`7|nL$Z(MA#-ysyMc?7^Fa|y5Mn~~oUV~O&z?+ue4ZBGn`-*ii9Q~YwiF&< zWQy8Vb|kq6f+M6)Qwi!Hd**mCP_&2CCdhbBX5KR`XcNP2m(=_tvq(HcOw6rfYqHS( z+JC@d&whuv=Jzo+iXnK+u{NcIaH!q+Bx^0!pBdrFxZK$-e(%vt&Bn@Ft+mU?OUKK67bu`dLMs( zC|qwx@ZZS(XugZ?|7%P=cqRr1NBr3ynYjNS_kG+1eOA6=v*ccqha#ad7^CvB%gu?q z;+sb<);%j{MG`3LO#KwtWe5LSvXGJ_JD$o+P3p5^zT<-u+$$IVi3<`1#NvhniV9LP ztD8ghrnWo~5TiMH=qY-%taZQ$3HPX8ya9b!>Zl5Sr?*&VHSXm}!{`a2jd}&(Da{Ay zf{ozh@cLq^Cmv>k@I2gKzg6D}TyjFsLu7V&m7ydJC9l@Rf4wEF{l(^5`R@OvvU%Rs)YQr^ zDE68*22~?|Cx_xE{cVt?ZL5wkMde8TW})wCPG1$*s*lVTO>ZwDKJ5tH*$p{+W&_2= z$t!8dHXkf=jAEy_8YhRsBF3wmI$VgGq%;mmL!l*Wt*_^P=W5BG+pg+1NN#i=AvA|z z$gx^(h=rDwQB(Ka7V7OOhQvt3PBULQ2eT@U^*wiVasR`WoQ=@HwhS8<+PNyEQJU7f@%* z8?aq^*sq>o!`pwBB+@-;I71@o5pa-DE*_lKJFxtFG&rHl%ZEh@-z~fKe-8|>Z}Y^n z%Vy_J!MhM2@j2M^(wl~?hry~DZr3b^BN=97UpCVn;zzKV@Wn*Dtd zygIa`X3zFjmEyEFjss(GPCh~Etj`mQy)ZVa*_YoA$QE0L(X50nF8B*iOOC)@BnQnX z_6@CL)O+zWiJGB^|Hh7+FZ~~%Xj9K;Qj_8#^0|4h|6S|1Oj|Y#HY)qZ7h}DgmNbqe zw#?J0B}P+T45djYTB zIa-iJrq!D^KZIecSLuaZ*yhXk4s!c=_ie-#a_S&jk2+HC9y~m!kH}InwD{9m?;kUl zn_BrTVz>7weYjl6S^mN$N@=;3LOV3HIUx&#Jn`0pvgfk%r8Nzb22cu63*t6z;cD$g zg2?sj6b9lBvg8ysijO<}<$rI*Gt`d&=@k0>33<>7!y+PdScWab6X?Yse``j&r1WiHXCb(PH8$KufW(mT#y8>k+=$n`` zThW{3+ zU%$eOOfwi6@ckO&;R6d<3ME35!{NuAbGInuuOPLP98X!r!9`OXaw2-ZrEfi>Y+w>( z84Od9@ZGo2tM9<&)~Jt_hoTFVUxiJCzPi|d#FqWGxHhqHvSn!2=w@pWy|N&UJINoL z3VC>9lk3ghS?x<2ueuo6gKRY?s-3Ng0byKP(I!HR{gQUBci#Y^^UZFdvmO@nDev8f zo_0Am+E8;9!K-lr3=brVc&1&R7^G1vN5M6p&Zf6vXM;tj$bPuWI<>Xd|J+ez666}% zy1KqMW*_|znSY)UKU`{Zx^WGJ;QxB<1E(+<@2Eyy1 z@Fim$tSbuOXPU@P+>>i+a3Jo15D#S-YW}m&sZ$^8nGyGuUZ&g|vrvboW;d7ST-@Yr z7iZZWCI4r(@Dw&kb=gIA`$Ti{|MX@a>@EJ?ss9r_M7V$#H2I&R%sPMjkR$i4J2v1I zkjc;-hP(T+=ee_{Z!Rft49>`2ligU~I7rJs*DbR6NY7>nHNF_uYTsi`&s;n#)gS6r zIk0z+pz6@;{`De@ptQ8pA-hx4Mm!tuET-F@(S1*gjJo1`z3HU(D z4{L()%1oX6?705PtS**1p+p8o_y=pqr1^0_&(nrxF{rZYYCi9Z-kOLoZ?EM`mUQZM zE9aep^lgtNsmHj{@y33!l$)GPO0t6pE4_A~7f76#)c&+2A7a;2=2pe1{`;poji+mN zK!=}ecI1lJG49((FVSdZZhMlho)m@BVq6{WoE_e|ZRH9}+i_7kQqS&2-*B)=joTCR zTRdWCruwx0{glmo%6--ut~)%A%mbst^b9Snz-O#B@T2YhLQ&bc{%>RvSL@8^zq8c& z8>!I#`T3?yL6Pdc(8u2p5kQ-@iu=#QQn_;%!S*SWZtTT|h}&py^Ik1AMCYM&E(Uy+ zi;a70`y35Oin9w|G#XBwaW)QJy{!xKIm9gSe@W$euwyPrC>um6f5m@wbpcam-#JfE zvXfcY@3h})I-N?XYRP%HCDU9Sj7&-!-sv7pJ1EJ|J<>=)1tyPd%U{ykmdhL=PC*&sBuZ$hnZW~^%8;=iiz`3WIvrE@n{w=3A! zqfCur1?wA&wyzhwceh$etv+s;AaEMX7pMCbV_MFZ#vTsY_6?Np$Fk_A9C9KhunUM?oWP@|z4YhrhZT zDXhgCovTCpQ&lq5QYwrPhihAk=#U4$ZFkP%fAhtq#rLIn`AS!dCCvT73=sW-yhuGvA)scO>u|+ZI<}ohiGW|LXCYhq`3UH@<_z`liJche2Ou5 zY!X*v)`V`JW;`ofh0D)9$$h4BD__dNgEK z`V!f2GO}(vmH#TkFeI~r)M`~t`C_Y^*Z%XIkWDY{`Y$Mzio*d>)hA0r24dG|aP^Yy zQ^D}Ds`U}}%QE-e$ll3j==tGT?n%L;{E_8r{Lt{D{+`up`Say#&dj z;}LIS7w?B}}C|bm{&UoezoU(@& z)$F}^;%0YnXDaHtK+N^fq4HwBXkRNdX+PLp2#%#yH`t`!{zCgC^_+gjpE2i6ZN^Wl zye8NR`-XJAc;*iBtcQE#!e}Jh!B>M7-;e3MRcNG2%gB4tMX2dnLE5pwlz^ig_yROt zyb6T3-GnHRd5(-F5m5()$)u?HsqBwD}(nvKEu|CQr7ehMH%^?k@#J^z$!O4z&)toCxg$` z)pb3bAGs@Z-yTg0_Fscg(MU-g_G!mp&`wm#7pYx^2kd`&l_RU6aASx3RpR3uJWsZU ztB+xF>|2)!coLRJnc1+SMp5=S_-#a{dGrq1&)(HNLKH;R zCBToGGUG!0b(GBQl@dvdBi91(2iAUc?O2WcVAN5PDmG@|iyIP7###08xDM@io6ang z!IVOoM{n(@OZx<$pIJu zsCN7nkcf+-8yjyGzY5(Jytu==j84=LyauVg2_sk|LK-|J_`yBIvm>HN~a{#%G+cIfr5%_Q{zp~i}51))ph$Gxh&i|E8k8+COj zy_li6>B*vxe>fTh%5h(K*a7D$Sj3!ZEBg`tWa>P*f)*85VWc_#%TlXh5p@B(L?3Us z8bYTUvP?To*W|hLcg=4{e@gzJw@pss%sw#SF|#HfRwH7K96dCCW%i_St;lzty|s(Opii7tP#RX$E?vtmTUGgd_ALZUp%XGlTx%AaVegNHzJKIIO<1 z%hT=jIU3YMWt`8i^6qGf^D-fCYmsm)TIH^QYxsPBiY)gMqU9>fC5UnUXKgHpw8#O<1d1Ro4efILqg6?c!&gM9wHpt1#n&ti9AVk~9-`+gfpanwE)bW6L zHIq2K*g@M*T89f_qiYA|gu8#2W2<3gG`8`e<|P5JwVNMJ9iLA(0eaj-2!1>E9ZOzT zG<$xQc=;;a-1gkPry$?n#$WJS_kNav(AX8XP-2aA&<4{;xrTJLSiWzD;kZqAa)hYC zdh?j6BL&HL4c^aKi~#Q(J-7|eaN$;?1B339MA2t>q9~b@{h6yiw^^H|f>a|C$aI zrN{4}vk#9HJN<=0_xCIP&~^3td~b{>^ctiR67MA>Y@pUhLifR!CHhSE%ZuU`+FRaC z^DLvN`49U)^E+DlFzpvegKmD?s<^KuXG7KKDshpoeT!H5aKjRLChd2+ie#Y5ALpjJ zlrZ?X1(_t)jtDNJF^$qp4Mno{6s$&sl`!ci=~wwJoO^dukVe8}z9;A9ozh46YJvl9 zYC}70YR1u&zTuw@Lwj=tk{%U!^T5WFnwMcl8$^E}qoMtvPL&W1B?|_?c$ypU~0$!z* zW!?7g0Ci;S+LQ}i5M*mBroy8MR5wv$vE+-r71iAE*QpMlQL!Y=tKa$lYfC6;*!clU z_QtUNeJ?r**%X0cXSfyj4mqSXAk#xsLj8ttlfsd=;YX(rzMh+X>prZJ z7dut&m>1YasX*HJK=oK!%xv$9V^1Qn=F^A8dGD>SZHc5{-~L})Ujh&1_WwWCRW~=e z6)9VhC4?wsuTb`V-wSoKXWvJ+D6(XatTFaMWM6M829Z5GS;oHa%gpbb8Pxax`aiE; zrDvWw=W{;G`}6*Mp5uAkE7Em6E4)IBy5j$SFpjP}Iz0S6(aExJ-tkn;4MW`S#!qZ) zac~q?7on-xF60sK)UzWnuRI@e+90;%1Mknyu2FlP{<6;P%I=w=1+7|Ti}Do1xW4sC zvZ1K%l&<)yXVo3P4Nr4ThDnz`d^}q#Dl}9jXJhFpt#@3}!l)(qaU-s0;+xyly3(X2 zHg1|)FjsWy3UzRi9B+8=#|HjAyHj%G#_C&TMS>Po&s78`R`r-Dk&;_wnx(!;R;6m& z-`^Rv7tiC!Doe0Y9m=%rd#njs22bTjNA4;3P>)fET5W6mS^Q5v7t5%>AKu5dK)?3Q zsVD3mDSrRFY#9HS31dqa;lZHcaR&_N&z+KC8+MOcVA2CiuR!vtw{^!?zCAZXx-qsw zE#!Q}F~`tTf~iVsA*rsx8GpaZybvJk%TSl6eu~fheU(AZg9d(1gI*8(?4DBpl1xwY z-A{06;N&V&)?eG}(H;k$h@7fn^7hO^= z;r!UP6dBO{H=;j%MD1~B33PxRN9#VEMhna(!(BJY;yTZ(tZv)|S#*0l->|MmVbOEp z3jV(t;LpaZKB`rr<2iqG23ZXGXm#{eNKy3`&Ai(YM-4`zK_F`^`#9uyMtSw_-5^!> zFGJ%?yvoKIJm+w%eCk6<@3~X_l#@Lar92gAu%6a*jocT%IjLGFG#AgQ=IM7dgZR{qv~;#M>?3W8 ze>+U=Ysqnafv2a+o3@el$@WvS`@*ZU&xSfT<~LL5MV4YM+r{mXYNLTCBLXI*f_7gp zWt7yf1f;ho2^CAF&ZuGDcD!*k44Ne=<}+`a~!Jo!@Zp4vC38iHUmD zU-&h}ckivs<((%k$m9oxZll$1upZC$ZDggEZ<=5)vh0+;nV4bQk&HE>lxf2*3}tVz z-fwbL>gaS9t58|k!8qW)hz0KhX67ZZ#drVb+Ztt~sPJ_P1kct6jb+_ojPI-$lOnQ6VrJWeinYW1n~mdT(KJ&>49-L9J>6C*Q47 zH_7Zd9QT-y!m1myDHdl@Z4lKsB<8-&RGH76qE+lEeInG_=8`UxCcMxgnXa;wL?8F0*R#=L zd*IE#)^YOPtQSL#9{9wuD8xKpDJmS(`td}yvX7;atp1HD4dum94{K#FffR3*v_zFO zl>)6CT8)6v)SC=ykshS%llL52)I*;i>;LJvxeHx?Jl&)S>$ zb|B+~w&VbIt>Qcn(+y=h#rOr^yQqrZuWp5|!zuEQaTr9Tnu>{+vfg$u2aks$u3;DZ zck0YlA->G{ei^`lHI_*nKRA{%emQA1<1Q!O?=~Zaf75rh`Yt>5IpC{|)&=0tGIgZ; z7nxJO@+1Rpo#j@`CvCwm`4@h?$iCIsb5$Rqk>xL%=Po4celEM1}I#9*8b?iNjuyD3wur{OerK zvX&3h1u?AKX7!z4pWWDAi^9EjGLmIeW}EId+`bX`l6tMT=>8hovpT6g&fU>;=J|F_ zUkke`ZTEsGUT|;k8D59==T3)6w3_q$=h#AgT@=n?5QiHO-)-g#z9aEKo16~sOD}{A zlqx}cF%d1NC%CKsd^GQK(PTCDsV;~8wc7z zPOJ3o1ES)p>9Glw0}fVObD{j?v28VxC)TEm?mG@eQ=N|;MivfESg(C{!Z^^)&5CB0 zH{-Q^cMMO80GBd|PMCf;<0M+Wp|#dfL_YN_Y)BFUwig3`z3##VpTNKvFLI`9kO(cc#T=#qRoU z+m^Ctd4Ax#v4Tbz0nzjQS$}L&yqVfI#juw8no8%;3TCE13^&cXwvpN9UT^ir=1~k1 zQ=j!P{H9p|+hkW(^AinBLt{MKG7axz#XsLFx4w<9RNAATXPcIZ$%J-d~Fj@NucGNXG2srhH9?Lfvv}LO*&$gucsJa zuK!?^e03Z2dM>pUKBrOw99a*YFq5^!f;AVrKeF{Vf*YNNohoWY1)>7o{#iE2P0l7I zCDpbVbU*EELZX~)B`mAc*{23_I$8bwn9ja_wDgm^8?pEgF%6^3J?*vRpA=$$ z5f=n=uh@0A7fD1IORg!Z*yZjyic-%hBTeptR#F)#fLmoB4D!Fb-(sOP#N*kx>j=!- zu(+kMKtcJ`f4Q{iRJTS=M$?Y7V@{IX(7=X8!%fGTq_Clm_*JDBV=ZNNCA*?0+y9Jm{Y9;~ z8+d07TfrTjA+EJQbUQ7TrbaMVNQFj2nfewpT8ib;{-vRCOkMqNNz1g}uva{QvLl5> zbasd#@R}FjtB6(c{sINnM#p0JwN9N9l&f;IF>vS{LO+V_NgaKzT1V{5OJ3UdgXudBgZ5&^c53^7M!Aw8hIL)eB$o{& zR7-pbDXt7U(tq6$aTIawk-=WT>a&Y(lI$HRq~z!tj}@I@)+@EpmO?XG(vtOx9sVD#Bys-iRo=~Y zPMK+YP7249%Q*JVfq#TLKip?6pI7DiyH(QQ^;d~Nq5P@6vgD1lUS0=XtX@$@n&Zo= z>K&@F&F8&QdsDL~Plt|C`}!uwfrews1SWPleJc-=7k!0H+~JFnVm?gcN602!Ikp~Avak*fuy z{-k*28t>k*m4Mc4~g`CbS(hVv>ix7cavj>9LK?BmZ9omNEUVhmP z^|sB;l5Q0c!+EcKeUAqQ2D;K61GO|8sEwslG-!O?JA`_;YaJ)7Zk#dy-e<5;&m%9> zma#4hTJ2qqvZJF(_X1zWP~<6PuvKqb7#}H5nb=L-PBxehcEa!lNEKH$fx8@beA?Yy zHzpTY{dG)fV1^nc3(FWC~BoS8q=^vECicZCLkUM$EON6}jrHL7D*3U@6(0?~j z6Yoe}_7m)BK0e>k_uoz@wlDorxl-V|x9mM-)_-Lp0=@Yo6*F7C7F=G$%2-`ZXnWUu zYfhM%>zs^ne)u=w}F+?vo)Yi|w-Gmb?6sj#VD*he?}BF5jE zMP9w)xF$6UU}Sn69h^>k5^$nNjq|Uco>DVw%mo*Z{~(Q8d2MYWNa@qyTFM(v-eKT8 z$DwhpT9WIDcy{P|bbP(Fl`1y8kpT;Q?KI@|NW;%_%*|EJ1%WDbhpD%`) zY<3uv*GD9&+(`XslchVCtvlPnPOoao`c^@9ewKkAPOD=jYdjzP_*8o3n8TEgHg6!wc_|5RY`%`|ArvU2A2$ z(PjoVZ01v@Bz4!#!0q_!rX@MMiaJ_~A;H1=-*Zt_mu1R2`q6UV^lqNF*6fqiEK|HV z#Gf5q$Xx3%oTtjY1qNsw>1f4+5k zJoFZv3k4lQj-ZUHTU>n~Z(dAKD45@hv})kDRGu-dp08TWpBKenk!i<&eJP~tz+xNq zwdwrYb}{=;`Kx1!RZ$qujBm~L5e$um;};^EN#@^JZFU;C-9O{(pxD*8QHpku7kxHR zHa3(as>Y2;`x30v9QA#wMiiV$z4usoC)H5B9@C;%tQ!~*ke-q8q;tc4xaLUV$B+8X z|7i~FFFm_{Luq8Pk(`iM$N<|89d4p-dOy;Otn|oKcm6J zt!O?u`;DD$A(VsdlHX*S^Bj0-c=Zb|nNqNV>0~=H3C}n>p)#9pt2v&T+|?T^+YNQX-_NV@{0&-D)WKa@0)r@h6L}wH=^``G1u%@x$q}3(|5*5h zokF#S3-eh1$z>-;*FNPWuA6&W?IAQpj(iDfA!b^pJJ0hKESjxE(S035-%*uOs=d6n z=FL`1%jMMhLJ=!gKpO+pc|Xl0wq8_!E_$_EFIF@t$iiH1%BoO{D>K>d&Yj2R zhUe9asAm}lqL79`4=`!V|JHRzBn9C4D``s9_No;8g=%|sMBWEAkX*DoU!hc3roVpa z;>9JQ29dsEn{Mz(@#xuLzTCQ@X~!3tjyLL3%SB3#%4iyfQMTS4dg8u|mJ>T|vGxIU z5{$R9zYK9_Zn@5)>08R0{LEzkMZJxU?U-s$s|@J%tX zoI&cCi4*F=xrVnF&8xA;tm0>>yq)=@j#mT?XV7@I7Jm4k;{3U9wQb2+>#E9H<^)yx z2PgCw0gHrZ;1A-un4?weNIBd6NkO?^c~Auf*KcbJUw+W^Sl6 zEn8_^S>SPCS@bd>omC5q>zez5)chW;ZQH2Aks}~+NnL8q9G%iJ9IMv)PunZUm#Izs zox-B#8BK9-HE#CZd^o4s`j1AXy&-2rHx?~CTP}B{%i1T_%Te9yT6>&cUc$#RzK3(6 z9C8ZldYQ#7a-piQXe(2-aB6yca$Z=-R3y{4z3n2hgl&&<2lmZ3 zcjrq^%X>-r=Bx?o8ITW^N{Eg!udS|TH{fucCl<;_c6Q%UwKVTqtqmO?Tk}TgG>Qj5 z>s-#T@w_wem&fjjzKxkLbA|S*%n0MPrR`%(@dd{?7(&Hz=4(O2=K|lAXnEOC)r{~u z8CwnyWY4Ns?hOQ@>w_-0yK6>q8>5e&1Mk^2A=13d+(WD5QWp{07YlKFYhP&ky-YlB z_ml~F7G{`8EhDr~e{DiWN2qdIuex(~6}zP=Cq;yKvsduppc^yqxaQT9f=WBC-}D7R?qyOhc46+GGC zkH1RA#8X{TwaB~H&)+MSUn5a(OJVu;Z)!lEzE$+Vd_%5{MCx>`X5lU0uixHO^{Mw0X>Q{C>MJWYd3cR2Dx?t(B66;w#;tqQnTb$Mj0Vhs+C(O!4>BVK8S&;0jU03U7i`u_|(s`f7!FH=XP1vzhRS0 z^{`{^xu+w?CN7*=&%@4Z+K}em5M#88w6T)Q(brJdZR_P=8}>EB zKY#HH?LGs3Xt&f*S5fh`U?0ABvv^YU+Z*O;notIbqK148!?s?^)!p=ptkfj?3nKw0M{v&_Q9y9d4pCd0@k)aAKVP1oMN8GioZDv#s zuV1miT16=jKnon+g^Xbs7rGRVZXUl*icZk(RcS{Iwt^ke;Z=tyKgBEw!`W;u#>7 zNIe>*B%&-+#BOh0?Gejpz0!1&bOp3P*zf7&FxB!oa@brU>3;>B479UALooT#y>Svn zu@b&4fiHM-Q4=ZA@K-s#xOkB#Q{23AJ02pH_D}H5L@JOc2F!p`Wy>`&zIeTjxFR5Y zwjfY#D2o}58R!vE$8iNld*<_bcG4!$sQ<8vVcQmtxp{nCU&V{OT*2H{$h5xW1y7=k zy=_sp5syE+xhg~Q9WR0G<7slEj}mAVsM7bWrOy=W+$lCJQt5iZlh>p+ZKGckSRbxL zX(CH$GQx49Qy5KJaz-JhHbz;IGWiyEJyDM}f#%Iv13!D4LVU%r+HHp7J4cEY%}ivk zOrQkoa9yrii`BEcpyfmMpT+>z$W-2wWq$4?bB*qKnM)f&pF%s#6#JK{!vUDt+%VJAmC*rE?9}oK|WQ>$eACB-2+G#h| z(Q1>si2ad$t(`RM0}B2fmJ{A{6U&F3khq&{KGREik8#!z8{Q{+Cy z^;+Ew625nRj+Abx*$p&MTHMzl4P>Y7L8T9*OMi)&lb7~oYYb?}e{aW^p^6JX>eIel z9>k<2X7oC{?A0lxG7fV`ieN#^~Kdh6&j_np`{kht)GhVT7SWNJ?7Oj1tiga0W1a8l0* zz&NHdN$`HlyJqzI8d4JIa{jv>DOJ0`n(N6w1lVb(-i!#C_5|rRJ}7;yFEyN>vHP?q z0yv@B1u>GldMIBqUUp`wZN+*=x}K#JuBcsf)3~4MAjRGevz5}ULFd8>xD6iHJuq+2 zy_(76m5|+Jk?$7WKjEXhv$Zg8p`@+dG=pelifrWE)Giys<=8noX2oN5yQVRe79_b= z+2V!k1^JPSYoxhLdnAZd2oHO!?EoHl7p=V3SGxPXS&cbfvr-|319dmI&S$M~l(`o_ z%mDkn{^fgADJnh^cn<;XxU(!v!5q7?^U)~Oadnb3J4pAZMusUTQi1!+=Y=XxnN0jA zI(pV4c~{$61=?~NCSI!dtiJIG9I!*X$%LxJgbHq-(}^-v-P>AdjGc_=-$+f;D%z`% z#eB0vzlj;bRrL;S`raSMVWbL*At3p)X`>u;!=D>8p@AbA%aM9l9PY4jHB zB|Td)-^SvvnV7pY&qY{?=e7;9U`W~4w;yZ`?nS1GttOb&SxE(nW_5)bMe*?Q+87j9 zsYL{ebGX;;jNf$P_{WF&8^xl*{h0a&w7uEA-j3a1HP;6Ou-G>*pR#M3|fY zf)XkmW2$L}bPN{HK~e1KwMD5@4ih`~=pF}Jf8EToV1YM~7x z1>Np^okE85*lAkdWau_xEe#6z`KqaPh4*F4HSP53^Y-~lRnFDS9PW}6-=|25KeTak zD6=)h*4L*~oNvZ8cQdtz3W`+vI*v$1mlm6$j6zgsjcg4}7&(ku{sLn(Jn3g5c{jFw zG?e3F#J>T%-m>oE%mQsr?aWA-{NqZ}Hu!H%*oRL7{Hl7gIQ21WKI)rW;!y*Rx!Llv z&#owGDY%M;VXj8YPcM$tX60Acz9gRkKeACE0S^n6hW((GqD?oW0e>MV!gkuMYW8*|7Zt30DlbM>8K-S#E=D zb=lIR*?7srM26xV2`7VcAmj*E ztn!ovR|0qqR_3|3({w^9Y4L8;F@3YWg>rcQ!9*m!ncZjqUUuF?`P}_X(UED%pVi!~ zNZ4toPFZeW-QbRt<4qm_2GBm+ChYcHV%M7k;@uzJ1j0Iaxd2f(j+uI;yPEOqyPT z2d?b-XyRB-0LF{N5T6_WwJg#>XwLD4;Awi1^fnwTY7Zbj3BtOkHI;>KO^C3|BAX%0 zbxkJwG}t48$O}?|v!{E>ubs$z7x7@4%=_I~aJ}C^#`55h=2r7i=)lupQ*FbvO!F-z z+<-i0=naqC9Xq;<5g=6>fCpEr@Yc&OHXtvEmrb>PC4|>{8<1!M%?Sc zrvtlbn=QHY&-|%!Pa3 zg4*Vu)hPf$C5uv(WeMXb!u|LBgyYZ8e#|yD&I82{b%=UVjyvo3LN%jshnnX6*I)aX z5Ylb4FZL*Pb~4#;AnG`5O+EExMM9*rfAqG9tTg$f$%tQ1bmQ6I0$3wK*gRA?Jk5q1 zvGH&l2;aRC9ndzl>aS0~_dQ9X013=7oS#cZ+mdF)Ju7k&ABt{ZveqP$-G6b<7T3LhdfjSXWzg=R^eT^G0@x;JOG!Slm($ zuLu#xxQ#9s=@ftW%?*O1anBC}f@+vB4Jj12mRHL-H`7$vKw_j5^Kj|uuCfcot2XT4 zUQFlole`-(|8?eq_K|}wjGJbeJBfipfgQHB0IAvF= zi-=+?GLFc>!8zp_E+y!7+B35`DWsS1KP@rhyMapGk{EG-VR4Ea^ug|tBLKeaQ}M*5 zB=R$zJ&97CS&@w?3?i^#ZLTP_19L|bHkxYB072A8K5#b#v6`8wf+S3@Q(3rnd{kC( zt=iBJzf^bW@iZXN;J6*=S2rq~22(%j(g6x4b`flrZRVt<3LG7b!Yl)9-2IsXp9T0U za~Q_VXv5AG|Jm|!cVmeVye#iLr5H{MI%~=l@E5EYXO_VDQ+69v`;-~der@=_ z=RzKvi}^XQ0t1D?8bgTm)ricw?y;^Luy2%YU#bt@LDWR>d+nppa>kr_<)Q2zv23{4 zI(`|rm*khaatz9I$_H+=h!o83z`a#KACCTq`dB{D2cjMBN+Jkp8YB6$jM2so`-U7Fl12!R;Jt)slr zP5uX)>JT}R@+@n!1ubC9Fh~9BzMmpeS+|{?oWQx7Q{@(0X*|bjbTxYMDWt)kDo!G7 z9AT<^RO`yi)xHiwXcv*HYzul37h6o9*ZlLf#xfh?^y&$Xx#B#nNKX@j%jhGK)ek?s zwJVJ!w8Cx4dMq_}*5?3ZcxU}sf{xe*vYVTcUfgx91?OjeeH>Lv{*|{CO5OaC!}aZ? zw649Q>YdyXvTVdO+n7I?B=Pbih&W~&d>vkdfpfu?s87(12eFbtk=v8&d>AUj?3y+p zRU=c|aCoz#;j*_g162>#-3#=%UF=n#3$WS_T;>5A%`PKkB=4w8$9{e`ZS2gf;WGO= zG!?IKJV@kQbr{VXX(o}L1%Oznnb<_)T;7G;^ugdx!LOJ!J_6h}S9hehAdG~m$6y1E z6SG+a4^Hu@*p0P4TSvN3;G6S_VW3}z)=4Deu1DEe3k9Ag3S%0sm_`{~7d75C1rQ}1 z;4PC(cN`(B?(H~RyG9X}nr`PO`LHMFs^7HP>|kXdA@gYqmOC$Ky1SQqEk3{GLZDsU zOMTUQecNqORbv3Yw2NnRdIcXCbH>&@TWc&2qt3)K1-URL9V`F2z5Q1s@|xFDRS7*n zFxN}sPk+7u#DEP10yC%rrmJo1@)u}`a}Ua~q#3<7dyn6)gP7b^s?U|SzV1Zag?|zx zFCk&!h;NT7LBDjS?VCKm(d(U9P2qDtDsMfL_{kJB-tSfF;*^g$sx@+zUwW=s&ZmBP zVV)zjD3Gq3j?5%9#mIBKrit@J%Ftdo(}H3VanhOwy&Mji_uDG_i4vT(h}2?L1FCG$ zYt$NDO?PK?GmQxnQD%e;-hUqMb-8?`;Nx}V6 zL|*f_o#2;;JOtU{L;|L0BcIyd#S;4KsM`CH+o>~cN_3G0qQlF@&eRj=OOk(=m{a- z<=aTun4RqzHDnuDHwtPO!qRKpLZq4AP8vx-fe#K2Q|7e&|0X(tv@VO|^M&EXmsnk$ z00|bt;t#^^o-Xo17a}?!YzyEB%Ev(H_4f6F`-A{7W&kfYybms~;RP~b^n5#TZU!TW=8CV!_a&k4Gl z(P9i)6xyf3U2jZzGa%_a1}tIIW0jkl3Y}q&P!maWCZuj69W&>V?KKlC;{$!fk$G) zK~Jbg;=s({w715m@%{O2MVDM+yF+g8v#7*gct;a#E+Dct!#ct+h})EMOlJum?OjJ) z&Gya?KQ{Rm)J9#hA7o*dqNdM11vznG5Mh;nnF3zolXz?QMldQ(jr7vjy!vMA^L? zLorNRFJ3Sm8jS7TH(tUj=|;cl5--x9TQ-KeeR@{?7`(3I0_^u8vgyKMYVOKaXGfXx zP95+=^$=Lxv5z~RQa^bxDj27RojCO`t;w*2>7P7H49e$(-8Fgqw4!e6#B2z@qA4vD z7hg#$OqAlX0{JThLC%g?9L@{g^duZ_2p|JOlISzu>>yquWKrPP4~u%1wyrU?DUfv<@; zl#V4}OhHfP*CZ7CCWl|Utx71J4t-PP9_Er(^8U?8!L1o!*8f}Jop{s%; z(dob^6B}Snlz5!z#B+x@MGDjiiaEm7=_=v7A1)jyS>xJo^@jGHDF=W4cxPw6%Jg;k}! zH)$`-;rf|DikNO4W+bfx~cF~gx+8kE443)iiIQa8Dmzv<`C6sQRuAR9A~#ysG(Xi zeyN2CitT1{x^$sR zfsV+>Vn*5jc$YA84DuH-Tkc!;*2ZWiVW~)g`~iRro_I&w7Y~ zhtgL*2FoFZvw30!@5^Rv5K75G1{BjWwi8NXf-VGavm#t33ugA-yNdd}Tr5dPT~2NwMlRw!=x_i(OXdSH77X!S86I%*%14A(dU%s2r-lW<_GYH zgx~xj;qNVbGPwNGLw^8vIEo6tMITIzv;Gg^svvv^Z)gh=7FR>sscRCCg#t|uI|!9d z!+dR<#ub8OLv2uKDgs9-0q64W7Ir~pPcmU?>qb8i&FOV}tc7o15$Oj)-#!6mi&NxL zP+MSwi`6m+6OiK}ZX+3y)^`ZFk*8YN_3G~(;B-38J;aflU*P)xh2s4Q zouzB~Eci4JJfIr};p&xTtmgi#nnbX`DyFF&TGU*~?f(L%8}1pgodinFUMTN2s~9D0mE4U9iqUgK)7uR@QafdE^gzm~8M-`)yxY@$Z1 zFZE!M4Z%fcgLfALF%XQOh)WMOR18rus75}JtETonli?w-OcjlkdWBTD*$AMu2n|k`QrG;1}N2PtY*_q5of~BgFXp8{&$&!&LplL%%2F?AziB zh~MG+cFi!#FG7_#D~&1HK(|47lR=3VMN#3e{`>%Z0a2p_Oe_l3iL@6>FxfXrvY8GX zYgf5hP*oPD0g%X91x0jUdo9Zn7cj*bZ7;i^P5 zG|*>6CW&tlOwtYB0t`dhIg{ucq+_u@U`dD?>n)=f?hwGLvJSJt;IFI@$AOY;7Nn=A zC+4zEWguD0zGN&=GG@DGz#L3sQU}$bUd5W2S6{kAS^&q}2LfTv#A{6R z$bbPL;u8)Lam#W7ip)Oyp5V?3zV1~Ig2#I;tMKcsARa)z0KR8?6ZBt0|7us~7%?Qi zcIvt-0aCyW7!xtb^9-Qovo6CSCOyQ;!3=pv8uLGkv_Qk>oh1gY9_#XBh{!eMgMheu+g29n@Md3fQEs+oBxH5|zIJs9zUh0E>Oy zbP%2W*l%EvXU~W%f=j6Qv7hg+n4@95Ktt-YF#~b{cn^VxI?c~dpcUcao%O3$Fir;Pwm!iC=8fF8L&^qh3N#5L z5d6j^jf$)vfv6!6TFzV5cP3ltp>4Fz0e)dAM=T-vCswd6A*zSW9~MK)j|HHgyo2)= znH(~B{)wq6BJUVBm&DBm!c`Rhz6xrP6hT$Wp9&m`0RS!Vo4Muj+ezZ?Fg}33N_8zd zbYaD*Z_vE8#Q-sN7_BPXa-YPQ8_t+@NJ+qAg|%c|g9s}hWJFO2KJMP_p@Uw)LU6rb z8Y3$c`9uWbimsaqElJ`8$-n@wUcoF41!Bk21_uWdvna=v<;N|!#}|C@bE04eU4l4n z^9qP_3OsJ3+8sFEFlm+79t6(rT%*yM?%YZ&Fa%FE9_KE(yLAiSXH)HH2*WlT6r*1F zJ?A9x@^Q%N;9+YYb${zgj1V`pS62-mavf%i3YlNwuX|`{vc|)@Z@AfS7ZR9?=dfPU zI}8R(Z8nf3VEiG5LBYzS5cWM`fLPir%0u8n1KE zOv&BROZZnqUOVU&YA{M-8brYtU`{UJ(V!>`)V0{Bv%BsA+d1&0qXdDVv%t#ex!C_`MU`k^qv;L2qxED)k9qOdh!1(hUl2P7rCfd`49seo6^qut`$$ zn+VP0v7<{%#J<2VXj5=))d~Xv!0;|-2n$DtpB2QqxVTIbVruhQc-xAN%kUi3d*{c4 zLapT40f0I<`~9IR8%MbJhX>m_V#M_!Wh!9@mZ>TF2I@fIuAhOpS6~7q_Vsq9WZB~5 z;{nr9fLQ~?7$cG7BU->|0=e-PwksVolARJI;fH{v-w9s)cDR}j-7Aa_Y3rKhz|GM2 zhko4utZ`u_)*j28M+ea&Q`Z8v>TFGj#RcNb(qob93TpEEC^ZWqx_kE-s4sz^bROod zdy!^SqCg#0AuxpRL;pfJFfPCBgOX~of@Ja|N7q795@a@*8h10Gx?nE~MrC=JsvFMg zw0;!O0Ej)Ucc9}0VBaOuK1kJ{;3HzngkamM4TQm#br5Vn@~=T*Ylg;Re>3Y39~k7; zkfG=s93n@*G@6f*5nx9J7`iIr7t$E7fKnsAI`2fkFSNi(XwD)V;Q4@d4%48*LGP`$ zR)SF8ZbL%~z`FQH)gdqpzm#QbA=r9R2x_LQrVg?<0YY=C2sR}y zz)l~qv3U5QEe%JOeMCaUS0PSYPc%kxAM}vF61&7T+~dDnQ=4E-Avi8j8`ohG11~!a z$r5+K(OQh^j}gUeKlDp5<}W_AtIpN{-mnYCc?|agfHHDvaq&AL`}U(@!2XkX3945O zK$N#9v7`c&y!75%(2s_xa=v+dBOmBuKZjfY66Q7ZKo){3V3>l$uvHtkDgL*@y$jt( SzY^|v%Sb6o=G-;@_x}KX7dqJh literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/lateral.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/lateral.png index 8d8512f04292297428ed073139f2772cea8af17b..4ca0627274ba6f0d82531e0e6bd6024426a2dc96 100644 GIT binary patch literal 100402 zcmeEv2SAfq*0!PuiU^L1qbOoQ6a@kaRe=D~NkAY}DWL~Qf`kwf42TW8s9>k4AiYVG z4q`(^lqxl1L%Iq9A(a2VA(YXX`DXV2W_Rb?b$2y+%Pr@ed(QKmb8q&9FX z5y<}FUw=h;dwIlm@JZd<+snnm#nAu<`qh?$D@eiRp;rua%}|D7vYOzt7tYfK{G;RI z1s79-b>3-BCnm7cbDAv;S0Q2)F`g*3MMUz+v)o zK+4c`+dH?dF6Oll0apKqkr$wxf z50UcA$6SeCocVE{@doDei`JnFray=px@v)Q_I00nR#8@AYAn!oT^F32`*hDT@=8;8 z@Yv~xIWr--W1WeVsrP@-)|4ct<>^Btg7)SpbMEcwhw%QIE?$thr{&1$2bkiYe|JV2 zJ~NBy|ED>iU`WS)STFLl;Z51FFLm06fjHP!j>EGxpaGVQFAm7v5bNmTWlSXDe5V$W zBhlBFhzG0K3%a3!b@FucA(9EsnnW)mWc$u8u2`}c5Z6o#>RvcEXzBS9y}?y1$$QE! zTyg%8Q_)~|s6KraER?A$P*Yf6EbuNFWW;OEI+6aCg>mlXte%CmCp>+1H$Ov|(6HPX$*~&a(txJl4XWWQ3RVbHrn2 zuj43WD_MV2i)-@p-d1z2v_V_9p;?X20DvahLYwhi*Ly^~` z>CsRYR#X(YXRN72bJq1DS(_mgK|9_~+U&8oVJ-FonV?BnOAU&Zr3q2b1EJ`IH}`PX z)F4`0coDF=;JycY&Ty=S2@DJ74P+r>=%M8gP$4|Ouy!p#>=MNmeP<&9sS}_WUjIFwoatGJ1~|38nL|?dLb;@`HZ=fSiH8Q8PKDEIJyQJ{mu&f z*;>_6BDq*N`#It?D2}pTWM^GqB_3c!0nHhis)N;qBBRap+)$0GM~jTw z1Flio&-kOv+<-)_e*8|ef+P*zRi~kGkml6=L3^@5LvAR|scY=jOLLlfZe|sufOhwS zXSMu|Oc5|NPMr$+m19549@h^RJv~cJC4#XB#m^epmmwVZBpL#WC~yrB|9r7H0virM zK8@pmfm3ziMB`s^@$5^#A7^HxjgAWdKfXRx;MX}V!WCp;QgE=)AYadk@RD*cd4!a# z+|)(NY{-;BC@M&CF1yc(m~t>qpuut?wcAWTP_us|nt^9H!SMIz0)f!)VkQTl{9d49 zM;kUAh2%*n&29C5+MWsQIiM-d6{3+q^vwgV{_Fg`!7`^;{P_@_#K?# zp-w?Tu@&zG;*qttwWYJBBOJsf$ir!>!;Cc5sgTcP$5~H*cNYtDswMCx#vcBj))v+@ z@b7e7=EQex1#7$)$#IW2*-=)`%LtB!IpLLjtj&lXC=Vwp@RTw$*Gy%6v6d!YPI!NB zM++~Qk%tz=2o8h%(iHxH{FIJ4-U;|BfSuTw1;fD(ma<+Rp#8aVm+E2$!vQZ!HPX~` zb0R=UwXdvc;2;e3Iu7f$TpOIsKmURQs#N7i#Cj_`oF@&NOz>FvlD-zliAp^z( zH?p9BsAWYnWJfK4OaAznz@KtBj8 znikn;j}r-{3H9ql1LLHkaTI{bFjVk)c06WK6#dQdkgyhVUI0%~0k-l7?Xu;H@_=;A z###Q*bt6p#4GrwUWserH2fbgxT2s1(@VK?9h8*-hz)-)|7Lc!&ETlUWuore8zb>b_ z;{v*3<2-1LRFoz{cFGQ*v1kFku>|M3WdqN+oy5L!`xmUV*2qVI>5#rU#Ur-ip4 z)&e09qKS+ne(x-^G@WLa`hOtuz&KG#f0l(>$ap*Jm{UO?AR6tJ2TV)B)rGn+4#h*NwFMfcr>idqtvuk15n#qt7bxaX5eO(I zVRg*Ct!3R|;6CKbA&Jaz(y3JoxZ!Mk_%&V%I4hf%>Q1p=h{ZdaX@TAVAJ_w!teG_t zvJi)YNBXTW>V z=(XISC`3ccf@}Z|A!`H}rXgU7z>7oQfqr4Y(*Y*RzUC}z2;N0|fM}oz176cgZmNC2 zCNfK@k9aHUoU?M+P`8 z)n9s9FiKB$j$kULfGmlwCnu)N#1qixuaACiJo!ZoVB-MDQ$wuLbJ|l=p}6oHURnq3 z?F6zCAUd%l9lJFhG-PFRQ19${u~E)m>vthIt3%0Tz{v_)m_CQp7=H?zKw9dwK7v~>x z*R$!{f0WzLq3nQuvZ?)CZB1YEaq$8u!|#{5^Iucn?^E)r^ulbC!I+2x#hjT8140oL zeSVQ%0JaC8P9scrMi+<)GhwfuE<{m0hRKWx;~>lmmN3*`x?C*lpQY7#W#-#6a5 zt8%(6y#Mz;K_2m=@ZdAT`=1krf3O$D-|;+ut`qj^os!8Png2i0HE?pb|8)(Vy6$vz z`xiz$*soakY%H2yQUCiP4P|Fqph1xbq)l&@%F}Qa|Jd z=2Q{?y6}aNk^in^IT)N{8`Hi1E$o>yi$7@3oNRsE+0q)JDDWC_9U3_q0-@tbp6Mo=$Q@R1%5UdqWGRPbIe=M5; zAQs4V{YWbiQc3``K(J-nQvdhi9YRJ{R!Ux87NNxXGu7c7toP$6{ub+nBe~yOFaIsv z{K@Tt|1I47Rx>@}V-Vg(sa8u72R;2(NbgpRq*h-t^b)#7Ds8<-q=oX+Jd`$7f9qpa72f z&57-@F!`CX+1!c;LQ(2px*=nFUChz;4?3L_*k}FF|Gs;gO_|K@$$(J6RGl0O`v2h@ zG-TyD1bo)kBo-$Vb3#Ncm8WP(frCJ=1A|)6|tvB z{Nq-gU(wMVQT@4I{(Vd3GJmdC{*U98IcNl-pa8JtoUFwEgh=MV(qE}xLR5_1*!O9R z{}^{71JHxqj}%P->{_0Z!C&Z6*nP`RWA0hEA}1#`{RXs(Xb(6XK%8@6ci;*qqDrEXUO^5DbE+B*B~o^cPi z!QJ}D8{e^{f(BYToE7)KeXv+Y5IJxD!e9SOG#a^xi`=%6SM=aKu3!BtMhY1nnZMlP zHy;oc1r03x)pyzN#Hb%cs_^UXJM!@qxwb;xmRhuM>H1mnEks5N_dj$jB z`i&8=2MP+gNvZkzjG#$+B7BvEnQorXhw4O3l1b5!p|n4<&Vu=5^EvmiZ(lsBWAsX! zUn@VoES+YaVvVbf-|MCpt7z7Doep*stH^XLwcCMgOwg z(XU$*dc|7;HW~|jz>$d4jfwit=VHF8^yi*qNw}Z97clLE#xc?*V|Ux=!?wMzGc?5v zF4a1nQ@JCLZ}RUS7#pbSt`Lu^4cl&NmS$J9Ww>Nwv^yfQO-NrrWVfYlfgkGY0H4%7 zWXa?N3+LICPfkj%%EcrPch>0C+(D5hBH?c6ILxW+<9VZ9NkwS^AHpqe$W`7@GTjjP z?dGGi>$|fqP&;EUqYEhd-S6Q&+!l~lJU(PoG(Oav&+03P zV4W6Gv6gQ*xoU^+*th-R5}2n{RL6@5a$jBtt>bR-fU6v#MNwt+)9ulZ*NI^=PTGw; zJZVKk*Cr-d#B3s?t#eJ#3#E>DV3cP`!Cc%XDp6IcEJKxmA>aB?l>k30a!Eum^G2Fk z!iC%rT6EF3A>;m6w?h^!{W+S_M%5A6{kar3a9PsE{JH|MJ}PJ;!K?8u4oq|{!acP3 z+grXyC9Bwy>^|yfXB;NQTCTsl71=uGRZ@P8zh;!#9WHJp^0>b5yqJMd2Q5gY_VP}v zTg7yiaz{Fmp}Ib z0(W5rjN#XeZz`aqt+>`4C8U3OhsBG&-@_upm4m6zbA&_7D2w0d6nE4wL$sY zv9E+^LVGUr86~MdCFNX1+|f_w8Fq#KUsf()e*N&Q`%T$l^v^`h=e~4-^*x#=#3TJR zs#J#eC3ZaLo{dQ&^FfSSJo}yZh;Au=Eqwu&B9Vm5>B1)Is!om#XbQ!5R9p-*8ASW zOI zC$dD_4pEzpZbE<6Hr)9y zx05bO`_RvLfdD=fWIOE-IeNdo-np+OPjB={b5-wQ?xedpiGJNX2<2SNan|sz6w3o4 z^q;ZAinKxZ3;KgwQP&hDF)eLhwx=*O@OFc` zZECixqU@ruU}eXe`ySFhf+*CoDK8d>M#1I_aThI;nj_oZ0!64El;7j+G7JWPN6 zW>?EVS3_D9zW*ny;bw!Q-c zJHPw*^36Al8}7FnFYKxhd|;hyS(lx??u$aAc}n8GJRj-;GNY|80k3QvP3X1Qxsnnh z>|ZdyxW9|=jmgXh~1(YT>_qnv+KibAqYF*-goe>BxlW3C8 zd;e4aVJ-Y*{T(rCG(q5aw%_hzr?2lT&|-xu`*MONC*ruf>bo8%*7TCMt8A<5b75sO zmO9Krwipy}CV2F|qcbl5Ao3*_SXklZ^+_$1d+I4Fq61ByY5YIO+mw0=oEzj1t*O>* zl_-!L%r2Fe#H+NN>@Wshe0*qKVVNX6tRA0w!saGnye6e2?+lQZ&@n=|YQe4=z6y8q8;uti zs7*0xl^COk1lTQDwAA|$>;0;({-WVXQ%PcXh5+&BS?is&J%}7H5%%Gk(dzt#CMyBN zIHx-LggP&_Ki(?yj%!t9FW$(p7uhray3nDvfc_%A)NG!;eNEXrJ|SBP7u13R8?__B{nf2F zrg4;7Q1L+fqoBpLm9wcj-B`BY{ml7}tCfyox!@7!^6l$b;Axdp>?dBOr|0|f=TN_eW zugXrdTzwZ|VRZMf zvhp{$S~maeneld6w*sMk5X`sN&fJCA(RA0vpksH?IMV_GM!U|nGDMU;1dJ*pcI6Jx zSue{+A2%P~n{ue_{(fPC0GTzfv=8VQ-N6Dee{ZaQc$VYCB^}tfq3gWB(G{eE=w+Sf z6Fbme$*<7z#`Z8XT7kz?&KavR3$sP>5M(92m6)UPLqh2XTMqf~>G$5e$n0)t2wuQ* zV@Oy?sv!KKpHmVt_vr@!RF%|nLu{oDd&>Ef!g5Ku!)H_qYgJcflr;0m#;Y8tQ$3K* zZ06Z2Z?dE|rRZ!?{b-&Iv!p03*{Agd^ZCoxo%~I~)ZVS)t5?xJZ+MkChjb%MR7Ph}gADAUkVb+kK)Zh-HJj z`U~Hg#oNT@pUGO(<=2~oZ@w{-($qRZNU=}W&-ZLdy~}eUfAhNF{7RRbdCaxB4h=)N zx>2Dan=~TdYqoIuh;G=T$0@ma7~GFM_$M1>X)!so`x;e(5(9ec1ppik%GYMiBKJ;!&SHi9rH zutrj0R$$+emK#N=%=*PG$))Y(A>jZ;r}sx8Th&I+ zZ`SbzTx*-=v87nG)m!&WzbnX#1}`g0r_NEY=vyv;@yy}xiAp#7&| z+b>EL4Vq+oHlT$Lvd(6`=oEO&UyF|f$kwXAn3d|+^ZMomF@vs*$0DZJ)!1zD_T*Y8Jb^?-p2NiF)6|>lEKyQ2?CIHs5z|j#p#hu%u;rG{}2M+prD`sK(bN zS#*Pcje+~9%_n;neR(7tC*$|&rFwaYK*MVL12=65d17z-)rEe~{T#OnhM3%92g&3V z5RzB?9Q3U{1R~6}xkUSp;H&aG3v;4dxjuE)#3ccGgg%H59yzf>+$;{go<8#7vPXUL z)tv`&1Yh500ynCN&EYQV)9t=7Vcd!=BDCfM+Icy1sI`F7U8%sR1(E!QVB>vf;m7AT zP=;JsI6xQ)`JG$GnGN=9;jX7IN!zEoMN%Iv&c}nKNb`cd()ZqQiHFKx2Q4X;4FNUP zCYXw^+HSH3_&Cg?(`zCEAleGX9@2+pNM()-~mi+G?Q+Sr%Jm<&fPkZx$bDsFIT zXIpn~vRCU+M}Ns=YUT^&9j=Umo$IDEOUKE;uUM+7*Poj~YoW$mL6hUTrWIb{ABiR7 zIh1~LbwXJ(Ccv_dAJ>ZCYsHN5T|JeDxx2IKcn&X)%;3i^wiN7Bm!ca%!>;32xMB+NG$ z05TFqes4;HyV{Bh25ugse``MrCTd=nh#>`*m!@K8vFsjbY5NR4KRqLzgUEc|dy=S~ zW7+9Vhul16-Y$CL^6V11>EyR%d>>L!C$q&X00_AdRRr=%=<7e{E>Vru8oge_IM#xs zzkP5bF8g9ebkK_%N@!*_cbhr?1R%`Mtn0&eSV&b!N_yuQH(HljTCO)dn%})Q&&MTh z34>x;SAcnM6ro&ql_4=G`B`L_UvkZ*hm_hhdq$oV_1S8MXY$iFiKqA!*AbA}QY=~S zP#)-6D)GMe@cbk*N(dbv{>eOI5}0Q|2~l#t_UWJ7Z`_O!n*(}$fG0hl>E=4)H0LjT zq3ck2O|GjZ?i_?~vv@{^89^6Y9$P0^GINAQ8T%iv9|c*Li~C5gv{qO2t#G#tB6}Wn z+?+xhEr^2XT>-|Qwak<02!i>;Q`wOj*;d*4m{xHj(Gm0B9MzW-qjV8auLjFWDgzt- z8F-z+MNEiCYM)svmb45?b6(izSysUPxi~nVY17XrDOr(aQ#E{B=iFB68R9t#Uu|zo z@>jKy^tL`IE!T(LAoaSjDN0N~>?MUkr)c-Do|DZC4FnVHbgPJ%6EJ!64jz3EWd>?| z9*iEh*&*mD<0z?@e4%mF4`K-PP5JFKTkUxq-g6x-rAZo7lh{~1!(h!+pi88qacH2 zqH+UUc$TfxHI435-B}}13)be)7QS4hDj?&^te(t>eja$7+I$7$$xpY>Ipa|WLXN%? z(zkhd;HJjW_e0z4GaQfZ{5HH^=$0CIxXrEugc1wj90mb7>jeKp`QSmOGz+K>zN8ia z!tOy;qlA!rW@2tgVg9NvU}NUbE=d{%lqN~up)tGAJFWwSI`RpN~vLJX$)7E4Bm5KTtde+KC=p*n(_SxRMiMKhYmFNfO!QfxRbe$dmXaM}(ag zCKP_rMn$Q%;?_8oOT-WhdgZOI;04Nd_ZJS_(D&xcsF8K^m`aSY?hRO_c_&%s%5O72 zkAK&j%P_yV6?H>MUg%0exhf*w_~xOSC67ej;5#98EJ;O5K;HFJ^ib@uFVJF*YFN5Rk9l6-vSyG`YQFkS^|YMvv(*79n2yWaO&@iN z6S0L6Mk&_Wj-PCwn#`07zO4d?ijnE!HaqkE+dh{Is6Da1x>DM%CBZo-y5UfBvQ=gx zsHUL%A#AT4?EC7LR>aW8?b(VMg2m_v<Hb2PcZp&ReQ!qnWpDNRMwR_ zd`vcp)j!!K)MoPyU)L(1i@9kdHxAMz&h$F^0=I6xz#5bS4pa@$Mm|X|+cMqG)#!{t zut`M7V^zC+GFR(PS(m5pTauhBE}$7CRzdb%t8|CpfsMgu9IT69uT7E8w|YG$bftM; z&LX~iaiho{upTxDU9fpcbgkdqRv+Ptd@;zt@miCx+eE5 z?=t<UR!9OOqkXLqk61!uU~lGPUQGi3jJ6~O z52s_xZ`chC%@4+0w27s`g7aI0fYH<5o)CAg>*Em+@olQw4N~YYL;ze93pf~0ZMMw! zO{k$gn#l5IX!!HhoLag4?E!xWfqmHm!pYevYc6u`nbVlo>#OI45M{8YZ@*h-Iky_a zEBavAh9efJj29b)p3$RMl@65sj z&Zk$~k2~Wmz+h@Rx)5LWJ@j6Fs+}X&qK`{DKD|q+^L1+{X7wlE zz8QIzHA|&9GeiOoOK$sV>YWG2OPvCqc4ZW~FdbjW(PSE~{cI)oY?f3_xlz$Tp!jzk zI~x~6ibt;Fvm}r9R4P23$m$wgtL0`AEAqIbvi>_6-!g@)tLi9bD#C>BDNR9BO7y~& ziGttHc4AI}MV=4ySuxd!hInY9a%;p1 z3FgbIB)9JyHUUY24*FEMMy}+GF^lMvx-7xmrmA@9*e|sqcp0FR{nTWyC6IN9+ASQz z#1*h^>#NwIuhD0FXMcKd2&uu{Me2C|$}_F-+S|OH-zHd=iqiGRp(aC-T)~Mowu=&L zSA60xGoSX?9GlxD6>1zz^S~|#|1YXjdjUjy9}TMsekpgDKQ+^DOAz}aG5moQ*Cd|4 zKPAvrZm{eQZT;%+h9G*dG-$=Nu}%72{$3tVQ1+(JPhqF(k5!62?8wTq(%B8TYAd{h@bpee0mZrPY)b-KXnj_mf6 zKLe)wAP?CWS8X2ACksrXTFT_a?)}TkhrY7}LFAhfUcvau)hc$UAQ1`DxtxS_CATgt zNp;1<$e<1dtxsbc8gEi*q)I@RSEFnlsFNoT$gY{=Xtsh{Jd5qvMT-|EQ$~;3y5)#> z$D+eWuQq;xoP?+$S5d%l{S74&$k8UlDxV~;ft{#=kHJtr}dPGzXsPHgd_FqI{OwSn4C+x?Fye33$m6ExY+UK8Axc|1eo^dpf%r4) z>6I4z8bU^`nNAk3}n3{OY`AjUd5SA@8Nkk9xSCd@6czsP7F-ZcWc;*?SARNK-QTMjX07zR$)^u@kd>{^>^ z>>=MaIU$m~^9=sl(0KD0E@D?NEjn0^J%S_J4)-@DbSh2`6MV7} z6J;--SK6`-y&6=-R9f}&*b`=(8!{9avHGF?N^BpnbaCPM;acb9Np6K={cA6G9+Q6n zafjdsLZBAhGvGEnV>t-mnsv&zr!QhVftS361BYuBk{1vNp3h zahXz;z}@Ba==7^&{KB8sz9pl;G@cju^aYeOSE!SR8AI-ipPw z<>YnG4}-bJU>vF zLP0mTUk+6Mgi_(NDi-7o2il8w&XZ<~{5|(p$?(2_XOqf(MH;j;m-h`7OV|&iS9mAY zrZ7+Ky6ak*c$h~(*&d{GY+1woMqiZ^Yp9!NSHcl%pw-&@Eo{pc_2KH54)5a^jAxLJ zB2It|7|(;}KvYPF`3wnWZE`%?2z5Ma7T?8$fYH#l`3Ou+bLBUOtG-p&CmQ@HTAkzO zuk!rN*|p&4u*BN&4C9Cw!i#3t&pKc`)4RrkpYR&mZIxRp7_Sh&jjkIlaug%G^eWknE@|wz*V?h1@TZnu3G8`l80ro9cUgX8bh(KPyFz zC(j)$WM@!CPjah{>LmixDe0EQNd(hYMu{3gesoNo;SVoUAS70?t!cXLIJZ)yc>tYq8~w>FsOzwEFTP)G3K z@^lF%zp%Xf^D8o)B+b5AX&pogLQchD|91AcPcJ@DtdT#yYVuTZ%Avu=%`!RLFF}ZI zOU^+|LP2=f3CXg)*^~G667&<9fl_p7rh^@{Ybcr$F+i83@#@I{_M;ahW1-9ao=cSD*Q-pIn19Dc0i+pVu3pRHcaa#=C04dhM$CLUMgGN4sIFZj(u z*W^ncJiN7@wp&m@bIZb$mLo-5xYjr2Hmr^ciga#*IK0trW|$O6IeJTrCw?rr>!`JU zxBpA4no{+{wb9t}cx!vwPFJvZmqvNJr%3UD|Apoc&!X(1EZ^0;E;UYT`)1cls5V$D z2#x(5b6@g&-{!it?LqAdm%?4MPL-X>a9${=yE1rVm0FsDU64wJU%+5b!dBGvtxMEP z>033T`?!*A3e1PvpMrEw;Z{&Gt9zed8Vaa~6Q zY)9rR689=ef%%R3N095S7W;I0v6mba)Q=~FHRwEkbv=6xhH+&!=*s~hAoo-^6YKz{ zE^HA7E8MX3P>rx>tv8pMaJ?}7els!Y?JA2Kjr=v87^n*L@p)tlsL?$eJ<#7+V8I&h zt@#o(iHciusG#!g!&A)uFYjKQ(!V4TdqAevbgYF`g#il$+7=ovVGHs}bv_f3O^QD6 zk6%N0#6$&-Rs`Upis@v=_;B2i$(*!A=rXW8I}bjQWZU8`Glv(-3EI_>nR@25@}t!~ zLwoc6FM$wpVkhkF!_~~M262(|U*!e`wSs!_^37LesdrT;K5edyQd4vE)ID-Sy7>K1 z~W)YI%eCSh^*B zp(j6HkY^gupOx7~jjmrYa5AquMi>mR&cJ}AyyXsmf%d%M_*G!L`;kQR)MS7#ls$J^ zq~5p_IJSRJJqvh;L}HZcsLROL-ej{@Bd^i`ugDR*WD}DDwKXK8Nnn@9Gc`y48Qd8r}%*( z^?AXcezLsld}8fLR=>Yf?KVu3ol4KCo|=N(t;GZAlLOXbeJ^$e#&mBOs5OMXlKicJpl4 zV+joh)=zvm+Fp*y(_d8*kVq}(hjv5{3>0+L)xfJ%g;%lMmQPzYayQ^~j|V#MDget9 z33gcU)gkR%WQ2Bue(^XeQU3YlwbUJA^k$j-`sW@XB(!r!u0iO6W$3r=u3J^=QMIvX zu!ZADr3(O99s{4t?>aCj`)Hl99&LAHQ%fdjA3&0`wIS2zgFY%kR;#9D!Ws|<^e{{3 z?J=;>Fum6aCPkx6Oz{C~i9xzIeJI(gi;)(ULu5q0&$lZI=nmFCV{)MPRsFC9Z_EP1^^9Mqb5-1;ePA8#MppQ{|%uo%BNbr zGr|hXDwKEb?r(}cB_w4jc!8z!43$z{h;PoBzvG3#I>qR=B3gw+KmBpM0>dyPEng)p z`^y3Wf9dg_Q_^OMW(n?%vfVSm^{ol;`cmh@Q5z2)-2C#LDX#Rg$Z4XoZo_3&Zqo2| z!0>k46E|%6@a*FVtGK+{fE24|5W}Dt=$zH-=(yBnFQu~A;ORwXt;*T)9YtRv5VYXI zZoi7+Vpz#wP=j7d+IiVXa+kG&Xl{UH|5g<_%(c;rS;OhR)V-aJ1uN3)Xdt#mK63X)9o&6{GAhPhEN-J;lDHZI^w;1u;2Vk0m&yv2BZ|Kkfl< zquL3?H92BxYHL1s%Uw)_fUvSzy%FOWJ^o93*!KK4hxjfOzTo<%Z?Ug^yzSnXcMBE` zop}G;ZW?q18-vIdqJN3C=^*kw_aXk;b0U`$clR&8hPQMGFkgi0R;_BdymIJBS|dE5 zm>_SrHuvQKg|E1m8Pq#`0Dp7Tb2v)Y8wj z-b(BcaayfgDegZJ2;AtfaLmbvF>*nA1p>5U;?2=-JVupkPFGwXhz;3Ft9N{NL?6Yqj6 zzd;C1&^0(|2c~*rJaSTP4Z=UYOTk_6>nclcRtY$b0t$*nBuwGkC03Jud?ZboWC{Ay z_ZKIlKEi`lLcxlDI^QPdh@(m;-6*LrN|m1PY6x~jr-1rgO7LNx9bhwGU>uzpZZUX2 z-L%97lkI^yvqqsWt9wV-jyMpa8b&5wuC{v#Dq@jsHtm7a?r0vDDsb6_>w&8Yg!ECe zZ+ok9^*fo2Jl`O(Du(3qBJ91mw+9SYB)q~@SJ}ioTSN^EYybqHK5_{;VBVdh_k_^I zPU%(3BO9I)kOW4W$v#?1c-+&1XOAyn4mIEFSc0prkaz(0*)w;=-leMy)b89&A383+ zGN^+m;frOJO0oOq*0&`(Nh_q9M^kq*OtXpYSwIQJV)VN$12@ZzY*o6W(sey(U)5SN zZ)~PF=;hzK5~p0)C5UUS5J}sSZ}5SS+s$!Q>{iH=y%MGSk)Yn%!^K+XfG9C|pSZ(j0M(t>&kilV?t<*|6 zOrra6U+aru+HmJ>7Tvn^!Ntu1v*|bpvRb1Lk-<70!YFKPbfN_s@23@F?Yga_oK#b>~@!C5^M$<@J1=k zA9GJq`ChcP3&*q56g{<7kx?5}lp8u_B}X@lx&$1`uuufQ$!;I# zmRyO9kW|&zF(-y|1(r4hvPuK_${4RR=mj42@i#%#RK8rBU}I4wpf{?XL5yz8v`7nO z<_lC@557KwY-F|pPIEZq(FK5+&v2D3>I&++tUo+-q**@s=yA+Nivr{PfuB0>Il$Lsj-p=bo5+uTp@}1dxkiD7X>@UwvDA(N^TqZO z{RumgqYAR4Gcugg!-flE((JPKCawcSGXGwj?NX=$d3;l_H&0jE>2(S1(uHqU{XEu_ z3C{W0>F((%yDcEE!YoTW+WBs);qj3nDcr-m9%Q~cixle*^a_K`I!~=jzX>1a;jg~( z>UP8ix5{f6gG&(y7Co<64RUIjsO}kNGzh4x(FPrepT62A=oL)}NFS1_ZwRQ1itB$O za!D!UXxR4KS=h_I%}>J8NcLAvz-IRz;folPhP4|j_r0UmjjBe9bZ_VG5^}H!UGHwm z7{)Icx8MK%-rzUqPGjr!(wFzX#3^{$Vqeo9YjU(ic;5lGlq7Gp8?xxklMkvJJ<7f{DteM|iIm)2+3 zfbj)$-(M4N(?6IPzQeP>t?2BxqpR)WjqadK7Y!@itsYso(=gY#b$$KU2i8$rs&(xW z2$BTX=hr@5c7TpPHpiWt0EncPS(ivn6E`-Bp$G(UO5DNjpnP-gn5hFl@cwIqBct@k zO9op4Xf_G;T5%uqzGzh)R>ylmDCCkae?4%G*0>2;XA&l|izsYVcPTRO*?>cpp22QL zrqGrlL6aoa4WDD3)r+BnOFbR>tP2=J`!A=ndfp#4Zp{X#U=-GFM(wt`Nx;;Z+tTki zF|fG$wMM(bmAbcd%Mr?l(lgFIE(eE3gcObHmF1elHpDKvz1v>R+LqQC`Nr_TuxwnB z*|^5!u8hx)N&9Xw`jB@!w<-a(0I6Y3kWqm!@$FJ(uX}fl(nD<~K z#b|oM6ul1Tu(LNt<)|Y$E_&OIa|5gmggh%9ohGpf4hmJ*l66=w+;%gJwi|C4%dTZQ zRaG&(c4jBjJkAJxvpIDwvucSKZOpzxgkX)Zs1EEb#$#FpHh|M*o;(8;ljv4fLP9l3 z+~#qie{OBxu{Va1BTWNHbK#*kdjsYr>{@&Ft7XU2O_hXx>hVMs!#eG+B3}Xo^sc@@ z=dZS(?-}bPNgm@5P)t&JA2utmKsu|dckzlFt(PS*`cWgh=fR8gMDR7*@H<8nf=!J3 zUex%f%^#lZ|JvT#sbaOXrT@`2xonpKSGU*%mFO(YvrD6W&BO>#VFlc+NF%l0){Vim zrR(GkIF;bwdr+D@>76sE9f36I=yk@#$qt*#tHXOX-mKqTSRPU>%+Py0!5n+eU%P>Y zTq~pVGzvAEbGxG~LO!Q=Ad9~-OUJ`K#%>2PBnW|xWbIdo@ zuv!tb(ZC%>a{h4@)k%?)$e|o`MoAnvcqC|-ljhdy^3|ZGnJOaTf%zzRETEV%V4hIb zyS-$&eE)f=o*nB|B~$`$Bfd!)%_9~ucLCp9^20s>-tWmo5(K8#7VQX#$(9MvCljF zB_=(?&gb-9Oe}dbQcPFr&ZrqK^1bN$p+aE0iAmnAD_Jq{$+u7{VXv6r3nbVroO)5^ zTebGZJE*$bZdIX{mi?cfTG)OlqBIa%Ym=!1q0d+CP(azm67crP;|BWgzMvxzy{1*f z(nd{>UTk(B5O(+qw+If35|jo8{l(`(4{)^T)#)BRr+9Rej8wC#@4w50>vP|wjvgsd zVhpV9Rw5KV?rp!+z<<$ite5KGcC+UKcZE<(Q_;?OQR7$Q>P`}~?;RZ!TGHHYUtsSs zc~d+qryt~&#Vw^9pVc@O`imHejoz({gf(-y2rJ139BQo|*=-M0&^(+X(UMq>f4x?6 zY|^u&!;>$jcYahoUn|2~4Urxdb-ALZ>EWUMNrO4q?ugpz0SW_Il!}R$9v(b5+*{O_ z6Ohq;SZ>Y8nZZvnraQ9JTUxwc^DJVJzxGreV|ta4W8y9_j;S1|ZK}T#g}EElYJNBH zQ$2_|A;b{)mXEFL2GX2na54?f05Z;S*;}=bX|0$ zEvRKDW?hf{gFq72>T>OaZ%`>o&^*|iyUVj7d2g#SxiEl5d$cqH91q>t*ln;``^iMc zd2qg2()z&HtD+mPO8OD3`(Nw=87B$1vS8ZN;l4V9e)Nq``z%1_;*4<6*WA3F4rwM@ zpzPxpSf6Pj4IQiYn`b$r4Z*{}(q;VJcdh}Dg7?%xVsu~gVbz@%<7&33;lB))3@b?O z*fjoHE@JCDXwwUFl=sLEWBV-co7d!VZ*2z;X`Kp#yS*4}+;g`8NM`7zX}~vJ%wuqP zez4;42G7n5V$iwdB|u~-!T!9pL2a9CK^g7;G4>WvRVZy6C?E(3f;7^d0-{JaNQhFR zbVzr1ZcYpLi7@Jw$?&`G45{VbIBvZFn`=WP(A>D1<}mF(vF%=CyZLE}N#$L4OWkfG z>@Bt}-Sa3x=6WX0PYU^;iWl0QM#Q|GJ45~dOtnx!qbKs4jmYEr`3kz7zFzHzT*-`{ z^-hQ=L1#P#v5^4{uFrA{2Mf$pw|hO5tK{!L)<^Y!XF+YBe(R7~hA$)Mr3`;4Rik;b z>l%HT@f0@|$<~Vjl`0u;XNgcq{O<~q5D1Ixd@GQOgEHs)_c6tC}A9<)Qp*msjXgQFN;1rUq;V#w--F|0)oE zhZbzz44MOO*r{Jit4Fi{DL6t2Li!NM`?mGCfvvcK-j0C|)>C!%%UxgNkxz@4M+0@v zIdTi_Suga_naX^l$BTR;d!>(3`VZ8I!8werS$+u$w7>+;VWp3Ia}Eilyea0$&2^8Z zN2eK2WW=@gZt{E3zE$+8_=O~&yNCOI0z6nsHPIL>b?HDN7ZNQ&Z~odqZuIeb`-`~j z<$=`mYh+M^PJH6><#L<+)S#~Y+w2^-L9&hMKcqZApHMaGzeV#0hQ!W(>0L? zDcz-^Y#I)VNWMpRzgNhR*6kln`kVR1mFjD@c+ms@;LK~q^>)O;{#o~1$=*sfnr zy5^T-Z~#Q(V#WGhE?b2{v}~nM-n-!+V|ezBh-bHvx}|X zN}x3}({0Z`idi)i)ZlXjA#k7MGXg+vD8==3&sz@ze(lX0{ok`%Wa`jLf8>Ywo2s;E zWMjL!ygv++dcg8~c6dW%tXJ`GSiz3z;O6cOHe4b#HS68R}u@aMC705qbXb(NsaCi~PFka_Uv2WL> zQ8!p=wO}~?$OKwJy`i2qv}I^1H0n*FYfNt?hx3rX@D|$-s5~(-1~ZnuB@^W)%NHN|fdg0eL9Y&cE!4@l*9Qb+*R^`%F4(k$ zE#!qu`o7DVB3+c!S(@fY#$pd}lt<8`l$*^|IsdF?`H1QOz?V-RBkI#G4Q$rw#v=v9 z;Z@p;nN2agQ=hYFz^wG=GQcXYErRbaOwllDYA?1b(?SmdR&0efN!BJ%o!@XFr@GcY zNsf}IV4Wee5f+5of*7pF46(eu<}j3>3+hTdFrY}2DQ8iC|4|U3$?#y*hoRBKwULoo zgCyiJwPMQ!txrc2?w_5LpR__S)^A8 z!Yq#<3a*Tv%O+@{^y4$K1W2_-c0Bz{8YZPu3FQ)9WPkDK-oz(%U$M9A47%eofSLBu zEii0Y1>hwL=k0`g9^=`sYRWZ8xcawCwrh?xE-OuA_xFJT&6XM|m^R6g4Lusrcl(FN z7El`7f84m~Q=5%w9Cnj`A3?gaq^7{>TdD`64gMWSNxyq6s|f^RZOSRj;d;vDKz0C; z6xHAN@J>b2+*VN(%kUXBhWH4xI-A~}?)Gp;FlpgeF!&{5b+96*uAUQ)M#{f&;X0cl zWc;lt^;iY&P}CK%_@A~@zjQ!#s>9fuN)lNq+{BTjH>mV^TT7@S4~n=TO@b1j7Y>p^ zin&S6@m9^@fQ$fF7bvJ?Oxcg zA(&_*^ZP{s9^f$%!-*|$g=V4=FrTuCRR5FiyNAg`9_(t=T6%vKAaX;`r2Q{FY z_7^cJ0CVF!v7`rpCM^Zs@9l$*(z)4{L|2~!Z6}+Ed;D9T4UcPIo=LrB%Vj0~R@yV8+swRg8b}VCU#!fNZWyIo} zpn8qnOOT)weq@ktVN6O@d(kgNz@z^>JVU9A(8O)Qg398{K=Di3%k4Se4{FjWB&!2@ z?!Q#71RGGfqC8edH;oD5jYka`a9Jdi_T$6*1|O~nA|xm_KsTGVU?Ybt=~**MHGlvT zsb6~$&(1|&p~_{BPLl|7s-U+>RANb5BggE6Qj9s1)&^|i?p~2RN`HQ}Yil6OSLe?2 z5TUn-UHlR|9H9Rw-GzW1%uTK*NOc<=O;&x4dtwqEtx$Dlyg5}fa;ovG*y{VEyYjcE z>**;D0uKi`sJsYX+}YqHTND_|Iw}ob;*lBW=X5{r>jl=B2BDy4iC}ZGYCzcqsv<|T zh^6Q_4mLSvvh8wTPt#j3_vUke8oKu#9N|Zs%?Kz5hVkr@;|-Nq$|%?)su{(wp^!RVlT6Be6wl#=#_CnhnJK zkyhUUz|hK8pD2$5;0Du+ia!m7fEf>nII_&MU-z6}`fu0gG8WW68ZYm0{%K@^&-7P% z;>HcLCyv;&KMD<}%`M%({|)>zNH(V9{BFnLDj3Z(0pqtm8g7?|MFrbsz_Tn$75UKZ zH1tX_$ITb5y4rd%EU!(aF$kYkST(%tDe@OxjLIB@RWLJxGCJQD^#oWozUxUFl?L}Z zhsX@6=;4|VG+#)x;#@}$UoTovg1Kas64TfXk$bm)DPwTKE5HN9=v5v>;qq}lF?-#wJYB`I#j9RDt%#*#XscNVA_9!_x|)}G$DMx>60?2Gnxet`nL=g9IiJ|fi%fC3jY8m(0PQUmw&BZi;%-q zc3Y#4&Ex7K#y05i=>#GkrKVHcwlDn=%-Gt9CX0(>PO$IQ_VvLDmQ3qexw61Nq`G$q zG?<)+=z|-_W;O`nh$PCIZ}oZ+6ewMicoru1g@K%tDZssmXWKo(=}Q)9(Cl?8^oYfi-M~UEA8MMq~NKD5EYtF!wv-st0 zRKFE-Tow)B+3Rz<)pOh{$XZv%exUTt=br}<7 zW^=CiugREifU>^RF+cY~L0xoBN-yrI>CtCjP+gGR2nqSW*{%T_shIU;!>*)Wy;fO|vN4hD{q5Hj&S2VJrgS!tw zdm}vV$>s5k-S(7&39t&&D8S93J@=i%sQlIFb9(-((Wf#~xz4#vrQGm6)pL(eHU?#; zLktDSJxjkyZ3xXIW)5gE-7wfHqvejD?exOccI=Z6wptQryzA$E7=icAFdA#xWu_7`o>22v|fh@Y9l>RFA+sAGtUPQb39*sEUFG)PXTB>FefKU zysMFFUbhBX3R3wmc3P-jt=dlyUv-Sb{DrF6%m`?vVWEHHtRiJK&ZWsm0pq`9lP&^6 zAYRNRVHn6`tRnYCrnn~qVDhea<902BIXviBB{SLY|ESkhIfnJ8IbItmSH39ez_OdF z5j^cqA1l3$_;n%IvFYkg(d^cjA*hvj2cIYG*1htbfWtoTXmbKD_0>Z&Dg@(c$Fy<2 zqZkH-?0aAI9&-F6NnziBBq6(9m_mI4KN|>TN4gDgMq+!TuE=FW_Z?s-M98+_A3VP{ z9cSx_=aAW7?im134-4j@rYjMRdeQ2c#zVR5ORDBzwpbnh?mu4(wgFr{N>`YlVi3Y@C+ELkE=U#y$ffM*Dt$ zw*)BMCRQLpuS3ukMG4(*J!8w_=086*^uIR`I@!^00s^Yi#<9(eh3hj~PIk4gj<1EW zik<%Vr13B~zj1dUN;sTZb+!*cIAmLC%MNkQBVk$p9fkio2U!AOvbjNhX6Sc8c2IQJ z$cXv2JfPCwBm;agg zA`6QFtN1%@Z4iKOlOTe06K8mUzwz~zT*l0%?IrX|{9SFmk$EIC%O&vt4a_@!v62v( z6z%Gc+%+Q~o5ELD=?5F{p8WR{|K)3KNM2&P2vCD>MKT`1uaWa3nE%0MxC!b!1=Tv4BKnmclUsBKCuskFNxAW@V!Lh(qMbWhr z{X`XO-BaBEE&&?iLCq6A^zrALTNHgp)`8W31u}B=%NZM>$i+>v^xOIV=Srf0`qNo0 zRbss1ksUa$jSkn@K~LP>7^Wk zDfP=-^t2FXuR6w2=HKG~>k|e*?%c&pfA&U`>BCzKP;YYm@TjUujwVzm+$qgluzj#J~R#3<3(F;{>+E^@hC^;P>pK z>;VZK_$e33!Cc?(nW^6&%7JPS^H!XjQx!i5D-0~%_q-*&iT z5?_;BpX*%{Z6qSjr7@pZt0`{_F?u1D28hZ{!_Q z9WNTVezNW&MZNd&re*(MQizn!0K||1w8BFFy0ug=XS)9kYzjE);n1+Y{byMJ*GV7` zq3v$SaYi@iqo9(l4n3GayZ%tPP952cm)geqKgWkzYvVK6sAXolr$-hx4f}?=p zTf}-qZ*Bww1GH3?F0ov{EZm}xWV-i0!|iY}nt;tRrQCdq;QeVVn>8FXWyKF*ZpnH6 zVG?`K)5F%~Ieoi-osUUuOcy*l=^pd0AFSQ{)(t3N-Qcszzt=uZhjBj#C~ z6DRRcBQD1I7q5`j19h`-?m9+%qfAe)`acO=^5kuhM>68GX92etF|L$}a*K~|S?qKoeVk~_^Qh(3mj-CVY16!Vp_zAU~oHAflpy?g&703qW4 zLIefF)o@t|4(s^?L;Xuk`ayPr&yA?+W<*1<^o|;@ph|Ji^_u%C^D87bfJb@XOsS!s z-F$LIT?)W!v+0gLjAT~lRyk}gFAzl@RR1OkFvK9YZm$5JU1I?;{>jUVt*I9M-k;Zd zbH~5L8-J$RO3s>3CLRTve$~)J*W0FM5((qeW4UHfy@wMER}u}!;72AB zM(slXS>c}U+m9u>7IYEHuP3f;>chjLs9uauvaHwjy_}#q=2>uHdE(UY!A8;(UcwW8 z(!Y^V$Fm`y=*-FV-j4I@#rt)~4cBi*dK1M2KvduI?M+L>xg8$jG);C_wZufSMxFCq zgyfT}N@T2W>5^Cu%Ixiua8!c-`q2>g^r{|V;=-bV#Uz7ep_Da6wd@W^xf&sxy<6sW z)+cZslu8rXahHI-HT}zn#Oiyg73M~KT@IV$-nohef@sg~qM(R4I##}1uvT2okdrV5q+1iTO-@aQj`t`K6xt@j-y^MafA8zuKP>xGv8x^RK-?w>Aq8 zhdr1GlgRw@$hK6nt`BxbaJta0iIA|nGTBlHgoG-sPfM0W#%uF5YF_6En6v}%%D42I z?m5I^Us9t4%Qwb$PmA6lp`wXLjqQSuZo6``4WxQ-Va?bV$hQhnp3^ zBENn-yD(BxwydR^J;4QoAEIX|KR9QzafB{AVN%|43%Tv22q_i2Rz=AJz>{L@Lu21e zgFx2RDQ3ROp5Pzu?sUo@;UArxL$fs!iQHvOG-gRQ+tYlL4IY~D9_zzQyiR+q8)f}x zKMrzUwl9BG%+~sh9*On%?3~i5L{}n;jsD`Xe(4GW8yhz0AB0Zc2PKO=OiTbUqupn7 zh`K$-^>yC>0F`W^x%vXN0J9Q|;+vFk7PJ33Mh)~B=8Wx*H}^(&7Pb6OF97@orK~Zp z<&W@16Eu(85#4W+Ul1CIKYg02eY&UOVSWFS{|cWpMj>~?kVa@=I8P(E@9fy4O)S3L zOs-IaFM?5%U+Abu{Q%Yj=J_bGUMV3u) zt^zjtL9$Q7KxP=jda>7x-TU_8+T6kFz_`sOk8NXEsz_oa!)5qy`v3Eb5}BY-qUu}d z6-YFGMvfpsCn~4NCOt!?%Mg=ou)N}({-i$9>CjVcN2ib-W?mcpKqF|b#iwmY@uRM! zE30*SIH#z@wbhmDrj+~94>^FHib}+bPf?;u;6cjcqrvAgzcv)@3zY%9F2w@T0Bm}V zD%1IQ$R}@(OgF8RvogA(oE`};iT#&1%_V_+sxlM4y^&AMqFBLLAl!&xnVNWf!G6cp+pgro?z2`kdoADFrD-ZJv$mQ z1;&I({OaPRfAXjpi+c4t{TFfgxvd!l&f_DRX~t#7&n^OErgKDm6+iW(fau!4=V<`8 z&=C<=-fJ61$NPKs)t!PYV;#;rc1@ zfB&iG3xi-cqKqOYe8UGRUV^8RjaU0oOxx%1bOu*po$q`WP=(Y#WxE`%yg|K8bHDsn zrdshXQ~Sty^}}?jl}^6%#KSl?vjD4w4#wT(XJU(uL%?{oBCW=+4v^OkF$Dwo7p;p* zt9CFgAMXpsm+DVJOyK%_#G_j8xUlu6_doV`OAN?&O+Nkt^$m9xg$gdRK=@w6A5L9*KHFl+ z78eywaUCmhJlRQYH`r6uOm)9JJ1Q=*DnEE$cpqCgfp`Rxz#eBeVN~pdO2meg$nC%$ z-v|6Tx%_813pN6UN)P~=B`51JF=R0NpQWdvOIPG`?%ynJK`DF4ID7mU_jAbP5Z?P& zd&Yg@y$aIx5ZnxdQV@mQzr7DOvuBJr!fG^>q2 zPlY1D5hmE*CvFqLye{q_yZCGu-A-om{$izU3Gp*8McT)QdEdI?G0gOX#8TrT%j~!@ zY7wQX(H>b}Zmh6K%tv=uGWKl4P8|6@SwbFLu-cTGxKNq64$-W6w;|BwLbFBGy}2-Y zU7vSN957Q~F}0n`wNl0*PsvI$%Z1s5=s%a{#^Ks_H8n{zaO#u%k^zXJD1OgF8=ebVi@^=?bV7Sq`Rs*>3__NcrP2)!?c45Q7K^J9nuy>sR0{hIU)SX%Cbhl z4t*G%c}s%OU*>7{2@q759{I;|n3i|pD7515EL7}1$Ld_H5qjWp8soS8JybyW-5&h3 z=BkdllTlnTvcP``0!eLVN?Gb`l&MqHoXB1#uH5cKjcGT2WypojGE|qPH)~;hjTJtv-5UnP4pcu*&cz@79s4^|Huit!G5kQ`&^NRO4 z)LcBxImS9Qr67)d(*+Y&5pQroI}zcF7DEwXt3!)U{f>VZd@}7{cFK|xc&1Z^#rO=! zm2j{|!P?Sn*XZb0w?oy)TOB(Dh4`jd)XtiTA&9bkttBZWm1z%zKh-p(n2-A`YP85# za#tmm*cHFxe2werKR0535tw%wO(v&w@FuTVT-R7Yjd+Ft-MGGhmq@iLrdOv6Z?Q`l z(Oj@`3gNKw-m*{f>nRP`)gaBWFy4Z$6W+hHre`1~aQ8l$YKfy__ia?Yb@X6s zA8t78Jg_c19j4*vUsgY>%Oxtee$#~)nJYN4B|(OCg)|Jn6mxgJz&7B`JFBF1CUrZ8 z2j+@?;rwGVJmI^6_u1Sno4_nwri;traaGrrw?LYF=9nX3Fw$I)o1 z!H`slo^IOd?YpX06$wx2rzfmH zSB%$OQIIh0r=ejorlbtthf!cTRcvDWt-aJ@foq|tLEJ6|hek#=wB(|Rw0w?{iM&Fz z1RS{I?!@A8ks*W`bwiX>EJU$^-KaVdVNR ze&n;>mSlcfc%A5wyCC-9`;>ZW6qE8A`U+9Xu=?W9; z!ZD66NWCBV=_f+NAHilMSy>r;0gV@M%ui?elT5s-ggB#<`>IccQk~&4QwnI!5Kjo| z@$vUk^|JcXDvFNpScnVOvBOxDd%JNSc|ASw3U|M{V8WX4#B5I zoXAc*{5P>4t{d@7dPZ(9_T6O9@2d62beq=aFrc-*b-Om!mw!bU;NsFAGesNXHy~iA z65J5>^+PII<5=EWYj|r=fR`RGitUFw+C;KuUZMg+K>_K^UU9@ag{iOqF3{oZYBNQdT}O?L z;U`S>ahcW&-E}VQQtf;seAL+RRJ$#N`h1v#<3KhvAV4@>Q$B(J(KwVy7I7BkBsT9E zepDWX(PW33=wT(FoIFv`mePn`vhzM*4h9k91CuFx#zN_iVuPuLee&qq$hbS>!I?q3hXCHPLrYqTQ}PGx9C0ZN&pVp@v8xmYfH`?-IBE4nojYOz9$G~oT*?2`?Wg&A5I zzFgvqjN;RL)Mpe+sp-#(jKv1}(8Su234_pjO$px_aOsq9NxD8kbutNo^zBQSP3MPB ziy0oref84r!qYP}8f`(|xo!y2oRycjHK%gv-I#h*{}rndVoI!(l}%BO%TTAv>Xr z@%>1jnb&ZtIn5tb-7sCUac_Hq-6$CyQox){gT0^P7wL*cTp; z9Pd8yd z(lbQC(7(vg4kg3xJgaRV**zZvrGPG_0LHu!`@L{^S%*D1I_rkit2cuahCmB8q++uV zr-2NiJ1|r(rtJ;|+by)6yxP?Ah5UxYt#v*bR&Gi!MKg~A3sK?=KS!b<*u}rM{uq4^ zSjI_jbH8qtwrYifuDML2Kg$ck4Fm32Mk9x%#TX6bQSxDoi*dgnnuv`s6$iDbvFC5x z-nL{nG?k=GYq`;zX3GdoB@I=);w{CueHr$88L=){|Sd7If|LK!$ig9@Bc^*{QP6DVn-15v6MTc5J;-415;SugiG+i7d`qi!r3Zrowt@=CU< z<^l{{P~$0IJdFjL?SooCNJaUVWlx0WI_`5$IpIMfD?hzTlQO|W8=(~xnmQbz!-J7%8g} z&WvZS^E%0Y&F=`S>)_Q1$U+M$9j%zsV;s!j=IcB6bd6p+`21NZW9v)&u(vfjRGdkYA}M>pWBh{5?*Tnyt9Y0LT5)>e|~ixV9} z@Y(Z6^_bUdG~(YJgMpllt%WO%a8_%U_61&xd2n2qUs{nayecl-h0N>;gz10N-t?zy zNUwCV)kY;PJYyBz`IN7?@V*jt8ba0OE*?%E7<4MY#d%+1@whqplt}x`!-%ns(!IE1qpI?k7iMTq7+c>UL7AWPP7M0saId-^D&R(w>JjN(D&hnv>wD-Wi zlSH7y5!>!ms-?QXy%;-=xH?^sed*3}a!=YJ(a^P^`}^t6p_IOz=6G_8lvnZb%+=h? zn`^)OV%LklcH-W1Q#v~#u??Fp?UUTK2Np(sF$LwP9-+vm96uz_`>x!=ipm~u+&aIE zoAL0q!t4Lc11C2=vX3{zbV+i_+1(qtoJ5A{u!CK(i|Vk0TCsc3=5TsR|1qd0L10vb z4B7QN3T#|a61pj}9y(9&&uAUw!gd}22c6G^FE$tpIic~^^S1ll9Zz}trm)M_n&(!T3p}FhwIYYHS?zS>UI(t&xMAc*7xs$v)alJWf_m~ z^Cl>_;>56t&%1av^tERe*5DaUOo?e@&e#$W@~#HjePE>31tEwl!=wzBL)1cOan1)(az0*H1RB z0H7J!T(P^I4)=+9?3z=W-uC#A5D)|~L^9k5*oKzmUn5xxFY75e@u#ZopYS{USdpVT z4!nv_cYf#XO)itf8@BE9p506(fzJhZFYzrrufM0?My7BL*LOaZAdfrr5x~gEJQHZD zN*9;UzZ-Y&QnzHSZwpIRY)ro>47P|LU6k@-%Qzyz6ONV&GV%w`#Z*0*rz6WRkuPD9h0^9)q`h1i6bcf zp^&78cBxwIqe_qKdi@6Q2%J)xe()pB0`rsj!UiAL`#xoasNf+$!3CeY!8RUaptrt6 zkMpH0DZeWxc*|h-&f1$6AEBfLGFS_m9aK5ax4vd9D}>{lwcrROK*9;_5YL?agdDEgh_ZX$Jde6BP{YafH1;$5;`$odcIKBi#f>jDvJ+0y}Kzs~Jcv@O1;TNC|8=%4GjBf^gT2lwWgad&3h!Y#?G?3c`SX|nmpo7~2 zswh+hPYktO-FL#sSH2ae?K&7Btqp$~xC<$MHWg`4qO%JRm$iEj(Fzao`8#_qi6JZ> zzg3D)ft7%Bf19+VXTUefDtNGOO$XZoN$a0)dnqn|66d#URGJ(}5t)_QRa@&Xn9J4p zh|%k;-vQ#lD=ypMym-g!Is5^5U{<^BYh)*J%2L`1XmM*9W!2H%$OceEBK5p>ovC?s z&PQzJPVad^S~h6NWJKk~>E-csOYe;Pz*4%zd$wdPi=B|qqp1M$GJe@c|QoQS2gyFMA@kJBN)C?k=$Az$#0=0^)M}UyZ9kV?XFFj z$l<`;9!zZF%1K5B6BzYC=r4#i#|U`vi^_5k zQ)FIOT9T&=&-BOe7@)O>5*oOUPrmSFiswjkDAcIl#8U+aYASj*g=PQH#*!9pc?YS+ z3Q^VamZ~LI^i&a^%d7MbC2Vik<-aNyG8DjOe|Y_&iZjBKmYDO505g@m1SA{c95o1x zh`t82OEhL6m&PJK;4qVp&ogdHannyE>O`M|<6){wEKk@^!>e^uXPV9s7 zXT6q5r+u>d>VP)|@>8=}K<`NCJvDue5t?S!j{E)Y(V|aN#Xy#-`UrT0HpQVYsXa_I z0SyiLJ6gySVvwRn)(pZ=VTER)-!z>DJ)DhL*M|q>( zYIpi0y#_T$Hu{-ej?%x51l*~qm#@Q}ID;CkcpGJjI;_>KVqO^FhqnmLh|#c#;nsRT z??r;}OEx}1DosRu0Loh|YpA7il-bFgR&c?D>}=L2cKiBzUiPM=p)D0POnR-g-Qz# zqBYs9KRL)SlJO#l2bDx=4K247|94zvN)3+pT0UVJ2YzYRizZXkswH&jE8HtV?m=O( z7oxz?*C+;a74Y*^-^}@oRy-Gt1nl6(qk;#XyVCHwonZseLLb*?R`X_fHluzj{>*v1 zp3RAh?}wMiyP(;lt+F0Gk+?FQhB%$4K@7m00;A1L@FdHsOU0@{vAM;JXCeh@^@+(4 z)K2EV&LHKph6nFuG+zM*cy}S!;Jz}RA3w(SV*qt8=l1=(gio4VB|k)Dm}EYSp%qcD!hxNfpv)0&rNC9=fpUCN-AQzvPAMsT;w3qmywky6@vc+)SUZ zW=uf|-1fU+_fL1?#PfU~hmW3jkcP3K9m4Z(Oeof2y+q$!z9pcHF^FdmH=ctrNF4+o zEN$PKswwjmtxe!EiQ2o+xi$ljE@1)VBkpkn{NXcw{`tPirIF>iWtJV3Xh8 zy97|tuX}uaeHXw>675{zaU~lCeB^S<=jj5~t-9mr)3z+WK0fnjWhSFF7NqG8SHLx? zn^%PD?w(*5hwYE@Z2^9Me&3QvINW(b)hcdwwC8@<+5z~sG>e(~hk$fWOYn9rHWYa> zv5yeISX!V}%%^ZNP5i@%k^2nyxti_018~SSiHwo6r~5_*Xq$G`=q=M{O*lU=RgLRn zYSkTGJ!Ct%w1<13)Sz%Ya{uciEA^I7$0h6f1s1v&6M0D-Gq*k&nC>(-^sFh@Ow8yz z%wX9guU!h9DqNyjhWWlS83AG8Jt-6Y@iOy;BZ?m_)zp^fADkWI1Om}oF}H+Os_;b* zxI5n+NQ8rQM9QYlSRdGo>u3eK?KP=^FDb%Ik6w9^5t1C#DmH5;^vjQA=J0Gj5ugLhd&LN+HBzNJRv z5SWYESK|c13FE46a;vY2?JRDMkiN?k;q5!5}a55SImv*xCq8$+7wIvIp-fn{?~P`wheyJ z<|_MiAP#w|W=(u?l+bL_Ks3bAk2O_GN-1_{Z7mv{bMUeKcwi1Q3d9NAXVoU8*BHU> ziyLS-SQ$$5#V9=(A~`!bQA9oHJMXy&smd6Te{uZegRXL3{mmhIZ6*n>kXgqqKD3^q#fUT$B(cVD(x zd)bV`sxz#?X{|-j$FRCNqiRMnDz?*Jo~HpDh!)s1Buc1?xsNNvM?nDxMv@y3Eb5!U zTaiJA;j}U#ZBo%6B`}t!4>D5ByUY)3xvGl(cSGKKIoEz4vrDb1MJ#2c$4lr2$`;QXs31UV7eP098+s^Ls-uBJ?HzGiZ0%^T zX-s^rl@^za^D4_WSf4&( z)~xaZ-HX~SXNQ$e`}(NZ^e;18gSP8Ms`iXsPAB#(BD|`ZB6uy(pvq-%=$c*N(D zz=Q3E)l{dLr;rsUxA12}{GR6=!s@h3Rns?+T}Ehb9sxaRuDe^^I5cys9o$H*pGW)< z%N?jG+$jBJ1pbyCwbQo2M1DJ~^Rx6OV06!|Rs zBtx8dUIe@CiNJ7HD4D0!;q6j)A1L0=SGm-vVK{4KU7&Ue%z3R!5r-1wRn6bE_!ZET zJS7zG%ItMtER>5tod{iLS6E10V0hl&tGd3HuQxuoKIRVbpi*w0)zOaAnOd$G9xLA$ z?{AL2BG8JdX?++=rm0wDioZ0*pnwu;cL_zd$INXto7Iozro}TqR#yCK7SdQB8V{Sd-b6I(2N7ifhTutnHM1?*jUe3k;7qM1! zWwmoN7Vjia?+a7K`NWa#Qw4}ox#0q*Sean>+a!3 z#NOP-$9Fe&7dklY*04o&8?33XJa{r+#IA)Me#Gd4FInyk0aNF#{&YtD>75@qSnlA` zc}~K@TJ<^{!QWZy)qq_-$udkscW}TSysNuq@BR{NIN3ld3q21{BRr`#Ai*N|^BC=~ zqcB2`BFyZ3a}@mlkE298vo0>Y?dm$8wTk7HUQDp=5qcpZ=7DI>-JsN@<2^ zeb1`8X7r`lk`}-C#Z#(M)Ebk!dDiWOFZmMhkXC)ANlrSe7|Z-&m+(V=8`iE{)j|>K z^Kt$!qqC!|o%uYqpwc3RoI8e4jD~bMn$CEmB~0B@{sz*(w~n!WiTu1WB^t|+Y&Gw= z8a$Ov{(fg=N!hE~gvs;N5WJTQNl78=PUOK$gXB5}nT~Fh^2(F5ilyA+7v|4u6YK!7_iLmB zwcF2UjGUS)wqf`_VWjrL!`-@tfr;tm=?Rm-w_Yi8u#(`@QI(dmWhM3XorEAVQ)iyYGB`x*MH)dNWGPM>6n?~O=9D;`yDa}--6Q0veywi{o;!A~h;zM@CgSa?` zd>!>~u+off&1jofi5O|a`)g5_LHfmYj4b3j_cXfRv^pdMF9IDZURnDT(Ii+Fl`WH9SaEJz<{F7>540 zltLJ*b*B)WSP?8%<^!dF7quiBiC|x6+h|r&!+Kl<$np+7IcnW$Lc(q*!~QnJk_ZYd zRAGY2i;Zl6qJy}NzCeN{#+JGkVfs(^mm3~wej3P#=FSDhs~lYl1UqUaqX_s~uSV1a z5%h~3se(Yc+xhR+@ic9Jb_Cv3Jd2?6C=#C1`8Cr483oC9XNsWX2nK`JWsv#C$9&x zdVHWO=Lco_o}7H07~093+W~2?kJcB%-2sgi?yXc{o-mA-EV9JIk|N~nJddY=pZ_Gy z@qBY23qA9BtgyW_G?^ngyBY=08`OBr8Ct;ki7i(_A_y?#yhQ#Wdhnm5=M8UEP(8%W zdWdwrhU-F|-hvt-h+Ho?63j*X-t!S0X(3$wr1{vzk4(V^g0GVUmTZuE5aWYJM)tWd zjWt+USoWSpst#zyOev{U3~u_l7M%3Lm35m|k*qG(i~=pRVVj1A|27QU9lY^_T zujh00I6I39)iib^Swr+*Eu`}g|e~^Xb#TQurf3|0z^$jYO+z<24x{m_)qa6X@J6*(Wc4SUV)JOPYMaUdMr6lF z5IUIPV!U-rb>%o6Irv+$g0XG{KO3ZPl6;_X^%k?tEHXve*Mt1Z9I3o6S=|0LZ_wS{ zcnjIJ{B}&ykhS&#;jK#(C$0H{_u-((5JC9PRzv|n@HGSYi&9O{3?B&I^&z;$-mO{Z z{N!2GgH-~5M@ek#!8+a4SQ_M&=d;{NDXd3tShnbP6G$XW84f8VGFthA|LQD<>Y-@b zZ|EI6IK3;F%jODiiG;s`bnt8{{Ovr1c8lVK$x5+CgEBrgr{yf_`AUWK4ieD0*#Ww8 z%X}5{lpy*&adnTDJKs}+&_P4^&KmcvEFR1q3OI2~JfYFxhrBPt?eKmy6YbFCVOFv| z`{x4gy@hefwh^f$f*e*BlsSLbQ4=-$;h9WQumU~59DMIoNI7=cG<)E!5x9jsq%|Ev z*jpe@a7cjbKZB*V8C{D1`~cH%s`^P3v-&5#2Hh{1rN%=6rD~o)c<_|qeFWi1o@?Fd zouwpt88zpuAn2z1|FHFzQB{6l7pNdA-Q6W6Ez;fH-Klg*hjh23bhk9pol=4v5RmRh zl+L@)uipQ?2Z#jWNsups{c~+q^!48^|{VpA4Z{D4=*QY^J%GIstV!fJ{XQI)bBw@98KVe6gQy#jN`ezum<^^(Rp>GQKB~Enx)MzXEqd9UCrt&#zsJ>7kW5cH z_1*iD%bWc(FmiPjh}^k-Z#V#M76z7U^?Q+Av)d6NXsL>woK#leR?6UH0`pvfsjwO) z(9}z3^YeV9QHZ3L`AF`x-VZtkLb|$yIv*drV{XB;>#!<=Hil(Z4hJOg7GIRtf#g3R z7*l!vW(x^>P#Ig^GQ2(e|FQ|jzgU?yOt}0fpJzrL;57)pp=0+;WB+pyx=r!W!KnSTug(-o|HTbK#}j(m0T)1k4<$nXBmraS5m&~G2#y)lNPUS)z) zZ~Wj%QbwL5d47r;KbH9KR~2>#xrnQjV%Ro(bT5JHjToSF)~At5cy4tlsjkv(CE zh;~l>3w$dH<;Q$MWhNt+I2SRS)VX;N6<04uM^??xxgVJtdIy+|N$xE}$gOO1j%V9vcH80@0lT+^y_=5sOsE{)YBaM1Ve>U0-6>YNMH zfCw6thTw3VO!P0GWr<06R-t0}O?@}&zb_I6K5>~p;5MUvV2sAOQC#a2h3a#0nLCz zo+z}XKpJ5nVCDs$8!jWPagciNfn|}9()@onWcM2MZX>2gSr9YkS2TO_P`iWKwvF3u zGZ#8Cj3CrjwP6mHkBib6jENNee!9AUmOv$C{UT5?gA)aul}hk0+p0-GNeptfDg!Rt zIo6GDZba+PP@!x=9=8=pd%K^*-eQFQz8VkxbfIt!cg>1X{nH)e-T&nT{!pFC&nFRT z5Oi*TR(LHj$j(QMP$8bo)H!_izfleSf)fSvZy1x zJITHv{KH)A2x_B@*?;sPHE5vn22u9k?X=!T$Zq_Cp$|_`_HddGDCVOu9bJ-J!!%2B z_}o!}sZZ}rMeMz0M@O3}-~n}$+oJ)pyZY0itMLci&MVN5WdNg|P7Q-u6VXk57p8RD zr11XeQv*)2GS=0lwQR zXErZK@FNA@+k!$dyYKk_J@KEFt@ges*XuwQg^8BLSo)JM1~w}m#cC;oE81tpR1E+Y z=G1~Aut#mLhd=}IWRV;mQ!qHC&5jpaCXmBA=|Of4s-@;90n1lNE31`aRHtH;M~>fp zJjV0fpquyaOuXA0+!U9~jXwn5&wMrnVd<8O__0Upa&b5QudPYlAiES)F>R3?7!Eg4eSZmuQcXSNs|SEui$ng+(hM0?oVzntOo%8UFN|wzsb@ ztJPBVC1?tI#T1&tq-U-1hj;=ii@LVyhL`UCiNMisSUKbxW=a>BbcH1%J@z_k%SHN0UD{@t8jinNp(Em zpP|#KqlSfrHN65y5DsuED;Agq5|H7O;th~8#oL5|BY|I%7c?XW^143-+pivhanPb+ zKqM^elu9=5sWa~)Gs=JI+P^A})_0YyGjarl1E}hfvedHzT)bchI;y~)epbEw1u7`( zdoY?l-M{0*z1J2JJ}z!?#2&C*o6#M|4|e4tZWIZ6p8j}qen4c#<9NS`4Etp0M zDC&08v7i-KGYpJ(1*D^pcd5qt84_-PrB1yvaA?|!qSx4_{5TqKeJ1F8vkDBPOVvtZ zFXr?dIzoV6gD}L!lhOTn5#1?E%n0o7^DPAj5VYF}(Y-Rr15RNZ2qHM`5y+@bazX#a z^0EX_D!6}cI-W1LKmU&Bd5W_~m7 z?dUdVFYSyAKSv?&?R_|1AHa92;WfCfOLGNVfoE|q8BUs<2B?_f%T)aWrNi>~LZ6HY zJB2M2vVoua@4pi&@X^~@{ibM*CNKI}$Xoz}bQpE(mbeu7ZuXMhvka~*K zc&;RLuYTQ|u30v;6+N@(grR!b-Uh!v6h|hNKq)cVXrtu=+}E67Wiq+hMpBrfgdVP_ zCR(yN*E%kjgBm<}0Y>(F=bOVD0h9R-Z+Aw+c6@M=&TcPv`Vtwmx`==~KX?Ol#KyCk zNoKGS*fML^fIiEnrfc4J^6f5rAKikg4cgqan;r9Bi{>g}!Dcz)3sG*5&j!QF#`Iqy zi3~sM3Qk`?|8G$Zq0K{hES>uh@NPP>b(XQV< zl=HC)i*x*@0Tr{&6T9nu)B%#jhvWu=-D4pjbQ6m2-Fi!AhxI7LJ?v@?X)5QuE9JqvB zO5FhB_5KkD{pzheRsU36jz0|@`6d<@5{ag#~H-)3ax5N;3#>um1?Bi zWN*Oq36XP_AlY06#U}0&G7%^8chb;49%yb7 z)+Sqh(cr^|7p9);@be4G+S(dOpl=#eGsEJ6T;uFyWyS8Cs8poZ%KeIz$ z?*^G6aAA*%$`p#QGEgz;N%3Yf{d?H>b3tz_l!{8T*p+oguQiq;QoMYQ1&T0LG7iw2 zzG?!;2yQD+*Va7-xo@jb;SUHjSv(_#^&+zRmY#i=qFp<7`?y@@8Q`WDJ5b&AfLL~+ zkj483l+2-^VV@XS1W(_|@Z~Ku+H3@&39_~|75WYX`{r8TTQ|68&#Zn(kLCbpZDCzZ z32||9hvjz5nQ|P#+r!t?aw+l|W}x4ufsugMrPR$1^f!{v%mAgscdrkrpsQaJ&2_It z(4-d*4Ddl~vR@KSVbp181|yXaT29UIF?0IqTcop{W6r4XGMrHZ)Gg(XLr-_7sKCXp zYZE~kU5KcwJ3Ty3Ila6A(u)D$1<+`?^muooE?m53e+nUALs8w<556EzUTp>hL6bBOolF$I{bu3OZ+sGOLC0@N+Ux`v>! z_{Z;$_cSeXX!j}wl53xvmLu2P?{CiWL3Rly+&#a}p!AlSEd{2-x*_)G$w)=R#DV<$RL*-xv~qe0Qvx@MMD)7SRPKYkT$!8e2bEO8waiEi~Xf zG6^S^+^3q%TQRMn+BE*aX5D0jk2?P6%#=ch)l^u?2ftpi{_g^G7 z$AJy%g+ae%(D17%e!mBOEX5+w&DKc%P3FWNL#RUYb2&nvii*ktEv@*S&+SnYMPLi^ z`@kEJ995m)<6<-#b$u94qQ~NNSdIpBH*G|{fQv&+;7!2O7aXTRV{?{1$KsSJ=&OtM zyXZUt{x<=;`J|7`$q87!e4YBYx~QtjCDt{F|7ro4dMk++uYuKyjnf18Z5Q;vs@and zqXa_p2g=Iu6CgVYXpqKm(hUCaRZe^f+_F~dpEqwo8LmLQ0^IN23Pc5YOzqllkJ}c; z!+;gZU~@pN=>X!{;XKxg&z~5#77^uC;>|=l%v5BZ3gD)1SxaE={0VX2bsr)kEgkMg zwF-izzs_Pbo>~SI7#^Zi>W-qInowTjG3ly%FD|mumPQ%WvgCLEN^RuzIxBVSuB?m* zKMKu21LyPf-OcrNp68$Kh0a!BJ~=BWdy%tg{;R`m2o+MPqt@0#!G&mka(_0hw2&RY zBOaXEL2fi%qV!`{(;hvEK?BjD^O|P!Z8-dX9cP^swNQ(sxJL^CU2kXQJK+0ld;4NQ z2bE%y$Zw4((>46_oaEe%1cK&&=tdkgx7tY6&Vh4Z#SN^{E34Q4B?ezk{>0k*jzJ+1 zia=&ckvlS=JKq#Na(w7+!4TFJ+8Nk1%?6isfyP;+@k^YN@=$QIXqHsu+vOPOJ#)pN zmQYT&&xCp4-*63!Ao~x`ZGK}=(IzN^F{e~pR=XZo=E%VGSdyPy%L3c^y6u$UIC{z&q$U-Vwj}L$2Y7$M`hVZ4{Lub|I3v?@1Tb^Y zgQRDKWL#3_4y`5WZ&V!ZC3>4|*38~pJl%57A_g^aS1Y|d>u}#P)i=mx-*EyG`&!^^ zaUf<=^y_s#BO;x0Ax-cds%x*r7^(nSUy1;sq$3K=TZ&Q_ih^f3;wY@sFYj-2J;3b? z2`{8fA!MjFL)up*U}lOcw2OlOQ`|>RoPoGsyODaZC0D*^;V_~AYlTDAM_x)4>^E&w zWNoM$5A@zv8k5hb&cPMJwlFCD&B=<1YG(F(ujE4v5X;I|G^8HLhlSs(;xKbjZw>|* zQ3#9`S%X0BV?#xX5m+HFjq0LNNbmR1)%_&x+Az;r7%E97>7KQHv#>P4A8 zUadhWh*u?vVFkE8*24;b2U&yjRw+BxMkzDgGbJv3n=&@z7{&%jzTG#66YwiHpMPEL z33{Vq;8p#8S1y%vc`U;VpHoRrT$E*idco<7YH6t9-l;cGKxU`fTk@Bd)|eo?;ZRcRjFJ^ z%h{9ENCS){3FJ4?bAg5MU*pJxX3MJv!oX^u;ouDcj1f#<`?Inp6}>AMmIiDtH;1`qpHVvi=6wCDI2?Sqjo@yxL(uVONIDs;D-o66g5y!Pc5Vf3Tlm9L(T^1JERsfa4TPauV4?`N)p1?~% zONbz>pr;`zK9Q?i)j$-Ntx#m>iGsvL)FD?vhu-|q$zVp!0s zh}k_~O8V8KwrL?t7Ja|2_1s~D>~RxdJ?{)s67tY%tGbW>tUHRmr^R$Xp%B)ffzi_{ z3k>`zQfi;MS`AS8HV|>zhJ%!@6SL{;9g9(Cd+k5nf z=|?mrQe4Y(mRiZh_o9sZd*|n-`NQwi7Q7P7;uUO1i&jJ^{Ox3of4q9P^14a6e!ie3nRF&awP}?ukF>&a3ai4OYA;|PU@3`8E7%;3zU~_5ZeE^En&q_^sygL0lR;iS* z9mL`cc1p-%sA@Pwr#O%zQG*-bC^VZFTC!+PU)P|j)Z4k!wFkwQXNMTw-6izch>J3J~vOe%~FtK?O(;sfFTo zgf?jU1U187)ewIy^yJo4^~Ed?&boT)p2TMpS*ac2JaRt?1Mme@IOIUDO|#WyClX>^ z$J1^+X@WieNBeEh=}sa`zPl%Giq)a{FlEG~_w6xwlP#p*h8(%)JP6OqS_eHWAk3q_ z`R}<_qP@{_HYTcB(Cm_sn#kHi(tSTjMci3Anj0EN)5*FZ4)zUUaMw1|)N$P54E!k> z{8Faj-|+H{i0?j&VEl(URVStw5$UL6XtrWqhjW3g4e<#N^T3hBuPCgQSXrmV*`gqg z;V7i=w_f>ZQFZg)6);w7eCoOJs+7p9bjZG%GO#KWgIr@r)su-yOtVt^bfhO0Gm03M zalLv?S<^dJHQ3rpiAvz-X!5Ha=fKvrRow^$(`bQ0Uqt|g#-ROVC>>RJwztB<^$Pj^ z2Z|)Jz!iPz&$bMGhYx6X5d_>Nj5U|>MD@y||I63?LWZ6pW+blTluz^=N!Lbvwm_l{( zZYhYlJ;|ChwM1IgBN{y~$s}?WABCLG&Yo_LB@qw#MSF_*EaoHOb008vJ~opJruksL zzrhnty@3%9jZDw|AgH7ExlZ?{dNd%hIIu3SaRk71jhsy2U^rzFxGv)AY6wo4Weugc zZ!L0Y5|KwiL;KNx`SGRP`edHipy%VmEz4&7)SsPiHusA~InBsoXs&v?os0lE_&(Bq z=2c6PeCa${PMl58^$g^>p@37cdWU1X)H*ZgV1VkDj9*yYMqFv-1z)mfD*eU_OqFJH zJJcS}*<*#@|Cn)xucea5?E9xEWFn00LwK25iSE)wXy;)sbR5cpJ`cQx$EcS^^@DSc z%%hKv)E*kk{fNaJ_(}A6?li@{Fd!)R>mgRaDGq~}n7BaH7tE-M4|=OrrC&xu^Q!Nc z%nQxZwtXYIRYuZ02Dddt(pN~o#Wn}j+w;Z*|F3bVSqRWV$6cYV7LM5NDu@&wo||dB zKO$CxK9>dyUsb#p9R+~L4Q4n~=`GC*Rld%c@J<=exF+`-2k|w3m#ciKmnSj{NUzW7 z&sB+Ico&B#16c5gdxwmU#g$u#uZ$9ZIBmFb7qi@A8R%j6?XN!8?0l=Zx~Uh2lw}fK zI~PtJW_EdzdG3D`DL$ijynMjYH_|{TQ|o+-4N<9K0W?4?29=~GlMw)S;P#4`0(StN z%dzGGrlqGdy$@_vuN@6Y`o1jDZ&Rk3`cxh;C~JLTjr)#bkG4FHTDFnDm;#Si{2o7( zgtuBwQ9?ki1rW5*vpM_4W;V@g!x%6lp&M7kpkI%NSbbqOT>4dSC$S*I%pN83XiOj| z)vaGNkBHvEBokaqF$!@a(Mj3 zURjl>a_Uo2z~7W>d>rj5Q$2Oq%T)y5^;d%7$#;7xdsa{_DB1?^rR|-7@KEb;| zE*dcbbpC8~`6K*C{{f%P(2iI8PJgcuA)=jA!PxyRRG|V!UH=!)_n&9RN(-aG0ttSZ z{FWmUEEh00>1>^@ISPxVGh%Gh>mMUOqBXWbJKw=bxH6T5|Df-U{X>k5(y!`lce)dH z*~XBt>zFrYB1nts?(2KT^hx6L6-Hy^LfKoMIp0mnWzP!M6x1=~;h07|oPEmDQFIY) z-IVZd21+MD|NS~{JFymMk}ys+QB+PHl29fQ@M_Rp%A!#qJc|DgAc6vq)AjUbhQNAc zt5=kP6%DWnk>_C6kR|1p@bUu5nBJ??jm9spRJWLLHoqY5o9dyyNX8fM?(n&;qd|_6 zX5m7V*ZUMs$6PD3@_ujYcxR_X!yXt3VySA7{fH+9r&&Q`48Rs5XX_1u%`kR~ob`jf z2^ip9YhTTrI@eTO;gC5$?SeX#w4y%1uuJLyf#N;;CLElSPwBETZApA6gbDg zMl=Ziz?n)?_gcEKtKk!9%UXFe4N8e=REcCFHh|XtU^tS{FUckSG4VcT=jkb*D0(?Z znv4et8CA~Th|u3Q2dmitj%wR!-6L$=Hw>vw{1mXh8~ViHec@}6Wsv~(?gvbrF5dKq zg{UL%Z>HxBv(_Y2t<&%z{%N_p!-u+$gvJo}5xyuqrACkPCw^eydcB#5U^Cm!PwSt% znA-hZU+U?hMs_!1lGtl;Kixne7Wf+i^oK(R4}Q<0{c;lfwubPBO92OF2pilp*FREF zP?i@Ez`)SNwF(h(OIR<-A#TjGe5Ecm@0kK5L2&{Cw3*#tV0WVuxAaz*&we*+;f=mv z0y)k(U?;44Nu~nj(663Iu_5gw4>`lns31;#uJ|8km%p_Hta7WEqy^6|%vg?hC8f*1 z7x99AQ|WG3cI`2NnSI(w#$PVLH+O ztTZ+I>U$XIdOg-9BG}7exj!w683Sx$JZNGS5X)x?fm2+gC^x3HUoR77nJPY6wJVgs z{F{sa2MZMdi|iif`u)v_k<(KHCu}_Qs*II#>A0-Y@(dxUqNgTCSXkKKt#k?8xOQ#b z3yfgF-|fQUR)q-)uZ6CxPaJ>KCnpSDg;pgb3P~4dG&MFqm_K*j0tm%%XM)6hBuVCA z{9ypk$TBR}*#kEqf;;BnN-DL`KA-t6LH&PKV5QCJgKn zD2IX_P}Cef%U!A`f1g0Mp`y;^=OX^EbY}G*lZ;(L1^jFiVnq{v#e@AHtG0r&c~s84 z16*0))YPUm*3Gg{`?Sgcl10+`BUz4HRH10w{uCC{`g|6wyxik}sF5UK0|F1o6+p2p z)!79zrbT^}{?@tQ%2q=4PvPW<1NMM{#Y>l1GYn=M(;K7alKLG>_X1`7AeBk_&cDQw zyfE(pu>J~D9s0{reOXS}_%T_tW2(P+ks!6%M{Np~UXVZqMH6u8rb3z<<@WU0qO#Hn z%0QPjPD=vb_HQXBH*~posspMp?qY6ry;E}>Wwg4AC*J0Aw^DRlJ?ud-@&C`W45Q*w z@(zjSSy%lu1SrX9L;$x7qM*AT9=n?}b5P76Q8)a%Wf*bm&0ojQ-!HWT?I`BIX!Xtx zpVrm5vE!d!YU){2O&Z`E-sX6Oa?ZwC{*8b{OFpeq1-65LrW|fKn!DYxu>G{ubM)Q> zkWw|GS$xpoUP90p=5{uVI<`WVqVNg4^FWDkxl{=Ik4(9N9y=@!B_2PcGr+S@7o8*h zf~J{DgLQ{@A^5wQf4!0obon+6pv!01WF#(5-RfHlL;EevbU^E*TgU*hX*?uA4`69o ze8J%JSn!p-8XSEemelAYIIgg-CsStjTkA`pobC=LJQ~^%5XSr(I$pZE&GB>G7(`h_ zMH$!_ipwIx@8F9T1{i$;h1hd!I&E~&P9b^TEnKLOF>7+MG>-mPmpk8jM=Wi6ydciI z!{(7wH8mL_|@9Q7QrJ)QSaq>$=hE z-AFXV+;fz9w!}_i&U0;1(g~VxKR7&do+O0Z(f1Rdh-7` zv@g@?mx@hAyi3Bgh8p|8!0he&tS-#Zkb}p-@VyXN_FSVK*-{O*>Yx4Jgg5?2Ci8rCePPa20 zTHSI{V?mc!Pyp}rA_{*Gzdoe@%ZFRXFrPB>#sJGTV-wtXS=At~c9>A<>rRMY$91oUA32Uv6WwZQ(k|Q*R~1>xXgX!_>ui0>r;CjZ+h*Bh1`++ zaylalhN{>4Ta?uqv!7~=Zi*^jKhZ4U^DWB6gC04xCGSA+xWWnc38nc@?-S1%x6s#F z&+I41FNe-&{-tQHk~98OtZ-H1eu58E3_9?Go}&%wx$b*ph1(;VLWUExn~ei5l);PF zI!;mkFc^jtr)lj@Qz>u+{06?}jqe?s;O@d3n3Sa*RZy1HYgUVUJuw-KJPQkV{3PE> zj<=m#INHDQIbe8=?E6D-V5=`*E}${4_A9E}WtCI+U9Q>T_nw>n)n)qJqyy-{<5@DE zgANDQfj3s;7g*t<*pyTS=olCw@4iv}+SGv~74nRgTKo2k{Eq%uz$38jl8oxip4)!O zGx#76&FOsGms)W%N`L-4xkIcAUHmHn#GUgYqU+ar;%ki3Dbyig}MD?9pcDJ6b!(qF&G@rrm z0%?}+vlBpgRGy>DrE}0Pdu*Vb?a#&$9E@;tNC-C+z)+;ze&n=xF`pl~3 zEG;bww&~TL-=iEJ!y>iS)+9deEY5!-i4QTD(@9x+FZ3JcTQ<+-@(GDs*h(f(6F_S6 z(X0gp1%YzoMJOssBzQn%rRlqO@4z@c2@FUX|BIt;e$#$<&_GKGCN7q0eoh}2EpGej z?0vSIkTwL=n7_{U)J}DQu!hZi7(IzmNAZq)2( zLLobS;Ou>S@p;&Jxy}L!s7Ro)Yd}*H0&CM;Pbkj|rb(i?mVvqt2D2SRM>Ob-%L85g zKof=7>VCpJ7pf_C52_H;Ds|M*55-d7oVUj!fPN`A1rmm zpnl?jRGs+6`EZer|4$usT*#4ak7uiV_XK?9Ak|&Op9Ddh^0H+(d&@v|x*mdqgicca zCp6t~(Nw=~&TSx|_npOP|FYO}G8ZN^2A|?VaOe44VlH#_WqI-|HZKU>-OagN+IoLX z)HxAnIA-0KMQ!Cc(TanR5=tsxqHLX|(nJc}L2|wYiqA7K!d z{s-8lhgYruM&A?&6GfktaN(CzNv_CLYWnTQJ7!QyAW}%L0Ne6*$)N;zg$(=IGBqjq zU25WLy{5m!VgQH1%Oienn zTyEz97z+)n@6|7n@Md+q3LvS6DoJ<6-UB#bU4@i4`&bYR*8WBDy-+3ykmr#PFOc#5 z0n4!gWB{UP#aEf3x@;tvY`A@JIEQaQ1>#F>?om7h*3`plKI^hv z^uM>qU)kd;N8oB{X*u=v#OEs7%J7%40qKp-Sd{oZ*iajw5(<0=Nab3yAylW0)!q;! z?XC|3rbDqzgXJ&rMi7AuO>;Akux~=H5|`et{RxO#9F?WH_dS_AZES(9GWWH)_L$6W zZ($Qe{GXi<=T7*t!_XMZz@BkwkYv`Hr{-N~;8aC6+rJ4~4`77>KddPEBpB^$yHqFP z8L}S~N5IFas-yCKDKF@S$eX2mqmJITCWj#ShXmecx;Y*Ji+Bzzpx*d|IS`2>7J>OP zejeT=b7XOH9Ii!$IF}K0TCxS!MA^5cTw`}Dj}Nr{7MRO2{4aYx zi93x@ULsydiWAHyH7de70s#Y#6W`mhv|R4GU4^F!a-GU6V8O9Ox!x?O2f{gxRQg>W zXQ6Kc7b1H0ahW+Fl`LULYo!;~*>^pd9RPxukgP!|qL@i1u;-9JDlFwoATb(s>YG=p zE!BXO4GJBI%BMQODo2BQFkdtTk8mrAf*Z6Ceq46zBdiS z=_O;nyoUDu{&mwbV>A?5gb_DDxL_3jkww=jkBAn?DX?vK--fg!FgU$;ch~aBaAr>X z!|_gJDU*W-7b~0)4nzv!L4ScctUS3X+(RFddhgfpXKa6_TGmS85A;z7#~gWxv5a9c zXdEAx1=Jz;M~Xd&I1Ir!6`B&<_8w1_HP66U*Lu`^! z^~Pov`=wmz8KQ+y#n0}5ry=2TTfBe>4Fgev0Fzo*33S(G%_CcemQt3O)iN%$r&+R% zaNibb0y64WxA5zl72+V1B)YDN&(2p(g|6e%6!JMO{P=iy?!Ryc1gIBW)9&&mOXsmO zz5AAp^T9cX`tExsL}8-1_&0NZ=(Z9uo#KM7%)eRys?3p@QX+&UYLBp&rPJfjTXlpf zIhNq#i7al_Jc&jMxu{DMS95?MyeDBc!k!=BngU_J$9H@n#6EIz97A_w)pdAJCI~8M z2a_6UvXHj#P|W^+mwp`%bpwZRoiTgOra$Nt8*FM28b3G%>f^8Bf$r}h=9;84VA#YUql|eD`c8K!+TwTFz6&Eg~ z(agqqQ_Z6wd>8L@VsnGZ^NB@)nkKJB$@`~uZ^s#|1Jpjnt~U13sb#Q#DP!hIcF2>| z`PyJb7x6u5jVaYT@6d_CK=d;Zy5vJ-En}=>6NMS0ekOfZ)H&FvLE2X@$Qa2gC9-(u zu+*x-k16qHrYyly!1K3xf`OtaU&N3zl}J{CMag3!Ii8Mo|uqr`MkoHx~vOJRH{Snf_x(V7PUS|%Wyizb;cV^wz zc^BIYmnPhgkaT&5tu&}spl=JpTNTJNf?tvMN zd54MS;XzLotHm0^J)RHl$M8*sUq9*?gmNa6b3*8JPC=KP$HgH*m3}AV$mVm0hIu+W zUhC5FOtz=>@5WUPJ015h*FnVNexbYOMcPkjx79)?7eCALh&A&d`C7nM5$#QRr)pRi! zIF18|YwCT!Fo-l<$&iD&Q-*a(qJNcrU2dmw4{U?oPtIYRo@cHML!zdylbtC}b2v4U zSMH>L6%lUtJUfrSL1r#ZM6)QFj$OqTTat_=rXTqn3^q8C(9$V#1lvq?2_`RaJWaAv z%JBP+5)1SW;bY$EL`#R{gFt72*M}&h{39}|eNcTUi+u{^joQSs_YaDaFGZFvtAy&b za$-1Lf19j@6K?k#PicQ)M-!VQJYNWR^{!gm>&ceRW(<&+cYZgBVJx!5t#}CC<45St zp_jXH2XnDIntWx^;c>qmagA`mh^}yxMzgH|HgK1C!`UylM-a}G(_>`_yhG(5O|IV+ z4?`x6K0la!wwL%2>hQBFi>^rSP22dAv~UR~&F$q8)(pIDQ41b3BfZp;xmUB!t>`kkHK59J?JabaUQmNj$o3(a*0;Yt5i@gpx{- zQ6y{M6(c8}9kPd##VLlOpse+$V9dK*N6`IP|J0y^%|<$~Ra1Wx+0~R(*NzRWd*X+( zKF2RyBEE~g1*KXPFW8G@OckSP2I^czvhd0H-=o>k%!-)~ansbAycQQ<)5`k0&*8;`+}(H+OjTWbiqd z|6u|q#pI6!E|&84nm<)SQm4~WwB&*;G}uKg``&2Jw2!~R$Ayebut#&NXE?mbrWd_Y zdexlsJh91%cbJY22+b#M^`my3$YJwl`=&ZBB;0}G;eVO&D#ZqxO za1Toi@{&~BQ!`A5raQM_zDL+sM-36=UvBrrD(nJdkHde{Q6&4Y(THWSPts!v6lOe4 zx>o#jV}h`6F`5$6)O6|a1|oA3n3E5@K5&bC7U<>3WsaS^Nf;@C}J+oJQ`oR~*Fbgh!0Olhu z!nb%oKAL>dv*}c___{Ik!|Y31hGcl(dYpRXIpO&539->yC)-={ZcqwVzW(+Rfi)l= zfw<=tawrSxnnsc^HrkZydTSK=+-otf^^Zj0Mwai+go6}mvRh0iPH+nU0f!setYctbGpA5exY8Y{S0FD-966x>gA3B zEZ82srmn|9Kkp0p_veIfSe?F8BYhiYU#iWmqS%px@3w015m|a(0CSaR;;<019V6BE zR<1~=lyL}9QYe@*Taqtjoi~RmmZL%Wm!E`__rs$0<9=b2!-}DKX`%-MmsdL-5H5>u zo}HgdfSfk@hjeCfjG&Bh@y*&cCd4X8dBFt&Fp6fhsEpu65oyLHp(? zsG*brKMZv@I8cwXN>EmcBTT3vNy!!TxpD-OSox&!yx%;|R3FsMGSewUvN%0nzHJCV zn5j<9U@TR$yKp}#^hMfLJODeXpQeQU>F4Ij4douN~Tb30x3R43DsNqEniP&80tdm^8m+bwe`*B|KC zBkr$sK8lawPkpGkCR-qscqwu}`hzSSD}#&&?b}J_8?wH@);HCtaWM$2Fo07C5vC}Q z>tT{}c{eM_@A}e2TL0S%+WNt5V`#v!1SIr@ML9P>5L?>JBx=~}bra^B9LQQ-_6vhc zDm@r1Ic%ePd=lVB!Kr;v(QR?D4 zO6m*M>!c7Qyugv{Qlf}v00MqM1kfgi;Z4u&w z+%twHmDV6mf#(i}g=Hy?X9lO;uk`^W&^;yvKTCb6dUOg(W5fUf;A9|b%mpHMKUwYh z8K_u7N)?Bu@5%~MEP~Yx{?x#^F5m|Vc8BBC7J5Jv@{GEVbfCO42@2#zfKW#cMd2w` zq8&*p5*(=$Wo08myU&_ML}IcLbEAKOzAy@-PM>v}7Zy=AJs~$l{2n#UGQuDUK^b=d z!>vqx`ZGojm0w@zv#z_KOi3`?h?#m_9xsK|C?1H}mQHy}6CI3*@-89gj``l$yF|f> z_?}O^N^3i2lrDX^+9Ud2EFavuRbOEA6H^*psWm|5^R)FLKk-@IHr1$Jp7;aD`Z>y@ z!O&SUt<&D%`@5@aBm&i!k{b*ylO?WB{gDI)pE@gssLj8{BPV)k3IBO8Y<4=q$tK$m zF^||-oBH!4+Q1RpJ9c?+I`w2Njhxf@ozp;kmu#LnOc|N=AmTm{Ye;T0yk;v6dclua zEYVeV>v(j5MC}$GmD2dz^lZh#Y4^|nSf4a+AXCP_D@AQ$@^THJ7xk_0{{V<#lr1#gnkFNUH~>7J}M#yA+(LwOna zf;;F{%O7A$;A*F8RGFi1ONiOEvSEIhBRJaodavQNhqii=z8Nu>SfTfJ+TO>afZ$CW zg_ilgqIj?SM`+OMjK`)R)?vj@WHdl;vO@Fi!I zhcvZm*0E}K4h-|6^YavMS{7w~joCGxfDSS7Sw4&KL`Nl^129tz*GUFa{FYfHOEx+h zpG_2gk@{DnvO+I|-CJ3mZEDGBeyboAhGf&qT;{lh-~~`kMtU~4wIKzh9P_FT@+=YO zW?<$uf~H)5>ngQko+Xqbv}vH*Ks=`Qnhs-5?xCPa+mD^rjb~Mixk^|8<^JjKEjgz@ zlyWJIxxCvhYX0`}%2WZ(putqMvP3G!(&xs{Hw0BPn#ArzFDpxbPw~5_6vc^<`^xkf6v{x&NR&{gf!XC0H~7H-p-*ilDWe5rOxE&|1> z6i#te=F-tWrP};d$NWA)Fh{b8kADP}PQL{|#((Fbus?brnkta#%2^zfGM>u}TBm`} z@)qMuR-NdHhjZ1H`dxIg$ycei7mgPE>^%JSCOn7?OT|^DP9zmy++*wI)LD|r!D8wv zykM+Ias*j_2W^}2%#GJDdKBouPM2GDTenVJWX`YqNdxPagA&$inEG}R$gy%+^c=vT zrvY3R7K`*ksrXXnlOw$EcYN;q)ST8ulC5K3r%RHZ`^`a>JNu0gYiB1+i8~K#LPog6 znfc4CG(RmyR=*48ObZ*h3!y#f0L^9M#3_n)v`>%{o>1j_3rF*=L`@k9X+KNq2($Ol z?~xOSV9mMWhnWE9(RmL}b?k8RyhNH+{n*3w#S8jtQJt;5SMpMg-*r~sbeNzsE)5;^ zoF$jkm?>hZpARz{j%r&yCl&M#gE^9WjzKI_bHe9JW}P$USjZW zuna{U+3cAsArZnATfS7#ir-Q^Z%YFopT*S9XFjDnpATX$KqjJpclfxCrO!{(TQB|m z&|p%2Zrg!7tVoa9)HcqUPJ{I`dzVgyQo%vmQW{S#dn-o*X-Q!QN|LKm{_WN{iNs*r zB13~-KnLxeqp1cF_SZz&H2TCG@r%B9Ck4OA>;b&*N$MhWuwLBtOA1%(rF|5PUX9Ps zmzg?0P@lbj?i)Rs_CCp1lop^#dm~DHZD>Xz1&o!cR*mvJlio5&64JC(0=|w84wvCz z30ZL=*Vq;S)Ir41jv5lx?uv<1v4rHIy`eCL56G&UlOv~(q(Z=?Djpw;qXosW|24d} zuCgBh9Y?&q7_h)FL3GVs*@-jAF&l3yGs(EY-xfDrFmzOY z*O55SOZ@(9D?my$6+C@M8mvlHCA^$J5hCqhIBy5DDzz&A9(ZxJ+CjG>I=`coyD~nD zJH;VoO;M=!3C~`>dl7C|EK;_Fn~yK*(5Xe`hzX?KEA&)`RTTEe4?NjUaDng2!rYR+ z&hKH5^#*$VI(@vup{pAh8WRf4t4A}vJsd36WQcM^l2Oj7-N$Z?SqgetVEyn#g+5|! z>*r_mz}E=hAnY316m^w39+%j?^?8zJ@q@7auUH8^>sr?M; z5scq>=K0>kUb&Y(tVhH~7+E5JFLdmUAu$LHUh>`KEO*hjNXk9V{)tjDE3I?roS1_; z$6kP8oic8{C^KeAgArd3i4hpKo!^5{AngyDz7zWEhUymc8H8W#7hP=ni1En}UmZ6z z*!5-viPl`0pZdv3s_BRC#0d!EOt2}qkfAuDu$NJIui`l!<|!|Vr}M|td9co2Hi0tC z*x&jaC(}*CVA_7=dqOfhRoS9wlsA|V8SN5DQ{ISuXAr7{T6586H?c;)rXsdKdN3pG zo@E)`Ki*b*2xye6&$+Mqua5?L!Qu9%qxy!Oi1a%fWm($G#T|r%aarUi z#w&i>1Ha2lc#wokK;!{)C_u{ZLB6lJGmbbW5FqN&sA z+b9WNm-1T$3yn;yA*r)nR8uhp1{=(j+~tOqx0MS{66RJrW1Gb5uqu04EyM_*d=|Q& z3h)cO`W{*`!&fc2zo}^Y8lwM6ADt^U=}4n}&s60#e|z9f&Wy9!R&#C~)yLdp9cqCK zrX=hBQKshHW%m)mS_*o*PT5Zv>YSn0{c0D!6(V{V9|1_^;o9&y!zjY@;K9bcj2DXn z;dT>yBMyTu?UhB^OC!nGd2Jc6rr2v*X=W2=}!Vh5K8)D5QPrJ6dK=(yy2USVbnLLy=YT4v$~k z=zh4hsDOW4p8n;IqxALpmN1#1ubAj%t)xY1eJ<(je9_Xupm|w_0AE%yC@bBfMiRh| ztf7NhsBz)Fvn}szZF#~=g`0^%B+?aTp6HVw#6`h{=N;PzHzw2lG4Q6LOpVRqSf33H z+T2*b8;GJLP>L#Ej(-h0S?B8PGH{o~%hEy+v6br}Vn5T)!DL>`W%-4SC_+2=bUGEv z)7MZKbCV@lni*lM=h^#4j|T!FD$hcd0`Fx<4(m#+xQ__hPXi{wuFJ|&#DeZR3wd3% zWd_+4<>JOx&j#&4svXi``qI&i_ZRjW$XH$}XqX!ZO*vN=_q3RUaYb_|2>aCBYS)Qe zv^UQqoK_(QwNCHEWjlkp#O{wbnue8~TIoEoeEMc6>f70zmrV-bTup^tSL@%oJbdQl zvs0HPN+GPLrw8BiHiJwvrFFi3+Nu=*dB^$hPeA&UmfZcy2P^*udGVP5#W<4>-2cPX zRfk2{HGNSK5tS5Bx*H^3Mlkdzc8lvB0hQZGjxrv_ol zr3Hf3q&HX1XLtF-M-N<7(f{qaJlEj?8fK`1Z2rvq{nMon6IJ69%)a*Py^qIBbu{_E z$u%o)6I!z5p=Vy>`CbMZT$VuDU^keH`0j^kpRNm{;v-{kw#{WJ5-R$$A>-sV!FVze zweNi5Kn1jM`Ca=*J5)MDUep)8s!_^L0x^J@Y_`EOnXWjmw$)U$d6||+9sAiDF)sa{ z zkR+mU=JV=J;G^C~kDD8ntJ3&d#2TppH-nF>MAk!@^`|>O<(r4!OD3_jZ!<@I>?n*? zeHz50$GYgm->9@`EG~S%@xA|->=Icg0gkue-M1$~FM*$XMJuKx6Z=C1>*AGg9E|m4 zI``*giW}B(V&^tgt01w)G3V&|ZQZ!j!&bil%;(8kO#+T!$ii!!7UZzboMrv@Gvy{K z8*d@&`X<;vc`eQ+tc9L>{M1%PC%JuRLMQVHJcTHdm?)4q2{!t{@C5hpB`3FkGWJ*s z_E_Uj{-?mA@F-Dav7FsA&Bf!uyuU*(>P>i?*EA4oXUUhF@tfF_WvJ5CTce@-?}qK~ z^b#ntm;ZPl*AuGX?x|ebCwrhWY@6mj);k3GHMEO1GU%huPHh5o?iF4EBDQP?17N&<|nf@NjP)NCPIl89aC=#Yd1$}3pA6G`H`$?3a zJPtGebwMr~({ycBnIDUVDLwwoB~{ps%x64R4M$%*<@VH8`Q16J1^iVIbCQ9lb;=UnH*V z{Q)5|3F^{qL64RJto{3%!htAU3=~sUy*<5AS7|E&9wZu1q4yL^)xLJ*mPS~iT$ z7!a+0UzYW^pmP_9PK$Ar&GV)C1m}PG2{=0c+Cs5YPzo=1{jXLvW{cCH_oJEnyL6RYn3w=0yQt+ z>CzIq)i9A|o!3%|!@7nHh&V2=zt}eTZMTB7EtlBOXUS-xl&u z-<>S!7^akX;G|jkP9>aJl&qvD_Pqd&aow;Q>M6JH?{jzewt)eKn*{l0R2`~8<*Cze z5z2>DGAu70aL3fdnCM%PF$^8H%IzJX7v{NRhTQ$iQCqrKE+=@0-X|D?wDh6$x2gxN zOyH0BzRzHQFlmZKFhy$6uYP7K>JGB<--MdF6h>8))=IofnnxNQj^-$+Ws>@x4wZ#A zuaLK+l2F`ptTTd$&rs~^?iVg|#UlL%0wnfejJNR-$XV$g2go=3Uyy{IuC7odsg7pf z*QNFp`hy6uioIo;58AAiJS1z&(#hWXPZIg?_~=!iQPExGGnD^c=kZ);j6qQ%t{?3z z`CXLeBOtFgw&y@FUW_nV!U43UKk=P+q2!!ow1?q&Sx#c1KS~6pLl3iOzK5V9CG7G0 zmq0IKT|SOg?e1c;r<$&O0^=u8%UJ=Sis=e-tW*)#?~Rk?ubEGG7e$MHEPJJ(Ij)X; z>>*s$)(+St|Df)F`YPD=vGIyHV4-0HDuaAV`ze5XNO^n)p6FY~V<|qzD-O9TUBC9o zk0WJo#j`#rGJy1=@VR;q>Bo;_1~PHcX{qJEvN1o(*nO$bnb`*aEq=_ms|UzLAnL&i z-sHCb8D?}Z@rSWgK=>@z1{vT9cu}<5SZB{+y`xTh32u`gSsN0KN5l>W{Rvm3dR+C56=}*_eK5-`hT24<;hmPZKo0jdbQI;M>fk zdr=a72vFbIYtMRUj&=Ig=eY3mfil0y?%t8#OyPrsn^m9^29Bskzfdq%+B-h)c7ac`8(XMI2!m`_V>%eeK1w$^&a$mU+o6;)7f@3J45t47K(Lv zJK!w{7z9uO1@$n-b1;^X8E)wwMJ9|dIPora6AI9c4ClapFrR~37SlQS8W{LyfWOM0 zc0b#py+Zfu8Vu?1F)&!Nhu?BTxMKw~hBygs$g~KGc)_>0w3Dc-_A9a%pO;^xe6O)h zK5Iz1j^}NmL3pXr29A%P!{@nTpJ%K=#1JGuY|2j; zWZ-RPk$c~+aHBpO@(^M%1 z>$FC7TLZoq5K+@aK&ti658GTxD-2HPhCiP*dG6TFETWtQ$)=sHiCWj4F39g2#Cu-f zZ}MDFZbF2|Uw6IOd=yhc%MfYgd~4&;xSTepEX2b$%U?=vC^+ySdNv)!b5vj_u-a(jW9Z>8h!8R3}3&#*mo`1`v%Hh@*h1s z4gpY==_pqrIcIuvD6MolcZV#Q)?4Bn498-CtL4Z{)vUFASbotV0)R3d;D#Tn4iRwq zPe-%Mkx_>T7=8I{zw&3rZ@O1s(=XZeKyM&u=+`e}*QtJ07DddfSOz-3b<3hi1$kaU z0Xh&L!C~CV0B6=LQQreft+5AGMRgB!nyKyqOrypgm?QIGtQpMA?eK07#tB7$={t|X z5QNbxjw6E_n-n8*o>%o>=%8RY*kkB$#%Pt>yYq*{JPdG&K$)qVHQVmykE>E0-iL%=lu7Qd2KcJ?x4$guSU=J^~slE4O_DjBzc0~&`@u0Jz@3Z#d^m= zBgj-~8m{+TwRLC{xH=~kDCB-<6M)seops)u&bS11G@YXa(S{xhZ>KSrwIR3izNuR# z38fFa*$lY+%@RsEx(%AoDZH3B#c3c%hMV&E^M>= zzGZz(tmm$%wN5sYGsI-I7<%t8ryeUwC1wu1daHZsmOI>6hWT(!6s< z%k=8SsV)m;U5NK<)6&v%1NZcc(%iX*zzs(|)6&9nsL(icim@Qdw)+4o12Jd_UO;pj zH#KRzZGz?W>Z_TyWS62vJUws&LO7>%c2r0>3SCs0Da_yV`n<&OX2Q=6(NI2*lBX(W z>Roc7IR|MPo@3sef-Y*#Fr!rnZVk?bUY)|R^qF$GnDX|pU}s0nYZFjW)tSD+y(oii zSl{{xG*+)U`b>Q$t#NX$51w)1T~M!*TP><){Y96qW&v@flf4MgjZ}_fbqvUwTfr_Z zthN6nw#i!VO^!OFkS9~h(0skKv~>JNI^CNh8JtEh)?$Oh@@E^A?2>Om%#xIGe+Ld9 zWw!_8!|0ZI==kKF6%JKjuSTTG*nj-I$8O?I(H?7AQolzx!Jcs#yT4=brkq}hr6Xql zc+7^;;XL=4y^hVRm*%r*lXf@jGwcuYOfV%_jszlMKT6$J%0wyqgwRRPsytVbu0y3| zM&*Wk@N>!nNxTZuL<#Pfi6%Q{e*q|Pj5g|PRE5#%_$-C z=^M~5>kr#dfJtJ_fL>dsJzkqUw$xi42fKy!_wGcq>hLVH&#ik^m=Ce-IZ);=J$Udk zl7t_>VNZV1!rXWUF;!~N%V7x}O1pmOWw+j&ec9&}8Y@_HDlQI#Umi)^ygCD-T2 zMgu5k*0CO3x6HzK;^EG~h&4y% z*spuxzVCD;FW}po>^s?g#j>xPV2!=-++MGPdN@{o&V&P`#tY8ptWZ9NpY(caZfIw( zy-xe#JoHDJ=%DTdLZ4f6M#*4gPG@`^npXcE(ezGR?E=2H8Kss$D|j|n@MXd4^PZnM z#hZ!ACR^y$YCA0qqVhf-b}8A^q(It)D8sy7EUk8Qgq(Q6pPA$W9M5}AC5ZQ0BmAPw zQ+R&UFHQ7O+Sr`n_|zO$$^^m}u6gIrAMxEO4mBm3U`tO@yeWpuVipcO-*~f*=Eoe^ zw-1q{D{k+n5by3om9|S&>bWO9n=h}75wh`3Aq`Y{kcLB);DkrPWQ2Osax1h=2qN76 z2N+g?sQeO662DR@eTSpd-^uuJoAA<@JjH$a5F;-TRTKG9F(t}$w4s%ZArJUSofx-T z;ql-@jKe@wcjTun8N~MjZTN`l#ou<@Y)J)W5Yq+P{2;2QGzM=wBQuC!2HG$@sYfwI ze)=VY*dWj*{Ym|@SvL~fx9;f(@ZG)8esF&sJ`})T9z*wL>Pz2oaW#4YUnihIC!}IUvq)XLhkXY*5Bdd9@Bp*|tBS zj^|$!bABzAzovlV!yb~b4AVMCdzSY$E1RZewTSym)@NZI^O~gPwT$?8)SF-*r=_=W z1ki$4A^cOuxBW&J6u1izf zyyBa}L^x0^-OXPo#@rc=aKOopg~PZOE+<*?e{6F7%M&NnayRK6ll=9BV1^37V1*~9Ly zKG_%_dI;t5HsRotA2_!~v4deQA)beXi>?xCV+3F1o4--l16iV*k{?Xg~_Upf(KDV-8mXhS!ws^hEW@>u>%0taV z3!L@|K>4$RbC!#BCF2<`r6_L3t#8rfiZXs$QshIC$lpgvrU3{^1vX}-Pz?VtkOEl# z)rk)9!Jwmr`ViIN0~zGQBU?uUh!~HJ+ijM-lbKf3U($f$!;f4W46`jI0hTR75?$)~ zZyu{TxT8J6;}sGCD^`jCNgVAbr!1lE452hH_;O#J0yPiJBk@Bf!VHZ;lSEA!+WPi0 z-+KTSDzzPHp*MMhf+AxvQ{;lApIa*Dl#NYh3u)g*YqPw*nQ){yE_-j zKhGKBqO3;BX|H#Ags=qPTnZ!CN{U=7ZfXyXPMj4b%DkRQh9D)1(O05?`9EnGC%|Y& zL0yMbPP}JgNOnH|BLgunmhN~h;V;~eNogKjDb_PB1BD^RTvBJtJ4h<~sSbXZ-2s@1Z4_*E@`CD)Uhj(`AD7NCQzhhjZs85% z8H%S2-34zdu|KlDd)w2xWiJC|xz^{bZ- z!3EJ>K&w3Hlu0a>#AG9ZT$~3cCnpo=N#=hAEN;yl`8Ux zW+oQNVX%Ajt$qS&lwga0qz`T)h5Z#pFSbi4yEv*-)ijw8xr!Otj&FH78ErxYx-}Xy zk2qDLjR!jOj5_xP9a=?&-7Ptx;O3!PLYBOC{bnPy-pr+(_w)qZvG}CLQBSZ)uo#Du@fEDvuUB|JF0Tm425#uUiabceC+wFF; zeDptc35Hgw>PK3qWBwBROBP7f2fx*}uRafPmmWA0>#C>X0+P>PE}=EAL^37ou~xTq zIu}a*^sAp>dx+KFi=ic_Y&%x}Jd#wH>D@TMO=ot6kA%OfX3>tDHtvd$060$WUFHH* zGA=jnFYG#Wfytu-578T&BuGH(fR6&k&R{T_d3zwH5$wyy)JXZNm+^}RWc1)CtL1=b z=;&#u65>5WX2f#1R;mBUiHd(K{f)n9^LBIdO7?MuRVKusWB2&ID9*c>8PKeS)Bii< zA?}a3^o4)gu(11MxafJ@T`i<4G$NjYrtZf_!hP{=d;Io)2-6UyR4#O~2H9kh_6&o1 z2aJciQ=0lGA`bT$RkN@Wn-9(my8~D61}+Cm4*Ajq=i_x7e`>cQ^gq?Z9hQ}G{;{=H z%k@{po`nE1>6VSm=?uq^61%;=-t$L+U(p`kUHlY$SWcmoZQ8t?aC!Z7uVME5q3_#9 zHc|sz*^k)poJUch20M=j=x(;!RtX2c&+l*lD+Fit{BDsC#j)zHK< zdv5|%*iEl9O!wW%`FtY1VcD1ZCr9F^TdHSR1mhCet7XVkw z;aGP1t4^ft8|pC;OU&FZgkvZfY`YH9?y#0H4TWI%McK4|9k3o1PMhtZFeOr7cr*9t83g^{Y z3Yq<7DiRI;2t!L%nZEIPp(YrjtQrvBuU&2kjU-J{v7M}B9Q-E2x}xTEUH+IkTG-ub z;JRY6l_m?cP}U6hHboCb|NKhs;p10J@HegU|k*qMgckdoH3B#&KOO12hgV5TBRnXA;OVq_o6muu(TLDSjUp3qN z0{CpEea&v*y|fm;S?jU;Sicb-t_f*g+8h!yQAoJ=M2(-)@fcNRJ?U17>`GF$=p%5A zG9}n3IxT*Nzoh@MF8vCvqkh*zX`(9mFVKWME|p((^z>lpRNF`b1oVLLa~#|Ltr4we zt3=#n&T&Syd9s~+biy%=7w@XZw$EVD^Nb3nWY3O**8mk2{VNL1Q9)7dQSaaNJINz$ z0XuAyUG&Flx2Kh;2Uc#W2(JLhEKD=(rrrmqXKJ16_U=@XvXQQGYP{h%u&AV!^`$@F z>>rgNM3Kkb;XVK(W4@b5k@eyu?-T)@tQ3m6)}I5%vkmgpaL3FCQXgLY3K$3&*;%nV zI>zP2TkCgtYN(a1-<>O$Eq8cwf_EYdhAqSA8VCVuS#6^W7$4T>Siygp`JEd$YX$x0 zsI(U2&Ln27hE0NIFNDSMQQ)KQ&pbGCgfbyFGbu4Y2XHJ@X}EQ)9<`%}gF-;P%Gc?T zzu)j@yJHj#4_kewf4u!fBz1&K`{Uh_QP=~9u!0PlwXkxk#&ybKD}5lp`bhPgWLD~}*Gr>KF?qSIni!1BNLsAz{sNJ~nhmuJoPiUkM zUdhJrNWP$v$M4!&or%Ht`V!dE*bik~|0Ow8VXbSju|Evq0231VjlXQBua8RN>U0}# zXR;)s!5P8?16OW5u-_P*pixU{H|y=p{Y>|h*tE#JFO@VB11}V!Qk*hr-S|}ZWy0p$ zS7!BZ7;;y^jOZX?1a#4s;re|0Q?X9l3y3L4v+yv6ek#kEY)H@^pTSNIk4c9fcRa ze>=R$0x#^%{_n41{=l<>av2Gdf&VfZUnqV!^x%dQ3u-v5@9cz1NJnaY*BL<%*><#? z__aB7{gSfaqlnv{7MN=)5&N+}iC@j+ZHqTTKlXAGKaPhYTR~E%((1|1kGz{l@yjv9 z@eA5bZdJ8EaT}5CC0$XZcpD(AXuP&HGRbXP5fOmqSdpi^!l*jCW2Hu8qPR)CLh>9QwQ=G(NLJC|OI(?c+7 zu8r9nK|#a-t@8|e)SV{UGIJ#4bwk8u-j6-AQ_WBW5LQ%fCj_i7<~2#H`!P>Gu8F(@<)w)nYH{1&OlT*lJ|*Q8@@53t42(;94F-h~#ULq4o75L4EQo*_&e#0X;oEKD$1N>&dzV7?dLZWG_-t(To_>Hla(qtDn?a}Xi7AltGHA(aLGMANr3zaU5Mu7|G*k+4AQjjr9$Bw$M{_;Bxx?f% z`)D>i?oHv-nc2kQ_Y=@-IK;6r#7FeRP-3Xk zEBVkwmbD2*l71%wo0K{2cl67ixre}WgR!bWc2TGYaztEY>&u= znR*wdEdkb4L-Wff==lUkMjjAU1l3Xr=aRGyQjgNHcO27n{mL-K9?)%w3Opf6f3s7` zVc9C3UlazJ=k5NYKkL%X;l*O2lt!dIMvE&-Jl5<1y-G%|Z`Y@^lZ4F!G#Fg(q1o|K z+b6v=qE@#7r)JO;>~iF?^)HqA>LZMMINSIH20c^DNfmOnW6^6S0mFJK?vo$~Y&_kl z^ffcFrg6I*rUavPv=3zxIcaysi{C%C3V-qvpat9Cm<@hL1Laii4eVvS!voScHI@OO z%EHt&?dBw)5C@Eq5{?t-r3W1Jy$ALO#_JK6qJO}i-$`O>=FXlM&>j;Pp+I$gOv?KM zF-|QhgY~{C|7BRR{O#IJJ8`Cj%kCt$GVHks>(T`;oaZx=*5^>wtFJm(i_4&?Oe!E9 z3XtHn=`Wk{FRATSv*fq$6-*7X-bWrv@3Y`y{c}F~g{`P z4iOUj+1-(fAPI?Q*0_fcbfmp^qR{#&X1uG#d^zn_!|%LKc#`8TwqUijsA)eqW~a>x z@&6IE$H=ABbZl`RJUdTuquFCEFqc3~eqleeyWX)6*YhBw$xAMb$x}2EG_4{WTn~*K zq-iA9Bu|lR6Y@CMxAG_`8G$ctyJxc~YORKo^WN>nmkan+ryDKoiJN5?5%m(o8tTW! zLZ@*7jyoDPG(r^r@=$=0{*p`33&>@~M`K#dWMtVo63ozCf*i~*@9mLj+)MVF*GD}A zlTZwQ-duqg?uketPq0D^Cv9W3l{j){y<3Wf9ZTNa4ekl*AL-V30U|aE%%fdR3cGPV zYAX)omu=p}WF zmUOv3rtYm=WU{Kn*lhI8W~r8mi&!u^gfGf9j5Ece+?ieLO78lX8`rij9BUG=O zOUj*m+eNzg(lxV1)V#GJ;AE}c@J5%Ife?D8od~)A5yEw3GReQ{BC%_WZzKB0Lo1zI zz>8FMzi}Zwlt3iXe># zqN-1JjV>m|-yL^)T|rSHks>}MLzNY+yy0GkppF1z#r(7sOm3x~rLv`Mz6<5@=p;df zk_4|Em-m6p@1ayS4%PbhAhp}8Ja3;D+;MjXc$$TwTdAV|HuZ*gP#?Lu8-sjqt=E3i z!~VcrLnah(0=k*Vk7c-$$oAgL2M$uHaKQeLD}PA`Z11OG@|HEBFIFdyt4YTSsnnj* z4`|ZYepRG8+k=xyVN4|0H2+Ex<}KUZ@>ITh?3g(qE_+$B5kn9kmiwGRD7G7R*@6D8 z`T7OUT$>t?6x$PH%Ne4lTp`dJ@*N(r3DYWMXu%C-vA_!{=Kym?B|66yWs<2fz=<2V1ome zQ6oQuXO1*?T1Z1y_+Fo!jf1w%5!*N zTB+7U^mHspsWUzzgF|^H^;exlBhc`MSL$Ya4F^6Xi8REDg`=p+sG$8x1 z%lmg8%G#UA_zlD|Te#g(R{{j!wa)emaG=%y&4|CcHJvrFF@kj{GR*U^tZ=1e6L zFuwP5lPBV_WRfi|f;XX-boNRtaXT(UG2-Pqs~U6i+3D5kIy&5W1*Mw2Im(zYE%2!z zI6S16GbWDFyvP|>?EcotD8qA6C0MFbGew3&oi*@=y1}Y{$iTPuVyy{#dj0ACDQx)! z>)wM0t~=_uxpEp)}-?!;lfU zd*&?Q*CO1SXh&*o`#j#g=4vo2OlLd${7nDVUYdbgoXki;6UHSI=cF@9a}Xx4{!{$K z2^hT`k?5f~HC-vXvDAA8nfY?8%-p<*86Xtk4@>1At|?ROr*ko|FXPf`2*0F|!K zcp-ZSb-KzWADHlaw=Ksvig%XOKfziPyS_GGt46zy>6%@f{D3@E09d$dArtBUr5N|Cq>q5P0fo&xwph8qa08uOOro#&N2CRlNfg#|<8RH1twnt>+-JpZBie za9FT7a!UxT8_8C&DI1}mpuA|JH?@N9dV zQY}yD%R1(i+G`w~1kU*FergxZI;x$DHYv%fvsh{g<=8RSkTTM zgTOY1Et{HTwd>`L3x_0~yPpdOj-Z)CqZ<^hbios4qV&QWyjt}92~}ED2xS+n$xD3* z)7j*`(n?Zlz(MbbK&>0t(-{?!bOdP=5${XnG_wDpy$CsRX0q&&(EY!h2bpudqN5A) zmgolfn-z8c+ztk$KF7|%BW_)hvW-6@kJ~xOvWaHCC$eWdMr=bG6@*V{X_44)l zH1+a;@^0G&Z*x1I21Z!G8Znm?cYEYxJ(I~o;t5Ryo>4B{R})GM?IEOhi0L)(i7RJc zgGjpMOEP`m{}N?|Os-Z}CJ7;De0=qJ{)ebRU}===_X&>dD=f7+ekhboq8HoN^DyI{$7BTAOh2f>NEAJQEPNNZ@ekaBnwfTo8^{YLqzgUxS zAoYHEGga|{sWR`&^LF@mNqe#HsAVzJ96X-`Go6GdvLQm}pgWze@%uH%-VNs=5MsRO zc~wO*4`FW-^`)fL^4{Dv7uS=oCqX8F|4k~=KRg7ct%Oqd(ZFB!GXb&1B*JVeF&;e* zTiJA6Wu^l5HR&6jF+oZj2=!m?X~Tq&I<9cdfq!~G7dgZMTk-=_g&}4zqWiy{uQ9BIT{IgT-)U*% z55?+^aj5Ut-*F~G3l?FiLSZ&7nA$0mXGDxK9eyx-<13Kr(ugKqAObpy~y` z-VY;neuZlc)^{nX4Ik$r5g+)=YkA(CC>77vKtzwEKRHr0Cd+&5A!>3o^k4)DmIb`z zEEDZmw%de`PbhHLWWUy2fdb(GJBL#A|4P#|G81O)XzB{?VFaJN2RR6V1Cd8!>uiGU zy$(fbnDa?D89m^-tA#hFoQA&_XD8XQEO6^~iaUUfjAl_GA<qdZv&Jf0qWz+@9Uk>L|Hft?@vvCP zsXUS&H16Rs_}Ja87@*SPA*J>x%B>j)aMSZu9IpRWeL4ytH-q%I|LT=iAkeG4aaX|u zVb`dy9N(8muLFZOmeMhxW}nWN`>P14s$PBhR6}|Y zkx7^q3a?fy^eeJpO`G4hzj$bgsL%MG%PN@&W zTT+r*u?%xw%*cG~?^mqQ70(S0fk=LuNLYm&!2=u3XGI6!&vya8_Rm&F{vW>t=|Ct= z$}Xamg4{ntmD^5ic`g40tKIM8WurcN6HcItPMnAX<;3bYYsy6={3S&il9^j_a5MZUV7OM*EHf(NbL6*-KSk_+T*rUJd`fxK z9%%pol`N92gJ@^4T(XRl+BQF)kY*aV<;b|-zrr=9$B4+&SNKIA_ zY)mRW?ulZtc}3$pP5Pi5SOCHAT_5u6At6THSEenN7YgCu*e8??_$nXBttsGGocxgK zV#(7%<#Gn?|NjvtWZZCt@gcDOD$x$vp9eky?Oi~i{&8=9{VQ)xRalhl6b561gX=el zhU*dYox^pxl6ivwBL+?{oQClGP_wODq}(^^7kRAbPhShh=j}YklH)dJZFJn?EHig`^qa*$f^% zM{W_$TcvgVygkh42BmZ{Jm_JLAkEOBY%l$vz4)u#UlV|^Y^?W;{H3TB8!0V_M2`mz z4u0D?vhmSe#<&WD@!cgEif3~c55}Da3IZS4L?Yvlq?RK$kL%+*iWo-A;~#X|EvOgp1G(DKD^M8bQFA&LkWR>f4v4~Nf`PqqB z-LHIZ?dvXfkzW;U8aNFg4O2w)S`jIstg}XV3#cBFds-tOE%YQ5pv{O=VUQYTyJi5V zQ)X!$r;?xaxdh|?7|P5I1oJcOx}6d<&!KO0IMqs}M&ln$xjs{CQTH>9>^U18&&}RA zR1ma|T1Dc!{NqZtGCyYb6U}Bs0~vkXcrx8K?R_2dflE@k$^1Y5Ay4&+1 zVhv3d1PH)0;ZKhr{N>L-8uHaA1?j332~%_bDAEtUKYQc6LJ3c$2x*xR9(`*RWt7C~ z`(}EAlUU>uHS(LcpA$9KefyO1C(m-;;|y%b`2GpI>LY|?U(u@wbLxQ8ecR>%F$b#J zPP#3q<2L1z5q1q6Kv0yNtyA@bU-7h@4fxf+W<|#e{Hvz_p=cF()D>br|0nYsj18m} zHZjM}Fyh8_`;IRvu(<8z^}$c5-@FWdDm3|zTI!d+rn}P#D=z-Qie)lFK>kYCN&Ke9 zpz!9MHgz)HN$jWduMYSPQNq}WY%u@voR%~B#zahR^OEmbOU{TyV&e)GffY!sDd4O` z9JD?q1szVEua`OgE4lWES%#=Uks^HB+5U>R;a#K!#{2n?f4aSK^D}!nMl}0LE1ZmK zX_dE@cRsK22VyblgMCP;tiet?EGMn?%O~dmi;-bYhE(2w98Zn?dOT+`Sz=dJ3u2~^ zc-jh0Pm1!Zb_K%)f+aRngEIgkNt?MF2Ab{u- z52-5h)9!DLKI5(D?zKMskar+7kruVF7U;#_+wgVnPYzTU0eey@gi zAnfYkJfZo2y2Xl=WdhCk&GtXKB?XQXVXw8DpafF=3FYHsIWoa|6$O-_a;Bj1iuG8P zpk^wrHz{7S4t7Xd0Bcg~&)gyhftQQ6!UhfcYjgja(%3r)?!H0`@3&~02`7|;Gh_6R zcCnAHXLi|#9hO9n>>&hK!#NsGnUP_~iok7O(XRb}iFT(2Th&w|^auPxXJ~;u;jD;y zqkT8Z-FG>?`E=>MDwoJnDM2})k*N_if7nDH|CTbwc}7M_;pLg0G-Nfcr|YHYK%r@e z4-Xo5G9Fs$kJH-(wr4n=ul7_P0R6O>HPHH*Zze4KSZp9pU~7k%<%>%wMUku49#DAJ zz$8JV{~xe7f<5D9SBeDPu}F6n2;#7k=p&I6B5=r5g^SjDir;AShtX|D4$bqv6M2`W zdYuhYG+T=TEi;m5+lB1L2Z4n~k1_=arJC%XJWq@wsocM3OVV_xe&f75&IAfCF-V`O z+k|2DC%UjS&Fta?7Y~Be_?JUo$zb04JMSG$#OL2=ZXovOU8D70r=TAid>Ne74w1cQ z66BBliHagj?OyO3Wwvz15P?VO;m@+aeCor`~)d>?98BJ`~ZA%?k6fJ+CvKO4X`ybuL=` zjoTLZC~{-@Q>LrdwNArE`; z-!5~bMgEmgL^dwPy2YEU%A2GJux6i1{A=6Ft zBG(N6Xc2jl{Lfe%UJ_R}HtPE~s$daR@)XLS{(N=0*E6qX;YXO8h(4cqC*QLKx) zulFtBm7jzMM9pWv^4aWsW$_Tbxn8iAU%j?v>u$b@aZV%AY_`^aeR8@nfS#7-)$hMi zySq#H`sVVq6c2uW4Kv?1K>XxdwcZ>maIu@L#B^h2() zjdt*MK2Lboe3gHu1m0Lu>Vb&4?8PGM$tgX*IW1i*r?I(QkeHd) zX?79sPj*z-@7qGSqV2$JZKVFCsX)BlB*oGfn8V3lAa_m}h>|sUTkE5K9k5GuF zl=)_itr9y*3YRCC^X;j7p?F-!)oI3#Uc4^%^P1He#(&_klql1%&RnOOm-_3xj;pKV z$qBvWY@*&a2mSWdoKtld8u?|~ba@kNvdv(4S=mbB{z#d#LDX2TbJQbJPCj>6%X*up zGSd}J>Wz@XBfd7DY9x+0E5SF$Gb>OMa(3eRfU{NkTZ0NWC$J8M8 z6JJ3rUB5CiF9vG33X&IRz?~mapZyL_ zsRj*1YnfE1^#`8YPS)~y0YR=+q;z&e*=o-W)VvAizQFTd_>8uPB~;G_eYKgX=|;Le z{gt#~c6IdqMT`1rgt<}_yT=-P>cz)xp>tXb7*=Tnl!J%fH9(0Nmtrj_euNLeP#mkj)PzO1r1pxu6j1__jTy|u# zpB8a@-=7(~(Q|AZ*4_heEA*Wl8WH;^%pyEyC+F3du$8JKXwXzAgrHQ|s5UJ!z;&XJ zzAM{Sh*ICPmm|h&F(yPjnXlV?&G7BN{s}2G+yy>jO)7%6^FWZcY*BpO(n2BI(}c-2Rh?t+o!Y6rXTJpu zFghrrc+gI@qTDgs8KG_%G8KJ$JuTCcLnd6XA|?>9TQ~{nj||_wKd1IVci{DQ8He7G zhvivhEevkH5>$g=Ox3G7;a5{g6JlC`1@a$F+45y1ai(4@w6&d{D5c>d&W|)TVSA99 zy^zbj8bY(x=5wXZPX1gnwKJ|AH$Y#>T&~N1F`ET2d+k6+5YT_E2DCP9cHX|K(y_f> zfwk;r#`v%w-%(&xFvn&+ zQ&P%+``)XKb8zVUBtO|DjH%JpSzP>h>g(WJrDZpQ^4x?BMe^8`2@#j!*3i@u;;v4I zrd!X^Zp{1B#yze2OTGvnow%nB{yOXE;~`ZYy5wkEX(CJ`g47#2Wswu8+hwO*7+n3N zj=6nSvfJUmz3+bBVc~t&CX<#QD2afb%k?r$3Ew`mI~%k7FFA+?eD+PU&IfYP{aP$N zmD!s%)_G5%tFyAB_qpK8$a-=Gwee_}*w_?v-Q9;zvALp1|F6Ak|A#vL;x!bxZ0?lY z*Cktvlxs5OmV}{PzOF^(POMzUrDof9OSx3U<~FMugGDYwsiALfyV9swGbj`Z;~Fz! z4Bzun%=``C*ZRqPJkN8^d7txspYwcPUgU0>WSKG9#=YtdXUtU_tKzUMT9#5jgyX!0&*Hn!@6xJ!;>CuM&BidFQU)Sy*1 zE|@~iH9Sxs|FTDtl|EvL!v?qoC~@>{C&*jBzg(>sz&os}i0QCdvFPaQtlv?l*r)rDRyhio`k@lJ+75XQ(g}> zyF)^Y{OdRKD5vDc45||OjxZ%^Itmd&*i%f!!oo*is>${exUY z6RVzayLD)8z%!lQQv`qDe|5Q??$tFn9`z7S4s|a)&ndR#AAuM1)0^n(;K#*n{9P;? zBWmoMS#9^)+SWFb@rMdc%$L8-yk(Y-kO*j#Ep$EwIo-Hk zn#`M%JvNxms_mwFYUC`&wZfW6dsbWKlqpt~Jh-1cIzPWC9&|{ZJwv)LUGKI0-aE44 z3nN#$J;mOO(N<7hxJn1%ZFszcYhoRh1Vt;?#_}UlHxD8`eUtb)badhdt*27GJNT{S zi@Yf#y>l0$ZX8#o;&D7aOT!LO(wCnzci*;j-uHB1%9{Roxz5=4V{dLx&fGaUNz>(J zy6+6W?V`-9ux2LJ9K~3XKq@q=fH z0fp>ReGi#2)gs}9ZC$c;Y$^MV&WX>10h968gd`4Ac^*vVjIPon-FH!p$jG*Qm$1}k z8~v6r1vl~Qc{JDXQma&jn_DK;DMp$j$7OF%2HQ6*edvAHD?0EbBp{wK(pvC`=t za`mM>SuG`dU!4}=&vHM3E_#V~F_icE+=q8Zp^ zxJnH?V$7QTJRdptw3)u>hD}AxL8zfwY=JTuO^0^lMXB%Z zDeh%XB-^^X4;B4m>@!=L96n$cG?Z%7?ea9qS8abQaJPyTO^R${dQP$~P6l73=-T~m ztW-w+Tx}3O@+c{PKwDp+OP27D)G-dG!5|%#7rL-eNtlyh)4}*&8PEGKb+%82{`PxQ zp(8sqwWXx;75NT*e)0B)gs@y`zXqR(y^XTIH_&9ArQnQ>8st3&rLJ}Q#NKO=p(_$1 zMCr=CN!UbO0?b67lRdE$spT{=LHPlZ2G43Wy^x@nTa$OamKbUkx*plT)b4BPXZ1YC zDC|gk?rAG*>VON1A%E@ddJX^>v<_5U^ThRH#M49I=^{4Jf;SMxH>#%JE-o$@3i5aT z6nbe482L&YqWd*~bVY2`0SZRtrtCUlz-tWx8;|+vJ z-_BI@17j3nZ4>ys(-Mx+F0H|Q8`dLuxC}QVF;{67D}%F(K#7m^B1usqv^B4ioNx|I z{KG)jj>nq`h+;PK!}Sr#2;K^;q?(6vN&t<|0$+TX7EXw>`QU842}v16f`%THp_{Vq z9uPhUkTKMMHV^CkW#E{`>fR&Uz6#G@!d!+WkV0y&Cnmw(kK!W4%<@8KbG$R`D2-_0 zD!#NTxN(2lnw1CZgjGP_vz*;EaPnZqMC|bz|GvVA^8sJ3_eeXzUVJ<_`bzbdX{Yi*>J#7P@L-zda<2 z;jXb6wW@Xg%K(qD8(&N9v|RF4F6eIw-hkg=miMTBSmv@DQ%+~@MnGc#Xyy4{Md@g7 zC`OhWZI06(xRbyufKcYtiF9*Cb%@+H*3H(!);xzH2xTA|l7g2pwp9poct(AH)HHSRj*?@9&m6R{5*Q3-H;o(?+Q0oC{|F77OdXy9St zC0hqETn@l#_}}b18_`1+z=Z56ECMi50RmvpAA7*Nm_h(W``&DjOt zqYPnM_~~c;y&DwbE@VZFDV)AEmT_#`JPBMVzhaWlvCO3fX#6Euh|;sL=8X`8GUE+% z<0PC*3()vP2!PS~Lx$LB5V+ti7!NLXg z&*mH_cm-6ogTKr?`dnNh;B)< z6gF_gAM$r~C_cf5ycbSev6C^_%Z0(ql(!n0hM>FDXJ^%m! literal 81586 zcmeEv2S8I<+BTwCK*few0d*V{1VR$JbOBLH1VR8INC^-K1PGyoW>myp2N98G1L=r> zlz?Rrm8Q}=iqeY;p_l*M6hIwkXZHVQySuB&x%Zy(*5`T8x!KbwJ*^eoo47eRI96!y z-)F$V!Bxq@!MSqjV$hP7eo-F$vw&ovrN)t5wxx@M1HH{d!^Fec+YV2_aqL8>Ge7Nw z!yJetkDZ8pJK=CES66Xcyp_GXl`~1)1?K^pz;$P$E#3}~vt`}`hry9zFljNEj1f#` zCqh+H7W{=kiX)_8X3YDo>~Suv4t0qXJb_@f6Rs&G4g+27GLe+riBJQdbnq@@Z}6|T zthA*xayR&->gr0sVQ|(5@nBp{DTItTLK=GH;C>@rotYEzZNrp4n_?qov0%f|F#nSQFiCaqi3}FctVt zgvL&oD!3K;FG8IqTJXii3QU{v z5?IS)-Qxa8i3mO3J zb}R4`W((Anm4_7wF3cIhHA$ZKJK<{H&OpZMsQr3yGaogiHO8B4Lvck~YZ1s+6d2xW zzX8lVT-W!kwWPDNO{^g+j#04IZ5do$}#Wr(YD8FNs_Exbmg?29bmTmRi$-& zmHkg}j3R~t>nT47Ke+pAI$%NWP3Y_-Ny0AxWsqF;!=CWHFovTG13729P-xLr$*E+$Zp;aw8 z5)NbQX^mI&vW64Lw)=sVI0BCXn$tH_1>U7g)-%$!*EK|X>Ecx(E&FKi(;(~a18qKx zd%Sgx?14m0zyD4#g(MB0Ri)_RAqoN-^$b%&BY>kpv7VLS#iU@;NO8Cnv(alV zWlADtWyD#{4)Zdm6pWQy%>=M|SX(t?^si~?8)`w6ddAJjua6i7n z#uh-EYDCaG-UE`S)IUm-NJ+%^nncP-Oa7K7;nFOP%~vD*pQ=XWe>UFu9h~8)>ZJ?i zR%aWKkIY=nOl;My5g;!?5l&qdrmwE*1I0{6o^|qez+sGiOh7C_IeI&pVazDtUv^$* z<#$aPGiL(HdY>!V8ZJf9N9e(9oaNljjEIi9jy66ZQcBLY8A^IsnHUgkoV{JGF$9>t zqlTA00tUq;CjNlpl$Nox4Tx0$J25Z|nuQ%q-~>m||NOk`gENBRK@|1TSJ$?;ae>xg z3i6&kUR%q7V1=Cy*%<%V0-P<{?>-+7$T+gv~;~0 zx!e#*0XZLJ0DDQ$4%WoDM~d+oZV$4FgCodJNYL)317$0K8Fd{^NqUAzNiZLTKE?}V zEmMjPBWnR%^2g@{o>P^w-ggM}cZjTSWB`o=ve>-&I37aiFs?g+3}#CN`azmfG|2k< zY)HE5(6}}fFi#&nycfV^Xdm!-Zazj(7X9ITNLCmr0>D!~09$#3ei?Grb%b=xz**i< zyS_S-q6h2&w@(AugZ6J=Ev9ZEJZ@&FCIvkYFw}4L1>~y%hjgb4?1eGLZ_8=^ynwD4 zI1iemkFGir&a?w)E*d~DjBC(5XRm#SK$tjG3wVe#8d$3K{3oGaDWF$|hvJN&ULoYB z4IxXY*V$`7=#_;9AkKhd)D##jatQfTtB4?ZNO)jH{;=1}P1) ziKMmjp*d!0$Yz!Y{y^q|v9i>GITnhMbhXto_5ovnY;;H(FfAE7BQL|{(zMrK4^M<}`* zJ3?#+WDQ2d*WYJP0#O+OzB6V9WdZ$t4sehG;JVJb;2v!%*+3lzqNb@7vwy%Q)fri6 z{=HT}3g58b@3Spig3PSWnAg`?9m*5{mCR$?teD7{Hz0b~C5?C0l`uW|qb2SAY;VvSDhNbLjVg&#y|Ej?EoP?Z4L ziIM3Ty=mz|Rwf0F&R7=%<$QxA@DP&t7h!r*FiD6Xz>#oCNf~LR%(szV1}P;jhlI`k z`7Qc~5J$qE@g>w$kt=m%B*zg4Wnx!9^g#bm(AT!=1!`pxHjUlYXdm>vwK zsi_8WL*^AW(*x8Np$3Yr?mi}<*V!+o&=&sGP=@E%we#On-|tg$W_e+*$bcf^!Cua6g#jrGV*!O(P$46U zV3!ft!;y$&cN-k*(LYu+_#5K_d!K_Yzc;jpmAgI8pT!u#6=!#_BR?C(ULKQ{=&dzmu%BkTVMh6Yyc_J5&)wXe(0ZvVuL2m1}{p36mS zkNUq)c?cOe3kc22ckpjh?Z0+tK*&M9{lmEW=e+iZ0SFKQM!V5+}pq|Dc`P5UfZfybXhm&BLE_&GYv1 zzUFmyV1t!)JV_FwXJ4~9+1ZwPHm<1&gGsA{EB`eHEh!Bb|E@MLZx`{eOJ7Jy>2C&> zf+1M8!5;PB!k$^H_=EP$sz%saksN0E+Ye3n@2xiAyzw54B850yP8ygq^xc$ErvMn4 z`E{;N0j|xKDWDrsICnfaH}K8Dgzq>WQ#YVf;47?RkgL^ySTzGcEKuwEo>m~m-!w)fv(QM9_ZV*xMvPTNr5Ai^Fb6`iVdpf`ujUk)PEdgLP{cK z#O35zh;SCIK-F?NR`K#L#7qcqWEF;lgCnZUKYwHz{}!N$g+c$I=ghI=uQqMwnt#YR zexEcWfE)bRP-BEN>#Xst5z9!j%7}lZ1%EfHEcBM!e6I0tVX!REn`f|AoxSB=0CcGv3w~dQ<5) z&wGDe82a|){XCloC1kdRL$5debtmzW2x%#BK7$>n*m-=;)Bp-#ncuwJ4u?t4Zkx^D z@j%Lo|5FcSu>E45w!hQqyu>~ihyL%w(_G19?o0-R0+{>cP}2V|KcE4ZW)bi?Ta$)~ zv!l*m7}?<8*89NTHh{V;D`yYye)K`(bYg99dbm+#E~zaXT+&0>>imX|=85Xh zjq50?JM{v|}k7`=a6w)n3JCz1d?uz#Ck z&aowBz^P@X4F1B1!WbLQ#@utGOG$~#{2KxqC>{Wz!RFz2BH%v`RxaQN6=1e_0Mi+~ z4Z7#Qil!mt0OMkpE$7rcZ-ab3lz~Z#vrxlVNJd7Sg%{Zd`44?z8vgzMG?`>&4gE$9 zjKp{?`d^EEGr}IL6aa-t==+b4X#BM-9U%wR6Q$XR7WUoQb~#z(Ec5=#68<%LI;81u z{G8b^&#C{n_xiuR*Z;jV$9$!G_658Dy)?&sY5G6=r8y)LRKj53=j(p((wv-(l(?+S zY&Q6}+IxkwVCg)F_g(1!KPl1vkMgh)*KfhSKk_=skJ-5t0vrkZwyq{8BLl3GsZ92e ze?bw2F*fX5$^+iJ0|5D(jorVylJXBch7A9HN7b5aX9xC{;4nMzqmdBramRbIfHFAP z2!5jyW)1z0ofY(pO8<3C2#JJ)9Vu22VKX5q*uNzHWth=F4yt?E}di96}u6x4(?MvAs=8Zt{JsoBq7{khMhgtz&0y)#g5M+!Osg z?#+fYP1VO=o+qa*IKwFo^Gy47{kl}q4Y`NRQ=gjM*4({)SG4A8g$0?MS_8O z=Ql_`&G8z*dTc1QxqV*x!R?Dm^)57e^*!vB@@+>sIF|}Rf2~^$raJufRCg_;w@eRb z4Zl4oQMb|lrd7CeW*EJrKur9r-n@Du4Trp=llla9;c!=-@2)yctLwjTv1Gk6k7q*Pn?Uo z-zCYeWe=pnL4B|Y^gGB^;MJ#TIoR>X)|J!IsiTo>g(7#OK27;lLTD>E-pud6gWz8r^~`4z%a=BpW&6-5Dq;VmDM@8%Ca z*req5D8l>w>EX%2^25c~#B_OAy5w~IJkg&!&|7J!Po_MVNc(k7b%qnB$fpX85zAJ- zs671$*sxF8mTQMy-3%}2Wo;4O;bx|{u9U93k z_YH-^rJSx!jTFpe;6g2`?aFTAk1yfP6pr$H`%piA2-6ceSgzdS+3eHN*g;dV2rwH! zV=QnL_jJ>%lMX9nZnC+5_nLc|M5X!^y~Z+&NBq&_x?p1d*mGk`e{zFU3XRbEm|8X< zH>b3xK#jp!?{(&dj#q0wanh%T8_IpGI;l$p94rII?luAE8va})s6flQDA&Hhz9f}8 z{>yH|Ugepwi->AUPm+BomV$TDTex_6YF0C)7|2CQ_(-$w0Id%ggQps4Djr37wnE0^ zY2#*>M^BU{dJ(?kU9rxg7M^a;U*{pCurx|tu|xr3iJ)KVplML)lN~L4*Xa!8PxM#c z*5chP=Y9uK27IVvx za{3FueLrPaOt#bBQdNo8%7gndRt7!q7Myvl&db*%OnXcQVkZmixfw9trN=Ro5;#@7 zESKJ@CgDTJ9xx+_O{-Wunfy7N@V>WrA@APTo#Q}?_nb4TjPFJEU}5=V?coXwas`e! zSmY?X#asu-=cFH z5jQzZ&>y+&$mc-#yRi4m{#ZxTCzG#4Q_R;W11XPBw+YU;9y90q(43P|4eX|6Sty@L zPrCfNc;Ap#{k@-07%C>I^DZ}P3LI(j3g1JHyJex8DKdpl@~_9oer%6>jNLXd(h@je z^nhP}xXxa%f;?nUv(>Y9n^!$BnSn*6WHLEhh4$KPXj@=(vNAEPaD7>GJUp=LZfMzg z-!i!l*^mzpUaK!mvZxxRpkhK_QHm4>^4j)#d>(i1)y2^(BhG$PShu`W_UEi)NSKWQVDxLap4Z;z+`bz|Q<@ z)#ao7aT5!z1`Og=jOnQ&S8B{jr7t+?($4j=3&s%Td(&TtpjD@VTgxp-eM&;hCu~0) zQsQ`jP5TS}xP(_0RsBzfg}EQ2S0{T)aF0&~i3dukInLq?Yt zjCUv83+ANkdbgGP6yG{gLQT%#)^2L@8Lyys&Ciw(>_xi}vp-%t&q-HvdSic#niF6a z4RW9!{gIm604kS%>cmlzx3u7;)7f3rV*=|sF zEM^ju9K3x~Pp!>Ga{S2g8Y5huNDW^mX>Q3U)(W9`JAO4~n-|D&zlecY9lzID>e0-n zV`g+N%*54QB9&F)zUQT?cgYRZV0}yRr1#(!6XTEW*KeCdC%^K_u=%_)=&7UAmqt># zRQKBCfu1MF;uFzT$@%Z)*Tn@+^kwOZuAhksUcIR;HY&i;=yWs9*DLn!nHmM9mPtNG z(GwU!&!Ew1b%`TrW%t0KoGkq(8J(mjDi(dtm4g-&$-&Fy^E@TG!vagCYCed^u18?Z z-GT-y7FhbzL)PB&4OVmY*9+#4>)Cc(KzfvySRkJFNzIUVofz+FeS%6r7E?G|Y~za52{Se;>Vs4Bzk!aDiP zmH^+wZiRd#YED6x?|lt^p315KjhIJX-qbAq)`_C&_h%(;iulm>pe4#HW6DK77?*p^ z#Hd(wbnZ-=-k}qnEO+19T=At~!00=TYq7(~2nDaQ48PBu^j5Q>Ct$KEUGGkbJVVn{ z_!B98*iD-@xl0^H7kFD(Du+d%8P=6)LXKD;O0sk|12%zOmEgH|+NLt@klxNbthnzR z4SumTaS2ry<16Udei8?&Ow3XO;78}6pU_Q!CS--n)aH<0G+}`R3iC0Q5;DOn5m&_n z2RX9n7Bz=K|UYtG>-B0^qq}YMpCb;+5M0v~e zIVZdeg8aeFZj0vuKV6V}$r&T4xa0%4trfBQULw_e8)iC`XWa5VTl`1rVuA&7_K%Kt z-o7Z`r)ri-sJo*wbz-faE0#09mHhbVf^70GohHA*(uhwc5??A;lcSTXWwt7KdT_Qa zTl+JTqS_HPJtSQ8qGxx?*uK?qPUZtvC+nZb6`t{mYkBmvt9?=Tri19=`kLDph=L_+aWJ*CXkxGMx!Z_4t_ z<~smZxz=40-GxELhw2HqK3*_9HPWKcC$mo6H>7Zr314Ttxl2`i$e=&1(SY`xKEa6I zLlOm(SHjh=Uz3m@OD|UAi9i8krsyz9QSI?I}Bj%7v5`Rp*<-}%U-n)nRjmiOei1Y5g zaXpA5&c$c#4 zR!fiSx%S)qr@KEUP)4K2dZ?!__)&A}dpgs*JCeHtn=tX_HPfOcn2#WDq+o|>rAye> zPfY|V%%0p~Dl=;-DjztTa>(g#Zfhx6Ws8JVm1#({7`>o??0Yx`OWRbcs_Gb}>i@W7VD)g1f$tjLrQ`jU+qn%ADmdX`8+O!=PR4i%? z9FnnZ+@2YF=pNBtObU^!mm!tU8T{Rf$<6KYMqEM@0=JJAoew6U7Q?PC_bCa?`R)YQPjrZcgQi+bd*JLX;=ZD{Xy1Z;voR((s<8PYhzT(#iq4X*8`eM=2${n|HM}Bw%5{waxmoep;)hL^Mva+^{EpUj-Z{V;W-f#nqQSmT5 zk?WhmXTJ);7kte$Awlf@j&$F%63^+}4gl9+?`h%4RN8QT!o8ZOALa!33W!vq{A~JM z3n&*X1Jl!0Y1=U;mDAuh{l;ssZSxlW7G&Vad_|lF`!<#JAm*h%>Pg%lALiiv2*eiJQCK(Eved|;HE?Dk%EGe_ z$B2*+Nm!KDlav(+@wMs%Oo};d0uYfpz!M1&J;|uSHUOGwpOEDgJtoN040|B8h_Tj4Tf=4q;eM{A30qE*651gWVmMf0b_SU64N06)24E5v+ z^<>|j&=dqIK6!<}-rD|xnSgL5{~SaXNaK}y@?AeEOn!Ps>c9eC=~-=RU)TBOcAtLW zxZ!O{&w9M@W)M%N0HZ9cX$hS1KMeX$3Y?i9E>fO;Gd|R1lalx4%;3?Ovj3w!E;;PeqF71H0iM)s8(eHW>;^huZRP=6&X~{P3240zYcq{ES+zW zuU4(odNn$eg0`20wUtZ(V)(GZCAU;*delaEpYip?Hc%UJtG-Jg>U{GoU?jH%$i&|+ zt0f?pHdvLXbkc z&Orqhg$0@Ic{9@!4FI`z?_K`dKGJ`fvMK!_K&#i%BLl&jwWzjVoRjr#DiBfGeOu$ZW1x%>b~sn$1z$;gw|PwB zN(mKXh0B3cJ(ksX4~905#jnDA@&yxUxE~vNV3hQqYh^Bmz}Y2i>?jXucz!?RUp~g5!VXlNUWY^WmyKp^y)=M-){< zS!b7UYX(@|L-4=7GMNG*%LSDh@0+xMazIi{%#-_On9<||9w}RkK~yJP)s;^38Elv0 zuB2Bi;BKcMwFWS%{JbwzW8qa8GF%X!TJt8&M$4YKu9J6*EX=EaXQ;V#N2G7^AWEHA zIj=2zdh`rV zBKkOpKhN%6lLD0qtJ~Z7WJQgPMK=UheKd;m6#$;?8UJZ2IKCNu8LAz~)nJ11IR_N_ zA3ehtzgJ!<+se_AcchqqMlSvVMkBjjq!_Bvjh*J$I(~lv`bE!^qasx_^+4mDIq`#0 zpw`e>Q?JV>)C0&p(?)O0l4 z;zG{EXVEyucmqd|D*_;RzN`+^xOCdqDO6foB%wS`(ClJ9gGxcjK>Vj+K}Y(nY6-{B zx2h30!sDyZWI+P)mWVt0s;?OS2H+9?=f}$@c+pQG+*-;-FB0%gYy!ocd)=R)V(0lX z^rvKwX2H0GmT?V!iw}$Xy2qvgaF7~5S5TD8N$v|5nK>Rz$yFY%wJF;`c@#~nN&%cI z6$1C#BRqn093&26B_H=}T*kI|P>X!QweAX33eYQFO<#=>U6rxn(7`omcmmN2@Pvs~ z8LK}FI;P#q+|5no*&2V+cykzJ$a?@%IB0|p>Qm0+CZKTxpdzR@!OvAWF6tfUe@3JN zeLtBacQ=)ybP*6O($JMR5RuJnru1l5ynePk!|^jGIjEVtiOy+6TW37=uIh>wtrq<* zpov@~MZw2&lIi-PPM=V?e31_l`J>jcYSY;rk%)|!Z}eB}`Y?}K#wCOGkf*Zc=VfQy zvRyCG(FvD~{d1>+pOVo=!OJS?*18$KVW0|HAxx`1R3^o9zKyFp=bp&xsbEY@GI#G* zuf{j{!CTjM6^c{_FW+eGKR&d3Q(QvE+3_2`efYdHQ!r|dOspSYH-*|6g29IIRMM|< zI#%3@woG!E33}VNggc@}VZikD%Z550ql7=M|MWIQc+| zPT8eEv`}2Untzo4Fdpf~^##>6nmYhrRd(Dxt2MoZt=W44i0aai^7~WVdfp z=zCbv3o>wq`bxPwZ?Y4TbK*nJHoesa!E4eyUY}!@j^+H?G-;K=lKFq>+CfFsQtA zlz-R6aXfAEi$vhq*}*l3g5F_a7Kz&rEB?x>ID~3&&T8rnvyXH$d)|o(8Uhn^=1!-t zDZyPceSUut=G4~q8+VyWXk$@sBqb=p+QJ!SbUCT5Okv<*e^ai47-8LY-(Z1F1W<+3 z6Wu_2Y)Bfcj^Qw`YHf~*{G4;GJ{fse%|b%Es@QL?@ELgw^$ z2i01Iv6RYyoBH-;L>#c=qH()GmDmRNVzG$k2H^;gD{J>>In|Wm1+SzOo>m+6A8D!) z2%K~iPDFEM*I$YwJ{nK8^nMpqT@V2Ot3PGXgX1;A^ue)9Czk^`G{N5RtyXk+6LiEsI;{9MFGh8nUw|y<@j2=OF_LR zSmxGBUtKy+xtB*zbt&HW7Rs#Z!={0=68WhYwkpU=V9>7p%0q9_bZyM*Y^t|4Q-DNuX;c!JKImjWCjLXwwX+-DiRNVuewk zl2^ZZ>{JQZju=RM2iUwcO~t5LzS+BNMJ)YX0QynNDy-G`Ca1)Ad-uNP!O&AxlboL} z>c(!~h;AxAJFnWa5m^1p+9h^#$r9p99~M6SEe*|@j)#%n7pzZJXYdwWjz0}S?UMzqGb@p zs67eW$~FM@qwKM%wty)MlPs_E&8}fCp)x+HJcX8&xlLyY+pE5&hpSYC!Z>3V(uD;A z8&8_UWy2DV{CGa6*PB=s^7Xyb64V~ra!^;?BYL`ZA+JdkqFh8upk;Pp?AgtZcw{v- z#4IZlgAGi&hXWQ&nYg|eny`u-Ct3Mn+OmTIhsv~M`DgEEFH;0?SM0X^Cz;#0LMy3h z>7ME0eUaze49w@W%)Xlwiim5N!mK>?c(6&(>$oZ5GdTjqi zD8dY131P6%JLauZydz{|S<>fhqx-RbDW(Eni&X^<*xc1@i4tzcRH>SrSaQyYMto(q z>bGk?WeJ#j04eztQww#BJ5|y51>X$g!ZSwm9u&P__?_NgBLVQcm;HG+Q{UEWJBKZN zCmQ$8lC$L%W&KI&&(R}P$>6e*_`GkZb# zP|1t0>qZ$;8doNjcI!)3q-^<4tVdN=FW@A*@Iq3h4lQd`dXhNu;!{sI+Fm-*cXUv0 z-i|TL1mTctzI3*K1Nu^V#r4!U)^|Cuh{=;je7^17Nb{%)4SwO=F-S9))=}LPDri22 zcO!qL2NdVP&an3O4J)UdHVn@EY)w8RH{Vp0W*B?NS0A*5xUG760bM1K30To z)l{0381>>K9C9lmC(g0>3dM!-mFb=`saW^cO*U@6#aJIk1NWv0sAgbKwK@s&;!`A3FIn*1CeaM zZ=hf5nZAlWl+b4|)ajP(KQlrD3MCW|IzDD}pEL+*1(C<3`>;X`l@uH_jvA#|*2WZBgAwJugQsm&w5Ch?}VWOxP zggt66_b>5!m<`P_=j&>B2b~{!`=-kha-7jEKoq_g)7-%#b5zp0hgNQtuLXwzHkX39 z5Kr7VHwOa=Fo$t5J1TPy+~`=*{R5`<(yoH(1~Iu$zbu$|6f?1P?U&#I;3`9lt-<2yOG-w`^vaDJ;o_1GqKw{{D3XoT}Ow|ja4EIYKgRq0<2Vsc+j;MK!8`zDL;jRo` zvH99W4u7KIT`WDxX3nDGLEtu|(e|tay4-*NXo0+<<)!9Im8KcFK&ZO|#GkGOad2w$ zpR`8g82?;HeZci8&WVF)c= ziNIRcY(vGVDXzY1!%9Ywd4#PJLY4n2oxUG>PJLozEpKaJr#>F;R66st#1PcW*F7vc+|27r403dC65qZi$NneQL;UTn_nD zCitA;b+l*pd=2DCyo~kV!GP3B^DTY_Bvr*}Q*=RUO3JnMv1ZR6zBvAI^Y}EAE$jh~ zsw9G0r@50Pp=D4_z@ltEwp&9Byu0Y0ev}K?-XfpusY|yPH<4Hu2kaHtU>Au_r$eQr z1G+(ObHZBX0MJI+3P!}6zp6@}(Px9eDP*7I1fX4$Z(~xhnZxx?4S>tOTh!HDa}t;w zW%GJwqGts2`Q;mG9GKJX^>%)c-r);U4m9x;KQlkoJp?;&^Ee~gL4Up80tD6G`Pr1Q z3|kO0g?$6BZv|ISYL6}NV!03U^%%v58oZwXOJhA%$|r;(CJRL|VAp<#pu3Np41;3G zwneY*8^p>hF4`44d-qc0VPI8tCzdlFzhnZ&`_*N|TF7voa-U$_p7?VIBQG$XK>{Vv zvX3!>pNdd6kn+o>&2}fj*eBL4HN2}wrtH_zW0)NyMma$GOkcJUvO^W2G$_I~ZTcCy z{g)l6!~+rCL+(Gx%>leAD24 zkcjX_v#ubd2WBptk-Z)=0hK(^&1VWp3K~?6>WA(&iq%?L_Igf8K0x}}k_;uk6$Rm| znTErGuq4O4*S=r+$P@O>Dpla#gnTX?<{IX0Cd8dQS^zDZG{WKul z?yT!v+mEUYFEYBDT#)0@b%j=#Zq1qsF#UKa&-(LRXFmO-%@k7*5X#>tr`tgS69vLE zt;1KJ2D7#+y@9)}b>6+Y8D@2?t9(n>DhF^9FT<&&*;J>aETZqIOVislnDHzexT6Am zlq>wj8ip*mA?I}h`rzhD-Yj3a?CrAGhL5tjuH89m5tB3hcK-RRuL^&wGQh$rpPmC{ zU`g&c?x`07iq?7CLl4|~tSuZx7@tS{qUFJ4tK2%`83J+x<1vr^2`yfLzBAI(ATtnh zb6BXa-n1hpXM^39#Dj5WEedaqXh~5@*QH4Jq>#vUjf3xYXc;6$CN^BIV@p{RkR!x{ zH+vui_~H(j%+Fa78apmYQ+MQgS^i`~H#=%eGw^w)7vbKZ=>6hSC4CbnH91NLmD*1) z9$BC0dlaSU9GI0Zz|un;7cfq<+MVr;U@#BO?>~1`By|d1dt-x`@_HBj`i10~^Kq^g zyqHPaAYc5&`ziV*Q?K^1V-a-^Sf9OBsOb)14|AIkLVTQ0BD=Wt(LoV~)#5?Y$b;0J zKf~s99?89%QkL>R~|Dz|M@c zK!}jcmfA17P;+uF?1f8wd^Ub ziUP9st2PJq(Fc1{n}yQvr)zUjE03jxG+tK_U zY+9m9ne1-nvFA(X=czuJC1<3d(lu)e#&8%+p7nS-*&8~FTG?F}+3@X8hW{x7>6 z&QE7bsamF3E4HXS5g|t$l%QYvFn7*semp&~YL|?V#K`0-!xtZRFX|3!^jv>lC5dOK zr=iB@^Bpgpn|tM|cYf@7)2FM_x8F!oP~%iT`dJTEE#{J(@hLlOiEnFkbgoH8_6SO7 z^uZyE<^#xVkVyX$y`FH#$@28jpwks9WMF@rOPdHaM zitjh8#@kdoQ|a6XrLa$Oqi$FX-7%e7moAYnwr zzFvGJ1XpToQKq9hI5}n)?BeXHKk(k`=@jw$R{0V|OHgMtO|NSSFP(amsKJxouu`Un zMpJmcb!`bn%zIgLa!=U#D3?r}Z~DuqFn_rkMXi|eQ#<&v>07QgV5Jp?UA)BQuQ_yW z>b~@hCs68e0F};TSQ-#`T%r8#;jpBFGj(^$O9Dn;CRW5JTfmOi$S&$G99WVM@Z{-r zpO$pH4eRrs>^fAiJOg#nQ^Lb@{8DhQM&!fumB%@^#v{vX@_#NlekEEzCd#-r)iAd4 z%d*O=p29FemZR^#4Z_DJuMnwiM~{l4T%xBdeeHakS_6jrv39}EZPQq*{^XiRd>vU{ zG75f&)3cPN8~joyrlw?MHv6AD9Ft#M;bb3xkX}@xP(wF{; z)G(1JaN{-UkR2QoG` z^T^Vg+fFw{!-b9G?&@A&vOXYI&DS7l2@D5!o!!m3vZH}e~wW{PoNuG*xbnttJ8fv4y*a-13^DWtI_YUX-fkbX`<;P5(`(du_x-Q!aU z_TkRy_a^8Afk>x@@+ovxt)*r4s9#`oz{`S?GXGzvrqzpbRP((&w%86oA*2gLl%5>f z<%b}+rzsFi$GWbrFFRa=Da<=Y8UPjo{!cEYA9Oq&uuyv5n;6`vY*|;@n_^LnI8+>l z(9Df0h!3yBTkv0)syXDsHMvRjy2XR2x`P!Z0ls%9{3BuqX>D-|r6k#-_IHQp5lrs)h*BJHwfu|a!q_JzH(V*LUw}rW){kO zunU03LJRxSrM4Q;jVe&2oM^MN3(s=e6Z@)5xLL|~z!2eY zoOE!L64LOZ`&Rue1*yW>;1KQh$qCU-7t>2yO0ZGy0{RLQiq3Sc$9m1D`~GACz8h> z4NQ2A=nMA}Jg2tx4?Mf!QShv{4AWG;*XxFpdFP`pjr6vDw}ONNqvVD?dkv==tBz?F z^=`9szJ}k+O{G|2@&Wxg&38%x#k-hx=w!o_qbA{(?n>`8D-ghXD}H%46eoecs}~(v zTM!bqft9!K7y;CGcXKgRb66&3dE(x%cz2KD=Yq3qx^ZESTosOP>0P9f;rwkgKFz{| z;4rQ23=E}Bn?R-83xkj<{h}`|5**Dunk1B48j{H8d^I$O*=B5?k=(|2rm)vFPh3TEAgha4VE@q zuCOHZ4bWv8Qk~lnODo5;7Jw>3v`QnDk}B{2{sY%c_&Tb^Co@y-3dOQk^&o>j@&TIn zFDi=1HivAR&8^!(RBi+nyGvN=pnz0v=WZ|m@|(7q6N`CjavC!F&#IFBlxhhdahnz5 zv~r%-hQ@|XIo&!umDJX&SR&rk;-A*xpOR~7$g_ra!lZW!W!d*J9p0 zYIfMdak%{$e+-56l0Qx`Ah)iGN2HRzrmU~pWxUyc@VM!eZC1pqMv$Et-K4bT z17&m}IpeXM)5V~g%~Qm5m#myXB{%-`o|WR|zZP6`i@nkJ0Q)Xu*W^s`F>ZS6-UHBC zp*0Xgyre>vT}YQrs5o9DQq}(x^{`>u?k?Qjsqx{`^O)WzoK#9-?Z%~S9us#81XGO- z8v(~!v)h$S3mbRqdGxW|uBf+jIsjzczVTfD95R@Te_xMaqX;;w&2wFBaky?oU#8ic z;=KyXVH2(w>eh&r2INuRWlv}B8RH~J+`qQRvGi73gJ4O0WLufGVtv7*$|*{|ivNoW zyD0(Bg20A%c3OR@pK`b-t8UqSE<8gllqk5-_3>VJY5zcIKQZCGq8|tXj!On#Sgya| z55PgFn8Q|5pQ@ekfLY|ryZX5jwpB6w7rVLcG`qDXCDYFw3_Gt_<$pRJdoO-R?T+al zpML%2qc!jO!C9^Vhu-gKtcKxv(ptf=@_v|AjWQ(~Y%{?@U&W-^HT3 zm1RbSfGo{wotX$8pxk+9-yHTtPq$Arb_O_~_3S^W7V3=itlyP>7>k@3!;JW1qXS+o zv{Nq%OL~x4#}i1lY`ouAK`hD4Eg`gH?3TFThabPOYnU$W&EWDcry1|ir`c!Dl-kWq z)J@$i&^#IoSv?98DaSIkNJ>feN6pQ`4`}5$fdrY|u`)Im`7Pck#!2;Jp#--X@Evm7o~d zvpDODWiVDLK2z$8;m(N);V|di>RSo(bJ0y|j`F$l54aAdHXU5=8@q(~=!j^jwZw6{ z^5|0I^tExq!$cgTi~?cv-4HDAdj4R~qE#kB(U&GFmy|??cW2tyC0%V8^sDtwSJi(c z><@cQh>-3dsB--9%Dyx*vU72le0@^uu;q*sCY^5VR&dYp)7eO5uFbK!*p?iLXT2i| z>FSx%hA6*j8yDF|C*Q1sNA)?oMvXfsYTaB!H=$oA-0+`RX%{MZBojRm)L^^|RkLx% zuei56%`TT-T3|ztCU{+D~(~kzh)yY0Rs?Tl?G`Uiy&`oDP?Z_kxZtn!19KUX+ z^u3Ei@)=jfqn$LG=?rasX4vkUeKn}Sana|G&;z7E>I zI%$twNGdN9oHaLa=bUAn;ULNpD$Sv=7bm$OFuH$0)$(95*bcedWSzWJC{;x$`I3Uk zHpP4S`A3Q`x4T>@z~t87=rpTR!uovV^ZoEHxDR^8jF>-NU!Uph)G&~GoUHIk<*@}y@(`6^g+fWx>*KXLvj?%jf0om4p=|R;#IJDm!mSh(L zLOrzS;V^Q0pw7NQombK5%Xa%n^0lp`-n5)SY&-Z21aJ;&Mq6Lm>%BdHAULG_>hwB)cqy~_F3hnK_9+b`qIac^!rx9Lis zCa8UVPIpxp5UlOP<%~^06nO!KU55GvY!_hjO>6ag3t9rC@o#_X7(yGH7ET9L=w`mW z7v8Qk-MQmpZJ7Pd%M*i7mIxB~v3_o~?~0W!s?Z2kdxa5lLCiL6{a7x9f;%yhh@sPp(J+x zIx>qOJ^*zK6ZNmJhHMVhpO;pO?tCe`RA?2%R*ZbO89*+WIo1~IStv4x9k-)U`0dr>qV<(sVNIx|&P15Uv@wM7QzSH9MrRs!$c zc8v>QqBpCmOWX0(E1vHLuJGhAQ0qw8CDLVxGTB*as4Mc@NqpGot8Vh@c-ct>bGIrsj>w(!^R8GKdEX8T&$KGz!=?9h!mNq;pEYj}D2|V|LFdr z-wdcgOIv6z2sy>PahOI?y>avycxN_QVPKEX<-s!LmJ6NDv=2U|a#R(X9K~-v+mqrh z0CkWXvqczc+5#r%wu`g^M1@q)9;76a0;B(sbMgWwD`IP)v}I(<}V8vs#*j2Y!yI*%2yoaq{Vhmf&P{>^OLKNyFPWs7ZYkNU~)SYLO zp(U}eKI5z{wPwXu$MJ(&pg`+9`r`6s^VsUe^d;R(JbLVo2QPn_d&2t31gO2$Cz__; zEbkiJ6g+okVxIH>mj6miAUI)`Ccvr{K%vkoqNn=?tnIDf=Ox|TeSFQN>um!;?*LF< zJ*yOFP+qKgt|WPoG3k5Yn~cVJP)bq>;d-ywom|8|3&35OQSvC6FY#oQtdDz0$W^zo zROrO1uuZ{rF1AGqfo=N!g^Z4dfThQJ5luI8?p}XN^uzjhmz#1AtE(Ts?eq4futK1Q z+oFZ^T?y}QUk_Yovsm{`hSToqO+OQM2^MbJFuR@q;ug^8danp6Xp_kl2)F!|Ub@~Q zgPl;m7`}Twgkv~(WayC0U_)`1NmYJ}cDzr6T!Zx#&uy?@Zo*j1knPDqQz`<+k zFGyN0T6HRI#o5&3v{LlWt!P2|o7hhel|s0@Jjv)Tu_a!XCE0Z9pvyI=6${2oO+VK4XA!v1AoU#Kx;&U$x& zb0suCgc73?kAh1084nCgz>@tq-4=J}Bo@$5sWt6NsGQ>aoa6b+f&c?ze6;HQVVNhd zrjLvQI#(HChh^#Rk}>eqhy8nc80S`DJ5U|sAjE812Pomi+ygYrD5Y%v7)Re*ej6R% zW-4#E5Pbjb$ddN4GGUZ{y*OgF7LyBBR_}G44(%P8g7XFCU;5KM7daXW^{ZH*p77gh zZggL=(9gmWU4LAH_Ryi>>W!w?Tx)qVecpr~q+jN(@QPHSRSztmJqw=kGsqiG3eWu* zel_>L_WpAabN8Dny-k=}v;0g@O1D$S(L;{}s?Hv2YqrgHOmZAtv-d*+eZBmUY0#(f zD&J0+--j0(dcvrSzL;$GNgi8}P855*IC`K&`gRX++V&=#^U^y|=|t0Xx4@#3nhX1= zDebEYS1&&|RfBreAJkolt=?FeCn9;TTH2|-L^H`b&+XapeO}{-{PA`v&lg@lut9QG z(WnGSB{`%LMg?K+S0<>xE*m{w2~e`?BFpPt=<}i`7q{0Me@b)`DJg%tO&uM^pZ<$> zYPnwwf9T@C2STGy-|o5oKofEWMzC`Ms(Mt&T!o4s7~-=jX(xzT*N+xN`NRliSo8BN zH;U6Z&7Y`+PJ;Gu&I>5YXFSQ7w8g|19?Tzx75+c=-oh&ib&DI85u_v)kZvgj5ov*; zQ@T@-P`U=BLrSCt0SS@LLApZ_P>@i%k!I*_c%R{@=id9i|G>A_w-$@T8Su%y_p|$F zs84p52Z8M8Ui3WuE3BV>yyhq1di{#J-2tih*HsnX^t+86;6`9J(1oX&?=ifqTf)3N z{L8Le^))|BpH}r$U*Al*!uClp3EBANIWy~WQtjRDEQ8a7n#Qf;#l>!e)qU3eSHo-| zANTS_kjZBcwc*c8e`F>KDlyPum*7{s`ZsPCW#adgJhFPc@nyM=RYy#@9_x1{ralp& z7j^BPe@*}!Y+7f;YzP@zG1Wy~iP5s`Cawr1i$q`{_QpF?cC>I{??C(YFxa&~Y z<#F84nv@^fq!{{BWZ(eUw}Y`8b~R!?kk^KkuJBNh?Lnwa9!2l5_cfd#Ten7sv(p)0(Ajo*IjLfP)%vv^SK8O47TSU*Ctyh!&1?p0CQglm%`nx7b> z8l_?GcWiq8s*kM5C6Y=@U40;v57xt z%U|?Tv6P)!9@EvxB%rI+D0d;LvEJi5GK}~iJx~0;V9ggu;f_BOEP0bZ^QDw9cUAa~ zkY(&K+fJKIK|I!!!cCA4@y{RuAZCb%+4kb<|F~Jfnli{c$_b#&x4vq{6>hREvmYVnXUW!35ZEF$%p8g!%9+oYUe;wEx?ugODw%_*~w;v|>o4 zo^a&Ch3|!~PhRStJ4zl^w*6ljjPV6%l2lFnT34~x5TFPPDcZon`UtRYTb>g9Vk8wX zhLoSm{zszZzp*@U45XlZt+&s-OdYk9Htnf_&C>xjy>%$x&-*hK2P%^8@AJ3%8>|YE znITBB{8uI*7hn$FIy9hWo1hf;R_?AA>aZBTICz&mbtE7#JZNUOUHG@Hi40PG@aGNA zyNaQ!Ljg@dLT>&InEu@jSj>{}KlEP({zdI!{NTS)_kaHCN?{Be(Z9+vOv3_Kr~zGy z`F*8V_lo?Mi9Cpu)6V>>Wj{tfoxl|TM_ybB4dl1nC@@DL4e5<5De@5vg*kaA`|sWU zUKR8|vs$kCIRe$P>&NV0De-qSW;$dZ%GI8tkP^vxlcV6@9DskOrjY`_xKmPd`%0(~ zAuSHy9>zcF?C(Rym&pO^5;%<0xZ3+mu&xR0|J@*sGA$SiOZ4H*tD(eze7aT3sqh~q zvsa_}jUluA8-$+yQ)#>aG?4g=wwnKYGznj5%J`KEL^BB{T$wV`{F`+2=ODtsFE~w{ zSgr__6&X22Ns<4np#2^*3Yml8yuns*^>A*1E!L3y@4-XU#K2HQ{-$@Xh6(^2z~uZa z;VNz64`(4Ktw0vSczCpjU7b)TP*OOg-#Gp6aY567lTM)OD#Qz|MGESMroR;XXKKGY z;1|!nEUI2DQv;~m#Snq`e-jpd-%kp1?-N>@S41!aWTF$t@7@2qE)XdO)(h&l2UkO3 zBK;1_?GNt%FL_xi0V+Q@2qV49;)$jI)N>6ufU$f`#%RiLi@Hdo|L={^WPs^OCttn` z2eX-i+({uWy>7Ap-ERm;juf&qZokTH`F|CkT&;@*S(p05y!7_f5hH`%6U4u-=r5Q2 z|3vhcd;dQ|M1UV6h?oAC=l&~)*BMw|IUYVb$ONf>ZyNl>3D~S7q&w@1CGu&&P-xEV zum7d%tDm3(NCv7YF1(Vj%|LoA8UByh1bQ$Q;0!H{7~`v<2w9b{`<(zg%6czXCELiN zJNX3;4i09UsqO++IjA-{4)L}bZft;UOpM|#4;4)q^Ih4f{~kRJEuc=!QH<;>;fWs& z^}i0|kZH1A?h7IA{Um!^xf-r);N#}!LAdlS`42d37 z`R~6~6y~qPDEv1I_Dbq=0s%!f{vaEfzDJ{+4Q+wIG_pWW2a}y130fgA>Krw?bn*=~ zlgKZx2O$-jnjhbUCar$;1I@92i0LJ>GLyQ}#sw$We{p;>c!zt=uMRxQ)(;f~pw%PS zeq==Ru8Zj72Cn3f9Y(x<%apUxsGb1#fLh@kd>i(9kliQ@voilD;r!2SLC1i2>95Qv zyedjaD}nk$_Cdyt-R(?P2})r{2Cs51!rW6kh5c^4gB~rV{YM&$yODJNwHBIiaG)`H*= z#zKK!{8W3Q#>pb*VZ&JPu)jo;fKPXFVpWw##Zuzlsz<}d;H9BQLF+Vj)5zIEqsK73 zM(rpsFmsb<_dnl1zd}Hm7U#H6&%sWiV`zluU)-20HroQlgA}M5J;BYz8 zgKYc%JUV>M_TOA$4CuO5&f&_`f!biH^DA!-R~6?$Mg{LGrc%^phdxEHVd zi};2#qJHiZ8Xd7NZAwy_SLi*!fDk__|g z3(q+HA-jLLUl+;!wPl4@dPFl(u1Ok|^&G)cm&~hSV#!#Jx|^EX7QYU#)fPBNghu*a z-PmNl{qB@n3M6r0yW(5@=X2_(3smFcHiKt9S2O%V%fAC+?_cH+A5u9KB1;8?r}xW6 z4Y}(f^DgV-Bt?t3O&_;YS2izGivyn|gkE~$k?*VrPe((Aro0v{|9g?h{LD|P$^R4w zBtb}T4h))qnXY@>`M|(<8~Aj1YI$4KZHE`T=Nlh$YdgRzV)HNX1QrTZ@q`mXR#6m+ zHqdtety)J)w|tO6ZioYeUr9s!572f%^2~ay%QhQQsI8}kdl$F|p&SP-D!qJ1x3E8> zQv%m<1Nre)na*GNiH}S~+-uiILDFm5dk87^z$+BjSdE^~R+N23NjOvwGvC)yu2#I# zSjrkJkIh#Fwm0mw`cL@yA6ebU0QPpbWSjQt)qYR#RXL5y0_F}}A9)IRQ-`1B_EqtS zLXiR52J?%&7K#6)KAKjf_Aur74j6qHreZYWe(p_;UMUw-Qv_znA)X;tt#-09;*LC; zjq;500J%07-e zNzroagD<)!j!43)M+Jsq5%cbLVeUWGKWKCPTrhkPYn{3MVnsH0v2P|T0e&My6m zr`hUR_s%^X+ghSB1JFNnXC32)jMq1=77UrK#iPmA4cS>et1G;Xd5o1|STcArl|=6G zbH0ndCgO&HdyBeWSx0!ywn(l>hqvXhK+I~<&>@wc@jyY(h>`2~kT9jAHp6gUmT1@L zDvm%(qTX1JIBrF8oz2o2e|50R6i0<=mp(ymrmu*)*2u=W4sFAshuD!^DA!*FIZ7Ci z$=*5(n;6Xxh+zT(uf3s|<;d{p+^uGs$z4=|eH)^KInagaoK*M1%BAVYJKKc!U!e`i zFmg9Pg`_0`I6SvV>=AulHIL|@95I7feu-gp0-O7JkRF0KZbV-IZVPy z#tF+N@_l>)VKsB=h_iQ2jb(8`O;5Xo_TN>!KS|_Ti(G|UPH)sCdb!Oj9&~kfX&_Y5 zI&@5iDDN+V7p*27dV=O9Rj;sV@C&XPdlXLSBh%!sR+n1~xNfk@7n4R= z4`TQL-mKqrnBUoOt)Wu0)w+x(stwR2&%Hp%FUtv~t}w4&O_5Vut7DCe#`UIqO|f3? zE5-+t8%Ywv4WHOS=*A9>1WLmR30QwUigov@XbJhCt1AFa-X!*B0Ms27qr1N>zVORE zHb3`d8|{`G9V*j4@(n!QLnpiYAKBFkO&$+iqgBLO6$AZG->Tuu)cA@#*E&rwtTgY` z`o8mrGyL{|^^{}5p@Ru|LaglTUDs_dTugjlJ&89l2Jfyim~JPDkcSU`76&{(2cL(> zVlFS358G4i_99Ttk~?Z23% zelT5+Y-BtPNGK;ti_-=k>hoj5HX(c-zKGeesf3G9XE}pf z<#_G;y&g3%*Sat768Jlgr;-8jEuCN787*(A1u=z6w3}f_n$uV-e=U3NQU?8f?=r}G z2{GQF7qor1QFN;w0k`@9kOAZ7b@wq;IQS;k>cuCsl6~Sw0}pGPnr7?^d@3_wq^DUa zcDL5VJlf7n2S?p1Q+7{rrM*q5aeeq)y{8=5AGZ`<(z+l}Q#fe|_X?Ia7~Dw8EP{M7R{66|4(=c#5rO=(Ifymk%K z>m_;Jx-}Y8`|Mi7!;LmCdv#_VVdUdgbLjC6k;Y#2$IE9cdT{g0y36DAQ~0h=?eWXg z+Hsfg4L!SL*|!`<^WN}z;UEL8np4%Svl5b|_1YKR7xcle>7yQ@6#F;i6fKm8Zl9Dg z*`$8|Tf8cR4C9Wu#O|9aHe>&IF&$G=Wbv664V*e*epr8trb#@f>1YmoYKcnEd#|8p zsd4(n^`zs-XS)$UE=Kfh5*==(YGj&4CB<8h=Y{Pn3s+VAq%sgFy#L!*#c=XqY5ot>{{nYvE$Af3V8p*}?Ip?tT8a5j$2iU0RdlE0URt}nQhC}{q=EsnL z)qibfs2Na=*jB$iM~VYYcA^Z^v@m3h>*59mIfd3mXSlR}(dBt%i`OkOFO|==tV8kc zHo6(b1xhuLL*_`NbWz!WfR4FHUVs5!_$>_(Fu5HzaA0o|WSyT5Eg#V>S+fS(E9@-Z5MXv#!hCiu(A|#Ynwz zpI(t>Zv*eVuQ|7n!|xQ$AkC$qYaCqnufI|It9UfDTY(lnyV1ZZJVJX}^89R3pEK!7 zq8wgH6#bW97^hQ>yM~&qin6^IllSIo3&vaxcuJ`&wb?3P1i)lH(}WKw%h;3J7uy3t z=#mtIHMCEtrctzd_#f4($Kdp9xbQ=Co~Au{s9XCbtY_ij{iryoS4HFD2zY~G2kyV0 zp6K<{S_6(sMsu%~u;Rvfgi??3yZ2D9lxN-9lP&K+qJI$Dz>Vyjq8A3%3pd$5Isdr{ z-~jUgL1awja6@i)_Ap;FMrAv$J)_ESc<77PvkDt#z6+P!aP^%kq%lWX3weRPegj3s5IBaX)s#rwiy{Iz> z$q!nbT=@fzI3v&)2e`!V}o6=@IWrv#qh}+a)X>#l9!M^8RDTYqWirOuf2+^ zIHZN*$&G`*VYlwjeBy8wcyySB6O{bCsBV4s%qRi{~ zlY4AM(YipZY@_uHG;i#WcZuCSj!2tKIB`ez<#w`c4Zw6Ujif4>0K#_-q;N+hBFI8VhdI+k5 zf^Jw8VZ9(4l7fA4E6N>G&T}XR6-RsVu1DfKGu)w*w+3$xpyN_J2W^CO12RFa9*_0N zCpi^PTnINyn(ySfRcd(IXb;)mQpthj6L^m5+iV<#EC$j)4~*p#Ak>Fk!jA9CJuL){ zbPn!{NKuRsaonCB)O2agAknR9s`Xif(rEhKL_>W3#M8;TKU1M7aBSLdq$B80`?3V# zJbKi6I3pfuc?0no)H+k=srHUhcDr{G(OC1Ynpurq8~5dTurT#F`A=Ai8`vU-WqKW7 z3Ru!EUm`3y%mie5N#55Py{So&=C(tH8<0atL61_!Oc0SRQO`p!&Pt-~ye5*zo1{Da zwM9^l^oZ^B)h~|<&{!9g8@~r-!HCI@`WSZno8$fZgNoz{nbYCl|5(+mpt9Xi_DQ>3 zgYSiSZdF5cBK7uui^Kl6fsb-d`QO!il5*_)z;qRE4w`xBr+x*qy0i|&tb@Bk%FG&B z)DuZhH;*mR5P|vq4L*02vr-#ULd8R zhQvtoqTUxW-F91ZOYx^7rIvb)401dYO>4eGGkDysZ}xyG()!*{6l zov?iiC3&Jc-R4}Pn<6y{S%Qfb|M*FwC;{cIt#Py2`1@XDNYU1|?3Ghqyt}WSnq%Xt zqeSn=dIK?tAyaYi^lMS)HnaHtj66R#da~1kBMI;x21@NNe5719zvHL<5n+r^a<&}s^hY?*$FRr&fK{~pTs_CDi8n`+3&2rg1 z%%A5)dKkS)URDpFMVP>5)LJIfs;0PUUqF!WQ56bbKO1cHDw-4mA!h|9C|=O=l$aby zEnY&SE<`nwLWC1};uFHss478eJhcXb+x7I}uUL#Dwh^oC97c^I;jPQdw!b!SCa5SD zx-a-mfc0+FJK+^W4SW>$Hd~w<`5MSAf2NwtGSt?Qo%IxI%-C>%TjdwYe%z{wS(R_m zHr5@VFPP$RrbgB><@pX1WCtoZ;hYVwtP^1CW8A!Jpch)9>*f@X%bNC*m3khp zR&p+Tz#MaRrA3_UmyO$PX0p|Z9!6I z8a!crW*598kHX+QPdi*+t&|P46@yx5hoIfywcVv&*G3-DW=bDf=Iu0ad=C;wv=zK+ ziJc+BbllgJGc+Etr=hfSmy`GRBZswEIRp>QgBa%;% z8}CkFc6)Z%&h@of#cK<7}Eq zJ(&_AWj;QhAJ`grTe)+kCU1M20;v`0Y;j*XBGF;fV&>aq^G!G^{Se-bm4& zsBko#l^$J+S9O9!ehwE38zYy=7fX`VE|t%X@9R~T6TgX*smN%;dFYBJRIQvaRRf35 zjGeC=I;#$x_hUa{c!9@#8*1pW&z)FjF>AP$ayZfLvn&+`@5}B|6qNRi3v6XmzFbV} zIaqk%(c#kliA2|PkwS074|C`Q!PM%_u;+$l?JVLX!DfGuXh9$*CBGIXd=R)a$070B z*g&>6fNFxRez9#@=pY&Lf7gyV zFz3*7e)xz8vF)F;Zdq|Bm#Kku@|1IAf%^G_bHk3){+z7!A=wFcaMYtQg*OnO>-}>? zLz?Qxf)-5;I%$Uh%mI>`4S#5Z?&sPTFO43L4i1q^LbNB69ebC{`3L3N^6_FMxWd+X z=CImDnKZ*6dYR@o=)s~3V(@c43KVod!F{G}Tu1sQnhtp^ctILw2FXPk5_{ym(_KGz zr@a<0kl2^3=G03E3iO{=_uk44cFG^n*;6i#HI?ef%YqtQZf}h)NHc777&PeRXp6{# zo4G_zF{Q2b)iMoUfj;gYV1xcMHsytC+EgsI#uit8f?dtau89zl%Of>3>EbhG_wC7Q zl2p5$=345L{gt_TkgzxV99`YA1zGI+^VkavdB`p6S6em40E9&oda?UrO69=OVNwMt z@K(-ZpBqE=`_#JyqM;2so*#u3K~%8m7l%$xAXV$o&s@J- zlOy#G@)JeEVql@2!x=c0m2^KDzDCmKiHD9BC@B7a->~bg`$n^9O5=l;w8}~*Z{ke` zmq9M+aa{mZi0ZHq9T6x7^O`Ks)@p`-I=C!xrP@-t?Q{E*h1i`5^w;pGdGg8ktC8%r zwg_fcR>qQyr*9!A(PkAA;e!ovF`DPq-lELHQP)h>6rf|}dCJcCzb ztvA#22^Qj8jQr**b8eE6hzK@9(|B@K$tjyPUrm{}DV`;_uJulXvNCV)d;eOu_S*xK z#$krcxpf_6LO(ukuy2N~c5nI%Trh8qf0iFi)uE}_Oik=FOcNKP)tA-CPD{OA8NiXA zW*7u&xrB_P>S>-~9MLYeVZHTtZ?`TAxGN@l^@ob+q6SJg&0~#DU<48^FI7|t2EoK- zCeC2?L@;m9?SXEt?6eKsXIO|0han*qW!DdGQv1smqF(E<#*N?Pl?I}z8fC#2d`6LL zy(6ToJl#W@E-=yA|G}e&@@TD13su2(9Sm=uoo1WLg$COVL+(Anzt$re{Lm`^QmqQoHb^*yG-wU%$gmKLM#BHBiYk#a z02YG4Cb`G#3e6H^YcZU-dySSd@z_g=@AEp`W?x!#k~ll8Ktgo#EG9cC4gMOcZNz1k zz+?-nkF-5$Y6&0?_IDSnj)5zP3cYZ~G?4k{P=24DNsxQX*O*%0XbxFp`4c*Ufwxi} z*rLsL{sL2b9x3O!u2MyHMo;+07{}o0X|@;pQlgWO!7*)<>g`tUA8r?qm9#gwPSfMt zX@4iIUXK{Jfn6h*{3dQ;1AA}Eh=q{#m*4F|-hHz((ST^Xe3g6FFoZZB(BcZH5eR_E8nW2H8vvh@!qGf#sy+m>3A`_exn51bwOvDk7$OL z!M-0*VND?`_&*Co%9LmF9rBfxT|-UxT)=D=VN`dHXK|OD`D2|Y+i_wva^Ql>6dP?D zA2V@Xt?K!)5bXq~rPsln@r)^GuqPdC#tma!*o>fs-h;N=12!3Qd9%&^it(;X-ST-jRqSx>y!3kjjj5`Z>u02msMq<)zG|_d z5dEtMKbEtfBxPzA>E3;Bo+Qkm%-ST&mAJ6-)iE>Twk*@Pcb%ybuTtJ#!wew!`r+O~ zV^QaOlGi16YVni0PyuWU&GGTEs=7LZo0}W^Vb4Z7!B$dQPaGWz;TE+YM29x8v}MpQ zJW5k_Yg2@nkOt-V*Vc8EasOKC8(o}HPzDHNsibvf>~{2{_Ax8%W#NR)HTe1z7pu6 zqLUPQm1_``;Qu^1jJLjERyk^clwYbkmNVp}45`uV8 zF;hT}mhN6c@m=XvElQHt-|@aMKt)r?8Ei1C*TYKu)8+5lRN%Lu92iHQB$9y=zpXhIbddz0Hx971&qknA=jc9RM{dKUU~ zODw)trUYhM6JbtT1ocj>*rQ;Chk!g_;wjrKReul7@`Fq|M$9_n@gH zW=hNhYd$qMlb4sz(kU}n>3AC-&-7KzVmsm*8fjx= zmuV4xWq{beM)0LQl17*l3iSNlFU=DSFyh<5*$0vnCwE@Rj6`>;GEg2%r6fh7{!D>> zW}^!%mio{ZLNAFGA$O>g-F8%DVpERNpS7{Bs;YeWPQ-)BPl0wOC^teW3Laya=pVNG zmmp>6!F~2WFY$joKsZWM^RSm2_3_IA?t!%s)bHRJZBt9asb*{X#d*0_RI5b$^@#ve zj+B}aVvqsa={9}$;|14A8?zyg;-8zw4+Pt>#hJckucxp??lf(Oi5rCq3JpYsI1Pg= z#~pH3;VY`VSIQ5`)X&)^=WBPENpD?xjxbrzRcTS4Hu-nbM~r_duG{DfH>bV zw`0IZh45WsEYT#ghIw;JzFUv^!!QzHRVf~=!>Eo6lq}KV@URjY0nCXjrXiK`^{-vR z&X?51SOC~wnh+0LTX<}2Y;MWQD;Xxh{h+m`dW*mp=l`1MHYB@OES=>pv*7DphTkmj z11^0d5;nt3hi|W@!13;t+Yz%XEv6|eSY9gpo`hp{e?=4={T6$!6)zYMW4$_v9d;NW z;a_|DeUu&()$f`x3@g5tCF7<(;-yGrF_NW!e?5HG7m zF;9O{Df?$+C}aVg{Zh~tB}#uV$qME!KK=B4A#@4I0Y>bFvL;7eWy6Ug7Ginaw&_5M zWJGrxb-&qv`{gW{*6^B(5`uV zN_NXPH$|jIVT8&--P3OzQ`F!P)4Gi$oAdGI%@m|$X%QgALR{#RM1-O~e0?q5$X+?` zwf}CEJv$-xZ?OjmC;>>SNd|+;lm{qP>4tZ9W43;7K?t`<{4lXA-yrz!Kf_+l!$9cD za2(fLU*PxupqAH%gjkon+xie44aZ{)zkN(tbzSp;7`StSLhD#mnP#zO(>-hju7XSw zx8EWH5RI=2*g^QL+1zXV=A>2ghiuXEG5PYGLM+zxA*g4P*Th^mgy@Ej;-9y;KlB$E zyYDH9+S0)O{KJOxkI}^wwk=?aN~`>Y@Hh7M^srZ1wD?pSDv3^taBzSf>R?9%pgv5z zMuD);Phz&uZO!Wu`}a1o!ENvY(!HzD91a>Md{%s^^AZK~DBjm4Pft4JPJ+F$5P_&r zOcZ<^FHO+k%@lqo?fW^l0EhG97ya3x5yE_rqOVJk9?$m16QjX=;MmfVkVKj00S_N= zMGjT=ihr(%18nfTg36CFoLq(DyZX(wgV`@!anP3(@{f$YT0Em$v@+E0IAqF9i3$q* zY#rCrNXTR8>c*x!3BbJ7iMfpAlyo;bf49flK#=>7ki-(uOJR7MZ>J(9=CCh4jb9r6 zgX0x-Z#r(~x{$v-Vh6T&7$oRX0e)$&>-v@+mZ@DEEePatHbKa|DjrG8c3DKw>qkD- zW6y*ltwL{v%)`DtawiDfdwq*36ca^=f(mTQmgz60#QEkelQbUo4p6qbMgPO@z9Ps; zIs{PNZ)Xc{$Z`txjfcL)!}8N+hvnRX+V?(n6`)u-@m0oHvE^@L$rY>+O|c2~uPu8# zN(R;phu% zIQN9X|7*C}aIUt!>Jc43)Q4|oM;YWo|A`%5rca!+@&WJD)FthT5`L$hx&N8`k> z?NWR&k9H>H8`Syx?#eXF0t!jV{8njw>jCBdLor?1&rO%w;P()*<^Xx2SCcCtZlZ?n zhK8vY;oV%HTa8Kl)x4hX53}|qpXG20kx?x_1lI5MP#1jYu z{v(KD-2m4>N`wu{4`)yhn7R=Kz>#FUy&K7{2b`y;(2#(a-Z(dF#;sEn4u~maK^Xl-Dz;K;|ndo03;zBsiul_iW!y zBz;}^&Oc6u#tD<}mnxD5i5tty)uTQ(S`M-*9imVoQfDK_`2X;%DD6|kCfa*j|I$}{ zN`F=tj9eXG83}>$0Cp7$kWy@@s<1qZPl5)!!D+%KUogIX`{rOKO9vAZo#fi%6a#9d`N zat5tM{)ph*%f!g}%T0;h&#%yf^|ybZ!Uj4%=GlJ|H$D6*`Js`+cU~IYfSXHw43OHSkPt6F zf*io5{WCsATlT8b4yByG&k5rZID9`tZ`Zqav(J)-qWf)Tdjv{J2xSBzHHV?Go~a|B zs=}WXdXo(Y2~t3+$Z_rYe$mEcq>1dkF@fch5D~Eu7!1G4m|RUhd}KJ484PB9;andD zW)+2G3r}`7kyGe1@JRkXM--rR3pKylY#(^yWvUh_r1V}U+S&0L>)I<+8JbB9s6ueA zZ58U56u3jR8z0Mw%zO&&EGb zulD@-EzY2|K(9z;XNwD(d$cd5o$+))p3D{tHxYH>Zd8c85Ol-2;ii2AfSJ;zF-&3~ z5|>%utFRg85ggR+Fovwq<#HG`>LXzw`2j5A0>GdNkv9fi-J`GL@rjCrLuT8eHQpx>7TrR6b%3=3;VfUJziO^8 zY79{9gmfJ1+1XK~8oo$=!2&WY8*>DfhyFbUUeZd0`_cMK2tj*UX9d0R#A~V-*nKIs zCxHYF=gtHJw4P$j!T@T+44@M@_yMuVl-sn^$>s>K>pHi7wPtx7ZiKD^SRuBm3CA~} zRjl-RD&Of^S(aQJ>qE27+j)9b@IAyJ+g%^v1j&$&eCK_B5@`EKSvm4l)v>~##R=B{ z0cWQdr2j{)^9utihY)@I;HhjPasRQ@$SLwaNQjISyE&veS)TXz9*{vs$9( z0H8DuwCU^w4g6V=@TBh{X!{aII*Y4GCrSP~h{fRuq2Hz&^e)iUQ@<6g{+Li`*dFXR z9(W^--DN9FV}SX^DGz-h#nwPkqDdi{PeoE7;r3t!ePd=O1H#r{k7~~NxAl><#vT1N zUS`hsy4S(l=+5b8lYCn!kwzRqLy-jl!;D&nZf0Xx2qYq}<0S9{fb620EtZ{t8P?b8TUg7 zzc)+KwN~ZKfm}&KIXKA`;3qzGT2$~GuL6|xv(d|=24DcrM~UOAcy+($md6!bd%(Yx z>@*MR?k7I_d7}mJdC)RH-KopSa>)Po#PF#Ccd=Js4S z&I9NPb)88g&+Wjq%5mFJYC3CYZ?{6UQvfWW@faK4(VbtUSC!xD10uf6NF;@|`rRIc zNPy+n2^u0~PAqzC)Z}!^H!Y{XktnX?7N_JLu60?jZN>l8$UF7&SxpCMU$+W> z!#D99cOL-DLMymH3&djpRA3eX07K71xnica`d2J%B6;hYn%XUmJr6273?+tuZ?;5!gDF^Bu46P|Vf4p1%_m(mp6 zxFbNQl3yJv8vGT9Zv}u_*%qElP4P%fNrjW;72{`Ae0}rFcC=IyGsj+N&R+j<@S1JN zhf4q=9{V7S{9XvT-;vvVv@{l~Q>={t320W4;n+l*Zs@*}6%!Z7Slo0`>k06;dcpQ2^CP610aE%ski_uTz;#mNV9LYJ?|C>m#Z&*|su%rI zLR5JYgabd=$AWY5F0>0Gg->MmBf0%X;C8}mKm_Jb1EKc~;K=133<8j~g&28ul~X*Y zpI&qQ902M|otMu(hhcNm_FP9nMH`O4Vv4{wfN#lKO$rgEw0b4v zfBcIqWUHDK!J1z=^0+!0;3MAe=+BudYZ`HZq`me@E(+VE`-Yqm2 zD|g$Fm9yvBdIjISWoX1PB^>kmQw(iODn@Wrewwaf1>9eks>Hpv@$zjn7in!7Wy(7P zQA&RXR1Lo7U$cW~AV^V2>)E0b1~I;+Xjxb%yi6D=z7~{=<##fqXQwgCKGB5F`$O2V zSA|Bn)$DAqUnzK&pAHitO$m#2r%JCF)WIR)3D6B0e@=pC@(@)OV|a*DG$2TvLhQKj zqqv4a$OL})uh^i3{AWrJ*f9#pU7qd+{>cU4wN=Np`t<6h;M3-7uxHoM-4KqTm3M&~ z!sVBt2tZU^0N9$EpoiO&8)1|bzifxoy)z}-Kc@jytK#>?75V^ZuCoM}S0KRXey(_V za37un85+c;BZ4x{g9^eQs-Zm0ek>EsF%#log2(XoBW^U=?0yWRd}qz+2cHYKxUL9( zUsAa@#P?%gQCqztN2{GNhuE^FQ6Vy#i!K0y-d6xh!-h`j9OZsffwr`1e@JiP;97e) zEcEuV|Em2hbPqX_Fzh)1_IWt(dmT5VoWb)uK8jlKTa)Uu)0V#U5}n^F(^q>S&bd7O zCKFP>@zxA&b0ONo2TiGw&b$@_z{Jw})))@>b-&(ov*c&sS-lgOT)B9;K1wvuDvj+x zx_$2mE0{OHkk3V{*v-)vA?#D4ol^GUFD$J5K1eq4LFxV7{Te*s}4za)&>WiQxv8%aUK ztNqs9YL~Xqo$Xin-Lw&UhtPYXlyiFZFCF+bt3@5xD~4HBC`VWCZ4mm3Q!2u4nFW-` z`1@Rz{C=d7{sRMWp6f9t4Y{Za)MB9#r28#6G7wVe({bYHlunAARH6c)E9~WV0aqQ> zhH8%BWEns!i?~HF@auu}4L*uG{Me%7!(aXk0rOz};x+Ie!4V#!jeMwfu>f#Mi@)O+ z!w~73yM0LXi?Q-N$8zyzT#^BTa};#`i2?lSBD8a{mzAM;_(rr;tqWlB{20zX0B%srK7>Br+|s3w^8$++ltlpC2kvzD5VO2NZxA={5RK!MX*p|o=vus zwT|)7t@a$!y(h#C=!Fp;UMO&MraFIjp!^Il(SZjNg_G+gMQ>TPd~>EBIy>x+>(+lN zhigdhX)xic1mjFlLPSs1HwS$*U_U!EZFN-9S(%5Z=PpkwEMC$%A}r{tEZ*#~bxE7Q zR!G}R!in)f6sbC&CdN1^ThS-^%qH=#6`m(b z+z4rSt^UdI(P3d0n2>@M$+h%HG180qo zNa9%?y);6m#Cg{{h631?|F}`0x=6c&xNE*w^u4E=RSIW@;aSZE1ra8L!p!Ce31M>j zQk#OWih@j@HP1-qFYl?UPnIk`toitpTSU(GLV|^z?A~a&rGW5Y%%PmdX@OzgSDDiY zJico<8w2nMkGgE+r6p1v6sJ%V%br)de1es`rF{vu9yv<`rK4s|OCy%!=p1 zCj`6zXcEHN!#SUsoif~IjRTP$T_cyU7gBv>oYAU(YBbqcdJ2!zJnD~OE;bW8ZC>B5D*u7Y>4L1jw>3tO3`B_ z5%d^XSb`LuuS=}Q%4J_SohT1U9FhcBe(9$vJ8!;@x0jLz$Ah2(Wrw-(Dh;zN>avv*e%Jb@S8xexJ7Jfl2SJPedL0?FlC( ze^5bYeB=vzfQSIWBxpZeGxsS<$aI3=uG3isYdL=TikoD=gUk@ zF~9JNV}jYo^?GV{x!l$|HDi1fDrMGR#ilj7SAjIy@G}?%-wUExSa~O~;EGIiThL(6 znRvC53^&t_okb0K9qTF*PJn^Mw%q`9$Q@wK1R%Ts>-mdIfy~dMor!3sh;*)jb&1Bu z7e{mc%(qtepI`6spePS*<#JGaI#&L|v6Cf7CX!0X6nG6j*25^)LOE%MDbcNT@qU%J z1dyL+zEzA-$&kvs0QD${1oDUNPxuC+lOi!vusQ0LHvm{-LXzTA>8oyElIo^E8k>{3s*B+>bX9-fU?)E+I$oGRFXWJQ&c#yFvh z%xC|5HW;Z$vz#!3NijKhER-R)wJqX03&AF2o6HtQ@ig=(4rmg}HLWo317O1Ej0J4r zh`NrJnjxSAOdmW|BLoo4c}7i*G|%dkJ_zps+~BTezw2!gX}H_O!LR5lZ_wQj@S+gL zauoCPIJR2wWBU!gR_H6!-9?h4gm-4y=Lth5a*n3#yu5GXY80pWiy( zeL7HKrS-WR-84T5f4~8{Oy#lmF?pVkk0|2uIXX;=aNsk#&SuE?XPh9A8=V(IHXuoX zC*e>Y855EQpED(U^gL~>?TBW64m!@Fmd&i_jyH1)a)-oB6fG#d+#h5O%t8FUdT`uVM1IN#0Y!fr)Z;+$M|EOj8<3W8RrMYPKPQZSRn zh6pHm4X*x>94b%1Kqr0cJ9%^e{-t#s`Q``uw}wYDjnmaSx@$Um>|}kCJpv9QiTtiv z^9HB&XBSJvZabB?7M8{Jf=y$}hw&JfiWHghRK~yN7 ziEr?iPOxd@XC{x6=-c}>Yfu+I#YOs%Lc?|HT#7oagY9oRQ1v)q95UZUg_UEwKE`#C zY+Am~OG6hY<1c{lyPqI_B;6y#M@vu5OKAVRfc-TFqWT7}@Qgjj{rf~1tJMUrn5nDJ z3AlhZyqTK~zz*$T%&fLw2H*yI{Oh!EHRZ^v-Lvibm9pd`SskB3E@|LqzKQ{QBjcdO zY;ze7H6S7YQWoCc6{c(c2wrMFWGIXNPJ=bWWo@bFdU{g2g_Q@t@Ii_I3Q)K@g;thx zFu;Fp%1{U~=zUv_9JsE3P)Oi>cFK=}8rO(AaWsEVa({1o-azfe>_q*chu{}hPFfFaeAi4)NG&FR8iDKrg zBL~;n@08+$jBmz8C>va6iN$e^7-D;tBBqj}7x5<+Ktl-R`2>jyCQTB)o%$pzzp8Yo z*(t4w?S7Xx2r;DJf^Klg85$ZQ62QyZ(}#Zlb{L0XdFjmAGP>r;(*z2!81SSrVMfFs z`(JyAh<+VOaX>2`lzWGCeuwKu}#(Sg*|)UXD-04wDiPszCe$R^_26UAoS zjFbCy#ILIVXaqgu7k)DGtX`yB_u4>!VyAJu0W7tcCrLcAnwsxA&6@zK;^4=Odx?_G z;maiWbD~*^6?S~&zn?UjI3Om~G0jKz(MrXz%mNF_W~EsS+PZsWnt4#F`*(MDHM~5- zgw5gw&|u?h=lapXZ%^D{s?_9Y`vat#(W@~L2tP>?jpIG-Mf^A7^nioJ|`Z8w*^K=NAv0iSaL1CM|5?6V5aZc?4j5X z)A_M}>tkA~--ku4!~NYuuekwI^JPMnGkrxk zILS(XK{UXUUniM#{#)<#y+nrZrr%fd&~X^7Brvo&55Id)84Zvk3pbp-96H%ySP0DG zS4JGqU5$u-!~96b@lOY!ym^2am9`c6)w}{C-721?=sCTXS(k z6~E+qwka2;@7uh99z^INYx^h8%s}75|I#m-^e215E2nEg%E~@*D)O zA`h6=ZZdgsM5r)~Rs4~E<9ZL10NH&vG~yQING6N^^pH#FT2i>0f(N8zV#VE27D*5} z>le%hyBYIFysu2$$KYw_ern29y`kJ-ZD;b=d@dio)q&&To1Dz}JiG7qG;eizlolKz z9tP+?B9$$2m^`!k-ma15wAMTvPpX|ZQ!Wi?DCrm6wuSEz<5k7Z8$THb&HGP4T=YeQ zX9;>FZ%kmR*xj$gsl72KwM+8NC{a*-h|9!EZFHtS;`YEC+;5r{D)ZsN96bw#5gmO` zZ?ykz-Kk9oMPw^DN5Px1-5^l%QtFz|^@XnB)V*G7n9`>*HNYQ{7|=)5ye@@={W|{Q z*C3~T#;uu~m`tb^Ki?&)D)%;<1xH2jM&b82u)pNeVW4D`Mz{;bHXn$%?U<7C*{3}Q zDCCYqIu>RO!2lHQ+uCT^!vEpxEugAgoA+TU0g+9EbO|VVKZlEIlYVLNpQ| z?ni=4apf;g_tGLAc{m>n?mErdsw1S6F|J=WNmn-Q?CKTim93V*dnft?ugOPfFe7#> zbbuR0JVfFc49n0H?v`3M1LA5aap&2^eql+}dn}Ti{sey2bxbksw5M+64qwpoK?W^- z>?Aq@Qbag%T~_D+=>LKpZ4^}?rcc3NDQ(ylm^6zwxGD=|522e$fqbL5m6w;-+~eox zhZo+E&NFQz#Jg3VapFDkkUjUz#w50tx~vMsY|2Oqh*Eq60RUJr=ohl{N^Tin-M?SM z@Ee!ct~K_%PsaDxQYB3h9ps?}GK=v>7rAHn`Rk7!dNQXpJxs&cgu*ZQ#^0&~=2w@z z$F(#k1-!k5o;iK=8Z(xDy39R)9MI;Mu$!zs~(9 z?@j^4&-_yOCBovV)SyZ_#tc`9-fQA8xQy;|E7g>rW5LGUa1|*XY+`0fVMqX*kM20j zZ-w9GgzSB$_ZUR5kxomWvlE*p`9$$C?)b^RswdW@r9oGdo#++0f)`5s;04#mYYpru zvIwxuyB~@T;`zI)N`eiuY^u24U;B%Kc8--;q2?)5(#`i9Q^6TMa;3J7%&7zLr-Dr`~7C$ONw>-2jc^Dy% zN|STa*U!eAsYnzSty4{d0sj?59MznOm?H%k~w$v5P*yD!R z_6tNH-Fa%6D z!wk;?3Q=y_9Tkxt<{Adh*`83|xktV69P#zAtsc%!3VH;r1|KU7==jyoJD=y)m&~ux zbbX?Ctbcj3v-*J?3ZNeThnlt^?><~^ra%SP~aw&bIM54gs<_ z42h$6gM2vyiIHd7D{>YIFVKO;=FXF0grh6FT_31!n{VTi%pkC!}higL* zm^Jg#6EYK){Hv)wwmC_8p~<@O;2-5CN({yXU>if9DR2ZmXcH%>PFQBv78&BwOSW3` zOO}n7PL#xj+35s{7=@a(*I0Ea3ku%bZ&d;9%A>9t5n6AdoS0BHDk2a9M*VHgS~4dl zYLG9rB<%S1(5F=(!`O9PGs2k$AoH6l#zVeHt8}9NE3(xU?&A2P+&CC;Ej8gsiNF%> ze5LbLM}H;&A#3-`^k&5!rp-ey17U}#{2d>VlO97#$L*ge*2`VujAJ)ou9UE-%_~doieX^&rQm*M& z7h9$BZS5%?U{prBHBdIutNph^M?(_7z_sZ4TUD+XAgR)u>aqK{(c@I>+Q_k=yL?dO zvJ0KsGhK2Ifq|~4`LN?=tGSOQ3tWG22rjZuUqe&7?Pf}gLBL!GLYrC9E7|de>bww< zt9^+?a1-}75T!RojCB@2$av9*NKn0Itk1!y&30$%Xw_zS4efp%zm`!|$rAW)+x-{qK!v!hI2dG7_I1A3D6a&0JS2P}< z3LH-FpjDkDh5g`t;F#GFik2oYq;ux{fbItEQX-zl^NpW>eM-vWOUfPTv`0o*O{XR= z4eK8*3WqlFs(Fs4cD2YVY^&4t@iPq_zM6BJsK1`3~{Gewi?a~s)rsdwXe>M1|lT_ z5X_;7+O7qO%XUs^bG$eSf81nGNn-Vt^b}E26OGAC{4d$ zWaGlh9tPmi44djbjG#hz>YW1iG2p<=$7`8?4j8O2e2m1k_t;@5R;uzgQf}P94IxL> z-D`BoBQHf8v9PCy+F__u2T|~ld4FdZ$ut5a-=o-tb!`$Bu9aJ&t4ofJY!JFLm!tk* zu@lwn1%O$hq<$OhXlp`+m{mI+Rll~VQ@1?FX{HxgilR2Fz+K#VyfOS;5Q<`xe1%E` zPXlPBhK9IZw=$iI{Uj68W*sQq`p7Gzwu`D7(T zS6T3KFB!DlJw!+6YsGtE!iHN<>)J^$YF~lGi$(KnS=yJ~?vj4)uJQ#~HPl;x!#xhu zW}0yg)B>1RPVGVt1~kk#^t)r%f!y1vDyv?Qr->f|@>&IGU2>nSgHeay0w3>4n<)%1 zWoTf?-q%MQee!lihqgtd6A5gHpizcq#&0`Yn~aKcX@+%D{V6i;_(2dVg#dZ+yY;Qi zUC>Pb2{AJoERBuL;reP@dZKn;x>Qzx>u^t$2J{?P*I5YM{L)doV98gt_*0sle@Rbu zLB8YjXWZw|!{A2!$8fiRuLK2GB5IKGl9@3&QO3TPa#2Ri#H2aw-=~3v1ns%JLp^_}v6t0quamHGG0jcs**d3}PPVrzbG)^k$^=|= z^#vvUAZtx(UP%#mffyQUAu<~;GG1sASKR@}SDHeK0VlpnL{8%PDdbn1Uvl8HZ%8o! zDl20|!0rW40LtjL6vVU=Cb+A5J|B5c(oV9#!k&C`6L$!)cnD}K88)u7nu-PRo=)U4 zQZ;tmTl>5>fZQ_5jq4ftl8QY~2L41}Rfe*5MD%=xVC+Lx2nD}-dvP1V=t1uTJb}mu z^vzUw0%fQ$z8(8BCaB$4U}SpS!s`~z(I33XSC_(OiAsll3^p`bsr?>ARs67=B>9Rm zO4{f2MRd+;1g84Dvp+O@8`3^}<9 zpIL-2cG*@<6gw*UUFlO#6duSh7Q4ot>S;cKf%qi?GEAT8R}ve^O0c?HUey zo{T>l*%}oM91#H)@Z|{7Q)qvlD>vbq;L^z1(0vlXS>K&`02Z zjcWVX$5JPscCmtwmt!xsz7<8H!Zh?NB`EuFgpY>u6q37uE}qH_p&tJT?~C;gsEH)@ z7O$XZ6J9qKB!mD+LlkB5l&p!xbV>- z9NWc#{na$DHFyj<_Jc2P(|0~ZKsfoMgHt@6Ql5tk8xxJ2@Q)R5t;WB#QYxZHgAr)b zS0kj^EW5 zV$tb><2Q$5t9DM8hIv^`iSor#OnMj}Azurx&6H+IGw`}J+A}3TdX_D#2B1(XAIb8f zFL(xMh^D5`Wy;_@W@n!RsKF~AU>^t-8vN^1DVD7N%6(p_mG4F`&-h!U22{fdI}gv6 z!wVnLP&g-b8Op9nA-gmm)9B59pcEILs>16$I8~ub3&oqf$nENIkz&>)%=c2|l9*fk zr1^fscH)*9+i@@E1vQ^R*qITQOh=3&ef|J_qKF$drZ%7&ta~Hk7cL}GDlIZA;YTIt zZZ!_O4;QGAIM9w|2b`km*d&)1Ul_!4hB*l~ptfFQbw`_YtoUNRb12NC+KIlWB`$0z z8Ip2vUIjsey=BRiI&$htQGD>_A1;7o_sACfw($PKtTA zNr6i*Y~m~dI7`$VkN|1Glf8%33^v5}7vaP*-qImBzPs@scpr};t5IfyteLzgER)8; zbg0Gea|zAWvo1u=}_{djXBq(gf!=5nUD5mjvIN;HN%Oom&Uv~ zA%7Kt!Z8SbXA(zBP%69IMp;fcuUWgpmjxCDYh=9|XzX{0pdtm#oGR32h$+j2?D#FJx4k7d& zlqGL+QI8vT>lNCEXrizBo(#sow#K{94whq$v0su*E+Z&H$iR;7m7qEcLSQSgF55rV zfEQjM3DXZhrysr>X1DSQn3CqpUBTF9h?a5CNgSJA4#e#JqiaB6ks=zURh1wt)vqhp zO#`79i;Q6TkAwU>;O;N%dxW0Mcf$5>t}hjGl~ZDd?$^{}vTy7GNBadYX2fR*Pr`g= zxJW?<`dr|ocv%BUlvgpF!hNRgN2~io@!5+9@0_+}rrS}(ue;;pyRJ1zFyF!Zo39y^ z$j4&{aHeHSM7Dg?s~je=LreyI)D6A24jo2ZJ=B}7Y@3Bw2b*sqr-SDrErD%^+xp;B z1O&?_U@7mgx^=p+GQ~}Z9ziB^-3;oMKYlkG+TSeCaLV))U3bXWD=Y_a%?nkd^D&&^UwLH?vvmPIpV6Pj7IyYUnXydB z6~kjkYoSeF0{V0+bxZ1AS9?}o337iJ34?Ob2OLKjxJ>eo&R>N$MNU(B$PlyZ(35*# zDXo5@E;rI3b2#1p8FyxeB6y9epM`}~0CupQa-=?dT!pCC4W+{-m2gypri60Cf{p;yDHPeZ>8=97;|Q(C zLzr{fb~4{#kTUXDoLrreJE2{~wH5S4lrF$)tsY09kFi^n5P)Ie3IXZX9AlTXAe322%t{#xsY6jsXJ8VPB43sZp$=l*I1QFpc;OOVMEs$)1R09H& z?6D66xcFndLeI0s0RKK1Uq1_op&?F`Ps~G>AV0{{P{r;;-np-YnXu7>WcpIW`%?s8 zjF%dfLJhYYPv`t89A^kyLNN(zJ5&TVA2N(DixP(57%AC{r`0a{lat`yaIy#9;!fhB z#B3PKp2VWZ3rHRh?fGqUMPdu7(xhgFRXto$?tIUV1wR!&PQBlFPBhuvPvrnt+sSsw zHdvi)H|kyH@MaaRe;Pd*4pATR%Ms5?}`arNS``t>~TCcpGa-izl8GrN_8RKs8G+3JLDjgK)yAYOa% z+*{s}hnLikij&4-sl6`@sNC1Q&f(K(qkNTlmM>IqFB;O!1`SQJUQDc&A9T*g{AEo6tuO$cuHo||WrVp^kqhyIuzJC!zZMTNzrF2AX2ysBI z0WH`EUme;FR-;MSBLuj6Aq?I}bvUa< z3Z+3dvk3mHO@Ue=^bHXR`MdwR?Jh@&1jGp8@VVKOD2}GNhZD(Ofd#kUa_4)pYZ@7` zx1L828a1jiZ|k32nA(T6yjv$>u@`E1+3$cbC$2a@XEmrX{)0s%iZCriv4u$oV)YfI2JaecwtRexq8I-s~qL>a7+vuN3ZK26eA{ zaMH^{nz|sJ+4W851Pi(+=3f=)DzzstktG5kvB03JP%__>;R|*_tyGvDz`%FT%~Xp= zJH~>#OJP=&3iFBax574Ex}Un8gsPZzAJGn%n8mq22rz>*dpOs1#T)rtDk#@l6pR)c zNTt>uzZ*KXE9Mnlq7u*Qy{IY05N?{lJMEd6zXogI7)W@Tto`|Kap z4O^z&giv0wgNkx*&ozK{_IPRgWbtbMnrGA=s@vDLy{3?QPH_HN6w9ILZT12Jz;*e=iLp+aJ&K2|^8Yz}`` z(-b!tL^-V>7WGJV`q|)}H~Vcuhy#JU&Lz25Qw&vqPO<40z{K^Hohv#$3FKlc`d(Mk zTQI?{o+0?o$)K7I04f}u1?s9UAL#XHk?`%_i`APIPWvJIQ4SpMs=u%^B&OVU&MSjp zqDK1yZqZl@bZV8td&9EQdSB7tdO!KXm6rfe0~dJ(LCzPhT*hCj2uqVm5_#{GME-Ux zitf%jUxo(AGv&@K|7K7#58O3c44fccl7qDdt25&6s)vsmx9&PUT`Nzg61nlIhH5|$ z^r+nRq-S2xam=|CP>gulK4*(cr?R}k{ix=i_C#k+|BJl04xbPq<;YT(M{KXV&4HP` zYnT=Yv(H~|X?>gMxtwRctS;aPz6q9;(^TCX&kySJ^7Kd^U7Np+D?p#4^We^BU@>a^ zGK2dD*7%%^H?IWxP?8yV3em;W)!l;B-faAC1TkkmovQ(b1<^(q+IJ0w4F>ovecbHY zI6wE=E5)MNMhc(i(Xtql>6T2sm^XYZgYDKDmp)hLMX$53nHX#kuSe}ABQ+`HW9zdy z@-{6&{v3_!Gt!QF&2+WNu9Fi8(b=8H0ZzA%>8I#WC?i3(`$|Um-j2wmFU4I<0YLiz;NC^9MRyD}(VP0x6aJMGW+0MOq+xdPLwa_6W%@u<(uu}a#!+8km)PS9-9HZ=*_PH{1KR6I>d!XKEwZ_yK%Z_RPZu(3n!8? zuqg2fZRyN%sK-op+wJNt=6pgg$_TOCkE8Zq-6UJ9HKI4{FK#oC3|4jv!&SpA#jj6# zaiV(9%Y$==?&8w!5to#Q z*AUy~>tK2m8H8~0N_Ea`ZUp+f3(a_@g4ik-b@+H_*wh|=Sh--{d1_a=wdXdjRj%nq ziJ3)$RD%ZNo!uO7+HOn9n&_FNW|M?%`DGqJS=*)vK;qT$)T>`M!!7@+1cHnG=37!4 z-KK1(xGJwN`r!=%CosPNdGQrczM-DD3KGp40lswKliR6Lw`)hE9db?F0Wygj+<@(= zxSC0SN?yi%{N{P&JtAjy^fz?l4^u&u73HPkD&~E=Y+LuM4+{UHEZIquy3(p=80#W> zAq{9nE4e<0YuT&B1n8+$9^ayev&6As58gBo>!{~1u@@-UAcg1m?VF+=2))DF%^b`lwS6?ZA*;01_WqSFbDaUKSNd#=li43{` zz{0eKZgWtL6DmIyU?i45Ag!MYwGre|L{0@|(5g6tPr}z@l+k2s1%)ltI2N~ygqA2( z-w^eGx0M8??q)CC?bxIoJ%$b#(GS?&Zm9%%eiy?=Vt^77rX6J&8L)PCG4xnu1Ll0m z#j6)(?LBo=Dyke0jOgAkuXoj2g-2m23xClk=j(IaMK_wnAH_@afBURBapzuVT(P=+ zb5fR9FY5#v4CA&6()1iYUR0Fv(s{o4nT2=7dTEs5Yo&6Ayk*s~oPb%j&b4heju62r z3VPF_7h6I-aR^SIOLOpc{U{|YS3~s_`fc(Fn06+rKQ2o2y)Skyf>Xn-f=#(2!bJ67 z<4|Yl7ji%z(1GK2`-urb)c{sX!glY^hZNR)SLV{LF~L=Z`xG!1K@hXB%X2Ah3SOH% zJ9p+ie{<}ZSRu5*ekfVH)Ze$@BXxxQ5@JI)qaBaxFG~}rAZ+PUuO8upe{S6uHlT@4 z6CjgK)3Fk=^*XN$pRc%hb?BSaFW|1U6OA5!P5`;LIH`Ceo?8Zwl^NPDmKqSPFNB;C zj8+kwepy}^(4;epg5{O!9%eq>^9uj?^;;;KRozSdvJlS&Ha!rFnoB{hL_Ef(X_F|? zW0zXg1p}hMA+aD8@r>X=A0E~)!l@-Ns-ewk2erg&P&x&<WDST9=x zY0&neBbHIjYr|W~sso#Dv*C2;BvMuvNKBj$ua3%?{wS|1f4Lj0Ug)kfCm?w~w=Tp^ zU3_LJRlK2pDEVYGnrPJL)-hO?D6a7R|~co zdIbFb@qQPHkjs!|cvmZfm1+0UVYW@Mdw~eVS9rTfPW|hb7=L%NtEj+rbr*ouGJ@U= z#;@%HL3kX5kD=S-p5dtthzp>_gr?#C`=_L?&27Eo%CHYw2XmEOv+jG165p}iXM*qI zvGlapR}+p(IZsvhyFb-EDmJ2F(Uhi8aK}xLNTu3pQ;YI7`g;L8B@GBi7pZ_J`T7jD zPQ~o8t0u94k=D4NP?-Co#uy}%SDAyowz*~G_n>Smdu+E|BAs(guTzKQsOk=C^QKYGca_}3 zB2Cd?Pd#Uba#z};21ohosUz5WwMwD`QoW5*zwSu#zv&`SZ&rRz>LtgqIg%MG@DsK$ zHo_2+giWX^_$Z05*dmKht_u#1OMlx%>%R1H9*^B)5ukf z1mK!N)A@x}zIItg<=&8Zn81a_CLlMkd@sMZS_ZMqPFEJ6jm6$HXA+=JVJc~mOYw>n zGspi@KdRxJ+rXNa*?=Q@t<2s8%kezhtbu>&Hw1p-G>51@nfdeRCK6>l$tWifYRWUN z~Yl)6eUSeF`PM$J6A!r=crAtHZ8dEP>CzO<#JUaDobYC+9k6yRC2_yRVxv2Jut z6OX;i%xmzIz5pS zLVhEptrzLbC$S)$dcl5%GR+<3!k8v5KD*w`m{B(xS~~(97EfL~S0L2Nc%s;ar^P$&BOF}~Ri zXe6K&;j$uY#k=?HI(_$d|DwexY~Jv4#8!PTVtS0}4sO!-B_HHPb{O!oKy!fk`xFRL zN+znSYknr*lmRgY^JJXb8{3UXIrjlhOUaw;-|D#fNN{pDCuQQuiRlQ_juWn#K~D?~e0QNV~&& zY-4P%LA(behbrW3nq5$_q)U`<^Th452cmqYV`eh}|H_Z?u04FF%_+%rdVk|E{fbr6Sfa8d^W%2T;jdUKAO? za59b&3$n(=*aGK#=JgkQ1b5920faI=+Wpyqayrl95>86szVrc)ex-6m1?T$y=j);; zgPPB3*s)01qJaNTPKt{LyVQQ1H~o6mQmLcf^ z0S#%=Vz;;-XEcN*Q-U(}f7*&DA&24l=B3W&<(TY9SqDO36`qpW44-OLd7}4RrRZW?`YHNQ83g zRpgz!P6|Xxi1As^(zP#pe8`}3;LxEfx0;k0`xtyTz`J>MP36AVUO?wzX%Zfp$`2*4 zXY+>#T!brP5V=P78-me8TfN8S9>S3+F3}mUYkXq3MMZrsw@UIXF1Ogfbz*^1t*}b;djhZmIJSCW0S*8(#m|eEmQpm?a=hOIi zs(l7Kd$qG@1A1ba<)Zyg6~HCGX2UDp(-WhMd;ZRkER|1pf6dm+Gk+ujLV2J6_9{@a z0k*?T&Ku|T@v#tbM>hk&htkXy#TzRtoi54aw?(s6wPLRI>!BVvlRDGQ>&uvjYV1eD zvw)VBr+Bozy^X8F;v-`Cfx&=(qpI!fm}36{HA%ZK1#;_Wd&=&cLmh^^cy^Y!VVIs& zK~3cL2W|eQTa4&i)^(K-)Qyl31RM5*KjLkg5edk;!(E<%icAS! z|1Y+0FKVCmM-BTg_q=+!@8YtkVdg`_eSNxj;IC10OWD)e-HCHadz*TD<2#7|xZdLO zW@Xvz@(DJ-rpVrdd+?Jgt!eH-{w-Fwt>PNZ>o8Dr8I!N!Qd@o2&uiA@w*H>V$GR1j z|7_u{&1s~p6!;I8?XbM9oO`D2&f>G)mqnz0cW{VTs}aD*LnP@YREJ4^OZ-4t&_!dCX=4Pu}Cl$ffrVG+Ik6^vh7yjoCL8h7<%;4dD;BK=TDm^o)9qFK7wtcKC&YV7># z6DL(gzbTlci0&U9>}*WZ$e4)g_`kRee{-e}F!CG+aR*t+(U31u&jscf5OJU{sx<f;g|KO$(p}FwtXS{jR0^`D5X$ z5UF=Rw>kQ^uK0InfWCzhA45qYf9mExs-1!u6R_n1zZ-fW=$jtDv&2HQVt%s(+uJdy z!-$qTE^+&-@rF?@b8a$bIWG#d)ut+KSOQLW*+7B0v)LV|yy;HRR1m^acqydv>5+H} zfD=JI1`Q@)97X$fC?JY%0g-U%{c0un{cxx+H{)Fs8O{4C+nd!NDL60_m=@yFMJ!tG z=+xSM{xk%blB1#oX#TLlnHkj)Ks(bHaM^s7QCRuL@xpPid%v(066)qg*eQg=V73xG z^>7LnR;rX;{?SJK<%yea<1W88I4GLIX6&94EuG1>2!mnFn)Ijs9+MohRvG1dX*Gra zC)4P!Az+kBn69*WF1s^2j7q82?;fBXcOlM;d8nU#p4DsqHiy79UCCSvs87WgM#Pe5 zNrLs4KXc{8G$jPfO`28eGD;Uj>}Vzt})2HGaamhZ<(#6(PC@(b_%Kp7U%-? zM>%oIotin1y&?ZlGGX0|RJ&(u?CJf9ldCEL?jQI^AAg$meE$XX00MMU#PLKjI?052 z77bSaPah?qP7u7IjC$hP-nJ92_=cNQvKc zEDz>D=m&kk$!E8hxo{T+`c#q`u%KD$ z(d_TSL$&=5>P`B znv3Wh^AG);28ju?mMyPglLBY2x6*fSrJiq0iw~tTc>6+|m$L}H9zw~ZxUWJ2C`85g zr$LqzXebR5C~ev8649=JR=jz=IJ}28U#ior<2)yqB|ghsuHvj@IR)JG!sl`Y&nKTV zFJKbm|5JPx7W7-GehGA%JTt!fKXww3A{U6G+E!XQ_3u29b6Uu%Uq9fS=E0N4+)w@@o(i2OPPuq1w!K4h?m4rjv2}<|V39={P>#zY?dX5k zMd+b1j6%YgXOpl-`AJlljjm?EP{{cQk`$)Y67;x|^EGnrY(S`%o{@7--dt4U_%Tj5 z?w3skHR)^sjgk1&dHxXiaU;Q#r^!*Cxw}?ky*q5G>o>EwJ*l1+mkQkO(tBZ>9)&w~ zYN@3Gv7Xo>7|Z>K3n13sQE96t1HWOaWO|CB#ps8qps!>4pC#1J6rUj+9h>K}8kYr@ z)FD~1v+NyKr)8O}90Z?LCX|Zp0802yW+}bFLT5{xW5=7<4dr3?V?k$9G+3uAJ%mZUu&(1Fl;4R;x?CT~=eeN^jq|6<8SC-_O)x^K~-_m#=iZu`#!&54J0 z6Cm$46Xn>7Fe|^mHsxrp7J6I*v;>5Ewe4A*+ZIea2w2D%5>Kw2LuZrle?ZyWrclO1 zU_~l9ZL9A}Y0+TKJ8!}Q5Ub6FC{(FsA!pCQ5zh8%4Lhn$X~UbsBg)j@k*l4=BOfVJ zgKbV`mpNHKe^DNjeQ)sM{WoIvx9zP&Be{O2kjXIbSV&u-Y>@daIdTUDxM>%0eN>Lm=;!?9NTXbODSJ zs#Nvg1`Y_}ab8F(4$X0N0+r2>a$CoCvx+bggHAIoqBN{B~Np5DBB`o?Bus~Jk2+f`ovp8D=c_RLavci#;IHy$${XV1)D9<{40Ac z>_~-|Kg0AUp$*;R8l0?H#P2e+al2cW?jsSU92&(yps8&vk&tkMo5|M)>1i9Vcb0H8OvGt7fnICd2+|en&^;K*?kD z>OzhkQu5{F6T2Lrd+-4}QFGGR+633DV#f;A*JQ5odzV@@$a2YELia+6^-PyA5Z&j zO6ZIuqEk1j@@pqKyEIKqbh(Qk8%#~aS9^@bLD;rrXLY+?&ySs4>HH7}t4jHI$E5r`62i(FyUF^Y zms!sACU(U}uS`yCqZw?Hp73;38R>xTfD-*-|1~01KUs(w!SxrVTLQ6_K|o5q7F9); z0T7yag7wEg(s36YF{=xnSLf3F=RFgnCV}oho>gxO6Ur%4yUTl!PBmXc46J1M9LDJD zepF#ld)pL5vgumLSciz*=T7u=uH6`;xFNVCupi~MRDJ%5lc!_GIV&9+#-{gQPDVV2 z z@sr@#s*-l7X-;Q7XGFmeRq9}BURPL94h4C%fri=l8Y{J2R-PPlhJ3B}Wt`PKkyZHM zz>YllFDcz;@w4Fk%bSv;GnNdAZy0ZfVCB07(AMez*Wb?JpH3sak#LuDMV*Uw9C#V1 z)u>S5+;q(BWlO z2@85zEVFe!FfIf1aRpZsemK^L_2it2+{21ksR(78N&li2XV*88yCzkRA2 z@aG&d^{{!SvB99)wrB%pjPHDRo|EKWyu%P_bdAOTNl(P)K_Sf33Gl5%7^%p zP3iRPiiuAfLqhp82SwiOdT^ISZvQe{gMnT&jt2ZJ|0*jO2*w>Gfl-t%UCDF^r}zvw z%f~}pMVE^%{6~G8@YlSMhm<1D-m*s@xkZmgWn&u(}PiZ!xEP@E;hls?VfBjOi>C@*q3FRAxRus zSZjY+!Y9{&Vri6u!?jK&1ND-7YkuF2QP@BSf0rFt*MF(b?^7okQ8cWRY90DVRmc!C z;*x--(zgfqKsGryAK!0#=pB&zw_7ek6BrQ{x9C*viyY~@>4Kju#McnfWpgEk^B zl%8vMGTn7*&aaHcATSyS$8fLNV*0{0_`Jpp~`XpcrL%+1$q(#helWFPqXeTMc}9FQeqU~*3aUOBF^bbdPRZ7OdG+% z^gYwt#Yi?YeFB%tfQCu(vBHcT;P;OE7}W&NEI#97&Y~-zhseAxWSS03GupN9ltvT} zY5l8fzjbOK5d;3|h72an6%L%#svN91Z;rR6X~j*vq~BllbMWrG3$NCxO2_dd3$Xjd zI)0wftoFU0Insc{w8#oiDAr!vHgMx4ir@IDe){Q~Q1zFQ!&QJc*4i2TcbVxw&dJw5 zm9g82h#C7!A*Qz1%~2YWMCE4Wm8N+AR{l@4w-fjgRKbZ59h-*2uwy;s7d6}Qa%Vr2%C{?}_+)@%eC!kC#y8w-u zKbw93*UR{=u;z#qaBqC^AE87%o(QwXp4x=-{av}P1A>2bOLo>C(m8(t3kzvA)%ZUX zhl2QWm(k_~l$DAhi-Y`;fuVb$COh>Ll^x{hx+Um(e1NT0p;&TAOY%lUiA8~|hTzic2vmwb7_)IGj~a&d%e?}Jr|m&x^^t5MM{8lPMFmiYUr z<~5YR3oi);!-u@3q)!0e%QZTtULUopu?dBJ+<@9Ptds4Q(8 z*zELdX%fDw;cdY}ev*Kuq}++*j9TJz!9U3+d}IK#fs$YFpMLItZ=oHcYyWG$a-!d# z{ajIz+4D;OK6gGwb%VY*sV-c~o36bU>uxn@&>E;_TT%n}3B!+{#D(c|r4xn@BWMOo zu=u$_4ONxBP2Q9ha$u+-?T2mCO^YtTAgL2(%-$42D{Sj>=1irpPQt3^?>GvMIhgY_horpDRU@`Hxrm=LeAg1$TeE zT$cJHH<$z%wdo=ri@Xls@@hiBB`~=aa!j6;$1V*%g}7j$-=|zdiAD)RZOR5rW}XMg zmcIS;bCb&pxX<98gXOOO9r^-d=$yskooyy!AA^@9`nvL57nkaiOdOzU@1Sb zpr^L|R;Rjv>#?iFdDHF@78mC+Zug4+YWgl3?6w4325`jxd(gOuj2jeG(;@7j3kIsb zYP0v%Gq;P-*pILbdzv8Dh=~Bbda#j)Q+OP26G%(tnL$a$bh1oX`~{5JgB#lg5wt;G zpZt@8`TOY$d|)NQ=*`~#`HY7No?LS;hY<}{io;Mv)wlVfrTB2FY&}jzw10%ei22~j zI5|phs_=8>?XS_fj+}F#IrDPhB+~z}8Kl70^xK&g{(0&mLOS&5g%zcvwE?FHf`)Bm zUijBGcr+*;{I&FbJ++5y%Wbrvso|^OL0jMLHBgnqiG(NrBXfTD5#4bmNa9AoB_lLQ z^LSv-cFhTcr!%TyrIs&i9UE8^pO(k}u(5!>yA)Tg@xDik=hAe{*k$%spl8x+`oZd2 za0h^1Uy<@*{8`3-zJu#Tz)mKUmi}H`eAy2`++e(!+C^n7jLT-NHGb2`F3e&3rqy;| zt)luJYaGC}p(PIbr{)Ls^0$a6@s`Zt?*HzVDwsb?{eChJVqE}w?q4rvC&fwG{tEWJ zVUcjc<8kc$1Je_ea`4oPaz~|dw_UKTPxb_*%gMEBMhx6107f~t)%oLp-3ebXPMrNE zM>yhT3(N@7GPZ$*B@L)ii<}tf)H@GFqj@STeYf;@!Q%fo4%WbNfRYoj{OM4QNGR9WZc^0LrxFmkMjO1YLEAN@ zTDJz&AKMK+4{dP<^g9$Yn%N4%w7!n261%ySheB-d<9%C0<3Y#_*k*0qm{Yf z1?+qFZcaqKn(m(2YrOm zGzN}T$@nDPlqV${3d>L0?PXqQSPZOjp!gHsH0G9OnjX#+^WH5HcJv{2Rb)|FU({Xy zzoFFcbNK(mAN+X#-D_Y3iQ2OsgoqUBz!{~EHR)8M+ZoWE8mjG=+HKw^6gE#o39vJurN zg;k69D>-@;;}(XC!@zj8leIzyFI&-J!m%;6<@SDk!YA9F9k3*%wB&!J^FQDB|8s8& z_!R~fP~+8cA)&BrTd1Q+8G{zd)4NDNNCsRDD)p#DOLdIal3&c1Ucv$dBHx`!>pUOx zE3BvFMLh;P%4q1CUwc@bc%hKG%h9k~UJ*olQ3~$Gy3r#D3;Z8%PqqaS095}~hW~q_ zVm-jr#Ymq3hN#8{-W~C@dxi+WdUmr zQa5iBy=yZ`aP1RmSx7SK|85pYcplS~2(16!EJMU*#nyA*pv6{3lefClJ*!AD3w^kx zSNb-6zRt$$+Y5|YccDd__~0Pmtv}i|TP%lt&P#Z&FfmE0o`=&%vXcH@^^9mnvO;1dfq6CO^WU{riQ1xEn>>z-=H2vHCLz z4}sA>5Iz#zd>?b9o=ehvrI6+GW%C&!Qyj$qY`<(zp7lqA;zBi(gA7?T@oZ#i$@>#Y zN$1LZTlS{~0ksKSck?BS_`VHHeSoogc|0Xq>6~WM62JcY(D~wFc`=cho_b@|MfxXX z`1`w<7{c6av^q}xHa7xbQ1+3Xj^P1VeY*R~QWi34UG_Cp%w$&S%97RZWCpLA8$E)` zvY40e+$cR!%%qEqw2;K7!~7&0xY6nx#HqI2@nYzGZA6>o@?8Ra?hZ5-VrgD>CzH_! zI&!Gg8y)C0WN2;}FR20*2W11L&2t(eU)Cok?l$GrI||0(nUa%o%|F<)?*DQXW9ZeIMfM=Sx2m~lBW@^QypCrRA$>t<1WpTfCq=wCc$ z4G|4WU503FHuH?sCpITLBFt0s&HisLq&>;t(QO=`ED)7L+1MhYDv1BRkb zr>~d&6NRINylXr#M;nf71i_pBd1WygD!h18Ul#Ft2~3R9fF(GGp}QMH*!5-m+0NU+ zc9VecP7{?B3(vHd61&B`b5K)-W2?8effJPG4Nt5?k|q-<4M`+%Qa_UgY4B#`P#1-J zoLr3y6gIooo>zPD`nV-bZe9mp_~hGdGE^KasE8QIBu?Ct5 zidcEyJATSwNG6L$TgOXB!}7_VFZokF%|#&nY;7ESqGTMYA`@pf*L5pnpmOcb>~0SE z=ZlU2*`y}9rjf-0u|@%jV`;Bw+^?1`hM|#@#WmwKA2w}7LIn8O*I3dT*qhGsU3hkl zh_TS%I+bd8|5*l9c|x%AKVjTp<pOl;J+u6+J?d{c#OmAI>*UveORE1K&iEXe)3Kwp|rbYE#CJS$F7trOJ zy|%Cqf^fdtYLOu`3Z5Uf}i z;0xDfoa-J|jY?md3{>Y&`j15He7xO{=WW(XL6_wMuyXm%9d-Z64|rW39=Om_67dUT zE+DhreBobu7k(x%jdynRbzQC{vWbuRrss|21dgXC8q@D`ybjPx|BX(5N~ z+aP`G=I#9$NJqzFCYA<2k2zD^H)AjQA)m)oBCbLOiQCsW=@3J3ZE%*}DV3+-^?HsWJKh_9Fz*8stknVq%bG2`XM&jj?a zcC6f-*VcW1X^!b_&R_k)7HsODJ2IR<+m%SN?IpQ%c7M;HYJ1V8E%W!*f;|>{1=ggE zY>5v%vr9`XJ=Mkv9c!9`yrPz3%f#e{pIWqe&!UJYnY;qVbFol#lH;2h7P`4NVm^0q zK2Up{nd35Z^ZB@LPwEC^G}yW!1M@#hvqD3oI`}#G4R}e*Qw)sJ+|LRP&K=*%I0rdc z+xMtEp4WIH2uQitqcy7GhujjWGuer&QT#ltL_`dJH z3CHo;e37(DeC_O>O#`N}q4)nkjcMYOk7b-PYs(9f-Ql5@9w#qL3R{noY%jl?+lj(u zlmaFNC&6{%rh3c9e=jd$os*5k(swaw!M6H!gF!PbCx2rHvN+Iw(4OtOM9s9^5_x`H zx6D%5C_NTxVy&1NO2#@xmh<9u!|7$3wVm0T0xCR_SKIC1NB#mvbA4Jb7LP`Zh7HNj zUH3Ynb>yhCgF>YK!Pw7)`5RcdiOC0s%Q+RCw$ojqFK#+SIrH|H0WvpVHovUPIy8z2 zcUSWf{znMFrP5%_-04|%QS%{~DwLwvJM2KH^}GR7-2_v&E59 z!^50V9XOjPv2J6eVWZOjYwz0sncl-VU%bvxnJ%Q1#mX&IDn)4}aw(Quskxk^(Us#! zb4mGjF2!=s3(aMERg5xAh1JkGET?2%hh#cbQk>c7Mjfi1=R0is6V4C$$)4Be^Ld`n z^L{_?=h^mp?JK2Erbnd3vgUaAzGnp2*N-JG*0;5S^6B`?e2}O_YkCr?*JLZkm~5yd zFTT)v7^yhI+YmEBDcDO%Gc9uDEWJJ2)tzUto$dJJ#G89B*|8?PXIi!$HF0JdqEn@F z%%}s?YVgA=DPU}2}5IMN^j=C0ZZ(mHTWvR0N&k5U2u zZF4Ss6KNQ5?ySxxBg={-jL55dB1_l;O2g|%!wHzAh6)`f;ep51ksL&c`xe0cTh$_C zD6qqDM~ReR}t3iMHM&w38PR? zKnzBqbwHuROQMz{z0eNtRM*%l5yJ#bJNlznW2Uuw_%gezH!?`$;9tBShC=yyb)e$W zl51QbP{ze1(&k%f8+6bSK%-aqG+#+=GQni>wk{7dErKj9_6cw$B!K^MEBK&s<~)=F z@z$O24}|kwcY%WJ+fi_qL<6rQV#!X0(lok)Df1IWW=e%UsjQX63?BHO)U(8%l|B_8 zsS=h^94f5g_2m@+@O6_mC#C~Sy||(59fOW0Hs~JgUi|rq1!klI4GJNVO19BDbZ0MGm%1JPpE~q<^dakvA!7| zD>HMAj0%YNNn1G`;$=a$eTL7y#}9dun0K9!=BfUslKresy23Klxtc4^)Y)_3}=oP7HqHP-LIE! zefm5Zd|t@o)s8%{jS8cBZF(y{O8f2xaHddG{PZcE796*ttx}wPzql~f$41bUE zSSMb7wx7&GP!}yl5cLT-Ux3WGQ$g22DAe)5$JmG%~> zMH0yg?&xIp5H}w>o(=O)cym8<$*NQk&rq3osxN}7Tf8m6g{cC|Rd@Lt%YDM!ke)RW zDBC3g_Yw)kjbI0>B9{2+$XB6ZNFO=!^??O4%bVTa0!R`AqSsMVtXZRxqSaaaz0L4_ndVn*@7za za$N%15<4?7@?7miSI@(h@}yz4^#n?_(jnwDAa%hQ@^z&{L?lClNtN9{=35*X#sB4yRsIa!YW7 zomt1C%)sjbV3DATW4d~8oqbm4;J8nfFk8;(f@eiG@SDWzYtfqKH+JPL z*l8-%JBxLT-@xlEMmZ6&f&^H-pt#IX>09c)rS2Q+{?`TD)#ltPUEY6&Zaf}r#2KBf zyXRTYyD)2|_lQZ21JIPRt8dSPvVWi#>&N`sb1pxT$|x%$u@GB*mx93ac|uFF&6ok% zPA(*(pcX!+RqM#bT*NR>1?6b_o@R~nKgKyFimM_NLr+p;1k5HhkFG>) zBzc~Ld?6*qY`k=_SbP>vcs!JwnCsFS6gEIFMKS%6HCh#vg$FOr48tt28Q?ysjm>i3 z4UI8WuR9^C$)Vo6Y#oa%fRdx_bzb znqdfOhIsE$_uf9ocYJ@}AMf$_V|2-yweGm`JkOhsM9Qp0%6HdEliuG@K6(A7<~89< zLUKaa!N;}h0-|Cf??dx130=Bz*C&Ql8UcXUSNYg@wfaJjvYa_j9ga6BQ9f z-6M;-d(`5wsXcgygXv={o3KLF4b=DhYv-X-Pyc=r5>AqPx8*cFjTSL9)mqaB&8x<1 zQao9=kI;V(zub7|;R{)wS699{%X87b98LXNb0MoDos#JS{eAV8+#9Euq93Meo)xy1 zIUMxpm%zJ95aLQZhJ6xiwsxfo2H$t+`Q*)c74#cfL4zoNUe){e@4xD1gprVv6F!Dr{;VTMjFXXYt9c#N+><9^y~5rwF&qc`JbQBc`|aUZ9VyX;mAK) z4L0L06>;_dZ|(-;ubn4j%CwqwdDw5uUJ>@r`7AAGCfI&C%vvxjacFeTWL^)!A2Kmp z%Fsv_U`49HiV{uu-U8cUp?N?`wqdg5q44IHiA`z%+v7g-n(LPZ(~*Nq=_o?H`k(9V zQ^0Czn!f*8kfROYnqk)8s_)N#P|HwI_xS}B-Tb`}uxsEluyTS$9#;|j)OLN8tdk?T6wvDqfndAr7#!*Bh4yvMkg z`-I=ta7u^_)?QU0O({}z<5EmJ8;-wx>`|xeq3@8g7hIsq58s~?`G!Mw+VZGSMsL6Fr)@IuWvNX73Wue-c&cq4rd_$X= z*2oaM_qhD34kNz}EyBj2F&+#pB(}B*JNDz4E+I!QkaBa_Dp7pmF?=A;U@ne3Ww`pl z|2v{`aa|;3ZBobB&*E@*u+DzC*us4_+G?bk1B#2+T08qIqg(WmNx*Pu zsbn(~ zPI2u83;1ZJB^+hh9&;y7*e^+-j)Ly=Q0l#~+y~J&j!ziP)7B8@E?yUpDRVG*KG)#d zDLp8&^W$XIT!K&Bnq~7_w*CB=ndARdJmlZiAdnl5dCjIQneMm0`K;Qh zZodrfy^wYs?x%qCzAg6dTT3n!;ZT8sReO?@jSWB;ABlOHGi33ySk zp^Lc@gPb6py?wIe8GYUCd7g3IIFDxLJ3Ai#4zAU+nO0AAaWw9RtU+%B-?I*}fBxJunT=-x~?9Gxv`4k2w z%i}fLNifpZFmBa0PWR<;eA|sT;EmZX$CcV~kZP*3co(jSz2eIEbV}0}b zXr;@ZRdXO1CCr>c*wq^vulCy9nt+0&IoPB;yEd06oWPm}FE+^!%+5)LUO}QQ)$P(N zmM%V4inw#)+E=7^#hOW~@*|hUyFa5$;QtH_R!qy7$&E{}Fr?v5iuTN=IG8v*7<8;& zRmgB$5Jp)-F~{wgInlALa^? zdIXlC3~a`i1p^Ekk!LrUpFY}-NspO8BcP?R%JgU`M0zu7f2EP3L-cU@@St0z9<5#Nx&7{VIcFkyC97e@&3CGL36{*eS_I--Kd#jTnnT?(~vu?dd zsRJ$v{J-!B)v=q)5E^y2bMgwXbrh|1*pDA!s_x@vB9g|k2GyQLYyP7ZE@nR8UvkGK zR`FlD^hLb+a2Yyu?NH{1;+z9E7KeKmsv@dD*odEC?z?4|iSu|pUgMLoikKL!NjNgb z+!-U%T3MLw5`IPf(?a<`!CK{#Hm#04W?8pXy8lvSa)+I_W01dbx@$X6~F$c7MS)@?AFhy4K9LccWv|Can?t9j*_@(p{sWjtpkF+xs=iH*ZVD zU1w8^`fCj;oK0hv7nVr2^mt>sWt=Brb3^^hH+f=b*-^Vt`GV)S#i6ZzhBwUrx+V4P z+aQcw2+k!(#?fhJJ^Zo*OJi`~!1lY!c;co)?z}#YkQu`@#@ISxkJQL$@)!;ViTIK9 zQ7M&|LN>ikG<568wNG?{ZnxUR#yuNpUT;h(a|HCCYU91FHJ``uRBX&S@TBn5f%B@e z+3Os-OpMm7`W`{Y*y2_YzzRhz+s@398hT$#3(yde{``=cR=?a4PmbNKy`|Z&&366K z)3sff>83Qtha8$4$Z{~4jvxdDRf@u!$F}Y{(AWz}f|OrUKEqFal~KZ0-638#0Xo=G zVO-``)2T0beUvs>D+P}FWWMCj*twXT`pcAe==(}#Po?52)aQSKe0H<>)|;~;ar@Kb zZze?^sIyQG^G-TDfOKZp8Y$>;%Li|Ozsq))mb>H-VQ<@%<)2OhZ;oLf&zOWULo#EM z*FLcwR%%I#&mDf$J3>aieO%3Y=YX&*$?S!AufqI{NgsPIY0ISM5c{!E;1ut==I{x) z?f^j%Y-0TD1PN&2!urQMuj5`P)Ak~gSE9_`x}ZO9$>gCF-(Tnue~438ga+Xr!y~13 z@ms|)B6bo;XN9@<#TKoWH&cVjAVj>Z8+*67!SZX`PaEvn2euDr)B4vrHELvWW9e(f z<4Q~`yv|xT^RLf;cdhl^iJM^x!0m7KX{aI+%#ybzGZMU8Du;MeoaZh-8`emF;Nrhj ztAqQ9Zo+MxOTy!lW6+s~*_u}~pk{WT+?urx$qsUo%7up5DKbQz8JqZHDAm=)=zNX9 zXY5w8s_cHBcpdJ0;gY#?>;w$n+`wWLH)Z&lxEOel|Ztp~^F95e2*qUE^>=GF`U zfEEmVo_xFeos7N$hKO}TJNv-s!Dn| zR4OmO^mgiNbAo?8=D|)w6(gfINMYE1dXNJCtd)l_wK*8?vY3##Zj?p$N@8na?BnYS z$KEe$aO;8K4G_<7q81STgU=K&7PB2O+BII!>LG~`OLxb|%VgB>re*QT;#L9Ijyeg| zpmBBQW;TzT$U;lYAiBQ&V6FWgnTHj*G!)4mg$o_z@N)xf2*+(a@X_r8NisK=PY#bG z%KbCCi_&LB)CPGa-z)Ak972ITGT z4)ZH7`6vCmbg0?9s|v^-Q-spejhPIxWjXE)*voh*cq@?6j`yFsZQWG<$&n&+iOQf| zMZ=3lkbj>_yZ@@r0+U~10Z7C#TI=}H!Ac6_avoe`0qYGrOSGl!Gf|2;^oEgzk+4FI zO2Oa*Yxo0dhuy;b;h^rLeIn54Vw`Koy|soBd|-eH#U~>&gy5guO)ihD8tvwjz-T3{ z%s*o`a;{~21A_})MvyAXY3))qVlTY2?6jLrUQ$t`^Vstd7to_5B@eyJnF4O=+wc!R zh)a@m7Ut4FUn(FIBuWuM8;5w?>!UJH2o^AZKED64s-{B%2l36-z%Oa{-9TSsRS^eq z5MjMpc0YXHv^}}K=2~u{ZbPk)fMZ`~xB8`9V^zMVO0d2-Bm03|%l6D;4iem1AM}Nf zATU{JYtQ_dyY2*brLzp6-z{BI+qy9joGUVIz^uM58Q{Ow9Sl7ixAi}QfG-Z(jitY4 zqAf?LD=@?RppVBhaZ7ZVhO|(7wB5B58~a`OeW5|jPoJr``#*M=I~D)I=a8QPPNCYi zuTT)C219q{#?Mpg%m-Z&@LXMGBdpNQukuXfF?*5`s9TF{IJ|Cc9?YdQEK+uwXt&o&2 zfkjV->1ojW!r!U?k6l5*r1!<;E;VYF@s-5sWj$zi#fkQuPJLgrdv|BSc#IWQK z|8V@8mpF4#&12$F(-K#`)}e&T6R{h(iKs`sH<&xQC9RiMr#XAMWT8ViJjF%uLDgJ( zSM>VQ&n0=y6qd{!zPDsncrN%EYKI%zSJ?!S=*S{l%!rNz11=ySp}W{=qE>jc&-}># zLDDSnoNLSDc@Q)DR(wzio5zJ)!eof8sP;wU-208zi?)tQ3Ej)`-_{Be-v68DUvdL1 z)RPd*&Ykr{=Ig?dEE&TfQ9sZA2ifZkBS+y1LMx}v&6mdPtb>ADQlw==&PXWVjn`{y z2@^k(vTy{^uc9-A|7SB22@Qg7Y!I5w0GUr_co=Y+q$PFJ>IGDR!zN7%SS?qCfbsmeAQO{-P1wIB5eiG-}lu}jx; zLhTlo>s|S0=4Chs>HB&)2;bHO|6cg3VBw<(Z;ZH;VHFI!v>%vK9Y;#8ZZz0VJueu+ z#l$Dn%H&4qROFM0gd)+7$^&`b(d}x3e6oJ^TPHKC5Vb63Uw$UvOGLO(*XWrXlI|nQXC~ z+0y4|1646pdN)e^AE5s6?d1InYO0^aM4mr|iIVSu=?E#fjrRsh^ooJ7PhkT$*M6;) zlz&5z=i5iRLfT6CSV?(!TA>^J8W@=e8m?*C&S*DX{*V(V&>QbaWk7-Zk4%sB@1@ z8m5v5I`)p$s!x52uWLC+l8{GZd#K+%XDCOEd5Q3r0nM zQt);{ZT^-sMR>CEoODgOO$6FDFXs!7nnz;k`|byil44n zOrEWshkfu!%@u0ymVdC3^tgP%FiWxkJPr4jhAqrn5uHF4R-1L|jpg^MH!$g)iM2E5 z|E%@JbP}ZZqa`u#_@`u3GV?j<+3XbqB{mwdk{V97l@{oN$ z*C3y*i1d&9Q(2#EC{~sND{c@NIo^u-ePb?9$Z7d@1?C(Z5Uimh{^cq~%5Et(HW7x& z(@2oHs2-J6c*m@TPi@fNwOu0dhQ+Hjq^>eY60c_F&DzQYThPF$ z)T?ExCHGA$G`zr;S%R3E2d6km%h%@=9_3yO$>-t6V;`5W- zYJ-)q&YxX`HywdI^0T7lhWF2F>Ay|J{~<8O@Z~6)wvh3K4&jGMOp*zlfupx^(Y$~P{mkFG_V9q< zFyED&UM$Kc;Z{gSK|8d)Ivu~Fz|4I?L>|*A!>g73K||vp!obnRzEQ+aO$YXo0m9P4 zHT{$HOKnwlNc$7CRz9-CI(|(tyCbyB^un65PT+;LWm;1%%ade=y*2%xcl^Q<&k;cn ztMn>?+$*8(rbB&qUmmft;S=Z|*|SWmuQ0c?yMfCvO4 z>p67W5|*WjebjwnhteU(|8!TdM?^Sm)<0$N-j#QHNtp)kH%wKhDlG5XX~&RhJo`W^ zCm-wRqw_U?1e)FL%4OKyC4hIt?`C@!_5(O|+Ly7zCMh4EEt-c-<-Mpi4+oIMoP7Fy zKWoaGQLuoHUy~SOXq8Tl@iOYn=jiRCOW_=DOq>;{GI^z_dE_JSp-7qSNPdHXXlVd| z*;$=Vxkc_5)gR=BDb5?I+O4&8w8PMP_n&%r1yW=evJ4i=F*a={;;n61ZCLJxbzVdV_p|i&Rd+yv=e_e8-vd+?2A_} zc-@9B%zJ{79(*RroB;w#gw8jqFa@U$_pCPlLN0WuHHpTj`Gz`M-rJ2c_ zdZ*nFkK50gU=Zdq5~`^IfixaAC-O$lwAv_V6-PR(U+y#bp(=4h@`+_IuiM}qa*S!x zj9U?W7TpVL2N7*X>#g#fR?RqnYsMPt?QoYQKXo5!_3|gBKV?0@-_KApW;T;VD+5UO z2l=VnSCYDd)cdJ3&i`uE8Qn-R;%RiXJR#pB=xES1(|7-{^#Hr))CUx4cc?`THRn4A z(sp*xdWQ-1w);7!Yp0)`jbY1|)jFajG+_NZmXY6qdE8wPxERi^PIIEXlA%kp@?F;) zWJ&(znah8m04Jjos1$TFDgL>Zu>UONhEBKJ%L>yI^%bvluob^ zfFM3ibDbG59^&Gxw~4pYD&7V&zCC8Q&hm?Co&}3~o!ct#&&^@Z5tI}@Z)ARx$26Y} z!K-F}*fSFEr8y2panhxr+bZn63kz)&9oWdYIQk2}cxRf6AHgs#EQ#!fMxG~?Bi;es zCbn>&YZMayqaYYxB-LNdhtF}e~zt`*$U0*(YH2p#JBiaF*zrM@KX!HaYpK=7qJFcNXDw2SZyT~I{ zE5GRvPG_?I9G!9idJcW#PCQppBxLdrDFjSx4;Uq(`;i_wqoOVH0?-t^Ws~GHuJyeq ztwI^}`?cQ4`{6vppPtd>fxjpJZIZwMV3&!~4R-LadQ;>LiD}v<2oY$%V{{Fn)-C**hK)|mC7D$ zA368ed>Oyq0&68te9=w5uGD)cS%t0N5t+WI-xFgzg9K<&(@43KlTxGreOnaEmA~FS z%*3hInSZW8o&=eCvSM?@4v)<#C@XUqy^I+;!}$BgDRN7wJ;s9T?%R@RA*%qepZ{%@ z9$0PH7sNLOQ7l!?v1j;u7Z}xCllwjFYh+vs!G+VF1WZ6 z*pz$RNt~u%UNMQ<_GPBBvL3nh`|EKqz@+4A=jjhXH9j8i{>O6D0Tsou?p9drhhEUguDaLnYh7%M7Ue`9VCm;kvqSh`TN0DV3&u(rx76hxRKTEZ^i<9 z>J)Vxi*hqFgZ-Y|)00>9OEUKXb>ZH2y%~D)|1<0JWZVg!ANh3)>$A0Tp40tanR|kT z*4-CyW0fesjeebbvf7jYwEJhxU>8AM#+Ce40@#cVIRJO9`1MN)S)Hn{+cbTK{hlK= z_cimcjH4wsVf3t`M=z2yhPs?G=e$YQDYX{t_wyS!7;44j(U|wYq93{TBmkmZuo=dH ztVD{KO#bsG@XqbyKrxc?r5H?foh(N?uNXjiLja16UN^IN^6S2a)7zV)PI+MI(yd-} zg>A-Og1RzUc!Xb{tGEgqn+2js$6bQmy`)$C9B{ zx&-}iS2aHoCFYcXac-n9^WAwYIU8jbYGWNt@#}}b@5lsU?{0h)J(%i8TCj%VL=w9S z!k3MnKv1u<{=P|=tnOepCmt{hqHgnQcB5td5`RsB^FKia%$c0%^?3efvHIOEB)vHac1EqF4M8+x4V|l!x$z=Vn(fojcJ)!cf1_>+R{56;Fx9uis zYoq}J>^>LoL21?%e1iB!P92KVf=2eswS;_rz2eV+g|h=ZVmZ^*ho5=0vdy7V+kT>* z=!RWZ&UIVpiQaS_DY4lcbL|`kBt+Z|L13?6`(27${_^D$aPZ>pEzbSBB*-Xg-<_Gr zj$j#zv*i>1RdCmK5$zJ|?!wV=lvN1PQ%=3e)h+r2h-b0UBC{YSKHV-J?ObaFZlDyz zxRGZNv(cHb0~FD>NsylzJ@+>T9fk@`%e>YstM-1j=9xA=|5Y2$#R1?}d6vd_RJ3;poGH{e_Ig2WhQmMQqK9twpR;t@w44`AdJ^Q8gJJ@lpNEt{Q?Wm_StL!#AoAlHV--23kQ6i4o$5x7Oda-BzQhYZ1f z4p-8v;`-^`iA(pR0^FaSH}=~IZ;uvg20ZD~hYt&5m9D<@AI5)0;m?||IVx##AK(a^ zlYtESxPd%r2ji(-2H8E6y2FDiSCwyJ+#y1CHK3h=h;j#gaHn)$(6hf|UVSVH5-r9Z zL5z+))QjUaqtQDVEKg!+DxgDuqMm`xW6VW6MS-6Cc4wk26k)qucUVi$a^o{dx{E{> zhK%v-FTXA%KiHmTup2H;6N>fSUYTk*E0ywJc!Xe_4Io6Fv=8crgCwd#+FuIjo>Uvk zYV7ylDKFr>^JG0~)nou&t{%#Apbk1TIU1w>S1Ia}?ZGV0rRVMql4B%1lh z?!6YQoqu{YyT+)-dt?6S+tOcO`5gYlHkKKPD?or?(%JtA3H@c!obQT=(mqNs?sqCl zV0X%F`*|`b9dbv_LZmHGR-I*A<354|v6eo+zI6R`)J>O<`+y7-k=~a0n&(H@9Qb&L zu4?KzYd~B5(0|3t2_o+)=Y9%vn*=#Tb4Ae@aQERnT0HKo^w4k*Q8042-7LEZ#0M?m zc$E4tTO6W}bL+VW)DqTqKzm>>dM3j_{hdFs^--X1;mD9qHTY}b=RjzhvnCcSJv2wp zT&rKIB{=e`f4rSPWbIykzjhCZVLFbegq41)G_LdiCLz`IjD$>&IQ9cnw*w}k{& zPOMPy{W`|%l=RS=l(A>jr4g(ol)3U=QWxzTDb*N20B z?ZBYYQd7yDmv5MpGrp_e+gWqyN|HnJyQI;j^X&9gxJ=h`Frwe(u90>!(Cj6X{F9;} z&UcK&?JJ6%zX;Sl%0$jtyVlo>FcWFK2!^fNGIcVOd&bd1joR~c7wQ5f1G_z7OxN~e z%=Mf>=|U77kw0GiR?NUc^{=17oQYb*s$~{&GU}(t=O^mwh}s413g;<95%lz1$+&AZ z0OPJ439)v7;z9*~^#&K8KM7a|9@4d*z*^!CGU+Ijj-ja-#!aK^d57nJd&#Ki3F_dd z6VHx<)xN+FaG&#|wSH9~uw3iO*(|LkvXciJ1<){1^i1Ore8I$-GS-oyk7NOLQJLMK z0Pn+8#XWc7=hD566AwOOd)kZ|W-oOnChUUC^jZpu2Nx=O`JdAUY zeB5h}tvCMWx9x)n7A&9$iI^8k0FM3<<5%sVE9VUqLwOdh5vv0tyMh1gEU0SLiS_L% zU_P*ObeTW zvu#GewhB4`-oN8uyvXeCL;Nx)!)(;!nZ>AL3;Z^Z*5V?nvkVBNAiXd5!vh|C58lU@ zPm~?!QWyeJhRm$Ud&Aals4#hLIqrAI^=DQu|3TQfp1?kkA7huY4y2@im2-j|5Vf_^ z>s|5#)n02?-bi?8D}7@|MLX44gvk7S;V@Ql-NT*Cpk0I%;5!`NUqK3rvh(|jr{{$f zjZ3WGyE3b&jevAv17va4?Q!BlSL7|@{&PF(i}AoHdhib^L18F<{8xJe^5-UgG%~FJ z_IfD@aK(>jT806Q%+bA3Ts(GisKg}&Nt!uf{eCjgR!f|XRGNkD%#QR z`{$RUe!FfyGvPYl(^cIr63Ao^_fVL}YwcxATN5Gr_khwN*S6Hw-S8Q$cDnuWqSHlE z;~lWZBh{6z@d-I?-FT0&_fJxwo9I@wV!8jmH$b)H{c7B@h-CO(ez!(?u_5_;+mlnN zL&)Row_`;e9vB1k{LMGbEmg~v&G|rL(n861 zo8gY9Ys)E|>$X5JQ6wIkrWCf|tjg9JT2Ncu{QOv{VBOx0_H6-&?oSElWTdV(pL0|L z>D&3-F2($#Pedsn@Wx`0x+!gqtweMw7CbPBNTRY&kH4k!uQ2iz0m6vk1Vr)6i@zGe zW=Lt71?<7RKmqyl61`3r`~7Uj8sJr%gptxLf?D#(G>FnKwQ?@E`?oK_0#0OB$xJuB zEj=Gdl`*xeGuM&+npe&Sy*5j%jsZ(aVewVvUQwPwxqkAkXJkT_f=A$`w&5U1>jLMk z;p@2Z%f6uBR`w$s7+C&K6tT>zkA;Dv%)TQ|TpMMn>?El8BrV`{rbopTB@ijOU=tPq zeu5dyP$gT;8gjdCjYMlgK&XcEo{LYv*6pAwwUb&(t;l9Wu^?Ep9;zHKAtFkpC*Wk! z9wRaUzg?{o5V=Z!dps zQUYb!heh$STND6De;@C&RH?n(CWKntZ+gRu&*sf9Y>$P+BwKBz>14L+U!CTUnXxxuoFU`WW+iM}CmofTA#w@+*XMO-fEJX8wL zsN#VZuXwFfcES;#IAzwG@f$B*lw-OKAG-pBeQph?|ssv9r*jgG$v(pg{doT%7znHYScgu&X_e6{1 z816E^;qab6U$ydy&b9W&z`t$)0`3Qp0aK2)VS(!wk)KLU^!)x(<;|$4EvQitw#zcx zlYy&!{JY=fAd`VyJ$H}Jge;}EiPsv=irUXlg};aY0P(D>fkD=u16o%%*J&FmKDAv3 z7L4==m44BqFP{WPXF4Pu#>XlrHRG;LFHp&$E^GE#H9-((wL1RKZ3he zJO~!W!1>K94wPBNVs1gDASmkx8dl7|Q*UmGZzw)ycPSj}a@6$kQikuRpoVPbaSYY~B1$Czz_2{^-jqQPc0Yb2KX-KQC~240LK& z3fxEQ4lK6TvEc^tZ@#&6t0vg*dgDu>!AHe4W8;b;?9#-Zc>o0Xv8DTC4#o_#%J=RS zVf%BM;S=+Ju$f=6VgXD}{4%j!B4>;OWS#WpklAL35Xe-3KdFwuTkApnBS}VEs}RBt zv3XpgmO0#W#r34U<~OXkCfWF^b&x#yM{5v=uSq$^J7?M$K==gj;o>O#YX%S}BqrQr zg>V|c$bARa@~h&aJG-r8UXE{cNGhXHfjyuVwDDv2tUr|>WCuBpn2UK}e|)fi9J_S% z%<6jY-5Tq~FRK5L;^sY{p_igb5Hv@K$&$3&Tue>Ze3w6+emHfVd&8tX7j&uVYWqOw zeSb6ghRk0zP^dnLnOPo!fxznO$au=t3XG(Q`Ew#t0kOm3zuk~u{j(*NC-Jye;Z41r z4`SnmR6q>ut$}v4A=r0+j9OpJNc1lj)iHK}s@(C9%Q7ZCeq^er4=;3EzdkKck`G6p z6XAs;8kt0Mr0(M-5OMw&AN6j#CBr;kRWKZ*XA82-#_<{w8)`TPU7B|=6WMo1A^4n4 zd#sr1S||V#M*OzMalWdhi_FmKoePh<=dO`48~YZ4lLCJ3-FKKxKd2C4q#_`*hsKEA zt^HrE=L;W@87n64xB;-|(bXi*8X#!i1buMxW0anw(!M&)3xJB7SMt$)4tavLW;lDZ zYe5Y(u=ub}nb-H`@@+695zpG5LpF;;nG{+vrei#qU;~PUZ03nfm+7cru?SZ6LK*Xw z$&>&@yQU5V-*t9q$Mz3oTPTfIx@MqW+^>5Od!4KOyHjV3g~!HX^lr^^?V(JByqSUe z>6^>dYru+=(^sM*v|)2%(u~zECu*$<3;s*&p{ihOb~dka-6BDrqrSoilFr=seDVfx z>;Rt{rcw+_+!+(M)r}s`55C{tz@Ys+7NOih>8;eIMQa&qEksYOh(nB}C7OL`#~O{s zuOfcjNf+~;v`r)|tD=fsrkkz2kDK;=eZSeaGL=;jz23r0%xM~j>?JV2Pfuw!r$c0$ z;4kyOo;!cHAPw|&o1oAgi9Sz|(jUEFvcaRs0hF#HuX^CZFK6YT>LtPo(9(juer1X$=aC#gS@S&6N378yT~?(+IFB3 zH=Aw_VSqlLcWq*^ifS?h2Pj~{gPoi@dHOR_%W|E^l73S=zp@(RGH4}MYlG%FKngLj zq+(z%A)@UG(mtV|F=oS;TI(&xS#tRnjt8`i8k87Aiz#XXNYQV=(#Jm5(iA#UOvIUEt|VUPWjN;{ghH z7vxR*Q>g%z!=;BR{-Jb!8>^xru+z^NkM(n;DwSNqKAU?mMEk>+_J}G46J>rWkyqw||{PnWFLK zZdZ5Q1%&m)_~{@iXYJFptwOdVvLmXF1|^q7aIK)Di~iNL1}mN-7rYLpX=&D<)d64cL-#fL2T=tM?)c(&y7+0>q zl9rCY`U0Zx4n!_$KV*_}H^kksVX#qgqf0gXyk4>SOCjC<#M&h^E*Bh8_$KD5aOxyd zmlC^x^MWePUo!FQ3-e4rFrNKUwOkj{;=Y$JJhMV~Y(M&u&0+qs`Tl;2@pLV=t0iPl z3cs~%4TbrYS{I?(yxL<%Qc@CHObA!Y?B-OeO2+lFAbB6(Hdpsq@i*~xorxmNl$(q3 zyQsz)ydJ! zdEO5WR(uke?`e2-ir03BPj#qZ&(ajqZu@B<&TBoBmlS@D|K8tq#SP#D?_JFK0ia-p zta0yJFYSC7CmZ6MHdHGN4R-cGf?vkZZpy~))|(A13>Yk?Z?Y}sqK;7*%I>WMD#zXI zzIx||&!)Z4Y#Q@o?-x3Jb+QL!fESIFXf;25c5xhyp$!*!FF?M=y2v)7pz=CQ z+BH*+Ys*kf$8(Ymt+ z&=j24_psId3zN=Jyx6!s1WHqv2w8wyJAmlvK4OzG96&*5-&eux&=ky4M(EzOEEn!v zeL<^d#BC_Mu61SOkg1Gg$A2VoLFDgfaN`6(;3`0kVaPOONmx`JwTg8p*thXxWwr5w{tPlZVpYc2Nr?DPjuP@ zZuT#x&wm*H`YnpI#d4)TJ+c#=NLN4X*K0PkqzqNZB$os@es& z1=#TS&1tLslz|%B{qe${Fd4)^9ifD$Z1)Yj`l$8>U63xaG&X+Ya2Wq+v=9G1)1ehw zezmqJo7Bo25h`0|s@wfcRxkY6UE6^}sYB9Hoyx^-47Zx>qo3amQ6Y6AKFP6lm}-;g z;V3UlvyUFZ1RSH1BpH8DRDTZpX0_VNQeuv)&CGQ zKc&Yoj^)Ok1&%&Jh*#ppmZeolALtVAqyAiLtWJO9p>f;KFV)8OAnpID1~|7st?3GJ zbR8iNRWZq6E97vn!VXf7hMf(qLRPTGaVW+Qo@IUhs9f4i+5I%C{IbesX#*&lhIe$z z3ONe$tOj!W-w)ad^l3c-(%EGgpy}hP#qn;O zak?~agw6H1i_&nwXU2 z07?+cW=7z^PwpU!^jCCwe>`1utWS_}>vZyZ)X!A*AMVB|5AxEPN2sghq4y>QM-wj# zGthSp4krg)XoCB=m&Hpg(HU&6ekz0;6g_$dDJMt`U)>3FOlOtn{Y}ZZNj8V4FR56PXCxYW!;s4y>cQL8G_v zi6+)b?4mc{jtunX>z?=iLNF?-mfSM0_;RHAR5>D~6cs<$|H?b08vRs&c|KIIv&O6p z+Ehgy;BQQbCCi~Bj`nDB` zYrGAP!@+KV2jAvC!TWlZE;}`Lc>HUNt{JbHMIJ2J=hN(e_2dNr*|FbK9(V=|rLiya zGnEG_K-J7Lr#dF_1JPJW)-OWD(RZHo2}>!!TJ%8TS_DAcx0N|n>5UHmudbg-arR)RO7)??Jzn8W+nosZ>Vc~K{GtBmRS%_47e za04#vkK2T5fkIAii*Nc?eMY@%S+7hff5#wmSwBsWR;!fFNM<>{m_cl~?Ot@GHy{)s zBF;8w48>c{g9f6Mcw#P0RmNubFhyVONJ7`}i{vZhxVMx@Z?_4#Y@^i*CjCkQ1efHY zUaNb8aqG`>4~ibG=|o{;s_@IZ{r2st0_u21r1w+LMv4V}X;d%Q({o??pNb1!d9XZ; z%Gj9ip3XFZ%b{x_HSy@)R~78_6gemXSP{Bv{5@CeUpeM>xgf_pNcWhmAoOum?hZGhp%X?P3!p z2m1`tQa4&TrRPaiDN)CJNrLDGuI_waqwertO=?#YJXpE`<&0T8;Au|sC@Nq?M;qM)h+k(2f>!8$dWyAj&U+5T~Ql_zGUjJ4#7Vh-Bomv_?%epcPrTGNa}1_#pwBIS&$^Bb4TJeEZyJw3;! z+OAkc+M|`Wagtp>o%ULHh7&zRQOeSS z8;w{yJu-x`p=HX1D8aH+Zxmwp8nU*`xuRL0>;Fc6IeCc?P4M^GHc;R9k8!A6-l*(j zo}koQ7wdUTICf5)FjD2p11kqRfWxS*KSlT^<&rejQ3*QiyFK=Z`?a31wQ|KS%S;`tOvn8;nf2U2Hs*L+ zySpAOjC_3-2C+?L{?4pWp-jYOwJl`Yox2@34E6$t1zFq1jc3=s@FmQX0m0s5+iV=f zJJxt#zBwv1^pV%vjM6S$(J-ctZGZI_95Q>Fd>(t811?G2scui1JIPN=;VAg=~k2dpOlt|wH8R*d}`e->vdVvvPbLufliRx*yDn}~SBFy5s_qzM`b*}NE z$6VtsqVFDNKH1+JKT=lb`%;*dufjG(tIFIOyCo{+oaRuuu$PH=1;hv?*;N?m;XuP~ zZ+v@4uFJe%zh9!no_6f6e{AM{Fu@aN&l60o>*ST>g^TmqH zas!xXo9bEqCHWb-h}l;T#X|m=r?6o&m8Kgif{Vi~l8lT$x_b~je;$>@m-OCXD-T#_ zm-ZfltP=eq&~X_ie*LbNS|RiwvV?{%`w1PZCu2{oq9Q|juOHkyWwaR^KeYR;kA6`C zchTVRYiU`*&*Zs_r}n%8wW^nyc&pu%u{UyN$E<@(DRKf}Rf$qG(<%|Gj&o4eQnySQ;vhNbd2cn%sj_PK_u=Jb+TTX> zEqW*ZQpx>+YYP-Ov&nevePS5>g76{O%}}qIJ7^gv1}&LUpg#;-xCSa|jozTmgZ+?$ z`Xx$SV9?Q`eZpoMT(vpf(#-p!&{VgX#tOo8qGV$0Y^ui3OVIb``(5{IsS6)1ztny_ z5^2MC=&082rRexx5W2UvpEsCj2CX}>xomYYoya8oV3TRI$El$F2QBsvPB=E9K_`qW z**^Jovig_Mb}UxUCK4bZd?z4l8)>^6rB( zrg@Gv&`@oHPSl$?n=<|%D#)bvhYa!0=0y}eHkdNk)OyabyQ*H#Ewh2CID$lVQw)M5~T-XT(Bz`KOGdx`PpxS%jx=r@k+A(y_(r zCo|6ubJz_=TV@8?0WsC%1o*?OhiONdyVoA@oHPEm$>;Yech}|mIklgT*`-<~c6r4@ zuJQkom6Kpfm_%kJE=DG#phIkpt(`+mUU_&K7tg3kn&qX@VQ*vaW}sFPT-kLrOOioaBb82Q@qz* z?={I8;+~f!8}mx)rY4DfJ;!$^Y3bzh%LU6iM`6~8dr3?AH~b1a_z;Oh*L9`Zypo*< z=kQIw+#{&QyXI9VW8!6&pnBWU{q?+IBPzi*-APT}sSg3&Z5#U9=Pv)#1dxz2fVP+Y zoh~`jntHzBW5MvU$~&3YFwxDR zN$7+Q%;eK+>Jqd&RzD`tGrHR;fam@7t#x_lz9T0*Db zHi;(~RQBDTVUzLi@3I%&ZIUt@wUV{g&b!qVuU&Z1`dnVlwOH(p2(b9#s#I2EK92kP zJDbdT+djN;?0blr=(44{!Mn<%8qViRp}gkhSJIWBj?*vo$vF0XE5oq_ADOVUSM$52 z-tJ4x+dHURl^hydiVi^34E~h)FzWOD>!y&TpzlEnljHTT&*{%S0$QMEb-#QNG&SV+ zhs=6q#(aP}*?p^yqY&dHYd$cUy3Jx2x|LcR?tZ^v%vx*l=JW-H&}GNx&~KG2QMC*B zAj-3XasZj{b*QQF_Egv{xctyP4r=W3hVfex8@hO*m zAMaD~FK=QxcA>*X_aX&Ek2B}R*gOr4HgOoH#H!6*ENJ%%+AbyLd&ij7j9fR}hIG%g&wb#00UUSan z4pBfMdscd@oBM!%@{J=uGnVk;iip+qm*tbT$*r?5h=1zTo{Kzo#Xuj^EY&hv`$i$u z#{uSESC}N0RHZkwbuAttGh1>)-(&X)cQ7~|0thNOGzKqO%tw9hBVQx@n^5H;dXO%p zXLU~=FC+QZwx!Q(qK}Eym!VDl$=g57@JVc2WKFc_)^$^^#@H)n94rHrg*vA-1t#fF zy7lGHeBBd&pY*fLy*dB$;k1GFqoA> zgtOeT&791%HaqKy_DO7!E4yf@$W~ZcQ_t#~@ss^qO*JnfH#b55t5}hXY5eN8^OV!o zi?HuqLP86k7mrzmy$gP?4tP#pg-00c(*-H*o((S=kTRrG`2>(Kqeihy-_kV8J*62l>oYURScozHXRrURU zLnZa`9YDx$7KK3Q@k3+I<9blELJYAKzK~5+*Q_ywt_@&Cvr@mcYT?(dCn{wl2l;=X z>+H-K)lc8gUF9Smvy$Q(Qc&>82&sHyZbp;LGJW`PQpmt8)${OtoO&?I%LzBUM>p$a zsQ=T9BI2Lb$V$^0?z0<{u#@?Uu*w*SwZ4YoF_kht6 zkDkZgY^~d95K+Oc%`ut%^y@+j^zp@v$Nl@;Gd!mji#~sR>@b^I0Hd`$E?f!Br)u1oKc4MmU8z!x`@Q@_NZH~M}FwcbUh&?fP zhzU9D*a?X~>uU4)%rM_DAHs@SRw;o4?D$w?1nukT%UcIS-=AJ`zOOouujd2WdMt)B zY%z#9YQS*n(u+p%8dn~SO97>ZvE|p>B!fB$L=+)D04UTx7rh=xiq8x(^K@J7t#jSU zK7KI;XxP6|Fb}KI4f-LzQiH`hd$AM4HQ6Y#xrQS-%7QIxnWq(p-|1wNTj$T#YhEjp zL`2SxF(~fN*2#U-8i4-z+&M&5TmCf%@H*Rdq(piq1&o<|>-5j!_jrF_{#q7WXtS^O zIhx%|J}F6fSyQetm_j<76ow{1_D^f&-*CrfPSuAbq%#*u23T`zl_tH@5S>)8 zfEcH0&Rh1Y8|VJ`jgf0ZFe38!@#%!U?l0v9@C_6C!-)G4fT`(OBDw88QNPpWrM{{f z*w?TOMV`uP2+8d%_xw#`0mO$Kpb=pDmXVX`$WZakO;Dn-HDDe;v=F;r3h@M%$iM6X z{8&0H?ORSYI#1KF`k+klQp8ihP9D;E^~Q`vI)u!=rWIS1n1DEeUv&%DJ+YB5Zf0P& z$b~jZlO<3?Q{Rkbb%k$md@Ay{!`>{PZQ7DbS&v!L4Bm6m4~@+Jo*V}%e3{mOEH(AX zz#fPU`fEj{J-dp3m6PnT+J>;#l+}Hy6EK*IyO(mHqaIc%$7e6GE{%SHGDLBpVrcA0acK z3VWKlb1Af%YI5vMo$iiynS&2jZ3w(rYz7(}Co7D)N)3{u7}kf64#3Z77i)k~Q*#^ry+j0`xP z)ezPW?iTp(O>+V3SCAPF9WrO3yu+%0SvPINh{dj+R@HG1A6_?J#tpEK$o5>bZLR%wNLD zIu*z#t@##c_#Aoy4sc!DOrO_tX)*c`i{YP9H^!Pkh1-Yfnh%Np;x+#jHzGm2{o0^O zq9%}y%lyRB z>o|<*1-~ogG?;RB{1#2Mq|o;dFv}a~UsU4ZMZQ>QbaxL}w+yGjq{ypQ>)g$N|kx8A)|HiJUWTy6^gU%)a4Y zucz8GOT?Ib9ngdW`p&QQp;`_a2Gv&W)_HV%X1LjcR7qQlvxV*>FlntThBV5oI9pHR zUWP9#xw@~qZjV>uet0{`h46J*b}VFbf1ATzEC*XbG)Zq2%d>TDPXN*@fEshEpllH+%bfQ(8?;O%hWa_yp3Uf1Ei2 zvbqNx4${3We*6*^W_BJTYI7zr|8cqRUV$;}s9?cv+%1uxqthZxKByGC|I`mj{_j6= zQ5gRCn#of|LTN*KJ7ebZ9Z@>X>FoP2vI$@0K8o8GrFx93)du;B00YA?Ftqr%{7#fD ztv%@1#%PgI*9hA=m2l|zN41i;(-3Sbm3lW@4==BfE5#JvhqCWTk!fJ8T++`^M{{MD zRgjmctoA;b5Oq+eVd&8doqQyz^@nJ<5}OnM7hSy(r4|dn>MR`s zF7;o3kC+h9x7YKYFQ(8@dun2JJhtiM8SF8)6km&lCB)*^F27}~cN=jITT=z?p zD_T89X+J&=XF%VPlqaH+4;4L9eVHH86(v*q`9g(ZmzdY1g1%dhH-*nG67cdBupiq@ z!(Y+Kkv31I$-_Ju;Y`Zp-ZvMjLb`!n4zQfZk?^TN-+X%T&LPfUB_8zS{J!*rN;zrWp0}c8%fM(H+}+jiKR3v*WkP@%t1%dawvvPq<&u zioOlyu*)Y%*n9|o&Y5k^G8AL2tv($d{sSo4tXM=9(F+`6Y2(`2uxM+7HL#zN^7nqW zr~L^39#m9*f_gnqPD~sMq;0{y@JaV($m59m3bN?WpdcA5Oq%VWf1aUNceuaU77Yg9 z%Rmg+aIlJ(zW{tomX22Y#>mOY$V>-QUe*a1TQSRoi9 zf}A1zCII+oil0cf`TpK$O7lF~edrT|GYbEl#I7%NlKoJvFh^mcnCpT5_Z=DNz=b9c z>(XsVT)IPNYzOn1{e8cRsp{Fv@Wo4@>riaFP85FMoRQgg9T0!!FJMF!`unRW?TBpZ zCkqNh+mStAV|CB$d4!tv=0x_(s|Ts6aZ^>bk9c{XzZwpXu~A6tMEjF!wRv8v z%;TobYz|qV7Rp1kk$K$AfK8Lfq?8N?WK_Al*UG8f$lnXR#Rewg-X!zXua#(|yi{p( zKcLjp^Y#6~&4kC`Eq5|s`Zn`9$GgLlm-h~=K1@oc-AGC}L&WJ~Qm zhc@?kl@`xsNb8Pl!^EIEP2Sw>tnuMeM{KW>gns&7o@FkUMJ>{4j7@8Abf9}Jdi$ru zCpQt+8|9fX7v$y#633Ogra{jo^fl6ANxxrviMulQ%wuGxnhZS>!tll>rl5I4S(wFv z-M3k)q7wZsra4*-Qb|fGoY4Nh6Y()Cug+tlQ0NCAYx$)}^@1;gb4gun_lZXqYQcDL zP;>IJ*B?rtG?IMbg_5tQUAs^b&{$jJjYB5t)Q!rf+sNy3(D#lkWY%??*^Ql;b~ZHJ zl`K^Yz9{&UVQGK=9WH~S0=q6ZZ~@GB9E~ef4ZQ!tnw+Z}(nosYz9$JZXKN1>0w;w< zL}+HQ9+2`fk8Ls+l~g<8+m0{Wd~vRR5sNCJkGdmiNF>>$AshFgFsAC9d!{oxi-YVN z^MkEZ@C{vl{_5N?ztoa74-05KjtoLU-`;j8$STL$fOF!HPpsKG{y4cX-u6M(e5!;! z5Gz}Kjq_(4l0v1?_wH%>ja1)q@S0CU5pB0A>lW+w7D4_4ZBTw*!AIfJ)1GlavQ=%i z9Ch%jG+dU%XDuHH@hk}C%NYz6lw$)gIq{2zZu7f^b1+`n0lA>F@t2D1>|eXPd-=D& z-o5Ls)!ZCydE&M|jbl{^_@u;KR_ZmkWo9sBS64S^HZ3P=Go52dsln^KT7cd?llL zI+faJ@9;1-#aw+K2&Iy%gfF+q`0U=oHv|LFR8%xK6dn~?((RAIH<0hLK)UJRri|k7 zppG>P-oX`JUI{lxZxi14jdfxa$dKXw$qA*(u&(jYhPj9{52G9UcJBzcPx<3E6yEfd zBi4sSWW#KXtjtAyZz-n~LIk##RbHq@-Og8w!qCme=F1rbe2Bu@Ugq|_IT7l-U@l^9 zvo%6KeV!>s_W@D2m04mzN4NED1-Xb7ej?i|ax7Z_;*Qiq&__wN@@$4tsCOi-R7Qnp zqM=0dQ*Y@9o}-n^Un;_Y&)gaOEH%d#$AtO0$iT0|!x+z^^Btng>~pY{W}Z5S^GV9P zJ2?2YwYB~A(KIqs7bm`8FJi47jy_H&*}7M0&?eD1TP3m)6IGBs%BA9#eE{s`vQ6F#{Muo)PqME-=B1+`E{%l|a=x?fpuS6Oe8)-p3 z2WQGm6{=yGl}?Cez}Uv7677btDGjH}^`~2H$)q8StO_ahyx|W#D3`|@{I313pOsO! zz#2&cmNZ>dWe85LUc8#wfX_3c1K!{RS2*en;oG+Ci4}aTz?)U$ASLklD>Ofql+3Ie>=@Y%X z_L!Y^-Ye`DMr}Xg(q@g>fdP%#c}kgmL}~@qJmw6@r-nM9r0vNI!#g_N(KI=9EJwzb zU)_zo#30lPO1@YS6= zM>u!AmUn=T-;HvqsPL11c#2VTOF5F4$J-D(JowEXeG!pmSj!^|#1D(RK!SB7DWR|b zgK*RHR+H#s7j^fV%){?@X6(h>`nrm~!-x0e!%ZXUZ_QipqlWb7<$QCV>yExhR0M_bAtJ;@B4SP?Q}r? zv`62*kE3RXD?_$69b8+AA|XQm>PSdOy#(dwU=~&yYIDQSU2MnR7%s3rTs2CWC2Qw? z1s3@&3Ep-ZzR$ra_S*Mg(dhzDl z%VMpv7`uVqO34Lcor2-V;P_*00#zdR{*T8uLn7aK9v>)(pl#!RoaXab$Zl4zyzLQ< z-9B7_guSCMdqg6S6(ts!^%$Q|ZhMKxOfa-Y8<{g`dz{KkpVGMBnC;B`yO+@+fVb8O%UQCW@>rb+uNc^4)Mlx4scv*7&n7Q~7 z20yo=LAt+We*kt;FK5G=A~#B%w`zdUT{JtjNcF_AeRX-&$>C_+9fl`I@rc_q+Y-+? znUa!nY`Fpc;}NW8Hkg#YssJOm*sMt1XV?GGOij`!e2Wyt18 z*E#g>6%@v}l9VKtV|-GwuN>rRw;>0Gsmh<%wBt}5yiTIhG)k&ja7iW6FR|RrjOTHi ztD{Inmw-v%yC_bB)?`SG8Y5C1d#ZY|$-PLo@ZI>WDd2ZE&LfNR_u0%fx*xn_)2_+_ z)Rg@Xy98lIJ9N4T5f#8MpJll|U!zR4Y%gvWeb-5XQ( z4NOvgIFX&K(QU7|na2|}X)y`nQfa+9!f_Mk>b<)-M4GCEuVcg?XSztk=*9o}i^a*x z8nTvx&XKr{`MnQ2*xuyHz&xm*_@Z2|q?jS%I|zYZ{^JWfpx8#&D*OtENvfP5AJbZ} zw$MxJ2!|dR*VxS9Mi8=By&#=Tt-BCs0NuzY&`_L88m`l4nZSNKAmcg8)nab9qmiko zJcjxsCnD5d1Ldc~Ky zbpJH0U`0Yh@3D@*(cerIm)#A(zIhofMzEr|r!V9O?V+iMd=tlps z8Guw8?`L_ivbu`L0q~`7hIf)3w71&vegt?PS0@jF@Hh}CXtcPHeF|^M{l7#bUOdmA zTH{#?=BT*IxV~y-Ar`soF2SD`9|#1AEp3FU`VYxFXn0PP?EQG-k~0vWvL%+)GC_Ps zok-2lAIh9Io)9Ob>0=qeI-PnpohG2-73zExl*RGZ6>Eo@I>Q3EGeiM*86COK0dC2= zPo60zMk(^*6BU2GBnhn60arI`2!&2g1=bUz^g-G(;a?oW4=IO6Tp~RwbRU(sPn)d^ zD(+1uKU(s)+5Bcj{1W>7{lgmWQg&WqQ~jtJp{lFr7gCLna&p5}lthxA06iSZmO|-Q zh@2so5l7vk67zijYb z@aUsPxlbEWEV?z&j06NeQO`3)jld>ef6(38f22ijz=)u3TjxedSOUjKZ`5ItVe+)Y!nVG z6k1)}IzgKK3VrKD9dAdo=~0uZCXHkx4k8b~%5wbQ#=VHWhwS5$Oi*J|Qc@kvgqJ?c`R|_tb|kOTp13P-knnhe|C|&m zfRA#40=>cg`6VGuaCevBF)sYmGK9UF&@9`f6%nB&5E;jegwo?Z^5~zf3wE!H%Esd? zR@g17q$7E+V6!U2{(ME(eSB%g>Ee}W0V0{FJ|{hJD$@rPLijoCkseB@J2^S&1SN?+VW>1Mz?I}?sk^FPaCW!*py?uY zX=Md>PfvM-3Bj@cwG4R|bg0SZZ}ug6ak^NQtMz}62G6+rbT}ytBgjNtct47}rw~XU zk-bp|9@=2v#&qMMZ%;Zx458a6faa+v*?8gPfZED#5V}bd@(0~fpIn86`)vhBt8|c1 z$vFGD5RMn?zMdtp(O6^rIsh<6dKk(P?t~-k;7}Wf_Kjgk7qfqNXl|$vDZ{@&9kqW2 z*s8xgN9g@OHbi7Jlq%TJ#ZXAayd*Gi$?<{Z2=OVWK?20wrlDtn6OM0fE^}4~dAMC@ ziXt*LX(T6-uxbDSXw0dEj=@uN0#V;_+L$ z3d(3zszUr+Zp;~wyTWG*jsCZbQSTzqRKPl_Ua#)^4%N_%2!-gNFCiN8g-{LI>=X_H z&Ed@KtOAS*1ue$U2?>Z)LcoYY0qZ^{u^&LaSvDdQ0kF!exCH*6F?}{r41TwX#8eW6 zwK$NdIcSOo8nH1*+mK73{S0iOJ$wEB-?Qq6bXP-d)Mg379ypR(AITpzxaBf`>rw?V zB#RRU_ybVfm2e2E&sBKFXq=xfs!|Fs8j#2)!1livVlyhI6=g1wJOs~VgY-7$6%g6! zwRpbdOXbbehqYe3tr7_T<&i5N;}e617psUf$E)zaU3r({EaTeAJ#y(dSSaVne@b|n zs?1|kY)1Q8O2kl0z&;u$N(sVjpvxR`-CA}ruQN>0;B@@j7(O~)Q*8GAO=|z6**`Or z3S97j0>TLr5)$>JNANo@AFLdLYfev#h>UGxz_CCCZu+WET&{R{5JrtzttU$@!BrU_ z=(4?>alt_XZ|Jc0jlelrVvz-R`YlsYV0^fTQUp@N+bRcfJ(=C_5cB^IJ1VSHWy3X# z1Xh1UneT`c4bQSvT38Br?VvV}5*2?BP5PN%NZj@gI!?|7uxWC;fZdgf53KeAAqz^SSUxw!Y%!)wZi}4uc;wFtfY{^Kb2SoM{N`@D~nQu&UyF( z7*1EZAG{(L^(O9%rV2?-C4=r#IT#+%fH~@yG{I_mKeWpE_gp|FC?xzZP zT9GK0LC)cg4^dIlq#w%oj5OS$VN!|e6_@WVG}S}5@uLp+!O>@M^AlM@L_c9BHadxDXcQ@ue2Cfng&4ZcDc>QXRoK7 zP*1ieFi5yfQTO(21V3=$;fAL970D8Xy!`=cP21TT32>iK44~T+Wsdd#P9zYir|2CA?Q%Z?S)%L zVR7!s%tpR!w*4sj=kn6F!4IRj+(+V73_5`}RhA+vLs&CA5i0 zr_Sc1&Mh#P12=TA(?dXU+6Ok8`mbkl;8ka79L{#Nw>Sun(z~uunJ2D#upINco_?px zK9w-*{ckP8!G}6vz0C)Ke>G&9tCQ z38b}~>!aNnp79dR=i6Z%S4n;01d0<`U~q%x$ed4{lT>HIR`d6wKw!_jrx%ydf7)0>!Qj7v zDosM(@$%xKtQE&`4*M9Zd1f&9he~wqQcs_)GHw(ful45wy&jy3_Jav;!^u(q7HP6xO6bge6^957++5>u5!+o_$LumxPgyf z_8a|?+O5LEEJ>WQVqO-_JEHofj?Juk7VCE&C=FZnDCq9EVsScbu_uPD-}}GA=@%gM31I?_+4Vw29-`fffnTeVw^7G#e;&=gMGF-zM@GjN z2fEkOOiUhXe^k^^(Vmri?I1FzCPc$e08Gcxqf(~x7vOdx+G(L~f$}E~Ne&CQLK>D+8!m8fe4bqc+>RCo4AbO8f$~3+;)$CUt=&3k z=im#oj^b2S_-EYz6)@+uiGL(gK(BjTt!m}J_HSjD2_-T z%pV<_f2R4Y50KPYO`s=ne1$Gjxg0449PXKYdmo$loBHN@E#b`ycbLY7+%|xRQ8{ zE>6xBXyjf>(CRdyX68&pUW_Q9?i4=HlaqOnCkMxH|aknZ^FMskr)%|aKYbby( zm0;JL@|tyF+l+L634g861v+A5Fp&jDlxv%wK~i z?XK79G9UjqtD&NU;r;R(#i|$iT>l0-<-0)Vy!f(TXG??Ab?NN`)N+TP)Chv89&g^z z0CyS7vAi(yb<0&07zDVyoI{yn(V!k#1$9!9eiPsE`d|bg=*K2}Lz0$hfPX%i{~QRe z%X+vklBXa-D+kV`l%b(vLx@&-`9)&#U`IzF3Jq2ts13?o_QIav&(F`R00*_{+1V6! z4k145J1xJ-e1qe3t##5HSeE89T!8>hX8*3LK0eGD2-NCTbN_{CYJ?roxi2)H=}y>y zFKiqw@S-HCxkB?Xrx2L`KYDi;2D#jJwFWZ9sNNj^jGgrc*9zVT6|)SuXD?ra3OMV< z=)_=>3&7uj!IR*UO*~rY8HiYV9l#Musm^G#ld5DqSEp~=Me5_W#VZvR2!7Y20}-rz z+n*f!Td+$RaP-Lm4|7-hqonqH%LuT`Htm<~P!ww-tCsii_NE@1aBy5+2e{oj-F3wK*mZX%8mAzu5CAy-HFBTjn`75;C6)BF8bOBI-~oZ|*?_a(Dx&Ygv65J0IE!@_>C+%+%g1T6A@AmHa@K9u&b z_V$B-Bki5jCds{IWbhbIkqDtx1fAuyr`EYTyd>qDVFv$q#Fn~?*t@mGAC!CaPrA)| zyfvg0ZUSlVnyVcKY8E${9fZ-v4|L{#!Dhe_Rgv}$D84&M@B$hI-YOqrJ&|TbrD=8F znS6%(L*P9VV5~g`j>5R0dP*3=R&ff&R)%s)BnQEDl9p7i3?|vOuBfGehXG8ZdO=a; z>-mbH^D}&=Cq&37q=6AA5$W`kfN6s!lZqz|0`3U8|2=Piva@BrAN{1Mh%3fa;YS>r z+8@V=|EVsthye68S-V(l+62QsA{$~}XBD-{)8LeeQRkxKwP^tng9ExMoC0>Zo-|)# zKEp?)*FIV<#|S!`=d%51_0cWXA`o#U18$n*I?8-ech&+UpyMPLbVB;R-~0 z!U!l`?_AD+dtpBIOM#Q;;(E_>+*<`)j{C4Da{BjwU!RZ7psyV2jZ%hpIicCi)jfcI zpArF$6;=PUxDOv7B}3G56MVarX3?sk+E`LDRr&ubS5w^Wp+3=)#5Fr%IT>=b@kM#l zKB_OpMcAbE;1Z^tNg066GvI`D@xnmECIQTpDgizFJ*(yrJ)PJ2euC(9!<%1>yL)ex z1D?X8^mwf&*?_MkG71*CIH;PU^dQ@dlcM5r?Q}ZfaTuS=lj!2LnXf5y6!R%Uiv1ph!ZQo&20<9N|yWJ*_+ z$Z53UzBPsn(9oVQv2@Sg1z|+dQDa5TR~R97qmY7mOD{X0v7713?NViaSWa&txIY6s zhsam`Wgme5nRV;fx@l@+qtNgemw*GLR;%~tULJFg0^AE=-@*m_azme(3CL5^!lE2V ztq=y+}AESSg`Na zl!N`j1Yl;SZlS-yxEz82h)W*Wv{ykg%m?n_d$)#F6+DzN-f2*9xj0I1yj?RkkBQ2q5F- z&LCA#&UQZXzq7V>xH@^gb@sa`n15pmdfFu#En-Q~ zkt_Jz7A@Mh3{$sTJB6vjsf+T)XNggxRF7S;6eMAP_!bf8E4By`(osVHQ)p*OF+>Zf zDwK8oxk#Vkc=(IIZ#SA(*?gx}=Q}#?#zXv1avu=}Ynrl1yLbQM$&d-cJ}af6m}#$v z^p6PbqkEg}#i$@vBZGN`Brx(VW3m4nM}QJ~9|`G;Tg+w*4Mg2BXF@!d{a%k|>|HF9 zm8))$4N1I-cV;*wTOR4#_{rej@nmY$ubn5IG*1IIi5!ACP)lchNm7-4JBlBZnTEN8 zQtuAGl-8xj>ZhZAdjcj=CV(WLm_*JKm(cD#FQ=Q9G-0k~l2e;!$@Nv@-((0-5YYcq zQqYJ}(jYkY=Qo_b*ovh(n~q+Q4-imj%JG44V^BlCS&e?uB@g~;B}OE}y(nD-Rd7^POv&4IDA#~Tvqr;^s+p=yO17}Os#}3>mfGQP zUJdir34Ta)dK5P`Ha7NFSO4aaJlwrC6nk5mj08M+h4~<9D2ppiv2%>L3zF3m5>&VH z+U2{FuQ#q!Hb3`=<_rvQ-v92|N&^9qx-)H|U2XFhW}s~=Yi@&w4tSI$D-p`z-xw<| zfuwr@+$9}Ot;T(nAAtKXEG99vek|f#a;rH+UG68_E&p^Cd%yLDlF4E%q$HwjE4X2d z1-1D%9I0=%?+8F55OB1-K|BJkLWaOz55Aa73R($Pa7Snq$m!b1V%Cad0I*uI4~U3} zsLdbpen#y8=Ts$?Q_^~U5vTnn>fIO13)s-Vkqoy&=&l5`>o-Ys@Fi~-Y!3T?gQz(y zYv-~Qp^f<3krd4`M7+*sCht|BYM5y->UJL#O(oY~Q0rhqa6MyfBgnh2?f!$*QR#|QBT8JR&qFb;W ztQfu-#hM)XB>YMz3}%UG0bnNp()``_`}qP`f9l}JN775gi`;uyOM8O@>F;xvg3{JNy1rrQln;f4g)VRxQ1a8I^8h3nxbfWw zNjND8$5;piuL4|;$a`Cm-&oUyVKG|ZB!$#de2Eu<>rS};J+Uj;yLS55wlC`b3dG;? zY75x5{S6)=mlv?Dk>ZAOf#we*wh$ooTyvgC`e;-uKv^0HxweC_&~$Z336gSiz`+? zeFgAyw^?kZ0M-K414thdXpzjj$kH8Dapq`b@o4$>vtci2T626Y)BbI1#UYS^ckGAN zqdb_)P3Y~4*Q+0rCa8v3Ov76OE*^DcLRpMYTi|b>!1Ps|yj>xk=xG%dd4&!?0Io>ue){WA{@7^2BFg zx&#`5*r6Xw)CeZ1yB!$n?W!h;$-Mj`xSc2j&vg1_{_Fn0d?29FY~MPv>dKFrxBK-? zU?EqP$$&9U_M#kv0G&Tqzd#Z|M_2DWdqejZn(h$RyK(i2Q4p~hr2-2JH2Wuo56#`~ zRYwhind&!@z+Rr}{X<*=V&u$)mZfCgSl2+qv->y=Zs*92?`9%CIZ}+|p5GfUeyOO# z^!5bc;dG#J9Qy-OR1~l&Hv$yvWNtI`?Ws@pF+R#;{0R2;_TIm*2sk*J>7Fh=d7ZJ@ zw2E7>nz1sZNKJy}-$Mw62Nodyn_|#FiV>P&uI&_lVBpe@oYq5DtEb>Ql#6-XuKY67 z1++L>l;D~PbHm%4&mKp+X!969L)1tu25uK&<5#uZ%9(YvNM{LE{+V8A^;Q z#cPrtE*xEn!i;z|LqUpvT0=jRl`n1Y6*B7;-BV5zg`&gP`e~Ur@rKfy?oD^g0Lk%4 z;d3f_`F8B-vR^Dllk|q<{wRlX+T=YH&HQ%RXw~0oXza4crR`m@{&{TBJTl%jkLO}~ zXVB_L`T{Xozhd>j2QGg-bu11Xmk)iK94Ncd>einM}uI} z^;nMaXR+v{u`>uq;;?Tx(~(R?QSsjdFFKBq-}_s>{9hXU7kdjaza`A%BCLOOzh1qN z>w(?oedxzZiI9g-$!b$3<77!5)^ zT4d)lFc6QQB5QIGLC@hxi`4JE{AUY8;xIx0w>AdZx89PQVnZ9J$yccJaEcn9ybgD=Uw9mY<^v@Cb zB0Fr^dJuD`zEx(Czc9oO|7sM@Coir6d-dwo1#qFw?>ZJRWrWMB{5ifMmSyt_UG_=& zy8CwhJ!8d6rebo_KHC|)&Bq$n*?Lp3GKUw=1f=huMdt z>RVlQL`DuOe`tO>T9Jhiy;kPFQXuPfaesYK&A)V&MgUUl6V1`v$HY6xSsfhX`X7_> zjp+E~b?7vZ38a1pB>-D+J9dEQe0T`l#WA@j&*DLtu+JrB5b1DF+HzZt0-DB}c2@># zqKV2qr-_tzwHcQ&)!=P=1a{gh>g)MieSbsfL_~G>#yi|zi%L5Rye8c3&?KN^5B!;o z&VTk&GgeUlAJE+IGl-V_=U7FX5PycEY4Q(o13jjN#)>eCQ4f}~q!d{!-rlf0*m<(XKSnHq$&Lxd2>0wIuAqBve z1m8R+O;C*3z3i`Ei-6wM$7RR+5u%-Ry;SP9oshDQI@t_S`r=Ptd|e=Qcfud>`-AJM zS3rB!;P_kUE_!Qn8gz z68uYJ;h5qv`=xY=UkNF^IG;yQKD_6C-b7DL2GTbK95+ZoTOT*b_`v6G+~Ml}a97v~ zB|eF~3&Q}4+|@|5edSUgNQ#vl5@+S%JpRBII8HRU?hpdk_=0j1&uS0YngjmzfP;k{ z=$6GyWerSa$-ApOhLmFNGTl(-laQx)Oe;WA^VUcP3EUAAJfz>4<&?mp@&5E&{UKDO zyIGeR%*nXKH@Or$!=vZd44)t+r_Vxx0d%Sx%yeSuP!0-WeA)n5`%WD#P}5GVD|lh5 z((2l5nlUm0>jC=GxueKGIEg>stv z7<3=$OQ!yZ2`5;26+uaK$70>ecyx1`PkT4nUMj?QGayQBh=2#Y%LaSJd$j(zw zcfY;DOKU!X%MFXQ->Qj*Qt|T@CwvQ-U8~Nm@w)%gB%6no77pRxix$(&){lyG7Rv(jjUzbW#Mqj!SoIYcmWpcMYVp7}V znVydnykwnk@#2^K4lsnE>S`WbMg{tM>t}OK2djYq_*LLyd>V%|!=9(Y3C7vcl%m}L zQKb9HsRMNk=z@EV(D5D?Szl?69xm~%a1kye)GdWAN8qP@zzM6szf^^N#Xph!4kBhF z?O|Y+?_rhLxA&h4O7KqzOQCiqVdyu)^H{ze?+CY8vgYG`3YWv3kbzE-LT&2=Hk0o@-cM@keKzaSX2Dmj9ymjK>5ZBd7><-mzwM zR_+GK-pH-qzr%+m3=X$`5h2~bPeXmkBYFXKKKUbl(eek?pedGa=BMT1 zoP4;9p%`;-k7By{D0gxD3zf2#&dmRWSDw2fH9 zwx7iit}K$@l?#A92lSww$)mYaQUme)oP?a(u+iE&-nN4G`ube29I)$3ZU7Hf=r8$PjmD>V@EV32 z9IIvYd7Ryd&5~K`v~IGnNLj2JaiPJUUO)MEEf^?0y8#pwLxYHI!kegH^XnlH1cc(r zw_5?aO?^t)JC0FsP02Fop~lKqKnx}Hf7%e(+K`jjWcfRk<J@D@E)X3fm z1I-kmgt%@it`~sh7?sMOTE_kRtV|bh*eJm@b`kZ9#$%*BilKc!eo#J3;gcyGO2-lN z{h7|(ot;0J!q)?2a``m?Xp5rwa~t8Z#iq%WmsLK>dLt50LGT>>Ria}bY4Z+DEEOR# zJyjaU+7Wh;4Akw6F_v%t{v8jX-Lh9F(3Xj1SU+^fTO~E4`)#z z8{(!xc!@R;z%N915!IG>f3CywH9s-N-M{qT`d+a7iG)Yee;`GK%&b2_jUr}qS=8*< zv{dKw3)jWTU6qrsz;_ubJc$|SVKAV#W;ykQUmUMR@D>6gUNX09agQ;Sn^m4&MiBQI zKJw?1F;7g|FF5B~5T7OwTaxfu-NC2ImdVlb&oE2zJvlWuzUR|BFF?-yOq&!Sn3zwI=> zIa;LI)|x_NcwJ|^IZ?gwTog=Dfq`Tavo`LEFz@HSkMT^EV2Z8RRNz%e_$JZeq>?J}fd;v-(0#!eB*#dD0Rs9gL>Pd^H>WFe$MN1tnZrnl#`}hz zL|!F0(K=t5ax>XA2r3edBd>bEyq45{&$L9v0~?6>u})j&SzS5sH%8r^uS5jS(%6F=(_whUXUYbjjgf^#ggcK0 zVz}sny*#qCDviS(2x+g9RdWvyv+MqFbko0~DUS$;jzp@CZhw14QiwpLKydni->f}L z;zh|kRY=25MNHF^o12@wkjC>(e^4uR(<=>@=Vz6#OzL&(-q5|w5$jQHelhAipntS9 zn#_}j>;tHqSAg0X11unXkV*@gAF~yS`QBo^{-)e{Hq(}^5H?_*Yqb^7IMY5>c?KfI z)Q^nhhqRoWoPeAONu(KdO2F0`A0eL88!ZrJ4p4+k-1gHVvvjBy>v7&g37mBJ3lJh! zG(5_YA?ER{sZnZvF6yuuQ^}~5(Pn?}%4K_+YyJw{$6(l9q{=uKX|)Wp&uFb8QACj} zKfVfJRXp5!nOzuRXDHHM*$Hb-r*f~qIV|GVd;KyMNxH2T3^&_HM^#f1wgp)pU~KE2 zEr^%dm6#HYBZ?u@*pZWU0}qHL{qONvl!r$=xZN8I3is_fn1Y!=oYCy&hph}fIuaHH zl{*CD%QLt@1bw{%`$0=zCRU}n7R$K)K%d{fh=gBTJZ*UNVXdl__YO(26h=*$p z-fp??&r1Y)o*n|V5Xe^k8%RFq%T zH7*F!-O^ps3P^Vd(xo(rBGTOt-Hiw$9Re!d-3=1bFm!i!{4c-v``-Wh)?&??8Cf#( zJonyn&OUqZ6Gr3PYjg_oxVQwM4VEj^^Cru>>tD`Q$i^R+9&cL2gSZ2n%f1Xzgv_5A zcelVjE&046vn316H@Z@49n5;fJQzUUTf-=R85V!oDc{glV6$*Gj3>;JY}>i{e^~@WM{;C;rHt>Zo=TU=?hvO!gVnrKI%PR$oO}5KcYHU}SMUcE&IX=f{$-mM*wNWQK zTJFNsPy96|wR%a9$Z-BUfY6_J86F&WB`<~Og}?strEPyQ zYP-NUnO^u-?+#84m1eI8f-;RCQPkvbGQWB}Lr;MkNI^y~sa79gt|`bNezg2y6G8+d8)_%qt zI1fe#e&2MOcUTB*ntZ-h9vgL0j?<~@V$B6?3_Pvzydl}e>z2)CDI%V&hcDAe4bou7 zU4aIY&qo_5J@SJGvp-H-5+81`r_|lb;clbVzcxMgVd;r$^<;B(JiE!QHe$}-vFgST z*GAp~N`?HkFsNUIR16*qkjC;(A=~g=@|TdTQS0^11nsnScQcM@FL>V#SLq8%d!lhQnw_j;6KqpU zhHS9uR!W3_W6Q=*CP0xB&!*|74<|D1I^9}o2thrAd0fbR-$|J+=eimam7EMU*v`sx zpW-sUbsczcj;yJzHQu{EL;Ywf@(+K^wB`Pl$P&JR0!`g!s5e5fql1T$<7Yl!9>{$W z@IOa4e;)tGe&>wv>GQibWL3`G$+u#P`G@lMS1q+_TMfVSJ>0i@FPt^hdZVFRLbW*w zjkMbBucs%VzNR%iAB&Sq9T1`J8Wg1o9VZC8_p2kYmxI6FH+3m>?=~xVH6Y6KBSJ?W>VB9=ZN2NZ$>HzA zA7JV<$;y z_bOb%NVywM@8lM1v`Sg01oP1O8Jb)vny+riMksDa=Qx{w%p7&*OP6~n$iZCDGMsJ# zEeL~ULqdG=B{ogXW~jma1${|*WHiMfTKnr<@^3bc$TxH-Io%z>=-t{C3A?vU`N6BI zwXO_vZimnPXA{1zr#GGxH+COLJ@2NgscaN9nI$$@vzhAbdG`^VIj~*bjD#l*jg7e* z@Lg#jI)AN#chuHh>rbtdUr@P!2^oY{;6YS^Wmo4Wss-(7L_&zPQYk$^j z)2o)tsf{S^^`F*LmoWKD!Y@rO;J+emPXzCf`o6MF^C!^@4di99!TgyFCftZH8ENQ} zJyl={)X$j)7zG-|`sE)tpC4tm&)?lpHw8zO__?!dYyWw0hW7H4l39wF@=1NKL~iMq z^iD;I46{&SqcUzeVlKCS$&0=b->Rwyf)NIk#LUDS`+Kb7IKe1Oo&p-74`TGP&@RRLt9)({?hJ3Y|rw)>c zPB=fX4_7*>T4AZeG3-vZ&4Q}Z>DBX=TMM5ioyD5ST8Gv+3?Q*SH9VE39*(J3)wQSP z4~4@1(m(#1Di)(M?WIw_EFxi5%9`EWOA@JJspADq);m4VDXL%lft%iTl8gn*!XGp& zs`2ZiV4bCF&DnBk6{FG8^v&4QSZU|tOLKo?QMakxLW=k|CS9cV|11o#o4 zcQ6))(|L}+7G^%0cFCEk04mv;mXNU9R_GSzbA#x4<;C;YxEQ3*n$rnDj>J&?zA@wW zkYw^u>6aK$!iI#{g>SPvT>fq^f%7IDQAH=@qAIOY6jh2)qXi>*U3Q>kyxk`iou8=;g)X)9MbIaEC^A8p6gF8`( z+OBn^=PNt2waozqdq9qKH?@_8;FfTVFIIW=M61S- z^{0GUUjFb&Jhzj>YbKFats`;=AEHTh>w|de?}n{3b}Htm#2aIN@F@L3FEYU*p>{#C zOr9XF>@(w;HB;zD1#PV&Y@Ossf*=&uvfzq}r5C(eY8^_;v8#&SD}i`^irl0S`Cpwh zMmW}vTIP4Zpj%C&FtK=HWsjxm#&L{BlEv-yIjPUJ_U`jY8uqyE%P)jQYF;brgR19Y z9O}RDfg1=-u6p*zw~9&pTrXdtZoi*1Lo{&@iv}RCyijwLOXkDd!C{1`@{bN>)6b_SS7GiN|NI-hK0;A26}TA-O*bL24wxqY=64RgH^Y_Fn**}x ze*OKDIK+PUf=0a2e?zMvOb{?a6}2qCk4PocAe=FB%rC(TT1DBeE;h*(-#en`v5N*2 z8~V`w3`PfHlWj|`2!b()RI4{|9B(K1gs6X9-Qt~tk?L<-QDxnI#!r7VjtZSw4oti_sFC% zNd`C)c{V#4QuJ3yz+Z#(${>mkg`M+e}`Ys|E>>1meV&a4>ZC?jgENz8tCY z3}wPXg|^Eco>}x$Av#&@1(Re0C+{b5jLK2>cQ-${Q0o}rR*;3HeCU2Dcj|jeU1IG< zmgfvj9~sex?zGa}xMT`TITA%X0Psc!6YdqF)5wtS=_V!#r1aen_;oYGJAjeEn=`cz z`FmWZ-C0Vo!-GP6yFaSg%Q2%RND2GX)mVR_zkhLL>fOg#&>x&L8ki#Z?Y1>GLH7R~ zw%F5#%VC;E^&}d{$LQ$Rqw>n>lDY-ea8s%)3@K`Rcll$@FI+&YdUPy^Wx^3Pk0Wmg z0|Y$ua?71gHM8=3TTHMUyFoygMn0(unPWkf5Y=lPb0gzv%Gd zk;xRE%<|Jm-j52wlI^(J@(AM;g~Bl?go+x;KSIy8hb#_Yok8si9az?bU3nl&e17_cs73QL=d|Za=-g z=w5&OBZuni{wInmSokY)spsR;lMV06ho8Rb*UtB8{`fb-_8L@Y!x;vR!``{DvdRL2DQESJlXglAz2)ml}W$Bd(_?$vd?ad`DQje z<+N~ncq*zYSg*0mwZmyH%b_(D-mE}{>XF&QYpW+(O8LQEn)?0^n;b%6_wmlg?PD_e zCxyjzn^VMViTT|EJLkQNKEE$6h8Y&! zW`}O4&&Zz>w(J_WBE`Pqg>v+I-uQ zj^GRzhie&9>dos1djK(e$z_v9Eovqr4$6IFyx-s!#)&60TVW9hCStug|MAKu3cznH z>#QD0{z{()QbGYl#k8)#5!7Dgg|pG0D&!^5HVom9xg5a4D?a-#5UHy?z6Gw9pr}Iy;@to)LbD5sc;qB zHN9}HB45tHNg2WZtOAE~abLN3`u#adlA;k%P!kI{GA(zY?Ar}e)4~xTo?YCh)A{OZ z1YvEdpl+q^QnR#Oq|}6?c(G&}r&ls*Pf7o3D|*LEI&n}Jblo_S0kWXyT7LuM5Jwdr zDEJt#KJ#_d`-)wbn4bmr&x-oFHH8{zeBNdT_>Kt(l=6mH=(Vya(3v&Kp5dnUWYX~k%}!SyDQE!=Nf zKX(FWxujivl4AvU4L~uyC`~Zdr)N!+b=F-WTQd^K9V9jQp@ftzo7C;Vk26?qLHAMl zBFPxpnX4VWD40hc!`k=}g-*Z?X)Ae9O;6>a(%osU$w^^(xX{DJacf2she4F0jTv(h zAIUD+Bcy4+8vvV_ZwS~l06{7gC=95x-?$v#O=;g>gF(1BG?^Kg9oH=Tr7w+;#bHnR z(342~nX@No`hWIMRa)b5f9NqP$poUHEI`k>towwZGBLR5^o@Un9Me1iI2!!@H_2uf z{5^gY(7NxBR%AoGt;o0^4+)~!^!jrI;qJYb+Aq<$?Yyk`SBQAmS`x`$z&AR1XR(zmYkoPh55*s;;7^2?581uTG3~ z@h~$6zgLQ^Objng>tdeKZ zw$GZ@F}v$-n;($toy(V8PY}B>fx`c6M>hEZC?Ys*caepLlHqMOoFN3u6ZZhT+SSjS#zWLhWwCi)g}j|T=}b6>gd&HY9qeC9@LG;_c(JN&OLMUJM@ z5y!;cnQlUTGa>;9(;xdtS$k-~@Sv1neKLN_&uXKZ$P%m zg6X_Q%{L;2J{1$|Kt<_kmKzzM3+Gi&v(eKq0{VV)EXjb0FOz~Fx=?s6f$|* zg?U6_G!tue2rJYZ`e`9I@7G|q!Y?mbXyCHNEzje0vOoZs53prwuz19!Kc`?;( zb4OXvnz^px40s+bBdWd5?Mi$gd{RJW@@-lsv^bf??9Q3N&Y%Zk@E?t`l7UeRK_dPF6j=^<$GyOcB0$1Q*9A+ z7Kr;a^*4!{~aj}003C&}J_*M+`;W`a)gNNq3liY&su8(OOymz9% z_FAguN_}*7Vq-n~v+*c}1=a)7|1q#}ebHQ5EB$cTjQ1CX3zFWnTnI1oS9XnuC&th# z5ULl-X=Z^zfb~l!D}g@#g}u%-!+pqPbzu>(Z_D#ntXxW-K&4LX?8Z1hctB>VYyUhW zgPn2kph}?1CK}|D3ZjoL8#8A+kp1bw-_*_dLfy?FBDQyafXvK01yz|RSirRW_1$z#?|RiJBq*{2Ar@3W8(Yg`7m+8aZHCG&mT&2)qpX<|l3R6w1D z0SMgTL*p+{)KvJ;oCWCN-U78`QLmM;3Rnc|wAelzk3EXXhfW?(lVYb8Uejx>G2uIk z9U=}sYkh?BoyuDb(m5+%>*lU0LJS=wxF4DQT-fh8EjoIL89fi?g=+{o0eh|Ar-mQ`>%KgE#l=8Jy@MVee-!9HildPz zT*VZn#1Jg8lcL+%eebZy%Iu^+(Di=Jefl?5I2>4k<^TG$tuFSVj`7AGAs>E-cAu@U3^4TJmsYv9)M&!F_`q zm`gCr*WGxWw%od%=oPc+H9*9rrKM3Ca^N`n<4ZIKC-nyXtiyFPbV;ws5A$=msA7T| zf)v#YWH}YAaBB@(DJn_ubO<|QDW(^w@$HV5rN6R~3T27&+iH^1__w@IX`m~jY*7TF z-n?TkN~Ets_NE9+x@xMt08|w(KZ-<3UZiXlOP;J^XG6fb65NVF8e9e z7=QISMV0PuL^EvX(R(>)xnncZaPT>X{EhX9W$%F2u87a3VT(b}>uel!OqqT@oZ|6o zm+kJ?A9N`cH!LffJ&{wXj^<@TaO(PTy;{_5*G=v+RqV#iEC}=9Ybs78-E?!PJ9(r0 zOgi@I8Fu*ZSR!qRme47N$nz}&JPj2*j)Itrx|YJas@1w&j)VM_wPWPjo}*|8(aIHf&yfGVrOFC?t%uv)^Id`l~=9h3s41y>iqZ z$a&cgw`F|@#wPnev$E;vecL{osx9-8N?e%sGsECcJ!I3|`Gq$vu2`p(rioOLu-1OV z`42bl*j_dUsyKP}r|cz{-=&LrhI^B93VmR2WXX-N+8S?ch~a#qfaHq&@c)var8c{j zn7>_>*Vc6`MGo$|Np~>;BFPAI<}TE`N3Wziu{e^1=UF2|bW179L*o1&N3R@gohp(* z0j!Sux3iNsq3OBsbDQQft+K#j)5e9HgX|9l zYEfEJV0|^TQs+PIQ9qOSJlhwmu$rCl-V;`X&OMJ&JY!1;j{H;a7JH+aXwwYCZ}UBR z(HftW<<`#Eset9jj|{|@9j=u?;Lp#`f^S_JlR;rE{OdeKYz9S6MOm<(v%ULsa zL@@R|jq}U*WLo%E*~KS+pT~M}MI|jL;K&&4rVmM-eAeaqvW&I$Y+<>o>T>TJw-^-t z?Z5kl={rR_--e`5(RFu`rysri-9Y;*b0A)G1Nsd=|pk&V+{+4nMRX; zQ+v{c1ue$%eR-?r`~>$K{#~Imt%fT{_{*qtV}+|O9&wbKw9?>n7|i9#a2{PAt&FUE zXSB8Nd_rYYF*KRyD6ZK-eAEC@A7{cHXNE1Oe_}E;V}Ng!SOiShe2oI!%Zl&;IC$JK za-Ux>q^YF97sVQh>c6y5m$MoFMF6t+Z%5x*WpS{5HBdM)1v{PYU$k>sb`%Vw6F4l< zWQ8w8Ppf-N0700Vm5V(JA%{W4$35$=Eqz+wf$yU!(d-do@D5tE>(IHc&dmiXaB6?? z_KCaDIdW4wdk2OW=i5m^x7cQcGZ_q0za9G-*5anHA{W@2T)B{NDbd3j(ebKk4oW@6 zHt?m8$(yxyI2-&kU9SJ$`r%@syJtv*=RmVi3u8eUedvVAPgaF-tGYXT`Rn+l)9nY~ zo-lL%mIvsG9CycXAfiuAC@+6o-w0d;OvjQW#E>TFi*gk`WXImexBb&#)~AD~S=0sx zB?yXP+EyJLCto_-aye19mqz0)f{}C5eGtx0dC=p@h|@BGEViaU6VV~bNR3CTr5GV< zF$HI$@s3l=V|b<{UFFNI=%vRw<>w-ky^oQl4G!Zz>Al~e^=F%H*SVY-|CdbAg6nGf z!s4Nc`~YUFHwV8L55 z6vCw+c)%SKj%kc?a>dw5p?rDQBsIANJqDrFlo@)f|E|Q|9f8S_xpm0 zV&t-VsgpM$c6a)OBs=427SdnE5J2>xi3Ha|ZpW@t8zGJnz_r;cxW0g7whS23OuD=^ z6js_up+3m2jJEI_@dUFjv?7aBCi~De<;)s;c(KUa)2P$VI^o+VKU3!X@C-$l`pw?3 z!pkFnxM}84b-w3~xI1+i`}6J}Vd{g&{=0}25uEOyLP%fPOm?0_jK_%?^LJ?;CFV;K z{~Fj`=6oj?T-!^3YBe3d(VmwK!jSC$hI;aHH9NY6^1Y%WI%q&_Cp05CQPl`RK&_Ts z3tw6sA-NR5B;>v!47BgeMGePqq-14($cjErDfrCu)3hU>!}h3ahX2YyJHz~*E>%(a z0JUZr-CXVahhYOD}%jE0Vllxt_G4Eisg_YY$Cg z#q*6LC#}H|X=`9eNIDW$i4NPyktz^!@IvEOBW3hKn565K+i8B+HsznP zr*aQr$0`?M>wH*F7xsA^lBcWmJpvHhGVeiGZH=qcMt``UW?!btNnQTznwCbP7C~Sv zd0-4%?|}-*pI>>%A!3KvQ-BK{ghd$zCV;THvJfb}ip`)X)vxOI%IM6d9TS6ke=El2JpK$q*4_?+U%b!jGek@P|H$*Q73n7-FdJzrTkH42OgAN37qn@P1QRB{ zuL||Y+O^P5M^TDKxli8m5#BT%!q+W$6l>F+++RM$sv&Q=nJhEwNfoS?X9dvF_hLVH ztq&5sADnOGuc5DQ9C(+4qFE})(~YPr-&E2N1+eMjY%DAF5pKnO?8bmbDmqmVa=Ff~ z>0y=hb6-8Heg6W!_c895+J%ZGvg;267p^()n>`bn$7{7kBbEu%w=}$-RP%hjYN~i+ z4R2wfPny80DWjN1OeX3L|7EhUv#)N&&Lw~}+6VcGkcSoU)Sjxbqg6^1`rN?8s*!KBeuwY(0bC7cyv>{2lcbk+ zS@NqD8GpHx^<2n-|DsJ_eUY81C$D{uss1X(d7!~|{7*%3&I)NUyP; zyfQ?X1FLt^wnoZF;yTr3{&T~a+2gPO_tPrdvfy`ps4Uv)gC*+dd%3++tXgfYFWX|9 z?Xy?@$KdXo_-MOyY@7!Yw7uGN_RT#JR3m}`OpJrKb#B9e{Y(1_ZwW&jSAQhTQ zG~$87hjf}#!vuphNwG{HmiSYmM5E_M-l;aIu;ce7;+1ku$FhFH=Vn%WA9SQ8gNYrJ zvHxUjcpxsk6nH~q0nf|K=_ljw|2vk%5ZY3Fni0<)%S7q&kNozlA=J9rG8hp*I9s{; z_L1z$u!FpeFB9cBZA`9(Vf8D4M23o0R}jRZ8zgv8(|&e;b9a+n_`{_hobbf2EwUf) z56JW$_cGCrFp~1h&AT6*2M5ABP5VZ_+%(zJDI<&7!+x_8NlY)hMNFm9{-F4xM391e z8SI1L^kA#S{J)otCPoSVo^b3PEH>TiBW88QpUIVIe^Di3>9zAcXvX-WNWW-zt3U+U z6PI8r1+A$6_||-t~c8J82Xy;~ND`C2Tm;$rfZMfq{5 zA)CNQ{N@Kd=7#f`FXDRr*hR?*XD^-Ri_u(+PAi;rj+ITwT2FP(E#D32YpK5cqlz%z zMegOa(G#jA6&n|M}vNkC*8!;T#P<2OMr8e4j@V+R4G3 z=|-oBtv!mM)irH{R(+R+J>)0f9EM;nj}A9QwQI2{~cm^F~hjjWLLy8yz zV81;BBhsIN@{I_C5!{E1(CrBr<6+k!y$%>EYc{E`$xivk0LS0H^CUwrRH!GF2bI*B ztocZu7E-JcoPp1d;DuJslS427lbK19_5#TQ|O1A%%YLiTzL@R;Bj+Q){bhWml- zUX|-%E0Wz#VRewfnx^UFRRupGPvGz7y(Uv$$^3rzo3Ja2bR$vg09H?AWz$H|9Zl|# zu#uA|Abr;Dey+G&U`;SrW~KmU-*koyGItVQpe4P;FEbyZaTo{I|M8Y;I`2k!yiSw2 zn8UW32a^NSqD8h@gtdzxy>-q};G;laFrvWG6oRtS{bTaEz6-gG_r2S53$oipkdxkv zs9{KpA>2wC!RnmMCyU4ddb^W{OZ$fyWxGnyv&(PK_2VLZiXgPqjH2+DNyv3pv!+_haM*N$k_ebooTzGt&hCa|jPbw0>>S2#2P?fhcoi#AKhjs-*{J;;idT*8HTvL;t) zIUA|b*24f6LfOqi;aT;ZJsO4AscLy98{U6cHcpFA3fisZ2^agc2$HeKVi!Q+3+VRQKp+iQTqEKEKac4B`w7+%yZXOv~8SZQPIVqpH4gD z?ZAr_vnyQr@A>Y0B$(r2+_%~*A18D-z~j2uiqvQ@QR3}2>074QUaUbau^UBCh+u~pS>YA1_i9FPB7zw9x4Iwd=dk~Jx`Nk zAp1*3q!7-a%fAUw3YDhHK{@=B4N`Yvq$D8HyKZE=-aQgL_95y4v#%^PTDtUF;GQth zSn?zwsRbsvEe{U=PlkxXS~$b}H#P0a_B+8prEmRrv$rf{L14 zqK~HrlDZPT0P3bVhGW1RXbx7$%!gcL0;U1Dwy5{4N%UAe?>M#d4@xo)$;bI}nBD3Ruz_ ze*aV#jxF*WV$^E^r)Rutxw`Fw!(qjq=T`0fZn8e-f5YwrtX_pGdbWOTfpxdZ0{2c${FjY3yTXQz^lFPSAZ385yi+{sW3Hu)2%dL zs>}LV_?`hDQi@7>?bSoS5~o&?%H<{SaWEwm_`y=M|GodNLZTgh_&1c|9HY3A&{4;7 zqQUJ~-h6X$1*(J@nMk!pb`89Mz>NL9e(Uqy>0>3Van%C%a4`X7*B?f+ z1QX0Tpnv%km|Q5xVmN*-1N+-UnrF3MlbG8%!3`>wC}>DJHU1)HhT$pq^_6ba;_8;e zPlMa~H`AW$2XiB;Ma_E==Z(Qi^%7llK~b-R2J54Ik#c5A2fz#}?=u>6jU7~tVwERm zVVzXaJehcFkJ4QN1Ic4)_>vt5xLVU+pYMeeT8BF}C8Q*EUaY1TEzyGXb1QdWiB7l; zsuS^eSrtbMUZ<&=vVRSMhMPr2NV(cH&D>d`+g?UEym8nxn?VKg4?Y{-Ot&hVg(zTD zhJ;|n6zmz=mrP*R_e~m1<9zGs)Rj~HrMTgiyDO4>=goYBG#dKNrD=U)@Q1n>!m;?9 zvUnGFxhQGP_Xyk(V)l5uV*yU6Tk24r(kp|#|CUHIIt$`X*M%~C(X3LJS!@w!OGMTb5UNxp=|r^`(`jVL*Qn+UacjL z{CUTtp7*um#qZJEG^M@zYZDeqhAppjCwUu+I*~Q3TceF^F6=1}ACqaPN&R4;^q{+O zTMsX>z9^U7;HB%dg5~XBeBp1_0{QqZs52zH^oBigZd7pG0~cVGtiYOKuP)5kFbFy) zIo=pLkW^awaazc?&;cbCH*sS$tS5ir1k)Ycs!N{$^GSb3_lvHB@=x_M?@Cmt71M-B zZpr@=#`(Eh7&?RHwL$&6DpYJ6ALGSOQ*fedCf0hg_{F)V<~oBY8)B|xsC$ADQBgZ3 zBN@dNEKKk;*lGxBxD)FC2>%2DS3VLjw*n3d4l^34yU8x1enot%@y?Lf;Z`FToppWD z_vz+bfqER|FAnr$VT{+O;y0M&+<#J32ASdzoWeGririv@2;|~KB>5zgoDWlon0JmX z2f<0u&>0Y@yQdVQNf7F_C37Z+?$AVPN!dn8z#Q8Pz2yx=NR1n1$NN4kKEs>jaKy z2zY4(8>b7gxt)tdU0=?-mKXC-?4gr7;FDHUO5RQ*2qw}hd{Z>nC}%1vbVK}=Fcdx7 zX%fSs?EGO6_i|XE>N$2)C|!QAY4Ok6xA+vG_4b%jw=lz_6LeOJ124|EIF2n#pRk5h zptw*Ub%dtNWi;DC66>nZ{}@hdE(~^Ot2yNVv1sJ`%nCS5)t~PH3fp2@9R}TjEzy`8 z({4q9dL+{I0!601!)lMOak{79m*Pg=82!cSGD!)QYTBHe$Rt!;kSq$qe=GTm(hA1j zWXirK-!?(nmTx)69=(P!Buy5vBvRr*q7A*&hl!sQ;2LlG%M~phU9yMo6fb7@U0?on z{qs=&dh159-(RABP6f{Dd16L~c|q7aVYjEW09&U!1Qyk?{WHWJw5pB>^cq@-kUOD8rJfI&jDSb+JVhL(87& z3(XN;7L#gdM>!Yjn7;HP%kiU)gs3YkExu3r-HtzmQIg<~-kffkdYhP<#^>bbKhBjs zaoC;Ws;3lwvmxH{oOR!nLBqgQ-LrtTTi3!g%FX#;9_E>MMD@?MveDyW+4tt4y9M_ZF=rH-Cv{}~s{&mr>_peN@1ve4T zzG9MwCK;$nf&zeyu|3e(Z#FGaCvo)adhOtL*c?9W>IVpm#8`rr4O5XlO~PCO1HQC& z&g^_9?g?dABdgn4`TDikeF;7O5?A&#vQ;mtinM8dfHPqhf#ANE_-UO zH%>kJS9wK#Zz{=#?+blJ=G4;w^yv7vad9#GZn65tUM)Uwj|M)qLin94r(@HNg9TPq z0Xscw{7XqI2dgh|0~{}^PSE`UyL$15O%qpXg;}h;kMcd|s`7|QCk?9DFxvJmhW9)B zQ6bPf&=3rcPFVe$dQ-+xyUMP(*DrR^?*R1Tc}F-6EB;8(&lm42n8t_DFXXWTPd}x5 z5dvoyg);$qxu@Wame26w_I~xut9-QK{7kS=B`@qGxJqU5=chV?WqJkyRE{~r4Q^^! zxeH0VXWPKr%l!=u`2bf|{jDsnF4M-nGc(nnIuVntrLJcp4r~x%;ru6ri;AE~W>tP7 zmIV2TaqCGaDqZLc!u^?b=`?edE>hb}Z}9vshJ~K51;KIl7y(xgQ9LXlJ~r1E0M9SQ z(1sM4axM-Q9?H7?)o~}b%<8}(^8SXm?eQ`1=|ND9e3H(2_7m%pCdXs_M{yGuH zfDG%i2y$b6LwlUpQRC(~H6UijTe4@H!lFEk6EDkFwDdMPgj6&6Cho@Ge%9Ry+wS{7|@kYg^HBUn~x1Dbta(5ge zcK@ACzCyy2YI40<{eB8Fd%4gaKdbqBDV)0Zf}f=9O5;R&=6hn&M&n3`)%NXpTZU`{ z`ER=$ofP3jAE35N_LusH%lp%ylICN%4^r0kbKZ5&Hbl!AJD~!;o2u+7kea7%lNO)t zSP)3>$mFVQ{Ay!T<*!C?R<;Laab&KXT*rYWMO&KM<}>?4{E4+(3Y2U~(40I#m?Qth zttMAZ`={TRgIhK?&n2-(1`Z3dXsc^lec2;TRfghvqBNPqh};!`;H1r%5+NA;r7nu^ zVPUw0?wRQ9)Ci{gr&YCxv~QP}^wN9p+GleW6fgelg7oNcrNJtR3ldc7PFJpCLr;+K zO%0CGV){P$+vRp$zuV5C_%j36Px7;mXxiSsn4}IY`(zW=Z-s8ZijuP9c7Cds*rc1Z zbuSfl_ITxJscMjDE(=EmF+6_GGMT)3m%53svEvsOg~&NlR5{>O3~=)5{k#}1_5t_s zRO!NOln2ap82HX3ics^&J|Xzec!#-r!YR z`E>#f4s{1O`9IAu@ewdfD)K)>%oZrtBE4EKk!G_{_f3=6_g zMHM&Ren$?0e2`~c=Hr*W}jn|tg`uwip-duRK=UZpui+0vRgtNo#A;$`k zUKX|HrF(|~c2^EF5vm^k6E4bBH3cwudT1D-1NxXtA~Y>c+(sbZlmz z3TCFFUXZ%b`1?2={0paIn|}&I@!3wWA$0eO+vlo20e4KlW8r$2BjU=g@#-PbxcWJV z72^O*5EiP!Q80cL{95;DHv^I3UG%x;aN%3}KhvJX57r`nmAY3BV`Qk?;Q&JvW%)Yb zkD65Z9}hDGEroqVE)fdr5?e5)QA7YgFn+_ ze*;nuT4Lwoe=}TlN+2_PK=8g=Bf7oXNH|VAz?En@;vQg=+_q2BWu5_43pVTpx zO*K=}w!J*YAo2cdde8mpz~ASYlO7Is$EU9ytN^@rbQfHxT47W%2c*iP1XO11Grcxr|F4g*ND3lrkak;Oc>c_h?g^h{a>N0Y zZA0cI_ZTx6c2TS*^7cG2b(bX}RfBku+lhmua>r`7gBvVsiSgqrD>HeH{XGxmBwMx} z_D;Hu1!tjND}orf(7J{9BwikRdk#vo7ikE!meWpidj0M1x*H+dEQb$guZv@vK(Zv~ zVko1Prkto>V+*&|cXfX%D>EVK2Ee`l;Qs%4)Cbk;UYwc$^dAuHdkQcg>q~MG!ssst zspj|lQ&~du`I7~ZLhMQdWzqRTPzR3NP@s?Fw*t}kb;D52%|ADRL zzJmrtB=&!w9qs|3n%4ZqIuNpc+RgOsTdYs+0)ob%quOviM5zdA$cDD5X zFA?BCvhqKq|FJmv?}z3qNOO?)Twm!vzHtjF0TP$^J#2{daE4J~V8O6y1RmoTkzEe! zT;PHWrHv2f;2o)waj)pj$X@REpH_vW30*CDq_0PnSpRYS{3G4WfrohZ>7X!@V(%Bf z76l*cHRe4YBYUSrUcSg@u`lWUH#-Y=H8-77GN9AMbrN62aPA?Mgm4zJ`SBItWC6R+ z|NUfbvEY;0?rK)bKfdP&UOD|^^%6-6CON78(M$x5qqy1M5VChzPpS?4%zsOI_YsX# zC{%Rs$JWkK*I~0_tg>UFudJZ9L&aqiC0j?%0`CuQnTApH$S*`r6+&GTX5v#X|( z63*2ej;E1VJP{q3wt(0bzUVm{_M?ZL;*R-ek!qm)&rSW`#|1!Hxk&w9^nY$V+T+H0 zfA)7_Y3>S*3H!&>lja&WHaaW)f6GhEMmjh%GxGXY`th-$1~-ldogC6y|yQn~#EbdhqH`V`$)h1)D)5gmuv%)UT=dex~-pmdtwdH32BpX}^3M&^gtV zUF{=*GuQ^K9g4I*!~g$6JzlXEYOsOG;eT6#q6NGb0{C0^v;#^$$Z(#n&m?Ovo=heS z@+z{pTz0Jvx-Q2fT~kESH4@bC1R9n)4#LF`a z2|cH|*xu!AC9A4WF2fW`XTyp92EI$b_P*REmgPZ3hlo(+gj9^ZQ}^e`gm}g%KME^)s=?i~Fx(AjAov@6C3^ z+Nx{C z!V*TtH<|!jcBOE$tj}^BOgFDbJ`bh&zJc=@HXmn zSdcc+1hfem4k|j%lx%W8a!d!xE_^pF+nW0YKfn8qqw(EO*E`vTqK;v^-*1!o+$Y-i z3R(Eyr&SN6Q#N47e`2HvOa4~EHgtEOta#<6&~iO+&;r^7N*(#*=;eG6!8CedtSC>OgzvjftCBRh??Kc^}Jrk8@A@I5o<5Ou`ZxA4ks{;`<2 zstQL8aX$W4^jvOxzm}(1LO!vyvL@~SUu|yz73JFg3p)s#ln{^(K}u;;!D**6&nSjK`CnUmdq?8@h_t^mjBztbabKlc3#wcegd zn&TMYOBR7%Ii_wcw1L+Q2qNVxiIvMU0;%NRsuPAL@LdXKP;$`}@0$}XoJH)Ml*U&| z>1#b3r?ppb0KyC=zh^bo^<*rbSb| zmJ+Us5NPZ$TTr#$2wFPbs|ndz9v(K#e^3PtzTF3=XR8tgJOq>!M}vE71tt7-dw3G5 z3!U`x?l&}1$dMH!S#waXX$vX@ZU=~lUp3!J0M>D&T_-UP&kisd$D8vmPyhh(_^23TKANWy8FHK z$D-X8F;N4IGpzeIyUCD%&ewM*F(Gf6$Y=IJ*K?I`HML}u8}3ezTSE7bfb~*!cK_%Z z<)#fe=;&UXF+S@l6JpLEJuzX=XKCkNsKD%*<_|Voxy8B-2!|t@@Z?a#2B+H*Yxwxg?c0rg~&W7 zq8kw3kcv(A(-fN+UX5Luws^0Vcmzv&PB|cCS{{*?T1!AN%72fY(OuSILs{&BPk|vs z2~>W|F*H>iNK7pzt8?@3m_Og-(C{7*^{Ux+wuufKF6IQNr(aoeY_Zv<#4D#W`S&;y zz`;BUsw`6gJZ)A0uVe01!}l)=SFoUx+GE7U#1s;z6COw&qfw{ykcB^bRZhvY_KmU zG#twVB<#>Wv~4^-`bndHbOsT`m2*T;LK0~Toe#E zQVj`J*HhorCS=>Nq}N^ysFE69wJW>v{)x+|Q(PY|GyE4&y$XZcY|ya?Xaf^D6?k-E z3Oa*>qMeWps|Yjb#F@*-X6JjdH?#$kz3=Kkl!;XKHFoxe&<7BA;qDPA8@HVFDw8|K zHbrb}>@-trKLq&V+mnkQU%1qr+)P}rTrCjWpyj*Q9HMqG9Zcbhf@5%SfZ;M1Hqe?Z zDvI{nyEYbvxMKj$Z32Qo;}k@x#i=!G)1lX?lJ2b`b{3{hIH)3kc;mWx0C20VOeaXe z%H*If4v0IATF(M7o9y_vDuCAEHj^5&BtA}a>oa6aKs!fg;tB)v`26Y-pStdJ8wrZW zKV0b?4(8EHkq1o+E}((8Lkn7~xjtyU5KbX?{Nr2XUM3|{P5Hnu(@z8PS`7j{pT~Ev z?ZiYzDge>D)ym|O0cHjZgof$Kqf8e7DhBcTN88(%lulj<)t+lZ)q!$cKyG|zTQ_gSB_oX=By~>j5D@odFd2?e4 zGe4CzzIEcFyhm~tQ1>ZUv?1^n{@%ll%Rhw}@MPk`cLb1A-m==ueVM%gwI*|Ryn}r1~>YZ)+}I`$NFdCv9iYzot7Mw$PJoH|+MMp&Y|ZeLO~o?D%q?VWrQ6 z%%jR`1Hc$>I^+Nl7SkypI=6x%4^R&lntP@8I=`cFxe5J!%()3Pmg;6qv~mO`XmK#D z3h{FCdEbHJfx#`$qY;Ft(am)0z_Sxf58Q2YTEV^blAL*YtAOr8UC+V5%3_>fzvT^3 zP4jpIIup~j+>xDKY{B8wWV_14JjEyJs^u;T+y2D+btc&?amN^8w103JS!1MuEl2{oBSmr z(a0M+({wBpSV+bnTWCZi%qkg*rZe+y(D)&7dwN~CF2Xy4m*-sv1J5wcvxDI)b(@c9 zUQ|TZe>Y+xO32VsI7^34MP%%021i(<`Y;n-={`L>>h7Sk5cdEn9r>kj#ZZzYrBEza zcLxc9zn}~b&ihqw-uhL%o8aT}2n+uf&;%~2SfXM9dagoqCS+D^uk0zvk(frx7g(fg zx`;Td+NgE7WSrm@)E)B*giI4_ZAP`_P6qhzW4W|zqvHW6vn-j|q%QD8r`*-T)bCfR z8G(n^vE(DW3P zru!gnNLAn|su`DY+F95_k8zmA5;ZFndyXRBKf01*$E#(tz=j7Dr3&E5>SSxNaGvU1 znfFh1Uk7{B3bbm<;z$X1mp$rLV@rZ|*HyDGMdhV*$zrF2ZJkxM?U4k_AqqtiW;V7gX`Cgxhp0?8(pY|s%Lq( zsW5`3vHTK;x-++{8FDX*E63egi-#6@&=G7Yv)WiudSu-4Kxc8)k!j5Iy&{1aVK$ny zsoE9Z0Mgk^cFjJ>nHmNH#eL4BLF1CUyo>KbJTk1JOS5LONQUmG9PLovM`HLypL}WP z!7KP$9{7G_CS_denX0T=^nn!fKVPm=sS@U4`vu zqmnG6WVaM|r?w)Si8e>CJFDL2hq!}C7%1zS?|SU|3yGqLT0HijZGAU?E`dr)$#+B3 z4CNQKYMEx!>KBhECAa8pt~0!F`148P$J&PSGe^2MW+f3ftMFAfb%=0!F}lpJKRE+g zUGcufRqMEVUX@y$BQb%o6%czKRQn&0k(If9-3I}fVNQ01309uE%-N8XS&_Qy0Gj?t zc1{4jeg-l#w)n>_t>*@(u~RWKzeD!o7C-M_w7iV6v`d-lz3WSv~KxgW7LZ)+ojRe zj}uygRXSp*8GVCZ3e-H3fR&Qp;1Kh@?1rc9!p>N;Hll^0hgQ;F@Hz7rl8^5`l)5Gt zwUY9(_k2AgAw#cMU=_oC9V||jog_Uc74}%y@BeCbG!gO6KnneQO>pJAi$3|rp7Zoj z(Qf;g`{t2(l}6GO4nmJ4>SJV0CRI@_jA; zM|b?4j7=6MCWjPztn$^GhZAr_1^L4zIZPpEn!7xS!ftsMdsjsom!i{1aZCOMUc9QW z1Z#uo9+`<6Z46Qsn^Ij%lu9$-K<~rW-mumfSi#+PsAa-^Vmsk`Ikq@qYmj)iasGIs zgqh@5KJ}_n*q}ecM@Js*KPgJm2x^RL73;gv4SabzsaUJCW;K%AqEmJlN-ji`B7pAC z&u42fB6)T_YJB&Qn-e3_B2`@ANNse~I5H;nQv1F)$x3ZB+(EOo2w56x!|X8L>}nn# z+OHM?d7ym0C!4K2l||bUGW@t_+;-H5s(o`?Aw5}{2KyBNi0FJL%V?q}#P>w+*xlNw z>9`;ecym(>HGvD#R}WTvU-X_ePB{FlX1zkB{^(6>kC^kqR)F*RU9nA17vIO{HBdJs z#1Ysg~;BswMpy1Z?U2Iw0{a36=_wtsa5QT5j6}!Q? z9`{!bySrrXy(D)sBroT<_jRcqE$PV%oy~RoUXL?J?vA>OYdxiB4dak(d7?!FNmxt= zg`6xnubKGLyTVjTICI3B$ejM6iOO}~Sa;S|pX)WT zkMzswNHS@reZJh_v6Vu(M=kj)EK)lJZt&&kDt|kH}rHOOiLn-N4ta|55YA(r&{LJ>IKTYV$$SNh##^I%J0>44b-z%s&uJ z^;$YcJFi^}>wIed*&2tbUtUst6}Qzrp)^@O6q?MP&nbRonA;0IJl)^EYnna0PHHC| zRQc5kWgNeiYY^+?g?<<7Q95WHJNYyaIbOL~{Y6E93NaJQTfkEmiz!VH;OnO*Y|7aV z*S6lty%;8KiPblTRF}z?E5r}xE~KK$$+_jcKAtxQ(6Me^_&8A^^U`?wlcK(z+Z4`@ zcjGd`t5_6L(eVzBQYpO*$cggYmJ3=Wd-;St2$Z}Wg*q({h*@0$F)PB`YKA`xYnR4r zWU*-;#(s}~&Lc?cct!8%WMjy9`qphV?;YfDuswGdclZFQqX^dLc&t~ImCEAYc1Q*KHfS9p@sl#3)1gv4)%)LQUT^2;F zzN1fAk#!Y=GZf;i{73s^E}Gb`HwYJN7_Vf7N43z2h9{5|TPY3?Nd|UjvxL{2*R`|k z-XLG50V_12kACK)F@|@Q*fntB2{k`%T1-w}jw60p!#FNQ(_1vA8rrgOcWkols@_IQ zj4XWO{)iy5fhnE`EN<(ae>U!qr}+g$KzDbw&dOm*za z>B0iudpO=@b;0Cq7|NAFPoxH&;g+}z=8e2JJ&T4$>kMam8-e2|mb1F|LHN6|KAW1N z!n3m$YawtLP}FUG=7aC5^RT=3l8&ekppc&<@Mk(hfHEDnsLy*|P*siRo&wkqPJQH@k&t4uj=lj`erCG@C@SS3;Vc1hY* zvWUpo#@An|DSE$KHMM?eopv#J_lb&1F7?9O3}-ugUQJ4>>C4HW#IzWK-yWt48$`I< z!$e8>N=F3k7A(|sv;`1__AnNhGXiN3W7kn*3mEVoFnO<|%Sf0IE+tO*MU3#Zx(n`m za#FRu3bF64?LFnrE7|aWP6GjH25pd_Y8BHoi0ufV64Ui<_%Rk5$04HszDnf#2M;{| zCkWX`FgvKAA^(L+eLU`jH8%_|M7wD*jcxojP`zCjoGtdG9zcFb1X#6bHkP^IJN@6k z*JSqVQbaA&{CuR<8dzneMaW873b)=2Wk%7j z(DeG)!)uBUth2H+kUt2bC)NeRq|y(M0e0LJ2+=)^ipFeZh*QR`)yXj6IxuWJaHjvk z^b=7UEd;-#@X~^lFV9VIebs;H5oi@kn(9t3mKts-8co_1@#9*818YHmOpkkj9ijvR zGScQibl=}7{-DpRA?;?S_rhQR$`4`1Tj3$Y(&E2tS7mb#n@Q9yRwqM&{dDdGAR9+7 z4vY|pgnAT>GxT=er&qed35_Ke|0>nw|!`drAdtgj=uinVyBQ*tLaX72J(S_R4>^Bw9m8GTscC(pJrY_cg^(_ zWFSL{DTHUNd}%($i}_v@VS$rlBND5Of~4S3n*a9gonbx-iOVLe{Es04Zmc&C#rh1L zEFGwCi;u^4RC@SoIVpkqT$c=;u0Q@Ovy+sJoeW+K{p-Q^ zdHQvSmG!rFcrN@HVaF`JwqPQ$Eo5m=MdZjVTnUm8EqBIFI4#)pCU^ z3KNm9KFFxBpCGgyVIkK5kw@lDJQFj`)N8S@Pwx{uct|DG%DOKONP5Y6t|j^;ZMBbZ z%PP2n2pQtk5ylCfRtb1NDO{J_hogN>FvEamK&FjR;@ACczj=0j%0QNKYzPFJ8MbaU z@A0%H`9XgKv-?oN1Hp&I@Bfoz1ZD7|sTw4?C(_pz;7v-w0B`SvjGjJGtgQ}9*0$;5 z4r}^ot1y$S9k@AZH!R?S$;!T2f9#FOaDtID3)Sqt_89@oKh02-hhs*`;WBPKPE0nL zyNFIF7!%#;(MHVBbpng^M$tgdGut&)t@X*kBPYbM6HEryfsk~Di9_%wbGLRRg!|oJ z%cETcqv+{g?`7J>FIq+|mv=O_%`EXLWaTr_*@76m2VB4NX|15JBbgBw73>I?o*GM| zE-zZVPgfGjHW~7{lPh4hUG~Qt-AX?VF)j+8`OBGF#x+$u)7adS2;?i;uG*T3jt@Bg z)A%v=x~}TUii)tnN=)-co&3nl4SkFDVZAKupVVpBNM2{f4xP@#s(#VN+(_T9_FoSLJq~QhmK$cC&x_9w<4)YD#x!|v|o0ncjNE-j}_j5 zVl2S$rnoDGHHvLO1quf~^%vl>ML!B2NTUmXelZdEZq>mo)^rqm8;TBnr@f|+Pa(dL zbx!4}bGsW$5068>W*exoNN*=LX~!Jw@0&ac&6@_BTuw{OF7u1Wz|to@rubz@(~oW!!oE0xW6(i2VL4*;em-QyXCflf82rmO`z1+M{+R zVS#Rrmaa(H629Q;=6bQ``fl?A{xfQksP^M~i_NKKeKeK_hajqt>1B@|ngk zJgF8BR=g&HV4HE?hh%ELS4Co3TD%0KB=yai{M_FQ~)v6c0kT^R|c|NFJn3K+OZhlhr~4c)TH!O0PbnDf`7Lk0`dP7+35O9Kl8r`AX6&`&nDz zh4tl{9$3;TAb8(&I8PFwfm-Fw@Bf%YE=KdozII^BKqOL2>M8wu`qmqNsaTUBQ-(~m zt%}J#heSIr2t@^vK}-!|nY`10xilPcKz6yIhv41Uod;DxQe*Aej(o}EkSfc2CgYcx33|-N!6E70xhiBHDSlVwy zW`|4dlt|n8I{=sDin*=}{5FCbWMw>E+vuX3dy`^U??erey>Bd*G>fMmIPq{X&ToHph`&M2n%I5gMk(oJ+q!nTFr4Ldm|HeU z@nfKZLRvC@f=`urZZPm{HBi~}9bt-6;+5WUTRX{^lVu(J6ca!~E z!yC}AMot%$h>@4G9;?fK{)VzhfsEXtGi{jJHW7sG^({XMBZ*Bw7%xN{p)?8J30atM zqb7qE3C|uC9L=??_U^u$&84Mf-B8y7#hwE1U&BEF*rSOJXK#wL%7}}nJoaSoe3~cF zX@CO*Gy-(Wp6mL9QqA8$ib!y&1}|ky(;N0pX=x7k}y=( z_H!xFVV;bQp^4}812dIRV%PME!bJKK+P}{w zxfk;>v|xKV_jCnn@}PniWM*ekoa>H32S-njeVWs6%QKtH#be*?VIp4IsFsC?9labKY{XHeU63sXN8(km^ zANyO4>*UJmAlBPydm$(3*6uD;fN=!|Et~-rDve-@q0PPBP zvuBZL00T3u({4>|s#S6u_QHN!#kiGe1`Qa$l+*SE7*mJp(XO}cRx7SHxrTGG`>d@t z5WtgrKU(65|MfBT^GsyHjeFM`dof?I%ObsZ4Yxh)#%wCWqn5`$l2=ZxIF9>_(e9`z zg7j@hz9{ba{p-ODc-<4QoK75|2|#mj7@-bw(x`qE`5|@5r45bOVHWoQ8FW14d9I(H z1+@d5a}C%M^bp*GWvM7|c31MNQD0Z(lM#RJ0zbfc>b6Ke9xD)GJpwR8tBJvnhE;nJ z2Q?N)cbn5S3zG=|Q|FOlOCjrxtC!?!9;?W2odD#l<-mXkcRK8Bh)CSrVAL~>A@v7b zw&v?rf7@|6t4qK>BDZg7R)JeCSIk6#-b+(wK9$CWGado z+>$MEg?tK3N?r4YjEDtIt0SDMv>*N&{0O{6E(zb+=wA*=FDDP@A@v0UG-?CxJ!*=} zNN`pXb{fmb5LE5+6yv~MoQGqjh;V^Mthsp79F+$<9}~aA#JccZseiCpzh69O2N7*} zyOi=z9OmVDAs1K+{UL6Uu`iNyY5r04*>%a#KX1tTMQ1c1>@vPewYV2OY{s1~IR_2U znUu^E(Fa*?t(+`)JxN=g-2PN6Q* z!((`)TlR5$qNyG=N4+}0?gNk$B4-!921j9R|F~73yVcC+GULPh{(r}ayKh_^uzG&& z2-~b3`3JA{dxrmD-`FW}(WaovPC%%|u}Z<^XPeb|Qw>8`$N_|)5vMy)q@K@M=RF0? z)7AuqJUPFcZ`-3--?r#q;&=F!z?t!**0$>|@JahTHnYBvo#V{&BV{UijK2Idkb6s~ zcL7K-L-URBDChCO?ufNBXUQOfF3h_+T}U*nwc=>uj(z{|0j2O<-^sjDf$Y{#>C|62 ze}@}@Wol`8(%hT(XL0~4-2y$-^!wNfUpl%Ll@a# zh=FjR+(B%#n4hg<_@??)tV}Jec)bnyljt&|T8ANI@Qfxew~3|nnYQMVCo09lillkL zm8EfX|FGD*PFu-jo=w{45~==LOZqj8ivny14c6)#hX6}e(!%a|@wN^{a>0G2KO6h+XLhI$$iTR7 ztOkC#MPb(g>maR~7XD5&3mXOs960vCx*vRJ0;-|#fmy7hQ8bSafUHxu?DrMr+!K_u z{P59nu|ZgbX6T^AeovOOT$Cqw({%Kg0mZ%^dKJO=-f7QS>L9xuJ0>MZHa2-Y`(5Cj?-jtI_^q; zqTfY>Zs8$ZSq7OCr*-`u&*m0wyN_HsW0m1=ZvEFrP-e&Cz&EwBcVlqZ$u5HfsYC_B zy-xASSz^Rl*RFw`95nA&==xK3%;RIC*>~@>W~fP9sKsV+imb$PNEEPA;42KpVT2#H z#VH6fMfQ&y_54IE7Pz}j%c<>+_{f;PEuuma`9gTw$krnfB&9C_KV=c;+oA2lEDl@%KtfgzeKg$(%S&@ zt>~47)u5K6hZ!#q+lisby*)Vf)SqFp7oZ2knf&0&+S z?Ae=E@un>qQ~$g=r(G0C(+4a&y^CMH!hC$nyn?U$WR(;qz3^nz_A&+9PxPBH#y_YAAQE2 z3g#}G`r)QItJi|eK3lAqg;l~=xIMYTgR);azoO_OdMp}S6Ct*!U%>EsZ_Qt)Ki>OPJoU*Gn`&x9Wjshvcb&eK!k2XxKQueYZR5B@{5b>^iO7@w zN&jEEDB=n@o}9U5KlO1R6I}sz!1GURg~dWZ1yW}tEdUJGuxg$t;W(N8W*Ff|XjFuC z)F{iaJF`&az}1G&_d5@(>f<5*3rtOgf-*~QCYPe!(x^OTXYkhjPYrOzR;=6n)oOb2 zUM;0KgCdcr2#ZWyk+6S1@Z^CEK9}+N7VZinZsD${cr4!GI)SaPqsx>#-e;lEm;>|% z{NcE#G?XAM1IRjWf`I1is-y3-I)O z=S_mcvsCkM>%T9I&)3mO~Ya&eP{ED znRZZFO<4DzvfU3VNf)WtLSro2X;(LOF~K?|YBskaIutvJTo#F4f|)BeXuaIV%HCxf${Zp53dzU^xL z;J8)IYsSlntAzI6YHJv1Lr*ptr|p@`+3T&rx_%%*fEmBnq0d0|_EwOIud+uO z*bh|jQ9YPaO?x%2#*D>f1XU>P3Z(KR6eaA~-Rtc*62N?IkfpgAu;?(O!5thHx9D5d zz5+gNC7?a`N*1e%)((sbD!@Hd@BA*8`p*S%P`<$lVwZ1c;JAd zo0r`sSfI)4vIfX}-Zw&abI)(Nyx_{oMr0Jw!Ke_m+Avlqu3XR{ScTmPEZGf-|2NYt zs%MDLjDu;2eEYi~;6G=)9ydzr{O9pMNAI8Vfd9Ps_xOL-5c+>C;{V;z|IdT}!|?e3 zaP9x+(f=d-{^!A=|5Q-?XA=L1-TnX5#6W+}&i}>HL4&y?V(QKDew688_u&P`5c_^T zr$34ax)>2F6+TEic=@V2-qks|5O-q8sBp^_2I(uQ zjZ(2VY`wGGeiwl=vHtZ4!F!&VNbfId>CJop#)y<{r8nq0{nGjQ)xU3!5g*Ayz&%KT zC)j*G{1RT0`#A!}5Y-7ib>LSy>j))>CSc@+zi;0AhoJTx+0V75rqG4i) zp;(wSVk-t_LZ-@PRe0_kp89QNh5HD$7#Ih_ITrQ__kSbMG2H;h+@FYYIIn)Mday0< z3mRoy)nq(XXYzJ)0-uPIUH;iQ7#=9|8Wf(CK+wMqriWSmO{iyDJ@5<{-2Z^Y?hTFU!X~gJ+nzUwv_r zT|UF~VUX{EoniX9=g*!&2N&gUy#CjqA@yvJxBF+*82QxBfq%DEw3G`J9|rv|7kLL= delta 69526 zcmeFZS5#A77dEO0QWQZcN(U8Ds?v)TMQKVC>0OY}dnlo75CIht6$RQKjNLs?I)xgI+&F)nwf-&QAAks&y}owe_uyJ z;_6kD8p%85la}t5j^GwfmhLdS=u%BQYF2H73yN-9t~hdp^N8xL8~1(8mL@3^bvF(> z);0GUdGl_a5NOpLo#v9SJ9`wXd zNP`rTJpR6+I&zeTgcQsE(ttGjvq(UFbAY31US(7!esT)94J}3XkzmBtD4C*P zU!o>{w01=yb%pME+i9YI5Q2knXO zPI)v1_^Mp90qY<89H)E-K4`waQqKI>V*gvl|E%#VkNwX#{ue3#2YCbfCw*~#BHb=Y&rWbIi!~3FT0+(f#!l95VTU@+AOd{6F`zDzU3N^cY2SUmcW3eET*NSh{ zV7`~>jB3gg(1P`AH)X!R(OGI|aVd`wto_KVn{Um)r&sIb?>fDE0kkx`(b*|k(HZql#1oJJDqubhh!Emyt~7BZrizD5YWSeO%` zLSLv2xhp;=c6qzj#0yJ6>u5?f2i=TwK-RR6wt7zo%s*bJnnDy%bI4tnNqEQxuKWIU zAB#}*CH1lj2aHiD6@$BaTQB^g*)ja{HT$9bhebveY5^_0uiq~o!>c$$G6hb)1VSs$ z-Edim(A#24ekX?C?k%5wWlG@gr`1dUUGEF9-r1jDv??r4ERCW%sOT?S`2P6zl&KYI zT9;_nKBHFdeCxvG`=@j~(hV$>Xb}$POEN1o^7|#SYwwTQIcBWCL5Qz*{A-5?+fBo1isZ0~k*0&)PG2$O znXl2Ba&|8D>tSGXx+qU?VoSm#`y>4!+tCKUD%tf`x~(3W)sbfme2EHXEyBWmUOmPYuw7))_qsakF93wly_>&6ly)A_W3Jl^T5Z@K`?)^5 zoB|z`LIj-o*2fD`BQ8yZIY(v7j)$?PbI*<0rNe3~#ek_roqhthNVLedYzgc6In{f8 z<8FM4!;*`WaVKGK`cQ)q$0{aR7xq@0Mr2vP*d@h#$~W#s+DcWCSyUV*d49z`-=)rL zd8u)4MI>@IpIlTuK^zjp3l|$z*xSp92{!h;;t2f76&dm3ZJ0BYq-&~(Tm{F8Q4%E+n)4Jl5mnc_-QpSqK=`JG3+z=j+oRSRrB_2lJTkfy=qDNH{x!#8AHBQI(mQDT(=c zNLYn>Di*7u*%zo}SwCqw#vNEIXJhY?+QK>P?qs_6>Xe=TWUp5-=7{%q;KY5tCHY=& zFKd6utEw!<)lBJ8Nrcr-SK33&u_j@)NV}<1ghu!8Z}p{{IC7_)*LUBWcP@HI_R8&b zNfnFgHA&Mgc%LK)W>|(zd`%`#5O;E)Q+10#K7?wM&0L$wdR9fHG1+(HUbpLYIBzYD z+BN1>9h<1pLuUlM4?5aYQ!wo&>KO0WgFT!~-{3}hOmEAJ>ite5#9Z>^2|&EJ&W%!# zNS)2Sm-Wm;F^i=RfyYWoOvUe)+V-adk8>Ut-O6@efa~PBno2m-9z{oH86z8^U3(t> zKI(Z;YgQk>1J0OC$B3I#muTjtnqx@k-5jQ#!DGxz?y~5Sk&cB|PBsSk z@%WooIVVM)yY?Y2=nkC@ucU7O#TbNEUoG5$M+>vfkZ$id1nN|eA%xD=&Z|R5<~#cs zm)p)v6!J-)6L)+kVpA2y0=fC6a`byJ?8Gto8)R|gn9T+RGqF5yTTlHV~a}C zWW3&YV=Vo4L}H&=hhB&F{HqU?Y*11H)-6BfiUOu4`_mph>q2w*9&}u(dPBadU885G z$+i+Clt5B?qriim`5r|x*~~#j%g~tG;|n4NDNTsWh2(8ivSN-;+4*rEnGZW-dK5KH zn>J|?J&961En1h~KU|@Xc^DAG`$hjtzN?8- zU(3Az&JU?hK2ps5>L;F*r7o+q-Y>9}fMMSez6@8)rO?sY_DGMwl|VgQTJ0DP&zwqd zxTh|AUr;yyjZRZWl-!uy&NsT8V?h(5>o(O2lP<>Lr`WL9p+tR^V)D}6fCXG}lNWLo zAz3KFH1SnJ3*+lLW|t#H;}#=mYA@9IGu=ZrUcx1L@QOm4Ln>0*uJC6cF7-uhpz?rk z_H>1(EV_l9;GD5x(qY_TN*D84izW%)gJm5o_2&6HR71BivAwYx@$mFNE_0O1Sb3JNrXa=K~!uv74^Mu-W?J$NkyjASo$oy6slF-V$SVU zm8izv$YpUNBj-hoaCwl4#*twI$FTE6|I>w$jnoEvN06Mu$FoYgXKn;3wrRfm3jcUE zDOwsyb#V$hB#7p`LFnXTc7a!axqGSL%*uZ6mi%SCTStN)(|@%67@Oc+`^gLn!0Yln zzE4|3Yj_(&6X3OQ11ZM=4{(cMX%7q3;~TkeOW5D&m2q*Zxt;QK*YSR@i|of!-fWcQ z@p4+2VpJO1wNym>?e1ZZ_aC$N|VS?@m*0k0fV5Ql1m71NZCg(^$VB^>XwYCTK zhVFEz%#=yfKW=Q!mY~~oHE==K%v7Z)n9ej!QS`M?R(&*_+D%fLkAH?yFzwuB`f;1) z?xt4?mSaq?;Z+X#ZE142VE$v7ZMq*E5^t4$K_Bq)S|vz9_US3;lDewn(QPGjF3$yA zBh^O+6<&VV5YwtG#CPL{oeB0uCd$h``r5QR~c=NbGP@(UBpC9L&&J@IHN0jeH6wjs<{o24RoSYOjt_AZ4$t)c#E zi|uhN*2!zw5S9hilzQP(ISqnKVihLu7!z1Unt~AvxbG{0=m-rLhRfFxAg3p~C|}Uh zk5ZLAa!>1R-~$6$(tE4E`0MC#O5T|sNNAqB6Cl|i6xQ^)1>v=F#RKMao5x=uZt-Of zx6JpYzrPoZLb~mCQ4$jSL%RB^%r`4BOt8cm|4N4^4A9%>>|J3x8XUO}EZBykG&NB} z4_h~mlYIPoC97r;EMoSat+ZS##&T3f@CG=Cc!53&aX*~VG+OkHk?1jaLtYjxH1KSn zVn|;)`!M3=3b)qw!0_|Jp;==Z?M<0Sf!o?qQ0NqI;4!%D5=Pp&zlADv9C0}#T#&b) z0*&7ag{Hm?ymUl3TrJOa+BH>^#Z1m@e@NQ}un^Ut*KDHxU{zw3xJ;zRP0pEIG>QGWrdFAZSZ*b z70k#iHnPYCu;pJOyC4t5C8p}E;fr?6;p!l^03WI&>KW~I3xa~ zzKgrWx8Yv*Gr4ss5VH*~(W6HdRSa;j^lT80s|v}p0xJtU7`Q5tcH1S}PLg@Mx!li* zYFTwva8)Cnxm&@stdy8)Md4~7QM{L?I~gOMxU z>O1Y(iwu2{iOwo;4>lvujr`>Mi#%f|O_gNV=vi$|@&02q9yuaPHO}9LX4Q&c0}wOG z_yq*${*Sy0j3)En32Hmd~l;iS&X&`0a0 zpU%YvKmNd>em|!)P=puZlWuwP{)ePPvz|LKH;x2)Vpr3n_7_1w#uw^mh~UzYW`VWM z+jO~gv;Hu8C0j@BP@Y#O(fG9+vIq1kwj@$jNG7}%hHnmvzbJMuxHiRV4wT%hq*&^+ zMiXmFib&ff|F^DS#k|8TClOE5)@^j_0g``_lQ8OfD-HkP74^Np%6=(Byeh;OsmXdxm+oo;6(6soORk}Nmsgd9$gjICQOg_~u(!2*ni?(U8)Mei zlgm>hlUyLPRR9W3^OKts&p#O84F)C4Knn2o*C%VhPM$RyE4Q1izqfiEi%>tT-{|Rd zJqf3_%y?>bfgyMASF)hCOr@N>88O~srg#Pz|E=)D&yw@uFRW}|LD69fA2m{u;nI_} zaMV=gHljD{9lQ@9$4|=Z~J^91y{3lZ@RI>y`=H*jj;>DfpK^qDW zbJ6ZUm&)8}Ea4S@|Gq?x^OK_WkI+zr(d}rHE7x@;i;hesJ>f$o{B*5f4EJ~I@ECFx zrlOrl=bX)q)^HDd)c><0KOse7k}cw2@ua7a(pS)afHUp7Z6I^>>E>VuHDPnO5rRLpjWWT?^iz_~T0!=KoP;hMzgL-8S zi+7dnWfp3d)D5-Sk^BXNB7@Qol;=P{_XaU_`CNZ>5qNsBVdNu9GRFL>usFAf${f}2 zU{tkomo)cgYVuyy7?~CLz z956=_Opb}>RUo1Ylq=a?>uy_(;v#cZ!1jlbM{*s4u}s#Aa+CLhWl>;C|ABS!SJ+9o z>GoihVzK2M+QZDF-u8fwfzWg*MqQq4ETC|&UE&D z1ZR5kTYD7ZNSMaYc>u15)C1kGgIP^d@(Q9Poz|4=NzX%SsaZMB^IF?Kt~3i%Tx<#g zd4f5fRYy_h%H7rejPQ-C_c2PQLZVYuh@&`^GI&Pz73tUgr&R#rV)B-Rgz(wJ2`aVh zIIiL_>cO9*yZm~<8614QB?V+J55e^@cVw^kRT#8%S$jDRggk7Bym&!~>CfgloMSVk!-u7?hvhCXXHCnCo@xwq>072p7<^gZYS2E>Gc=Q`0nBfgCampqY4EAu5g-LnGkIp@mE3A>AaM(A#AX%ikHa$x zjx;YxT~L}@ep=MD=Tv~P$|mPBBf)b(`~8bdc~^}k zmZ|R0AEDZDdFE-mjS9J^)k#Qp$HR>lnE~yq0N0IfDf* zl0S47dkvX#Wxso2EOT{HI^VKdv?k|+k!cgiA?4JjsB)SHhE(!~-N~C6NKqY|H!UN2 z`1Bd>>-X;J=VSRnW=-S^V6x!peEDwi{k+#6{`kFML~B7#73i;;=oV_T#V;) z`Z!!US(QC8TR43bZDo>H$9{f+`j|jY__8o2;W!ay3KY+bc$yCFu9W!K%Ha~J0|p-{ z$g*&pFMRY@2LQDy0C;o!;}XeH((^p2oHvh#IxC4ONs|2Sm?eYyEe3TdBv6M zhC~|SKN5mlcfem7l{uaT!U2KQso5lHxI3b@h7M+L#oS`j(1OotSI~_T`;*LWobDUf zMx0PpjIyOTQ&ml8YhV4c&sPL`^!299zheQ~Cs|;U#a}UcmW0BG(Ur$}Fa<$vRD26J zgu5NVD5V&)Am;k_f@fUAmHJtXm?KQBf*oEk1em(DF^C85|KxP*)B6jX0f=+I4VI}t zGJ1uC!kRnvn!4Cfc496u~z+NHdg@ zei73r!2>)H1fvoUcdsYW*PPE$y?jCpZ69>5NVFSxtI!4RV5QM>>ett!U1KOoqnP3U z65mg1z)iY7jdBsc4Jn)lyf)8Q?TnuP?xWThP~gkJ__G5$T*T5`RCeV*=6kIP%(wI6 zioneypuR2c_PsK5KtioZu+HLl3v-EF6{;|{t@W38k#6Hr->&yG2 z5RcY$6C}_6`{tw?sbEAY{_r!s3`pt6FkZ~h|9T~7P!I=DgUB24M;swh70?31wDC%( zgzufPLV4q=v%i6*ijY>`J?;cqze?S_dt|KtSu^d&TR_e*cnqvU@}gGuT_)oS`?r8t zgIMW)e~W}$tIS%}xb#8jqLIo!NFQ7_cnw%Lkqs>HJ=anE=L8Yh3*AD4)BpV0OL-`8 z90iN|-kl(!wVYl0A2a@B;MCgYYyUyP`LdjZ$ODvGbr^w|cwHGOdh(Y&f}u?k7IDWC zz(kB5?Bax6{{rM+E_DJtu*PYyzArBo0DI&3<$bUh;QB0nhpK`FDI>pu#qwAM3XpT; z+1;Y_e{4)#^%B@tnEneq@XSS0WX&9N-H*?FMPR(IiVVzZCt z(L7H1@1KMCC2Du*iH0~uIYBG{KNlMi_z$GNm;IiCIFqfk{&dC<3`UO)+Au%+ccT=% zfCHlVIuPKwJxQp}FbbJDwuDjNsjcki{B7(Hltea#NIgN5b>8Ivzc;=cC)~yk?Yn{D zIP;}HE~4~h!lSn$kgz*ScGiUUo%o>E?`!_DTp5@lCYwqPD;^2Xr29D=C0}UPfT#pt z&U9d*zWJ+v<4jcOPrvOnl&|XrMzc`xZ(ICXy&-5zJf0D~lZ&K-1FG+ScdaE~w;=4q zZ}_DubQRXaikqlG1soE#Rj2is|DtTLIE9O#AHR_HQ5=}uj&!Wj$w9!VyyO&{^hNaq zTZ-Qom?1q*&1_BF@tkA?)kRX;=tl`>ErsgW9tGfs^u_JbxnD%%W6l#b%=3WYvW5M&RDgf5_N`EAv68vf(6*2W;X$2|+dgMH#%`^;B7()yIn z>BD2nPh+>nLWyRgbqxk?WSFJ))^X-Ts9uIrWROFj|9>{29)!4G)dN)^yLtH@pdHw1 z;~r8BvPWN5D9XSW=gq)^Q+-WQ|Bs$oi5h7K#0K@y?YB#IBADu$W zV0EW7TI@ij02jVT#c$p?fvo?bR=0~SDAG)kQyo=e{$&*6j)8BK6K^fhwFNdNjcm$) zLmfAY%8BHVPu7x6i@Nw$8F(PrnJK?jLk!Y%8PJR6puZ$%2^qfd`vONGaG94xh|l_^ z6zmqMqQ&My|1i>2h8SndTjMS?N*Q+CzwU*k>PnKq$PqSm_GZF4h}tMj)D z?`5g!73c{#^rZ%i*$uR+#R?|b$@1KNXCc(E`MSuYW`Jof3lz_qF+r~vzZU*`_30;Q zpJixqBS5|vIZxIOm)q&c9PV#e-GjV-?aRw^Bt#dG#iMm9!D#3gi4XWnuL-vfDNG`p zjF;q0Es}5Aeygx$|F~@{v8W|-aOMNy!aDa=(0sCh8N7PD=%*gZ*^>o^sBAE}>-q7$bDne#(DkKR zcVeZ@VadMP8}QFpawIKPo}S^pd!z0H^m4W7a0<|F4}i)59`XrUG?y!?%2C*Q=P7oPgpo{2z(BQBY4iP<()+)F^LwOuJ z+%q3+#oQ1imN-TMqY*$ma#$Z9``2Y(a)R1S>7JTu{YtB?N?#t+X_U;ggd2n8XoYH#oQ!z1c}J)LjRc|$NvMcx z=y#p?RV=;$6G+33{aW~!v~cz^nbrD1wKtbv@rh&Ein+{zEJq*qXwX`~eFal&UM3#p z#TBH$NMi249=ai}p(RhAjKE$Y;*kcz)_AbIKCvq3o4AFV`Yl%kR~`9vkKa}40A!BY z!*h_fB1oI5?*Su4WT@|AufaFIeX;`J>ge@aQ2;kDUM2FI>WLuSufOC(Smbk=GfOzL ze%uNdH==nBm$f)}`96i}$S)TmzEE<3ibxy&RP8)5@q;{P4Ioq1G;}!mLUwB;(@`!M zagSY(IW!1%lxz{31R*=ZbHEdh)XD8H8>kYluwm{6);EBa<)(e>_Hb}`Ve%=ufXmW2)%85@H@ zEdsSeb>Mt_@IT4(Wf$9X}!azvN}?lQQPWD}}3?JknF<^<(l_rnhJsh$A5li7k zqG0y{yM#R`*V<9FQ{n!6I ziTsgX*{IUa^wAb^9TCJxGCl+R!iDDG;sy8hpK$n&W#$DX8CM19GRp+sF^R20vqllJKC6=U%|8P)e<(C#8nf;c>1$Aj9#6X#ULZNc}Vu#A16 z2uyT@)VAcM-v=)w2^3$iR z2q0VZo^T5{_3Xb*sq4ZEy2L*fi1sdkQx@#rM!=OQFQ(2Mr8+C<2t-e1AU?UZxfb|X@2Ry(pqBCr$5)TR9lKvR+1Y*rcTGK-a=dgaEkNr8x% z3UeUwGIbk$NCbT_Lnl~!SDaqCZ9hLoeUs?s3oPnrrpG^q^v$JO;=62wzjCrVLu3DT zR4-dWPF3}HwPPls_<8o{d--$%EiIVK{FCO+OdTliwCgpVjzS#j&<&;o+ zw`ygw=ne*HdkKnrU$@%m5O0l`sCH8wE=!b9ritY6`Ery9XgwOQRsO;0MCVd?Lqz*0 zyXFAeFD0eV1WR+>A~M=Q)<`yEot^!ANfhy-sCOROHX@Wt0N&iK?hB5#lZl3vCO z>CXW9obJai7Da)aFFig{Vi~eL)gaTd>|)R~MZa6{tvdn3{OyBc_;X&pMiVJMgWQ)4 zyas)r-wJUID>)7JNkuRU-VI>k@|+yQtWx0xdU*v40>>M=Uv@#aWh>6| z8_;?yI^OOyN%18=#d?*Xs>(4f=FXbg zf)@ITPXKhVzoD5^RdI=#u$Yr_zL797W&u)u5$L3c%XIk)Ks=7v=Mr2R*TWh>fY`<4 z8I-0sNFmB~^G&2$;0cL-NV?Aj6F*W8M@$u`gb`autrf|4T6nisyQb&AuS} zV+8{6?8=x}^JD~VcHmYV8<2lrletXg$-!}5vipEp+}`@w@l)ks$a1@$9UF6|lO{en&AS7is(POz;|vM1d)x=%sPkI0rgLZK5@UYBip677;) zYT6d@d9Q`c<#4_oY#P1uw)FU0tBAej?5WWkSAZ0~TyA?3Mulm4+a%#w!Xg8A4=bZT z9`lz2cXW@KI_a~rGaqH}uxp`zOY88UXM0FzyCq6q!(NSSky)qyFio5XZq;1~+PG{j z!ZSXk%2qZsAoox307a4!z*>1ULXnC`jy91nJEsw+NkG-!RGxh&%Ya8G~ab@hVVj`qtu&;3;}Ho>SCL;fQ=3pUEhgbDECURuugtY@=@{ zvq+!y`aCi^)0=}l9VWP|8*GP(Fwu#my_Nb!jc|p%I#z( z`Od|S{Knb8e2jJ*WLG!nNiHYoo$e{zK!6P5gom(0r4vpud-noFNn1fJL7BvmeN|SN zwWVRb`aVw!JkN50OXE}3?@0T}F~+dXFv#iK$6PX9Y}^#DX%xsq%tDRYv+dXHT=>1y zEdu&3M6sSOEXb*C&!W-SLmF5X8C8}8QMXKl?LsVN^rbAr{R|rUav8+dUBXoFo!EA$ z%x;PAGs%3S#|vuq>m&5+Is;S-yV;b@EIc!?;~mWZq&ChSFl~!oeK&9(I9YJehccq- ze?8EX}+wAB=%lUUTS(;gJ4%YjAYpNy z5&`iNeCzB;g+uIHA@iw9=gIg5b=4w>7P`dU9jO2Wem!^C%5ran9N%hR=+~BkNte60 zFrR7@0Lao4kxiauOK~oeWtEZIF5@Yzh1w~D%cnp@N%N95tXOQ6#_u_ zB5pTuk%g_zLo~UkZBRp|d&*~)x&RC}uIus%VgUwnhc%LSvnl);c@y!!0_PO586{9? z%Y!%XyH2r6T7br?6eLrg(C|mmfLzYjco#<>`8oA;=_xdiX0oIAq?@w6dV9lRW0L2O zPuerOFOdq90%t`X=AI9-mkYbMQuulHrJ`+MV#&3LiURLCHIP)D#x@u8aK{C-pp9;c zWuQlOzc~kS(vvL`hedWO7k_sIe;WcMFx*#m8GF$EYtw>Amg*;?gk9UrJ(WR^F*O=rt{P6Mr~ z?C}iUXeyJyB0N*bPagxp?tA)sCQb;$R!sN|^WSV>0O+C`fQZL$SRU}@%qv#oHG%k_ zMLw{8sL)WvsLrD956=7@RsYcQv`?U5aHb@|Ov)TUHvG!uIM5Ko_{{2kOmwePC}y@Y z_>l6_bt(j`PBjdd1O^PQDezJaLJaxJ8JQ_hL<=aTGPJ{e#Qub!)InYz3 zya!;}@#or158u!D=l7!n?a#di^8RMK!uFKLtucop2MmP#gz+(=rwcYXj$Q27I9Lhi zCsk*R!+i}_s72asq)F{$6%x`Ej_avrxwSV3;fSX?E`1~(4+#K=JhnbK z6pvs$VB=CDtL0<*=1ct1hPEXR8+v^AYj4%kcDa;zyK+cTTAd0Pp8D_}>bjY+DL>w@ z^QASHOfB}~!0boYg_jm;&j{DQFcb`}&MA&lyrrfV0K`p|Y(1H}U2jx?i@%NE@#k)1 z?{XX|`F?gsb1g?YzE9YWdm7_CqD)=|d0rXc_@0qWV!eGXiy*SGQEXiYD|(-3o)oa` z?DdQwvNR_Ojx~k8ymoL-4MNokUuZ1JAXir*Ouf!J?5>t3zgMWY+>*9~g~^NzM`*%h z1lDK#3(y<*!m3vZ)REsBl>=?I_M}mP7$x@tN4_djaTf_bQ~r&HrXP6>joZ|9OJ$u) zTc;$90ELzKT~ii+fAHOIPNMrWBDoS4i5QA2@xoXwcRAZ9&oV*`W%U}>fola?*h4-? z`F%pU{GjxII~n0KfS0NVvkw!7kq3UuF5?a?PEiCWKgSHPDNMVE;Z5^`3DIh2S4GkG z$O*fQWHx6Wzjq~W;6&DN+8t1I*Bw#h$WJ~Ps!(=B=Td!ixAT*pt1MD>9<3PJq8!Mu zK%@&{5(5u<-QS~guj@yJu*_AtueuRA)G@wRF>JD50&>*$IvK0Xn-)1Lu(}J|$#2;= zDo_N|ocpB=tN15ljrl3^AF1|h`bQ6@Ck4x?Ck3C6HSRl0_BIj_{+3sEtXRSrk{Y`5 z%jK`z5L^aVQ4Mc9*$o3o@GX}vWXC}PjUSgPTC6_%Nl%F|#@kJv?w9G19SR8@pekpz z)+tsS(B5e-u-1GzClydX<=|h8xF=DzOvT%K1EvYZ$#^ zFA3LT>)VC#4C;h@#KK{OVdFbY1lzxZk8h12x2|v;vj>Oo1}Gh?2wMeCngkb7k7 zpc^#I6J=QZxTErH%Zvqqq@z4XnC z&Yb{}dcki^+wg)z!nC;6hj1{xwCu$XCDN)Rq3YJgBJVfLeuY4O{Gj4Xzurg6(a9j$ zfQ97gAFcVkOT=F__?;s-!vKJ~)@q|qaWVS6e5H`OEjx2+acM~O`F2y^bt@TPbXBG6 z@KTAcalKC|@jMvQ5AJ~eR=XV0LKhjHt!o8-6V052xTiK$L%NR`*X}p8Ikwe8Ax_&Y zg?w5ZYhD91c-l^OY=_rw3PS?im48FPiFtf1y!geKd~=_ItfMPyMMKVH$<57Y+w~89 zt5$nlqxPbBogLU+9L9U|81T%#a7t6bKE=lRA9BSB5IQrgSW8uvGNGOKawqd8aT)Z80Xutt&cA z{QN>1#Pl}w#91RyvYY_mXFAv)g{4&Zg`KQ4WvOC4H4p+ZuT?jo6|?q_<0#>0c8VSO zkKuXQ%u3RySy?gu8)C2#^JB$7%q^oFe5hZ@Itz|RFc7e33*1{Gl84QAG$h7-$JUc$ zx>s%{n=GWQBuNCkTtPCGhsRE}xkIW|u?Q9QAKy9ww^Y*(cnTZ90`-)>9Pq&|?@rkr?)$j1Kf5KwV|0zjz`Kdrs9o^slm<5H?^x+#0f?D0cEhpIAkE;1 z;Pg|adJm?ma+GpFEXH@>jU~q@x4C1&!KSUtSLySi2*?x*gCpjK^3ycRk3v_yLwmnlfcVxy) z2*}{{QE#nkZ&lnR#h(63eKyl!V^brF)}3C0Zmu@cS&9*&{Xj~>4cU6uM)l!xhZvOmy|2*EWK*_6;4VL^) z%tkyGs3joE?WQX>4&rR=yH`-0laroW9A>+j-9v4tYC&uI!W3|dZ>wLKgLv+jwi4SC zPE%C}YjPP^^6Va(YqOtcPBG=GlezmGfr>5PFCCNJ`&Y^FM*tFhgrd5kcYe%9$49QW za>PuAHYkR}`9bq*%;*?HK_LX#spPTcD=OYq_X+1v?%Z8*=DIgZpB;29tnOy-1;F~R zc4ke#z~Jx2cBTrNRn2%$*KNIHlSHq$)-Hy?FLC2N*>?>u+XnCU(?nGXXEb^~*}5;_ z(kWlVqljdN(Uk1t4&4H`wwJpd6?-EHCA&s33X^AJM3<#7CCTP7%V3!!2Lf*_Jc{7$^fq0Z6FNWM=33yhDUQh12P2&6`eZt3`T+divv)meD!(4hFH|?1;;=X{OhmfEA{TQ>YdbjW zc6flbI4o~;71t$azTokYQPVRRaPd-BppBof&PsE-tEyUB55~@fkdY;J%$(koVEGTP zrSv3j+^+BM-8<$9xVfhqpKe)T%sTb+iUy`{3ca!kCyOnvvOi0$ zL71xD6Rc8~NMxx{JDocpq&Mrl%@GYRIq-*}1|3-UP2lo5rvlK~fm1e{0YaTWCvEgP z>rxH_v2jDiiJnAi~71NE{xp{i3eV`3h!Mnef7l20;`EdtuSYH=_p0Z|an2M+0> zpjl1i!@A+9uI8tV&vhM)-0I$cmYPA($$aKDNV5=4)cXguTmwKb>a=Lx4bB`AoTGO< zEx~*I)u8%ud%~HDy79u&=%qJ08lTE1sRsNu7c7CeKppFz{0RSDC{9;aS}R+_Dq*u* z^2iCFmn+E>Ao1?;X#31?ctQR+*gfx(+2?eQ%NdxFsn6u|s+WI`OBeX`8teHSd`3Tv z(X8p%y3fZ!G=y@Hc!5QOswrwQ>XwDF<9T}$OXP_-yo&rv^{gXcTJ(TOrer8y_~A3t zJp+#M>x3_vGxRPbp#sIG7T=2^b<4!{MmN3x?Q<1+Ah7Wsa~)$8w{$H^oz&^lT~Gnq zljg!M^(vUy<>1dS;;dfSX%1r!In~;&P9J_`@scortot~}tGr#tmOUNq#nY9A>DWib z$;{`s)%OC5Z%8XP-r6^z9D6B5QaIvQ{x)&Vl({pBI$tXK8{^K(w&?V<|D@rT{^9Ux zZyIQl6Z~|})V$o)@#^lv=?W&O@iDFx2@YCFb03fjR|^tVwl!Ne;^m#-$0l&sKMtqN zsLiuaE7DlI-we)(V|;SVT^fAh1=aS)2_-sA)$l%968U4l&$|);{V@4`- zmqH@r-#Tu*nIsg?4Oh9;nhnXh9uzMRiPvb{K#><;8?T>SihD}lL|;gr7h5}iqTl7^ ziV)JlI!&wk!9A zP%!5nMB8SwbORbC9)UjtJTSDb(UI*3n~TsXU%_#)d#jt;d-@~DdD%q1(WyIE^{
XB-&q`qMQ#|eZGYo)|0q+_xW(~^eei2;;$u$+kRlF-02Lq!%$NXL+8#sFGU-l5|$~7 zH|*`~Ry(@^OZj`GA5&E>??*f8Lz8QYDz|ny zX><4Jhgwtu0=Han0kK=Q!d3$N00E>lE#?cvb4ByB z#~g80n(r8_+|{Rp*!4fU_}&Y_cScqnxn4#bfBc$#lHLa(CzU+eW| zb5FJBWZC{MzJg2^PzE4qkPTZO-TdSa_dQ_yo}t*Z?*MUBC@a@n7|S?~H!HDPY6kLwVDddF&*Yz?bQ zsZoVrj`#ySip>$%mLm-b{b{AqDFTMO(?6XYA!p3p=2|(29oEmw7ua zPnPE#KUp>o7 zZNMPY?(^i;xA26yKfj9s4uk<^W^g+%g|)IpdQn9c4PIs1<;v(NDejh<#oT#5H)zn+ z0p5IjtFIxT2v7%k#(FR1T)!v~^*M>F-Ekrv2-%5VMn`j(1my{5y)2VV`(`f^PTEcd z!n?**gS=7?)*&`nl5K&K=ZpBYr})*XdSh>?@x!|D(8{#&Q0;O3bjRw2rH6W1gf%o4 zi6DrN_gA;S8sgE?e50r)dqDtNn_bnzw$FGu7wIhb@3EHy!b1v9Lp5*~h)BPGW~*-( zG%EkNdy?5gBzE7{*sS6Iq3f-qs$QS)QNc~urbD_rq*J=2kq!wZq$Q+3G)RYplt?H@ zNSD&3q;v>U(w!pZefRmE`2Fs>cdfnr<1CMRzcusB%rnmn?M`$}Zz&tZ?1htx3`ZN1 zmah8~*K7{Ubh!PS${|nzhn^Hq;;AkYtXDt26<0wUkn5z;c*)`!{^FqS`sPQq#7KaJ zt)TcKRADzZ51R7rf#!*u>?z2X&CO^&sD0YT)3EpA_Ki`(KyoI-dYtu_^r)0{zhgP^ z?VeD)5U=SEc5Rx?94l9@!iGf)t{h^vuTQ4A$|+{%I+R-X@auB=wjv(JWjXZCUwJ*- z>pbUX(R$zy`*YPgd%j?EBLc0Q*2ZhpQ3v)xn0T)p|A@8Z*0nBKfoc;XI2oR}cLTIG zD&5AV>VGc=xP0<8edYyaZB7K2UlM#1*}xstwPf($ZzRA+Y zEWU-#*lzLDW{uZLk7q^`)RfKE(|;$-1=FL@x6(LiU5(y8I@jlRXj5w-g^Am-@CGJaP#Ic3TT^+HWj z-gUehdC>FQFBq?_hFE%TSopf#Bh0v1#HTN;+7dwI9;m!Wexe(gkeg0!F?u|m6z>zkl)pv7m9tYZ* zKt}dELS+rrMXDwxDIZM2q3N3Kavt86p^d;jtlv-o&&}dE6?v{oZw-zrd|zxiwI&&|@vZq(UnK#R84P;>;$P$@z^3HQ}~OqUQitC4DS-LS!I zFO6XiMIqGWrl}!Y<&E`9%4e0z eI#9rBtAGfjko*j4Qua<>?g=LIC zmu@K6O}fnUcHNo9Q60Y}zg^VVKpxr*ybN2s z1ZK^8C{sxArey4`wbG}LE{oU(7bhbR_CiiZG;g5UnO{F@bTvfDilNixNH3+4+>!@Z zK3m{X=%}4v0ZR3Ez#Ve}oZ0xVw=*iPC|)zS6RrUTdv)sdeYm$iA|80ZZk9fTyZE?s z9Kd!AczxL3qy4{auads>YQY1CwpoGi@L3!*3x}uWL4=9v4IvuJP{qgNNaT~QMe*ws zg0u%8*g;XfYA9FoJ7D&ZPTs%*RzbZ~$f7-{@I~NBoUr2(kV0AJ27N^VXG6l;;-~i| zYuv2AfBwC6s51??b~iM>tk13-4BJ|r7JOZ;))eFJeJ`HI(|ku>m(#ly@dnx#9Zxs; z@rJj9yqCV<{+~#QW;atPGO{WI&~5drtQ2fV|H}Wr*q`50gQ?5Vnxh2PP}L9CXWd@! zeS5RN*f8_MyWC4{d$OP1*r3!#J?{5YE97B~e^Nxwz}~K|YiT9P6JTWaeqk(wX{U4F@hZhf*Oe4b0_#WXV(OLN}!#FzZm z@DY(g8f7>C+^C)1V5F6wG5QK<%?Jwu4m;2=3|_EPLdc*@1cB;@gU|1^68N6DM`i1;MH*r<9GCpJ z59iId=TvMYYYKE;n*M-_v5n2#!tKdO8;akz`tC+@Oq&MO5mJ7rZTv~#clp{@hm=Wc zWbJPMzPmc$k^vq8XbZIh6ffli!`08FN>>EmZEBoqhN?g|CXF%I#5QrVO3KTskZqRw zpPC5#1)}izLb+H=0t@6iOJpv^zEh3p#n~-rH0VH6?W*5Z^gA)WE#$6`QU@~S#~n6S zsiZK^0e97f$z{fSJj^@#!Z&YAD|rX>w@np9)a>i-*2BA=?X>?$)D>?Hs!fx3!@ z#oT5aK(g5T{Z@`2=T%KrR->r`UGrQ8^|rJ9?1xmzw6ESv2pP0eS>Gc(|DX5>QaPkM zjc1&9i%@)O4Y*1U+e zOPNvj9&_)QHE)D#h)D}1UK1P`N361(J_gvDWG9+I5WB^n$$A!#yMjO8$a>J7B6lTgWTXL`Iyk@hb)k!-E`@X=NCZV{?op^*`$+Cd+V zs;#xn$)x6UeJ-~q%yJBC-nAU9XKCNly!qj`Uv+fQ_U4^E=HVyLgMHZ0DCUW^CA76K z*Y#;IhrjQ4$%*4XWCF!_N_)%+xrcy=>@;!DMTE|$@xJ4xmY>&`#0i>T+Y8^FTi4PA zVl=aPJNEY%#LxU5@PH7Dx!3m27wZvs?aM(jAAFm$BrcWuE>YD`?GJN=^ZLyp=eeYBlWFJaNl*3NeT{E*SPCfGr+>0zXj%E(4syi#4}7SpUx{wSEH+{D zANcDW?ae7z_%fxeDc|3YFXn1+M%jlr2CLl40F5 z;;E01KSqdOR=Of@jO56r^u{q%&qGUh#@=gwRE4Gv7Tc6=nmv~{Hb|Fwp7y^YleEDO zLoe%wOHTI1lZQqo;ch+ZOdxTLmLvLJ>l8yR>DNm!oIP8^Cpp$pV0E0&^ib==qY|1a zb+QN4F{E6{fw`bTtZeNhk)%G8uUL8sGzN5ny0G3=yLR|1B6m9DE_BPA#}Zvq5(a|_ z^H7A3MajIpeF985=&w)vD;R5WRad8QF)1go1QcE zQy3T+c=Yxp1B{rRsG5LWK&BeD#2O6 zWsV3$eM!{M<{SC^6%(d>K8hy62472uz%U8}FIOCKa2GJ5rg&vd@d#($(38zcrH7%V zZMQaLtNe9H;GFWDkj1dJ`x2iTK8(kkOv)9eOVNb^7GmF|*P53f0L`O%LA?fEOkDV02qWTIw|Idqx`KBZ$cbgI_ zwe5+Lr&yo{@7L&i#-0m3fa3jbZ>#14ZY~9>C4Cu(s;a7FKu6Him@Y#(`?11cyYXa} z7tTM2Q&>8)8`HY_Vm3yOE{?1z9|Th7lU~+2JovFTQToDVD>Qa9;!BHc({p@0;IXMD zKNtuLd8mIREjJGf67#<}BwMX5oF>owfqf_GqivlvaoY*V>?A{hzqou@eIy?|JSAt@ zm2;h!f?eqbNJqs9JsuH@n918{c~X3A+H}`W-G|HM`0SpjFw@7U4wl6Zxu0`AnV!x_ zm=8p_@joH{_*AZVtD$$k!q&Zw*@I+4xZ-g_@J$=ltD?pF4-fptr^<;Y^xA*q+w*69 z=h^#ZC}pD(nttJJX!jMZqK3QHlUOh=;d(FBm-n?PMbnWlqCU22L?`_gYwX$eTS)$|=(k1(Q zH;2E1w!Lf2d0PB@t-e2oUZdO@ zjXwQ3TPf~7x@pyiWDDvEZD6)&T6xpe5$ zg_UaHyHTTBMVXt?uE=7oR)1K$nCFgFXZOo!^UICBh_=W4P$E3HVd&DKkN*gEj+ zJUJs5oe1i9HCK5^svCUpV|o02g0lTV-YbsM`g=xN4QXjSR$WR76yXojc@k!>jtH6a zoLhXO&9IuIgz~KxdYP%aU*P&+G=BP2pf+2rGmr*)8+xCa*8a2~D^8lAP{MX2?HD%u zl*nhT=o31YC+OnhvQ-iHRxYxaj0(lmQz$+^PAnVp^l{c_C!j0FvNS{Am9?AhS8hFG z96P_!t#@TD9*DTFFSmXP)+%=F1J>%#Xf{}5w0EAN&>My5kKi#e{S@Lh>S z8Fbb&5ktzO)%@fut6!Dfk<}~q^1(>o2(ZMVC^jXDEN}Sa$uh&~DvNFe;rjy#pA)N@ zD3_Kt-I?zXZ#Jl?&Ky2|8yF`P|MQ!r^D!vM^FABQ5Vkty;dS7 zMa=Df7o)Je+jFiEDHwy(Gt6yOt%h|{-7I0J&Lx>p`pRh4CvUV1zU5iU&1yS9GPR?^ zY$bhuAub`8?-LU)GqpThtMb(?ENGiOw!_BXYbtefeHasVo`ca1yNBWD4tfiwJcRTorE+ppZ_d?3IDP9a^3TE*83FSWUBMI)Cnj*O;>=Iw25L+QJ1X<>$r>9TI z1!xuGWws_{g*1za+k@qyZ{gzNqGMv}uow~gj&8f3d^Zlq|JFn=)o62{j*9j+rs0dJ zJ+>qAk9(A8D4wCCTXo+|f85rOEnA*ZkcjFJfyk# zGuLpI=;sVfuNNKTizX|OwT+V=<$FU&tDV9FFB0GpjYr?iHD+Z48$Of~=^R+o+b~eo3OA(I&*%aJYHb z+-p$XSP2Lg@3M!Sp%ow&s)ktcvN>yU>A?4u&-OPx6MhNv-uK_Pd|f1y|8eoeWTZWC zRwk<7!wd}t@-$N+mrCGyhi&_QL=|(}vX*4P`F6PUw-yKTk9mj^FVQxd)uJ7_Ha5r3e{(f7v*T9OLA$v=_ zZ?VbvzTd=&u~pw{a25|v^T(G{bNH>*_Rx3fu!soyB1x0hO&sk=l&K%bO!xCS3@Vgw z-u^mR{CHPXqe=idpS=a>;@T~|!%1d(Xk)*%^(vvEq2ZMuP;y}{-jP>pQXz7BWewe% ztrkV!UOtMR9?dtFY_uTpT#{eyVLFhG;*U5b|NFggwV??}aO{=;bgwz~1D4?b+W;B^ zLqAhVmaF0X7UPFX!h&q{Q?w+d z>8o)7o}H^Kg_#{N2XXXClAK`ws~O^^XczB(=z0xKGrOxrOUod=p~q)@C8lJ$d|;(X zQ!b@O!~dxDQBtn|f?I(#Sc*WW2#%Ik0$~y-;e{2uS8RujOk?0Gs`HOVx-%jnkHHL~ zg>OZs?-`IbVu$U%@$RAlJRB<>!iqlXoKvnxa zU#87i4Mi%*n0Xa~%P&Jwj_{NynU)?K;oDanYJs(VVd`Ty4Wpg}qv zQiS)gG56zaK&O1Vw5iIu_T*mX3sELa81ux}_azlib3$qoRnlC!vIg`Ief7QGdvkFN z2v>WW5A@dvHSEmJf5gZ^@my=jrB-ftMP73wYxTBlL}D6g>uM7;y?O07m95bZT zjQ8?_#_h-7siZz

O%lE(WPb5W+*66B6)5O}3cuf2_#(lNNw}JVVe)mpWGYqqYZ) z9rTSVCQwV3ks|Z6An`Nv-bv>pZ_pdaqt33xSI|3AQu;e4MnuLkInzN31W}RY%mbyO z*-U(rXuE18cc}(6EkNAU2>p>lh?M`18>h!e43d}jcZDY3YrbI>7|xZ90nL2LaPXf~ z@x3ok*+A=0Fz6XHG+Iwf+BcSvC(PF2dfoaZg6+%u%m-rhNCdS1`vh;ISIXv0htCpx zi8eb_O58qrFK1QK^3b+YGI;w?&s7A7yGZz+q65JZ{f>KPi9wzO@IABZo0|g0$F2T8 z5JFByEST4UpwbFiGgm?eWHJsxc*XI~;z!8?Idse}(my4q&Hg0w->A|S-4{Q9#8lM$ zJGe|!2XFZ4!N(q(jo>a3yO7+ixI`I(@e|snp6a^uZqOYS2GlQQPG78R#oqyFp-+D& zO~D}@^ad&1dk3EguN=0df?(YzjtGxZ=U}j-oMEK+5S%z*to3$9ZlA5L>$A$`;c8fL zO#HU^$=jbtq{EhiUY`8VNheBEf?)lGfKME`+!YmCd7!td5hs5r%YAAg82e#}uL&H?Jkp+^n3S&ibyAM(pps20IS6TT5%h(^4N6u}slhd`K^OpUCY_aC78nm{|BXs&?k&z|cAp9Cv zgCjN40{9$#%1Yqo|B?`Y{n^TbxJ_ZR@C-c2qti!kl`2w#ESB=aWg-7K0hzcLr&Qo| z6o|nyh2U7fxWi7h3lx)T!VgY)IHac1u8Lml zretr<7-@I25)`Hn$)?)>yPtO9cThabcVVkhsqGpP3WAinsbkNH6dyi$G|7_lI=4N8 z&l*ld6b7^cvZTlqrIAVGrPH@h4?T>EoMrBfJW{5`MF!colwplV_YGVlBeGy)k$5NX zd^>%)q`TIMO4>968vo=aq>&d1^YVrrAlVaG#WGj_3OtuVKGjf{j!r0#wVxr5{dQB{ z1SUUOTdei#=x9{mA~pgxm>tADxwXs&@^ElKyAwQ#C6@y4g&TH#eGOXIQRZ7p{bS%} zE6bEV7*W%Qk%v0w1xaO0@)DG?Mns{ZR#J8u|73ZB5ch_HmjfA+L07P+>@@nU&$NH7 z9300Q?O3VXLz82d5Ck7n5GUZ_;n_p6mBFuCi$QUEhg$+P93B%4b}FTD8ZE7_M*xJO z^57ZJBGt&1z<{7XQKBH2Q3PyD&&px8byaDJ5zt#j4jOQTr-{fKuwh||=1tF^&bJ1b zpgIV=6-4HN;33B%u@BK7an?qB3G#F`7?i?E`S*Ue|AHC59d?i%hixyx>Q}1R`KF}B zRMa%F@9ABSVqh5ZBheKDnGyKgw{NFnJDxo!-J|pm2(WZ4`V zIu<0}>q^ume(aGSfSfNTBohKdDBPci3a+Bh9{0owYmR&i&*S#ZkHp$q9_WjwidhW2 zQon=_zP**B!-d@jM*Zl|*U9O+j}e8Z-F;gRCMDb_e4-CbyEeLGJA**CN>6dDG`BZH zy4AV;|8b8xF@Qa&%M(RTKSW(~gXM4Jk6H6!zU8{lwij_e6cq%&*xlV_3{D6I&Px=T zkXfyLsUwsLEff`}6U>}Qh1?Yfz;|Rax!zoQZgHoT8hm^vq=?E)6D-vjX5Yy0rb9U` znO+LF02{Nz9REr{^}h$SjMxF=Z4c6K_yLeMevH`&x`Z<%e5!xLMwC^8AlMTI+OSiglC%W6&#Gq&>GlZF+m#-* z<7am{D1_`rI%dTBN6);|{>R@SAr9U_It8}gfoJ9_b2PL5_Kp}`3@}~o*XU6sFqLG+ zBz7CoR}AfGJpEOA-;Y5Ei^$hW_?=_(n15~u3p~6$bAX|uu7GEO4q;--y1Mep%E}%d zttxHN8dv=R`lX4!A7VyJ4S0a^kow-Yt&wh+d`vkIdCvm{8Rqz~eRUP!B|z_UC(zbV zCr1q^Rkq-#E}+(6UEyO$UZQ7jN5UYk(k%GTFVp_zB!g|x=R3t;by-TtSLXAbg<;vW zL+bytN^o%`YSm}v22t>yksR^Jhw0pip4mp96K2pC9txzRJ9>LjH8eDo)48cAsi>0J z_1L$#6NuP!XhF|?WnEpWRH16NNRH6ZRNbvUdb`vNO!Sa<7s53;}-}%T`)+!Rh zWqm;;Jo?$ky})TS=r;j;1O-}g35kh``OVz%<%~J+$xeFHmxSS^-}ii7FiHPKG@EL` z(GC}jXxk%~yP*yoy~%g}K*!~k7nUz&mkm>wH!cRy+2NjRa7h5#KJ-B1AetW0LGbfoEI=xjK)WpZvcL^oehcDGIw=I~ zXwT$HZw6L-V%|T~0^c1i6039ijilU0q%0;VJ)IQfJw_`n<#trFXBFvOFHh|~_UFmp zYvjzB4SD$`2I-4)(WBQw{~+?9WWHjK#MFa(YP%zV2kz(B!72v zDjOq8Y7Cf<&9R~w(f4nE&j6QHYr=?234t*#;>Q~!F4fYYDK%Qmb6fe=VY(s?j7ZAh zBoPzBK|-W$Das5!=Gr6Y8Gr*Gf_sN2d`Sqn!0V{)oq!D+#?e>L6#{ndKfduV`|OFV zN+m^gBxec(kcXY0&o7$&4(|Ahplzi%UPCt+%-*rPtaea91&7CJP zpD63~NkI7@$7Ioh*oA{1S)3<-xv+waKPaqGk7tF=_*&DP4biuNYFP?Q374Q!9yz}b ziWa#uF~OzpwLkw7@ZVIT5LXUR7y1a?_*nql76C_&XfYM>zu+}85)H2Lj_W*3&FO^y zY&ZOww7`w?FL*WN0TyZM6NvXrxAb|2lJGgSW*D1BOP<2vXaZv5;;VqdTNfK9kcnc_ zn&E5>URfAuM}e#WFZ~@Bayytnqy?ZE8>*Z1_Wr^rbqc(kQqA^(frrfuKrzI4Tl~G! z5F7*wKpD(+^Bdhzcek{fQXZd%B^7l)g|z;R?4uGEC1j($F|vQ}{TXnT&MkhR2|%^M z*G-mSSB~wc?EOji0y%J4H|QWVx$%a+ie8;=joW>%=i)Yh_2*DHVCD4eOaU+fikN`i z>jGjnXGX(KB+`gLcxVbtpR+=m!J zBq{t~2ajj|mB z_T^bCrA~_5E-AFanCDTNuJ|RW&NYD_SA#aV5j~btlmPUz%K_T?YG!|594$ZyitQY9S}5{pQJs6pYF28pm`^b0wp1Pzb;=1G%qQaO_4FUTQC4o#;_s9I}tvJa^LA zmE|2smvw71@o9`PEN>=CbdxjKBR+i+*T}{G)bkkqKvs=3|FRVdxT2ryEGA&h0ZzPF zL;5;5fkF@yzzDqsVIcn5uInFk?_AD5-MveO?hgQN3pWn@3Du|#H zl~g--gX^nmYVY4pwOtJOk%r*_11`kXnFu8mqA%-A3WfcoU0PiYMF29R8k^@C1#t)H z*I=rl$cueSP{R#d?Sm2ufG{DeVI?i7&CBYu6T*p?Wq$&OjS!fX_`dPiA^X`TB@-wO zgG#YBwUuY{iiy>IG$1|_BtrQD=)RBDvFvLh;0qv!TiDv#RyS_W2*A7!e#C*sF$Sr3N)(Z2)@ccOgNNd3-?au zwUk9qQpX-$2hfFlY&jLkf5`%)cIMtaiwbgE??i}n;_j;UP+Jg$bQ zNZLO0qN79V{sO3tK1CUgYeP=KP zph8;Yhi)`ZZc}-6Ra}{v2B*E6)!&O`{`EjRbkZ^lzURi1YVTKZeOHsMq#S6uZWS>Q zDC~>?PW&nVENJs!(2^3N$Y!-Z_&Qm6e|Z_dCj&mwL+26l;wPQ44EhnGvo84%>U}E_ z3}S|S$JuH_&@kW;7?dpM?@C}m{0xNP^q0jP9%em^`j1bov$OZqc8K^c9^sPv;jIb zsswH#*bInZ?C0QXLg060foI0KU;X01d@D2#h#|KB$lZV#$za+e3hwKJ9kur3OFKI; zz+3G!8UNa<(krPEGkX!g&a0c9PHQZMm@Sy+3fe8%>LT&c$RZnF@_m7m+Gm2GqUU6! z-s!sl6-y{TPH>EO==IFUDEIn6Z5T(~-|jm|4-SkT@%J)~WYR;_@JgCD#2yCt_LXQ* z5z(pi_>=~KtV&`cHHcZP@tsT8kvR7vfZ0-<|;u{(}YSW4<_mGnaw( zC?Ge6_ww6#M-W^9tu|f=e(N74{!~PnRt#C)71QBJE5+gD9z;imQb{uc&o5>eJ*boz zW8Dtz1%@Yeb zJNwkQbm!;hhY6#c3J%GW3>M!4Jo5W6fWTt;Ea(bjq_)8`jB(Qd%p%a!h5|uQp?cPo zM6&HG2&63iIBuD{JzGP}6-8(B(H*-P1lm;;o?GpZDpZcK{_RT)B>*HMY3u1{A&cg5 z?U6F=GEvCEQPQ}eZTMg0*e-$$0@PGviEJsVD^bj5^lkcNdWC2U&`QN>R9)y6>{e$E z>$a?teMCxJ03PdhCNZXC|=FF+a>blR0AKM8eXe#W=zr z%_Qh3qu*1w`6hyaPFLl9w1NPmmSoZvU{ggrw_kZ&1v)y)r2}q607&92@9)PC=ZN2f z;i}UNWdt|1MVZe^E-B0e8?;CF`!qaTpnt5 zFJG($Y%P3pw+hEi`Ut#6UZDNgWA)Aw*fJ-=j3^VbFpdhfbYZWZIpa`5Xx+&m!ra>Z9Q5TlW0DJ0+K26-rkXHU!pl$&>;_odL&;*%+^#r5igOuOV(NRssDCRih zqI|s08sT}K$RR&Bnj)Q(Tbjh-@Jwy@R}GZQv6@Q_CyNciSznot;C5BcW!y)}wj_b+ zA2fyyu}E2;&BaxBe*(ev#pR`JEy_xz1hTC1;~EY zEHfxC2@PxQ@PSCq9lD?%ArGhDWA%Ev-cN4u_8gv0KOn0}43~CQX2oo{#JX$ToS%by zwe)L~t6GdHg-M@c6gBv+?Hh~DWEK&RQ?)WAA0HnT8uMOH#gN7m1%EA;xi7AU)WHDT z0yvMQof8UMq1VFdtAcPeS2Ar5S9KHd0+NQ7&P@M{cBl~Gx=(5#^C?SqpZ~?cGk#|4 zENyJhM01deltpH=kO&5F6^y|oX?)IfF7>{dS~XMHmZXeqGfH-rt&yTlJi%a6#;s(rrCel%e)2*c`D+7x{Y@SGJuE!AobNM*O>fp%Rx zpg65}SX0k4l>#y@|x>RP--*J>(J}Xkg{f;CAEJYbSVRH58L(g zjbT__q_#(MBETo*#$0a>lGccgtq2f&!wm+EMU|F#Yr?M{_!9|Kka&d9(9Y83v-6ti z&V3CdH*!Bs$<9Sx4hK5Q-aI$t$xAB5EN3Y@U^iluqBo*|S$K#h(tsRg4cvvBZpr}R9%^6SlSd6o0;>_*~|!%Xkeq0UmGpCPyW*G?{O1*(7Rp)uWlR6g zB?kRQ{Mtajch9=J+;9rqG*!W2FHE8p?)sCB(IZgF_HxI8Ewf^OU7|kSATS#g86+6ui{X2$lDa zcy`IX>i_Rm#R5gJg-%F#CgW6Wg_2|`myh|>IE#kO6`5KY`(DeG+kK2LDu{d*7%eUj zg4Le_4ypBExOyCj?=8Toj>!}yDXDQimM^lp@^Y&3aHJ9_9~RfE^|F3QHgm-1LIl9gFC=YDJ^FeiN?2l%SSU5=aT5JsGWPte&Kozq%B|zi83vys!;KlJ8mZ_Og^q>lFYYAl$6z03NlSVFwc2Fv3gUd1*qUDG*s$6eFD!}jP* z#TNX%ZTt*D2NDwQ?1T+XnywaQOOdCpz4L##WOE*WSee-3Pv-sJszH5fXRg+gxB1lq znc9h@tJK7&{wH5Xo+r2I?KH~ZqBpsLv!u+Cm4fTagy)PDT!fiW?O%oo}i8zd3Y6VMKbU<&Spt zA1qBqz8m}yy`t)SOxhUnh=M9X)XN|dWe_=Kvg*fnR_q#l?YlGogCBXL;zu7t+W<7< zwn987ToM)1G)`yo?osup0+}^*f$dMYai!}D1s{IDa+e(-dAQUuE}h-JwuKqAnJZzqvZG|Sc+?s$1f=#j`}Pfsr5?U^W{kw< zuz7PkO%!Co<_hUwHa%M743U^WHaqDt!cgz>Fi7Gtdfa)gxL4(z&utLh)PC( zd)>}H5Sypbcq7Giv$sZzWQ{J+XJ6KN*II3}&I|e2ine;EE+XaMVk0LM3XtN!j8aQY zW3+T^7Z+z=K+AN0RUZAA1)l0x%V;44F+@sA>S8VZabef7$P;F`iq@a&T~@`L-**_U z>R!!a46&(OtSyrAK{w>PCi9B+2DL6F)aITl`f@S~mZ@@Je0)AP|46{#YcF1=fzjRXc zr0L4|DGK_#Qype~v)PIO0r0_E2`30|{o!v(6%EyVrxL%UkRE82ZTS!0`;GM>)lx54 zaJR`yGy;|3an5VQ4Ks9~7?8b>tsy5nKRM}2=XtyYt#pzE*;JZk;%QTAWZv~VROnG2 zU=V!Q6&En6_e8_spU3$OL8WQA%YL~SXPcbZN;;xRG;g2T|)Gx0X6WbR5MWbNp47kLZ4~smUzN@u011B0ncEghJ8m zqQ{?S#*U})CrfAJ^t5if<*&g0zPgp@;A^?8?pbTDkV`4=nY~-7SE->2p(KluV2%qO zR-xra24ov~z|LLT-lmv-BvrwKRPR5Uo?)~8alwbYrS~Q@cPPfv?tOLU%b4H{zTj^b z-kN5i%*6ckFP2q7ZK4-4`T9*oItGTigvq>`w*9tF&IVgr=%>u{$$)V>geT6(Y|j#Q z0hvk}(>5<0AmH3HK*|FrqIBG@+nrgPExn3&LLI@lS0U!(97E6{o#ieRcWOC+0QRT^@ zlbV?q(a7Bp-ey}Au)m+ECS2PkUOno{DsZ*~X`gN|pa=vS*q&75Sv`csQ4BM-A>!_U z;ebjje#szCK%3j+ZWDqyI@kSOBemBO0MN;Q zSJ0^&&V_CmhWK3&{&_7yE#BRyN+jb{DD1+U9m0v2J}4cn($^Q+ z;2ufi(XTyQd@trSCjheG)__>0uNGXwp+ZaLwZbOFx<#-5ohwP3VCsY+{Hs;oUq!LR ztahMNJlg7H0%Cj?<8e^^3ahE%PoA6W-!mRR-~WBJ`Za|`Cl>snkg&n6p%h1DICvns|RFd#JqfU6!7B2GW^mbMF(2p$W`!DmA=0&XeLn!!K zbo{L=H4BluyJCs#>!mb?@}{D%-a|>!cD&~YH)x^||9kle(>36ESE>7nYTmq|0UeOY zq@<*;ImfUuu9e%V&|E2ynB`I^F&MSYP7O3eE|_CN;}Hf_8W(wGxO%GGc)90fLwj(t z^f3(>rV#Eony;M3`I@p~aJY9{*O2cc3cPFm>5iviNoOK6M_GvOt=bM$8H z;)O5NP&aDX5@)|sa}VQw$rUAj-c$(5jCEr?c^RXKz>A=mOvPmw7_NLJ$ZHxU*NSj5r_G_N3eZ&O%c|1 z65nF8C)VAoUwvRy4SirXP?azHUWo*%Lj$evO{UkvEB#o znoJ^z(MI1&oJm|Wl|yD`Sppyt#JCSx4BWpUoExXK@LnrscMMvV_YwR-pai2DoaQA# zuTrx7QIdd)>| z=k8bz2vdIT&UTrMcq+ZSQp4PCu31qdsPsUX_5di-bJ%62`=$5owJ2yhAWzx9t$Z6x8_HVk49C)$J6i4Qd+_HrM(s7H0ZU!9dnQWcEtA9U`3z(|Arj!hbtI*hzh#>M%XduUNGb`0#9i` zzud~-|FAt6Aw_-KXh-M1JxD$?H<$T@=am=e{;=;9n^}z6NKWKtA9GpB!R1gBFCwEX z{BWxJnQFB5p3DKGg)@wZXyW5SK)giVZTrVFEX!a`CwB%y{EtOH@yAgG_MkRuhufxD zrK>Bt0E!>8PwGiOPzLL2rH9fxfm`xL8jvik?r^V4g*>TbZo?SGeJ7QD$UnAXD8|b@1hm^Y9poX9wi{N993T<^-HgR}22_roXcN zH82aVx~~Z^GI)YbyjiFou^T%*^FeoO={K-6i`r?L@zNdm-ZP`zZiT*ky+Lz&d>Z>@ zWAkYB!@0)ey5~%vTR!I>4kin7DEj)m1p}m_T}kLK8~LmcmxAm6aFeBchEFT>v|Uh- zd;i*}>P>*CVt{D8!t48XU*IKr`@iJoJq-sJsDguo$K-NbeBYY<+V2f3nXLmomh+id z-k|_9owA68q_g`9{UFAp7R;sN%0NQ`xc&h|y){l zh$Cg;$s;Z^En#v)u_YU%cL0VD#Y9h+*6EK_Q3ee-SR8S%}`V~Sc zlpz*TP2Evg${VN9_=}SrfWc{24O{JvPfdII>uW0--nK*M((kMDeFdOCpI_!OQH-w` zM{Zp?G(*zrbApOc%#M2IVTPnvVM=b@m!K3)#Aan$?X_ndOD4qGzZyfrqgXOl1VM)5 z0K0&KtNf+UDzo|$|Fc&WZ!;z(Ft;&XrkP+?c)2R{m(CKpGgZVP99y58 zvdL0GP-Bk&7$Zu&tNR4VenSiZBMQhYVVgh9zx0xC=`kbh=pm5T7E$hOF1Fx_oG`{q zKS}~H96uO{I7flr9MaXMnE9PcpH?JD zpyE-44S_1=19rd}T_1YGBZoT2FC$~tD~ZuVnntM>N=SEu(%sGf;ojdnzVVH5 zba0N2!?X8(Vy!vXoa;w`j7f{Ac|Q|kC~_mH@t^|j>P#^!KfznTig`cfhGs*r5p!-9 zZ!wI2t@yqW+3Z+BGl?DK-phtk^_nWWml15G#oX;b2_(EuCm<6SXSX;uD8Jw2xFc%~ zj_s9_OF0+{&#_sARqj4qgz7nBmvi23Tx?KQtCVQZamG`15o8*Ixm~ABNAdWRYBX z$$>rsl-dBKA%(|pIT)=cxH2Tx!_934LU~1>8EZ~32CUkzpxaxSs~r*jXZ%ik#i4c- zh4mJb$hqP|UWmsn^8bpwm3xhCQASk*MG~`n=q9=DLooZzCFYLP9k-}pYsWoXNFcjG;j03=vog?sk#B> zg2|e>hgtIPY?wZ4bAKIcyZeJo6bR!J4m5-pTmm_TPA_;t~ z5Q*}P(Uo&ZU`&`h5H# zSz+&McI!DuR22j@sY7)dYP}*B5y{!9hyp6^>`OY>apLX# z)M1ZKPvbM`bhNc=u&~z2{SaZ>+$h4J9fae~@)ATpoti+*wI+<&YtrHJ`uL7`-yOK% zm!y&ML_F_&20YyK+mQWl=*h^+fx%L!c9~jbw8eN4<3G(9DZ7&;*aaM|=GBH62$sE5 zFQnr1Ro^h&bh#eR;ev9Kh@(=u0*}SHTB@l~bdrmMW%OeqFUeOEr;Sa9UDH;OOwWX> z15j$A4_;zWBW>nBHeO+=Z6$FtP@oDPV_OCwaA?jgagbrL@xdg*pC9Da%XRMkc4saK zKROz%8rHO)amK~taSpPIt{IEzG58`;xF0rl@^}9hW8$#(MRdttm7(~3=y|T?eUarj zg=UkW05AF4=4|QEkNdt#_8JxFlbbUm*|8(V40>u4QSHE{czYcUm5eZx%)hzPpr}PONElwjk{!cS*`uywp4)O4+?5#c;9_-< zT+oLn&g&|@Dd=&ul;XfC2l~gh-pW#l(;q?bf49v?kc;KC3 z{tAzls(b$$a;|g_ zC5b~D1oFy7hAiL%AUf!%lPi>TH;EUyle8d~L0o@0vZ{H4 z_uq8SMoj1%Ipfx2tqsxVKQBF(X)iGnFDcuPC>X|*WlAHH=d)hzBPq8!4bK*lwMC4@=%5J zNZJ_nS}uC+PXPiV;>)D&vm**PXXOlLD7ekvW8Lz)%Jg#={li+Lha9t&S8`3%$!R1m zl-&Jjr59uuH?UA!ROL3#r`>q}@-U!_L9|n*GO35%#-3}tebxUa|3M@Vn*V_5C`m+Q zP+us6W}UVu*zeJ?+}7=u0e3E~c51kvAgw&5sO9t0n|80eX_@FL4kv7@B1nbA0P8{& zIE00V3Mxb{E-vtiw};AUHh!fu1^kfl>UCP^dAZQxjRLi&U?Ih!y6ClA7q~{u>NDPp zVE4ETG-Q8)N7|AVwGnGIkE6r@ULf=;bxg0Aw2O`MZxqW^bHpXfl3)J*J=0;=Pf9HI;c%NVuK+LE77MbBo_gE6UAg>0TSFc=h&v zRBG97RK172fMl&NhK{88^;~Ku+^HT=%76u``0-qqGPX%v~0KvZ+_ZqbW=d7F=2 zm;Rvo>S1}QO?f2jxuTV`UfBEX{emtfo$p0bW7G!qYRR^ZvO5H}#o0@1cszG}4_X3* z1}ca|=FSUX0;XK)GjR#2hx1MqD?7+q{0Vq>xi^nsX0~ab zr}N!|OWH?BNf$?&Sj3&fkQClI%GUn9L0B?-3}&PZqI8PeL&e-3AuOhK5UZ1+Vb61! zp}jTJhElAf<6|+<3*5kJ06oJ zpP=?hKq*P(&0vJMlkz(%(uwKRC}JW6NgvFzM23Z5QwPa(G0SL9!aGyk6)|zaSP)wm zOtFPwdpAp13|BW7FBp6Q@^oHRu7Tlkr7|xC>x@YzWUA2sVfShWezjtdN#EDY-@bTV zYz4)rhASa%M@L8Fv#rd3!C`1DB*J2YQh)HZ^uAo^Fx6UFBEoh5pF$K=P1?f1D4^Dn zk%yc6lLHAiUPDY`ahnmS;FDDXs~#!fuoD=h^;+EgfSI5EyodlBv~B2BqKRnN$Aggm zfdI4Gg!Nq1vPN8*l-F{0esE7#^cGI_>2`PTjW@yhkZExF4~5&{jXLhRw0K}gs>Ks# zTR2ZwiQGiQ=&vN`%<#4%?Rf8(kuG7G3=9?)>rm_|y{EWwf-aVV&mVQ;tOe(m(YMC~ zNkkbuie;ux3f#WK^EzKsWRekvCcN&vsX$R~vn=|{3*CoJSkkmqHns^(pyEyh2z&Ww z+~VU5W{{dqd6zLg(eNOzX&y)a`E&D);Qu?YX@kzb5u zZO(h6N8EG+Ifj_bxOT?)H(h{7i%kLVJZ@j~qzI8hDhDTI%sIAOK`|NOW1MfXBRbv! zRm9=ivYxGAcSu(0d(Q;czI9ZjPi{ZoGv^_XWd0 zt1;vRYEhK*d;*d@mgP32WeJ2M(yY~y3hwk~E2w$sCun$&;dTT&7Cr0#jg&N{UEhy# zFmUw3W`6Bw9MwPfNfnv~Ge@i8*Zm~h+2fzSo8^JJobYQ7yso(Uw$RhR3hDf~He1Um zJI$8|QlMJ7pb=-HU1B3@7bB}h=GD*kunhx$_dk`zeRbOo+wW(5|ESa({Z6m|e796N z3M2uFtUIl!3x8)tWd8+r((vc@#Ra+mWVu(r~J?Vd_!nDUw4l)L|tZbZ1(tAh5lsX=6U-RYaqPv zvIl}sJ4$Z5XW=^)gW_zKy~%@WWN5#gq6e^Fj4aC@;g1ypQHj_@+0xSxu52TZHC1!WN`aq@5>VvhaRdj*RKdRt+|~#JbvR7vA`ne$1o*%iHqkiaqiI@{O?T zRWix$Bm~dmfve^sDHWWF+6Kl*Kw^u&fL-&hDpto6nv!DtfQF4VV-JVM=>l6%mZKen zOrJWhW=TSUCLrj(j|F*2d4^akARd(?zqxYRYC@tav_heX)j#??!*bp;V?Z?uL`3+@ zS~oX0hF1y44Ob@=up7>BCni%&F!R{;aV39=d*ILYET_6F(s*dlfc$N=RR&!u#S20# z;`LP_?zY&WxM?C2^3vd^SF2I_mBzygI9va6hQ(i(-g?(o5Ra{7M4&%E#$g0~{kQ?5 z*dofbbBaZG0{d>P(J9TIW;+3hG)8AfK!@ECP@U~H%ZXgPQh3TQm%fFD@J8&#+xMH> zyGadQgKsSWsrz`e`dqS|8|@2HF@15w&tYBf$R+HDj@h!9{4Q?BYvRIEVhWa5obvI)EQm+FPIw+!L0Ib67Jlraw+ff3aZ-uY4Zz;Yf<=MyVeE4jT-rMc6Q0yCd-!UFMIDPMEW=B z3xR@$_qw0qe9&R34O*S|Vev<6(^cX1CMF3&9<5n*-s4P|JY;Z~IpRzVxnCMbwE}W{ ztl|(TNB)^)iHh?rK@#jiVCwKL?~zEC_ATkEW_dgmCYS1Kv~M{kUPnNe0Va+{gAnMw z2;mF*;AH-NAHZ|k{LCe+A_Dh&VuonA>9{fzHNn)NUZiS?({4VS)fCf9e7=_*5Gwq; zzez&0d@oCBijx_XVOjOs62wW_KU1gnDVtlF+tNjoJ>_eZNfGa?mE&wmDfk^CFOK8* zKTGoPJ0C>0-QT<>UAojZ#F}8$X$lOEgV5}wynJ6XPPEU{f{9c?7u&Rnl`isGuvf*{ zsQEJ>;X*F%Jy-XGmSH@1`QIxM|Dl8f4ky#n9z9UU76`V!_yVS>dy(~c?bw%k_VN>e z3@MW{GB|i9@DH)!2)=)s9r9*+2MVBa0N#mU@P9Tq!6i*os_LxBa6Asg7xI{C=CkNqeA&N z3Yw7n!g(KmZ++o38!3d;7`^VU*wtMv&)laIQ5YwNNc& zE__+epw<`?vkj3ZGpx{E+!8#WJLa|=KTPPQ1PZZgRCXO+NL&`rjOJWvE6H};M0%L| zh{|u*jfkRLPdY`vn}QW4q+j@mNe6q4tF=v{1tG=3O#s$~ar*nGq}40&=iU%dBqP` zkUVPb(Ku`k3Poz!BNnj;b(iso$)@$AP4*jyD8?Xv81_KJy7GGh{c-*!nK5}|cs?-V zk78|bFU5uDz`-t2_^Chw+Ku*@e4qcYO@yn`r1G>A2@7ey}X1R)T$TxXgP0V`vC6wA%=56@fKpsr4zKGr1SP7DrU=Za&trF{Wro)$ZdXS+X91a+nOme1C@uf=M63h$ zZcK2Luo$$m4u=Et+qJw9Z-T5Xu=SQ4PS7jYbE0}s(0K=k!PPcsx`^(lp`s0y)QWGZ zeS)MDI{qU}z})dT8Bz+TA3B-vkEJEj4ydDJBR$x~s3`mEVyl5Mbv8Hn^_JMv`S?j&?}dxgmyGcfsXq5L9LJU%K4XX zGb&xOZ}Y=3M&-y02wAqlUPMj^D<&p3mcar1f9c3*0JZ(mpTXuIU-zd1wanW>(TNOx zXK@htjaD1Uz?Y9xBS9%5ewT<*lwb8$4GKqXODh}^v;|xULD4UV$2jG@okU2=UrYebj(YRMZ<+P$C)J+$Ub1)eet{zet}xq_@^F5>;q+3XI8r!O z6qGl!RjyJv*Hro)FAQN4a*K<}{e5x7QpY?GGXk-$esivVh0;vo7vw+J3m@|Fy>;1C zxE@+q{9?9rtI(=BbN1FQTeqkDCyU%kY<4CMK5KveEpxp-a3kM1p8}Q0SD~1A1t51q z3s-{f8Dhc`hrA<+sS-XMAA5guj>bu$zo0$fe}2DpSA-<=K%XuN|n zV-^$g7tn*`@nFzlu_m~vSunC=mx`6CK<$>ydr46^YmAhL02aS{bmA%pDP!tiNqN}6 z(}kk|U1;3Y@%HW8P+*|28PDO?7iqCuB-W&6pT6_BmVh0{B=dY*SK@HuK%4(T;uI5;>&tIC3l zCRCl!Q6>7w=n%K`nMHVA5GR^%p&B%V(r?)@7AlH9?dzlBhg~{35-qMLWn2|!V z75+HC2~aZH-K)$=x=l-&n>64ge>}o9JQsY@JREhRJg^F4y-Ua@MQSbQ4)+xT(`?`2 z0|O=o4CYUAztd;0RxlnuW6ykCF@NER@-TqxOOJkL2?n1a_6H-hc>}j)a$ooCAj3f@+{{DgLmN}{{Rxv2PlI^QTP0T?rb?~m zS9;#iIWDLs4yA$OeuH zE8{F22w7|jpfJ)G(5?{G3z zq;%q(s)LQEp)8X`oJDt`Kr&u9e=vc?q}_nQETA0|FChHlo7sT9a1$FW(x7HoO4@SA zPJ40=s8b<;9ohA}J>qg9H|Sm@Xj=LeaYs|kV>1S)ojjiD`QYx<`#dZ;z0Nw&&EIf;UcG3tq&6;W!IzUtV7?GQwEg$nt<-G*h1&8wxNyReq^)h@J zRMgj|k>ZtsVrHIaDF1EzNTZxtde#HS$hV~Z-39CoX%|%~A63Wu?uLgL=?z8XVWk46 zIK)t2JtQSrGIm3_%zDiBL8uZJCApKjI7Cjdl!P+Y9n5IXVYc_5_1%Jj7Ilp~;_wh#ra8=YZ^rK`iCO1YpVtE)A-ARR@ZI4Svt!qNYJ+aQiLGl|)2XSVwM8MC(a%HX2-V zNYkYJcrwL7<1u{_PSCAg>vPb4{YOEvZur)g`RP_4sLp10o>Ro0 zmFcDE#>ekOVor@$(;x996O4HBI9|a#?P{_CzHrW{=-|f)@Iw^*(`SeRuyk?8-52|^ zKYY^Lw#>*B3fzWXKZEB->rHeIH`x2BOs`5`ps-T$J~PY7bJ>%P)d4;Fz0Y8YW@5N1*+&&+)e)RJ~Qx7Wizp+%cy^2<9she7^>qWKQo1u_D*XP`lC z-l|f)u8^0IZMxBW&06cQ3;~yvI{}xSK%N(bZ2h{Z+t8iy5$eAl9^- zwP`Vwkjp9?|8pMw=YlH|h5)s59B{#;u)t!nJA}+96i?TU!i@n}fh#VXRH3z`E>v{m z>HH=Z(P4(AB!@K+{h{M@i8EhuxrGTKZ`u=XYPYxEX9S+U4*lb0`0_J!LX-)4ksmbe zvH(x4Ka_?qq06i7qO7$79z7YuN_AcV*$}Fbjw<9#T5A#C;v5xBE|*u~uULcUxUAOy z>6EhPV23H=`P%o5?=-Gb-kZ3wl56B3e5J&df$KOqTX?4n{rE!5?u(}JKoY8463aQC zSF}z_W$O(?ZzQSBKc`GGy)ZGx0v>1dgu2Je8pKxg5^BX2h$2 zXY0jWmJ^8c^>&vs4sjoY;m&{VI@W5yeV_v8zR^0YAF#Q|0aB5M>y5M?$)_-YL&{gY zxp@X^yQ=KDvcB?6xjE-4c61j~Ez?A0uV&}+^i zRO8bj9)+8_tHsg!SlLxA5faDfYKz1A@x>&eZgh%2ytqG#)PcLmo&Q3aOD;$%@SRtG zyrp9pzS@q=vz=|Gl1}Lw$Y2|GTdizAe!&kllGJQVe(6Xr@@&AH8o$q09`;boe1oJY zd>rV`2b6?YW|Isbv5kYT53=;&7L&JAH`>){T!X+F5>OQnG-DJK>O}BOWrekcqb|1M)g~9ExS!Ip&Xc>4cO zFTWM46+5x}E_C4^vGvO?eph!9tWWTv%n$oK-~I3926@u>r`Ma&3Ap87I40zVNrgm} z7ddR1R4a9bCK>cxhqzWcPHL6EL zU3A044!HF9f)RJ4e9EQf!Z^$+cn<81ajbSY-(G*vOgdJVMti!&&n89&|B0wR-5kyn z4?@nFeKx82G_$~~Gu^ix{v3F@Qns1MJq0_l6(F+cg-)Z45*E?dj458;b{?_D=`VFd zX96A<-71PA8J4Gyy5HdHmp(`A-t&O`&6DTQ1!*Ua?em26fA`=K6XYzfr!)k{?-lzN z_TkmUC!Nc#x7ScR0vYs1L;+vwZ#3|7+l(gpy0={-?A0Awh4$FV`RC?*KdqCqRkPMI z(&wb^1ckNZ;)&@%Ns&pi7+WIS#MZ&D*)c zJsW6TznFIbUPK=sA`2AkY#sttw4H6qBMF2E1p_A*4Gj$k#qup`&o?c`kCYxCz7Bvg z$8hMQt~ZyI@PYr6<=^p8(A90UllC*tA(zZyjsE{0W|i$Ce~r~N8u0tVMWq9yyA0de z$mly73yEN}n>~p5+FWiZme5H30#~jl*Kk|o&oEJt^L(^^R~^+%!#%xvxyXvjC#kiQ zl~h_22lraaVohN*n(#joZRVtWED$zK2>41@MC&b+dEkMv;C;E+aNJ8IQF&5Y{j^NM zOY)hYSY^BIZ^FFE5-q&--k3|dGS~gNAhiAY^{qInuP5neszt>QqRVZs1t%-~fs;v; zyUr)d}0$o1b>J)4O#}i^{ z%_{v494?QI?V{tMK%|Y@!jC#ZF(TL0&$-YZ)gLWjjCHe*Lag&BJ39diU?*yDs>ig>tgoA6f(2RzX zx;A*Ax_#m3e8&sua&%XX*}rTjQ8Ys?BBhF53VGvgz4d&QYUfW{5F~%QU9LFiS+IY8 z(EjN2J%<_lzuf>Fio&o5s~_Jbv)D+gLbK^2529I1ttvRvz@S+0e((EFu=tWb1}x3v zOahuY<*z$}RWLZ3(^8Ht+zSCBLOLvT`aYcYB}B%DwP1c!b9>N;(Ej+)?A~b97wxt_ z#1l}v{iQS+?)?4gcn`SfRY{QSH#n>xfjuik<-30oGuDL7dCy~;cJw7}xl_SVoDdOz z-^Whh`Q2VwzhWg*GVZbiX0hzP#0Ycp70OG zufv(Xu71l5Kf1ny^5Mh!6aVV$x7c+44igqYncUUc{s7w*a5X^tKE>Be2<;b>c0M9- z4GU=YIRBha2r$b&tID>WNl0rk4)%GhML;m>@d{|!dAz3bT}QyxaBCzdg~R=GICYHh z1^&%~cm4E0>Kn^H{7Oj{Dcr>J{vNy+rE}CzOSD54oH41bpLgD4k&@le`DE5lCLVkX z4`RDoWmGP4D$f)0IP113pL0XBs(;uVYO~$N1beGh^8)aj$?Jh|X_VVN*tIq5p0T{f zit=*Lv(~E&#FPf#8R+b`GgP4DaInCqTCOolN1Nq+@#WLX=<|2}O^RCy8gSyN&xZL^ zxvY{Ld@V+EgO=xWhe_M1(B1s@PC+__U_A&={7hdwx2}El#YeT^mn5mHQAd$=W=ji= zZdH0Bz-x$7>J{XEx*;`QDDR;5-Lx3gqv1DEGe#NcH{|?SUR|kGz-$F}&DkG4G;^!~ zJYqI?--AG-WLm zDK8LB`TCd7ObR0lqiJXF#Mciqfl;ru$(8+LOHK|?T3=jFQncCHe$ z#c=`rB;9+#ql6?X88jx~KPUstp`VXe;Y?Jp3XrB^gzD_-Z)r@5!BNKfa&;U`l*E70 zzGWx}yb>`sox;T0LP-aen2_4H<)OLAJ}Bh3V=H8rOz3u1$FFcMS$HCp=7dI6MIkkm3D6))h6!v3+jY$yZ66qqtb!j`kstq`Tp6$(IpE)J-iHiC+ zeJn-_GaFqy_{IDAuEzZ_ny3_7D_J@x*?MO7T`#iWUbFSrWjJfnKomx#p|QTuleIqTuSe6634A*QTEm<6N8a z7IO!s$cvF0JWHBCzF`b<_P&5S$3T?*%f#wj)T=E@_*Ww5Ow$&d?64^pQdn%F#Zky? zargd7v-{77nv9Ea#T0gLe&F{N5D0f`CT^m`+$likF~ie%@@~YS+N4ZRepr@uNrVSTKi2<^vC9HFcUeCD3sN0_ygDJhEqI_4|i~pQ`>=c zf8#?P=bS4U?=~_)JTdpxTXIlRAoPFvdiU8_MKhTC?*T>R8}u?ZI#GNB^QDWP3sC34dB ze=PQ8P%BNj+KGH?H=XHu@hOsw=XYX@nwOw-+hykBfCPt*EXq!a_v|kLA?m(d24>h# z(&V*BE*?-Pf6&=s`{R;Z?Eo=3x!65rF;02fc_y4k$#`$Odqo%*DSeutBUK^mOmw51 zE7hv%9Kt^z^efeK$lu`(gh+EmLZa1srDb0`tBv|T+zXycY1H4&<~b65 zSgSiwxxD2{*RvYQhN-h#&ZIG7F>ed?E=Fwav^!iP0r`cKPEQppna>#}GA_d(35C@( z=qxc=uXkoxga@@{Eu4|CsZb4NtnouU#ma*&=U9pvJ*muiXkyMm(R`5-GK#am z*T+6P1e>&4N+~tIhrwY?zys}jts`xGAKrnUN_zPLZN$A|MOPevOP@B#6VtO$dxAIf z5%X!vi;9>vP(g!Ufp9!lv>fsW$Tz{7y1&Dv12byn+?M3$$XoOIiv}o6d}YN=)>)0Rs=qgpxW+H^lW2;`RMN%cyB3A< zo_71AeeSWTo{``j0rv*ml%0@&_xM{E7LcFLj?^e1X@A2d{*q69HwPK)5Paf0h2efL2KCJXln6C<)@co&J z{Sbj|ok7=&v!+u8AnK-*8VBN`$TWUe>5ym=~UApa2_-o5azo?7faz7f9*kW|-0goYrEO;P$h#H;zba0>zF!mXJk%SJDm=L@M zsrX!RAI}CJP-=seN^Wxb4ddGnIhC~L0vOk8mL zzD7bnEaocTxiYBpYNpaF?Wor z-tgNLq{QhN9KD_Xg&G({QPR=jQ;M zezxGc?Ctg^PKM2HNw9Aq;wLP1anaUAPuaz4U6Bu0<>Gw73(~fVXuV)~_#+>?!QSXr zI_&Vs1=_h0GvmAW|?sd~Dw z=cTw(J!94Mnry5mfBFq}J!rlG45Ue3X*Da7Jr)5J0E4ol)ZRJFDFP9lwB=PugnL39 zQ#RsRmy}wu62&C71rXuj&Eiglyd>}kpwX8B31z|G?=u$X)0a%;8lttMv7`AO6ox3p zWL@n9h5_a5#oKmwB8M%f_38`U)gN?;hXndh9J$ZnTC;yItt8XX4FRu1g?h&;jkmzM zllA5wx&6+wwwGsZf;?k{PJ|Fyhk&q~en03cGj=~{pLM1r3w*8m*nw=^sZz!NCBPXn zVdrkK)eX0j2ZpTlTBcr{mkB`TDDbu(g<2H4hPio1s)sjtVAQPx_#4abmwhWC-DL65 z`msbtOe4Xmc|9GNzjD29B*Z8m57?(q%sTpor0s{zXHv#`PI4@v>pvR%F8f=@~m-uA$5aeYx$j~iJ z-yu_ZW3*UAD`$|iI5`tS_q)Hw}a+`2~8E58WD zeC}U$SRQHMHf6CJz1X^@b@T-i2$T?$D`CQ1}>^FniE8EciZEHb0t8g5 zoVvHW_e8hU?>PVIFYggJ`m4Chwt1+dD^aEmsaKQRnyZuYykWINgOeYi-_y$6^Ft)+ zYO+~&TyU!b?{F4)_Ibne^J|9ftLAzzc$q8dgBUGw;DvVOUi}II84C_KZEFk$(#|$! zc*gth?vb|JHBIt$ztPOipC(Eh<;&23g+QQCW{|xBJLB&OnbEU%fUquaz~>>@ty5V!Mw<9Ut#9|`?4_a%vt?RH%Dhi`(}m*$TN)ix10*@I zxC=qpZTj68A@_!md&7E+&w9q?O##nsQrArFV}8aCQRR8rPLk++p^5V2H$!?Irgk_N z#m^u&jw+Cq?LM?7?aWk9_LYXgfxdl^t*0s<@MGnWDJXJnno5Y{Lz}R~v@@m6xkm2#`9kW3oQ+fqIvAE_uzAKT_4MZ z&v6Rx#lB`={Qk```JfZsu}*((p@R2|8~0=#n<_HA3#qs!IJYa8j)`1}p`P>m!c@T& zm$QN6uXnH{+#8ae1m#QVURST7DV@+^+n|xR6{}~4(8@;Y7O~!23PUDYtO=6V%`QGi zR|6g0oz;bL%QQqcI(@$1ysz_%=$f+{~wlgkp`!|pJ4~LMI%~@+>p~^&*tLt5>iuSc4 z;n-9W8*7_tB!WK&_27g^-O8nufc?(<52?wUKQmEHgDmA9q)weM$6Y&E%*w<0vq@C$BDwFlx)51{l&bU+kWjd8!#;X8Mx_G zMpN7jAwIrwMIrUE`g;AiNSB%;Z?tJRBE)AcOgp?_-oG} zm&Dx5cUb}qGEK0}W<8c_ERpJ{ayjp2d8wL`8>!pF`0V-`;(kcTR^acq1xJMqC8MBP zy?QRu*UiIZBi?sqCt`jr~B{WCc z1+3Py9fOm|evg{6a5WNWJWIDDpE3-xs<2a zM?9~J|Lzo%aiDnUR3>Hzwc+H^K3F|?=Rw#`)}K~$>u9Mnp`OyAkfY(?fUhZk%D72S zX45hdveoGctkB#GT-_hG=>H551$m7s|0GFVBu@8Ok)=c<6WG7G9T`=b@uY{jMW-P@ zcA8tYC=VZ3@z$@rF<&gM8NTO+dPvVajku$;1dYBjj5qx0b%-P33(WBC9vjM^R` zgXQoy1AAyWW1Vqz(kF_ek1MgvUBj$vzMcIri76Gm-FpV=i2FR&Uo$DBqD{#wbi5sx zMIaDo-;2v)8pU^Y8p`)Fq0($>i~08vV-JeV`ahJT^q;5+X~H)o!YHqQ*t0r5ECso? z>&A&sn0cMADspp@9=GAIm$`c1nOV;|4{E!pwPIZz&AzHz@4Eee7xV-}K)5^9#C)i=VPT3MxI{uoQ04KgQ&Le`CIT!X#ZCcfgH<%nhIP-}Oq(pU=ApvBM?lI?Vo{X1U8JIJG-CG4|7P8FN}>{N zl7ulP4flD-eV7rRVUCJw)|>o_;lKCihq?<7P8@j+DGMnNKAzaOLX_|QJtUpJ6TbfU z;s0-7t4{#z{|}CB+D?SA8|tWO)EZhw5jpgqxoZo8P^#x^alXH{9Pe!*Mh~VtF7mz} z*K9dk)hqlN(lp(BuVclpdH2J0(`d|&NS+`s(<;pL{2i|*snPiI@t{+3@o!WVTkR{$ z81#&gLsJ{>WRo{6&6OrEq&$#z#70p|1OJb#_`i+B_YkDwx4++i{O`SSAh7y(mZ(sl zu5{SgA-%V4cSYSFLGdlUzJujljyH3eHbx&^Px|3XN~2 zgDf%fUH#_>@-E+ncgziQ1Z+Sk+d(q?+a5PQ&gDQT#nI)aw3wPYQ;)e)ffWqRl-W#?d50?&udv1u+rr zB)_-CiK*c6ufr?SXzK5{&HE*K)ozo*@k6Xsc9OGL7wZXT`Fs34F5edSN87W8P+E=B%yN(AKf2KZ!T$t9%Htb^ZZ4i6jTf*%$$t?Y-3V#UH}Z0 zTHkMPx{;mC*M+->)_SOlOU{i{T|X8b`P&REBJpPy{#~@I`^zg^VdFoOdFTLO{XOrm z-HZ>;K54pTzqx7|uXH=kp}BkJm*$Y^?f*MQlTnmlxS@rD=8@Z;FE9G7?g`fm-OSLC zoi9^=hyF;Lbr?|Me90$Krd5mB=ChtUX!>R2e0;;E$G5}reJbgG>DspNISKPHr{g7R zBmj}v?gK7X?3!I31i?sufxwUYv+;27ESW0@gI-Bc@Um8k2HpXY+e0%;4>joR_XrZbESyqfTIss$3UdJgz<21h{tM+6s$!)ZG=By^ zKYAE7TR0OLIJ+ABjOT^<@RB3Et(9j*9bJu zDAwk)iRl7u0?5E0k+z#1#)Z!V%wKl|Z?^KT0LA36){W$K{WsZsxvdpj?OZF<8rW;C zR{=j>?a#kxd>B8%hlv&wVYv?O*%v_Lzg?nc-oax#PO8IM4HX z7XuQXX3SPyf}BQK{`U6uwXn7t8?pNc%`?g&w0m()D7vO+w2xN zhy2(c3(+sO)=GNkvQxYo9EV?02;r{@8UnB}n_3pWRn@vs2%Wglq@qYlSa5J7s4wNd zGz0CALv0yMlG~_7$Lf6j?yDeh`F$r}Fq5g-f3W=mV}Z;PI9pt>h}R*PR`46jUry z4}5-x2Qd5%rNcVrEK$19=^Y3t_4okJ$uXSfoHa=rs*P)l@-BNT={79L?yDaz+{xB1SU4|}N;+V6?KNp5vheWSzM%09L$PtE zzM8*lhIj@j^*tEtP$IeBn?994uY3mF^BKhZ9?Pd6hj9*ycnox)um_FtzlE>I6pFt| zU^pKo?K@l9aj~zDUM8a$+f;-TuAix`W6IVeL{qUGkA2)gqUJs50~bPlr(>`X00WzW zRO=RWegGNM^_7^Yu1(d92lVwy?Bd%k;&-*=PkJLO2!63(4wC@hccU+%l&LUHCW&_h zj@@{qw(1yF{HxB;9Y!^)1bpr7s)03CQ^Ga8hQHbQ?y+>q;%kHv5+vzpXa z_zaplfy}FSRJWdx+k2q=j88gb#6+}%#iR|NE}v&B*c2XgFsRdd?d|_gOn(F0@QN&4 z+Id6bwFBy^glUP(tZCO#P6kQ0!$O6{x|f6d9K|jKt=`X6?mE0X3X=WkTz{5}uEB7j zHbnH2KEb$PeX>}LepQ19-o2$-0rqX9My5O`*r&fQJ6ikR6cQo_jb$1>Kg-p&?vHyn z=PoOY0T}92z8Q^1bd<%yh144Y-tY=xPpepN;346>27Ar7(mj#`5gWU-`*FQ$vlaq9 z_UOJmg-d%L38tr~M{sEg)jjUaOWm;Kvjr8h`O#C*umc<9Y91)rFLd0JnY3nBxh(pK zvElN*sG@UPZ?M3%x#6QbEy~+ubl=yxbJV_OyKJgz)u4#Pq)wvPcRst_+Um3CqT@PC zSf<(P3b>pVa$GgkBsXa;uBoFL7Y?0y-O)KW3{;roI8H%YHp}@UW6iOpJ#JZ9=t$|U zZz+BU-`Ypxojf=A)^Q{Q%idniWG_C(`bzJ#F}om>oPBiQ&adbwE1aJ!Y9_yT^jLhf zx4xoRm@+x^wxhW&5imf4Cb1>z;G+xHzb-XU@alBqeDd`4%b#1Z%O+~Y^ zJQA0iDRi3%rBC$ExZ$an4j<0-t4fCgPJFB&D6spwPEVd4&J!|s2z1L4O1@2#^Urcg z3Fij3DOayDx1h44`bD*iEeZWXe%Vw5faQ9F4j6i%Jr5eW4G4g*=$#EEc36{LFoMas z_))^I2ilYbQC^Uy)5-ulN%A|}Yr@u3A!yGQU}Zp-$A6m*{4pw3N)bL?r0*L@b2jVG z5buQG(i&<~G|}Spo)%D{UTw6S2rVY912s<4!Ws~`WO02O6`uAmSm_w?1sP;Hpf`s< zk4%B+fqb^p%a&{YWz$~cUjz3uiFzK$qtr9qAtmQkA5|$-(;mleXkegB6pQlKPeqG)Ue=Yq^~u7<_}^Zo3(yh|l@$`vG6bb~dc&yT&@ z;YL2EOt>rGr{q5C-o|pFCq!x`)@^$v1Eww-$mX)s&iWnz+F9GzgR~?y>-#_w)_B(y zBg9MNf_aaKI!S|^@lVotpzY1qxCDFpt_l=rC(~6OZ;lzXkN;`O3Lp>eES!P^N-s%- z(5So_=n&HQ({`@q8U3X8KxePa3v2wqTu?uMca@Ca{6-5DjHHbRD%VKrmEu-kQ@DHEEY+qVX0SDZj=(Y&Uw?WQQpVHr=Nnie+yKxP@`ic{+ppbl6K!GS=p;7Mx; zm2ZtZbP&G{O?w_>sz<%+_it4eo_q^h$i&^@Z5;s}mC!BX?5%C+I`(snmhgKUqw$j(2|rv=H-EV1H#$pwN1vypL5T$sc8Ny*0^v@jH(gJ+$Qt)Rs$# z^d#)AwyH|*e~3%9jjW&4_afdVdaNR-CZJNperdN@!E3gkjohBZ+pEQ4KM5?6GMS`Y`cJ8F!6p|ku9j%-Saa*F8`DweX47Jd%& z<;_`kzk=S*MwOcQ(;IKk@_xS7y}pXn*FToy`sXk{0ha~Egj z?*v5$R0A0}yj~7rt-ZWifP@-TI-L`sYyxxt4x_6g4TCCKal`{DG!;bikTN}kx5&dG zmE$jhp;-Hz&7ZnXbrVC-$HYSWo=H$i?TY1VeEN3RrpE-VJLqN9 z)a25D?Bi(rQE(iMcXcn}c2_Va@v@Qk!F+mXJwkU4%nR0(;Yf+_R|lcOQ>IufL9g;y zk&6yLY$*oThf?Rm;LIbu?KDnyf>iXd4D zgSPYVkV6~hWX>{4g(a32;24bVrcDgv!QXAz$Lge%_NpdEiuxZIlj4kquW6Zg-%m?4 zzdqz0#y1r2mvCEK&32<#4lX*K-PTrmMHsKVcJAn%vA_N6)w^E~NCzNKD)+S)1yz*% zQ8ZGdBg+Hw`jPX==IRBT4c$wLO=pYo`M~2awrsKODWz+Tabzf&G|Qj&TsG0|Fr+&~ z)fYExH85q6c_WG@JIjiK69zPfahIPWQ=pRoF(Q$OtJ z%KTZ$OImyU=B7}(f>wx&?oEoo)P}OPkJ#>_A9 zqNQex8G}g=?R2^)p2P%^*afwo{6u#$Lq(K@RGl+;?!6~A6*VgjiMpXO#vd={3q6gjGzJaAm*kWzAv@hz$gEExl{P zm8kJH-TPu9J_#A*xN~Qf7uSo~^!qO7ov?kjm%UGT$(+{k-ZX067%nsW0PX9vPR03e znpg{+idp?A&9VO^K;O2JZq*t?wtfG+#fwhyphgU@?!2_|18QAsIPLx|6Cr}U`*&*0 znFwfA=>v9~pWZ$V zVMZ@29r#pkkh%icjoDk1Ac4fXp2RrXl}>)K2fTz=rvYWHCD2dx<4?SyN&C3fOMYke zgyM6e*dK}H!_BXLNnF)n8UR(iuCX^vMaP=;R;L;-g4!Jt)1vSSOF{_vNL8>2=`Cn2 zO(!U4sG)b-6OzMR)@H%MJmyr^Nq2d)d!{8j(|+`b6-ybKc00#mUl!~^a%C_|xbFNS zMel;iM@X(;c+FBVNjmtBxw=bRvfoGfrMf$g9w%mAdYI9sTxiX2$Do$SyxJl3zLY1i zCLa?e|1LXqqjRKW$dGnbTT8vAxJ4QN;EslfC-heRAkn01Ia38GVC576}aNU&$?WN<(@oejo8vdK>zYcK_%UaKDZM*k3HqtFm?xRLhp`qIeX{g#ija;O^gK2$`l`T}ir|oNRA9#Q%`Gc!Oh-PvhrYnWnXx5d>1tRa? z5Fk{Q^>*;EFZU@C8f@_P8;nk}wLCFJ5)@?H$~NKBvu=^jmdL`(YUK}O(~sx*O zqF*_i&3i(7tDeZ6)Qm0OuAns=lby70Nwmk664|#WmZdSP!}j6H8)WHFV(hX+FMIm# zDJPW=Unu{jwn#e&F2)l$|06*^FHkoXAwco|ntb z%Gt!u8U5J01~~Essva7hE~_G)P*ut-1Em-9osz{WhpDvP@T%fM%G>>(`H_P@Vx1o| z@a{>q2sjhE&g)QE#TSK5MCc_ax5-d*v7tfD zC{ee5l&Jk`^6oeCQh9AZ@$~ZKF|ny(uiu$UsU<@y&zaorxKjc5<$Hq0#u~wZ_?>MYdlJ~KRB9kA2M5CeumKHK1px8Et51Q zkod4F;f}&WMvwja|xq_WR+?Ucq*VfSK~tVe@@e8s~Wg zy>m=Hk0dLWqo3|9g}7ulN}c*V>#p)9v-A9hXpO;7{+1WnTgrV23Aefu@G`%4g@JHQ zhkXph599j}i=tUsT|z7$e)FIe;W*;1;mbKdTN~h@SGBfzS#Bg>S(*}BFJa*qi2Uq$ z^ix~sv$|B*A){!^N9i?C_BI`1M&Twr%EX)TcODnjT)Rk`HOLgwX+5u}IZY7J)NzZG z{;NzC8R{xZf6Y9rR(~ydcxbZKw)=EC4pI5-QwZYtj6y)P29aU_BfkuqN_?zGR2sk( zVNVcO3}Gy^=(*O%p?4dzqwlG!7@8#%rsq5cTVLt0^DE+^A&d=Him)|=Q87gKM8vuG zzls^6oIPy_Wn0Cy@mjPa;p8e|&e1xJ7(;wAgfWqaQX4fSsTGknW&Kk~&*@E*-J#3y>el|Hc zKM(QP2u5NSR`~YC@g2Lo6mh8&lIPY^hC3hw&Gq>O+mgD*2G#kWJoJv*Q_F;yX7O+q z2D|kSo=20f@sAt=+t0R>_kZLXIA#ZZiM9?m$uj7ZZlCK1c_g9)o`vt4pN!_bBGwWx z<5N!u$t)1vMle(Iy)nJP*5Oj6*9IXbqJ5pwDw4U+Z%HE*jbY-@-p($qdu?8O!}9L; zO61|k%PHhG!t~{xj=7Fd*0->O%#^q~9wUBvT)7*3)ufVD%j~_qRZpMy& zT@wjImC*-pvP%-9d4>xncuUGPRLsmmImAJY8MUoIZ8v|PU3h8D>xy5$%L^?4Nb&#- zp-Ew#uxyp};Mg0i!S-Js^qQ^~*L}S`pPSl4Qo2lLyBE$eX@+pYt}V_Ku!!2H(AkUVfWn&KO*qajznH^IEHW#hA5( zOj_EOHebx|t46+C6t~I=%62<<-tZH+#ezH<{Oahk?fa`l;%Hiv#?x8_C8+uwaXL`7 z%eP%-7{2wmw^Y6aU|A}0Qg%v`Z{r69hBc(~L=yIWGhl87eNPKx5=OcJ z1|x&LMo^f+OrTHS^MdcyN8Npkx6<@|WHH26g+_RZdZ1#j&NsWnu6}LA9b@}|CHP=3 zGWkr#eSGR?+$Zd2hoBWf*7+ta$F-f2UiAto6l3qS^h$u@)pKVT2jj8#@682Bs=VrF zL}P`lbJ+oH=l;?vHL*?d8%N4)By10@*k?nq&YlA@P01yVD7qBtUmjfo@(gr*lm-d1 zVJ7&FK}!-}lXXTt`1{r1CQBGCRtMxD`1Cvj&H1=xCWnuXnOJOJHVDB#I$AdZG7WS3fn)9J*Ho+0cRivZaXoUJR4woH<(J4h?+^}4B`;Rg zmUNCnz$|_7ph7QSkL4;o)r98~_N%qXnohnCV`9l+uWI*7Ci&S%8d|SD2XD^{K;(`2=9Cw?j z#>t#w8+)Hq!=%eIohEuk;Rb`MAc&;GfB+X~HhxyS|M~z3_su0}4i8yadt+?BJgaiD zoUf4Op`@P@4GK_la3r@>v#DRfw#41`>jMZ*jaLM_ z+eSOaFW|_Ax7e{;e3C(ZpQt1QW5ejNJ>w?=Nkg&XA(R2Kk#sD>*lGmUM=jmq*X~$k-gz|f_=!SdQikwD@A7GS@&tA zd_G6!rp#pE`*ewWjJpUn3)ou@K+#QC zr_PV5J*7;WTwXfrE!$1|tgUhGkjaIGw+HbXn{I72@pn;{$&|H4$woO}fcP@&37I*S zt*!P;P$j#4)4wspSY|ds)oW|YWQ6OFuXo~taJ7UHsDKP`i0de#w|<7I_;VmAy-5Q< z?|{{k#wc?i#2@%>yf%?-ty`2Fp;Id-UsBmr!tv>yIR$rm3EGgySE zK_`gitLZE%;x)80F5(uCz{t*qo?4oiBp-`w_=V7-(pXVt9Ppud^B&-avWk1p=#Y<1tpr>a5RzZ?m1cSNX_(* zZ_s#pyz-k9Z+7r{E}-k>wd0lH(t8}bpN86@qEs=^u>@p-B4BDOJ)e6i#0^pKanwIx zXMbbg&{l_9VqmpMjJ0JQ=BLk+;UQ2-kMm0&NxWpkbe}j*cO|jBUol>mQ@0LehC-Z6 zZ*_>@$|(th_C6!!BS{oh7RyVt0c*bmo{9vWVo=Iz9&y#9WCL+LHS?%gs!k)SL{k?5 zw^)0bMg?37VeJw4-R$xnIlXedq7a(PA+rxvZ?zO>9QNEJX1zLDVRb2{7FRH!U zH|@|M0MAKKMN1VH$k!=lI$YT|r=`LCtGs6rBAll|YoOz#;^0Im&lx z;PP2BU9L6zf-I|g&RkJrTj^|VMG&!sS`da8Xb=(-+e>tPLOT^DHeJe*QxfXY5tD8N z5V>8IfvXhOE!m0{wKIM=#{u@9SDhq|1N_@7r8Dntz7m`Mkrt4~%9bkd_Oh_mM2)FN z7+ufQkhgY}i(8I>bd^Cb0v&P+svk^%ewf{2!8e|`8k46;%xFf0DaB+$WnpFGy|o|O zi<^6IdiDG;NIJl1y`HpOUhvVSo9H%Y!u*{(0M!l>oI$joRJWvNz1y|b)T(AY*Ut8E z`}=3ZE$5=x1y?9Ye^n^x#g(~7i3Mb*_Uw6RCR?z5w9g1Wpp>q2t*elBo%>(8P4;MD zq971G7y~mUjODy89T?-x>W@sX>8s-t`}P&ty=G4FLrdZ;nO($bC#2$oPXAuAQ-jyJ zIrfITV@!LcdBP)?3TtN8Aln7h#xMu(oX>+p#RK7{?%}6SU#s`{O}gByZvXJW9p`sl zWRVbEQ?&=^B;8Q*7atxK=4`p>`nb95K^dAi&|m<4rTXh-727iv6|+xEFdt{BSw614 zC{lx(_5UbYSGgJdI*g|LJ!rQJ_0W#;{T>|3(He}yd^Bm`UQ+E{!~FmtdyG(RhcM z8Y2u;p^Uq3Xf#u>FPhLH)r<^=>T6eH-yoSrWtOFHi<=bE`0CC^2Tj zc)_Dh3X@kGKVP!cVC}=cK^5$2e}P0qlo^TUoESSC;xl$A(By8Lo1i{P>;BC0I{KL& z`q{lgKuWlh#E@i6a66MMu+!H$#nfuesX1ktc@>HRlAEx*{<=x(xTAgWLkt%f+@CTM92acE%*7>S1vZ0U7 zUcpOSlbgUO2>D=YLiD|`s>-kKBurO3r2IzCTEQOc^`1EZgH^8!XHEQ`jEOs9zx8qT z;BlF<&z>fnO-L9(Oa*k-$rM}T#k4hr2v8X{{fium# z17rEr|8nzktN&Rb6<%5P!$w|qt^zirhI+yByx73fWHKkfBn^R3Ue}h2y#QdLP~&H3 zrRF;ymIC*T_~vf?gp=_CKKf&68iH5di;e0vs0dVz)vEr@WR))omxIVU%w?O4=u2}+ z?>ELb%WR+StCAb+9hfUg$(i%D1LXWI`^nike`?eICEMb zeUHaGJA94BRi5r)#}!3*nYhvimA|wJ{*c<`8Qaht!Y>4m9nmi^TA=fUgQW_{9)pSA zRlZjfS7}8eV>j+pq<_hHvW#)x&?J_W`5S`Alt2{PZw3rKEI&q#a=SuQQarMvJm-wvG{W#-#eiaom*v_CfV&9*ShP#0@VAjN*Sc1VSx_cK)M6clQev`UrO|R`IB=sQR9~O^cD3@Q*5%7z*fy%&WhN|^_S#en;5@Z0 zDkeJP2ec1Xk81@+e^#Ak)?TyZ!%2|8KG2xOF-Y`ZgAXGPfCK@|f;qo+Q0Kx#l7e{% zdyh=Z3SqCc8Ykw|C?zaGtTh3J1PcU$^##Gaf=;G|w_$OOHtpvZoNs}V7lJ~ zn$TzUOj%5Yl^-r!e8qCqI*7RbA3*Gd0l{JbpXK{7>u0nu7S3DrCzI(bH0eoh^ll7n z@%2O^utj;Rqu7-{yl=QzVEV{iy;`ew6=p>`l>AP2=>*Xd_ zQ;ip7&4$8dkE(PFAI|Rg@bVNMSSQ}-bs!h={O&ZrtYWTSBI1&2))WWS{8sJmKtL1^ zn5@4a4d`>jW?7+B4*i->5_qP!nHId#TEvGx{)$eb(q=)YOS789KRlB(Tg{wOF8>2} z%(NrU=Y>9<0z>>SyUH{%Wcmi5qr>H%J|(c2@WKM8VisE|AjSMRSd8Z;bdD)A-qi=$ zs}rUhNfbXxAg`wSMX6RLXP&(yFSTOZ*2lX)i&_(AfxL%B1Ww6KFo1b-gS7u1Kw9(w zW)}`Vx!5ykh?Dn1%DYSfi>~j?f#|3i7@h!W#AXY~KP#1!iMPnXIilJ1sz$onA>XOxU|)3PK(JAZf4#_{11 zjN=%zb`Wuz1ARory$2Hr^!w`C^$lEjKSOl$X-R<6rj0|RMudpTG;!b2|LD{`4CZ^a z!B=HDw1*O@p>Gn^GdsizH3#iuD>-#J?fR-h%SNY!MybH zUJ%+K%cDQR`^jX@40cd2b6+hmPuAxf~&g;033hxJO926(o;7NEhbd zd2k(Zgt18Xm(t_yUqz^quk$(WzW&7o?&(y3ipk&T>ev15|9XP_?*qh}iQ(GvA@Nt)h)04e1W; z)d>+^XeX6>Y4EpE`0I-@I)DXEI9aRKec>g1MY}xtXIE#(Sdvv5yhwx=*W02!6rC z`ju9Y#)!D=3%d!uQ+o$^(Jl>CYZLAmtKaBV2xv-Nu$?xg&2r=RGz*{KARv20cK1_y zUmFlAC!kemD)3}2vOiadA|w=b6sAucJ0BV=pZELxts@`@9Jm82$-UF?x(qr-(DI_ z6Qf+Yw+L32<2Ag0y(`h*LX;|lXt_P_2v7@={8h;r$>9;CZ$QBMs=p^g{hP7$BIo40 zx)+d>bl(8oKK#}X&A4bvLHj;pLdjjV>;z1Lly%|;&Y9gLO zG-p$h;=ceR9XMErD)qbeGwQFLJdPgZZBi}&wPyd}gn36W!HYmI>?3!Dhl8UfU#<_x zRUSWeEz9;T>4G6;Iri&;wV!Mzv{EsmKl7VmDlz9Zg z_An5xAus{NdI;NVKD8ou29$w7y|r!2yN-Yr=jf| zclB~HhIcg?j!VO&&DROcJ793^EwF zVqoboG3M00?IXIl<Fn` diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/must_avoid.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/must_avoid.png new file mode 100644 index 0000000000000000000000000000000000000000..95ba285fb449a6cea68cbb3aad2c97be3176bc17 GIT binary patch literal 70762 zcmeEu2Ut_tx;9`z$AV=P6$KqdL|RCw(n0A(0qI2`5JE|S03o4|g_%)6sY($X#SSQ_ zNVkk&XhB5~X(}z$NGPG_Upom!W#-JBd(XN5xpz3{8I!g5UgfLr`qsPi^HD>sb>Hpy zj)Q|^osRZlV-AiLwHzFr)2mj3mRG%zWbh9s&R9#GBdca-4+n=vzwZ$XU(Wy+w1+c? zAVP!nNe~Wm#o~Mg5r+lga0f3haU|LS<>TOq6UR9Ff+ld?6N^NRiD(ZG2SK=|v^WfOb-+SWQV^jIKIx+| zegWX$067_Z87X1#NzKd4!`a-~Q4bBq)s#laiX&v8NA$E!4fF-!8sM`B+T9uaqvh=6 zj)fl4aP`4@f)-6lNl9@S^gqyO;^5-ogI?4Hv<81?9~>HsVJ|^STuNLL!J4hJuLFv` zdZMFQfE7U>uIc1xrKzpysEd?j-Q!E}a%SCw!eUV#U__`-oRb6i$P^s=K1Zw%(%FaA z1f~KPL>v)>sexOe|06Wmq6J?t4q)2MCk2ln1mzHd@@ni4>Ke=sa6xrBcBg2z;AJ&% z+S*49?eRXx{q>AB3FZMv&#%Xr8_6?3%g4dX)c}ih_5i~n16YG0;Bw4qfffRL;xHIO zj?cuvXrwca{WR-IUo6(c7wz?BqZ1Z`adu+c0lP;BA0I6K z%iCPA9_;n8@9_fW^F{AagUL6dhFZf6_)?A==ZD%yfb#7!y8F|(fPlvgi z*(<@hIv}xl*7MA!#oA&?a!#H;SS;vokun!wp1a92K*QMs68D@O+2a6H{OixoOT%a0 znf@!?0efY-frE$NoZ+!-*q1P8!#-F)43g>Pz*g1qu4rFp6E6oR=yp6XCeY^U>*)c$ zK^~0r^})J3YhXRFkhx>97;u|9h%6p+O@eTQrX~y~qXF8npc}L=WN`?nYxY!}eSDqS zcDcl2nN5Ez@ddeSIfF3Z>q7vtXZI)%h8CBVW(~!*bumde3?`0{h0Xu5$Hgz$k)#w{ zQe1{@ORkITNQy0e2e$d5=7)sj`e#%O?qOTVA1@1v%wHK2J5>4qf%bqgGh-Cmlj%R| zAmI6;f!F9eI68YA#p2MutnlZE_4UPi0xftz7t|e`+)+%$&*=^6?Bd|(0gQdV2Q?2g z3JRRQSjYw(a9%90c0mU~#-h#~P;IUi(l2`ohmj7x4j?zMzQQ$e{wP7XdH^sXxW-X! zL%0<|UCPlsz|V>3CFQ8);paevp&hi1VNQp!{`v?c0!ffY7!aiWojjfV4NTpojZEZO z_YrhZ&RUWDgXZ=vpr)I!N1Ep%~u8ivd^CoN5wgND1TiwXN) zjIXDIc>vDHQ`+Cr^Y}tL8t-Qb4yUXEIL86Bby(ZJl2U;wTi)sQD5wLNfFrc!dCA1^0O=3Gz?=Es0c3~>$? z>Uc{FW2}ywl$?{NnHy3=9cyLofpO3V*WH+FMmU%o!yLf6fh;8T-HrqRIY9F9Gc?gb zfj(WG5RiPCb0FxTL6T4hqcT@{99rdJDLH-kyo|J*SYvzW`dgYC6PF(M2wF#*wMH-w zQQz%2`0fto1L*?#jFQ(uOG$!xfKfDwPQV^mGBQBx6Tv!|vQ>9KYNG3FV5$bwcXP)X zxT*OWnxlLT2~q?D3rk-Ea}+|~O(y{9rs?2l0t+zIkb)VQ;PDO`FjhMn7T|E$$x5hR^OD>u5YS|W%n0g?g;~99rH6hd<18p^*=k#@5<#H{r(9# z1AQByr2-7T)isf=YoO7utRR4?RV{g(vpLe=5v`7QgnRfQwSkqm0gnQjGcr*F-eurt zXsUxUFp*)kil$Dp21yaKi0a6td^fc69MjC1a zD2y^wuX}*2v$+|;0)&^NZUOFA=2k@T?_8>8r+iIWD^Cxc<6$p9N4T_y5yBAW?!eJsixDSR@1o+|(AQX_z4d zx4?6MoT87gQZy?S{kd^WEfVdB@#9iVZj0|L!70BArYi~7W^{N@dq+x!5b|I z?!W>-Vgach9{|#}w1GJuq;wsazKN8yp_V}aGrgNg5djPUNdYAZ+QFKb_ee88!%-l? zxVnLaB?a2?`cMJ`Fw(%y5@%>4B?;z(Ffzx3L}p3UXC^WLRsQ^(z;kNSj)#wd{*L(> znHodmfW)?FK5oYl`poO@AgLj-KtEEJ#3O!2hn;W+8ql~-L@-Z+AsP>0+HnH-yf7bA zD6#(Td~got(jEX}5dho@0R1xMYTyRxm ziMllOJb+b8^#$a61PxXR10{B=W$@EI*Xr#dL@EhnI7tF3iS$sIUNXWLcPvk`<-6d@BrFI9A#FCnBc$% z>+8VYPD%dzQi&{FT%NrVTu3DdnSX>2KphQ~=$M=R#o1&o!~BozXF*->A5|lqF-SG2 zTC`AISX6!ZvQ+V9Edqc57)(=BeW6M*2Lix09ia}YDLw=X(ChpcOXv%LQ0!}mp$fwM z#lw)Onco7?zRbtOVF(CKID_x3CuKnbXMJCI6kPn`$)nCbXi%Z}3QjsBzbbX%uzo(w zf(wujTh(3;3k9HmwkEO&SpewsjVa8v`8az3v-bb8`nHsP{Biw)RhC&O&K$*}K{CO$$k_@{m$aem5#pNH)11=8}my=l-k|mjW-}(nL z@^$b*Is5(-GeUq$HmC&6*R1|nn(Vuo1)+a*=QnjDb{*@FK%0}Fk3X~M2l>licDgTI z>-YT-^s5PKgKSsA0nzz><=hJ;!bRZx8~^xU=M3^PQeQg)LKbWpzO7OI>l{H|9xnZt z{qdi+{<*jS^zQ)GYv^Je{cf|VF!pQFrCY`;xbg2zqEP($ zHg-V1_6NEApN<{>M%!ke8U8ifMmpeJ=X2>IxC*r&b?^o74?0HyC=NO}XCI->XHd}c zC9H)ICL3|Wy z)7!qOnZscK6@#tg+~2>+-Tvx4{v*7N&3gDdxBZ>lKnX+=km0`BgG#{ws+;pQ7>sQ( z|Jvk+_{;P7kMK6OZ2zRUIe9qXaA+rh&%UUVEHp2Im0!X|7jRiVyg4sCjBSqXp1)f3%2{;Z_+fkbUC>4nrXBY-ggbLyB3APUR6nBoBu+*sOC>o|+VJjctz=xBLB zbYfH1%*RaF323AT9fTagQl<4|oom{Sg$z zm?9d&0ht{w1vdf&X?;L)28<)w{+v-2ih*0|ppAmeQ>L0U26@ z$(UMvuLF?6SLE$)nPGDhWHHc~^ZJs32CF#Qgr zNXyX636SamlZwg8V)mwG2w9mlG&*x#Oh(>UtT!~odi(!`s4NMCs1sld1zwh6Lb`7v zzZ5tP1+U=D{e2txC8eP4KAfFY7bkkact*?>x&LP}{hwe>EZW|%-+fvH<-P=CU+%-1 ze6eqc67z3Lu`tH}fi1ecBs;~HMJ>HqylDDvNq3YYzA)c=T$$DcTP{~MnC z#do^?h9|$5vi^oAf5VgiBzOV{ZBVKA56}t3Kb^xS;01VA)?HMD`2QK5e9KJ1L2u?l z)HE3fPcKm3Vf`1h;2of!QhLgORKgq{`B#*in2e_1 z`Eh|cw$s87IV|S?F|W@3pakmz`vD+zP$q_h|<)Q7d4cCNaep$gewdL5xH8RV; zKUQ)4sN4D0J?A-eX2}ZAV+?YV`}d<33)J9U50(G{=7}r&GX)`w` z*YZ^xcB_VQeDwhq{lu8d7r*?g=D8a!j;e+YW-aj?^M+-sR@Js_UAkjc@F4&1J*cty z-m+jD>9(}m3_l>BSk86Ob@l=y6mtJ(O6BpMAzqQvJ!KD{= z1xziXt3z~YWl$tJIf>C?k9#&Pxv(d-U}_pTpRIE%{c?RH7sEJ;%eOZBu3k#dswZ5* z)UL?OpZ)TwxqFHFs$s28YcK^%FAOHd$vIh@l5%8esVD)NQtz*jwOx8)+mgaK{#N(b zqWiC^`$;aw)C#v<={zohq!+y1k%0qB z&qfNC6d^~r;Z_QXqd1oLw|7f-6{dQeORxG80%dqS5*@L$pjXu$Q4O<8jF;kBS{64= z!DZnaWlN8cE)K#&!QE?wxq$HHZK@gIvaY0}=jbhP+1N00X#-KU1wqlzQfGL{kjW9Q3p5<><92T8iS_=lTQ$2< zH|clMqv=6#InKoCcP7RQOxM=zwc?kenj0zI7+lUs*|B#iui*$U0J*a-C#FknX^F-I zuM+93+qSgj{jKV6ly?P1X{M)O)jc0!c@Fkq*?*RTy>bm)NuKw0}{?66k zWaGbK*%CPVZv_5rHvSud&+Qi$642k9t#9(q?xTNiw!U?qf6KnQR*(xf8JRoLoiEVC z$S0`0DROn_mY9AoKSS(ktN$?+GlsyruW=6?>VnmJOzN$b$}%H6e2`pMvVNJ4nA`d_ zdAr^bTiJrgHH6 zhpY;~8Sz>j&dFajZPjN>V8NZDQ*~*ThW=j^CaeT^t77Bt`bUU)*<@9o^iSt$s$Ri_ zBPYC96bP#dcti=R3LLPYp0XW1TPU8jsPd4G17(ub+^tF~n>dN&HZBgxn9{4c{8rU+ z?-dcWpZsz3VQx@;<#%FtMq9g_-|Si>TTdX`yp7i8Yj}Z(HJDbY8n~i&XFAV5%O6KZ zbJh3i+ly49OcUHB9=9$sQpzDv0BI1j4CWS9&8EIj+79*UdtEhq1!czEp+|HSc~M!$ z-C4iBik6zMy|@PV`%s)<+B5LBV{-R7I^!xZV2NZY}=ASC$fj`u57s zHzsdeW_k9d?_H#-L*}5Co$vkzw|6Qii@c0b)ZOLzj3uXQ%XPy_+{%#pnvr!I4n1nS zW%+31wM5n8xS&fZ&WHT(u3S{$QtbmW%glXCgMk{-^X0fhOqp1yLzQq2Ez~WK81F`@ z_8gtE8*!oDi_(29AJA*7MR(T4&Y^r|dQ*7o7I)|K(D+Arz_Xtlyp0pkr+PXY3M?JQ z*FFAmApwME0VBh|^?4h3k86aOo!to4yi~ivp+TaDfi5Aj1O_I$c&MW)K*Tfk58P4v zRH^SX5MGcJDA2w|dX4#a1s+L5MyGo!ZwuS6yKA4qdOaP-5)T$XD# zXd_ZrTTYUQJ?(rv0)C5E)B;vCXjf_#IeW?`ZK_T+`)yLvTBbT5sUlSE#hu^)s&3b_+LqEp$O`y#W-vE!-$Itx+hdQIScr%IsvQMmHWNe zu9wr%N8M+G2er6ogK*lzX%Fw=x>Z6c-D9KD4#SVb3vmiu~Gg zzghXU#c3lm98?{G`m_Yj{3{tEJpHAwza)&;d`E}5jYsRg4%e*`r%}&MN0P7 zr{z-A3h}|dGS%$e!=VE_)Q2b3x=)ioCMYItfgftm@xA;qr7DTqFfG7GNhxu!=;kM< zD8>oVye_*w=-!s3dh2W}@3ll?&-%p0^-b)Eud<<`Ui^qGtlISv*RE#r~ z&)rq_>Yd=*1(_}J@Ci+q&MQ@Jr+R{~5QpisA(xkSA=NMY`8QgQNC6)y!;E;sh3|a# zns;5-+JzB3H-M1BX~{dUt7U5xFEJ_vJ-EGtnRpl{#a8F?NE+_aw1>_5lL{hPg z-|)hjTCF#*$0+Mf%jVAyDVr}|w#*+U!HOkJB}x<1tnN(RKUU^ku3z1|-GqKCNq}kO zP>nb|3KXO9{jaypmsX#g;KFy`zu|w2zM_xb@Y$iGQpW$PQS~t5MfD;a@?;f=+FBg8 ziSu)QyQZqD|AzV~Ev$}@rp

XZ6K(h)4JNf~!UCl~T4YI&#n^p97oX~HA&RDE>?nMdN3O%9{^$*v8!INTBj_d0`6kh?LIFozx$~kM#adqJ%8^n7qXML&~om^y+vFXDRXBAHP&Pc zz?p2Tr-)0@{G(#LkM|;Qe*A9J1wzpei%JE1PIzc`zqJ%hcA1WmYPXu38_>*3U=D?1 z3ju2F4=@qjjy;pd2?rXwK1TTy31&4oME=!sSFic*mw!9r-XA`vRR#E%Po5;~Hahom z+t#<})wO!(2j}GpQr-?IHbzyH&v5}1afcjjIzRp@csT8%^C3sYl?zcRoe$)nmd9>o^JjIn z7r5{)F5;w_d{H{SYJ9BP%2HOuw<=)msrg)@DhuLOA^PFD__?NZk>!}0tC1~~j0bu` zI}4F-J>q{(g?;a|Af4Ldz^$^Z#81w98fAaDJI(9rgG#?$pYOfeg^*Tod4c(aFk8^w zUh#YHI4AoXa}l2JADrV?I^>>}-^I0gh@d>kV=rJQP^3Ibe_9$n9D4G@)Uq~#kzP7? zDEVZ5z?jlR_XED%I?Az2_quMc31TRs#`+cI2F4OXW+&csA#-1C4q^;4BxV^hXd#37YeDBk|LgoTg*~Y=y{)qP0Uh~0tXA4=+xoW0l~D% zy2@;$!BA*yM%xUdh0$g`#GwB|>)VKRxxZ{AkXkHjjV<=uZ*)1OQlc~{{O55+0eVC> zPd1O8z|7Q#w({Aw-Tj5s68XW$?LmwWQ#UR%X1!l`kmP4+YkV9AFLeh}w5Y+m?OTZr zqACQ(R__TO-tpOj3NoXeR*EuCxO9W3t#oR(g-$IArOy;n+kzQ`Q}l^a&Y_ubDo;Yk z)X9xTB_cbXIC4|AjAn0VX(yd~d5v8Ax&FMikcnz+NbD|r^L=g?k6)H=75hw9Oj+Y& zK1gyptDOG{kx+SaXVNjiK#yMdUrju|^C+Tnf;wz9GXH9!kv^$1$JlzRjtMeZsU8CkCGnNI+l5&3R}Y`Sr_l|b zijRof=xbokJ{bXNixOJ7%(EvuJC+yq!XxdL=YR=nK>!76Af~OmgFMG_Pu4_>aHt@UdQjskj=sVJ1QG{i6^(xwlcVz3I!x3&7)V%wLW(dsIziJ$?v0-t%mS zzx4|K%KmA&yzbkIbqOIts7w9H4-t}jc^N9H3&4%y3j)`T?DIp+SQak+y+s|6pm5{q z*3)O*UxILXvN=J7cEWnH_0ZdRo-Q@`+qDy*of9>^Ev zc~DdtpW`uB`QCERRqNKo^^2sI1C||YUd}oR2U4ploeIh>9;;|XrL|ln{r2)po3vIKbe zY$2Hr`U~oJ5~zIa-JbJWS47$+=hH7DU0H>L6{mUa-i_PXpU3bL6U82UjC%Zp?1KUU zTTGzb&T?-u(&nq)Awbbvv5j}m&T^)T`VUBa44A;l50*>~-ryR!WpYDiwiQ3JqDN2c zp{edqASIokaFxEa%|Ae2Kl9@YIo!i@q!3GyN|!oEn}JOW;k88q@Ec~OrIs<9YBzGp zwgxyk?F@cOXiML^HJ#4$S`VG56T9EgJ!TFy7^U;>3dgSnUD$`}A!YmTiRJ0MP)m zk}H$<;)TWu&Fh`@Rj!sO1*Dr@+!pKlk~8xbw95Bah}t5^Yv25H`z~MoCS`iQt#m79 zr$=7P<`&mxSrF&%3v>MM~ z_tx~92Bd5=In&%?njd3}F$;P0`dpRe;mz)M^Sd1Jw6VLfZxJr{v#IfGS}F&u(b?6R zdHyPSt?%g71Css{dF72@oNg_FU@7zI8EPi=<}?0+nYKQ)Wh2G(cZkrEk=NhdvTCR+ z&Pl{ZfM>?x=$-lmK4EK?kT6z1$OP$%^_H~)m zYvqBIGYwsqxv1_kw5+U|+sMshmiWwvg_yUkxR*}};OVLg^9dTG9SHqJy1ExR#&G1=2Q0t6V{KDHv}SYeVpi2+(M;M%}6SR_%3n z{AWTw+@rt67^cFn47Ha@pZUZH8?fA%T|MB<-~TXQshF-QA*kBs_@=tRC5O9cWkqxJKNl^)K8F!b$=#S-opPyq{`N z3v1=a{i#J*hP6&krHd;CcxHtN3bYcE6(6-$3`^M@3A5YrU`_Dn(M_*SLnV0Xe&r}u zsv)8yL1>oFTI2rK9T!*ySpbkwt3_CANc;PdckA{T?7FvtGGKXRY5SOrPm%VsxynD; zf4@@cZNPEP0%-QV)OQ~r9#9pyoS3Vi2QtU(DA<9N+k~|eAwfri{$#TZqFXk+uH&>0 zYrTB@`_~W3!K{hhm;g^O`mFLzJs!Jc>)aSbo`uL8`yxUoClOsMJ`&!bul*(|kT7co zy6_%6V>fn4S-$(%jz`)1?ilu-*(d~ro*fI!?Bbl6-RCHtDSOy+pHDsM(1|smF!76e z(wH1{wRv53buNlrv+fNBb0Xj;*FNgcm_eZLJ~Qgm;=Ibucce@*Zu_SvKI&KJP0t(5 zvh}U>TL+4mSCRDY{d`#kt|!gXyepMRA5r^DOAZnOG;=x+kr@4{{r4>I1oGQWz36{- zCpLGz&i-gmyTCDl*eyc)BpMw9JRkM}t1G}hxaZof zWsiVf?i{#=j)v^0rseZ{;1DyxM-%yrWb!bADCOX4{ZKUG$Zfc)#6aWek`D!|(N=f~ zIyOIwbJCM8c&BvlL}NruBK9qR`BUO0gb-nDBdLW)P^(nf(mRNjk4sh?-ICUKE-chR zolhX8e=?;5f!%2d?gi@%wFQIxbxjq<@C;5gE8c(KQ2}`-u%codH?|l|D4G$|ALNT# zPHAYl;1O_?R(&!?*0aqfLP0>=On&#oYfh4a-63O zGEzN|jRMdX7KotK+mqN2g4X(XK+AW3J%3#ZlAHqmxjQ5$x|%KV^ZVxa@j)JM-VT2@ zv^L{UPdwIiTABJDh$m2j{;<`6bF!*Dc5`S#P#>KXiQk{wy{|7brD)1to|#2H%oCbolyY3D@2SaYJrz>D=GS9Fi#FE@1cit^Tj zaK$n%a@%u27>^UEvif|0v4?v7>Zz!x`tN+3lwMgy);}5y!DM35EnjBd@ed~njfM)+ zu(D`@v^60^XX~FoNav>G)*S72&*2;Ft`~XmC?f5y)ZVMI7MV0d|Ce<|2Sm(TF?li+ zJ4{=}x{>!mwQAhX?OKL4;S$(3xvg*CSR3gWG7M;Ec=t77-z!cfn(u2X-AAAsl1Njs z&wDnBh7RLNT6pZrR*7b*OYp4icd0)5Ic0Gj>4~!Lf%cQs4!u%sv$UA$0ZRTJzs5Z! z&96y5l~VYhRZ!16?DGT#6cGehO+TD9Lv>Wcp$_(sqhq*v%peKW)xG4YgNxh_pP57oq6Z>DdxbNpX&Ul^Y z`rGN0V_YMWMk=CUe;C*<+J+L{*nM7n?7iZ?>$-+MD(27RT=xp9mVTm!Vm*bn` zAr$V|cTbKhbz6FLFm9MLMKEA6w1}Eqy{o5tXVN+T__zoM{-FVa-s3niEZ@#L(KH&l zJy!Zgjpr2!q;gPqeul1@((e5BaF+x2&n8N)F8?4gWtu}?Pufo9PwMASGYVluBU|EQ z^k!Q`JAFQdkgf>{)aBnZo5f*sx)fsRC5Pn4#HtaMk1NJoM{_#vlb0@IitT z@3UhH4LwWHNBwUzMkhO__r|WSBoCnJPRUqB8-hp9gjIDkou{_4X1XMmHe-86rhP2+ zIM+y|y`S-V#m`U1{B8?D2-!ju6xbc_=l{goL~gqcc;`2bYxdUihhvdeS>(O(_(%5j z6^AUZ(EO#fPdtWXkw|Q=lt{J-@y)6D?I}v?XjsU^I#PXvP@uAe{M30ub}-Tfj&4I< zeH(ix$}=QOLba4Wg7hg(53KL+ilS|T+2ddTdc1U~sY3%LD7Y%Ler0tGELfo-?PC1& z=$Vd2zI}RP(gD`ac@ys>t8J;Ba#PWyWJBF7W%0(2^BvPXLK00m6Zy1SGO0c0ECcmn ztYW+}d3DCQ>d;UjdHUy$w@p&yE$I?OrBr4`=q%U}*as1lVOCQM73^w-W@fr=UXVham?VlW%_)KY_4pdED0D!-pK6Aw6*J! zKN{9*{=Q>#;C_Ma=~47a?)`bKiB)pB!a%sjPBS&xVh7CCd;6&R{3`ArZ(|ugxQKCU ze{D>m#Kf>4NkzGBZCmBg9g*0?pd3rhj5w3+{c__YF2V^@WY<9{iNY#|kF8H5Di%Iy z{JP5|P%wCuTsd8#SUL3JD(OZ^+BAh+Z95rFPRdK1&2RvREHekam7!hKT2O#i-YM42 zUgdMJf8$B6TCv^Q0d3f-yIXZdAUY1QK65=);%qSyF6f17X?Qd>H zS9V;>1L^mDN{=chQP|z*Nn*0|QC<1CiDu;l_N0 zYS}|_gtzsiZo1Ccgu2hnE*-*Ax3=Wvq2ox}bYwD?Ly_?kh$I;Ap)BW{vAVjXWVWfJ zBaLirZ5vi1XD^%u6(hs1fMQ3)!A?ci-tWYHfE3TZ==y<6Y|A)`zov1*s57`o-reQo z+ADHCol5TKpV)*OuB)BW9Dlc&bfjS)YIcwOKm%#z9hu5((ZZ1@V8wws^wp$tx~sB{ z@9fq74)Ma@1P1b!6{p~)%y|{_>WoV}FC)A1xJ#YKRqtg-ykZO z`!t*sI#9Q^k=H+tn`qdWJ+b?>F}$lu?6pc1)pn|Aseu92Lk>CtjQt>P<|CPj=_ zyy=Y5ToR%|FKWV@7LKiM$*`>vqiAo8xiW5$Kv#_O7{A;x+e6xu z?UvxMy<&(&6-t{qMw=W+8YO23(Hw4czKYJD8+^UNsLWW9Fl#A}zcDus%K&SRu2 z*}74E4dhFu*g>mOEYYX_DanqEy{ry zjg$u*#c>{ulb@kUmex@PMr6 zY<`_V=-Xq}pNslmijO{F_ zo;p2n5qa|XN?tKPQrhTKm(;OM7;K4IZhs|S0&`~EnI5qEO=Wk5O-0R+u|V*>t96oX zgU_oYeoBztP*N*VB+=;@;&65@rs`G>C~ zqsg)Yc2=TxQ+HP^8-dVlVBniub&>X=@h|qs9RP{jl zO|0{+T)5z-@naZr8|}%ahmwpJO-M((SfR9^EYOuZ_QIsX4cF9G-lP&?6C*sa!?Q`v zL~QP(@k1ig_@jxouLW(y%iD8fildD}#`2IAk2_8U$F@8IS*#z)sN+d`Ix(`n8dhAl zNkV}Ta#PB5~2 z+|vx3Jc-)hZI=+YqnnY7r>Tbwj*@g%w^k;9=PaJFylPsZR!>iB1|~mQZqS!EQ+loc zCH0y{SgXz*2T>@!KMvz)*~KnVJ}^xOTX64Bzr~d*04rM?ZlOYjj&SCmlFGw(?_R!v3d-o6CTsav76`KdMTtqr^!!smCWF;Z zkr6-FWZi4)gx?0|vmOaq_l_HEw0Hn;+AGbPZ3J-Z%k1!tAX=Qb3H72YAI|h##eduPgaYcVB4V?MCwNU~D>T`-^JM&wK+l`ao^FFg^5vV0 zqSwJtk{@j}0r>?SL`^tg?mTFyhARgGsouI(wp9%D@ZbVM(+)_1=6+&1P|7@tWStpq z)%)<2TcGN^iP-Adgbh@2S+|!sH*rmUm0;wv?E79p+e14WpkW2@X+3CfP;`t zPrcVLM3Uzfd}F9npYpyKwXePyD>RB-tA0 z_rlr6F7|ki!G5tPe9pHEzNjq@h_fIFDnN73A#I0_f8G_AjW1{{Jn1@cr~j#ZQtvGng58&f!n1)8^C zwii^IRkMLN1bV)xX3?D%x-cp#*@`%KZ*C~s+GeS7ML~BuoC5dVF*4*QN?CS>Av150q=iHuo1tcv z32$`3ZqrD)L~D3hBQ=+!#asn)uLss(br|m%*4YaGW&p&a1yq!oK>U#T2XekjcW0C? z_v2$_UF$4!nGOdF$MDpadWHCWxJ8ob6ADyOv2@7qFlyM}Hf>8|$QXr;zRE{P>>2gZ z6RH%8Eo#po;bin@{j6zE5wQ_2`$CluHaZS;O$dI^s7Z_IRu*gYX+cI0#7x}~(waFi zQRzoAZ@sYd^QW$Stg`S#JvBBMua7AZX&mYyWs%X3{95f}ZKHJRFUIT~p&?(aCS@=T zOGeHjM}CZjXeEALrK-1pk=ic*Iw`oqZC<)xw`%I#t(^-5}I0a7o`HWbk{u zip<2U;PA@VclggY52^alW=Vy3aN4@UeBbo5W5jhlXxpdYd1-n?gLIR2Bn4TMf;@RL1|-&5LQqauUH-tx=?@Xql%TH2>Xt$0 zhN*J9v}t-@_hobc8`;y3I=1)iOAIQQ7-Ft!&62B99I4f~1anY#s`m#kqJK)pG<+8X z@M(d5w(qn=Ro!&yT?=OPJFl9@O&KPm>-$~2Y;~_s)A2Dl9wWPAgWiIXqqB_=YAd}iBXla0^`wgl53tlrIW0h$tHOhQwG zrap9ukC(L5_+m17jK+fOe8%<+KN@;jg?wE?(!3*NzN<-8@Qry{M!z~$VX`7G<*~g_ zt;ouf2woW!XF)deeOo9=6t{euWYr4h-qLQdS~V?9@0@P7?6E0Bny!C&=#m>RF(Ye- z_0jaEWh2}I2Fjx|9a^D=m?8ursJ;l-FA$cZMNmSt&NU2=i3AK?RmST7oRQ zR81}(jq4a`lj=*yKCl{g$_UaEUN)R2At++x5#k|-+nPRg8#;js_XqKE8RPwvJo_s zM-n*U)hN$=4` zzH~<4Z^-AzyC2Owv=`(Kk_Yt*QlNeDi8Sk-2{zK6n6%O&IH5-<)`*(A^S=A=$6vuR zZgqyVZmjN$P=J(xho=2IN_f92 z$+J$Zou9UH!PJkz3A-qHEs2Vg9qUJoe{rtH%LvF#CX)9BcUn&-p4mPKPI5|Gp|iJi zh~(#gwvUx?=YLJWeedU~=2-jA!HVu-z|pJe$;)_1rr3IUt_XdWX?vA5IXe)xUK{BZimv`(j!D=3`~*ZBlurn_4^ zl9-jVf#LDt7>&})K|bV;mms?9$tMjcr=;Aoha!3dHZf?X1((go)Ir%&I(YJ&M_fM=UrzLn+c6MY zAT#lLMK$+nJEAFkjMUN@j7JI!A%Zo1%9oKOqV(-1&*js5y}CtJ>3)U~4PgLmwDYWO zLYY_@{8k51NtIEBQjTrGw<+;q9)J8Pb6T65!fWHDW;d3T=zLb}(M#*L$@=~WZww=4 z_tz*-_1}H`=@$Y?&kpV=liC0H?hH8WznEKdNF-Ls2;*!n=026voQA_`>Ai1La7VVE zbJuCwG2jWsmC6d+5DlM~+ew|W`zys;f^K$8VhzpGQu>Mdh$mo=L^>_tzLL_OXcRJW zp=*%ZW|LYKAW9fJQ~jhkr2!oMlN&Cd5BfOWQ5dQ_7;Vx z9VRNSE4u}^NjOY`Y(1!$rs)54iuxQSm^SN>^S%T5Ubs5q*D;kd2yifl4Gm6)ew08{ z9l+F0y_5Tx&{Sz(Z6znMkx(?*d#4+vGG%EuOG}J?cRSiQETq}Hyz}1k_3q2N0tfTE zP1f^ai@f~-S1K;O@l`%o#yLIVZsXDWYGqy3mbtwy4;ysDqZz)GOa?t@MNvdZ=ccsA z0nSM;4zP{J=+mgNTZ50={@8tl{6L}RfFMC85XZd+<%mA_`j&r-}9sXkNNd+6$>^w56P*~=~E zb{AIF@(!3j-Oe@g-3G0jtHBRHJnc&WHggux5bW1VC9+Ep8oW21!a|0?Z!%D>M%QE{ z+9iR?d*QJ*;?zJMSx9AqbhmJ@U|ouN>Ev5^YSD04_~Z;VG>y0D!-~l0nbGXfY9ZyJ zpQk_aguXn7eX6A!I-(Q?UE`E5 z$>Ut23r_p4F=BJNJy_$!$PJa2i%qupmUv;4 z>m3v1(2%_xp=F54Etv*BlRY=O<4g=mjF~oubNyXQ%g~uoK7}eCmFdr-c{aHmgBK;8 zcC`1077ayWt1h7~%ahB0X}O@qFaII(crRJN>j~#Xr$p$bJ6Qz>g;KoKF~y_xcY*Ow zP_$H%UfXRi?*<`8KUpU8{z`$_&k@7dWsA|5$Ij$nI)8*mP($d2krUMW<@}M-2iwIm z0>JMIy@4?*%u8adG5Lb-*~R|r22DT+TMJqjeMV*$eog!bI_Epc1 zm<954&WJa2YnE^pnmx5Tb^HE2a7=DxsXT=mxKf%fheLu*_TD}fRVqaAjoHJa9j1&t zCpe!h!n7A-UBum708> zQXhCVBt^0OMYQ;AkL5JRs68WoidtH_(I#Cj%HCH! z%}H!itVq!dvn#W_3s6(6;h|fvsInzPkx@ZvuASl|iOv~{5+;XyT31S^0hHN}S2PO47-Z;y*_KDRV5UD z)#C`7o#>YJH>K|qw2*M{-rgWy*dNoEU0QO#so>O`&d47@G$`w1rEnzKqKdvEyHC#F&a0S(f3b-|Q>aiZ+T3e3=JY~#;%Q6KL% z%}!C%-WV!m4(-<>>`gz_(Rtv}i^Aq|!SpmKv~hboAY=y0v;_?}^?*oPHrjb(;~A67H&X5OGT)!J>pJRoB{7K-wVsy}!!ZNVX!xfZZV`sI z?iy@#e%{A8|4MKdk+7jRlP-o9X$hXm3rXys_Lr_L4BQfVnIqf|@F3|Gy2&ga^o#u_lZ2b==MmQ(N8JaZ(Jt2IW4%X_t=SB(Ap8yA^NDD2#I#Rv=9Ya0>)^>29!% z3I_*jS?%kv0ngPN{HDi;B2!;>9sslcs90MwlY;>M$_NlI`uwa+-q~X&dTOvR`@SCW zCMWS$_iR5(MFHadT^_xQl6K1}9m$ZW9==R3y5WB*aZHbpm~(XsO|jg~h}MscQ{XM4pl~bMB4FofHVHd}x;kw9210YDX(8(Aej?YMp?%>^V{lBA zas3gql)@3dVtMcP>501oX&t1ql||i*2lKySL5#Wgidz|sgT_5hLhfNQ=Dru zn@`)lH|Hrn$=I_o9sl{$1Ao`!%PASYm0eVU*sDg$cZRNCVZG+%3;i&JwONH6lg0_y z%5}o3r614m?ckw^GKLrcF3FL9iG%;(EHv^fph~6oT6^3-a@Di~invd1Cv4*HRErNT z2Rnq-K6>d>fZdyUe{(VQfFD^ebL3OWHBO>^GQQbc%gjD_RP%scZxmgr2$!DvPEabe zQ^daUU8bE|23|c(x!I3TR8_*S(|-CBFVA?F)-CdEk5Om=V0)QS)uDyh_phMrDw50G zWwnKqnCn}aHSr0p;yQ5RA#;1N{2)NC=4)@uGs_LCC+xxx0kzvyyu0tj$8%GZ=T@JB z?yXqbhL_2h0`%pArVKNG;cVJTf$7}J?-u4gc0{H9Rx z)C0w;+?_zw!Gb!vE&UB8V-F*7l^WW5EmUeSH8Aq?^rI$B$`$>#~_7dc|An-m9^1>I(pjN>j3r)cJ1 z+VoPQpK@nc$zwsAGfd@XhzC#foRqG&xO$9Hl0B_D)EG4U|M+_AsH*xed{9zCxaX2I+1P=}U77=~n6PknS!erMnyHu1mul)c5C}di@n$j>>a?9L$Ud`?q-dAC6;pYbdOQ^#) z+Zh=^gVu_H{RchrZf=g`UC6itLvbiomyhN3%N~($_BQ34Sn?ETZZ(9^^$o!(xYBCzKBdTE$;R?+BKE_*jR3){xJ>F{8)Rs<~7+Tpv)Vq?ll8-%fP27#SchvfoFNq zDyVq}2h8d)M6z!(6S#t_ZO!Br1TH6gQtxJf-MQG{#CYeoLLwE%ZFlAX?v4!Zi4QJ~ zui|RO%zR=*`z_VjnrG0zmsKC@din-0lQ~@nrA!-Gs?usQYa|4p&AqRmT-9fR1H9@Y z8;BD;jiuDTaY6vMhntz8*F$C4y80RU4cf_~d5X=OJe~JE`k&WFydl;2Lf&2`!MBs& zRSD3L7|rDK<&wr{ty&jsn>jBAwg;Te3S124;#9~t0em!=Y+ZIUiG)%I4EdGzz9(=2 z%j`{(vw9zk6WUk2?+zn97O7qc0x%1ZRw)4sx?6vMl-?zMc?;XsijR-FzWZhm;WHTK zCVn;lL`!yq*LD&pd2Qg*Zr5_!9o`J74)i3)~%$3^2h-V6gB@2FBs9eEurSf z|1-4{AO%JjeiB>~e`1y88}t%kW^`^!TeECt?2tQfx)~cl=k@)JZ;8`?EgF)}AJ5Ll zh_)HJX29P?uRdHgM`3N+&A``1pE~_4n3Z+sYdq~n8BNL4q24UAwgVR(sL_l}{FNbe z2m?ylE4V*XHPX?)|D1E#+)u@JD~!IZFB*W`l8vctIg<^{%~!HFX)4Qk8d2@PAMYt$ zYd}rK=8XW&!Y&cAtg=nU$s|mIsY;}%o%+W;fXjPG149L|aGRn( z1cxCdumwVqRW_oI80)dU2~|GgwZ%?QyPN=Y&-Xx|XmkJ8`B*k&*}B)&(fW}Ytrj$2 zY#~P>o)K%NJs;hJ2QpL z{n&?jC<;;?-va`!WJ#j?GxS-N{l^fBsJ^NJi2nDld~ECm+gpQu2UNX!(#Y0kHvpOv zl&!BJiDVWBZo0a@*B<82_o)BZvE>`k?U*!i1 z0^*2$`UfpSjrQt7Bh^g)rQMg(1e_|1>Au8>kC(AELcoBx)#5mG4R&W}oRM!kyx>Y- zrZ~M-VO0WtfGm!JG!wlkvUnK!)IOi-lT1tb%h-q26KA|&Y&XxIuiV-`qFsx8z< zszfj1bw(!qUbMC@6HP8CJwGh3<=CshXBhJq7_4bXe*bG!VM9_t34Hfi_!!|{@anfl zV>2Vxav?@``PVV6BF2YZ%243O?EJG}ciz`u92^?0KZAi*;BFzZpFaOR_`hv1z#kvt zUIS8z+nQ|}d9Gg#k|9i@b`x)b6=2vU_oY`QedMY^VW%wJ-O0+>>gyz>;mdQIoozU2qVj_OPAWVG@zvV{Zy)slsx3m`xL zWyTz%ulZa)MwW4@fpY4X{@i#Bs-(~Y1_H*Y_uvcjI*a=T3-F&)gWUthPvuv)$$z!3 zuN{DSaR{>?6#8pczl`l+-PF7J`KKWKh1p0zAZ~5lE-;q#qLn7zJyQl1Hg?>kv7dUj|vHsu$#-hm%#(nu&op)4~xn4=Sn&>{7gCL<0Yw#>{+D` z({1cf9)}5T6^N+VncVN|y$o*%!Q=JS15C{qC6UjU^%Z^qknN>`3Hv{@0lIS%W$!es z9R$B}3vJsz3LBCEK*tJ5ghBBiJy&WEl%7L`s6Q9}+4%TjsZM{o3RJ-Oyd~N1{t#Av zr~o7Zpx5g+eq2aitlV3}gP%;IhspppI}#ln8DRxnXCJsuGZoQZ05ISHu2YnHjxedQ zYA~ap63)~_JCQFx(0a8P1N0Qkii62&D~MO4gU`#l-&ONXH-TZSx{giU_NQi>c%8C( z*$u=|&mH8B4}a=YhxD`PSyV3rmREH(@t$vD;_*qBIYAlFt!X7qCb2BBy@m3qFZr;! zaXNKq_WtnPvCwasvDiEnR-1x_qWUc9zL_%;Eo(}iooVFP?~(+ZAp1I1 zTy#qjU++sbjZFZ(4+$t9>8F}q8A~m@tvoDWo!z4NB)}M?$Br{Td7GZMe7vehLd0@l~`Y`bt(+Sqk$t4h(z>^y8~T8Z#xYf??$zNf)}rB9~ScAKT% zP70`|u3N*c?MdL~o8=|GBd*JCBWi9{VKijq&dKApPG;*F^0#mMjeh3m_@a;Ya)86W z1Ds#K0K0flBORmNa?5LOZ~pi3Z_WDcqsX8zE1>)~2jY!>UY|OcLoP2Ru80LpZ4R;} z!sk2a?-Hv%gkri~zTNtA5gJ3C|+)zjZdiLoQt_3Ol;#4 zrJy=WghaB;@bX8X33TH3x@H+eOl(D%b%Gd6OCzx5HTZJd&V4D@W_KnJ=0&}lf7)lS^lj`^HK6R5{z=0C4IIUs<^)|n|opK+1D`#qt^ z3Yuk+l{cz)q0L-493N%HB!znZ*rP&YkEWRr;lm*o${3>9ZZKe$SAXAX37s1bimj@V zRc`3f_!hZt{n@w83)PHtO z%>eAWZD1lP4INKffffyX7>)YLxz2tNP_2f4mX7?bSi@nMOBR# zqp2u`G0Ip=g*BjmUn7h63ZHjUMRgPv@ry4U!l$_we1CYk+ z6#Jb~GM&a%%yV2O6<8SfSHhcb)xJes{r(kW8JR!TW(l${f+pROj!4+aejnuNvT3Z{kV85yO{QmB z&G_jkKM-aeSsj_hco9ik}lxSvpA_9oIL!r_OitjPxWV^d8sz7 zW<_S_Css5xw4_#A@3ZX@H054>8CeEThr{yrY|TpJ_d(TYz!Ubvl2cG9*Spv(HaW`< z#|nzUA1u|Q9UV;z+1~+T-D{5n&D3{b?ae|f{RCe(q1)U2@~=!_k5}HBK6X}8dADUzQb`gmVdrffd=@}p$X9r93l^rpOc&4RD(^z5j=UEx}0Jpw##l# zkpezh=94}z5{xryXpJ*ueJF*SjO{J3S`|2fZTw-5y3uJ{^70MmXsz`Or34luUV5?Q>%OjeWL?89CX0*fwSD=UH|8b~#}wZAv^!$DRP z{V8t0zAbE_+e>^e+@30vV=}=_2eu4+{c3tU&8MyePCfg*{ezC9&(_y8T$!XNag{>6dhp@1;H6 zTUd11qZCpz5@`>r4tFktk?1<+%xzvbm`>&+@#GO(#amq4JHJtLWn$nTUcTz+J)9?V z$IMm-p6*8IF$72~@7@swNkKytg|BMqs)nP9glsPloE%(&c*Ml&-90^XjB+FkH7m0j zSjoNXO|e!a=c_%rfh75Pl|riK*eE`=Gr6wHeCTca)Q4gh8!yf3{AHMwPJ{NK28;@e z5#kcvO7f_1K+@b3jf}TfYR80%fcG*moEr6|5GJPa5PB&u9vrB6earN(i&Cz7z=GgF zr_OfDSZR^ZW_X3+7Exc7I^f*GH93_(Vi8oJE;kaA=%}W!fQ_`{bJ-VJ=IK3ZT%iV8 zuPfDIbs2ok55DCXqcVbIyYo#cL9z=&`AoLtTIY5UtMII6dJc};xku=tsG%@fQiP*z zmnwXoyse~Sf1~HUE1A-7_l`W$YbK{mN7t#>7l^SXZhh>Rr$FJ(SYNz?bXDFM|K`^o=#GtuI z?O$ij21}uTZld7erW9k!6<5ghc-o*0j(&?h>Z#Tq*jhi*msceLFM7 zL+ZOk0qgi_3?Cn#`x;9OBpjxa{<9EkNEad&<}B_@@|SRMWIA=9&Zx7m9ddCY_l*$v zvIY_RZSXtJrPsVZXQ9~RF(1JmSMl5doQD%kdMu_pqda2SIXTLO!cZYT5-IPjGqOVH#bDZbv7DSS{M!*?reKTyEdNmO*?kTbUvGI61!QX`3dP{g@BNL#)hKPbNU99Gbv&BW`g7bDoJ z!Dk=M6oHwlPp_@U!@?r(nt25LRi)NU?PbEg&bgVrV#h1B-SlpluE1;U4k_&yHUgc7932ONQ8*Zmb+^6w^LYz!Mb7z|}=1cp_ubiEnIx9DN*LLweEqUQUdTBRc z_o^oamy9LsaQITAgjQ&$*Nr`j8Z zP9@JVG|DN*DfP)xvx}L>GWohE7JclJ(;?AvW<+p8kjTKkz}L33`}gEOhY^Mz78BMG zc6D_P=J^o&C(koTbR<=cU9z4EpIv=!Du`-0LOg9yOG!i8nI6<{0pD>Yb6R0;S14&< z8U~!4xgRe(RN--dnvXSYd}Ge6eW}*}OS~P%n0HFA2EQ&-V{Yz5P9qWMIbO`BCfb*dg?ZB@d zLt(6$s-8Mj60UcFtdEk3RXB9QOJw_JT{=x}Z&<9ddyXkP77vlj%vjgU=zAr88!_=vPe{vUFqG*pJhz`#IH+RkQ$S<1GwiU8UTVknJ1N$#2* zTj`)lX+IA8n5U24ARk2v5?3)tN_JDGqw{CH&E{DN0JLlGBi)VHyfVkvbKx>mqmdb{ zJjTDJK?jq+HoNd>v^;{=pr7x5rd$V4qg+4k!~S$}a8kATcS)W?IsC)=VBL3jx-dMC zTEsu3qW4;}Mz79CPJ2mw`m#vC7Z~{p8ApyY_Qd2x^Rh8PKoWlLhJ0aRp^$bKfdN1C zG_^ej^C?>TI-$O%=f~h=<|)swdKt4!UDw#s@TcY1r^L-z`Xjk^MWX@u-(#E`06l7$vp*Ng0dAhHb8knm#&U;?A8<-flYJm+BI6lfL#3Y=Ut=MovsG&K(^+PbdqRK{zDo4-WH|d+qraS^-$R>R-HaW7hW;_`=)BV6^d`{> zJ`%``>Fk~zt=?L{Mc;>)`SsMxI=@^yoN6AY$?y>A<0{S&d5Z8k4o^B1O*#sBI-!K@>fd(^O$W5$Qjv-Sz6H~L368iEP= zR#c{s`2}?=agMDR__w-`=|&)n>$-BY@i#@)@T`?OjzkPrvfvfDtLclcq0H@6hji6> zB?-6IhRXvY?%0**i$hPL5Ij!1&tYd|*%2Z6r7H~>fk-%P%!UFv8$Q-si-E{RgBzBT zDO|R%9A>L6Wr%`G=`(wo7rHT-qU!e6hj1585%?1ap%S8)V*b=z9(KPF>5f)+xqu_v zj)lu%LPisc=O(j&ipBf@CxX~%&d{p~`Zg_z=(NS#!QVvg@I>TsR&L8PW?@z9yedEW zy`ydsMZ(wC4St)9lmX8*wMPD;!A)ApB|9Mz!^lu=SG$o1Smuv7GLsL36yAQv%u>Id znCUlrOS_k9AI{FjEaDW z8qbx?WgYZOHJ|chG&Jw(2mBrE(IJl|dzL?N;{{@&m@jk_udY?xbKI54bu7bzt`@Qo zN?1i?*XDbm+*GC0zP;VGI2Lc3MsS}r`)s5AKPE8 z-}~aFu;_-)P0A4o-2^UUY<1Lwp2h^S>Oye(l8IeDk&rv4zP^5uZw8MMbbKo_pD`MA z(}~$xu1rW+*n4!l=}&Vk#$5={jlf$5P~=`bwQShHj7jhMb{zfY=-K9g$*(FiZT3N7 z4R8{J5EL9}fIUy*UlYfY0x&A+KT+IzUxBKV#{V4btgmk?;*LIz9jV2@EX+33F-d61 z3n8^Wz|qS;pRI0%X+mknA>zE2hj2k#)us8auHxcGg}kylY5GK}KdDpzD{9PScFcnI z{j*719Qu4C5^;nyztcD9rq6I@c$gJf&ky%B+lU3eyBL!MZyjhgG&X)072%$kpN76I zNn&Tcx;sYcp+nune(6#)7i+%74wHtz^YKV*9%v!{@)+o_H-%vl*|Go2Lw;J;4H z3T~(+&lN4x{l}R2?ZB8A^ux_Eq?HIPt{*byuI!u9HS6ezmRD zbF5k_n&$xto7Oi1pMAYQj=sTpKOXWWdIRmb`^eN&*YP>7<^jjc9T{CCr& zP^t*xl2CNCnJJ&6OrA4#M>@i6if_94Hl68i^@s4CpL2HThw-{NrcFuHb-1Gwj}3VE zZ4XO^sr5cPpYceFQXPXpg!P?|>`6^Z8Z>A30=x8x4^=&mg*#uaJU= z`4y6@vOuYa{qJ=Nw3)?0@j)^j<^YH&_J2HC>%7iYr71myd5K0Y7W4{{dZEpR;Pz_2 z0DM1tx*;9+HtwwgaNkitwRcoMkom9Jf5G-EVD{V4@Y|DEhp3Qe9`m8Z_Mu#VPoV1U z{*%-&S)zeEUqITSBNmWK4>K|8K5cV8DYQ$24NtC}G0t5EOA0=6u~3xRK8?2oDjIXZ zfu=^sSrBKRdobtGr^^|Go%y`*>FahH1yZyASVZbOrzdaF@wEJ%+sRnY$?2(bHyzSW zf2E4B#&DRx|0?<`j6y+ZX?Vkn-bzsqLMVZEC$?fGIAp2OdT`<}v)n(vI14KNc?d%> zz(Z~5GYfbf@#px4Cysmv?xe`cJD7h&oy?svL$_&u2j8!UhK9V~&FUY{@-0JBe?tY8 zf|==ChWa>=z_gYFk5bc9Fp?U2d$~`Oc#uM;TCr1*2vY?HgB>U-#fgG}zKXUCdo=QA z_wfHtP6iYGvs)wvtDZP@6Z&{Dc9?+p2f`!VN~lqU?RA4Oh=O!tqryK3>LLMnn++UD zxk)0{eyj$WhK6i@K;Q>)=*qE5ACLGg^`K)-*H*T#En--W2sGsRUwiB;7pOA=dI2$o zFEon84BAz&No;203T`K>B3_W)g83B!&X2$nnu6L8nRzC?lq{6qJ9-G^e_29FRM<4@ z*oQeH{83bT24VA843rvj?;}%sId!@Pq!F{`KCH2R8Rjv8YQo3LLAp z6l(GOh?f=u6O0cnFp@-{LAttqraYtbd~F9bD7UGhoS&UOxVWO})2@nKD!QjUz`yKa%SPtbedlqWt1^t1pK{(K9Ea2GYm5YkRpom$T|JqXBcx{6`hOdh%X z$+pw3TZGb+APf9Boqgn{^{)M+XE1crM@y?j*iVwce{I@XX>s>weu>r-b+~Y;Fj?y9 z`ihW4T2Bh#L229mA6^uOKszJ~90+;pf%x-*K!pE%Ij9n?$~7_g!w=Rr$|+Gk^&Wp^ zc@$^%eRrfC^R*2_%nDh+7V2!fdr$~YMueVLyTkFMGXw?Rsuu;Q18tvnodh>8 z;28$iKx}DM{vV^W!oD)gV!vB_oqQns{FPiZfDZ`5f&fT?aBWQ0f~G&(Op{($9CBxp zT-;^>B$uc}tS`P(h?=s(EA2i)9-#gF$m8o@F(+qdDpdN)uDX*Xc%`3|(BsQBv-@Xb)rO-B zYz8*EgAvj2)J%>6xAcE&^Uc@h`BsJ8&nSUb=R1na)pF}Is(<@~eyB#>%#n|4zEbRE z0PIUyv~HvPm;yPO$pzLNDU-`0wX?=d$IXgQH;y(!NINbq9k;q0WZ9?xze`)uJO?12GNz~s8&{|EGF z%}X>?xi;|2sYd2=OlU_o9?s?43P3D|`d61@>q47StS)%3OL-|XJk^-cY?-24p+umT z(lrv>8p)xo5qH+s)@YSW5^+zj5wS+A)acc|yd-(|SplFJZ0u%h5aEz^u!=mtds?f+s+(J;bVb_C#7|!DU{@QAO zfXp+RJF?lufk&~RG_-?mx;vx+kf(C^?Je_@nA<5~QRWQJXpWc4`udo|A5`zenFK#l z?V7s~eK-9hr_C7?1xN!qr3??wX3uC0Zo|WQZxxtFVY)7PT(UT+AIK}qmW#}d=bhf) zI9b)HZV$f}G!Dosu&4EuOg@Zb!&BtxTs@@@xgP3BU+xoEbR(z!;5`U=c1wF zm?eKYWJsEz!Ikq&gSq_E`ThkPe~JV3P&J-wjeFg}8gE&uo?Jz8(E8M$ba^aP81|^Yk|d?P2a(1LR*ymIqMSgjlLQl;71!S5OZpBF&>j zmv7a+5)^Gk0V=zkJTg^~~I2otA7VB3=nx`AR6BWiUzV3N*sSL|&!S;L5`5fwur_12b&eWa(&@7eB3KN%EpMekI6aoxAzfrMwTX!ydEjM$!0Dpua&3Xpl zYT!&drwN;-G&Ns~-{5`?WYYG7hO0QOU%7yvsswum1O)VLcavqUS18Hn_@*P&h2t@2 z%cpSlB`}i!>vb`iFEeOJj?mf!-N37tUysqed?KEpM7#uP)rzq7TipDB8HW)NrVdRf z=P*J-|9<%UdwIWZ#(7;ml=(4}KGV~~Jxln<=c0#)*#>0_aVZIzjCBiU?b`<`Z-{a6 zbgAC$@dnA(P-n#MMC~1!Hzb?s33z)HFj3$fX-7em5*H7sp%BL>8xAqwy_7vTM_d73 z1J-$!5pXQ@OvkqAI&KX|67d<^g?&t~nA~S4C4G^=tUo!-ZPW9L!*WzOZpP=Hjfrk? zNx4B9V`@3$;N~`4=bJ=Fv_YGMD;Qv8A~V^{YUb`9Zm*jApTqwT=3jmKeK{Ik*x|Bb!R$>ooInDS^ZpVd2)do+aPk(cYIt)5re z9+!LnZ+oza2)8?3F*&}3FM?c|942$F9Un8VX#CF*>w|OE%9X|v2@iJ-?>GD1u2=m` zGc=!VVJs0w*{46r&)n6tv$F#WFflWVE8AH5K7_w-vFxB4g(mOr3+XePJ>6C(cPEPW ze3IDByDs-6O~*B_CtgjNQuWV&s7I?ph%9J7}yH z-|PQxBd||1c8`;(Uf+-rLwS3zZ`1tw5qxuB!|+&X+(RJD!1C>C*0q;?WW5oUJOKQwA(t{IK}97QZ6h?O z=eHZ%!QxkVGb3j{KDawL=WnoW?5h<|wbF2lyuI7Ko~YrOZq@mEXAbYOm6e&F_D$*LW{?V@moFCt62;eEgUM;`o4Z>YC0a=Q)Jq%}Bt4C~_0N2L>~)wBzqT zK8gt*Zyx!5v9iX%z`?H;oI+Zi7*3mmRepa)uHdq zdE)yHlBpJgc@35F<*FD4s7_KSHAL*!uRT%y=4b3N zLK>pDAM1pemfGny&LDE3Q%@-YUP)8$usy{3h+pXl(4cm%$v0=J#?2DEEP}54dfK&4 zJe`Zot1(4#)mfqRfnP=R=cRGRFBJ<#<2uUXw<2hmrxZy00iY7XK}sAcgD;`fnFNE3T2oRyV-x zWnEV#W7$S$vR7Cpzr=^633W+-=8T?HB5Sh8DI58L>5kuZ;22QxOt#FdC-v5e(wO>H zS^#FFV93p8tFL~gmpi}vnYbW_`GIE5!?lS{V9{QS%#3h>Z`oU~H#Gm68x1njs*&!Q zRtcR&JO1iXJ+n1@0NwgJVN|F>=}nH<=Ek%p_R!;a6L7#lJ?^TlWoY8AlOAdmI z1}&H+UDE_VuN7~1VT{~OTKNk)FYGw8{yONs$^i)M0i+2u%n&kkjw-C5`t4tyG|q!e zy_N^i?xPS1e8vS2jt~7aJR&5?;%t?uT^R9VEaX#^!*;YL%!Rq0BF_&eOm3~J#t$(t^Om)zyf;|&xT@1Oe5Gey2v>#je%>qR}a7Xzh1(|*YGg%E~+ zpD5VKi57IE)C~gzY{hFFzW*CrAshoP!yjM(snR;WdXAP^C@3sgkhK|edW!=_sRino zD5k-~Q{D=8$nC<%nyg|A6O+DWp8UX7@+!PEMgqMM<`^!!!?Y-0BV&G;U|)`2hooxB{bf#(JFb5nKS`!p1BV%404QY+&@fD!yX%n6k~Y&%If? zWqiQpQy?CHgUNYR;PToR4LN~x#f==d%h_hOXwHrJ@jcER;AD%2xIf)hxV;S8+#}m$ z+kULzDOfIz#B*Uy`^J}1Cp=SQHjqG3nCcYInd56~*PQhDFB|yA zV2ln4&II%@0Ha(}V3bR_`UVyl!;8Q{C>Ypu*(%K-#$ONID;l;n5q=0qa#{4g8JugR z_Otq0s#z@kWl)ReFx@1km!|i9hJ8#dHTr12HxO&+j~9^5ePYHH7+uW zEq+St>>9GyhpMVK0}?4f%poCy?!75R%kF7Bd%wGv+PA!0(r-tR%Ai_VUA@_G7>q?^ zpzOY{az{!r5ge-|H}Ray(5bi>8B$=(4KHyzjU-d{kTbxVxj*(cC~Ng2zYR^k*oXHD z*Tt{uBHCID@?VZV)k>I^gOo1RQ?Rg%u3MX;!P8|fbiN&Z`5#JGfj+Gs;WT1HUXsB} zH3EjcJls&gc=I7!%7OE~($r}GpnDO&+Sp-)weKKBA+8pK>V-I?p2jbIY;+VNUYgtc zihYg2#kTkK5#cF_1Z~$$w!qV}k4V5brbbcF3witHseB-3T!0PUuI+0&FJH<8G@fF5=Ka`$E_9- z!G+{zm-68-z)Dkg7s^tyME@?%utZ}z5e=H`vW2Z))J9?h)PqUAa;5W#bH=58XRZ&I z;qEu8voSzBumQld#l^)*v|)I5Amu@U6#iqT%0x*k51ix=21Q-t^g4I|mrM=v6@_Xw z`Cg6S?kyH%gEkjV?pfwE6||$$il|cjC6Y-zAv6V-igtIMWB*YQ{j2kGy+R7*K9rF6 z=_|nff5w}%xXB7$KF!+d!@RZT3G*9a=^^Pr== z|4`-eO7>}yyqrdc(*gVo?+eB7kFIIZMMkj&1`ZBY0rtB0Er<7X>T*fra+@bjyVb?@ z&4l=&>6tve_2~9ctiagzN~1*1-fS5H3QF9F&twHzzCyUb=mNv`fjtW_L)FD@`qT6S z{x&QuYyfGb<}%OX>wL=&5BNX=d8U$ZhVDCT*`t@T9Kccr;lnL!MPPPsug z=G!gisD6^zF9x!}s*IUpm!FNO7p8%~YY=rm)#O_h1)Xn_26EiQOWj3cd?)7y3n$d; zX>}7`BHsZAeCZ_PGLs`H0QXz^i!-Q4lwv!zOMYoB`pY!<3=f^{{O(aemE}w)qFP{rvXQ=^Md3|N7 zW&TDbo8K>rz9H(BMg=JT`WA^P>IYL_W_+IOQ!dKG$CSBFcCE)>p1xD-;J) z$f@m~0wO;CbKzexSm(l-O;FJv3Qcj`HA(-B@DW4KiMrmQB~zoOV{_KnOm)dOtvo#- zH;=$>TnsgsNq*XlsUD*Lm^wqN3x7yI70koI@!e(r7q}+<9k!xAf6NlFa}>7Zxj|fV z_{j@s@fO0^i2sFY1q?t}jBqjmVTy_y&h)1qt3V^cUG&xEDFJ^v%$)h{=3c-9wi)wd zEzSlP!=$88+{+N&H3dWIsQ1E)_r-jb+(!c8??yy9tcj7*u(_2Te_vlBH{70Z+4469 z>nIYh>X`<}EAcrZ;+>W3u8apG!M3FP=|qZ!^7Zvv-I;hKLFCZR2S|Z#kf+88LL;Wc>ccAQ zu{m0&E8#W9Fn)fbu~Y5F7NyHus#m`yLSk&3B8b`=1xklaP3owE(P44e$c81GW>klY zl+_R$A{QAZ^!`@)?vC?*zLQUrqzZ5Uvup1!UOc6+?f&S%eRVSVWDcgvN9<8O<0O2_ ze*j%G*q8cFmm<{%z~-q9-MLWOP~fGCT}%BeT=5lFp^-SzCIPc7dYtr2jE77OF%EhI ztQfup2q{ON1CZN?t^KRN_^P6_s0ib++P!mm;ji8UG&xnu7NGCM=Z~vZo%APj~!Q6G{hi_pr#80KWB zrp~lZpFr513Xhj(Q2<9{4QGCEQy8qbDA(_J+6cR@x+%cL8tv9tT3S*e)v7X;TvK`z zTnl?qxI?QYHbD{Cyv#$G7ZCnUGeVoeg&InV%lPIu^%Gx0$(DcEYyc!Rzn&*NI zje9kL1AEavOwv2@vfgMU=?l+&*mhrZpg^1GoAM91+wc8>c#WsAKkJc@TWP`!W=gMV zanJ@KKwGKaWl9aj@95T&t**gOGVY*z>->~K+KJDUCioZP!oaSz^n2l%S6;VgjU{L{ z`|*h8b)6=)8;@ompXi+E zw|JjR-mx&Y!_92+J8TZ#I+J;^ z5p`)R;zyYSvcqkU#NfRR+!4QfNGd+eiCT)jrNINm?#6}ufW!HiK%*puwyRX|9?C{n zwy9pXZ?17@R8&tr0j|jph=IfYDfo9Ey6{ z@haDCpey(-8$B2Yo;@EYZZf?$LN|%%0l^HRbjlNzk`&ne=`U}px4IrDq?BDjXmn*r z1o+^I^{(3UYoi72T=|V~lL;RYcmtnZGYC^{ZYJ>~1m*n}T}X%A982LGO_hsFF&)h5 z{*N@3iZbOIhJcgSqhlfa)j?LTr8YFlR=j;qq0^{5cW`vBpBd=`~p_twW52tmUwWgdJRXWZJcxT0fdaXJuj8|~! z4h($kHRf&9v#7(i27_-+JdExt+ec{&d6Q#{{XDaxPacko^DNu9e`EMVHzg`A>RKx0 zBeg6Fj5Uks@PqM#9+3-Hhc|+ER&rq!bOo3jB_t)*2D&HgA=5bb>|m7l@I9vew0at2 z+}|~ON|U0?)rUpa2;Il>)Y&N&(_d9{m5b+nrZT%1(*})s6Ogs}mW7HP;E`qe%(Wo1 z-Q;x^3Dv)UG)4m`kg<@ZfilWWHYj#j&>DUkNQy!usSH^k=so_|J7T zt9{V7pNZOye;q|8PJS0E!lBCve7Ak2w!`N`ZhrMTN{|H1K!S%qgacn6O_3bdiwv=i z(6IaI@DXy$gWpYnb}UjI`j9(%cUSTn`Fgo2h2K|gLLBAi7S^3?7I?FR zZoXGS-NUf{7Cld2yskbUKgQ4dW?BA~?IT^=&2Qwx>!cKo%%^D8T!WuNV}egc&{2Ai zXnZ}x(O6OgzYL_wo+b}aXuq+SAKcBAlvh~J02xdTQAcV-;>`5d<_39q`(mcc*{My= zwpI03`Eq;Y&kXJ#`}KCO01-nXZgw5|;>h4!VQto_R>yA%ik_Ii-;SHYp*MzS)9JIOp%c_RVgLieZuEw-D|_i<#Y zl$bbJKw>tzQ!?SW@_{~`n1>OH9S($oXU@!fh&o1~nLQU?7VL-dyy@e64vgo^s^bCS zh=mC|=6}VV3`z=jbi)MevOFg{+u`J(y-@I8_0^|&t#};_MpmeY-?hlJkL|cS>h)A@ zwpZ?iPGcdGe)^GLDa6d_1jDJ>egpbe|;D@(`~ntCrd* z5SrfD7Ev{=Ys#0ubtVg9P6^F>pvjyFj@+2V;l}Ec5417a%F_Sd@8Mb^>4t0EfZok{ zc$MRm4ZLA~qk4X*vf^0taD$wnRlGg^OftA(?W?BjN4?ALY$M7xHI}FIF^9o0JMxe! zq4%($ukM1IF%7}PAFD1h$^?IpUuN03&8<&{VpM$bEwfIZ3m2Z@C_+#F6!t-G-j2cjKHc1AWr%FViykHDKK*tE99>rwQ0iBzW;itB31g#*+ zdd{>Hp-;S38fD>yJ|mLQE+WEkP)khf*;xOp9``tE z;%YkQj&`{mPQM+oH-WJ!^L^I%iOeSBfaks44@#}@#Sc&dl{f3iJEHcu_`B=WeudUd zdlli1Y_`9aDnM7%A>X({5qI#mpQ2iz-qlprWbneSlaBl3mrH!-XT9v>v^gkpe_j2t z%oysSSI}g%Rss3YEz-Bl)2-NzjTLGs(Rm7C=hWoJp|^bJ@j=M{4oJoVp-U%8m0R$#(05!PToGcOdar(gXq6s+Dk%5z0C~w=YLpG6ZIew z(oJqx(^1ta89Ty~QnLP_;SYVA46`r>S@~1cq)xj}Po%sQMwH-e8LrocegV z!m0)bisV_UQX#r$GyRx)BUPH}e`>u&k2%U|3^K;wfx!cZTM;CDXUZgKF1v-jF!S^l z+s3D0sU0x%8mmzyq}CCI^pJtj0h`F5cU>qqtUT+(84zM?RmXes)q=#hJzZYQ72!>9X8Sy)h+U&30s8qTN$VhU5W zeIC1^Q^I()i>{A%^?T4wmHS1&m7KS&qYjdHhQ4A9 zSp1qldH*q!9cJlbhF(fL35ZmBm~GI%$1yAbjzv|texg*S{=f135#q&@Ll}QZmB9w8 zL%>BY?1eSjk>Np6W1)I(2?L7pem;F>yZ0UZa%q3I_z^S@mr3b#Z8dj!=Hsk>!{e$# zYSTO!o+5?iYVWl{4kU5Trm)T@Ya~TDVvgH^^|^?F??>35GJ8�IVte$`Ui?M~R~F zOf2CXha>Krms4NB-B9TQTi%fdXh-4z=3mrn!b^Gp-i06W-LEV+V4%+DQPjV(H8*2I zkf0<|WD@GQ*)TiRXKK}MwC=rJ(i?F0IRJDv*NU@EBY7A;#Fk^oPbT06mxlQ(#}Si% z{D_EWGNWd|kWKA%3sL*RsV8~QeZ`%7aS~g}?*@UDxaA0Jcqa-b0F_^7 zAIzw$z+&OG)_8i|HcQx|h_oqsFX*(vhI?=gCxmtjkJ57?O8o>%T(o+T99vF?_8Mj9 zgP3`2_%~v|q$-hEevItOzA^~tO8BXV=nJ1JS8AI#hR`PidOMzw!HXA9ug3Af(6?i< z7P&kb>|!s1>i2>GDW6!#3_zbKkypH+F3}@p&*Gc33~{^(*U}Zn!#{HO9LGS~%(AmrhmlHvx|iwTl_jCS~@iV5pw9{0YI>ma`dC~SP3K>T(_sY6U07N0w2 zKu))=CQrlgyg<{fG>-nS;pE`}(g5}-kq69#`+u2%_5W(@E5M@cf`3T?K`8-2X@l-A z5$RM~T1x3|mKIP-6p#k#2I&S#=@O6zkzBf)dzSF~{Qmd(-|Mr_x~}`aXU?37-^@F6 zj;EYqU{gPTObP)J`DudG`74|60*61VCzCCIpGct2Xbj-*-?JbXS!hT&K&bpqu~uiv za>nI`nm<+jbgB9+QyxTHky=A?=rq329J@bdCxUR9;@G7>AAPf{Qe?}rE6*-k&w2r# zrBm;7kM4LhseUHd;ql>RGz6jy!P1?mV!9o)#U$^HbcXg8jamm>Lf4bNQe%ieBJ28F zfsebTjFUB z9EIZcz9s%<+xu&sY}qFu<~DK>@~`Yt{>|UbtgakT+7k|I4kBcw;i^w6D`Q^41HRvW zVAuv>N)FqBaK{;W2gG2y2U}5FI*Orh6P`%PI(;|MnK#|)RkAA56KXwgQ*D~W$$w|F z&CxNn+e{u0idr~oKUf_#0dZaEzAP&R?^rlfh2nSBk zbw(c@x3^1()8|`!Vb86@_5}$t0Z&G^BmBqtajh1V3*W7Iq93tragt0@c5M4^F_=D> zz5{6DZDwIXy;^;y7%&JZg0i3>x~7}p@ds6WXI=3~$l9-a&1ek-yWJ>sCpR7FoC{aQ5lS?-OSGWyJe3~EDFmUsa+x5D*uj|7rNcp55 zPp-)8!X`l+rm(l5)Xn@3Y%Z2e;1|TE-xe9JL_I_J!gYj~;&)v`qz-Ix8uYl41%@)> zyRaIdWKi3-wn!^}er;J;F3oeNY!coTf5_k=FBdxn7A7ya1NtH0C*TQ!uFBRwc-*|W zK;@Ns-*rl-oX)f9q8O-f%+nKKUM?2Em*8sWowzHy>BKJR>R5fGc9FP+4dkByo5&j4 z#YCRNCSp6Y$Z?${io9SY{-iwHb%zjxoFM1LMCyo9VYR<6fZ#d&2v456_A@Up*rjeS z)<<-8mk;%|3gj8gN$8P~?wSjUx-AWC10o}d=Jj(xbWj*33qRpC_Ac#;?H)*zxG*dZ zo*h#QWRCbqUw(f-6i_6l!G0utCDsw3)7HfJpW_bNU{?s{1{ntg5H$Mx=B|kHm9Ta(b?~CIT6BFlh`l?vq@(m_iSkS5N z;Li8N2drrd%x-U@e!$#E(FSLfZyYW9tYcb`B#I@(t8Q$sM?R@|QdxFPHFG@GOXwQ! znp5_qUn!^v;PhV zW&{^}>VR@9+ufu8Edq|=;!0KhLR%}(ak3&BnOuH3q0otIOHcZVYj>U8j=smso$cX> z%C zC*I?Pce!lQxJbmG0xWIrZXy(NDF-V6mU@s7=~_(ok*bh?pkSZY_64m^Ih?Z(;9X#< zLZb3k;Hs+Y{;~oA4Yi4&cS0U9ekqQO$#=)fvi)!{j|jREHd0`UI{?&yGmcp7 z&+}d`I-rENt88sAyZ`Hrf!eCyVt*{@0|eO|9bDoN@#=k}+s|FXQD+j$xO(4K-wkw;5m80^sp~@mPDG-5vQSc)8*}jCkIc zsFjz_MW+>ZtIc2K9ws2ktP@H|@y{$S77uJ-=3$;s`>gKjazAkS@k?}-9gqp3&EwJg z(-Cnw9nf3>K!iT|;*E>@cn||)Y2F$zi;xE(x~GVt{~uF-`C(5IEN@L7#_6S1D41Er5S3eIVQsW?$DzNi}B>HdU2!kX@@O(X~ETjqI8es_j~PVf0a1JnOZ%^p_4 z9LIXYf zXtm!X91vEf0pEruy)-;S~d%grN&@#^!2=SWuZj7nsPSz$K?`&^e&x@_IFHf&!L-c2S` zD*{Ovlm2;)KciiJz=Ey2`5*r;EGPnh+Epd)x;gQ5<#sJzYXIMfD^uEQtakkFH{W@E z>VlfyLgjEz_|RPREOXMl9V8tT>G3?QMOeQ)*HP2&2vZwU0RuLp4noD@HTg@6uYJOw zac_WyUckR-$N+2g3`r5Em-Gp`SXuu5uR7W(A%|VOjQ{&Mv$)GkuGyHNxMpSW9xZYZ2N9ik6zQx zy&lUowTzSV65gI5wHKj;+75rC9%Hhr9j(uo{2`S+U7$O zqF4O$+MyL^Tf4l?w|}?I({|K{(M4*J_(xNl(WGqYf`x?x9X6uP!GD(XnzKe=JbIb1 zy-RBn8{&bCyfd|@-T0aHEFy4x{Nv291@w!Kxx1g9{qeVsa=(a4N8jwSMl5W?R4V)z zQ#C@H(iy6Ja3b4jBHeTX;?P;@qRo+Cz`=CW|3S;w$d?1w$YZ$3&3rkxMl6sSBO$~K zs;uFh9Xcgo*?Af#nP^fZWbgU(6E-7DcS4Tl`EzQ2Hp*hUChf?{gtpsR+*t1#f_r@D4OmXy_Oa zX|D%W_=O^u-5i&^zI;~%u0j(phfVSVgMob^=*SWSR<^Se%<5;;XK=a#zlEDwzsbPr z_-w`dK9 zW*cvFBg!{Uwc=8b$L3&QAlp71^Mw3+eAs6}JRk&0-y~rhtbmuSNIe3G5bMqR-Lso0 z3VX`Bjov5;C$V*;h_n{G>cR8gb}oPH_x)f`c8S3x+N8be?)`&WZ>&C%mP)Lj9e8aI zItu*HX^nn~HUjON9a5<~yHiF|?ZM@tBq6oFkV=oZ{Z#hFjYoL$>02H_A5X)}V{J)q zF3z*2ApchpnP3PN_nXxve(*rYF7WWEwT2=G9&cv&aAc_y7F&FnGKLcwa!P1JArrQp z7%CPeTUP1}rc7Vcn~0}<7omto^AT-zdEwcY`eOMX0uJnVUg!G?g?Vs0&?{PD%tv^l zx#NbCscRl=KUfK(AoX$7;*wKSqz^}axRoxZ!$GRQA%`Z1$tf~xHu?_iJhW+J{T~{K z9|4&z8BXZC#8*`0I`Hr{0~r&eYO}lx974e!Y?6i?RUzNGNI8xz5oW3_#*(ZG8>XrQ zn%3R5T6@MAr*~2xqs`;#+QjfU^_6M~_+wbe;Qp${8ffkb9oSE;KRX%ZZFURjv?b3| zVIcItAx-%_vfL8piT%*3cz4jE>4$2aEh~nQrAj~F#KiMdMYwhXJOiD63Nb-rrw^Ix z)?+`?j?w!bo70&(t#R42c-sO{KS~R2*etIliw%OS>(G9tC^*#ERWc>2w4>>b2q=y1Cu@xUA)1B*@65b7E zc0Y?2RSh}Z{}uGw@lfq0HPMSLk#XUS7aX+j=cWAEBDxhpf#@5?ueg6BNC4rV0w6@B zXmn)&D^Me;6D`JF@SeRU{wO^kk`rv4T9nZu=Krn4`6P{>=|@=Sc1kR|%O<}1ZH?Aa z@8M5$9Te?x{vVlBZ|V!y#=3n^XjHj5wmDWj*ZNiG)P3vK3#~Mxpz*Eqz2`SX^*hm- zHMecfS`;*@PVZxfzL3b%PQ`)W5|#KO=-!b7;7y0+1>FBjv6wtznxANedg&?xu$dIV zfrqEqCza4bpHhog3jRl<#wFa@a<96h75ZI0HO_u=)zqpf%zXPad~jONZhE%Ob5`|n zW4iAEH^6zxspwef$DNSF&BlgX=QHcL`})InQ-hySoE{CDYTgh%*qaJ}u2GApjxaxE z6H?4cXA8;K6yUw#!0_&VltN6|4bbU5+uHX(oaYVTNet^}pI?$rK(3PpigmYn0LY@0 za`DMAO(iNm7+I)V;AD2x$w-ZLI-$G&OZ401he#a8wKa1`f^|6gXEr5yaRj8l_ny_R z)E$D#Ej!`K8kckQ#hCP(rf;oS~CiYXEa12xRhOojt;#pw!Yo^%FoJK0DtWu=L->5}+|l zySWq^+80^ANb0nal{T0iiO70GMVZIW6tuv#u+Cls??3RZ01LpO4nn+ zpDwy%_P%OjKzl9SQ}{-mGl3@2hin3vh5k~ir-iQ7&QWXckP}^!1@FgKxMgjPLMxL74HD^0y6|m^Df%+Q%;NT&9+&PVTj9jloiYSa*G8-pp5ETQXd!a#$ zYIXL_z1d3GvnznD!36&b^)LGeJdk0b3z>BEWlU!&4`Zv88?RqmK!^m>6S=G)d1RIh z1f!*So5*4+Ly{NHDRN^;S)Iu}8CyCSMJqJii5P*xFDa0dd2<$~>_^P0v7}0&O|iwRR?Xrd4J`0b)auauBpTZz zt_jk@-G7$c)edNee!jpP2^I?Utq3d%1h zRaxxv&Z*Cldlx>PHLXpn_wV@{?Y>|ttE1UoWUbWS=9YG2oW@*M#LGfg{MacfmEMl4|l+a_3NVy$Cq2{}0{**KFf>!`Q< zTv?<1OtIVQjS>0*Enc$BhVf!fik z2T&K2@BnrV8VDaIEem^=TRZNlKtL*Ge!SAhOkd9=c-20;|*B`=x zwyU7gT_tw8u;Fo$ckb=SC(Gt{;Rx^Jzugq^`;{e#ohr=}G)iyAnTze;c21k$&L=@g z-)DHMVM?@tG3fDaMw2hgCrK%i1Mti!Y0A`i9;9M}&+P<)tR|#wtqK%D$cp;d|EI|aR+veV&>xxl))`~-G-|8H?pSv(1OR^;O*#z`^O zswTqvciQbV{66PTed}nv<@dQP?EKLPNM4yixUv6BMia=w#<_T11Shbq_n2M?CY1g{ z!q4HQ%(aLgfdi0_~J9oVa;U5uBggrdoN4#RwT?$Z1NJ2~;R zVlMbYc&>D*-m+jQ1Vniv$4>HQVKg7UDJr~gf&7HvuJO52AIG1i(#xla=e>zdMD5m=G~$(x6{-Gpj*CG7^R#y7qi>aGeOJJ^||>_~rc=R>wl z{#nTSUx`uu2*8q5f67%S^TGqbBDXbTs_5GMaQ*^4G+PrbaXgNy;BldZHh0OfI3hQX znS^j<0}_a6|Q8Nj41EeZl`5$Sl zhzE%(f)>MRx4c4-9!F+t9BxI#CX`-9#Pw@v2hP69%F_=W)BFV!&vC2YiF?w1ks#Hm zVCF*jMnGv``YhV1o->>W#eYqJ&~qYPcYaB&gV-}FM;-Gdp(9k)flH`cyTQ{EIQs%y?JYqMN7?DtxVPCj!yVG)&H(_H<6Rz!2Ja5WG!PvHG#s>Ejc_vL-9 zJ|&Lv6)hCT^p=C-B+kBKWlonx2}AMJwCA$A~S~_lr%Cmy*sAQqbDi0LNO3TI-mO z;tu|&M2ygz?J;skzYO05VvUzdQ}sKy>L+Ipy75GkSWtYF`1TUDr_{7^C8);f>ruv& zc&h4epgJKUyR+gyLfQ#S)!%o%fBjtLwov^Yc*xor21}*wB=#GHM~WrlX7q`S++nx# zCm)Gz=?nH`EgOuYd-OC;6r6}lFU58WtoK&`Rv0X&Vb1BOwOe|gBA0tI|Lp{E37aq+ z!;PAnm31py@D)iw<-tvXKKF*(cfg zY{6Leb#G~&hq-iAe6NbRDjtpvWuj{7a7OHc$VZzOf}G`dR<5=3ik6F#ma(OV-s{~E zfThzzwq-6$`{ADvK)0 z%}9-MxQ(WDXZ{p=E!wGB#R`vUH$9*5Me zd~9APj>cEf3egPvf<5;}7#HQsd&C!?jKOX_rJb>V9*kdR7wV-!ZmtXI`^*)4rcsfk zv3u=`0!0iUHk>Le}f26I0On{2rUbNv&?aPx2k?M*gQ~XY0$tcvV!VLLQTItGWnCSb}iy zS8rV4SeV6h)c95k4>$x=vJJbNwvPlYoPWN6XuVxTT55LDlG)B&9Tl#wp*LEO>jDFuBB*C| z+ba%=@RWR(!`a{Ec}?f#yngMLf^V^}S?y$KUD3Tc`_3)Kj$!;x{z{VNuuF`}{k$@c z7T(!34Eh0|uwZBlZsOPqD&${N7EI*5366?r)qEubMh7G~()EtOK?ZB@n!Tx}V_{BH zwt0l_TwTbRu3pQl98;7OXAzk=iL`fS>JlQn?44UH=&~|>Gj3s_LrPt(`>qm&P5+r< z>1UP4?LQJYS4%DMR2dD_Wy2!YcEa5%OvkMrKD5=~jE9?u{v3Qc-o>C~K)eum1kYC? z`?NO4d*-6u)|WIM93lUrptYMRn0SwoJy_tQmz8yEU{Yvm3A(2yA>vH}DN|!Fsnr^e z#Z6=NI}%dKS2rlxsd}rFWy<&4ZE)ljk4dC^yuncIgJfALj$^Hr_ieADW9RE$N4>5t zE*6b?SxW@nel7auxvu}P&(Jm@^mr=6`Uq1RwQqH5R}l!sX$}7wDPhN?76H^>6<6Om-6MCMu*6=OZoETK&IJF z;g^#rF_528qh?cAW(hkg>vnBQg^-vbJ_v6&L2?094B3MG%86OKS*QU_5aO9 z@4O}N&e!7H9YLztS!bU!-$Q7^Z@(2}kyTziiq^0;X_1=VV&W(tE1J?|q%RqpMA69Sw3AJ`(hrf#x0^q5_!#a22Z#AvLinj-+wLse z`Z9BT=h%pZTEwT9TRU?s>lOnM7M*=hCeGgt?AAJcvRieagGSmQO!$5l__wxtcxWS` z_MSGhr(Aps|8V-LhdE!oJEuYj-?>4MwT<)fW>uQeivIxL0t@+32#H!+iTXBw!kD3u zO{JS>(a*f%@R7`6d=_d<@nE8|UL%v!SKZkjzGN1ls}8TN1qu zt*_POHcxoRcE6+Fi#xM8S(g)Y0*S^E>sdyz-0W!uM(m77CyE7Q`!V-lPq4NvW==ty=x1fU;*D z&u=VV?aS%AoW|j*-W6uSY@i{1ypcH~NjP2eX?1k!%rSrMWkLIr+dz)(#IZM8=`*|i zPqZZ)pCGd5;f!u_Xf>3pEjWo|+JKZ z&)_!ZLO6|$d#F7LRsSC3?daFK=O{K1g7i@i+^iT}s39@9Q94@kG0(FYhDkQNpPbds zL94cIOAf%6e0PkV-(x!occ{%bbAgmBmDSkAIkQ0|`})A?n!Gr_7XB8IDVT_eb~Igz z2<5buhq;Dihsn+YXW8IRqZMME|eSI_X^1d10RCsn8_zF#} zuBLv;LO{`RHFRAyXjkm<>}w!Hfz7Qw8s?{W6^`9b*z+^fN+&a;%#G94Ie`Gt{67T9 z53UBSE$pe&%AAa|!&2=$y66}po57P#gSbc17B>gGhC^q*Z%4&pEa^mP_ItLAEgvlXxSSs zW<^v|#y_p#~B8K*0pOFIWL7hek zLkrgyk!-pI$jNY0r{9H1bVP8&=#44JGFi4GOK-~DJ^l9HTP<#e7FTz`*~f>wF7rAJNO<0^|j%ky&fPg}p(4~(yddsduB**VXh#>oyN zKjD=lkdYBEl9&rG87ii^e&C#}^$oIS&s-ek3-|WVZw793dBmB47!v|*XZrIYL*?T^1g4(N| z&Cd3{qF_K{$Y}Y!MJHXaU-oV4bJe%(1>E80?fH?FzaD9jvNx#&r>gW=Lb*Gs?QnBA z-!4DWVWbAVzkcG*eR4iy(DiJ5NPrVD!PTzl47y9-egC{nC&I=l+m2GOEG_AO zUx9QoK@0S+d9_blrLyg)%9<)ZSSyLf3ygiBxA7V)-IWTom#mL;o;RXSyDuG!n>SYa ztI&8Mnmbls%Y1aU zVykI4W7#Y`<}Thl$tvUMw(h0GvTizhV$y1S7W=hSvFlVV!kwAmOEmh6+P2(Hmu}7Fp7Ff(?GT9!F)fV=yVcq~7E-s!fpe2{>yj#N)ZPiFzI%V0 z!so#2Ka)iKwP_`RG!tQFWVS*mo6Kt(08-xJW98v)!k!J2jPBTT9LO zjCl1IQVD^9&W-(m!QafMu?pMs#g&I+Y};-D5yX}aJAo5oa*m9+%2Sp`mF5+$VcFye!;L-PEWwESv_L=gv1cUs7AxV}?mT z&}!oP>I8jXGcj}aMtMvC+(aBf&EJ3y6Rb9WlRnMGYQy27g7biLHM8^ez0=`$Fr3&!`9?}Yf5kmOs6U-I@_dK=CKMLIeM)+uWiqWAm za$rF!p+<;b^GC2nd<gL9ndPqgD?OF|KTUaym>O1!*Dg+6ibdPU7-lG&;kG+?C8F5`l0N^a&UVcISo0qae z01gG+x}l;7mH}_n=AfLzkfg8h*2t(+;&*dc9SsX17X;gE{xsab5dtPWf~|W7%VXHLf;vFT9mY=C zK7Wb`Q=zS@5A&q%KLQ4{aK0cIUr8-@Bvz6$ePBTT*F8ptpy9<=Xv@U7eKQBcPeyao zwWg9{DYb7b820Wn-b<~r;LdK`93lpBTIQnvA3y?|uOq#n$65*1HaYAcNb!KLoaS;S z&}Ah>`CLRG$dwC`%I4jJk4=hlrW${|;7lI`1Kznu%)pv}*4{h}r+`g?TI$9Vf zK=-1q)-I_fWJT}vel|FKR9V{g?}+Jy91Mo3G=BjoQ0d?ic05LU+Ov4@?kK&Pn$d-P z9SHMmd(o1Ytm#}gBT>T+VxMSsi1_DuBO508N_UMYyuZ9n0a&6k!6ftxZhZh@1&E!l!tAhm-sleXP{K?MUaDw6AC~O znRl&(dz5P7^wGgB{H7Ffj<%=vch>nI$r+=8cm#O literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/pass_through.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/pass_through.png new file mode 100644 index 0000000000000000000000000000000000000000..19b5cfaa07626a177d460d9d3cea323b22e5a617 GIT binary patch literal 68871 zcmeFZ2Ut|ewl<6i=7dBA0bwwZo75nw$vH?43ert#Qj=+#JSLQ+qX-HDCJ+!1$&w5N z1qp(HWCbN7B2A{@uif1!jyPw|{r+?BH}`YSd4}D!_pVyCYK6B}y?ZX`YOCzrwtpK1 z1;tJ^RYg4t3hG7*3QFcJn?TE`LWw>2v%y18MV=zFo@JPVLT1EM$;8tcYm0WWq2Ll$ zAYE|@3EE>kJh_AwxrBtQTwVFC(N=cuR?Z&$E;gQ^3EX$aSfg#xHrAwPgam~|_yooH zVB!XX!d${~LW1C5f)e~f5+Y`#=dJ8)T*w`2VQ^?CCo3)?Wl?@X(A5zW7>r9;9$aan zUA(a1FIHU4QcUD1xRP^qb+R$GL297ExXPl!aDHJi=oJlB11(K1Aq8;lgm$z6e^hKx zju_|_1$%dlGiXtU!C?G?(EmWAzLl+&J9XyN+&$137xEND_(k|(!X#;JJgw|V z&2V2Y4>KoMdkr~FRWrDXnx&?-KIs`xUsoH_GjeB;d1ult-gOOU07@YWX*lUH^5^BAimIb&7atz7N3FxECsU^r_mX)s|SaiUnD#g{C& zprEigNq9T=)se^pLk;?9-0Bp`Z`ygGt!+HWZzJu%L}i=Chw@>VEEJ9mtii?ssA2?N=_wT-QnmlIIe*B<1Y&~}jPd172atCfc< z$u4ZsSSYB-69<%AZ3T`(YJs}4^0Wfcg(Q)XvWK@FmykTx8R%F+S5;fc%vW9nX^izk z;ao+KDo$QjI6<_Ps-7T95#y~XY%Of<-|07CBPdfFKe8Z7gAW=MH8pyqopY4jS@C2i$ixQxrrSs3?n?nW)=pq1Aw#x+;23W-eOLm8!O&jWO0q z7cJ_5RMqm-GVyc(^7?3+$lF`1*oj%2sC#HAXcOB|D$0UZ3XX7Fee$y|p3YXrSPva% zQE#NP;kS0QkC&+s7N=>T4Mz#<`67ipoit6XUCmVWFggzMJ~oP;5}MB19w=WyoQ;r~ zD^kTrObw@o(=s;o)dKf)6(n%hs!kqe1|s61A6JwzQ5HKZ0PtXd?8|VV2>7axKdVuufrLC`K2l})}2}AlN z%HXSp24O}Xj7prPAv8-x5phkSuR2mek;ZmX_ck@w!>vEA5?W1_G)FKFPSe2<{B{KL zKx+YA+exUQMPNV?f6 zUlCs|6H`wuV>@9@2Q{p?{bzI_{;dsN|ug@;^JyPxbP{`u+_)gZ0)zi(s{W zTx%S8t-*@^$qKNQr=>6A zqlK1(R@qlgQOQe75w!UdpTTMw*a3~2{`ebb3TYa=D~HoYLn|kT1^o$u6|&P(Ahi*_ z7l$G}_tlHF!0H|c&njVc^hE@<(Q>|ETv6h)M7e&j=+#*&NVw=a_;{NE`_dE!F$pIE zWfWm~kpDcb&@Mzc0L3(N00u$ThMbMp3Gu|Hzs@t?vWV%1i!}-b0_G>by=xSe9_}cFA^3p>kwfnq+cI8 zR+f_k^Anc$@N~yG+Wh>^D#ie-DvtrZqdg(jivG8)sE8PhUznV|R~Hoqhpn@WV&tV? zyN0m;(KQtL-witc0&FL|$hLV=T*Y#p)o zHpWK2CLo~bI$#~mjLmT1?`m=;CwXPKnX{7zQqk25DJ1HoBdjfma+Yv6Gr%}#IiP$& zxP*Oe(}#Ilndmv8oUyJ*V<$l!2PGdJVL>Q3kw6F(tW=DgQ6OLe07V2YhGYO?BIM)% z`d^!TeQgW`(IAxi>L{q$pDwr!PG-rUjzo^5!NyG0jbLrr%6m*0G#}NnZSE;qDaN#pugi@ItF^sI3Sg+ zk;mbS`7_dGfrZ^=p9YvIfmI5>`3J2u$)kgaOU}oqGuD{7+0HxBO%Hv^W zEb0V6l`jBTSkNy~uUZb!8WX`57HZc~5W#5!d$3Vd0`{P`4&WlKEdlqB_U|-w1B-3$5>xaYvlrKMFe}0jJ{e5B0?lPfMihu>q5K-$@%r(4={uTMpb}^ zI2!^>Ra^Te)GH43O7u`01E^OBzNta*66*Eqy`S_-1_aQ?L6=xrAi@E6jHeZO0|oo< zOCE3`ehG3W{hB<)B!vGJA^^1)7&&;a%_gfE=6?hbkTc$20RkHrYdNUG01~td#s%Pj zwE*CIwD3dP7Zg-hmWO}>>CS4}2RKJq9_+x~eN8~GUw@cFKLBVV-&2I}*VmhhkgAEl zuxL->Yy5)35Pq-$ze#Vx1wn0y`1{+d;O2L4>e{%Y0lxbafV8pxQ+dP#_3Y!X0U!y~euK8U7&Is$e#Nx_ z#)u2^i~Sh}i3`H`g+#uATe69)4o}hyxvReiS^uRRLK1@f;$q*1Bx&ZWZ~Y62JgwaA zY&`!95($IqCxFsl5&vInll(LhQU9wae*oT~<_hWRulx+<!wB(Yvp|Ihh?goKdTk7E3%9AGsx z028o+HoU9za)kng2V}B;ZRl$qd$liT?4QDn1YB%A%?b;yr`dnK|NVPoiVOaIHU4{J z62kyVVSh(C|BW$*T&w@981rw3l{H)VzslwRuLcbmWZJNwCN2pf@%4;+)y@9@Po@8* zDE3dtpXAfDf6un9tvu|%X4ExRE2v%9$`gP<===m=Iq1ms&kz-~d=G9RoJq!=g5qSH zNy44tB4Xs#L%;kI0D_Sr?|1z{`1o6g#9t63`ihAECY1f(m#PK9xitCs@he7z z!^q+9Kj&O9K@liv!O4L5=R^M!9Ez;JUk>%lp}_77IMk2ja8Yr7Ve)Cpf7+@3*5LmH zw*pnDf4R~75rq9pRM6)5e`BHooTwk_D-!UpJG}p_UkU%c!T%9{MGi!NGhd;ctUNr> zC;+RzD{*{lUV{d|M|rm3fSF9s0>^=WMuiYgBsuv10~HZbk@d0yj10y9bEYe?{=lMt z0(k!jvn4zK{{?2dX2bEd!VYaWNY%!lZ#Dj3GI!EkzX5wuu~iDkf7IH+rUE7`28Y4m zVj^&Ip!+I>I5A!PsR;j%u>Bv&Cg4=V#@z}cb9!KGp_2$_P`XDG`L>|x8)*`dc_60a znjmdOCOe{l8AE3`Kd>O3(bm=w=W<=f%J(7u&m5vPAs-YMR|7mm)cg-}ibMf}=m*p* zE-Lul(F@5Q*BlxNfr63p#Ol zs45O$bIkV7S?j-XX8ccPJ^$AUNLs#f5QzgKWc<6#Wk5_)_qGx;^dyoyj9tC0j77u% z83~4TKK_lJtiQ@mR{tBsB|$RDN&Op>*%;<(tzzU0#sFld<6?lV3%51!0c>nNQKX6? ziAlUlm2y#2ae_F#1|-RhY^{v7y#coyqEq>r8EXrwsj7=Y#0@~@5dkyywSg#0z9J$J zrO8Ug$kj~9UJ%@es6dcLzVez$qz}L^{zflakJ}7*&qQvsDv3c2F~N}rN?|U?eLLNla^>wE|lB6NCCkvev2wNu)5MT;G$zAfgc z9y_iQeS9HW(N9P|D%!3nz-$NPCL&Ra*qe$rWM!hz=)`#uNpgQ8qM;!o+W#eNVVEGq zW)KA5a|w|E-Jb)$xG*4HkaPH&)D9DYw(COV;JP-siwW}!|IcRkzrkMk74iSgZ&iLp z{GUaEUlIRT#Q!Hne8AZO-^u<}z!%~d0^fbC{zDG&|B%@KBdf&63i_5<5Pa6`jsY7! z(#B=Y?tL{CfUg{#Fka9`{$G4W;<|>DNq%X~*|z+j_vb(R=!7K5e|X<6A-YagT>=mS zh{rx_*A%`E!E^OP;s4|&oya))$)~leY@~0WF|Xw?5$~>kPEEQ&egXQrox}wT*i(9# zf`Xj_e8XjcwHWK(9DBmBTlTZ1s*bA8kz1#mjw7h$5ZLGiJ&Q|`+f-@qUQ|E6#KXR2 zn_i1?T9WE!B?Ajx8mglggHNRxs|7dGs?N&}?z%GO;+-R0?DMIrZreafwPg=GBADV&7meDdf+@P`<$kz9dUSwsPf{`Wx^E(a5r-)$ zJ!7c<)Z^+H;KfZpd(oNFD5-7W!;$rcvWIQhfD6+qe7|=cfx)oOl$7|6cowDgW#&7? zj=*GZg`Zfz^ZQzeV2ijbch(mzsgjCnh)?YOIgRx@&)d4C(b2=5Zv8pu#s*WARvzkd z-MXHt5lLcTUe4N)9IGn&Zh9dMw0n{Y-kxFRU%&G=U|v~uFOUCZ9g#pO3~{c{xz_Kz z1I#N=LgM0|*PryXnIN$txzn?qG3$5k0Os{; zvA?&7|Kr6zxoN2FgqN4p)T?H`DyyHY+okhQI@snAP7mLo^EGI(^YYx6G*MQ|@7B;g zi#M$n(Olog3C5>-3A0gmqNI~ocCm9%4H0k)o(b!&ZQW7eYxTabdDi!}ArvrpHl5&s zpZJ3WHPuj^gaGa*o*cl-j+p4*+9gX)cP*b7!UkyAfB=GC(bOxaKtOPCwjcwr<>ky?6Empv*Y?I zq`G06#I+G`o3JNwB0D&7Pzfn?n(&*Vm{!{hp-3 znpC0n1^czs>*(dzQvYD&h+kg)V?6ui)!zpyC;{nXa**ao=@Utq%r7Y4X+{{UmJ$)il;5 ziF+{0luFJ?vsX@s#7JTbGFG}eGZK5YMO z?OYCmj^txS^`L4g16MT>l7#qE+g8Riy;ai(Uk3ZRBmt z0I!*IY^LLK#YyeWG7GVwEAS>hfH-tX>>+n2|Ht8-A-?IYo2$<-?bWDwXd=`(Ug~tm z>mcnn8*EesB~4DRmXk4{Gk*Tf#9JXJsPy8yCM9T!47%<{Yerg4oEv_g(|fq;(xLHG zmo-(}#vNb=wz1R!FF?tbpNfdRbxWQEGYR%?%m|xM>dlL7y(>WTJf~$?Lz&A!$1jU# zZJ1OA2X<|8&7f==XUpw*2HN+Usj@r!{4pbEJg_x9>Zymqv_oP2`EMKIkXBG8FBm9+ zf4pB#8&$zGgTT}jy*>&Jd?f41JCh?l7ur7_IHk>L4pXl3L%ql9guh}vm9_@#HSPx@ zx5f?z!fGZe?o6teGz%=GT_H*Z61xHl@#-OEY3A^W-_9v-dlM6NIooN+?5U>5c$RO+ z6G=hfglVzOKl*V2C0nWrW#FcG3BF-Yu(GN){-25=xMMJLGP>5>KZJ;#|vOs$n#6-d1&*Y+`^ zxG-x(jPv^@>8qS1OO2#NA$3bQ5Dmw3XVQ$q&kmj&-rf>;gLBOh%@JMjHhX?D12}*2 zIZK*uA9YpLsRs6=38g2)Xi+b^#!ogS(y!V2-B1B1h*BP}zev+06)bU45EIb?;*|f6 z$QXah2fIHEV%%>r3Hm54Tx31gLFaLs_M2T&4P}NTgOWJB&R}Q@1c`GmJ(*+LD^S_V zC(^eJdt-=vKc^cW@sWC%fO>}iV^vE@xj;2d+RiJ?Z%rrf)4LKd9r#%2=0XvoL&!Rf zq7-fC7Qu9rdRU|SbMp9|$ZvjhBnLR(tDMe;szZngJKE%8s$(=vjqiImDJ}+~7YpX2 zG7?Vs-WzR`ENjh<{!~BySm$IxXFy^{qU6ft_We2|ZsYwoSB5(3GlF((|1|ac;H`X* z!2>NUZOV2z;uE(&`D;!WdzaKdE=Zdlz3cWe_!~>TJe1x8v z-qe=ftE*f9Nx#y5w~2}|EYG4S&ti1_ah$+Iqwtr%<6pua%toh%tj-!3?+tJsBdRa) z@HM56EgO4c&XYZweZ9;?x5{ehj8c3SB!22@gAxifu-f5M2JpFiq8RD;J}f`cl>Mep*wWR=$Zos-QuhHcDHBY_S0fX-faqA@Iy=%(8D8`r zXI9#iSla}X+WxwEVl5e?6c8+Cdvtex^#-mzs=E(mP>nSAzr^yeUV!&a2QuAHp&w$4 zx{z%VF7WgL6XmK>C_>7h+?-L~`qg=F7`z*gJrGqDXL>0i@LoX6qQ08n?Ud5j&8)*~ zN0kOg^0Tk%OuvrGcc@WJGpH<4>gt<~%I0GnqF>n)Azjev-<7mWs|J`fMyX?GUSeRB zk}_^_qZIqZKBwW*^0#THBVslzfMd^=2LYdQEk^_Ao)gl_3E4S>@f$-?RV^~b3Cyy7 znS)i#DGVoSBYeF1;5~0ki^Thvanj{dSZ^t5Pa`Q|CnG882fl3bkB7oTvX^rYX18o^ z6>!lr&%L*d{!*&kZ&x?ng+=wk8Bt?q{8jDX$6!GZj)&F%T}T!DDr!4{urkWO z5#R0I!}Y0jFo7j?zj2E?PX-;l2cKRgnlzxvPO!_V&Mbay{}Aywb!qNPqDUcqONwJV zTsNY8*D_%a6@j^1Y3_>QAD|S+e}3NA_9~ z^tk=RP+mb_LVx{*k0|Tr=?u*S$40}2`yL3_^EO|);m$kkH&7qQE<1AnPTw1S9p@UE zQM!<{C-3BFP|7-?usg~&ZP|$%n1h@P;qV^uyvCN&qS#jRJJEDWS=lvd1lxy;O1q628R0ha&m@Sqv8RK(_vqrRW*z6-23d4ybS5pL(e*#^3I(RseFYsK3I3~ zJj-65QeSPB5+xX+aa%~j78ZA_ijT8f8vT%M%^qEGe%!{rzLfZd5}bQ3Md@LOQc0EI z9?9}+$IMmrUwLkC40GexSJe+UX)vP!R+f>F(-k-RdSpJE5}(l7;$gdQq7F^J&^eK* z8f152a@tj7?5(GC$|FPGy`vR{=kl6s=)ttE2W-H>>dnyMz^h=H+tYwPm^?P%`fpMX zMZiD3{hgu|I~CY@`%-djDs2*D|B0$g$xKBHV8FJ)mMeF<u~PM?Gtqq zyzryumt|0um445zbV{^PNE;TqX@*9ikS<>7_c_?_9vx5zVXOZ^bQOp^%>CR5fu1~6 z7$v@{A%voIvWgPl7opKi9F7heZUzij`N^Cn$p`bMlM|?f$E0%}VkP1H4AQ&e?D&Kp zKPs)Qxq_Mry;W+HzPOaX0e8%|l!-B}n!~HD|4b%us>%}wDDlYnye1}q5>O|ohboJ= zHHN_%lNd2B)VRq3LcY>LEtvjcgg{l1q5KV`NU@7jaL?R6SBy)En}b}iMYu|!&jq3*4|rPrZB8zTKYU;{=; z@E+6P9&CRk-xe_DL;>G6pz~vp&NCRA=|oYlyc5E;&`@)CjZ^tHW)>)_&cD*Z&gPDa2nxuQa9sMU1jX{M&=1#1g0b# zELne3?vcAkZMnf*#S0vOjeIIG0*^BKfGL6dO#Mc?8q=Q%_Y`<)t~_yvIlc-#ciV?P zDMi^hlx8y3B<A4w_7=>$p zwlqEId?#${!Ot#zMWJzV8e!~F8nTQLMiQZ^;tUHt)mK*H@aL*+_vh7x7ow%nbK zZKgim;`49xKQQjB#{^T%wKwh3ho)}wHzy0 zS$2DqUHt~<=Ty^=V@YbbAuY)oH1d+Euu(pHOi!Z$UdUnDyVM_7&zPih^O)!%ts8W- zhqc3x>L)qZbaB^EPP($hWNesU#DR+f6mF2N&zv>-UEH)OjP ze5Je8Vrlxai|u^3Wihj*PnHjS`7Cnaf$69615{s@S5i>H7K?;}#re_hm5J_?vfZUU zCs!UzmKS6dV9NJ@)9`_U-h-J%%a5u3gCuyGm_1JRmKXb#woX_UKMs7HUcP`cZo?3= z8cYISj>+B0sfq}fz-UIHEsKt93TI(J>2&#(EjngoMa7Eqmx+JeJ#}+s;7v@w`IXkN zk+O?eo z<`1`7O44_x?$|Wsn3-oZvy!-UJA1zF#br)Z_Jt`~jCBv8sBqDEanUcM*AgGK?6sqD zbbduY(AYe%9jxQbDE#Co-+?5%33lmOr22lByAnf3 zF>|K+{z0Y<)5mXCD+dtj_R0L#v-IL3EMQ)#uLWaCzfpNd#B0m9=w%9UPqeh`g^)(o zhM+Q+vZ-F&aP(YnUP09R{wnLNsPK@d!ET1 zU>P2H06A$<(C$EAcr7e$vi?)uc^3CjiqgWPje5JO^@3%b@;Fh|2Yg;Rd=60FeQ;E~ zuC!>^0}Iv>+$XM6@D#8xPdBsLJ8??1_4H<4;4g4}*{Qq!Q zV_3=w;}~<3XN_C&+V8R^&6YSULfcTb6WnS2V_GOZ|KFZ^s4);@xyeKmD{0Y(}pB~joU(9JlNBQldTfp*viZW*I(RMhcyCXCJIcy?zj=m{Dc?(_{>^GUE2N?il7f?5o z1QHFE0?}vBIgo2DkM|4}0*Df8IK;mX?53rdva0eXPsl`j>DTJPq-H|7kS05L?@CAP z8A=83rMTDg=z(qT-TZv8Pi~Y1DS2WkUW-&ulB{8H zlu=-`_wi;k*rEKe%Kbf&oBoDW$7qHerhTV%(;H8UQGKB=WKRfB+4hz(pumK~=;GO_ z@sf@$ACBl&Q3PZYII1GU=N9)#$ft7C&MgYlq_fauHv}ogueA5+f<$iWcmY82QfLQY z)HqLG^AyUH88TU{PV|qrpGPcH4pyOHTs`&WePW{gw9io!CXa79-;YONsA`y!CIW3M zURco#9uU+Sh-*_Bn|mKRJEyCP;b+`{%fiQl>Ptu~*vb`DNilN~cN|9yl8RdfTk1{D zS`6jdKTx954pRZOi1x95Rd~bOPI8rI}puzGz~LtboNRY3@HT8Pm+2RW5O- zsXTpo&*a=y^#kbw^dOPb6k~KH26$pr{QEmXYj=gc9p{{i@~V8!k>Go@Pj*m=SBm#` zD{OnCAKqr*H=x4YtH3$#C3l`8IcPuiu}qm>ueOu@Uup#!_OlAxYCb3$xG`DWOK@>f zc_5EjinqTdO3fMt@9)E=-8#Ku&AV^n!sVUL3LmLP=#OwCdPloLHC)25lg~okCIa`B zd{(cxy{HtvpVjT1EltW8ENgc25_?~XrHa(-=}@I=#W7D@MT?J;Ke9Vi%P1;Vf~W6B zF{jIldBtS0BFpRr-@*KyjS~yT6+W1Yh4_4Rin3OB8s?0>u(B|_#WES`z5vVnXKFV) zvu1z!5E^5Vb*5iOJ7R9ym{ZImqp5XvS)eazic@B(C)7%TL#EuTqEU`UcIjk=O?lRt zc3GKRcPCN0mBwu}0_DetG232Y0>t~yIC5OONjKRz9BnudwRE^o`n*AX`9}d7Kc_v} zT^uy$o%X>Ty(TmNtYfHF-zFxtii=UyhD&c3RTU%Ccs+ z#tcknB>;tw61I6jL}xP{5ZG`YE)}F0Yeng7oCtDS!em}n03U+|_I<2K>LV)WzKRPl zo0_YI)2-$?ZE13k4TpBd?WHd$d}7(3S16R=9Q({2#xWCqZ@*Fb#jSY7r27H-!2 zFJqyJ2k5iwHgijt_SM&vkC(btSSEzeJ%Pq=1{JBmHBo>;>`R$Dv`n z(jFx1q`!@k5k!7|61uWjQ}RUSK;rLTO3Rtu-Wt)^jfrMOw)I>znbM$XC^PVFwi7q>@%i@*LD_LQ4l`tCfO#0&uvD8D-^V}Z0Abn~8eVR=<=aTe!ixNHU zYj!;0*(83@AX)q7F*qVo&`N%0)**G%@J0Zf>28Ax?gs%^jAj^fzwEs6l1qen6-Ty9 zxT6Vy`;cxH;`oMzAd3qo{wtxJ1(9>DDcq$?W4<)A()-;iT4@qx4kJ4%X*ka-OUY)q zj~(w+^3SPD!{?(kcpCNFmzZhFeUJ3zX>glgzS|T>QF^C0ULxACclhX5PMLj^%QhU# zb9FVxTPR9Vu{SN!&&|ZJoG?9Vu`{80el{pQfamBFi-}sA#P;9%e&5K`nab;Rs^Vgp z%2NNUnd;=yuI7YKL5tcIH5$1=8T%_Nr{_Zt$g;TA=x|0ZyV+3V%r02)p%B0(Sd?J^!Z6oJTr_K?CnFJ^he1iw3zR#Pmka|g2-aM@;g2^ zul8*=in$3Mz1Q9=#2n?&wO>H&jFsn(iy$*I^@rTvIcbO{P%2RmrP`sDJUeKYGJTA1 zq!McxuyEK9k=KYy|!VNf}~ z#ING@ihes!V9{w#?~~<^7;)S!e1y(d26d?hzv@@WOit_fsEr?k~ z_aTCB1Mca`CYF$Ew6O;~`fg*n6D}6)7n<=xIyrp=ddMc~VbhRhp-A5=O9P`DDfErQ zPj9yc!H~tfm3TdLD^g_lU#1+)UGeSs^6_36_wE;(JdgC}mRmcc38nB85=eY#=v6j0 z-0=#w<$afpgA-WAAJ-kF(a^eorg8Xve9PvLzz>C?hSy>XelOXdwDQ>_x~zb&t>?hx zg=UVj5`~Hj#r4}8XM29@d$zHYEpEmn@$>c2s0VbDi?jpOLw-(7lXnz4*or^caasiM z^tG_n%eJ9)<_>h`UXN5YeojLtXF->TyJAO_bTqDt7m>B%_-Y^UBYRN* zkJ9T3Cy9m9kl#UFf%>##B!ZE0pU2ZbrA@6~_0bx6ct}} z7<%tN5Ls!+4b{0x3!DDEW~211c=}$Jl~1EI=;&!bhOolP*cy{EZ$q2ud5J|u|IFv= z6FbZIPcD`ZGA3b`@hR>!PeC>=X9(MEi#TXZyO5HTn+bPhO6PNF!vzt$= zvnf8;yaLwQu)Wd8RJQNS^G-JN?kWGAS(PsQN9xT(JZu)eFNS_MN=k9YG|j+M_WDcroC!6HD_zcpxq{W5DqnE3~mniYMdu1{{Yx8t;UdwG*sE*9a?S&yG zoOa{0ENI-GiAFz^IyRvEXHbQ6SGy3hPC%KZT%*D*G1kXc8pV**Hr4Xc1j_ZvAlHiycHbxE zdMiqSvN@z?yg1A;t6xEJ`{IpY>J1(_Pzi+%ti6P>a+bIK9)(3lrG(tEw z;zjD|4CtR-?V#9GGBRF{$ZzZ~+7SCH7oqnGfcof;W+bB|J@sE@Y zi_9{fzK?K@ghjau_Xva96gpz~qZ|np%Nl6Vs4AOw?u>IRhI=3Ib)q#cHWx5;Ptv06UsMNv~rTdLiW%>26w5 zZI@n;(_KO3F|}NJY^a`O6mokb9%I2a8R5ujk!ax?Ym2*Y%YAfDVxf*=2R9dWn~uLv z&lbI;()w(gTFr2A@AEa!h4n8d-c#}PvK~o zGxuIz?lP4i4AQ7r?9G1ZK(n}HT(Lb%*?%@UbfZ{A;c`Mv;OJ3&uYX-=99y{f=aQP! z+WJGK6V)8byQAh_k4HP(?CRp}D_%4*OWoAK{D5V$z>YhMuUxeP!xpL9S$a3a>XRfF zsB}?hA#`@@bmPy2<~jsqMeyuCskQqU;VB8K}O{V_+Go}r<>VM7+mRq&P_sC!O5)OmO&9>Oa)&@hU9Np zn49e9B%C~mNWxHOMh*5YV?}4RAMC$_9E^?kE9L$Tc-HF;3yG`|bMIb9v&sZn*m!y8 zIr*tq>-8iHniFzG*&$Ai|*@O!ct`Y#Kh4diU|!+I!~>jLHS><6Bw}Yst5ax|oFYILgz5 zW3nVc5ZA2U>?eK2mH~avSLX{K8DK1gCs#&HCU!|amJ5#pCth8nh6h8;K-kMuuM3K& zC>`{kPB@ClGJZ7)qT>*>UG8mnB#D@N280o=`-=T><@(~i;ZCoI9=MLo+- zFthsrjawwf+#wyXg&YIJc>OLBk9bNsTai1bv~fnhSMu6L8>HgXJFi(nwrqHuo+JxJ zhUdJ)oB&601HOeZ`Mj=C7qV|qWaA*(w=b1##n@b+6sthBWRdsCX_#1kq>@Jl_)yLP z9EG>t{t#Qn0JiqiJM0sI=y{-W;#lDR8xfnaH*N&#+uay1pLB|h!Uj4<-ZAajT=fVh zbMAv#R?XKE%(C$AdY$p7uYso&Vd!wTj>k1nibkgze?oGu zhiRW*#UDiTItlf_{Iebem6}pkxd7zD?+_O1PZwkQjVI+JMUB!HJbCGBt3!#77zy!s z6oWu{X7;>klL}Z{(Dg=Oub}pY*Z>qnc}Y}`T_pq*`268uGmbKf%u_CrRj!`N#%6k@ zg(K{s4wQb{L36TJm|K694PX1Sdlar(dtS)BW1LJZJe>SdSAUUvCh{KYI#U7^j~k7^ zn&AHBn(%&BETLztydu%IKU+RLT&I1zw2v`;KBGAKIJEMQJ5NHbPWNB!?!9oj;6+N4 zj=!DiiN*5;Q>hOUTmQHoIEojadv|(qc#CHo@P-Ud!Bh3|5*}uDh05wA1EAvranbCA zAJrF{LXm_>mA(jnZb$uETiDUos7c}iQtdx{X)tY>ZJEC>zB4Awj}4pacECuO=ut0@ zgO5EqlhepnIS)J|a~mZ=|6RkR`jSXOL+KQ-XI1ke-u((5S>|V{wumURXHgL5(KP7+ zR;nj_p4Vl+R%RAW&LPv%B!IhmY%)ARc2|oe=U^GzSFx%=#sEqNhWH@8X9QmZK17#f zv03=Vn@IOh)8K$Tq-x6tdQg|Ezhn|v+E96+SE>|tz>tU7iG45#svGX7k?Cv$kS*<` zTF82mg;MWg6%e(i=&V9!dxxVT{E1+<43VPrG%xrddDsDR)sQ|AS;-Ycfb;G`0Xn5S zNrU6F|Eti6>i(Vk>fSQ3_*Lt{4sC+p4UFE)ekl=w*$DLjXLNv)Lr5RcNoAZPiCC3; z^$AZ_$zD`-WL=fh_LyroaHsh$Jc*ukS`xKzd|@xM2Zf3=$vxah!6%i zG~~_lgZ|p8(6>C-9H3$XB59CPdTS$(c>yo;tjuSV24?R=q{Utnae?ZEfHl=h6<4*Y zgW|>f{G_7hg#u==F?y8s7^{ZZgFt#(_D10l+(vw^SM7);)84ioR}ZJ$*UHk4Z%7P} zBsH-7T0%6BNi4D&?$0CXSyizx)T8&NAr`HsVwpxXs*6b}ghpmlqp;)I`kF4*v?D-1 zZK&7ohJ6gRSw4vPxjNwyrY4{#*1-?s6p8+)4wd0sJooPi0ZVsaB@(`$JKHGy z!ZdS<>v3Sbe;Cn_?^5L4UN|dfUhsy0OcjEC_O>9O2scEQ5&0t_dqEu25WH{> zkraX0)}SBSGxSIelzywuD8ugrf?oFA7lnG6@4HkuW0&ue8q#tQlBQ7y2t%;G?Rf<< ztSxxxtMQlmEi-2LS}p}#`E-kKCc)WK=8 zK%K#UA_Z-ay*B8?qdv@nW+;Me5SLkbJBGfbng|(%UM6(}4hF7Kbhq;HAA}}z1bk&* z`asz61W7|`RN%z!j&j6Byw6#RkYxc^N6iTH{z~~xk4!Z$PNVz}I-}1}gv?Vv-VT|- zjtIw~nII^P93=VpJ#aD-<8W-}IpUl|5<%bd1By{wK5)5eNihapK=#o21%*eBqb5rp zX95D&$etm7L@%N1efHAh#i|P_@rEiHyGSfqf&#Ej*#R{H(#Ecw9y^}bhQtrmuvQr* z&32;SxKZBR_9|S$O-^cGLnU7R4A|FAzBCb1u1u2eXa@SA4*?sd=nV5~7yQ`#Sr~~% zdgLCE=xVcrE@`&DkUa=9;^dQPC>yHqh2o$fviB()2$Sk3*cuq$nBBXcfqZRpxQd}8xoS&p8p3$P z0_$L8=*L!qW<0j0JwqMUMKl3Q;Jys8)(Rx$1pp*Fp%LIrdqn%)K2N zkh>Ah6H|xO<7Ium&Dj`5Wu}&dg2IZ?jQ|u;-QPfo{e46yMZo*BjFChW__8gYIjZt1 zwzzS_uE-79fdE)n0G{J^`i^`c&hLn73hBV{+HzR?H8E;|k!%cbHRo!&N>|T&|twlczL#bMcT;JCi<;iVnE;0R6~|kZk?~HaCrZA%Q^WI zxZ!(~;KZ=PCgvnVr%SQ32lC_F^pif_qM3z#7qOp;29ep747J$<16d=ZlToqFo4Zel zoU=W+u!!_z%gub5u&v}v4bNm>@%!2b*M2<>LL#0i6$sr^`fF$gVS7$hpt&MQJjMTFoXeNBRGzH`f%i!r1!8bTbWm58+RYO{}H$aAN=Dc5(D}oz5PcD=?tj^DPQ-cFEQoeeEDy0 zo6L!2OnU_fE)1tsUshqgPCWq5dTYB9GIE>Lvk5buD%);Ef7vQ^08=?XX`Q&!=@!$a zvqNkb++e($W=v&8x-8hK2UFtx-AjO;?H4X1L=h`>3LE>DQ&g%iT@HKGy?BOw$O394s*p+z_q2a zPohv&;TH(I#o0TVB?F#4G_37#%#@hbH#mIL-+k=!1)ZxGkt0`+y3Ka`R2v#w?DOgN zGA_<8T_H?FP4O2d+4St8Pl_375@Ujr1bd@DbVAw;zm$@IbLjGDkcN4Uym1N|-3jj! z)E0k##>Bf_{ozA!u489Tm&;es8|Vko7usdJeR>1jmL{vKCxTWMvC}QaIRvU^?&++6 zamVo)2F=ClDaP6UisdAwF)teh>IEu9;+ zT-l#vTXzw}9~pD2z&FQL>H->d&948k(4Ie*UClZPhAr$a=PJ(f|HyOG;t6_X9;~B) zOVP(`*r8kJ`(6n*goAh^cFolG`rL?d`To?hH&GM*gOcs1A2hM}&(~T;>I8ndGCq=S z)6=vSy~FsVm!a75O`jf#xI1rpbLkrZ;uo4?TY9&765p&-4G~e!vjt-FmFoO@7klQw zeA!ZNdYiSnR7*E@MsfxmJ9tuIWudJc*>qQ}efkfhz8E*dfn4n2`l0?k(sk7}*{%$C z1?cmfC13mdG%t7FiLt;Po$2)H#m?P2-?5WJnvL`9{RzL7#T=bc-p6l|F#A)E0cNLG z2s2^B%_(;L!!iZ$0p|axm;#p%3aAz6#|zg-6A%s2^*G~eT#~!g#PnCQL@W( z{)6!W^%B{`wsBtOF&m+ZNr)xkON`r`)%mzThCB54h zwZoO>m{QT%#5T(yLgDAWF!Meka7I%h!c3|IfKDD!4+ViBmh(`G(D-m=dC|@agm%IN z?~?;Cq$0zil+7vk9?n3Avor5r(S6CxYc+!qhRxtT`dBpEXS%ZFV+^L&m$C0cHuo*| zt_05DwzcWszfq&7!55u(nev)}%C^+zjS?!6Ec+zKbM;RIOt(y4(DCOGYq!4Q6pa^c zJ3)K&zRr99ZKe9DAc6pkyMFe=(OlVg!5bgJH|eRyKkI9=@Z(zsYhyQ_;{FO&Z5@Ka zDZJB9TrgnZ?R9;=vpsH;xl57FQXgaai%5-?Yxyo}yLV+AyPMq&Lb+*U+4EhJ)`MA( zN7AzUF7kNeZXJ4#A9!kH?i?LpfKNKT>ms^2+2*O&wx;HZmjXq1*<~{vRyuo^8HVeE zt*@zPOkIoABFw*z3cOmn^>R2Z5^FTo5pY5LnUw()_jP6L& z-p!;{-b2gjDEahw>0Z^9&0~encTG{>Pn4W{C;p*P!OzfVpY|t#_Zp8kmw)b}olKAO zo7wui=Wdyqp*#IA4|iflJ*%$URWX>mn4U`&*+hAdR<*Y`dC_NDt4!p{>D>~)E#5Pr zTBwzl%9>a2wM>CmG}quA+8rlK`-f1GFVin1X8`VPuKpbq35Bsx4qLfx7btNRi=|ue z&Wo`Sj?B+_Cvo;Aqou!Fy#JS%lRz1sE(Hw|gYn`YE-5@>#{+&({jxN5>QVbog`08U zXq5HFY)tvmz3z+s05ZsIchKJxZzPfO=-D-4lJ>6y1qUbwv9s_80{1s{()e9G;R zJllm%kIDW0ShN|~gK!+9egg0I)X%^D*i7$X!n3|NSu692D;HGQ0z}N6Z$2BwD?d&0 znJv~li1V8E?u7Z|pVc^qDV=V0WEA)D+IjcXv9q-=$KRi4ODKLMlcA{d-gnzA{YGie zp~eRn@rUHi_!2s_cwXzL+V#wUrGaol4qT#%dBf4)bhz3NO?VziVPmg~JP=1%oNAC| zOV299mCW^pZQs$D-f!amk}D^AuqA-=N~e1*U(C%!nF!s68L7HCuV%wUJ?!#xEVo7I zOrq*gI*gZ*^AWo=VLwwI=E56e!g$trplud7Gnbr*?O+TfRzG7;B&J24k)H&1UA8Wk{x z5)DXuS7etMaUj1}rs;4*+Q-8&maLA^{^tCkidts0%2)zBoP3JXe%I#Zx5LI}$8Q>O zr<}J*9yih(=0ya3e!7`+d|#|gTB6Z~0=}cFTDSDft|vU3HfXxW8zuEcHNWXthN7je z8aT36dpdy$oQiX5!Q!TFw^9(oh3i8(BgJobk4)EhXqex-o1xy6w%8CjlQX`nXnr6r z=d-jk=an79g-sGab~@yPI1NAN{P|dB;G*ETU}ShNCUU`Yv4L7|-?_1p%|& zaQ?z~zdN-oxfG9!&En}OlcNWQ^*638malYXcHpZNrgw&B8YKY+VeXfutNPk#pFp#` zm2^u2x4CKJ3_YLYb=Dk!O2q&lE6z3)`ZS3>z-foejlk$zoV`->9}4GghYjqq$*F@! zVFDIAJ$lDRMq$b051Xc#nwX7S&Of2=PFa3*R>O|}sQ*4$D|v<|cXdv+m<0yZ@=X?< z-gU!ouJ6j>>SrGvPKHX_I1{l_N;? zZjtMVc1k>5Npgl!({eAm_*(8CCC(CK51(^TzfSc8Wb5%`-n{{{)b)BDjN;VCQttvx z==#a&W1!i-<>{;-X&2x^W3g`v^0_j0sHNX^+}YS1_-UB=U9R!?X4$!?PC7GM@NSW& z<#R2D1F6for5a|h13H}xY&zR>`G))F(U>oEeJKd>=n`=D$W{g6FH`O)r%xhezHUztS^Wq?XRm zJW}bPme^D{_N8_aZ&iZ6cWN63wBf7n{*m}(uLkdBYX1L^vGB)PF8sHvnp01u{lj(bOa zUjgMR3(TyL5l{%38IBo!D2wHhtw2O27=lf}CDkv71o1?m%vPop#d0KUZ zLjMf!8pXU^7_2tsxzzO?Gx+pD%$O?9OiVUlcgi*GWu*VRv1iR=)>0Q_5{&|IqxPeP z+>+jrmc9PAFSq;3gtc~mi9OAZeP}r8EM>~!xj#iaZ07;6jrxmUr*|46{6U0Oow7TE zXke+S#44KJuLC#)_pj{JUZNcfx6O%>>af3gW6kKw#lb2&DZKaT_$up;*STrlT&BsA z6}pv}R>Wz3xD9$ULXzdZEDGLxf~mv*la0@HHy?4g|A!O72lpy_I@J7`6q@&f^IYJ$qh z_Z$Z-wmX1j)V}N;NnJRuEBW=Vtu+0P%549o&PQC$UzVR_0=)i_sNFv5|Bep}clAuNnybvV^ui^*BmJ@$2-qQl%A{oJN~ z6Pq_t{b>!@t>S5P&1$$Wx?U>PdoDpbU!b-K)0&RiPmged+wLQpWrxt!>JCyu_`<4E zrQ5c+X4ZoRm6g4O%IDIn`&=XE(`EXotqM|eR| za(e^QC)&`qCd*hXC2XtR?AKHXv*^xCsa1G>4pq#oZG!A}!$CdH$~W2b=BoFqZ<+Q= z7S7O}cJ<|nnH{#_3u6bUdR(bhu2#Z1Ti=2rHJ`JlA`q<|^kP%!X8EV8A`I8Fky7^9 z3-xYWjR?%Wo(s3KwH5K}5dm*;z~o~SM{ILbN(UEAVija}s_%Ap-L=F6B!J((%o`YW4HXy(Hh6>@fxFSx%b0Pe|9Q_<&A*8P7G7Lu3-*6?G<(~IM&D7n**78ABAL^O&+S0v_6D#HV z9wVl+Bhcb^DWzk+(`DV2iXCE0pZ|d7A@@yGIItS9u zla0I6{yUv@Rok;4Dm2q$DJw^NutULUmMZP{+6F6-}5>mn5$! z=*fB|9MH~J^`k_E)dY_7(0_!29kzLU>h*Oyq7Hf{CSbTRg+8WkeN*>AKiaoi-H%7U zcGl198+%*U26T!r3F`ZsaeNgd44YAS8cJ!9;dm z&;jNMtkAeJ#K&jSa^xykp@w#l`wbINR8wL0nOEk^CWw9Cl{@*2#7i^e1|Bd?>?&94 zNUrFo%IYLMq(hf=%SLTKUj6(ac(FWSg}-Jwx^P2vYArk7G|^!yx{^oL=|YwcQXbq^ zEq_WEhkEziB4*q3V2U*un*Q4*O!gYMdFiR#Jcr%P{F zA<1QMcQzWy%e>Xn*nUHc>q_}<^eLG4H$CjH6a@{E{_YbD0+x67q@qNd#BTY5sI&yuVo+8=c zFD!K_S$x=j>Q{ad{6;u#BYyOL0HKA${DAz-hX^?nZj?`6oM4E6x0&xEN6+;jcR9?* z>a=klmxE2$ZVB!#*`8*6&Wz7}{`#o`DX%64#hpYpHYIkq=*Y;b z?H~p&_Sr5A^uU34*vngB7<^5W#kiRDcIPCMpk-T}$ZAP@EU&e!aK~b>f)Q6-lU4+? z9DkCSgCOgv1uBXF>w9nJ!lhP)@Ay1)=xGd^^HZtG*Jky$|NTWccVR9?vcfJwQ+njr zJ63@`hoF1*6bm1{^bF3EQL_b-kda)G0 zx5ZAlJ1|CTCknT|IN1AT;B*<0tIc|T44RI%VW3>t`!GJR`jg&FxaN#Iq6)Sad4E$m z5Z&e84~;YkEaE(kAwP|8RP@9mKHYEfYlp~@+++3E2$pp4k-;!Z)SrwTmc;yat_ihy zC~)6*rkn>=s-Q*L!<(>`_aO4}`A<+hrt};K_FCUwE4#}~Y-dtZALj@Qi{yj7?WOsc zSd^x`Q$31H;@O`UuC;Fov<+2UnNvTQ>wF}fz9!e3;SKJAyu#bRwE+1Z4o)=l{V-v_ z-ZV`H5t#6Yuv5a?=Lj)MKx2o%h5DonnpK2{uK!s;ru7P z%vY|?W|SEy^`M2hB=606^`C07_CY<9#^i2@p|7gv8Kk|w2-}Vf#NEaZ<_)=mQt0Oe zYWk8oa%Y)iTYa5U@(BmYMl~MpFt(zAs%6}2rxiQG!@ECcPNqcE3^w@(s!ir*7AC}U zMEoaQXFEuJKA7ByOCl%bOUkT(nR(A%w8o}facj=IYQ?=LC~;xn(%$W8j=P8n5o3Xy z-p_qBA9AfS*4JV-+FhEkg1Qg8wlJ6R2ClC0{24pa&gCV=^)~?gRhMgG<((Q=)3+w= zUww(sJwxpM&_vm1A!vJ+{lWuJR(`@B6f2JOmveK_&DHJ}R6JM@VVyzC`X`t5(fTxW zPrfRmSsXlH2OBZHETZNJ$67Hxl#i!od#u;EC9+@fY3 zVo>w)s&>Lv%_I@mDqi*G?ldv&SGl9A%xA=IZ(AVu9LBo%<(iyOBYLUoRnQ3$2*N2D zCDtupLYE%$N6%98P#mZ!K;OI%iOD}X(dMLlVr4MA4|XO-yKf+9fN=-zYu3JM<4vFF zNm1FZTE^sGe9bGjiDV)B(~QVRAMf*@n$_~o-o*Y{T2m5Oa_yGo70S`}G<_oFSr4@t zuXJA$o~joVcD`CKYvxD}_OwpsKYr|X|tMd6jsC(XzvXG3_{ z9;-GYil()Khz-Z%gCfmXKZBWllgXE|YxNx45qyL-br9?C$405)tTutF*60j?+9hdI3MRv6_-QbyUcs$>c4+frY`e4skn*0F31|^ zv2sm9Vz>w8sEQP^)nDq%(@iYpgO3_FoM1gA)m0|MwEf%M)*};K@N}3uS8rk6K21&WCQ!hv2>`_$g+`UaVownd>y&8>c2T*N_c7=}_42IH zOcd1fq1ZsV!&TVwBSi6;@ElI4uwr)ss#9^b8s|9Qgd*Q@_NL*6>`ceReWZgB_eu>$ zn`4~6woO(10xhX6Ois1z0sHGAd9-?<>Qa?rOP#| z*SLPA(q84#`oOl=-YYDfhS^(UQKOuhTU^Hlx<^y^mQlgeLo6O^WnQo3uN!! zRZ}}xS5iH*Yhw!Kf9;5`LibNa#q8WiRxI8I_cjSSjN1Gp#YQS5iKng|H1! zRJNQn;8C$idNB`GEl|ukInYhHGB3X^PpV^vjGqb{zg7OM>D8R_uMu>>Bq@W}gny;< zN`Jg#Zz*5DRR?ug$~@{$1y>PNBHk(PCS6^%jk2bbJ+f5k^t?i*nP2aixWw3ZdZX0$ zZf^oUY7LWo6V>Z7x8N?kO64%1~x-!Zb~afs{I4K z**`UFoR^DuTooadepp7dWL(NtOMkpmFLDUJB$;fqM=M{p5nwlS7vzB}r{JK}Zx)}Y z+k_U8&hki?;|%cHst!P_2cpY6x}6(}3!1mA0>+n?jJ3y?1e|egUMZ=?W1B)kuvD)y zIjFyZ)Q!kAR*9t1pG#HzPgg{KCE>lx1n~NcorKz9{jMU^PXy<5wYRK!cXzp@7___a zZFs3{)pEoDN3=F~n{SC`=e=t4jO^~bSr%=699^MjN?CnhD)_Nnm$Ti`DOKl_8-E%$ zzTBO(x>zeAFi~4+xwU$IY0%5H5RHkwn#To^yJme&smtmsiRWG!LG4cp2f4fBLo?J> z#RKm70HwP+?_gRVK0U*8dWI;^y?$d_d*`#cW75)gR9Wu%PA|@ot;h_2>HL%=q!6xS zJix*zKO}kSh7dgM0vsi8a1LSpT&y@(47ahr#W8J=Y*?bYjq&+bjX8BXHRjXEMWKC_ zXU;!rTrk1eb0vQIh*&`lRL;{W_z%Zwq`b_?+%9X}&REyhOdX+iG#>A| z={K92masm%V-+y8SL*Q|k6^PtxKdF3=es!0ZVa^_JRWJ_)M2mEzrk*({G)fyf4^iP zPq#VzV@DmY@v2#gcl#xyUneWIOxmB(FiJnd=qq=MK(qt;?|Yq*5w|B*` z)w*af5X}Nx7Nr(<=noH>svjR}uja~9qh?FRiJy;A+6{d@8%~fZioddY4{<5Fc9iz+ z>=^+G+_((hRAR9FGoSgz#40s4nxv&=-=#(CS^GP_jt}hG$?O-)eVVwhA=WASaUZ`S zS{j0jTb;9_Ipm_h4$CDqV;E5tF6DNbDry${)xL~ZE)Oe(V{9Dz?NOIVDGI2+*1sBM zNQY`V6c(=7sK@ce^ku6XC1i{?1HlQ}pvh1OIn$caEgR#$G}O9o-kjwXdTwr1Gey$f z#n(SIwI|1!#!z06)XT3+(=dxb7S$Jn4+dK1$x2%Xb#wF9|Z zi?(vxF2~pYP=yfBfs2)1(?M>trrj^RX@qrnq2w zlPXYS6?*Sr_fx7Y=Fsqkw$98{-Nhw8F>oxf`=?EiiyZuU}+E7*j2B+I>#@~0R9YerUUm(Jy@dA z*{^sHk0FDKU_=MMZN8rUx7dHxGT*Q&)R` zon6XfIa0=VTbwoQ&6{X}27;kl> z(sODTjFed$bkecvd63&5rzxOjXTfhYR)8+Av~-Tw;)qCoua;sOJBAClkQxYm=x(uU zUpa!rN&&as_kbxz>#@a^l0kJqV3+@cRbb3_@L^3-E+|o@;>}1z^lK}Fui);Xj_7HVyDl+r9f9RD@8RB9m+OO3?A=*`YFf$SvAer#VzH#{B>2YUnkr6hA#W#i-dz`B~#gA;k7rs z36d5B!obBr%boY-vt+drQeb@jiti2&CjBBfnE5`XgG!?t zCc|L{+itIbQwZxaX9o|9?Jw7Ux*@zGj};dfo`e%8^&iA;5TZ zBEl$Z%p@iypuu5QDEgdrH(Cjhp-80e>ZCT2AebtrQ7(iTFm0Rq&F^B)FiRQ>{|+<% z)dIXmD53ry@H3wd-tgs8JV{?=e6k1m=g;FK!8+?~#J2wSZh7Vlb(W}pRydN9n@ACA ziU<-?xD4WkRi{>7kAFtlW=a}O?2pB4e#V=QXcr#r%*(Wj1j?2151gcMu?r~jphnOW zSheb7++SI^zlAWf3jC~>-{z~EbGJ2`GliV6J00P&V?wXyiUi63jlSO{m71@a7lv$4 z_7oaDyLRl=c!7#zbSUEyPw*0{n%(Yxqjvz}S)PeZY$MFWO@$x*ESl!@K~@KHeRQN8 z-ui~$*0`%k-Q$p%ZBDTdif|oS@#T5CvoGhih&XmL2wtJD{e{M@W3SxuYFm9iWq=g0<^^yJs4l1 z%HG%#2u;@16uN8Y#uD1&8~(NYg?d|S5tepDjKL#))J}b#dRHB=qAB*r4@GZGl*&xI zKz)l_dOd!xwMijlM2gNXy=E5pT$kvnIEWNx3k)0uip4SJ85z-tbr6+|X&sqaQM_Pq zuBAjvLg`D()tMThf+%$7a0xjwDG~D$@)+ng+?*s)%>AST>Vab?;PU6kNuGxVAB=lz ztKC+HI)_U6it^2=;9F45Ku6>oj=%o*d9WAl0rA6q84~v;VA3&SqO)8faBVxcke|wah_;f ztobXxX$qsYDT$$rFV)fCC?QPCH&qfbuhN1suuts3FFi3bo4yBzalD2 z#!%vR?XsccU-Vs4#Q9p4PPYI}ajn`dS;}N);rF?2fynQ=4c$Z8f9*{;^r5DQHq+#l zD#QM$a|{7}``E@7ewQqj%`2UuF?0|%YvN`R#byFX$LgOF!ysCUDz$8%v)@Qac5u(F z;0va5&aLy=ey_)?pUAM-si6|V5Hn?;#wejP*OBVL0_`i$(@2sY=}@b}1B&9h1xpV%b9^UA!6y`F$FgrwEgJ&9)s_KdR0Fs~fFzt$~m5 z(9>{K(2K;=uzsHDT#ZXj!c=Hwe9JguwavMbQw4VISy_N+M2elEo`-hB8Yu^et$@GWaQH=+FE7_(yTD+sq+OuFcwElxO!I!iIsR`htpXh}%nRQ< zJ3rheE);SZh(gFWC96>IMQ|?^al8OHd7!vKg}c2!CiZeuGEEzNif3WP4Jp?E8a*HY^u$atEqKJAccH}>V@ z6*<@#W&#&3H3QI|!(e3YlH{8rzFu=w4>d>!s5S%TmA6R;qH9%H)H|LA2g|?S(PV5_l zfpo*Hg(}y$Q=)JgpOYwOx{~y{IDNKbTbEVJwpUx9J?Pp~_x0%7JM{wbY{_GOXffrY zZ!Z06gLR9~OLX@LUZ}L51;kzW`cl~@Ji%{sWNyW}Pz-^ps~*NXv2W_-zG*Q~l{rwK zNnoU}j}Dmr%AM^Ka>?bP;v03-B>~Y(;R6gZ0p8XU&lbiy+a;wXA%XQc zyLC8AjeN(h^EKft{4`FBkyDR8?(DaCDKT9N5YVME{T(W2@y%B!XS+IW2Q|8^k{WAv z${T~pzY?Ak?ThW zWTIuI3hHA@D#@TK25FgMxXr9$QjsEOt?ff}@eD)5kb&9#IhAk*5w-Dv1Ao`RS5>?Z z3!`6CYg?t@?a@r)_v#I5e@hJgacbxkzSUJwKk{uMWZr& zwiej)9~KHmENRMbS$zyw4rCeYrnHLqkIjmF|Nh$j`}eIxy*KA#fBg7ClEBbU^qtRs zQAmIIjq*pes<#fDy~{D#j##_c z9^cMf=PT75Fk69`fiD%6&A!PJm_FB4)6%rxt`w-LD<{EA@Lop%bx0DFetykzw{&tkVix4YM3mvsXH&UpY88tN ztIxZ5EcS|PwEghzwxg8}S~WCnn@F0BL^D|R6-l?20{2P(omM=p^jVK7^?Rl^T+Bc> z`O(PvZWp-OOqhDCj93=5#|sFU`EA82Dl3mXoj8v7%2o@Wn;UVRB}vH%z&nm*g=(bT z=IBo-G$>PcTpdSZcV|4uqb~6ozCc37f!34uP9Pdjpr}6Hbe`*ADBCnfh|(tesO1tkYmOXlWV#7{7rj zC^h6gRq00*j?4H;dg?AM?Viq53F!>^2#5LOhY-(Hl0^OC*oS&n4nL+N+ErL#HZ0-c z;cdi!5CV`?G6X(64Cuh7xm?;Yx=j1I>CrtVP#YwGJ}-$_KId1cJLU zZiwlPoof6&M}|UQ;5@c7dyXfdN)NE}thU1$FSD|eYbGrAm|ibVyi{l4C&Sz$Aij+p z*>Y--=EjhGrPcso-`TZ~fyGVnatHgmMXNn`gkSV}3|q#xb_|!LOu#m_`%K7vSEP*P z-H;{X3-!2U_ip!gT-lc$-IdoF#uyuYVch|z13a$8<@caoeN1Ke-{b2IKf zuQDWG$C36hzh%7p;%Ptgd}eBZ>2|7sSthij$SsUT=*hlUg7CA9m}~ynOa9=+p%>C_ z7w~+bOcZv!*&NOyqW+~USzcOOfq4k?Z#q%juH9 zC7OgQTV2dcJi3(y8b0`~n}}UdWv|-ci+*-a*ro?!)tTT**UDJ|m1-w{3tLx0ja9qe zD!c7T@!S;Rw3s)s+`A2Gbld94srKwOX~zN@{IEaiyVjpReQL4HTYPs()WJR>7$z>h zU(%c`((Ax*El_fhR(7jtoL>z29#w#0QV6D^iB5y<_j$v>6CvZyYYIgzp7aK zQiXZ*nd)kFdTX!Z;1Pe_`+W1IcC%_}1p@a@93k;7rRbVO%ql_~j6a%9-kvvu@x=1# zYnA-xn-_F%dmnkG&mB=cUM$~mJJz6|R&%TVVmR$RjCi5yLGM0R zhbP!KY{4B~qs?mV8CJh5|M@}QpB42BXYq9DR6i^qpF32eMB2Kzlx}LREJJ9KOC4>* z-G?+5BH^v@3TP**)AE3-sUM0nZOZQe>Dh;{M3kK=5b0%w&CuxvjE3h(l~<$|z54cX z%xyjcUDUn!>LZ+R(3!$};J?u-d_mwXBc~YBZ&OJ+A4KG-RTJoa9OY?xwa!Elg@mXI z_OokbnJVw1c~%>o=JKQ(^@~9Qf@HaUd!Qvs(0Y40?9~A66zGLIRlT^F-zjq$KtQt< zwziQ)q#JK8@>GjGiW^@28{|h~~BZb?1ovHGn>D!hA2Y2ZT2Y z%1!f8v+7Q?95O5LdWQWr3!SWo7?k)`4}be0+cT6{S>>_HuW#y|eL-zU1e4sQ9!yWu zw-pa{z$9-oQO`r~4py2-^&-OzR*a27%IK}{N<~;(oy7w&L`hNTd9K%lz8u!lVuP9? z>_=a=f)ok1v*Bbu{jEf&IiAo4ElzOS+=biT$|rSrsOhPqUwpsGshA10RfQ#Ms@~Qu zFwTB+f%jntLW3nD{{4sRzT4GKfhY<{k?Ez z&FYkU4xpC6$I^iQ$O8RO_$_;`hs_;wKLceUz|44pR4^!OuOHk*t4bs zQssGug^2^7Op*Ch?F|P6-h=(ki2Vwve&RVUhQffU?=LgtxGQYmtpPIaMf3ERJT*7Z zmjC%ir`Bs-gZv{1n5XlzUF&!ET_r&GkrEzY!kuF;Ze`|(r9emF6`PC|_JeBUeoKXc zkK|$?Y{`^5IyzYfF>}x=Ak7G4Cz`R^^}VHygtT8f?HS~cdmO9AZ_rAw1zza< zLmreMWYtpEEj^v=aD4*ufL=9_g+yBejNLhmB(9$Zk;KNJr2{dN_(|qdwxCSIxJFu- z`nMK9+=)F49P2_-kLfdnJJn%xYJt~Qe$J46#cK>0c%vIp41mcK6P{_C z>rvV=oK@BDT}c7Twa-1dw{kY+<+ztl!^=O#IjnbKpoBi>N82kmOXYo$+hkZdb^1{EDC}(9$k>zIS_dLZG;Q}fh4Gr?h$UOxUWow);fVFC1G4qyoTu{RoAKIG}U0At>kRDV2wd3zHALiy;oM& zZQ_}omsBM7dZ;4AhXX>p#oMuWr2N;)02r4hK+;46ZeZtj*MezhLg_e?GeMn-0$0Ok z`1>1rZQ4SoYM(Um`StRywf!y;9L^r{uG`zP1YT8;=d%xVWYixE>vj4x0y!(2tC*E*;_8fd>>AWkvX* zgNyfMzD&&etc5f-(aKmX4oN1WAqXZVQx{Y=;e%G=I|kq@eNU5gS0mtNVr)H9mmJ;k zR?pEEx$J?E$EP%sB=tEB{^q%|x|pZU=6G1G|tJ z(YGwAKLU4OYLi;69!kQ2j1A;4!2fv%i5PAV1Ri+kxFlG zuSC!3BHfcc!Am~3jfgP}$fSS58qDQT-yj-m5*i_O>veP7yyWD8ke@`TFh1i_r7g zND;)N#RvdeH6D;HA&TSmo5N$%0tmwgF;7mw=z4GoL_KhG)!wg5F ze5c5pNWb$z{fi&PbKS?YZ!T_tIZiDRa{Fw1PZ;ykilwowwsYwr zgw14tED;|&DMU)s&2jar#Y{_77n@8ziAnHgZW_!`M^{(rAn6cmJv&0S=f0zF3NyfX z8hV|)z-RaXjY4QUo}MP*sx1=Fr=bd>VG?c0(M+;fisLH<4vwmZ#y=sJA^VK&?|C=| z^Y!BsMWAY#zus|jadFKcl96O5d&9g}`uxQqR{oeN;63&y5p2DD$)_my| z&qVxeK}hH=&{J+8)N&-6)M_BuNUycmU_1(68!z@u`T?EUb#gI{`HnXToU(wkYwM9j ztchKgr5$T;?I3^lT7X4DXNq<4rvc>hSnj zhLe6Ra6?z+@7)gn_Z1R zYI=tK9TURI|Ia%2LAnz?f4Xt)Sb4x9d&C_9UE6i6Ymavx)I;aY3z>ks=a2a;73$Ra zxF<+?qLofbhtqb`68zWp8kacaSa-1>2sF>@KaJGA>u@h=hkpdtG5o zW!=Y3ZUrG!h~K)6XQF7vk>hc1J<>M+=e~`^M_FtWf)G@utX}@aZ-kVS1rZL?zRN=7 z{P)W3$7>BhP?Ghq(2(AHO1LEnQP;2X5HvTJ*1?Tcxju%?GxB{`1FNJuBB$GqoLGQ=(n zPS_r^*MF!&5gcg5Y5e@joemKNUUVh8h_yIi-9h%0fD_Q-p(YE%8_)jdwtzd+fIpA-BfZRW zbnU&1E%rOr=5@>Rw1d3e@Z)VC->3&9pJ-E{t!hUfQ(q4%@JN&5YU9TQ!YwpT{C)n> zk+7uzY1KaY_gvr*53oD(($mN#jN9w~UB#pl&=&$v`z{_!Q1baNrMR&tKf$4i{GUS$ zx&aRDlm093BcVH+MaHlq8}aU4tZuHB<<|_z=u6Yj4|rPBiS=F?#QgNi$psNm#}?C>B<5QK-8(+HqYWhi zOvB-M_OUVjuGi?kDxfn-9N3way)?H#pmhfN`{iz(!&QQCCZkh zth=rdvr**^qeI2or1?w0SwLFCK|?yHS-s!J_NWui@t*R($@g!>k@)yVy~YyU7+o^- zL($4yl9R`Y1y+Ad)R{NG1S$`4L&lKwU7`1CZ$7+*s#qp7=?UAwPCJf-KT`;02>y?eb0k7~dMGOL+o zd>)*l=f4>tyY~q}hRMph)*8bdp{S_%^(S}&NU(IL%J2g76)om8u7RMt$!T0r@Ut-N z=eK{8?d%sILZrU7A1)u!_ajH7ULg9>Y!ruzhQCcf)!XORd=i^~!UWpdVtHpL0uDsB zeu6HK8{Qx;=%hL^VhY1rde20u^l6x}2K))-?wBAVprDh80Sg**X8=5{19!94oi~zm z>pAc!kLFZYTN$a)45;(ni345l3TLi}KW_Vejf)H5J9XC%K#RErqR52n0fGc{FrkH5 zWxu{!MpG;>+83MDJbZPA`9_-GMrg9E|47Fj@)c-NHCJb%RcE4Q+nNpYY7Dpb8`vnM zc=gMZCXE#@6;P;eG#gAS8yP^rssPu}YDmU)P6G@ZFzVRbQaHi4 zQDv1bHmw_ZF{||ELKFDFh`!tpD53KO8XHnE`}vI_<-2yxo^Y%N+opJEiT zYXJ$uEbwG5<3U+soyyWsVGJ05(vQiXg1^ccX^R(d`qjhaJ5+3D1^}0*&m9U=kia#@ zt~JqWK1P1l<1NcHQvc%z`mwl@5lqgKiBhES6RVQk`0NRao<`XB7bmUGFo`(|LwiJR z`>rtv+e8Z6|Gr1;*)1ag$I~E3JB`24s4C8>9{Wq8z9`_=TL!M*h%aWi!9LM=6ORPY zzI_M0EaG(a)GMYepfO4V4q*LNueL!ii$f(TJUo|`-x$oz07+dwa;h^I@FdE?PykqX zZs}FMe}Ccpkkd%HDhxYIZ~nP+(S6Xo%rFdgH{&CoGv4^B{~jjFxZ0%^j1J8PDGw|B zo}cskO;y%(siBYE^fW#0se7bt;Ke-e8p5Rt zNK8C0X(tFODZgXn1PoEJnW2>|e*Xk5i~Vygn%D|d_#8+IN^9DD4k-S%26$`+^hc?e zWdeL!PV{5xi8^?gfzjY+z0M+3Gi$)uvX*B#c%RLO$ELv^$kr7bIIoF<2j5mkO&xP* z3JD+CSu@WeuTkb%Zy&MhecBF!z=x5~5&p)vrE_=mw=&Ydv z?$f91LOETU^Pi*^-MQhSo<&eA=zZThmc6N0Cotho_ZFzg7M&M*KHemEYnBB1z#7DB zA*3U2`n~|s>cqm0CXgF4wHyC+w}1`X0UEl_T2=e_>>@)Ux2P6S@mX8NTL>`s!p1{S zZhx&QXY5VoTQbbn5<(pbch_vCLvo@=gs&F@6lgf1XsS$7FJ1O_v5C%%Y3 zHgKjo(>kBI;4}C}j?B10_fC7hGaUGb-@xpR*c>CIcMSmrp^fw;7M*NRky9UOO!P6!gh|nxB{?6x!j1;WLS3&eyl3e)UF=G`nYmMX^prtOM zq3t>Z;c|sI-z6@-hS(RATOtaWm8uLau02s{KYUeN4qtxL1U_&j)78~seSN*lqzC9q zpG{o^a%m)YND<+}4PP?$9EJ8v*gY;}uNvRq0<&;zf2GL<)Vra_hWArA+)OL%VukGn zTD+5Ck?B*F;7fty6}HUoG|`18763{F9|LXNUHk(|>Z3NQ7u{Wi`HC~QT5vn7PDR;A z9MbDVW@7@nI`_hFSH#uE<(8aFhhiD|6sAW8o&l{k2e-ldG9G&mhpe%y0(>Aj^xHRw zG6s2clEO6*{ae*ClyDb?n*Dez_$r558v^QgIdhHRF$U+I`0Y4)8gbs&h$wl&7<4dqkXv8ja+x^}y$R zG%Ng6EiAHzHH+ANl}X`oT)iR^iQ|*Hp4m{DjT1DCSq7P}#tkcf*##1S=}$@@@4Z3_ zU+Og4DtQag^rCzYh<3vzW;4&UT-ptHjY4&xW>2ewHyyYyU?~=!Y@KU;`d`gW_6P(d zfdXfAk9-xj2Ncgi^T%U@_QZuVk7=GTi&SjE7ife)Ix-22ee^^dqsHre<7O3%i(RdN zQf+6v1-(~T^W7xr6$+j?+C_q-(}MD?)5`9$b?*9X>L3#wIU$}edKp##e~1^?ZoF9` zh1VcN%1BI{*1SPKUJEe0mSEzMt%fWfqw5;;fLE&LWRJpZY`FV>W%ES_a9gjN>J1%v z)q!ag<)&rR%5REvznn|A_9!Zj|6{nP=wzQKwlIKfWIR(N%6C3PDy3{Rs7Pv1pk`Un zcI<0Ob&%Cw4yU9WcNMW23wkd zP~!8>)eh8?oU3b{E;6a<8yFn&nb1rWzRjuk>mAd)bUny*WXvz{JDTKXf}syjhYPSW$`yCB^W z3EqqR&s6#)CxfYIMW>;4o=AsczOo)~5bMv)1z5D zFQ9`py^5Z|IqnkuMT&Xd9E~UdV<#r*oRC*%m4-g514{7x1L$tuvuWi7Y46g!>B1lv zP;_UBS?Ha673C9rA4yXr)mD)ef;L4&b2Bn7q3!rcGx_bZr24mB#q9+Jqcsql<$%zK z&c~+R7BFW?lLk#ozkfeEzXnpLn^xTA;{&B&m!`rrcdD2CjR&9D;N(W? z!wZ_iHSSAXzz+~b7OW{Ow=boO-(h0yvrL(NE35P1q>}&<7%>%ScgN` zMAx5yZ)b|#9$fk~ajSZv_fiDUgNw;8OzmzZ8rF7#!G5%948&yAgqM z#;bPTXB@)WOq?#~v6okhje99PEO^Aum@JhTM|JWAa$YhG19}p#4v}mTdnv@$Kquoz z9%P1la|L?mzg>x`Qg#E^z1M%zcXo=1C=NNBB*_-d+vc5D8IA=_q(d)y0SR0UEkIWy z>3_NsQSMb$1n&a^K4-l0M6IEU@%-!x^MWJ+s8+k17|*(>&nG4sQ{zG1A>0l1^sR6$ zB4s;)a$zJQ5tL>=DA)Q5Tew%_;m{i`&X@&;dmuMjxzj#uSqy<;vFvp|ThYm5iUTQ2 zpApx~NMvr`?)6Lm$ogr4e;+t}AChVpL%8?u1j**GI*O+n?KwRqmTq(>6e_Szb7j=R zkI#pwh0lV?V+%pgm_JY+og+KP=Kxn{NG$8n-md>8fIp?Thm>Z#2dj8X$n!_DllspUrt20NP;xn z28aU8byHQ^YkK}A?I%UB!0EfIGX7XIt_aRGIsKWtR zLeoGiBI(Dt$Ebs#->$PRZ|dI)&qE3O#tUMzT10rlQ9b0@o+Ho-+(ee^KbfmH$=Ihrdw-13i7q zm~-wZFo&EyZBc$Y1v!7m?@of`zqlR{Q5g{NiCc-mjiZkVXYV!;uOxgu_4aSc`Co+r z2JFJQ?UMh3gN`Rbkp+OvjNGog{kP`}uvrxl|I7Um5r z^^DL+CFIp^Z8Y^2>ox8f!Gxi;Vy5cVO zSGO3fetq*@n$tJzW@n1CowZnJn;KkOzrHuOzLfNOZGQ^ev>CFqQ`=xo zB`q~MOxk^Bx16k2u5B2X`I!1AG9h!66fTwGdh=LX*(04H7C5G>t=vlI4o-%0mb_-W z*rKm`4L+kp>JwS?%J#U9_n5S#AR))H7XSL>p$6DBA(j)H&F-LX1>L&Xl46$S%t3~^ zRkwfhZ%@S`>Gr{xXf&&*@*&7d%@u?p^|63OeR}$>oNSJ9nJm}i&DnG+oSp^Yn8l6~ z3NHXl-tp@FAV^$kU<9Qgc!90(#`?9({PvXPZjrFfAQBn-G_spl{w*B)+~84izRHIp zLo98^Jg(OHC;`T?^wbs=oci~r&*cHbUFSa^bI6Bl`GBp>uuU*$5I6^%BKZ%(NR%W3 zcq_+FnheL`Sx|%lsrq7^*OSam>SJT7|M2C%+5Qe_6kxd!AF6tEKzhJmE#7}32MW1< z%Tbd253G1Vgx1Nfek zg!96KxZ2zItFyi9bX>3jYOS1lVRx}QSk5BId&Rjo)Ts7zqG2F;nWWw+|6kV`^ntB` zy_2sd-r_i1Cgl9u{Xm!`yTQ207u7jfwI(4{F2$S@nKxc(AYuEc=EXq41@7!Oztjl7 zr6thuXZ(n`y}9$N|A7f9_`xA<+8-+=DNgCK@ui|k1{3rVfSB*-vi*%+5A&VKyo zts5&!$Z_r0Fj+Pc?2XtJjg^(EQDI?ShTduwTbcWWF;sKx=_yMk!ohG zb8?m@rChs~-4bV_!oTOf`{-%qyyTe{`WO{M;p=>w0=zu#pD#qYaBe2;Exr#b(Xg2a z0u}hfeaF4HN916Od>5lA8>G>}_5IHyDJA1Naim(Z~)#N+t-*3Ad zI2=SJjsAa)eRWt=YuC4MIDjHxA<{}7T0ua%kw!^rr5nkiLq$b8X6Wu1P->hZ27?$n z2Wh1n$&n%E+XJ5Ok>|Uv?|uCX_jS$Q_rCXv-&*Up)~z3Ba#ghKS)A9FnOo)%dwUMrLYH_hWGWiTjuHlq)7Z^0RbR;>v=9! zLh8dFYabGH2!(ZYP;v9G)Y@0uWJY~8JX<7DiA+v0k-f2Xn!>y$ge#0v&BEPf^r|`Q z!?IE8EG`{LdfaT0PR6l`p}6+ga5t~FfsUxBgx)@r3iz*wyO`<)U@EcqGe-TJ`fw}0 z5;L)+M1I;kEtiy(PnJl-yR7HcqumT{AMb3~S=8`MJ?@@#dGI@R_S^IRgg5VrcqWef z@BTdaI7Q#Leql20<=}5J$*0?oc!J+e1Rc1Acl+z}ac8j>#WT;rCLc3u9qVfIr8Jhl zWo6GAf0oHDmv6dmsa^YVFP@u`G7}ZfY0EPAvqV`mKmbNB7B_wbI|&j%`Eg~6fJ$|_ z;#sX{;`4n@tT?X(>gT#=f$3fHG5gvtE0EtBO56<(6ht#_+*t)ZMCDwM6WCcKl!Z~S zpYy>#IG$@Eg9O&Le#kZgb}hRpK>hTsnyCq=DEg$$=s1Fzx-APCGZxD|8`g>w|9RS2 z{*E8Lc1vD9h8t-)@vVVO3G35@S)^W>afwuw~QA_ZOcE zgfGa@MO={Vt03Ju;}iXM>Sch{&@XsEacXu$Z{PfB6Vfy<18i`B3+DZX1hPQ3;YKG@ z@(*AAq&1%x#LJ7HJ*yp$t@7zb!NxsCT`fXE{00wHI;f>sTFBDlJ|^D?NBN_Z`vxun zDjE5wEe(AN7%xgRcU!}mJ$NqPY)s(iP}<%FR-AhxmrrxN&Baj=bfDwX^|eVJC*|() zFu=l{PenC6mhds>La*WuhnlX7W68(Yi(5r}YuY09XstQO^>B1&^HTJYs$xREdXC`2 z%P_)z&fJ1$pG6HgfIcK&t=``Xbm}agRstTRv1#`#H7_GW>I2mFeu5$cU_wa41c=b` z)UWr`FP=@xHXX<$9tE;iu1PXw+P;PoAYP9~%hW$Q!G z8HBz=J@YLM`ULL&-FvG(;ISgIk2VGEHJ#=P+v(&>^*W@Y{0SBK2XB z8JS$vNus7|3@xtP_d4+kvKbX8joUk7FOF8LsQ*HylqDoW&I{phS-S};qVGn1 zHK88XkCCS0^pn@&*63_Z0rW2BlVgg&h zFGqn-0s}7-ASzpEDF5{C4M4l!2CoYCH@_|9?}n?{xP9Pj1UChA>J4kQTU%=#I<+8H zk0PSNSOZasschHtjkXjtf(Nz9hkC)G;faH`wf2cWG-#vO!zkdt2A46#Wdf=M*CkWiUahF0(5mn4m=J=JVxZE*k*D>| z@U+(m9bzT5nfyv<#U}*uhJNZs-N>UxlL;Em3hSr2I;>pH9nC=dBs~6nu|E_jwKKjo z2opWS3*W6n(}|b-$~r|LR3g<}w=$R|)3AjB5yXoXY{t8-S;pDh?kJ-QE|>V z1ykJ^31+!`6O(vd{{?8sF83}Rnz0^?{Mk^tSG^qML}yTMwAeOS?Dl|X))9Nq%l$5GBA9yrfRJYZNM8A5`rRpfB+|jDHdeLS?8(moFTT7G=eCrwRXED!Frp;+kyMLSE9|8q|2M4)g}$T z`v7<~syl}>y{ezXmTlD@JurWDqlf7ZSZyJGAdE!;SB^AxzNo@{7@ZD2-YRkbu3Wk% z9nVD)oe5Tm@OT^bF4hn1t^%!s=bL;mxt7tk(vAiuC^v|w-r|h_=~jCSJp2<$0)(*} zA5UIKyZgs52BpjPyopxU(Aew6#Cb@8{Lbujvk2iu5`{YCo%jH4)*!Gl5CAYo@x&Z& z#YzEuPMX_V2}9@ zj@nGC9A-bM$8<8KJ)||)mZKfw;v42}Rf)P3mao1QK+S;b*sT@to!VU3d^jBp_jJ)4 zJ%aTF?__ONp^n6u{V6ls-5Vm=wd>uVmFU6WC-TN=rJ5NHL{{RQYu6=xwCmQyW{&pS z%pY1UPR+)r$8WtMjSfm1;pU~plyU%&s!mK7-6om|g6~A!aACb>sttr;Q_E>)e`039 z2Ugv{W2 z*r(a1D)FuFKL)o)G2+%gK=pGNhS3qPUI5pX0(f(n`$13(N_;0cDGR+WA|JTBUF)tg zTn^fIEQaPFSWHHwU8iWWCUrAnsJoIzUainp0Ci@hW8bFcVc^3C0GbZbl;aQw=8GgZ zD~@X%_01UJc}=?ic;zHUi_boYVUxkUjY>HGDy{$u_Lq;7I=w1qeESUnmI@TW`X+`= zHT0WAm4l7Jcsambz%4*EUDiMLpuSQtXk0nYeu^q>EKHN|WuEU!xdB70p(|2{%IP_V zJE`MS!I#u>j(mBuknUdy`T-*b{r0?>Xsu1lu>2FVMf#X9FTVyK?=wO#^07(#ac?HD zP})h{sJW960WweV;XLFXMkHb1K=*l3eNEf7Y=4)wls|1mhztdg1@a(mUp~G1>~`$S z3#OfcCVrjtFNcaXFQ#k-7>_rbfU^ASJtM#>7~d7+MVIZc*@`4Vlx=s9=j5G}wjP#T zahO(S9isy^=PfoNu2z-d?XY|R$(ERXh}GpaXm@{~nILf2)W{%C7G}24Pjbbaf10b_TZ?UY~Bl0-Z|JM2bRmcg}aItrk# zs};Ckc^7+dQl6}`yM9abP+_f?yNQXqzCRkxtrl{5dvYoob6+&m{sjs zde zWNRH*RYwK|M}?*cm1f*8)|m*lEJ;8`0W0hzZQ#&!4D>LR~Q0F#%O3@!jMuh*(SzXxUD2=Vgm% zRn8%Nyp80Cg{LCWj}3HcygdCAg#O0r>Qv*$HQvhL9vc zUK=l~f==c2&Od;>HsU!P{7qHnj`OPZz({4g& z2@q`T6n~~A@N{S+9#q zFl=LCuZWFl8g*gJJhD==@6V2edVJjaq*!G=a#gUkSH~6dS^tY2rHzo&k^6xUiefP( zk67e7G-|_z4!feYy$llXwl^Ku1KW}a*P{O>KnQU}pI?s?emw+WzSAf`PQCfd1<5=2 z3|G8xS)c4ii_05CXB>>5-hVK1!PFS48a6*`03Bh%pkE=RumwkTd$G$dsPT+$P1ky( zj!|9sE@ZTjRkbAd1Kw79lh3b#X40pvW+tZ7gERM?=wObyOyY5@&_n*awUaE&3OA$c z%>e71csv2nLq%pt{{+V}&A?eXo@r0SQA8d`KS+0S7-+06B>@K zxQ*L9JU4(usVfiS7nDvh7*qsDe?{gfviUCOa92rZT#)o)~{mUGk-W_?B z$5tmkpvAH6c7{D?hTd8a@(l)|eo45YqkD&;{n#pts4q5BVKFLke$e$E(sq=zFVH)X zhV)+@Jzb76kWB3HAUwSmx`y8q^OO&o?7=ntyG_q0ytEtTOuSiqcR#N7*lDRo_}nk< zR53qkFlO}G^4}4WtSGyqweOrb$X6{9ytZ4rz27k1eJ_vcqlp--+-cRPBEuCcXok2f z3Oh6%7jgCK*d;DZ(OB6E@3fv0S#&5h#y$I7203NAkwDS?HV(m@RSKN?mp=2UQRbzeJL%O9X>JEWTaW&wS7d;%MUIn!wI)_ z(fLD%O0>VCw+28P*w8QzHjf}Pr1=Kz0dyIy?HoYpnPp~9{AX-HKx6`#0AH!IY+h_e z2%tgvt<4D%ff8ie1$(t|i8H(7-+p*G>`b#is$2)Oj+r zLN*}$|ITapoy(j8kPD`eJ@6Fey($FOf^cjf`vAz)Xh%0Qa0ZJ1&-|KYWOMrHulQ>M z$D;nLF}C*=p}`eieYMccQN8W9g{`M-XiZT+W|h=^Y#+S|G~mvG=g}Tob9ehOCJL+B zWC(BD6?1z+W# zkB+#On;LRZ>G|C8ZPAnon@7`xLr=fyE+S285ST6s;r$=KAGTe@pksm`Miay43W5x@ zSU7)hBkwDc99K#;F&eZ)F8Jg1b&;Onyq(`;gfW zer+7!oJu#DWn^mK(y>)fN?V-X&>!j5G~*SNp0?=Brnkk-?tz2b0kYMiJvo1lT1Ex;-&0t$U!A!k%x$T(3XcTI_J`-i+hH zJSMm+3ki6ll1E%f=&bdyZzadg&eAB7?mK=gj~nk452JDLf~vJ7WcLq88&JYGJBMuJ z+FAT`uzw3o0P8Xd(Cwxn8y@`C(C;^X0tLr4O+H#`Ug@Ub1m{(6ayO)JSppCZDDpbf z+59l-^#Ad3HQz7n0i6=O&pIKK=^aE1MV(+Alrr3n{!q0#F+4R%$uB1LGX;+lXebE2UUka*2?`0)%R1QB zIb2oe39uh-B8K&0<0dK+3C#Ee zG(Y=f?4CW4Z!;7<%eVb&YJVaCI5eWNeC5>j%n?mo2I!p{U@?(i;mdv=%8e@drq17f z&2MkTGZgxRK(dRTns|H(;7nV@)|^u6Ml{lD&kT+^uwJNf8PQF!-Ef|9p*EA85|RNG z5o7ly+vc#JvQpu@O*w@UQ$^3vJIpee6|X$O^LzhCYpKj_iNAqWP?gwMQqC`hvvMX& zSC*#-ML4@uh+NHhP##v}yi%X$a8l!fw7W>{oMEI7xkqW@GA>p-i(+z4G_WZbw3Kku zl3(@>)G%)Atnip5udJV`gN>$ht5Xb)9kU?Y>a@{_gy#(YcAI|gT1jGNYsWJcubZ$50oX~+o#r9i zapgfZwJ|X>?+o#d-5YPaS;}m@yEmRM&f-G>*PxF;V`}w9h5`rp3&Sj69?U4@zZwQy zfz~{Ke}iHUKi2h9TjKzh$JdK~dr zBUGD`CH~h-8ctcAgYMKvdfC=(^wpJl1uc1uHV966Zf||VfnVQhEvyT2eo!rM5up{HSyQf8SpxX$rBNgI_wF++_EAPwT5bfoO z(sz+f$P`ogf@PQ)1|A=q%(@mmnJ!k;E6Ew^XyX6Z>+#Ds_Q(Hr^Uusu^~WM&OJENG3Sc}rWR1mSOMnCN#6Izq`B2tQE>8! zP}lIIk)HkG-un3yYNUw#?#GJP5~HxVj4!Bf%Z~HwJCM9hB!Hhv0sJ%yB+YPy{giw) zhFo9Vo4()z8#PW2v8p>om`n#=gCSn<7D>nkMTrBjrX3XEe%)X z2pNe_Lt1YPU*fB;Rxh_^UK+GV85mUkz3>giYCq^2N-yozy1S`qcvXx2zWs))z_T9L zg`pzi`*9oVWxfMZ^B%+!NOefXlw)+3$i7jDPQlxGkH)}kBa!8UoaH+Gg3sGqWehx& zTWjNG)y>KfeDC?sW=v&YvbE-W z8{5>8faw7fe(-IOdY$(rk0UmgC(+-UZ&C27}@82i99@B7VVl z_#`WSHw#pA!#M`0hPNJ_mUZekjQHwxx@JizvmiG?y&|~4-{8(zEQWRoo&4Y& z0RWg;14syk9`=*~K*}3RPrURlXRn^5>1PHo1x-kpmo_o(1EmPedeIwuWpX3pah-xx ziAi1dQ28wmy-uol2dYc>j3cWU7tG*w=5dR@FBYm-SV`i7iKjCTlT-K+5H;N?F>8v|t-NL1 zQEAugQnCT-yiJ?w__m@ugJD{KVR_>ofGTbP*3F>?XR`(n>g9NgpXlM9w9Vwuop%?Lb`zjE-%)bWcgx+Wk3;?}=EOedlorac9!62lx! zZ^Zt%4oUms4=U%3nV#%hDG_iw>ILwOboZ9DR-@r1>c}c@zO!t>cij4wo!2xYdd$rTQ^%)6 zPeqid82g?`PLA~AokPw2x%m8@1`(0hGVZ-;hh|Zj<4l^@^O+tShd~s<$J<@_d5{0% zFqzw=z$VJdSgW1F&nwrT-<2^)34B8bUHRFH&eX}~GZj;>{~`Jh30zGVU+)|L6OU$k-8|A zf_%8v!Zgcr`Na)GG3imGm3kkY!}p8Qpt5Ce*%VAvmh+Xpp=U7Klfq4C(&xOXsok*3 z3BDgqS=zt+wSf*#xd2NhRP}`mO-<3- z9Dd$2L`@;nC>qms<@aE92JJePHw`%>tv|9KAKmsKsfXIP=ST5F!8c{YWN%7`YhfReSFbX%Q}bwo z$)p8!T;L8K(91;J#>V*pi` zUXMfgX{!F{x8dY-1s~-SkA6UErfQ~-&DiYbj#uH!%R$KWiGnd%cvCXZ-bwijKUFzwK%nfW2GU@HyuCq+>(@)%DG%5gUm;AaTA&rfl zmJMcQL-hzPRW<+0+6662GiHNwWkDlz?S8It%m}J3uvQ=3;FoS+Zj$a`y5u{$eSene z)-B2AK2|6iiRtJ4qPDg#H4+x=s8U=4%%3#y8= z=(--MGVQ>{P`{G$&BRhH#klj+fX3lK=chHL#yE+ozK&gIf5&-bT89EZFN35FdmAdF z%zb`=dr`%t{DAUe>!BujFOv~WemBEw;t<>d9AOoqQSy2*$_bZCowE{F-1_puWb!-w zY{368&_V`*?beK_VmjUKrHksh7Xo=Eq_mLt>-Lom_0rb(?c<^Tj!^Hrg)9Qh6AocB zt7R2|=)GRS9;r@GvNF}l65+c|Wa>%$>Z0q1wPL{|pTv9*GPHdi58alR#rLkE?YH{% z6|oFu+fI7pF(!6RfHw<@DE$%!DeZJ+)lvqrMfKDXyVq3P9`o z4aw)bUmxK6xo@)@pFy$W=Azp&OloH1nM1-}Dk?1(QPM-Vjkn7R8W5AevhPRM@$q*5 zS{l$k_AigRZwY-*~_LWXuchK0@wW z$45WRL|7i^0JGbJyW06wtlPHM^LX(Lfk1kw)M=+Wsk*?>Vm@XWkrP~p!g;S}4`81n z#nDq@!R=ilsTKlk3WepcRK!Usn_e(C+ZvLR%ZPwaj zzW>l5wE<1D7+|}8bM)gNU90p?XQ%bNui)CcA~2^mV)Xo%eu-Bsi>lN1TA8<(UOfqs zLUZo<66YT%#3bs$RAg1EohA)fm~ITwFs&pmk)|YVG`=4)_|WupW7kc7wLeX~pIFJb z-_z5-+*=s?g>bs>_VK=B)x5C?Z|w4*MR_o~uK|&xbJDoAWd8{sbn;!K7iRQH-SY+* z)*eM!4ud%EVbQiO@x|@W{l|ex#XA9i zrSJH^9&1k2ucKkw9}U+j2ZXL^#Rwkc;+L!NFogsaS{F)l{JuJ2Hor8-qYKmr;fJ%Sk zU$1AC(J0jUNzDu6vQ`j7c~W)9j$H=X`aMnEmq zf%I2ku6y}uruR91;PIBBzoy@KbK*!%XK1|5XdP0iZoLfrDMqX$vfjYNDRIt<-RH2( zmfeuR-%LMu3Gk2N&QEu9ACq_Py%^x;SB6o2kHJXzOyErpJ-*>)BD_2-<-a0O1qET^)8V(=#VXOUZFiX8nCXO4`(u)Q@7I!aq(QG0)bEL{=6BI%C?7Rw5+l_wUW8S`ubj|$ZU4hE!0 ze7yg7p;sf`-mO1q1o>Op4&Nq*s0-ggt~$%7V&gDum=LsM6Y(Er(|T*(ez>Djfy zh1AqxP#;pgMW2lE0N%HwzP>ba8t4Ueto8F&dhxYQDSV?y7OtOSFaqk>65F)SXK8x@ zADsW;4?)GJdqg7J?3f7}RDDvGeC#rm(cJat#ScH|fmm7nG{$-k2LuE-N4rn> zE`up!iTzsQj3uc?tvGp@*#{S=H7qu zdaikIQTd3Xi^=RN~eje`OOXjmW!Av=r@L zMRU$RKE*dPM&I-}ebEWv=$MTjk1QTnjSwkA%@>RR5o_QtYCwnTfA;yFPFW^M171n^ zQ}RYJU`_JUozC@}kbc95k9jR7r-}i>|88f3qtp0$wiYDeyXYUl?4+YoQy71!1H_rcN-_NMC1Vr`JcA+dEo`g1$vOtPjptKi~(HPszG@`Ada(yc?TUJ z(EAB?URwA7ejaEvbO&*|(Cb%jF=T5!C4=0)@*a?!=2!n^+`r)``E$1hoW4KiV&vsM zf4T|GNyFCM)wi9wgn`@X#9C+UpWgtD52#OrKHb@QcY1q*OTU02qOfP8gwdpZpIfdf h37^jds1uz~Cg+LDXbyc`y8!%CQPfnZkbC;#{{XIy%S8YH literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/soft_hard.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/path_generation/soft_hard.png new file mode 100644 index 0000000000000000000000000000000000000000..a92b819b94d1b25d5e94a98bc2209343fbd0f1e1 GIT binary patch literal 69601 zcmeFa2V7I<{y$!+iWZex2bZd#wGLEP!rmJh0c3@Z2qA+?7dh(p-Jma&U_vdp?e>2e2-1yy( z-+lAVHygE%su_Os&6?B35rcAA>H`yj zi3y5G2#QJ>i-_)nE5jwhAL8Od5>iqYOa1N8D0lXN2rLof>T0(SrXemQ0){$hCJLTW z0av;hcOO6Sx1W@Rt%R5WxKj4;a77_eCv-4iUJY@$q!3&JdPL`_F+z7AOch+aVq8$* zFHMxa3l@4r)yWI%23j;kMMZ@~pnpN5k)5NR7iPr}&>nnIUN{WaoxKGyAu%CQ_|j@o z-gfAv=A#4+Qzum)guAD@wyv6?y0Z>md#R5%!2`9_2aUy|UBQgdm^gboaLFQ^=u*oG ztd|4IYpDq=1-1{azE4CMbcOzdtFlQ8ez@C#WwV~#rw-pI1>YyF%)U@jWnIAbsYtO0 z#jpu)=jrOG?rUgku1(bO#ktr!!wgM6o@03?H$P1;I}axW)&b=TrgQLHnhXw;Vl4}_ z5ZDVB5rIoBEgtQ)JQI6jsKE$BT;3x4Nwg2f0fl2fz4W9v7VGMb@%XUO9_#LovS-Ty zdqg`gFD(AUZjM-2_Wsy?Jb?IoFgny=^a-h)M?_xf)<` z81E$oI)U}}#<~G5c7<-J*x9?Fy|6y+4yssJEF}95C`UUVS3s_JBPhFK(2(kRV?98t z9nND(E*vp_kWo=#O{l!w3KV6j1sclE+YVTlr4_+6aK7k$Fcm*HKx0*dqk1q4f{NG) zq@RyH(L?NnrmK$~Q3PXm)KJ7;4eP55cYr$(#Nh~nxUapNy)VMpMO@!VdZ`~l3ysng z#hq|RNNc${i8vfpme3_ggD32L9Eb>?6L4*JU7{8qp{DF>54UjF!l=OPkf!isZqi}~ zMp}3+HDxrySY2G#`4~(~?HC^1_pneC!5C|5h+CLxJ0dVzV4Vhzb)JIcTCK9L%(FI;wiCHhWDC5j#~ENk=1gUw3aeJER{@ z-%Z^2gqz9xb`0Lf9Og&VHP(}~hZ_=3z`R{`%^W-|jv8Y1omKECHE(HMH$9v^L4=5c zS$Le##7k%qwTK9$IROFg8K_DV9ge!FREG6x?@a?HO)|G!(G|`v$ZS)pb_)19X7sX)0%m3H(gfP2nwXR>>>Z6X?U&|u)%G<<8WKN0uR2ES=+Yj+JVae*6Y$#w ztOw!+bd8qQ!ib52b%0qki1t7pmS}{)=n}y`ShQ7fF)-5hMi?uL=sLUL5YEazdPual z9zl$NFf;c?AklDLXDvSmXAQd(Mk0QCs$wDtBRt+tRb;6hBjRVLX77V=)_@^QJ-l^| z)xkK&{B+e+u)4-e?YhPqSoU~+NH-BM*D)VGHFX?9^FKS!7wPf|fByoV0lyI#F+aqo zye6`F4LJId6!@{Ysws^_Asu{AU{vrYV6Hw6M}d?$1C0Wl(>GEE+J*4ZGuA>QjKuH= zj55S!f|i=P4?+#J5mXIOBaSfPCq~flVTcK^_IJ z0{ox19mbs%4nQ`IZGeGMMX|l{XG}b+>CgSldvBwO0>O{B7Xf%2_K1>VVr(bDcJG2P zQE`}%^ooDPm)3!Q?>a@rq$Gvd%}y&kr??1vEIYQxM!%a6awUJotARdjr}*c4f`ZYH zd?!0P^ZgTt#qv6=uoR*%-U;K4GV-vqhx{8JL_eU-$s70zxEd64f~ePZ*+cDv!8J6L zmBIetDmZU1tPASPca~!ez*QA27#-sckyiZQ#!+bzQ6V_ndoMFpR8kZ~#t;)$vQdJ~ zu9Z9#{g3ic?0F>v;Cu|Qf7!QacyneF5?BrV)raVOL~d``f`UG?F5BKB_5UKYk!XN0po z0hmkCcWp+Z-gah&uJ&$z9w(5lBKpqiczw7CWSo|Q5Xe|*n!4Eog9QR8R^Vd74j{~6 zuFhcmmCl!dG8VxAQ%cZR)k535Lwhg>&JT^z(sXjQLpop`pa8&Gd8K0((Srgk@Z6s} zW%VVeyySfT+C0YQE9W61*z-WHgB^S<1p=CSICC>SB5?Fe0hf`MFQDmCK%)r-I3j+) zl>q0C_XCbv9D&3GC$1%;Ya}MFr-|@mIdmg2B5?e`4WLCqJJ=Jek2vcZh6XOh$r-pP zG0=|JgLY-p>_<6cg#oM*btfr zxUv=NaXtpuW!-lHZp;A-_#R}fSYK!D{3#%0kJ;SBMZ6>RxI?fR->L_Hu6C^dB;4_coIxR!Ve1?3h-D&o-d zAdvdpSb)CjFo<^uATO*rK2N8W>jJ!D1$)pM2?$j&*peJTYf%S$Vcmn)`R?8)VaQT2 zstGj2%>+oQ*2*WLQHfwwmWHB?p;4jmO$!Pyp;6!6`@*Q~fB-r;7_g89Ryg2=^|oUl zphW+D&O;P9f3_!m=R72&#r|GI0I(NPw((x+O_n{(eH>)lN? zh}7?SjB@w{(0G5Q|7Qcf6^U=*0R6fVPKabCrV$S!GrvVlN z5WaU|r<6DhE+p}BkRl}l6M~7o4?WooT%H|=_3^Stu}AuA0p;IYh9q1>NJ`@Uj7xNR zC-{G7LEd&=Xq5Lqu^>2rCPAG0E*$@JTC#hy!ri~u^OLBU9rpd164?8A`LcpyNSOa& zjrc(BzpNx+Tn!LVv*jEINay{L<}K0w|A6en;L@MUzBG`;_i`vL{jZn(e?|rWX^CI9 z1c2vu(D8Fwr#&FMfP+~7=aRirk(bAE^ZVGUz{NjHS<%l?_V1rY|Js~lB7fbI{bO^o z^nQt8e}y>zMx(+;&c7NJb}nJrdH&}ds-)y+MIR>pIniHMzW?_Q6~IX#ulK267yUE8 z{y*EONJ{(z=K3E~@GlxNNpXq4PR4(1&i}bag`HIVGo$hk2PZ2~x<3oo|F47||3j>V z)ISpe{nJ+B-{=?FdE-A5;s55G=|2x&A_&S51O&l3|7hM5z?#~=b}$of7BqzP@U=sV zNdPEQ^n}~7_qk1@<=m$BUw}PD*bu4q`#dO8)Wbp3lmO-cQ0OrUkn59lG{%EmuA%q| zO_QZOcK!h8Y2eN2RTk%kf#I?BJ>;ZR|LRpAQ#GNbAaiBXZ4%`6sal# zAUkvMrSU;NQ7ojsHx{+5Axyw8fC$(tkE>}ASn}vW@qh-1+jkwV`Cr~`+rKVQCdV=2r34H ziHb@}h)J@uneWgRX$hE+$clg1N8lB}m8ck8NDKyJ-&h%KOTdNTk{_L!|E<|a0MW8A zwLi1{pN20Eb~vYZ(94S4Bh+qS=k1O1f~sHup+w-H0*#>MLx>XPhw)~Cj)06(5S9ae zFX4_-ViN4%?}0~f^BwL8^)x_vVL*2HUHbVwhA9L%13eCbnjee@HM}2?^$X(WJ6!YQ zA^*?BSz_VC>MzaxU!hiPaOSI@`s$}3wE~6hpTKp}QtvRlf2mqQ!Q4kqQtC5v z|5vEhU#LD?5&qe`+Tm~*dk|E8kO_O=ydoC-FvfEPMS|=Sdr>Hx{9*DLiV~M7`oBMq zCMhlTIiDcPj=TPKlKX{;#Xkz~{wu`xFBIJUo5Xg-apPT;ggNW*^G}sbEKwgk57dDz z5gvB`%c>|KLHx*mN{YX$%>8#OfRr@*2)sP;e}w|DF@qK15U77adD%g4<>0W6P|b=P zDD%L$FA*B|{_Ph~l?}bJvcgi^vEN#;2eJ$uqd$3_#SP=&0KGi(+0x?=?fl2Z;4ADt zNECcpW!5K4W^8^w{91=ZYugyXF>x zYA5CRCL{CdbJFp()P?yN|9*d4dOL1y(M)%U@H35HzFEbwdfoTCl|H&SVto7;rH;)i zA2ly`+%CA=z&88J_Rl>E`t0WL;av6kfxmxq`WK~Qo})LGhx&MOQi1&!CS5nBqLk3d z^)uq*N7y?63l{x&AIq~4_v|(pTXS{)7Z$9PF#5MoXuy89`1|iu=p0&GK1-+Xcked9 zZ&;q?qlJ-d)~##sC*5BE1yX#UBD?mZN0xgk39nu~SgiE&)ED@(u3^`=U)W0m4+jU$ zW;f_Com!I{JT0&%(cJ;OX`3$e}on6?fKi34MVj33q`;-pwc~ zSpQi=k>JJgtxdpqDbHbK&aa>E@{3X|7((W;*nwqzdnaws1IMI+u-Z*>SNXUdX8QW(cVc*!vDK-^u?`_Ql2L=in`Cw_tgg11kyVq4#Wq* zLglB;_MWXnDt@=y}`dArkh<~4y?GUr&ApgbZGIJs{H zK%eobEnbBTyFM}_b7Z};4_WjEbNv@5SxA^-L4kV_#M zKUO>$)pKdc1u0nA)o{mXvQS5;Jc2ymryC_lxI~EaYQ?m8mhH0i9o_$7J|YXy=hA9c za8|dPR4G&}c9!3_dFS3;9xcW%0wNoP)+trQ-!iR^xz zNR7kW*f1)Pxr-;F_N=7ap(6lQdfRXoqvqGWw+GF}R5qK4f=h_Dk*jw@C8cUHlRsM2$`mpyZMfV!jz-=Gk>n zex;?)4O`iP@3KyHdi(0J^w4lt*6Se~O6Ims?|KBI#{}7zv;&(aztd-;x12Cheqhc= zZ$xe;vM-|cP2crO=hXD;f_bfnWQQNxKfAQ6@cGr6xt7|ADErV6_q?*g&T!$N0iBR` z{ck^5#~XgI4(7uh;n405{p7*ui=aL^%hzh{=1HC^rgs+F-i==z&SFgGkz;W+(&#vU zKYHaUnSi>y5?Z?SY^1&6sS&QWOA3Q2R&PUWy(Jk>!jVmUdMAX@N$LkNz_nqeHPqkfe-Y++_gYUwz^CtNtTG#%G0gVs~_{v8Ys-(4>gHGjI7i*Cv&i+N}-Ftu}E9U zCATnD-{ReKv9MC=_0ug`ZKH*f#c83zQ@8Q~&8f1Z7B1=GCP+)cTbiLY6P3cYh5HbD z^L{!KG|He(&f{wPep|m~dozu^NXwLyM`@4HwwapkNe$)idXAa8letIrj6+qVXii`V zIV6;tSN!%5F2d9c&B?b`G)*?&h``Ufm+;G_fL6L^@2B@GmABs(MU>9?7G(sqU z>SfyfXFo2O-1YnbzC6B)gTv?Sl7%^_^-9Nf{zQ#j&jpLI9oQnz8U_SoNj5=v1O2%m9m|T8a+qj9T26KgQ!+R zkn+1;>G%?As@ufDFW-I6YND;HDXD-<;ySU6VOF z*0A5>^%|bu6#d|WuoBChdRmjEFnYfC09Uca0(XRMTxj6bt&TjBK#1>I zson816VD%uTJJK&JN)iW5MyVqYv#b!Oo{Ph8PsDqwr)e4Cn_}D0A{PFHCq<3Pv2x zC^)2gc2lf%LnkNC{lp{(TC5YU0o(Xz{Z~$LSru zm5R*q(AKTzQ!j?3UaIUo{|HaP7v1uY>|PZ?we?UwvvG%MMcpJAia<=ODSoRf1=OtV?5m!%#?Nvc(sbNw-#w@J=Z?! zKYT?v)A=v7btX$Wy7Z_em9ZME14bCbBuO1w0L&tCBE>qgP5M^sx(eS4wT5%atv9a-xMJCH?|JrRfHp z*$dMhfjoAzQRvv5I?MPl*p;B+sd`PmC|espJNkz6hbQ&tCn9*HZiNKVQUmUmVFl*< z^T^e$E}0!2HVK`fAsD9>61#2+5?P&t)vRSG6?0T?YEZn#T+Htm4!(oH&CiT8M#h37 zNZ)cc$&T3M#LMa`&@8(KXAaj>IgR*rG1%o=fOeZ?YG5PNqc1$i|5+{8f004WD%aSN zI8)dRS;@Xv+<`|EI#c)R?Oi#0_8E}55N~>Xgtg;u*WBPu(T|l8k9K>Yb>1>$t7X(G zI*no-K_`y|b{x)4Ih-Zyfhp9vF{i!I{W=xB2o&TZu4HRj*XIG&kW?kCad5zDKy*m!M+F{>+DCV4|Jl{ zxP02{Z$&oIBs(8I;(QR)Gh_?g?qqE1uw?V`lk@XDWZ+ZkEN*X5F-2AVU43{;9 zO{vtbi<6Pe@%wLoBw{788$+^u1EX9hHw208Yy5?Whg^=8RmI?fT6~C(jsqKNUTt`u zkiS?phQsAW(R&lcTb;^{o|WmzpMNvt$L-DYdz0a zkEy=Nz!qws1)B0=&f{)OowuiRq^#48k~S)Qh@Va=kyso2wwiaUT;7=(XB*jA=!ri2 z2acb=6up+bSkL=*rnl7vt~lRRB{e@1D0iJF$ZC_H(+LeXX3J9feSMXn)!I-q;qEVj|xBI zJ0?m;eN%V7T{z-Hi_MyAwy&2X{t>ree)ax(F~srXYaLAKQTNB6T&nmX=Xl_B{GJZx z=y&bZ#ef%`?*qo;%D{h>0spnI-{4fUem_IEiYqFTI_W^~%2Je^%aLYUXA>l{#x{4n zNuN1GRB=>1Qm2uynIm;<`r?L#vf;z|2ZB82b4-frW)*h3@kKj)JmjVfSZW4*W78+*^9Hn)}JKpm8Lx&$GrH0sS`D zbUBZvJ(IB|O2xvd&hdIYe~TeST`?Cla`aU9ACEik`%2;G9{7%B(4ZDK~g1Z(M&HH|}&MnaWujD%7HO%pn|dYuG; zUfl+5&$bBP*7J46hplXT5+4<#-zW&Fw%yr@dv~-+Q3aV-&g)65*A*S9gNu<58@aqD zj3>|F&5@TQM#uqYdViBcPK(TDURKKDpgj)NtFge&1mq1bD9RqGEpewA-u7QxR{G7t zE?`w)0YPgNi|f}CdQ-;)7w*zJ3ob}8XVd(qbn*hsosW(dv9GP>IPv8qVso^ReZLc1NJ*EzNAG0GOC(*gK!rX!MUksBQ zEP3(*1bleCJCisn9X#Sj?D>3!aGY$7Z&@{0U|xVg)?_b-S?_?L<9wtYlg1g9 zx2>YJ82(AwwDA5w>&|VkpF`I-%vGSt3{W;yDSPC6TT$8sX{=c8(J#Gs=&s?^CTjs5 zIVsV-LJ#+xj0;Gbqm?ncGNPsyDG?HTNJLDwOvW!tPWufncmGLB2~~;(e!5nVea5q%Fggr^=R7{v%NQE9sbxXTMKW7@pN7Fj8A{5K`NeRUSf~S0zR*eM_)VaKUYjm=n+myL87-qV{8Bxy zblWDjO>U6zsK_Fe?k_88AFbj>wQhHbfC-R@0%)WQ2k_)neLKf8;derJuK_! znp^F}Et9UJZ_i%Cqwe+V8hC1JJ6F$IC#H`xmlRhKg3(D(BBn}|$(CjL^}A7Wm<95fB*!Bl6CR0lJ@ zsw|Vkg?6;<+&+ST&?Fsob1Nf@e$o+7!|r+)$yOZ(MQg_2JE@ZVVL7sDWVtOc(b_z_ zZRwJI;c&6ig+8~{KLWpt4eKphNXzfw$$I+anzOJjVQy&RIfWjV{Njy~aAo8*;i1L( zj^G7X$4fQ^VOr}ObnF^2>Z_lj{YERZ&l_6?MOiu;3z`XMSP3ukT_yE#J1-sO!SVPs z;QuxY*TmdBrSZ3Q-P%)?lWG}Nr>2FH)X`+^GyTdWVn~Lbzn)HlO=rPH`Ed#_?Utf1 zx5(>zu@k*^vOd9b-Sb0P-7l!%$|u@q@)ftDS?j6QgNZK&A98TGINq5*V0733GpTcg z@8RP0w9E2vA#6=^zy70h?2`p)6R1nUzxw^q9r)@bv?Kl(o7Dq(`QbVPT!qeO`c{#> zYzlDUYrjv4$ZIWa9B>()>f7KKq(R>eH~rDv|IM3MW&6?P{(SNFZ#jbk43gZ6^)Oq0 zNQux$?fGt9+O@<9EQvU9xEP^9`IT1uz)J&N{;~|d?9&sB0ICsN@LY!Ncm5mH{L8fz8{L&Pg616UNMqCe7&E1^~-)n>PO~{&l{7LZ=MZ%T;iUX@Y{&%Z9XKhG)kK?ij{R-L?}WhO0HL zJXB5Rr)mr4N+!E(1yM1+L)qwr#Xl-;O~fA#jl!G9t-443SxYI~q!FH2cI z(I%(@x!?8Ra)px{scg~;e{PYY>pW6!>gNkWfYEI!$eDFc0RzB~Pj-ix)5GJn$MN^& zCuqg+zL89q0A;N+ws?Khz^=T)x$P;nNpC=8zZ_-Icv2#~%m%Zo*GSYnZx2guEjnKl zz36T(aMm%v_xVIDGUhz%I0A$)1XRM>ZjdYd!7NN^a~!^dzj$4vTe{#q$1_w#4qB7V zZHZ{>dJfvpE^a;nBfbYpr)NaRs%{7738=e_DlL@Q1|F$Rm&^#e-+HG$oO{9ZddWP0 zjsRCf8>X)+XWMFt>gVmia-2?#9NXC$9gaKN^n57Gss4!Q12bO@-jpZ%tdRlZD1(yQ; zj2_>;(D185++0qEuXTL<^{A*Ys?n6JfN;a?eZdlN_OaMhKI3}zN=R1}-!fU;04j;? zDTULTeu#{u;nD!+A}LUAOvl%cy$7DwD_P~XL=IW}F=J{KzM+*90h za;#P%UarW0xYYbCV^?(7%#R_MviNY@duaC^JDRg-uPQw!L-!0yiVd|$3WOM z{TfVioQ1#J2(suWG63gBeL49&lokVMjX9xsfd2&yoZ2#*`g6|@Zw`{mh1U#aeLEd- za=N?Na`QucUD%iDH)|-N90W1k`MNTTnR0HstM@Lg%(S$uU>E^(nb2{6a;z2x~6@e>dG2 zBQqDJCsJ;$9yF14YG@PXpf_?%V;HqoB>&9?`gfi;j+FZ6XB=)SLphbDrK>EjmA2oa7=?w&hdd8$eOn z?dux$7+C#gV|B&GD#|82{bAZ0PKy9k?>MNQ67)A zXO;ivY#wAj{^j)jG!w3-vk%p64+y4OEYX*g52Sn3dXD1n4~|~6Y2RDCu3nZ9y(=!% zPe3Vt*YBCv5@qupayEk?zJ)|QRz)FC=LC!uc8z4XQ1goRb;%9fHXJFXLpWoF;F<}&&dFSK;UZWoUyJmbZ+_a{cy|L#un>I$TzsIk6-af^jr3!?#x zA+|BMcG5w^oI-sI+VOgr#%<;N7yG zCXEduq~8c7+kcOb@i&?;ye9FQa3DR&!ouX0y#GjeG;=zybqazG0}9F(9#r0#oI=MV zHaB(B#)9$Oo^_8osrLL#KLORnAzP-lXCjfZ&``Lx#qR7bXYNCR^_yhFVD4G6f_yR- zRu^sCg^Q^s1Eq4E7Z`8BBN(u36&U424o*oJ=zXk z99bu)n71Fw6mQ8LfwhKHWA9ydb~;Ro%TpuF2^IFH+Rj-R^#?N-=xDHrYIv<&y?iHg zzLwdG19~9PQ#+1^G-lVFjByZe-{5 z^}OCV|Is@eCtp9=l)7+#^KJt-(w(TN$_c-q_yf+tts{XLPkq`?X2PTQ-yQP2&x4@I z$kcGx#w`!`Z^5~aKHnBqcTZvN)~!U?L0Ob*XVkVV7t^Y9M_%yPi|i+9a|QG_+v7TG zgG}MgAn`PDt6m>_qbz=LDtV{(D-!NPUdMDB^3Zra5`VvWD7EE zO&Qv@&FOCY5jVoPcLjL37x!HsHP0-bZj~OJpM(d@6uo}w80~&T;MxI7D<3nz7FAn3 z?R>=E?%W`VAQt!hg^#VRHd52BSHz=gxi?#lK|W4Kl$lY(z(7EncPOA1Ld$ zjfyjOGpGK@8z+fk6zx6i5Ruk=T|82Zr1yi=97ujLdO|b9#ZEjuXN3byK6^~UrEq?t za`Ly(z#|~L7jOT(`?^S}o3_pU8kvpp+MX_9MtTbQzW!m!@j(Tz7wGu2>X%E#g610C z(OLIKhO=t!cJL*wYb?w~X+^vbE3+3Phn>+nBSs}Q^=jC`i`qchmvmD%H zJNNJNqjYk-TV6-5@j!lPpZ{2K-gLst{INM}-4ngfue3PzT+EssOht#An3ms7&A0*b zT4Jt2k{#Yg=i6#^{knhCjlB1^YgV8Y5iOA}F`aVkR)0R(@5%ngvzI_hVk+XJOFy>ZR;1MQz=7N=EH^WM?n=$X>Fr+}I=I9Gw z3GK?$ZHkh4n2qv~i_mE6@N6jq4lBEC-KD+>O8I@O5>LvyOH{A)5VXX?LX&0XuG^1` z^X5cffVW%ZnOSJ}hl{goC&TMI3WhSGLxdNsrDKPDE=d~tkI~|Cd7>Uru1C%MmWS$( zM792Y9USIMP2OOuB8MaUChumK6GsPFKU`OZ!{vu(`;OIA_hssDPQl*mOs(KgQQjNyHsPdK?+Z=wl)S|Ojf76c(Osg0 zzp6z03b;QzzZW*%gRQI|>nsvXvTFYW6`B^7=ivG*$rE`wSA852dAlxY{d29me`^h( z%XXDZmMqfTU%_kSvKp|{JihKi8Gb^)`XCh~seZQZ`F&m>1MD~!I9*R4R;B1 zA%MnQ%$%d~&%ZrOSdeHFLthnCIFG~Owx^t@_V+(8k<$)7B_Vu)--xR*zQw10E7LvE z?NL@OdiV;}VIX9&sSdN=?Z=AzM>VSl`((KqDkX(9-h_hZ54ofti;1qZ3-Pq3}>#boAafGEnq4 zr6z+}Cus;ntKv@Ww#c5E+H>#>_vWxu5*u$>IcajxCSunN_U+)=yRIR+XBY@amQrzm zJ&8DZQP%fq=P8MF)A_X5s<81b*y>(xSBkUIP+aXVJdTccbll5dMzr5Z6w1%>-Ir=h zKOCHYN&*_lSUg*R&w#=Z_B}jwmNy?40#>=exY&D6=!OkQzQITyrDb z9Bw)Hx~`Dy5;{Ddfp5Hyt$X!YAVY({xZO*DPp-8s{ULe5pWfpW`iC(@w}b2UU`+wbq47RVmZyohNlf^AV;Y?8}+J-8qhvW8o}w`neG zYF}Q1%GAEaxrrxpMN!T*UhCa%^jJ04IrdjY5ts^dxBZTyDY>oAsf~Pw=JOrT(>rRa zt#i07PI%B8C)6VqT>7gt9*7lXJ_(&Ux=FG7oC4i)Cl|lWn*^wOpd)ZNkGaU0IyMq0 z{8-`Sk>i@wevObCGWjlG-7Q)FFw^x7h0a0l3nq>rCzOY<=$2O58{}v5EMW1EQkx%c zR-f21efL`uF*9;|>XoroJRzAB*}T^Le99JV))}CM!jXWFJ^7j*l@a~X_^NXwTU&MI zPEd7ax&;N%if`{=vNF|}9fG`zWwQOUirAzZS*}1drI6Cupd!Z0H?T~0;`!cCZ+mWj z1-ZG=Jlhe4HXY$&Z`JKLV{5AAxiYj97MtxuK|)=xLRh#+q?FsDAeVLUm>&<7m-5ZX zJSiP^rrMJpWe>M6$Hr0GUC#|t~clQ$9V_m9!ftTkz+yI+?cYi)g^&4b?3dgPML z7=2p`z4LCSU?6uhGJkg3r4feP zWd%#Q&0KNc0f$08mol55&s&ks*D6;?lL0BA*4!cSllCP0BeXWl2i-RnM<;ilk_b#n zbm5=v3Wd$EQqr{Urw*db`3I$IG(O|2=AULGqC<&wz}EcNwS zzPptMJvHC^(Nb+=x%q?qa@#U|_^)<+_p+wC+I$UQc5ItKc9gVlOKanx{;r3C3=yus z**%RyqN~s~nf?Jc5giVJt;z|VV9CA{^2edc+V!aY3Op?wvNDnpbrzFG5wBhYhfOJ$WgKvDCbl{%Go{%&NtW5)5?$a59REo;7j{7i2rz zPcPR31XX8RFcy?=O%&&U>qDhJi;t&nYOq|Gr$a?TS2Xz>=eHJ-_DT%jybVWJR|Imm z$18u!={SEkwHjXPShCo^%QxnLLA;2a%5~cy25?*Z_2tH&%1urZ7Zl{brA1Ki2G24J z234BK?G(;Ud@;(*MLiocdxkVs#7_Ic{M=R1%KiHD4xPd`f3UHgr39y1hbv4a`Pa|& z1lz>_WS}_EV6>Brn3>%r=HVGys~*eT-Wc36C+yA)k!6yiUi9p_U~PM@hAbQ(j4d3= zZ4aba=MRk*!f8=xXEmc_z3SvpnL|2)ImUW&uTK$bY;okpS0}mqf1M0|(UIZzwl8?m z-*#lj194r-REV{Pe(lxGoe!i;VjZJA`88l&r4Y>w6U#YOZCTsX3B2o4(MP05>O zef8p{qZ)$O+UGAC+VTgze4Mj8aAq6x4IkPw z;QXWhFl=l;OG9!RO)D?(*u0@nB7@@nclX_)-Rb| zp^DOb>@@@_urdBY=|yhE?!D6U=k~sQLyMl{x;?l+_NU8FRNC4${4gdwB&|@;bU&QD zNDK<($=f}#_^^G9d%6qXMF0Spw8HtZF;imWVc7U{YZxk1&{hE<-m^e+QM|e*RDXar zmlbyt(O4UgYO-BDIO08@+ryai+2IzpW6}58{O`T)J4fRgPNbbEJFgw%>2KFr4@JsTY@x+Srg{ zmRje+n|s4@c1};Iul?Mm2IO|-z8tp-%2|;7)jmI9&R6=naLG(}z#^CJ^E|!ig>Rqu zw(qR%%d{v2f9izEf=*Ulzti=kuh;IB6zsBao5mW5yBzMc44xiE`OC-j}jeimS{K;-Hbch%Wgj#U9dq755VZDX zuk!^%9Xq>Z4yU$f_L?vpnuJpQ7k*&Zstp3%i&C2CnYupU0KM<>d~sJ&j_UPV^aH)z z@;5=zCrKbBUFXgLj=jX`u3+XUhKEGloYn@xP6_g>_xFRdHH9jS>BOFki$^@r>@Uu7 z@;?`~Z|P88rv;LtdKT5^8z;isWA{$h2HhbZUE7p#R8c1LO~m*{ZLmh)?QaTXic{Aj z@8nH7-vG6bCfl2ZC8-zW>bCxRlQ)v=5bYYa8Npk-dl^_+1M;D}cDM<6*zuK*=HImK zFTp))`eRBEe%JPy0sO+ zc<#8-{^Q@XldMWVkP4n8jI4IAt#8>~P3{^s;D}Na zDxa!yt?;uxStNhB_hDKz0`}le&yN=%2L6060a~$lIPpMwF2M9set*=&z-3_m2y7It zaBSIk*z}57^%4P;xIoI^^7v-mn{AMPz^cKC*4s{#%pDt{sbJhuF(x7fza1Ymo&heR+g5Oer?D z&&yfj`5C@|1~DAS6V~N(gg{*KLf*lTiYCA~R^Q!w&r7KCNtBKAW83Ok#={UBZSf}d zyZa)+t4IZVZwaneh-ve(7ZsMf7gKNACh9Y^L6rmj^WH=A}VP-E7adk;C$L#WYUF7Ufp$nOgpGL8K=5kV}FS zhQu{-bo%*5M0AhjEVYY_?-$Z6)x-6-2P??cx<#+8d` z$2l4f#JhhRq}0sbXD^*PBSjgixrfq&K_UH;$n}F#PTBnyhOh1v8F1BSmOo9Z8Y^(U zRt>u=V9yJEA;tt`TJ?l8q=f&N=0fGs8S#RXmUaeb2E+yKKf;qfQk<*3zr;C>boAe)-zO;Lg!JU7g8B(Iw3m0k7qBY<_W-V~*M%6UV6?-)6`g7EDF(M%+vc zMSTO8&3}4N(N7eS%7&?PQfHU_& zYr!Yl1GdQ@QEz=rIOk-^eEJk2JvtGm*=aT_wHDeeNqP-&O9~t+RUy^<0P@yZZi|Mk z*n}V{m)`&8JKt+~UD-Aoeq+C04w#iCz4~`G~XtQ((=j5OZNo>bAtGbfaZ^69LF~zYfMh zrM@nbmAtMHf8YV`nFC1vivk|4URP!Ns{BAaC@!~m7Oq(^Fm#0GuWNynWTZ)$SyjJL zcuL${BG0k#3_VqKc~E_@xSpH)fK@)-nr`D>8D>buY2`kz;k8`e=V@r4d!T*hKGFv! zQD`7ai;B8dB-?X$V;XU3oCIS~vU#USW-R@YCeFXa{AFg4Z}sa*0&3B=X<#HQn?>=f zt3h;8DVS$WNld5({00vml}Ov3h+%wrcj z-%ebrI_!0#$z{b*fEwQ}2zeMUhHt?kF_X<=dvSrC1{O>i=<6t?Sx|mKi*7jyS?EJ= zr>!DD&46m<4p1y0--f!g!QF{0vs@{~8tBm5Ik_vb6O@q6d7UjykjBjJ z7XcyK1wQ$L+$_tIsp>i#XlYwXlM^1(RTno3CqL}4_iWRAm;Hai;m&yJbZmj9ecaTh z$~S*MGC79xgl#W%Nug7QQms;8L&`A$ zg~!U)QNaqmxF(tg(-B^xcu0fT(gw6g5D!2Q!-i;S6x*kO6hG~%hX0A zHy?I9n(@5JTv$gkN9ZJLlrg}F;=GqvA^WxYV2`BPS+s$BwXeCXj>+j`v8*lrqO=91 zzz|9jPb)d%pDRw}v>W|cPM>HE5J`<_B41)T#Bnf82sVWi5XJk3lBW+5LaNG{<9TOm-ithDUmN2Iaz#WNRB0`FuynZYF znDA(F=W{pOhFZZEiM?5BdkY(RmWXd)2h`~_4>>APF^=k-M`UQm389+B;c`fa)UDV^ zmiE-Oa$MVwr~p;_$mrYtDS6WtQM+GN(XgN6N5dLzO!m`m~dVp6_I`WV+t6vSIOj?**GCK_c{s$Jl8#j&^ zq1j~f0YquEo=Y+ba^!nnlAoVFzNuy=;6SDT+p8$qgANyI4UlZgXuax|yPiiaI1}Nm zCsAW#p8tAb@G{F{eV-BsC_;4UY&btw-cTe!=_M0#!#pXqupG@LBwnl z&ggH;1H*S{ z;{Z>KSRp#`-5zbg9{r5u0ZkIFt=6ju_5%OwbU!U}?e&&Dm69un1*OYfilZ$?^1QH% zl6m10{hALPOQMj=qLHu@FiARt2nth`lGn-IpgvFrMP_ncbyqv%O>i1ElsW|;cBa@E zvMt5pSnbk0N3YIE7nrCpNd2c~xn@+D^2YAdVS6xxxJO3%^5MsBX*8|{*xp184QLt& zc4s`?D>3WpkYrE+8(5sg0^9|E$ zB$g_B0-`)KAN-AFlstUms&-67oQcRYx?Y>u@?Zr!E&+DPxO9YR+v-l#SVh=U@4tK| zE7b$SprmEBU-7eBo$BG}r4%dOQ9?=tOY}cZ6+?|Apib7H= z+M_WW%NX$&Dr+BTy>~Bl3@~+#ZBLT%%*FO=p?&;`mvXSC)dK|UJN9o_pQ5S&+8lv( zg=z}D&p&#>K_9;cl-dkm_BkSNC>r@g#$;y^J zBjebsjLdM%#o|XoS@wnS6J3O1}2-LDBvQt&a6UL4@glR0b?fm%KE+&NNMeN}5Hu zf!2l_Knxj#=Mu7Rs&DA*2Uk-d$%q-ZJxkuQ&{|~KRq3|v)UYD2h#ypgf^()b|Geqn z+i4K)o16XEO5-+(i#_S6(`VVDbCeu{A^-bc(#y^zExn&Y&!>hJ>&i}{1}`NSnsRT? zh3#woG+7gIIcDlN%I27VL?ol1Yo&fVvJ^!^eZEav*A(^he@K|WG zaKe3#Cax3l0@t+7v!xd8<-p3x8*u@=taXl)OqK)>-IV9LzRZT62A94?nL$|l*I1qh zOb;hrz?DUDKwIz;ZLi7M?imVz3Iy$#hTd5-z{)(nt|-j^e;G3ykl#h0hqkgbaucN3 zuw6lujCZX+4I+5ehg*N{Eh&!c765p>J9qoDRum6f+}=|YIBTQ;RlsHj^Qt<(6T-D| zveH&5;Prfzo7~S3d1IPth zWmjy_{%PLT(HMlyF?R-@B(sL~60nsenI?PbFXaYVa-|n!$>x`f<}BScUUn5diHxFo ze7EhVxUU|A-=-7x#lw;Th)2v#jlwi{gM~JnqebDH?4Uvi*{R0Lr2pJanJgoKEQy95 zHrcm2#N(_9;)KC#o{P)gy3z@MFhxYZ52XDCUIzY+tt`irXLf8jdU3MG6XSlH6djE+ zb34i_O9vxs9})%}2&%{W6A#!RJ^it&GH%>NQkufoQsNT_+H(hCn~EJ+TXBDl);35X zl$s6KovsNRj>lJW1C()Ehz*3ix6{%{P)ZSN<*Tr@qsUWPtZ}&|0PZPvZ>+4XrLRm( z#LQ8>#a%I?{p#SQae*T4@x7!C{Gp{JxcOY};~w)Bm9+ksDc#_NHh6S50Ej-8YQhl?rAiu>Wj;pG9@i6chVR{dkE3%<*Pq{2!u}%d6mI6x@IKF@R;9}}y&0BYje_$1P z^Qh4^ABcqyjtaXN?1g*eOSyn-NpGeFOGp+1j;Mp?2H{gLx&UzsrX}1mqMJI}C<2Ny zl+-IVKyP>ZYfq3@n@LeIwXv1;gPD#I<+X0z*EuKfSzWgm6vFl{1u?Mp*o#um5On+lk~r)<-*lJSq7iHQ_FTyCt4Fd1Z;30b$Omx zyhxVs0xT=aA=$A!?_KeJ11Cjxw=txG$MO$_XhH5f<{h>%>oL2~DUA|S20YR0w?EgE;UZkS&j^9{(x2J^gGm8i z&muhz)^e1^_C1})*b#R^%&5WUy#@e@h`DXjXzIrXn-+-?IL6nv1Mny1-g&JtWbE zGK&>78Lx$~i10-kI6j7rxZ}L^!@%OnTyPvH0=e-*Mx8n(E7}k%&Npj^JVVpkeJaDEDSRl!<7)5B;yCWUsja` z8f!dheNbonw8@oWW7_V;&O+YXgCZ8TUXi?d&-t$H&0WpCsxk@L{v62HB0jp_@#g3( z7~J3yq4V7T#JO9E{j}Ios4hLl@(;rtO z=ZnkU0A&k-cpGOLX>4cRBQ6pbPLnHs< zKwiMcAh(e!_bekz`^)2RuM5+wsB&LQe547i=( z5JfB!Ff!-j2MO%VIirbLqOWQ*s5yNg^i+)@Ea?{UUSbbJuF8k0BvgAE+SwtFJ%`#U zUJ&XA{Mg}1x(gCI+6L}s3aVR$b}>`!G3j(8-p0~9YbF6U;^Xh`tPHW(XSgl>zU|UJ zV|W4yKg&;ej)z?=_nhzh^|maOJ?rz5^_km*XP3YO4^e!$N*{vBOrl_Jihg+;4>WDzF48>tn?mMAWcjpm|$V zlCk%;<~KjO{xroHXE0S_Zg*#K*K~VO!pQ9xm8;23{a1b*UOJNSl}B9((sSlq1415u z>W(dJRJhDd^)*k~q#{B;evDh6?n*9x_U))CHsbvSK1@ApLv>I)*N_Pz;i$m#+%JHdNrFvuPc1~)h!&aZ;} zEVNK&7F3QAZm)X#0?hrj*;tubxVsr24liK&0B4;an(By~d%4P!S6Ux8nt1O>FA&Oh zxxDj3fi!I5FlT$-Dj*ugHvN3eruzBNg!WE@n*%7r#nwpv$f~bpIO68foO>wti$&uEV-W9sk)fpr5MfTmfUq;UPPV>B9UuhVxW@vqH52CpUgoOG*MD5P@re=|)st7kNvM0NNS+`J1 zIHu^OC2eHWyYtC)ua0E{;T*9FxgaFJy+L%Un~rlGnW?s~%cAPcw8_8(J0TF${54yl z&*hfoI6Nm_>eIflV=gMzE4D5(>_2kslygPDWIHQwRPl=;R}>0=6!jA$|83yZ+)CbM zUVF@KJLDf=)qlYZ5Ybe4CU#7vnCn6gusz@KjV1X*Mt7TCD~-~8XXCNh>i$@*AI##5 z^M##Cry=R9=kgPW>dl?>OKd;6;;Qf(s9V_kRE*?cK73jX zv^&PWdd6rapZVxbL6mvPlwF9)Cf&myp;xi1DBHo$U?_w2Ch5HFr08EP0RH?@a8?;= zsR5Wz3z_0pP$6sd3mm3`k%Ak?;O}i8#X#}lQof>pIYj!w_wBT{l%SRthCIw}x+U4{ zUZFJ@%KWJHMQ<|hx6F}avl}eX<}PjwVN|rxqQcd7VYoo10=C#UB8dodUa%0S{wuHy1Tf>Dq@1UJp2cDEc7P8a##f@sQv@mLse@~k*tE2H-)8LU z_iC!z=NrlRzH&-hc?sm2Qg!U3Rgd#%)hZlOG&H7lSt5NX?8isq5;}9^mmi0t_3^Uj z!|E);&b!Qa$@u9?qs`qmmwtos5jLA#0G_#!kQHl^gFKxfHyyy&#je=Hq}a>Ei_W8t zOC1h&#(e4s4tQ&L>Dn8z3dKTlsAieI>sc{nb3i8zB}6VQ*RC#(8Z#;AKjBe9EwlF< zx*EQj)5y`ejZz2UT@xO6I+X0t)X6LTBgkrY(J?E(NtEo;Vf@pv)g^HYFcVJ9l5JfH_GfpC@32e1A@rDXBC?!VWzuv? zn_(F0Y;C5Pqx(4g7>CEtaP0!~q_4iMB;o#RnIj`sW>0R?m&6Uj?kL;T9Y-4@@Itx+ zc&m7bB=MwT&vEn-T@mF(sF`ltXpgN2CN5rV0F|JRg>NdqmPW#7=kf_O=*w%7=hOpf zkPp~glHgY&dIZN>HM)G~3^lp0RhCgx(!VuAmW_I*$G}%fMz!P05=k~5BL&QPJcy~8 zbRnr%h}N_Gs`t(0BVlGwmRb2bne)or8~vw3`Tfo?6h9jWLn65Fv*$=110o~vR>W=! zx`d=O5P^%sRXw)aq~%99k1r~nTorq5B0)iXaoyrpBaF@Qa5>i_>73Y1!ddE9zSB%; z`WZ?xV3+A3oGM72<7nOiKFzE!+IPG~MD)Dy$4_@GvJ5L=pN`Hla4Cgha|DtduT(eA z0O3={!p!t_8F{|^#@sYO-4f?PmfK60V1})e=vai?dbdi-f0I5V!`%x)xnNGcXmM2u zakQOlMVt+9`Vk_epSKEvg`R_N6Z^&Kc-+S^QtJ~8hM=QMIg8wRIp#)LfBl8VkJ;RY z3)waGcdehw#ASw-Kbq_{nncT+QHXy^J`GGBC-vHbM2X={AQS(o&4ra6S8OVOa7|B_ z(_{6nX#8O5dW=(aKs+xpPlmvnuO?Ok^F?{@VC=2vNPygKxxxfA_9 zl(WA=N#~pHJB`v~?-MO8hus7(X!(m?BFDu1^iPl*L&Y{&zLOY52~grXyQT&E4wJVi zk-@^gCcuWQ@`_r3-YDxpc-EhZRIe1RP`J>-c*hJY-3l<73sxoi-(g`<2-p!9w*Erdc}qR5?xb@f`*e9Ka|Xs+aQ=;=Rn@uYMC`GX z7akOWcso{i$_Tw&+c-o_)F_p8=}#;aTP`f|(nQ5?aLbMqVvsJ zxN^eeN~5a?Upw1HT3Z&@O9I85e_jreivBI?m_KEDZ=S&`M5vgBLiY*3%4*oHf^tlx zA?%ZQAJp2~<(u@@9~tH}`;p2)$xI^ZO?h}?f%{+w>nL^=@QF~gGx(#4!tsU{xq8J0 z@9mp5`m|TW_zKQk*J5hY(?gbT%VoL~rt&0$s8-GkDdU%NB0OlEvE8(2ytDynffBQ1 zLL|^K-k3mM!LeQr>A$X$hW^IP0^{Y*!Nd!1h13Gvg5ChY*v=cA0L1+B3&c~b-%uRWRH$WZ2=)sX2^}e)*#;_wlK}Om# zo2PH+bf=_t7kEGi@yy(jvMQ>ck!ANDMUfxYrRn_=b;OzUguLu8)kAoSula6Z+Ed;{ zV7O2L^Qjzn`Hq2(s~BGUaSZJ-a}(mPreL-?wrjZ%EJHWuoR(ArY$rxjkGBFC{qxP` zgVBJ0!?Fr0V+N6Pmkpof9+_*8rA9Nx0!(~}FtURIrX zG(G;p89_|A)bu9{rRfT_$(99CSojUi;cLe?-=>vVEE?tNR1a4@ddh#!RzBIeohULq z_LBH+C=NBc&;eq4#A@FWI;p7NXEAL(i6CIhY#RD=`m*WbwYLqjiR|Asv6Y8*K@8XoYJAIsN%xih*ZII>o`z5u#u+D)F9LQPA)%ckr^j}CgPpdHU zXtm*=qGGNL=GpVSQY&}1LNROxjEmo&$HC(96QnS!g3ucw63cH96pL2C*pr;Ho1mTp z7y;g>lA(E0F`lUaKEgyj3fNJ68mn9?C@JZU>C4)Y+kk7@m1kI?QSIUG8U#Yinu@Lr z`@)}FsgXvG{6_~EX3AaWvRoHO_?l5Z*q-j=XuQR%V|0Cmol@DQrFUHmRS_32Q(N_Bx5rN6clm)b-*3Eya|HbRqMdoI&`&1@{r|_aiO?1;b%s z#?jOhv9%#XGxuE(ehz{qPMSmEz6Bd|?HX#6j2uCcb+O>k?t|W3=6KxWQi^VLs*LTO zjtOpcXGh}fMb!dMEQQNxUyi#IajsvvUB8I>N0ex9X74KwQO6Xflp8`;73gE>gkj8- z^=@ZbIT+8NSKJ~_6dm=N6Q)}SK!u_go&LGL1gfYPh%*@$GF!@Q&PipyIB842>VBoc zAiK|1jB2qPnQs=<6qowyER7YXLdcIu3Q_g zuray8_Hj&+_2fx2JM~6=lg5k&T??v_PaGCtE~qYD>X4OPMX_B!>?SJ509B=rA}n=> znmcLs=fTB#^SnkO+g(lU>L9x|3H<<(^fBAkL=eZ9#ys+1mf<9-7cgg5c%c&P*~X0g zZW?8m!_~Gkd%=Sm6_`WkViu*XMVTYf-kth{xYWdvo^jbqXxYxSCVZ~I@fHZ+-zp*b zi`(&9s347k?%9mD9U9zmxoTe#WjIzN;93A%WLO~N??_*Lf6rAxW$6+1?f@KV<%_)zK6_?_YKMg5J25zTVTrQc^) z^)9J|6ltC!c+8(#Y%T7`i|rbTn;zcaV>?B-SuZloDE5PDCRbC~8bq=A>nt!&R>qDFll_(#q*`|GufMLgu>Kyv%`16C#^Ce zNQz&v$4!7RQB&D|?7g1bix@gruX-ujrXnFC{7pfpP>46l!|?w4Ws}f0io=xkm*_hn zo}?Vz@?v}AMHk84-+{9O1tyR3?zp@kp4*rc`t!?AMnEgYRm^(g(V$uf6BOSM}%FTCbWzR>>s_&jmS{m|JFncS2>su``{zT{jA zZ2VoS`5)T9>V2{AN$$Hl+rL=j3-;fwIifawDC>h>Hvfui$%cR5M>{zL9ElKO4Crfp zK0?j;J{WTM2r)eYF3%9W7|f@W@!m_Xs2Q6hbrv6tv5&-Vp`*j$pG0jU0+>6iCPVlw zdt_sT*%5W6UfUbd0xs6&^Vq!dmT-xpzRk3lm4svLf7qWSvIof7P;U-rUmi-Kw9|Si zBDgw#7Zu~z9ZWNzD2q2wW=g}f%UOYSgT=qr_klLle@#Fq~Tf_jbNU|E^naH*;trfBJm>BR1uNyto<>!?c;dHg8cW?pB}opN^2?JS$> z*Hd#Dr)Dxv@eF#BwhM6#;j5XY<$&seG0dw(JetbgQt~awz}l3e4dqI|Va-YLXyqWW+d)g+gf9a5Cnf+{*Qg|-`? zd`7(633mG&+n)XNJ%kja0~sCIXB|eJ>?3(6-cik!biHHJrO*m6m%RGyvW;q#;&)nf zu2X_*aMB5M?ln~J6sbtpX=*yM=p>6P4l6koIU)~;qKml&@?x@p;gHz;mRzB4Y-jV=Xw--=u5>sKE>8vo2Dbjrxg*u?$^}z8HhcLEU4JWoRoINnP>?i; z?2~MF7KSbS#Kh4u>vvDMk1}Uf=BZv~PQxhvRptk;AouUToHtMDE9JHl%sJ=ufV>9k zH?`VBQ!ia;2UeZFS>=q9w26S?F(M6zh_k)w>&uhGCJt{) zP|6=kXlQDh3;a^8))0`C{peoe!mghBa)WpF+q>OPAG@+Ob$KXod(yuh5= z8K#5_%kdn;l23i4Vx+L1y19Bno}wnQme;NT#DupVh0AVky_YFVc(3mbE*^aMgRAvY zQb)*nG1*KWrXZ?hbOS{N5-CW#m4oHeN%+jGm+IN&!F^iNm4f)zi2WLK5|Gs--6+rz zQWaU5oy2cp%A7Rw49XaeZtizEycbuQd5v;F8sTTE241$1{IZP8mkB(JONX{~-Wn-C zl##l2WbfTL>7n4MF9Pqd??07hp#6!3b&R=XjMvW&%V_xb&Txq2@5r|_vWdW*S~5*m zELQilS0NDMyY4^EEPAGS$ZeT-uoBBAnHEt~{014n8v_4*YUt%B*S!PitD=LkDM1Hr zEeD)d(`<{Q;okPvF|BDL4D-EiKHZh08EzBQ{|*e}@9_zP8$jTreRncJuLGe5&lkOO1A# zzt~c%dJ}B-P(uZXY}(_6czW(_tl+Z|3soXL<6oT)AW{Mbuq$|A09O81j`5vGQ zr%!6$q^){!eE*?k>cBF%=80QRf* zD6+103U~>7mPMS*S+t`MJsE`xDlhEPt z%iSt2Sxrp+s;1idHuKb@eM?OL2$dM0&%UsQ;hAc$m4YU86=K!W|jGQ>3?9B)e%?3r&#p z4kqQtK_t1@Ro|V*Q~WxPj^s1Uf@&L1PDX>c@P>9C>lrC;*XMqwf2bFVEJE1zZh2S7 zBw<-yntvu)b&!^t*n1F*)pK5bl@DoySfob~tVsBcuM!(~Uq%ksWHxYzC|eq7xM;R* zx_~nI7lz=2RUvI@SjC(lX^CSm2%!rf{y0#N*P5I|-@sJKd?|x-H)Y9g*8U)P%2M1K zI}+#6c>bd5%1N}H4`a5LuW791Tv6*}qz!N@&>>gS98Rj+nsQc6VL^pIn}YAUbV=*h z=+CXQjQ%A}0)#!!0pSGSF+=>)w=27t5(-}Bw@mI2C zkWvaFXu=AKZ99MI>jADkyBv1Xe`L#@fX=p1wjWhbQ_=+OKM?2_IY)0$1=Y#C$pGcP z6wz%ic5j2lYC`bl;Gji9E-E;()4^DM`D&`J5?EM9<&AW=aP7*LOo&(l9!E9o0P2jq zA=*>qb|yK?0t~ZGmnR)m`^s&O$zX^iqb?^B&i_{ibY(FvG|%3r1b{>H~X(I^peSXa^I@9#L@YaXtsvu+ua9Av52KexF4 zDIBTz_E$`vd2a}TzWLEupBT=~d+Ya~U$dYQeenp3m|Ok`e2%xj#B0}J3 z4c1{3A1!L~#x>`>v3DHQhjpv#a(0s>g4EnnHNfX$144=(IgWJWjS7p^1-<;INKnWW zvlihX3Q`a?Y{a$2Jt&qX#FzqbnmgllYX#CAv@L`if^?*2cS@7!1ojg8Hj z0&OWQcGSD}5EizHr<}d$9@fphZ=I+)Ul@Ro==xFo{V%Y`T^B+AxD9X)lA~KD2Ec+_U8kM8oL*+oxx0~FT z+g_jUH`WH#M&R$#aVHMm2U6>e1R#u7`6`{{iNIYb>%Ls=3s)&s{rL<`vFFAQuJYA* zL}ldqM2~VdsGeUeo1bir%+?NJAHnu%nVbK7e-Xeg3?DTH7AfI3zAO%^Yb`hQGzM{e znc~$;5%2Xob_$(BC+#fFualq1w6*ea8P~Ze86V33p`@kl?^Zs)4=nSwh!25#!Rp?R zW-5wbr_gqh8)k80RsblWgnIPh65RgxgI*H1B!dD8%xaoTI>w>Um5NP7%h!H)d@@(g zapA5?|L6;u^2jPXjBqh@Q0?*K#|u$tkt@ZEr!$(Cli%3vXKRO$tYqc64L`c)UH6~L z$$5Ab;<@(rba{r1pHD|;OI@J%j&8q!XYndp0N8zU6S>&B_iMLd8tw#q>U?0AWXY!_-^eJv293V!sCsq>K6^5Vxqr^GE*?H{0Wa_I(Nn*dnaz z_17)=S*u_U5v5Lv?V?o-Xlit`*jJ^3LcS>>pj%2Zmkk3m1#KC_3}`~OM&@rRIrTzE zKCK}$pySa?z1l;i4&yXEtGG8gt0&GSg2D`&hrD{z+Hl!?u&Ny&t)(*-7=Z zra7z&YtpfbGK0;s+Jw4|4c}_|TogS_(h#7YhLU_!Hnj%KeEP zw;(927h>Sr;BH>U3UJ_vCIC))|3-4RlFt$&e8mZ{&fc)Y#}3;o65pRVb1#mGM@vC# zB#mq-#k03JSF=asTxU1SoT{1zXlXyDE2u7=xvCaxA>L!>SDtRB6(afaIz>FF$dglw zJt00sF$gA+bq2HJ_T%OK07nWLkFBr)?ObSWk+r#>}XJdPXg`3$mdbyIcUC{ z?a?B18-GfYF)cOk*zR0Qd*y-&_p+$*`pQy})=zH5fFQ(pk@f~Gwznuj&@3QJ`-@k- zRf&=aaRI-*v(hQ84Mg@;wd{wV7m@HQITTI@BF0R^D(d(h!Q}?az;d zwl-K%4QXSJ3$3`yN;dAR_g@!(ei&#y@{;PAcg|~M_sM&S?0i;@`?2t$!(8O>=7Tt8GEP#$j^z*3Eqt2TH$2#igcU)%yDcb!@}bofEE*r4x4zBt6G@W z62Z%|z-{VYDdX=yl<$ySvP)2o_SDEwsq4*`1|Lc2-YTo2Et_=5S>Zb37I2ZyvlA_Z z@79-9LVCj|%lC7;w<;j_pf)_0=6i6!WIuQVnUZoPuD7xbwdGIM*CVxlMJ~24M>kp9 z$V)e2>gSrMW7p|hmZT5^+^1!d&-jQDXt|29x`ebkH9_Mo(fPM#64ua zgX-DkG5+U;IftlZgIKvY{|HumNbMc#$Ry!5h#TPL3?D}rtA}6xkty0RRH}8ks-22C z0};ahHRioJTG)0V5rjuqE4VX@Tf%v4rgC%(WJ7<04AcbfUUql?VV9JF;al!|eSQy6 zw68$#;~~$Vf9A6uH3IOQCHCb5!z&tWepQ}{-)J5hYjv+8oVQ^4vS`=mvWY-!Y!M7U zlxM0mE*oSj)W2;NBVw-=GMCpQn{a_}*%SCJI~&>`Rf%xFj&u@zlKZbO-8u7N?%c~C^VKHJcf^ge3T7x9;-dPio5sf*jxb5 zmv>gtpg@|n8YGgIQ336@?Ps3@<;p(osJVlhSUrfKF5BLVI`xlB^P<+lFC!MqxEem> zVv4#zV0AkJAd^7 zY!ztnccv-#V~-q7K}7eC=IJE8{2grnnWkvhQc?;4k}OQCod7IC+IzIx(~2E-4^sl) z@nzP?e_Cg0Snh*UOk}@xo@@WSeIPKfPld@%We1j(Y^NqFYsr=W`ut~mkQ*<7HcmN8 z`AELpYSc*9oPFsGlj>3U&-Mbb!O}|F$H!cS9 zm1|Ti55TAZXu*(d^1Dqy1}PtYBNK>hmOd)4!?sVs_c&t<@j2ye+0Mm72YQ{vkgrln zhA$qX?dR2z-rXWpiChf|4D9)ESdas=8L4uG?AB{LhM&t?nA1A(-%G3fviOX*6 z-M#)D_|4brPw#ESiaJ$VVEW_7BtYNVdhn}R0Qk&?Uh#8RI8(0Zf4uI2oh~Bh^Tbrw z1CvnYv&iS-eQO|YA>>Tc!KodrlzQSdkPfAcJJt78RWNx;N6szbdv{#_}N2JIXCozJwHkZHZ;8{K)5O@W8 zFs|bp<$sLb-VSnJ03wkOR<;3?n#^OP>q=0%n=m+$e>xe&?c zUjqCOd|U4O#pryZS3mU4UJ{elq(z>w)0iMgkj{2_lLtqpI@0JVO=} z?WW29k?ikTK(cf4ZuakcTL>lXK%TR5StJ;q9cVavx>8Hwf7E8o80a1Q$%9j;*E-y} z;M|!wuSUls{pueFM_!Yu3=nS?x7dB@K16|}U0YCEjcw;6*0PC$-sQf(KhVZ4ppCyo zEDj3Wj=7Lo>s(3uyLAVz^FE2(m!Lnm19c!owxUOp;b|mXC*tM3 zf0w&wa6rB4;oSo`7^tjJ31H$DX8a9jcVZl`{Ex7&fePL?`;NE!&zTTA>%T6h7Xmw>TBxCL_Q1%VePrVb2Ms?LFz-{4|9UqpQ#(gT^}d*^BXJ?^hp!PfCgDIM5! z%@<) zV}UjO_Y&iiTfdJToZjAH(*FY6ce)y)K)1hrmQ49R!}Siz?-$A~rcwpmhJ4pU)ls>)amXfIa-qcaq^CE`m`B97juPR{?yywy{{cJ^%%UXSn~v z`S@zm0r)bKM6~(>6{QXM_GIh=7=M1Y2bCZVXjKaca$^5cSt@g}dQ%BOn(und6*n>a z8WTuQvQW-eNqRZk|7CGw?jOR3fWZHk@Im$4b=biVal2l`neK`TDiHxfhjMVo6#zGw z8>@Q-J;n6G*zK1ucis$utvi?@a!#!Qyt~<=Y(CKw@G%VW?#dNlfG@G`7>6ZbiOlxp z##AhT&o1g~8@hy7cpR=PgI*< znwg9s0gk7GdW|6i*Vd-QD&#_6_2Sok=6F!%)brd}arlM8=A$X}D+aTCYXJz+VYJX^ z4Sd`W&`#i_`I(o$0jS0j)NRYBKL;8NSbK)?8yh`|xY@P4vnt*H#TU=?Sub0!IE&>Q z^eo7{O+YoihYG8Os5szj82Vt-6j@N?82M?BO+1P(2gL%1>v1B>sg{JfHuGJN>-b1J zPCOFvGi!|~v&koQKjEM05MR^)P%;-hnA9`33y|4@UR!R4FY2hGMV-=IJt}r+7_OBj zj@En6^~?W?1vtra0754MGSM9P>)y#o<2*nyDXr%HzPmB^Jzw7<=gJ4#PrPfzh8=x?A2SKlq+`AN6K}Ly3WeGdWnd2iQ>IXl0ibb#ZcO|vr+mbNKj7^&X{GuJLPxD4bu(UR~R7ldu6gR5o$ z!eJ`LzMT0?nsUOzOLLo&)*4`O7dA^6u!Y%PKp6SLO0Y|x@Ia@?B#YwO(H=jG4kmg1 zw;UWCi;YEPgRFKs z9BQNS@Gq*#Z^TDogkyROTo$_}cf|e?;sRhY+4bjs^zQp_dPa&a){OL{B^!gJ+o1J? zn%fvbEV@kU=A<%a@EewEkh2{g)#nw>o-tJEpfc(t-p~84#Qdtk&9RcWzUtJc-FlXo zBxrlR6=u+GQeDDKo8lzeb$;O2Yz<-v?9?JmS3d)qs@`o~vWdxi2EH2&pD$<OuC z&iX#oE;5<}z(z7!ml|P(i0GamN14ff)TPr|OBX7uj-^si4XxDK`>FuO%)KjZ*LA8d#IPwP}&a@|;aqyZMaSpp2% z9Ow-?kIIu-25fsQ1D-vW0mB~4;M*W9B^?T+uA2d1$p-=R#Kaa_Z3jvdBZl2b%30VQ z%~34AFTGa-wS2vV2MZh5FBH}Du}eZ>6-a-6edBIS5HJe>e4P1e98D7QO`Sw?VF?ji zmH+e^3j9&+2uha?MjNqx5)I~EngNof-3VV>gZwWY8YZV@L7pZPV%sJOKiAi-$2k{0 zQam6|mBUxD$mi7=r4=~RG6>9+ei;jybkOE7i_U}^=6I1Q2mcp`ILZRcW-)wzzlwo0 z;H7UzmRqDRxdTi)?5=(gfr9FIY0NV~BMEA`sj@ok)(tb+TtJgNAv&UGJKLpsRZv5d zuvbq;&5bcit~~zF#iMicDzN$8El4uv>j<%^@d;ao{vo@=rB#+sUApWPbB7-r z7{p@iph*Y-^bHp%uvr$Yc$R_JL&2vMqXi#31OXP>Cl>D`L@?s4ooY26472pKKWZZl z$R2d2hLQm7Z&R>j=L(;FI@(xNP67sMg$HnP*kDq?JnV%3X!yS@>A`zoGAMbEsvop$ zQPdA?5~24B!|xTa)ibrgtsODtgD39-8d{_kc~s>CL#KA3^ARjdo~$X%Kp3x6XdJ1H4(vxl!mFYw`YV8nomuXFYLru15!8Vsb1)B!9Xn@~fa& zK(%0-2+TngU`58Cy_Vpy>|ZgHB`uBy8F{Py{X8-v`5<_`0K&Uuhu)|=`x>iy=_xT@ zQp9{E?knInz;SOjyFH(z4g?9{-z1di57a*&H8*=`%jIkiF#cSdR_SqR=IzmCERJbV zt?q9yI0E2(%c)RIV?!MdWNf>Z2-Z4xakNG{1#EZa47LKrV{g(wkFn({!8elto>XjE z%U&|~!mJkUPAh-S33oESJq^4*b_4LF($=5*_qw8nmO)sy!_wyVPq0L(4dkaZe&uh` zK#Br(FgH_5ozzB=y^aS(L z#6UodRph&zlzQqjZ)Lo&T{LYT?+If-uaga7$Itrc*BT_(Yn(O}n9 z7JjGzi`Tl;aNiW;X?NA6t>K+5t{ltRW8{+`HwTL^UZEiR(lVFlkK`OZ#X1dGg@v@t zeDf5$fS})q4=af=EwSvnG!3xHKBzL?w_AW^n*o@EU)hGVHX5NVgSq-5rRF6;w+9qe?bz^a)TEax zYHFdF29Q}Jsz8`WIs4&HWVGl%IpX`1pc-pC=5XV{7n$-sP5K;8$e*I=!ygR;{tf|1 zsDkz*61wk!pekKC153wv02*gW>i|VB8H0zVFS6=M%R>kD@}kOrfm}qh;CaLFDVVq` z_!vDLcz0~O7_UZ2J~n!LxTCQ9db|KHo0#*9U(UcYRx$xJHO!~i1SRFQyY0$6gn_=; zgo7Seo)Lhx{aG>qs(acKWGc3P*nU-M3&G;Fke_T@9zJhzsb7U11B4A&G?0D>z#E++Ko*Sr#0@Kg{=FHoIA zARAya{h8`bSiwFc1puF)w;(XXQFL!y>fQ;%)a4w+!u zvaTa~?!RgS57L1Vb|V{js{#l_%&w?#SC7}!WAz3Omq)$xcBJ& z=idbR;j?Gvf0O(_)G5W}mynS9Kfk*7ug~{@ar{eA0*4_(k-1mKd&3m@|J?A`>p8zltfZM7}qhrj}iejc)nW*l5Me7kLow(!yL8jIRm?c?&-X42P_@7!=Q`F|_#b?NYut7k2w$QQJ6HX^N7q(^4t{(ljG`d* zvzB*-F-S3S%Yl2}cv33wU&#IPet9!+)L3_CJ3L>rXQWg=&&7e_xaP>9+Cb|#~c4>(k+`6Rr#NfrwQ|_?l^s{5@s-$?1 zhksw~n83NF1IQf%1&w~{sPTv3`N%VTm&W?dA;u?|*gT?R}tu*9`>I-jVIY`)?G$Ii+^C{d#=cBM*$o zkRf$|x%UQz69(7!m22Oc{C98TEfcthrEcaxEEf`Po5!R5PoE7GugQo~#@6pw_7;0d z9=zJ;h|B$ops&==E6Tk0+`j_)0Swn=7qzKV*w>eb;95Pc8^XB9iR>|REt>y|K12hQ z;p7?wZa*f!4)X08PL+_1$!3?27ypH~?B5tNLB6&_?-s+}wU(g28xj#7(C&UFqiL$# zQS-k{BqO<4R-mA;PpkM$-c)N*N31Dm?qEZm>i+9mQE=^tLZ-I8Iyk2uxHj1=^|@0# z3Z5aS4!!>R)eB48|z6GP7iEs6S4Mfg^?L|%ecg601w-?EJ3cWi}DmN#* z&?Q~L5EgqgoL}=1V=I%^r!!QVpDhnJFux6CdOY=s5!^K=!{Oh~8L%^F!EY09b<^z0 zMc$caBxHN@s{Tp?owqfqUU8^=8}eq@_cvi?SeDU+G{fj(o!gzISCApk6sT=5B2i}j z={e~+4cY`|Rd(yYM8^Z%x7qlz`P)6$Vny-nIGXMnYZr@pq|I+;n<6`0oh{FR(*JAh z%EO_2-~Bgfk&16Z*(;?8A!Ju7+4p@*lr2WqtP?6)ELpP-A^XTS!we=Z$Qs5rV~n!J zn6Zwr&Yah%-^q2Z>zvac{+R2U=6Rp@em?i-{@ly6>gQx)(6=#Z0uR(Mxol*9i+Q@+ z59P!90QmNm2q~VwH%VZj9FR+64>ILr8oy>?cV13tHOW|R8Xb#!}OYT9d++Y>Jr zu5BeoGaZ)5I0Q678m0g4bNG{600zj-Dhli(;bCKer(uCVe+c51N31(DP-niDx|&>q zwt(EB4+@gIePB$H@zt)|P&Q@1IgO4L>+XHGj!c@hUl1z#>cWoBe&AwKq>t`*DtP!B z|1?J-PF2YVwz9|84?6DDU>kP12;|e)1Cl>bbQV1%77wf$Q8|3Rb6eE){NhBed3YCC_Q~-n%hap ze3WZ4Cg;n!^_7;c-eE*qr$U1Cg8_S@(%U)Wbp6I7SMY7+XNZlq)rN1FN)Zby|KaIe zQa5dG-Jg$YZ619jz+^M8zS#0YY#T>+?z;oa7sbj|oV>KN8H)J*k!;Ma&HM$7m}4#f z9h>d2M0?KKiC$dGycmb+sg;35urORoH0+||R0qG@@AuF;ZD2V!Qciz9u;^!c`z z%z~2(LdW!N8<5%6Ct`W9VOg@V=te4Ezwk8pMe=2qtgaUt>dVe8Vb_R55Irnq(i;rx z-eg&a#B;W$l+Na}6d8U~6E<6kddaR>ycVpU)ET|n)QB!5lzWCbW|~SH9AcU5=|%ml z39-ue@URV%NM_ z{#|PBtPjQ`Nqh=?I@y!U{1>Qc!;cw5neL0(eneXSAxLZQNfge=OVHvs{CXnN1kw60 z`z24~^>GI5zx-WpG1V0S8oA$k%kuZ3SrY*U7MGuF`7KW((ZO;!bW&qmq6B6>_(q(yB3uS5 zc$Z(OFU{&3^0B|t^Ri316nJxSeM{?`s5U-e3~w{%VYb;Aj7j+g9zKPwuxsczVD~C!L~W0*VJ3707pKK#0J{4X1Zyi?Arx!=~9(!uuN=4}1;$bxaRV zrae&bx_lAFJ0${ZcI$&OU>+-K>#<;gq%&M;pa1Y#b>pH5d(>ca+vhC@-{IJKN6MTl z1sz8zILD1lONzb}IyB7wLZvu3V4HbkdqyQb_Kbe)M8Cbq-@qRSq&MVae=Ct*IjUEH zi5Z#7t1Xh1-0_yk!s}flPtl*2^SPN_h$}*_C&6qn_M7=7)VpM}ZVzAp*W~cj8158Vi~BFli;{BX z(=ybvyso5XJ>L2UkDE)<;xVlVSGO4==~Z#^`SEI7q~qF}AGb}c^{M}0pe09F#7o~A zPuLQ(8rP%!PzHSVpKhx^%V`1}FH5rE_HPyO7DLlvG0>z=VbAu# zW(FcIl7l{PI%|68`=!YfHTGuvII9ax!t=epeRegU$!=p;`stToHIocpZTY6zJOtTx z9~R~Io^a+PUJGS2W*&-7ihj}8^qD&71h<(pm3jYZu~LGgUR{m8N&NSD=sjS6R`q5l zW9}mIDfl;-M*y2dF4EErbW8FFHGWPKVp6Zl-XbJ@H9UI%df@WxA;UQ?xTHu4EheQu zfEG0W;(Fb)?t-kuY$Flg#O>j}%cXEnoU#n5YyQTnn);T=@V$_sE^_#Kyh(pJ>0XP+ z4X!)Gr$llR5Hd($rq0JrU=T~=vpEw@K2tdnZlfz2i~pL+JXgg*k|s|5ZOl*) zDNB5fDs$d4$h5v-U|RX!=Z&D5%zM?wj5;RaFa)Zk`O)7-&g!zmZeVAB*IR~NIqWE_ z4}Y>AU3VX+O-R%;Ms5V%P$rz`K2n!9ll1`Eiygpnf3KC9pG;?V8J-Fk%hts`^!F!A zwtON3fEFK;X|SC5;#*Or1dJKn5?1S=fUy~V>tK(ZzFm>}W9StV`%7MBTbZdSO%6>j zBv}ec>e%RazU4qLXiy&iKv77!+F9UD zxDV*R%%nx8Ov(Ub=+`Q`i}Q|u%GrPGf?oP#@mdNq z2olcQ^WZSQyq=erS698A+@^QIq1_Ggx-DQ|va%`C`)0eh>wuxPLD5QTX!m5Ug&TP+ zihpFWT)Ed0;0jBdBdRPTRkSz^dE0z-*m7D%T6zLn#X!7(8>h@EeRW#qQd%xG3Lz@ILGBiq)lb&reL85E&Y4V#V_mSMyDWE=icl6DTeBY=io`~O3t zDo+=xEcGgeTpRb7ot+z0D7lyVDXi<`{J44p<<)JSt*^Xx<$;$%Rz7_Vg>e501J7S8 z)I-@6xZq0%L10H)&c-`ATk-(0?1xURUo09d*m^&o^6-(GULZ6=w=8L~3(Q<6>PUG? zTqVEsRoKo7Ts(Wgy4AxT`HZkS98OckfWUL;d2YX;h*gN$)_BOi&v3}9lS%*fpsZ=l zOIq?MlOxZ31>>y6y>Y?6Em~FJ6mZs>^z-O0C2Zt;T&L=G20_TBCF>@;NQNErD2YoF ziAMH0H3kN#DpXcURS=PEj^aEWmLGb26I8$%$N6=S6t;U1^$c)a=S`5n6O`F%o`1=) zu(`F4@<;;KCow-*CgzC``q-T&8t?5o_^voj_VPS~AM@yb7dI-V>{dH`2G?zd1oBQt zny34|BfENUO&c@kAro7GetKMt)ZfA8KVc66DaDB`u8;mH-~weBd_`D#7m6u7nABr! zZl9!xHxB+nDku%*+is=$%(tLcNiqKJJ&R z%X2jm&5`fdEMEO~-nc}Q2^FzAml!?cbzKJ+Kz6YRy#BLdB;GU6O>J18Bc}}X zfuW$%+G{j7WKbs)dOKk4(b2!DkpSxn0AS-j>{iRGYBM{Y)5pV>v%BV%zAjq(KXTu; zgFHBs>x%U+#^$(-W&kwL({oBseNe5pDJ<_zOLz)rXjc zKU8`cLxq(dBxq=S<64>03k=#2p4aE?Dtga3uhNarq3!fTcuIBsM}VSxu5jSi7Cyl{ z2)aDfdW&KBFq)IP3J+9N{A{lj>Lz95Z9t6sXrYRm%<8trn^rn*_2pohAOi>18a?mI zj%O%#&@jXokqLl23Qq_jE_M_AUF`ljZx#L`O-PS#ee^R9C{+$z2$lw!pBb}%-(^eC z{4wMa;f;E2W&MpX3J^nD*H{fv(%sube62)kL|Q{{oR=WAO)iZpeD3t`_Oqp95Z9(zlD^L zK-kn)^|v$ITOP9P!f(X|@A@C5-jC*}yObn$cUluK_19v7>w zg0U1$H$F1MBgTEj1^`AWx;%TtoWoC5fdw%Z`s^-foWbHKn(ahvVUP5@LdJlT=>Uz- zgZ;!s=3XEXXi7)ga2mNiLOKUZTfc!S9VH>s$(BxVHbrC68RtqaTQXE6$FM@%zB9DJ zyYTtas={o8-Bs70;-lp)O8qipX|qAAyuAlP3J{oufTcTq&+XnB6(_d_lK@h{{b)~Y zBEWhUuu9gZUQs%eI?C)Qp-=N}x3zhUy?Ur`y3NQ}FIMVCxMRLvpptwa8CR#HbF7X~ z8uvQEpdcEWRrpj*L)hZ7tx611GH=|9DY?s^AGwdPqaC=#!kA_rXLW@DAQ7$UR3Df+ z=Pl3)e^1R9Eg_)%Aqnd<|G(uxYQ}~-FP0rcPFve}QNNwJ-ZsM>55?80bK=)uAYoI- z+TBKsh&Q}4vvgIms&r`qi$Ro0olF9OO5l$4QN(wNwo=f>-EEzAv4XrNud))VX=C>6 zmstz=TkIy4orZu60j%-pUIWVG5YV5N*v%xUX79W%2;{@fTp>~KTpjLFgPM}0qdtzP z7z$1C=`_HFYxKZZiI@C^HsXW^7>arxF{p#C=-=t#u9Vvuo96+yKnfU&{g}Z+kiU7Sn zK>K&VP^iiQWcF=EpLC`R#fE13L~ruE99VvH+VaEP{N+RS!GA$A{IHD6@%Cwufn$A%CQ52G_wXZQ@F|(9KGNOJwM%45gilZLaKffIA zn@!Y(+sqD(o*uCUG$m%!L6=qU>yRQ$wL5BaSe)NFcWZs=xlcVhb90n&z_qX&;%TBf zj@2>IYgig`_*@Q*qT9bTd3UeRf4k%J(Rt!KpN5T`0TzRk^&z4w5n0RAQwbK|N7g8z zHAIE}%wd3ianXF72`L5Aw@M%$zUVU1U}VWljxNYEk;VB$+~)D3TiqI>;hm?pjzI?vSYXCT4ig5hrh$%uE=>2luTjog@C-yRn=elEcL(pEz^Mrs z!ou?YLJ0khO&kxq%s4ADKr)^luYt`Ihws3xdjtecrKa4!XR0+m3Zcvzo9zd=a>YOD zC0zZXAJ1i@)U#dd`t04tEI8$v&(<^4b{QW_x2J=T;=H30c)soouXsaOLGX4YAJ=;B z<|EU##+A@5w-A&gaG@rlC#A%&?(B>m(BL0aDiN`_1{w(Hy2f{tE`V58$y%tF*+DjNh1KA$zK2y6l$z2#5R9u!O zTgtk#Pd)%VlNSmDNG)(%-{ONlD(CXXRTgI%8aCG}1UB*`EsNckKWdgSdV6&uz}XFl zjw8j)0CdlWLbw|AL10*0=I7(&C%>+p`cJXI&aNEZk!H;6P9LSqP8S$~4YCWR_>@`0 zwE*Bm=^(m7j^A1?o6KYj+lZ6pbm^#OC-pwZc|*nIXcPL@@8R7f7H~c!6g$;OT}o;< zF1yzg7n5Qzt;C<2bD*8-7daHIK|GjCg*EDR4`e`O>OONeV0E4`1F3a8g_yr<_<nBt`Dj>9Qc)#257n+J0d9z6`XO>gMI@hiOx{QU~ z@x5;V0lb0l8Z)f)H!yX8;V3$mPscPu1n+ydOMMZ5YXq@xU}Lu2~dlC|7GEsh{^7P|b%K@qq^fn1yCai^ud z)Ek)bhMX!paH3F;=FvbpEi;%YyG330>5=P~ARFywA{kMSdL>0K%0j+jhtA+ll zgvbuU!EeKoZdAly%yD)oDEmGp%UK5vq7$S0l~}o`gazKsM%!o~@05er=eEB8gEPF>OR zMLqa(kQkhWdfToWKNdrq$%G0UUIaH!1AUP0?SJ|pcUPtQ0dR#8qMBg(233dy8?^ll zp7N`I92w_64I_>nHz5R5oGdFm3JA*I(;Xf->Efu%&yt}4k$MXdsZ3*-ryrty!Ma2X zJZmz43Gij?Z6^mZ1{ES7UIxo&Es^;HohM>R-xbQ0b^L9;(^LxT95A?z3YmwvY3iI= z5g;(4+~w#dyNj(mPyz!?=)JHX!lJ3Id`AjkAj62~gn!nY88`8!vL%D6F z447X0H+6ErFdtm~6jrm$4apm%mg~^%29F^}Y-Z+*aiTlsPEwX5nAFj07zz%O4zaWy z-x?m)%_gOY9@nnNmk$)F$5XZ1M`?WhYWq`*}x*_)IY-<4mYPS3rr9oykhyl@_` zL4ZNM2N+a)=`t*&pv|`R!<5-@@;GlJt)FWf-@c4911X1wb;;%4d!VNA|09<>VJ!wP zqr>zC72stxxgCZX8zdX54=~5%VtM zwIQz+drO(F6Q=2%R7{ugoD6LIlW~gy!bRy;OYT6K*d#is=1A*tdnN(F%fn$$=Ypn! zArsB4cb2w1LI-~}%un;Mgl#I~@$-}o97;K0OZl`~=^#SMpsWfM+L@Rcmn8sFZv4J+ zLWPEt3HZ?+*|AlFLR#KFUbUtI+!<3AlDhY3*NOru5ZFaBo$GDceQZ~?vCj%{Kq+p3 zk*^JY#$8+=cVND69-ODwfmk&hWL{f((hFYys=hSZJU%678~n?w&iSV&L@}Yjd64&q zT)9~ChwpbGw&n1jR;$UaWh%Dr?>oA6lkG&)oq+iw+m1EC@kaNi<^%3mJdLzaJQRkg z5og;YkL-g32OGzcPak*lgvPvbP9NmqlJpF3cV0-dINHcGu)e-NIPB*0$h9xTMj_eu zbhp?vOhwO+rIGIG_Ae4lP&>CDy(aNy`Yy8`AwT3#D_-m%yFEUVRpyas0k57v%%5^X zs3fbt*J-fw(g>N8Qw#J~Sc_Ay#^S-0BYr8(*i<%6zy_EvbUoYS>zBP+(??E#cQ)$h z(_7D;fOpnr_BLXj-Rm>UXu?J_$GFc-N6%9FCQA7FbyAg!LcA5Y+R|&eUFXrUetv{E z%vw@ZW0u=850*1ron7SS{06b{pvdi^3k^vf`M&7w@G1jZm{7SCSXAti_^a^B>652j zsjp*>B)z?Ezx3r*koNXO-l_EkINpE$0Cbr#+ zjGPQBfTdabdLem#}y3Ve*K+2?z_|4-*Ww)a5;{*H( zu?v!arW5SO9SbjjE;~K*OZ1MVu|Wng#@X4bC8D)OqnEl+5{VSLH7Y0RJEA|he$|*p z{mku1Xfzyj!=6OrD7kD7f>P4Dl14uTr9?-o-FiOaib0Q4UOB&o<{*v>DSUD#_0432 z_j2{9+C=v4*D!1JRZUhw_LYW^QJk%4?RE-)t1HqH{CjAMrw(wLtF-13I@&V6exenI z2z0r!H713<6;wj_J{Hh)zGw*~tCxa)6JaAn#AJOjvffX8^ZA|5MCSIbmCH6~oNKuhnd>Z1xa>43Vad{Jw`;)$g!NssDm3m@lK{U@p zsL~lFTS@sFene4x-*-Q8%<8R{Ae5~jA~d_1+byQ8l0Ch164W59MWS^bC0NzXf74l- z!YE3C9S9qO|NL|Oj>gUF#(m!S#HT}tku^XqwQk4nVK2X*FBoW6BkecVqMW*Lx zMJU$9ZpNfQ;iA(C0dVT$n!q+eyxR>D-9Q*IkQ<+_@$7je z3#ovObUR<7v(_;?jSz{ZlAS%QiqKKN!zIwHW-xTBfOU%nX_MHN}rJxy3OXU#% z%=WJS!GOS8oeFPazm=|K|M$@`E{~v3s|KI3G!KQ94@Sp^@pvEWP?{;!g5$&qK~Yg+ z$iyZWCL&~Mh;cYHyF)uuIkXVKq3d?-!K-x}F4<5u(E-Jf8gfmwKXrv*m;8Rpw9nfn zsN9N$!Piar!rq9?18CtyifSs+&mfI+0T{7%y$^ONRtaS_YMU|`aMuNtjk$1>g@*RT zu~ibf|Fu68Gx|9al5tg`%vZLqPnm#tWvgbt4H`%k^yWvjHxw*J`m?ly{dj}}r=$BE zd(3*}{j28ZhdQAR-!{3^iMTUBm38a(Rjzwz0>D;c%9VNQ@# z*EMZR@`p+;gX)B}LVsnOyk;%5Qjq$0&vttPJP_w@FiSrHYp5qI`+Zq#9gIqNM2aOF zKH+hXt(CvIfJE*|g-3)7-oN>p30Bq1<``T|dZ-tdn0Kl#7x%#V12o6a!?uoTn2h>V z*{J5BM;yg8Z_UlPFa1=A>_D@tti7~WR+y}}DlP*hZ>x8=HfmD z``4rufZf*ule9>Z7bodB!=O6meHe`tfz`Z_`^OmA^2P}T@Air9PNBRN?M&%flI5VE zC?>`F^D5H}k!W?0J)~45K{gI6rM*tno-zqVX&H<_73kQy% zgFbmYbbVvQP6oX6rJ&=GJixvPRh)w+u-_Xm}U8_Q8S5f8QA0<{h`(ThA$ zfr}GgmZ9ZH3Y;YJW>8u2>^w;R3^{t5ZH-f0 z1yE69RjUiyr6r)`RM`gMjds>;)P7i_XJ!=_<7`*`Tl!?O|HL`9KuU~s_Co%yVcZs4R`%4!3LcU4&2C??p@fJ5~-S4EfKmV|IrwHX<=a={tD>9J$kIK z#zqGeS-$!d;pY~1Il#GLeP}T(4*`sh+t_UT-GsaA6IDOD10BEcTSfFpY>dWW_fvKI zhIm0uuKR14&M?Rl?u>o=t_yY{q(NWl*Ht-*=IZDfM6QxM`fksDL-*(6m}USHTOk9} z?N)@PuDWM{$F6g+e;-UqPdG1jp}qy%C$OC&J{?8Uo|lKNW6T34pu;k;zD;ueiuKnA z9=fnhLqf&~l0lfmPBn+onE?{qdjY}#0Ek=Kn!7GC>Ivk)tWrZw^LtY{ZhB-NZ2pwln zUD6xWjXzWI?-WG(rugNOH!4uMK-)MdM0_*yl{VoNNZli}&f1%z@Su+5L0cPkJAe7= zkcAwBuaj-Z-^E7z7_9+~&i~&8L%J>QJIg8%7N`d@Vo?Tr|%r%u_L}3kVE;a&lb8_peerC zBOTR9P?{Kib6}z|IfEt_hVYg$-J5n516uNtj2fru%H=;N4le-j4`k^d>W1aO{U}4W z0oI*F#xm!>D{h*7_3sHDL6>uf(s6SZGfa}oCjKy?Yezl+d(^l6VA@Hj-ThUiV31~f zzxRsF3@*B5(hj`%CiNY%Z&1lQ`l#3UpvEehus{_4z=7Y^^E*%l0Svn#$$^)yy^R6c zNGsIl`>9o!#QH6hO3K3N;o5>b0B$A2y5-APEJfsnwVMmR)=-@Ew6270K3#d-1BUbJ zVw!(7<#S~b!U|G4H6NY)Me$P!RGrnKfCVtO)mzwT%4Qr}zQx3I849tgI0aeLy)mj7 zP*#e3a))Vm8-UqR^AzTCx9>0sU$2P?i{aEDO_{liiE1svrGywBK2eLJN0Q17N{-!{ z(J2z&D&8sJ+#^Zv#V?l0^r;Iq*K%a}qo|{L-K|6w8&Q)QovB=u-P=nl>!hzRcmP$A z!FQf$zSjk;0HX;TAWtr<(-lBf;7~#8R|a4*0P~h~cQ`%;he!8>jynkxfyexjb^04` zWVYW-kFw&KHX(|ek+J`{cz|aEaFpK8a8XgzU+gEi?%~C$^#s;J?02dEoyRiHLI{L@ zn8ak#F|YbsO)q7obLoDZ>AXbPIk5{PD-Mur7p^zwSHojduUxP_`{~9*t;f=!No-wZ z@MKI^O`l|Bn~@5__{6<)^~HmAQK}8#(9*p|z5$dCkFqEx(>VuYA#lGv=g+Th*teBS z@^W794E=Z&&x408E^fvqTj8uc_2cqhN4d;*LPZ_q{i+LIpSpZ~)yAOMXh5&|V|ZS|(+PQIYMCFn*0SI3ZJQuk&{)_`;yj^s0OZ?^aI^6*cY5FK&-0W^oUP@;orgY;Aq2biF{AZPk)Zrv zXs7E4v5i&P3#}n=JM?rQf$9JDEUMYm{GgUj(K17W{);UyiyiTAq$*wXDoSydcei;k zkv9HSz%OcO8^3i{I@aaO8EEekopI4cWu%($_Nrgh)=H4n{f#yIfx(KjJO6j=2S_`e zn`I#9HY~VI}-$uUOU%3VhAMqES;#{_}#A<)HH5wEoM~j}| zvZXut1W-|E>UlY=;aX zZhsfXsy+eO_MtV-CoS~DzOZAc%vY0ZfwTyT>-@95&{zQcyzbYxyWQzPr6N8o3~(9z zcS4|hn8H3WK&KzG`-hJnA%0{AHeLL?`Oh?9L2ijB_XbxP0Kh7+JN)i~=RATw_xwlr z$7vz`bnz2h=i;vz2})`RI((bI*`f@7{hm#9*_Z{JiobY;5L`sepVY@9h4~gSCG*F&}0GE>jJB(%{L* zx#Pk=9@wXsO}cSOQ{X#jpJn4pdfeY{THwi(vX8X=r`h~e1BD$5{{jAK+|s=Xy>U1E FzW@MsyJr9Z literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/target_vehicle_selection.svg b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/target_vehicle_selection.svg deleted file mode 100644 index 00802b074cdd7..0000000000000 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/target_vehicle_selection.svg +++ /dev/null @@ -1,296 +0,0 @@ - - - - - - - - - - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - -
-
-
- road shoulder -
-
-
-
- road shoulder -
-
- - - - - - -
-
-
- center line -
-
-
-
- center line -
-
- - - - - - - -
-
-
- threshold_distance_object_is_on_center -
-
-
-
- thresh... -
-
- - - - - - - -
-
-
- Object -
-
-
-
- Object -
-
- - - - -
-
-
- object -
- center -
-
-
-
- object... -
-
- - - - - - - -
-
-
- shiftable_length -
-
-
-
- shiftable_l... -
-
- - - - -
-
-
- shift_length -
-
-
-
- shift_length -
-
- - - - -
-
-
- ego lane -
-
-
-
- ego lane -
-
- - - - - - - -
-
-
- detection_area_left_expand_dist -
-
-
-
- detection_a... -
-
- - - - - - - - -
-
-
- object_check_forward_distance -
-
-
-
- object... -
-
- - - - -
-
-
- object_check_backward_distance -
-
-
-
- object... -
-
- - - - - - - - -
-
-
- detection area -
-
-
-
- detect... -
-
-
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/limit_shift_length.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/limit_shift_length.png new file mode 100644 index 0000000000000000000000000000000000000000..0cb9eb893943ca2951ab8530a8ca6a7acefa27db GIT binary patch literal 121671 zcmeGF2VB(G(m#$XYAjfTii(KFV5jW@3nERLC<`JTM5MX2W$DW<3rOq*h#`uIh{h-u z5D^8DY5_zPR6tb9A|O?ow3Ygs^V!7!yGis(o_n9~|8MSn-LRi>&YYP!Gw&(qbB}D- z)tWV9$&3jTCd|^_qP}CogsF@P6DA*=_8nY#V9V5pe@*nbN)(@id|<-O9(yOP*%nEUnLe#*5}=&whqPp^#i)Ml`0Utu_3K zF;0qo#fIWxXYawj1f<|Z@fxC%s_-cKFJ6tqTKM5=4P;|)ifZ6RPIt6_iO zL^sQE26f~xe%n?VD;GPw={B)#_HO#_w)QsahU4cLnThPHIfz7aGyc~h=I@UJ! zF54-dj$Z5yWJB@tqL5)1yPzAJt!{T^#?7hu=t5ma3qNoebN zQQY9FwWk|fFZMY4BBQbyn^1M+Dr^+?6*QE!mo-=yHbpp1Pal#fZnG~Lc&xU4i!RQb zwprT7#Mj%F?j~)c<>GBkmvpq=vP05Vo#LZ|x5L}fWbj0qjE^nZ)`w{5ETd;2&wh@k zO|sXL^0aX!%4?GyB<;4S%IeVM;SF1FJ37(Z2EWx+hptT}s;m0g;>}&P9XI2wO^osS zWO?cB2HI3@byX74P(wz?Ngt=Ju1|&gZszKej)q#AGUldR_YfVmfzIt(J6z0NiRiB_ zx{~%LzAoDxWt?ob5WR?|UQR$SRmXI*gPj&h*3NXR=QcH6?3%5Xrlhr+GhvSb=UG=T zvbBk?ryg0x$A)b5$8|@lw;9ftu4AZ6u*L77+2FifbWH8s%(v{I=s9hs+N*oX>yULl zZE2Epdz`tOjTTi_o32eKnwZguaBsVsJl$@Ki>JAvv>c4%W~+(OLb5i|2cGD9TAOaB znwjpPXgf*E*^-T&?9?_>%uQTet+&8^Cv44lYm*(4*065ig_MqyhA;2|@yA=&K$`?( zI@sb7e=!w$qqX2c{Lohx3Jd;^U!si zjNrF3(1T=w{wB$5J4#Cd9WaX~-4^tL%_E|t4jtBk@piNGc7v^6L_<|c9Vcf`qLZq( zt_jIYmnKaknwohLO-OhhCv9IlCrxV`14&<9HEBtr0hMa4Cdt0;DCujhZtG2S(!>#s z-Mn-RHDDZlUmf+$6dgnMbsa-Z3THfD6S5@CrSGk)uHi}4`tQ#3r+nd(?-%eHxp>=c0WEQY9R-rpGf;)yMfBD+)Fu%P zq^U$lRU~Dawz`HlQ5~+)uxEUUh9uyq8TW6x8R9g&t4h~(M3PhWh4FA8AreuIeGS{a zbX)dwpLa14q^l3lYWV6INK5KEs?uOy8SGh%E-sB8S*4o1>vkuqk2&a<4jyb0T^e~5 z{ATcfUe=DT7#u)0jbnhpsM>S9F%J`uUHWT3^M|+5vIp?vRlQc_ZU#NTl| zJPrrf2=G56|8Q^*^$+JskmEQ{hf$6bCo3&3!+{3Y9G^}4JR@=@U*gx`8ID{0>s28* zI?j7?==AvumxcKq445JgQym<=>^o;zeh<-N{%2e zF3oZ3qopP#i4(_3v!DO3NR2c1UrFu%WuWmF0K-X@N<>bTYzvOa+|At7PR#}n4hfky zHC10-CueUxbudGQw#Zo`C-t?UVGIx$ar%0WL>iH_!Vh{rTmevL5ql;)XL^Nv900w};-z<&h z(Nl+K)j`U<$EBH@=t^pD*+DZik)fNDSSqflIa4GIle^IY=VfV2uEuHjjc^M1UX2MPtwhK@=HXHN;QEYYlLo zJZN*o*8D}Z>8VN6zyV4kXRE9BZ_;MutxM-2k1wZ920((OE;w><(sW&ef0H)Yore0{ zGW~Meq<}V{PnD)?=nVQjnl=q-qM9>|?cicG?QVtIdYBZ1^T=OV;$Z#hF96BPp-#%GN)C!II_%BwyGE zFdhIXOwVoIw6|>av18wp`D)q#&SJd6XtRYqr-AhIe@YvKBdXqdAX6gfvEIKaQ##lk z*u&#M=twBCWvh!BUZ2F-nPdq1yud8SL*i5s*@4)Wq z8LGO$sz(Jy$l7Rw#6AZozOaL62q4>I)(Hg)&XVvB3X-IeChKv7=dYs<^g;s<)B#vE zqy3xI0eHqC`}a?Hhcucf1&|snyuReWNF8XbG+5|=NF4xvBT1kRq@s=cH>pFu<1h41 z%hwG8dC&=MwCky0y`?Z6QOADcz_NjN`0RN`-N!r;geP3<2CIPu*JDPurRq4@qJ4?^ zV4@*rLy-1izEYPCVJ~}!ji}o@0_KSDEo*}{( zBeq-vbOYHrE-8N1&esO%8sW9oBx&HSArK$!ZN3&kI0GKl#((B4Br$a9f8z2qTTT&JCTF3Nf^o|0wRah4p4?g0#cYA$B-*#+o*tw07Y@_jPdpjvpr^DYi$3p zXNG_w)In?6_6&TNG#**easG?vNF?w8W(eK0E#ugc5K_nSu;wEpeF2KlRo4c2kRb9i zLpB*d+Slk9e(i2G0&l84!hOK~Y#cdmonK>15K2;a2I`Ce;~2^Oo791Pc}d}`s6%!h z5_*P4upjluAh3VPJ88f;Qh$#kzIh&sB3u@BX1=kagsRbH0jqkT9l0g4mFV#ZLbs??9sg-~BWH zjS2;Z$RZHI_nJxni_~HGk%tZa8r~Tqog+ftLI2;h1~|aQI370nD<}iKkVYwe@NOVo zjnPr8*Vo2lx==zO{t;oL)&6OOJvs}eOGl*$tnh@8Gai*GkQHHPvy8yPlaLMIiF!wm z1708Y4fZVNcSiljvP`-oe(1|kIXeS{WvdVhXUCZ+TlF{Nd`U*g7x<3iI7zS?V=OS} z@Kccl%?lx`{YMN1s6tPjM@%_7KKtt&>4?@LEC=3TbcFNO z`84G3Fipd9q=rzUcKVwL=gVlrgH4mt9TR8senq! z{82LfuarP#I9&RR!u9`OmOv#T$&aPOu^uC5Uk7^=W11-h-cXElHa9V+!@oy*k~qCh zngnyQi>Hmco3{;4#zhaW3+Z`z4|79`6F@*Hv}j9xzGff=rOq8Lwq!`Jnz%^nL26YG zFDVB-8SLIG)T5zgOtytS4d@%gO0PzozA00jixZ4Ly61?7Qubh&A-$$evUSCZFer$J zBw9!T!dP zAVuKd1dtaJ!Bnaa>ePXLIii!9Cvt>94_?oN3ZTM_u7h>#03W`bCU{R(#zq|_uTX($ z2bu>uct+9Vq>tCZ?n7X#Zbw0m(+uFap1Q3kQ4P&&O9wikcu9q@3XGe z`X#qx4b@l|)PKTZ$jD1VGmNbK=YPg{51cd(`k#2T&_HL66vwZO_8+nw=ks529UL;h zbt{8)ncG|69;Bq86 z?rG~^cib3Kp?!FVjE$BN8%K>eIah5h7u1Am$fnGAkF|-e4>ThqN63lCx1ufp6rG{Y z7#c#kV7R4`Ga8+b1S5`&%jeDz_I8D?kUty)uV&m4L$HP2@{3xRZ49w$Etpq`KMc*G z@{P>8F?7>l?gBIQdg>%kFvpPpLZ+4^jm*EEx&xNiA(Dyk4CJ{D^}WVCV~C!C_Yn0O zB;Uo0`^i^dp#3}_$|jap@~$|BqFb64y?Q>E)>3$57DqlHys zu+g-1k(Oa~PE5lvcr&gBjK%B!SK3?g(s0BFfIm)3iXbaZ;PgL!?v<301B*V=<_ZT} z*nVJi&>)S6u1OpRppUWocyT;|bN#Up%ZQPu6C;E_&pqHz4{;fc zD!8YPjxVCOv772h8rUyiM=$gmMm_vJ>Mi*7$4ltP$UE$i&)#m_Hv~K>-X7SoK)BC| zw7jf6NbrRV>>~`Ew40mtABXM#rzbH-MVm65OycM`bL5(by$k5P&)6>=@CrQt`q(7< zFz6pgLbp>K;nN$R&x6Xy%R<1+SukP|EFXu*NqtuGkr~ET`tuoZD5)`C zMxz+@b@SliJ1LrMmVC+bvB%+SAtMKS|N0%y)7U}Xzk8DFJg*dIJN$20tiLcqwl3D5 zo{qMd4FlW6u~pm$f=Ao5u?A2IG>L7R{(%t#$AW$O#{RP*la|2@;Gdc@^yGGX4@WrT zJ?;?sUz#^gNn^Bm;{+T3zh~ZL!N$mp_2D@9#0{5?`S;D6j0~KrA3wDeSlbc!Fk+4V zZ<{xs%NWhUuQNV>YUE_37zd6Jp zGl+ik`UJu#SdP#bdll%TK>vH+uYfdY~sTd8k zqycICH}m=6G%&G`)`cA!8oHnf22kr)g)f?o(~3W&h@|p2AF~)OR3sfPq5jEtE&dxq zmB!17%l+{Il5s+n`jhhfh^$8obp(2i7}x*k_ee%Q7&l6yJ2YT(|2O2RsVONbs|Io( zCC~q0>?|XL7nk{?(l$<__`k2i{ofNV2R4loF4qSA+Yh3RJTUfqXQRygNZTLTmxMmg zCvIa6$W+{p;_8k30rr(XXh|6#ZU4=uYB+Z0f7dX}$`N1>v#0uOjsd`8Mr@Qh9*J*9 z@7j@T|D9dSp>dR8AuWQ%`S3kSYxoGzcsu-G^Ul)$DK{%EN5Db3d#p6^viQ&7b(BEy z@EIsx1@r%qf5pJwpL~6BBzFDdOP8Z#Qta-?7dP2AI4__Npt5rVvd6=eCQMj90Y39( z=)3Df1+D9(QMz)wo_y`(%cp*8AmaomvoD-aE-rrlu}(s{I0I)WXbrORwE%Ac`$`b#liG=Eg#aY2s_@&(}gIMY)WBY^}s%O*}MvFwwdF>Lx_fT_YsKF|o1{-0E)hc@@ zOyt8x9QorWBZx4a5guwc8QmzhQmKlhhEB=&)T37wNoh0G9eM8ao7-ni45G;Nou7fm z*|K4IJF$H4FZuk8ZG5ZFinkLFQyj-m051laPn*VYexVt;9R0Y($H%<&lVd$Uqo^<3 z%(BWtvv4QZD--$V@ma;NCs*H}MQF2K-u^5(kdMjmi}B!kI>-qoxc*|Q5wL2niVYB0 z{oSuScU4(@FZs?Zh_acnO#n?jX6eP7RjMqG$-c$b{p*6ctWyhg6s)QuUu8aR;$!0I zb>DNnGPivziNqdeJ}e?_&QDnc=FoITXG_$R>1gUPGhACyb?`sIs9lX8W@3{E!HOb# zRp+wm%9MjB8R-V{V-}3@MrLw(dz_|-p(>*F$dt($M})R}(1Ix1S^JBoWK8c6BaU4J zDBpH|;HTJI2LYrv+l_&1#*!_JAd2}g?m9mszae59*DESn>!YIBlWzyfbSg~)!S$~O z2~yW_>)@4xdxbJe8uqP2n!Y??Zx+FQ(pGVacCqQF-R@-(R%Be_X0FqUk&>IZC3P*le}OJBYGa(Ubd?X}*^d@oX8*fE86vRRs+no(!t4`+m%pz@90Y z>-I2tiU0N~Xc<2)oXc9}s*?A9N`~k}0bN1Xsz=Gv+{_i5JUQcz!$l&-X)~C^?EdY} zDH)D~`LW{dVi!r`T(3-+81Lot9a{HZ6jeb-Y_u2+^ASduQ%k)~nxwWic(Z2Q9RpQdA(wy4)?1crPpY__-AB zS0<;ue6yIn#b8B*wtatN5AMFR2v)j+smJ&H(-;DT^R*xOn7{0u9>dQNsJ1x6&D@2+ zPxIR^R$-iu1+K;Je*1}!d3(s-7*_KFAI|m4-n}Lp6((V{o`)6H`Oih#^cRMc@Xbhl zGg9A-6qm*MW~3&6Gg9A>)Hfu>LG~)&kkmIM^$kh!jEld8d*8ynZ{gmUWDBH!zJ+^} zr+v#wealIWPmO*;jUA6yhCbq#NSo_f zUm!L_YrGV`b?XL2|4R!@jw|{1=bZ8HUl=%hk>v7&AMQEF-g>f5*y?)J)ESI2ef%Nr ze14WP)FN~zVPzV(hlGCo&)cf{pYNNKV`O5vfWY)JnAd)}FZNc`wS?vysX6ETS{IAF z4d^$tpWi%#5%$r7N5$qlC@L(Gez6cMDx^W3>-{VPr3+0#Z5Kn8mRKp&pFQneAGJ2( zR7%e&3)jWDp+bU_rq0&c5t&7po~prJ!*co&%3k_-@&QEqTfw=kB#Oy_2%}jHp?K$W zZcSI+2X8xWlZ;EqS<;aZ8o0^ljeWRj;J#Tlad%!F4H)d}Ui7|5Pg%H7v3KXdr^3LH zGS_q&*R*#BSz-Y)sp@Z6o0F}twajdPEWdJFKyPZzw%nxxY6oX(7f?%M%{qcT3xll& zss)cZHKx{`aW5#%Sg6o?*EYUnb$g496aTz1%80~JYzXznqMWx2(U04!mba6iU3a>8 zeIaWXJx|m<=h2a4rz?AUl5?eC8o$;%CM69vb;lP=H6F)TXAU)IE-dkReBn?|c*el{ zU002&%GN(!xPm+T3?;|poM(4r5O{LfrBYRvX0$-dcy0S&qmfBA%e`iy6nUVsS1zZ< zbfgy`=YXJP@x^!-@v<;lXI=J{eRD!`;%W~>ON1;Fwhh^I>%+xxs3oWF{9zIj{5bxl zUD%sdI+0DsycJONTVyEOPM&;OZI0aXg&Rz_@14D5lbkrKm1^5vViLcpeVau3{NaGE z7gDx;T^e`J^#@btXUdd^i3Cyfn&`5avW}iZg#abj)C>7NThP4uP}vp_zw&a@wYjW< z2>j}vx1NQk`ycQhDCw{4&A40rWWDW4Bjc;LE2^{8`4$jalhk!3<$$cvf=F@5?YQV>Q4L_B^*oTyehJf^p^6lyVTU z-S0CQB7PqdUU!NlTbWpp@7!$(QTUC*%%JVleDu>4ew+F^fpX^p`WkH{1b2DqyJS9` z{e=^N?uL+-+gJJBr)CJ$2Mjh(X;$iQ6^hY2YbsPtIqT=js2}J&HaJsQc0-28OKo9h zT6+>czbkRIB{Lw?1X$WAZ{>Z6bsH zy%gF|wLm~;vz1`x`!ZH+YU@4s+*q?q=aOUd_?RJK^ySR+3h04Q>fwH8s9MlPOJ@(et^5M?t+^y^5ig9(wfZ{LfNenqM+KNe8dnZcymXU1> z(|eBQ^!g|%FdEc4p5hDV8^l-!`n$mPP3k;d8U@O*Cgu>gnel=xnam&QnvVo|^EN6l z8=P3zp59jJXIp!C-jvE$78K#|VOFk~s_cUbZPM9!iDh^5%3f}sr_ruJ?`o(nG*;3Q z@ir{?eK;%oSI>-|JFMCmrIIII??V>A_Io@5sqg4b3OkdsW_i1}3U*mV9qpX&uJSQ0 zTvJ4I7#+u^RD$-dEKsUHdwID~JlS<}y2)@?%(h@k+EH42)%}Eb2Za^}CO7V#_##;^ z`tmsizn%{^J8M1_#ps2uu77Igv}&C2|SeT{Kj!^)7u^2ZJ& z`1f@kIWcwFB9XEAw{v!H-nE`${Ib*QpvTOgYfH(H;Z}(5n zt_j`P*C01=c;%_oT;uPiF)Uu-P9dK*mP=VL`Jf93E8>GqOH`f&9LfvdwM0NqIlaCA ziT3L3=hhD^pWkwC_8EAckUgtBhh+U+!KU`H!~UC!pFX{!)n|(;4_H5qBv4-9f+I8h zTGD$xoLwgu2Nw#?-nb@2VTcuSYV8;5gvrKw|8=00%4w`>InS5B^R@jRrWZ1)vdTL* zxRekoq~J5J>vE*)66R0=^-RDWkJTHCr=8K7DYP(DvFG(~xxqrp8FwuQ=+PFWg5wY8 zD8#awbMEG_bOR=5L=|^!7{BxhL9X-XvV3eyTOtr&PJNH|#F}f%ShBlnHhHkxH3)t} z@vg4rH(DAk(&I}@5^_aE4B|8BFRTKa2RdyZ|GXl9sW=#(;aMfzJsYUa%VKz0*$TvQ zX=pql^Id(Qc5Nw3*0p3dU`MqX`R{=newAj(JMwIfDulvB$R zg8m!fx!4M-2uMsuvl&`5MV2MDrN&FTrsaHknJ>Q0C$Tq>Kxf^wb|3!mCOfc|nHl)> zZuhH81<*v*Kdk7&J@ENDu%l-PuX~VEoR^O-^Vi?3%k* zq=P6%_kN$vV>Dz5H!j9DMHYp%C-A##i&!CwL#)&E?vev7w|1S}DcY57rKsr8UUi!B z#-5M4PG*bPxIKilrxF}ovoG5K1yOoP=Z^-pRgsg9wLBmd5ko)7OcaPKdi&{J6Xvcsp-MYHZlY7L~piCsig_6MolyLsDf)| z`W4R(Au#$+l68Z)2eTAk-rn+Y((ZnAt9^LNz(Gpo>I+UmZEvgwopyS?J20hbBgN06 z+`G5pxZD%@lDd&BXQv$7Nv*UGXBA8lG<-#Sa5W|;R6LWR?++_a+G@?sQ_N6ooIi>@dR6L^ zYu9rI=WLq0KJNAo(KzL_hqF8Cm50r$Eb>~{9Ob4419DO9{R~}JLo*E(+sPBGd|zlJ z49-?CEa+1X>`i6Wu2xD=w}gJQ8^jqujIsut@!Ic!={~d%`-Pcq`NSa(A|{a z@k%gYxZl0t4T+zzzI5>vZht)2K^Jh}*)V;yknNs9CmtTmwM^V2b|)XAnCw`;wyU37 zJDIy?2eoMmk>@8rJ*_YQ;hox{oWWkEM0?y$(tLFu=0qO0qo=MWnoZ>y1bQ^W-6uh9 z_nL1A=_wC-O=Q$OBjhSDKNURLT^LD_ND|s42WWh5Fmv%x*}x|a@~+065ewJu=fN)z z7%X2DhfR4;6|{mHetjvcHL1+iz4IACFpIO(O&5O~HERx7@z#^0D@} zb49Clj|=F@T|nBab8P-*ZYJzbfpOk{zZer(#c~jDYCc$N35YgoZmP`@+goZzin`l; zu4!OZmy%zbaAsdg{L!~JG9gBMl&idpA;_v59NyQ&1E_BUfmseFSs*j!D-5iz)Vc`l zy%e@OcmH&OYNRuKw4AtP&EcWJuzkaWZGoXd7G$G=fVQUV@ynD08!o)|3L{R=$Wyq; z3oXR~LbT|_VSRf}>k!=uMspbP={;{*$|k$amIt;pTZQT|ss-}y2Mz&9d|v2(<4TQM z8AU{JuxctFv({3dTXGYEUV-T1A|tRyL>X|nbrr?ere*}PYD8*&7tq`Av)1vYi))5E zEK=5%1iHP@=qO1nShtl`-S9#R;)5v}YlUpcJnS|Z9Aepid@!1^NfZ$q4a73Y2u{3+VQL1%!=ovscg zlbH9*T!mJ`e(i5fPu`n>!o+;BWSxUU#RhuW1tLRk2}7xs-8b&O6CwCd$;dOevF61F z2nfqA<4<60fXv0S)JU)btE0Vk?Cc1Op8uQ_?WxOf3RV2&0^z56%?TB(4{7=09Z~$^ zYclv5VRs%q;IS#*f=f&yl72wQrC1y7HG=0fM&^*n@I2tF%eD;sqLO}KqEQr?QEE7}L&Wees;gsn1~ z-N!#wcz&*MAoSXLMCs2(laGb-L3Pk6`%HeZ2HJ8m00QbNs+RIGA@Cvc zviZ!fR2InU1>YZ@W;}J~qPc**h`6qt>z9P$PrEWM4}KsebmRyLe(jL_3pX4N6qY={ zH=s1Nasi>-%K+CU!5Hdv@3o{ZXx59C$IF(xJ*-a6BA9L4z@76@IZp=tDDzr{qI;Dn z)F4eYs46puPVzX~V(#{NmGe(vgRP@#k&(_kcZMIkF1DUH0FNik_-xX~Dul{OFiS?Q zA#c&;^QACHx@N^n{^<-0+XbwoI(zQk^9e!gV6$B>7rukJw|Lmce!=&&7Jko4%2@|V zvwR0Gm7U0E1bfLiMZsw$+WNZ$=CXR0c!zHIv7H^ttGdyk_L~-7w$zwZS zxdq|)lL~zyv@yEQz>m@^es&iC!9@=h$5eOZib(YIT~+KkJWKZV@?C!2B`m<6CIiXT z^kz%vN@Zre|w0tLF{W*viKhA@L z2-a<{e?t*g=wbn(%--}4@Si#1AxigNd!BSf9;9vXjhic2M0PY zi?s}_RF7Q36r^Lzr-Dw;wxka(fz;}35!nr`(Tb^SSTFO!Y}+CI0tu>WtEn^B3|XAy zV>aSRIR}MYO^fd|u8N!=ID^qSG_2aqtt%Da_*!lRl!+n2(?SrJF0N=N#|0kCd}#*y z6~$A(K&9f$wTjgc^Rz+nwO=bFT>)L$`gOXp0v?YA)}|fjJ`%BfyFIM-Wa>p(v?m&5 z;77cE@8iwzxapMti<|g~Si66rU!_1P(@ibZRJs!?5*yd-si2Xhx=t;|+guEmU6(<* zm$xcAdf#_*Lh`~bjTxEVbx-96ZazHPwsOuU$(&#j=F{(qp%Kb~0WM0r6YWDpWNm!U z;;c6p72;%pkq$JTv8NmPr^{6!0H@G z)mi|kUgdn`01wl78**{v$O3hwr&q$z4sxxV%hHX&iR$)gJ@#YG(|V+@B@#8$zr$P; ztU+)fIPJIA*68tZ$;L~tl`gS#&}Im_hYU}v9RyE+ZL;S`WZd0*&JC(Q%%T3(YE}bD z?ls;8!KE7sO0Hi=*D}U)Ra86RZx9)-UEL8BGzoavU2Krhc}RI@Y-Zl7$VYdIE-(06 ze;vH{&b-^QN^=xHZi&6ubWQukRM$I3kb^sxfGQN-C>PJi{9QOf4oP(Ex`TRP*)1s% zY*Yq_H1qnFa2jM!3@y)OHrOM)~W6DIf1& z)XbL3T^6}?;N>>)BluOi8=B-kUb$F(SRz2bDl%>TjBx@-qq8e>csyFe`Geql(jv{f zv#4)xJ4(Gjx_(A&VxjzMr8~LH^6rcHRs}8c$(pDk%uf-xo%@sh(}gVyAM)T;G5C9nndDXlw>66{ARyfM?KhI%0IQ@+*0?sDJGXB`O@KI=15-&uTBJRc%N z5MM<+V>n^XV%(1z-b0^G-ghnEbdJ$@Nkfqo(0yI1=WfkcNApzXV9&AjF*#~B%AHQ!=+GQ@%tT&dU?3N~OlxY}F8Ss|BJ?#%sl!9tie>tP zrlKlgcAx+x+U$8H+HUTLYH|>J_wzA76sjzk#2hIGoM?$lu2|SixvBa-RuFPo7HPwS zFIb5kZ@h|#woP|RhZ0>g-&v%bTYH!r17uZ00P2Hzh7 zRjaiO!C}ktbwLtCeh*PeI#HJvi&rJ1N!g&iB-%jRfF7PYUdQL69o z${Ea|!T#Km(w&Lwr_U_OaKBEiZGYF%a4~e@rQ<@%N}9`jtG>6N&M=_n^^G;e7;3MC zbF9t#N6~pLh%(8Claf8qvA5k&+-Ia0VB(~s&y&|h=d6zria+PdkVRR3XrS0}X*%Qj zOEGU=TQ&(qmN!adpu9OPZ{|Hbm<{Ro8TIKsm8rhzo=t`9Ew*7m`lklX<%5~Ze9Ypg zTS`3k1OXKa*f~UYQre@cEX#6$>LE0IZev%JSI%Phyg7k)ue4FR`X7Ln4ENsTG0GVT zA)PCCmtpZ>-QA z0%*LyZP#h37t<{L`taRN*K5)!0r)>V5pqU3re5tkOkx*ZJ(ad$~k|3-?6r+K55skg0oV#SI<;s3NI}}{g znm(;mJ2-zhy(8V7|Lz;Tl~w*-FSL%mgR-?%mw(5n;O!~%dSuU4Jk_cyJN}Cl4?TPd zwyx-n1y%xFhkAduRygQfympNhA?&RUXuIQO_?lW|+M-a<$c zxbR96RDz!LB;D=Cc>W7;YHQM^#@{??A5=laXVX|(>Xma;DANM=I{A9GJhFw(Yh%J{P;XmL)(HN=taQUHvym%Ox*_l9&y zIX!fa;ODS)+>5_Lk@QqG9^+Qi4=CRl#>YI@9G#V1@1lrZ9cx2WR)c;-ZSTU6++%3` ziKOyR$xtkXuO}3~q2tC8h1`uU_*aDs4OmI;=X3=97S3S!-GJ{>oJ;JsLkckthDAZO z$Y=8l41z89gOyZ@&1d!Ogk+H-sX34P`NNwn<$jf4hL=|Q`~VoiHX3Vdb4ui#Y} zj~KxVOlsM5jY2eW&<6w@lO>I+6gW*Q{AsqK3gWXjvZ~TngzFD>7hTQ{&+NKXO_{A+ zeORuk;iAI5+|Owb{Gs4Q%VKm+KY!7^iC2}X0@&rrmkdc6+67AEt|IWAY- z{*eDrVciwUlB=qMhEd=~5!vA<=L%Hb3SW+#QcD|Po>?XK&%ewZ;x_;_;1o|y-?VR>F zWDaPQ~S%9L$W<@ z{Mvk>srBgFOvY0wsivRR=q@6B%w-q5ck|#oWCwk;FOtKMpb>=CoZbN;~l{e2ZKD}2o&&*2JqABudX61+d zZ~5HL0!bw3J%EL9isActM$;L?J;|BbL(p{=syyU-zx!2khD?U%{V6B~aQ&%CaZf*U zSZQ|OK)v9B^x*UN=9v;m01?gMw-6JBTv86E71Ae}oB zALZ`@v&eM7N17IRr}tO1g|u0D>BpxZHLtRWs5#HBo{!etARVyH5wf~(ka9goUxy(n z`t>^+@iPQl13$RuW*1*I2(MbCWTXD!c9CvEw`|#?b=PBGmKkQ#QRK1b*_j35yF9d| zcd4bfCq4{O$RU8bn3C_5(Bs5W0@H#U!=JwlDtAWqRT6Sb=TV;1d6$upWl2`@J89@8 zJq@rBS|;^2WG7`Ww0KljYDsuy?i^?8*K)`9{YjHnxt4s1%%z2c-SHhrQ4#|`ZQImU zwQpNoLczx7M+v#Yf~ey*x74a~(v*yRfsegtWuuqO(LxT84mynN?o8BWWM@Tte-f3f z<%Y|cAt|2q#^3p!G%^X^H%Ccs_A;4uZ^*Vm6#I~UJfcw?^t0}HD`$`4I})%os{2Dr zj1lBt8ajG2htqwdK1NY17bmu+;i1QXDG}b3eZS4D^>p^sSlRyJjCZVAgmTFwruCuM z)`x_v_lfjvM>a=HF|%mjl#Hl_-J7_#l`Ar57P&2Ka|R7C&-!=Qe$Nu$_UR31f?!=i zFwL_*2fB1`7ynF79`xMyEQQoV@2D#slDE%3X?!%pzfT?QJLrR3m73R2kAw+Q;^>#VKP--VAoN-oUI*o?-i49fzarnvz|wd z|L3cKONw&VVzu6l>)|6*n4)>lW|)LHc6g+{m2PBKhjlCrq7?1=j@t;%eQXJa!*6N{ zR=*HNCS||W8?~mTtQ$*;swrZVGlm7C50}^+uuFIFwk9wv7U0i~bu35;vH)CKt!8)b z`CjsbmZO58wkCJ~v_<@9T3@8SR(y4MLFBS%`uQw^_taSKQpwM$u!!E-*P_wT8-IXB zXe|m;{JkKE!ep5}J!Wzy$$y1UXa*nia{5ee2eEwI>j0^y+1@%-EZ^?$Ts~LgQ9iM3 zNJeRybM{tZsGj2US)w#&As`@OPsFCr3*U%or*E^=7V#CeE73zhG@ zVA>LRCUA-u#ibA5|3SdQCFMOX{Cif9=G0iML1E1P+D?M~9F^)!!R*OxI9fn7F!I>F znvV%_q>%?DkoBoCVRw`gv9zavtb2UHxv0`ER^=jAk@IDMtdrg@88aHTZ7o5!Tb?A9 zVUfcC1;(!={q`!TZ7?SLr{rGpJ=L~Fj2*G8E`DNYTW}Bn{_RQMfq2I5dX;2UJGj%? zgOx(JVMVUFpnSu=ZTo#MG0zYQ4Z>wnOVUql85Ybi)=0_ zE0!VV0#cu4@62Tcr+Hlm<*`tpFcGi7>AYBc1$x-aj&yufU{<0rVv1}pDQ_zJ>M;~L z_xpaTXqK&r3w&d56Wi4v^FLUOb05psv8MY>>nlyQRoPF5KQX^vFoe+Ha9Oj=MpyFf zvWSF_lxQb9gEA9BorAYz#_9*!(D#hM#m7Y@QxL!5Q(z4GtvTpi%EbHG1wh)8vQSWy^~ zJWzM!D+hU#)mu1h8OKbsOp{5C>uhFaZyg3PyAI`N<}8$muLKb-xw|VfAb+RR(7>mJ zPkW!8`a~W1#A4j{aaiGU?3P%*4b<=y*#O&CUgo=NZ@zPf!!X+vldLiWq?#-JHm0Ag z_clH6QdRcOV`Jal`_SGYQb-tl`X<44=FwzXMWt@wLep$h%ovX0=5i_w-70LTjJBbd zI&gJfj@_KAo>i%q<%@f>J&9$NLJE(P5{!##4Cc&dU2fgm&FywPP`gT{YB%OmwE*J@ zTkG`vym4xV$Z<1wy@5N9WvRCPtYp*F#*V9SbjpC5#Uo{w0&vi??R*~^{`^WXoFS5{ z{I-Bdgl&wUI<06=$0vohK=VhzZ@da!U62t=PR@?gLa_NHL~F*k#E61M^;x|S-A&5p z1v3#BdHo}-KSvPX=Ur$7XZ-t$%xylshmeASo(eT zAh)X$46LRR464=xpqPA}hZ9xlhw*w^o?>`=397=nUd}Q>sNPtS2jx9Lc}rOY7JA5_ ze(?&Opm<182*lF4?Ak=W77$ojG9HT+oUrDs2tH^+s9bHzqn6J(YergyrY(juIgwQS z6!5-jdN+CW0#3Uv0fioBfexDX$_bPv*)xMN1)6Yo^Jqq&>j2&8Wf@TsXxD6C2@I-y zHlGD;1xojMGCTtq?yrEy7_NyJ9=Y}#!@n_ntj$GsQDA8Uyz(_b;h+kuH*jewUw{BSjCgjS9asmJ{}z&-a&Z4!z#W3ER;x&dcZciL9TPJ z_(5!|cpHmt#{m{agub*b3rAArzk(S&HCZ|eIm|IepWVGIL%G?)X`H6&xXFK$m>Azqs;7|ef^4RX7Rw& zD$6l6IB3AJJJ6CHnw{=$u&JU;oN~OS`eK6X7r&_Y$iE|zkzXt1Nm_gbUnt_AyS+DtPWJ9tG)%YRNr_HF1Y$9`W)$qMLD*|}Ix zHa&lB0`Y^8khEeYca97Q{fP3A70Q@JRGB)tE|X7CUe?iCc=Pt|Q$n%45F?2*;b$MDPb z8G)U>xy8*loaqDAldukfp_EDHXB6sC+rbMf7srAJ_ep01=mS*`j+vkFE9$bSRurO? zzdUKa1kkav+M>dnbj>@9RfqeS~wA9?LvZ)tuel}YLiHPBOtyCly)m9Vr> zsX5m7qw>L=ay|d^jijB+Ce`eHeY3HHe`8Td!fYgh$=AJigt3uQ(kg82@rTlxuOlnePQ8(ml zTGf9ixh^H}&Go1AQ=N4S#c32-aZ4tY9O6#vOyZ$KM08ke^f<|x83Gyk8A3t}SW4X| zlkNH}dc+4;eth`h>>RtzjdUp87%mwlj*;|`!#eQu2INC|=$^_-Ktk}%?Ow}=d`yX< zZI?3#-`ih)ZRzRc^JHqGc4J@V=GBb#tBSaCs_?1-D0QTbkPen=Sb|JweB1uETWvX- zQ!@01OC#|uQT@LT&HJ>==gA2^=F43(*rs@lO}&jyu$NGu51@OypF`#%h!PQb#X6|% z2<7SR-n8Ekb27q&J5RWn-^)mTKAm|qPkNm7MwaL~`U2DC*WZPqdqJ9DY5SWM-lcv> zO@N^SGgcH;rdlI24|&r0L-#t zPG{OPgJ9^=n1j zy05y0r32BuMX>FVCa-cbt@10sPwQ#e_XP2V|IMoCXU3PB{rIE4UXvHHmi3?681tX@mINIZK>tPbs)csP+DI2I_63NU?Q(h3(g8 z%Po%?WN8@%$IRm)J|FN9Nu90cSQ|7dZX!KcgK1~K`YawVT!0s5-?`g?;KKPv_NF3S z!Z@U)&m%J3eFZ`WH8EE#>FKZ$wj^nC2EU;A(<}NHKc*My#x*TtG+mAH=z<15{jy0` zgH36@gKhCwh?EYIg3RU03e7PQLv@Os<&nMXDsuf2-7CX75YzPr3WuL6Qkj zaVq+3chSpke|~5|`I!n$SrQHk4A$Y;O&+zl{;n>IxKEO|8oui(*J` z4^N3uw)Huv_jz z+R>&gWau`@g? z05>LCRVn!Ac+%*tv0j4%cWZAd9&C5T84{-q)sV~@i;sP*E-5W=-qm^LY)_3y$!)(V z4w4+b`5jPCxWb3uWRNY%IuF{^vH(%65JuA7R(jG(*XNDP_TGazL`aA;NwwjHd6~jP zdx9teE{E1)=4Xt8N=Ji@h4R>Oq?@}Bqfiw*hV)>>Q{}-cwcUQRI->0E(x=Z1Y$n`# zSW)DePb8E$PaEWspLRgClYG~xBUrv74$&pR(hY1)*_2q8W5$XRaQ60Vh*>;&ncu3# z!Z5e&wW6yMkNQ9!8XQA9WdAnZC3f-Kz zu&l>{gKcNim=+$jC$wHUPOjiZ77@sDZjCg<$U+^QE%R7D-rnznw3g}CoePVV{_P<3 z@QpK@t75l#JU$RwH()h%dF^G}??>~T;|0!WfFaqSV7(08doBqB`%TX1tb3M!k*35i zqHxi=_m`mNHEtE@Z<-pc>drL}?aEd4;&t?-8@LmfOxlC>amyfcqE)3pZ7tuF)bwBj zqw4k&=8AjHGlDEu+dojyd-l6UtIN?wwzn87!Js`*2awIzJv|i(Ra!>{k{0CG&q!4t zfny(y*Ks@5jmT%{myr|D5^iolKBH7mlOMdb#qKa2>_`}5`Dd4YejbdZc|{1zM<9o@ zzCEt*U|REw+Nps$;;D+XhCI8Ta=VA#zf2eUk@8xBR{zNEsrg`PV18-XaEiwpwUDJJ zTyE;#Doo0A*ZR@VCFS?lR;@6y@=n)l!}s()Hiz~Whxk)JJ}M3>ThMuKpy=Ga49{}A zeYLG^tFIsbz|1u%&{py`F6>>Vj9;AEnq@ol^5!aqMT%tZmA!?+YFSRCvm;vBc63ga z*?6}mwD5%1$(akoe;9hHz54xek?38s1N2KY1c&8Ox3LD9er%3H?elV4u5g9b>`w}e z%&y4V#LO)VeZ&G=CCmx(y#{%^EF`X)=~tB{$IN>e7A+E z6E#0RF3O9K-{Lx;Ral=ro#_|&bF9L(`sNJi>8uQQ!Mo<|E!-4-){j^iUA?Z)@5Ac6 zrt4jE7}T;&@{Pjz(GK&Z+tM5h>(f^=jukzu_uuo0d{iKsi(L=%a z?)`Exu(-3KZZJtt>C@%kr#T+GPO0*HR@xUm)Y9_aK6=ZIl+^m`ndgcH9`z``v)G?6 zc+RwS^>sqK7+*zwp?K+KYKTyL^d=?Ih~(w+AFFEpM0O&|3U(|QW1cWo4B7}evF4ev zeh6AP1i-c%R{Wkd+pTb@>0>RK*|2t9WszUO>hOy5zQvt4HCFHKH~w`xBXrZ9`iiXV z?tZ=1hgx2o&Z71Qhnckgde$T0*2}}SuiAbr6W@4ZLpyoM%5@KSp!*!@eaP!Q$FL;d z0wlTSX^g2XntW?ltwnwJ{3vgij|GG4`zH#mX&2L-n%QNW$82qD>kCOL79Z3TfbUfh*sv! zebxT=2+`%8gA39hQlA{J4ZN|XAT=Y#C%WaA^%>=zZ5g3n%NlZ<-&pme4JY5FPhtkW z9q2L0o9EXZU88w1OsjB9#!y-9e!QPjf2ZItlYHRpQEj6q574Iu2} z-4>ih-RswFxq7v7>hCcPzeudgc6?iT{bd$aLyg>Bea`KUZ>X!g46Z#2FY%`CvE9qC zJl)722~lSmE#=2yLk23~1Lv=XZ}@4qPXjBmWuJPX zd*@M8*3e}>=ET;7(CCPPUW(t*058LjLzBX#*ZlONe<-E4ncy#zQlDT)Tg?b36#LED zqN|8ooYIi+RKt>))qCDDj9+g<@5ASQ52zM5A!bLzp9y`bFD?tA-Ton|`0>ajdx{b(LV;a^H&g zuWL_D4HseU>bzqYALrLcZ$DypDD=m~x*wZ^n`l%D(;zW;HshFlYj;QOJ-;x)xX7i{ zyIIM10!kt&v`s#f~B8`2==LzXhfsM^$_t^oPa7^v++n+FjZAIloXv zha0Y=NYOiA;awSQMmj5}?U$Osmqn%T{8nZ5hl&o$s#W=wSmr53e~2gw5%{HSS<|Ov zfsFTo@2+ser{&viVKWA+dSms0I5;WWl1buYe&5@!H}p$dufnz&bKWS*yM)?R=;zfG zt_n;MO{vPUyZ_+a8N!FCvx#fgwD|Az=oq{->HlNz&!eI4-}rI7q@qHlNJ2#zG1jK;az`O#-&*X;$eLw_7Bto(G#F#w84SZ1%lA3l_q$S`@9#e6bAG?S ze&;xOos*f@bGe?^^|-F*Iyy*SIEF)B2^X*-4j zo+qz7xzRF7EE=@M`RBOgNzNey-3n)(qpS96_#6Y>X!QPo=2HcM7*rHYMo~7$801Fx z1eQ^wj`t#$WuyJ@4Cr%Z=NRPTn&M)f8u4L#UJuupML=g$p0Z-AKZ48LSE~vE(SD@q zWUpHE04}g%lNKken+u$)r|VzaBO_Z)gb#wTvHi)7`16bNJeIw_n7SlI(c)#rBAv^N z9x^#)QN;C!(ciLN`zTI}9odt+b`3 z0jmXgqaCxD&_wW?vkd#{_XGU@f5ZQ;R%ubLvVf1YbR69(q~#oN8a7&SvP3njx621|b8eufKk6KIv!=7us~ zq}BJ(zq;NpLnEv8yD)TvbmX3vN{6jK=Wh$x@WuVUNCZ2bgsrL}&x;OPL96LAONcsJ)}g3C1s^k!>NPpAfp zgt7z>WH4%0IZ#KQ7@0ih@x36KvBU)FO@g}|DV_B)T?ni9U1e3^hT-6H8LlDn`PD*F zQxTS<1i6&J0VlN0rYHJSG`*jBsg_%Z0a?c{wPyKgNaS)-#M2YWr%*PnyhBM6TF&yM zN4r40i{x*0_7BH88XW5i9?Ee~9in*e-~s{f7QiLHIW_#re93QRDvSpJ^UV)G2H@?JkA)}SYA-}V_+Lv8}NU|(M??b<@JeLyK6Vd9s z2PXh2<`Uh&F-AyK`>8c6!tpus32RH8mV@*ZCm=}RK#_|=8qa5n&X(C&=Gyg}9fgkq zdWSf^FP4RZ1`mO&$})xG8mN>+AMY5C>SpHHM+T0>#Dz^CZ9@LIG30v1QZ>)=Mp4E{ z9!||Gv0xg)#6K+suUzb4UD+TzL^{lBI|mf-*rEuP=nI^_*#^f}o}))j6AgQ{m36I$56hZDimY9GF)=iS}*12t2NyKu|oQvHU%U z-&p`?l2s*{yXYAsx{#v0>={+d;^=WP^Y8bJE>9F2p`~4BvIMSllXJYs?z!}n^VcH> zTX%0_+Rbs$x%~5U>#Hu2j4hgv88kLv)`bJoXc<)8+F+sO&{CwD!X$_FLBF2qvgDE9 z<*%4RkWKPx-^#^FrG#(;#o_n^&aVmico=@By`9W_oW~#9%?0b>i{NC?R>|uokP08P z4I+^y0hwcjb*Sb>#rTZ|q#SA@2Q6h#eeY=X`YpFl5IG#4&JTw&Umy%cD51jF23*k6 z4qVGg@lTB$YI*#i^4#T~H(Q4ig-CaGQfj;D%@^^F)rr%U*a#_5^QCXbmjEKs zKPtSmC4*TM87u?dZ_SLfuk%8sLu81vdVZBid7#_ozMiKV&MPW9I+ktuN&sW8+-MeRPjJ(%DBzUfOZ3rd0e5NQ-`PBn&^i|l%1>R_i>pE)?Q&M;aClD z>sCgqb4K*&sL6Y&xV?Xd?qod&4Gct|NRj0uO-k`WhAUo2pcS10P~kjw zetei1h@1~*y0Z(z7zJjfB$Wq4PduGn84kQ+4kxIZ(QM zk!acR!k2x@l)A@%4-PA?qwQ0_5a=>pZPDuI;E$E&W$c65b7S3X@_aiv{@@c+^myqa zF>Z@1^No^hVt%8)GO=T#X25O4Xazz8YvtRdTBLWRqnG^SR}uifPvn###>2omQKSKrR@5 z_j=c*FAP{t8?GT0hFf~1F;MKRx%d|hxHZmka1-I8>R6<_9U=yyu60jp6yH0O$60}of1g}WMz(*hU`l`lsboF#(mBn4*yWToHd*lwl`W_6A#c)@bUnrk|564Z& z;rsmOeb9|%TJ$}y$NZ~mc?VHl!Bn_GIb>xZKZ(39Cjea7K@T@q_40Sx-bxD{P$A!! zVRDgA1I=$P>LzxsPpMIvS6}%ZbI^#s1&Z^DMEy64I=F318EVpAl#)A+CGE;?aJNOR z`+K9^FT6nJwJ~;6Takegis!{Omn0z(mREK9AcyIq1}!1bcU00ZAYkX`GI^3Ynhn!-it&s~8lU=y(@Vob01yp_lA zN(+!FIRQ6WhGG*G>w$pxaLx(n&-aVySPlsA@FYB&Ss_=<>_V+1_*pirl3FBC7%z>Y z(|<5)4*_bSSJBz36J|?kElZ|G=`{HWii9eNN)6CCxw;sCItqVLrXbDiN3NIZzrUy8 zcS8iCqQKdj@}dX@Jd`pgoqqCKq7-SYmu12SM69woWj6YpS?_Nmg{KndLS$to-j*6g z{3(Ar^99%%{fO1AbmC|L2f$aERm?lrPFeDgZ|VTQs+KGrMdUdpr9M~ z1|He|X^jj4oScgOF(}|Y<&Hkbw1b;X#z;hU#tSq#x+MXW5}+WiUwLofgRH!b%BXYM4W{HZl;xO~$z-x9 zhO7D=|HshPJDts+b1RA6u#VmPY5cG!{)EgZdB`R|c2a0=#_a32iS~u*L=4(F!DfJU zS-X@aCKsh%k0UhGet97)CRaXyI<(nw+{g}8RAE86>6>_#%uXBt1v$H#ey<>yIu9hb z4i9J9ddEXbD4cbLnD1EE6c;Dvc)3C!!kge+YNQA41?jE}HR}wwzIi2icA+U%Wo{(& z4ccUAq9b+WJJv^foglYvaL8Ea1y6JpFNofMRBHVA~v(Z?U?I; zp*K_4dL+v128Wqc?yJ>TD*`S7?x56qUE2(WY0>LeKa(~^W@<@MQ0Q^IVPwcZmltfz z`P*@U(*q3SRl{wvRqrg95_!g{_E%1mmBE8@|C9vZA2jwT<<_@eK6a~hvFLS*M=jt^ zrUe8%t64^|KM2HQ5ImOoHdwcn_nQu~9VqvVQUBk(XQW&pYf)%>(d9bde#ra(PQVF! zptG)rux_X3fEYVv3c3^y;eVULyTOGA)Je>Za`h~3yV!M=+KN`6aH!t{DWX0Y1h$IE(baQ=MGx}xVP1({LhgQXqDkb4`X zkb3FGFOQBt>v{3w+pN$j(1h5o`d{o7tl)en4cF!NL^B)0qFHmfhuD*S|J<@9m z5)Hn7$f5P)JE?f-_YK@lr3G}YQ+(dVBmW3QO(8f#v;VTTeo+$9AQY&QMl{YH%1M26^EUwmqcf(EwXMsPy?|{Iu)-cT;+lM(>*=4F(@0+Q{ihf`p@TrXmXz)6y`gqj_^{UN1tQ? zgoCa6!~c%`Uxk_n(yN`YNRfZyz^O{qoh=-~as&;8mpvq*M5ORPzwasf5scei13}EH z;oRkvJ)4_AeJe zVdSl>xlakhSk2Q``?RU!f4DOQ6cq;3{KG7kzIwaeG*K;14}5O;zGHlcMi<{7 z!l8<(ohRl>;Bz�ZA*Wm@*K7`1CU~BHYx5ObINvhZoxDzMKZgLU$m zA^u2=?4+3f*}gcb?F0Gc3>Blho?xR07^oT~`U#8fe->BzCb4o!ofnXqltL(d)9QcT z`u={?1cgy_TMqKH?`XfH;eUT&>yngEB#?6`hBL^<@jq|9x32SNDOlB_ePAS(kY4rf zKW{~qSYRW9U^vmSAzV3oBL{SEI%afypc7Pg(K)>CGj4*1At>T+8Kf4SUiO{5X5Y-Z?@lP)P?`<;c^fEASyZ@ndX3K7p_9Nwf z-w*Q~E*a;QxG)SFoKx^Qfz6Dq++=U0Yx%K^ps z5va&EnVohom3D7D_naJ&Q&r+j7%#ZTP8FlpmLHKx;{i9|T6%gfYsxN&Ka0QCPblZ% z8BJ~zS#5PpYPFeaTbj8A=!$sf1AbFeInW&zEY+VHd@I(iz4>O9Ox;!;uotvd#Qulw z4a?OA70+wRMD_F@fot{eqV{LuLL(?YY3PgOuRKLos6;1?t}-ILBUGD7WWs#!jfw$Rj4bXmF>R_R>w3Ql4ht5d z%K*Q_3MrB)#9SMpyuWtA=_&EZuDXMM2@VQP>27fRF#J?xkA{Tog@n_shM zwcsxP{!2T3#^Nww$^40J;BspGI#7e|PQdRjCw_Fiz$_^ixqvS(@%XqILn|d96O-?f zaRqz_w5Y9S*}QKheO3D!WmvYl@UO2`$M!48=J|T!K)VQWvoxz8+#p*QxDvgbD1b_} z;rwofT?Zg-Q*0=u!u|WsD5g>KRrL9!Ec`fXsM_y(MY&a@LtjQQ}n|M%73 z1-GZxKe3|U{!*N>FV{io-7>c#bz=~G{d%+KDb;3V{X+Cw-r~2uMCP%;BH#bXGuVfv zj^D-jBp8O6eK+O&)&b*w@}Xcy5|AO352Cuph2Y&6&Z^Gf;axWh#k}_LmpKlkwlV>% z%j)EBME~m)Zqi9HC(5WS;AiLLX1|AZzB9ls9avi`)DUrA^FB>&tl$4Y_PLU~*#xOt zoOPH1lSBDZCODo)XXUDlKvq_#TWyDd)yKCM3HI9Cgwmg-Z`=cnHUqc2^PgNLQDjZZ z!Y%p+v9vK#_EU5%%;-NGlXs#zHk+nqJ|#WY&AoB!{~bpt#U*Jij0Nk<@C8|xJk88} zc6Y}a-h$1>Isi@j_*&O(4_`5emS59AWpwRWU<@+9k*`p-lh-6a^cQHn4JhGE6vIAV z7bgzaJ{~LOZaw>MofsTbU7zf$->X95IEzNsFp)H7TbtT+rR6Gzk(mFZA=Cw9h$mZj zQcLTn()dC90)m1&13`nS(H@*!+AHy3pdr3EQtcm&H%-h?*O~h6810f)h>J;+0obS} zoTfLDh2+WJs23M8h-O4=8{na0J@vF9fF-ib#+2K#q|IOOngKM0c_hm;ffshxU094Da)DD=ns4l!kqn|K zwn|{A&|2Tvxf+kwBH6JUjgD~&^G{h@LIW$UXQm^UD#(1Ou^p7lBv9CQW*A%MMI}J- z6W(iySW!{ipPhsEMsSS1Z1YE6m>L_L21HnZ*_%1%EJufN?herV#-o>KhYF3go3*95 zSo7~4QMO&%=uPAkv8t)fkGccX5pO9g^oQ0|y_(t-mZ~2n%ElV)A)5SEl!DeL*^0Lo zSlvRLpEJ`R%dxo{+Qcoz+hhIWz!m&%p6nf=km7J~79NQ=-l9Ex4Y)#7ASqn0|6sX9 zN+UKcruwozno(*Sg~TiMx5&oqanoXNB^=kvq|phCO(JY)8d_H>jAd0_k{B*;LS*7* z3avL1k%YnAiY71f27i*~?1kf+%QOAYU^fDiu)5TZ{s{FwxV};un>^FR7%NTvd|Q9Y z?*0^^QIw%*?K{kQaK-%~VlHD_B=BMvJb+38{SoHkoPTYk9&-*)V8;bF9b>e8Q}eB< z(Yc(Tf#35c(UT=XVyqT(!NDWtu0Mb4m=5fMLL(@h{TooGp7gXo+Vp zmu)Big;Z9k^+lN{&{c3S$VnV@hguJh!9q5Id(63*9R(>E7I}U7?l8f_ID(Zb8D8@#eoDRx+R@L;CpY0O#eC3p?yna>) z-NTd=%9`0Z1~i3ss^p!@0KsYKf#pifB@Xt}RaHVFg!JC^yM`3MLU%)3#e94qYv5u@F<0tC@9@iu&aFd$445K)L<=q2T*V&reB?*E0s5TOQFZ zcW|w)9eUZ?$i64P*!$MvyEWdT!rQJhV!+X|!p)|73V(+)8Mww$QA29dHk2tvJ37-K}(I=#`}ST4PsiK zRZKuKY2&fjL@CUrm_^^e>{+r0=ksfMrI~?(0V%P)DPbd_wTylm;thzxo>U&ctNE>X z5tyq2u2mb0|1RLp7M??hkwv~+Ou)!rwUk5ovfG4Vyn6a|(x$M5ly5jt4pwGoT) zr|Pb@sh+MFM}B+(?%wZf1hpzOw7>$n4@olb{Z$@P&47f@6h?Ml22lr)2VM9zTJ1i7 zy`c?GBnW%%wefz(*n@>O%1*}^PhTvis^#q+6m`ZgVH{rwSteZ88MFd&vj{up=Q>y| zNirWbUR`dc#hf*7_Tpt%K&rRkyK2{}1Uc2^ufc*$BV-nO2Z@27AuuQL@r{c38t4Qp z;8M@1LZMaMx$GTrd?!lUO^8!54OJ57mwY(B*sfjLhLN?nt)vT5d6|Fx$&rCwLCW(uIHw2CE zq-@5>x!a0Q=kq2XxaXU4Z>f7aL5^828kYJ*U_GFh!76g?w9H6cQ**58yLY5)mSl{S zN9rt7Aj%;Bv#0-+adVrpH3#v@jjDK%4^l2-K1Dzc3_{K3Wm>o3_Ky{orm&iMWt@_z zyRW92?ZFXRWrTpgqM0y#lOQnE#wXbNZhk1i<*xPBRCRb7hq-ZS!r4q-sst}o3viPX z@2%DMz@E^V_2_j$BI)WwoyJdfd(O2E&-z_j7KA`tuarn;RV)HwG+En!wl?s5o3B|E zk}#QT9z6fKH=e_?ZLoW&2!=|Y5m7KRlG=>Pmq#|CU#8(Cs>}q@W?&+OA{%<6W7iEB zR{}1U4F|z&=N+{h#7Q2d7fMu=e@ue{D^l4gf>IFDshIkZA}GZeG1Kgtvd6I%_6Oi8 z!vj?k5(Z*1>K~G`_u1a#1b|lpP{R~(x(l~MTbx4nOUhahDyQck>`wWdsQEdC>>qf! zqC)9=Uk;uYCoxu+m=q|uF-^(u5%6KaE9Stg@@E4ayzxuO=_pR-byd!(u@3=w#!VAq zqXrW)2&%l!6!s9p7x+1m-_+DgmDuVP(zj`%)nB=2krVhlX4r{E;>&{H4sW3w)Y$70 zH?ccIEv*EeSjeVRp!AW0Kz6nDVafAd!#c3+!K`Cp5Pwlb%XqG-YmdGy#m^I@^_v>= z^-pe2F26g!%fZHyy)maqMdgs>co^Zje7Ffy*AktdPRkyWt+V+WCV(XgSd-mkKk+U7 zfH5j~N5o@L2>yk|}7@5o- z6&BAKo>cbHsz$eF7P*SV5C+wnKIzfy5*g_jIbK(t#(Zf+uu_4?rc@@yDl*!Uw-WTzwGn z4tQWoi*&@a5-Oen=K)-{ykv@`&C@l5E-c;D3Gbi}gtP^~$0m}MV7^H>Tj zV15}A@9B1#sQz`c&ERX-jdFnuB8+G5^PyI!xY#@qdso;wI9|d%P(E5_m2PQjIy$gf zWeIy8`3pAK1?L9$2I822xd&S7i(v=nTgt3A zkMS&bj~oS20UnAMl@zxZBN8(fD%<6fIw(3TBP`fs)0~@pBrcv*F4H;!fN(iXwq4l8 zb-jQqW@H2-@tQdh|FWrNwmcUn0}Z)IGGj>@G<(lj=o1W`>PuoFDYG{#!wPXLh=$lT zDItxoP#gt*292!-WCV3Je?AqbMQC_BK_8IPxYiq(V*Us1GmzJfXKh z06$MfD?$Ir`72?A9=O~2MGFzflTV-0#3^C*`%TPUfllxTr}TN8)McI4m=m z|N5-4A7w@6ABEi@s?X0_0Q32?yp4-eJiM8AOGj;8!BdFK?T6_?b54h=?gVM3(zpgk zdOa+ckJ7rC_{Id1DH4kcD$D}{*G=(AiNp=f(NUl~iwNFXr%NQ4$QzoU=P|NFMcr;Z zMzVCN-eWW8U_LdEauWxn#1lpc81CBkUHTr!c^-t+i!t9>QZ#U#T+YD=Zg!5%fAR0R zb#jG?=Y>L|R%KvdUi6VYbod=q?=O`48Ku4YA!om!z!MSM~#a-@_ zNrvRSiQ0FO@yib1;5B6`;f)h2U~=X=&KcOYK{h*o&plJB*rK&|& zl#SMDHm)5o7N{)t=65`@y5TFHH9p**x}V*0KNapW75$egwmrB6kvy`0c`eQ#F*rY3 zX*r|$*&f4{)5Wa6Gdi^kei=AA`{5b9yQ!3baI^UkyiR~D75YkBI;*`K@fn29H31!K zZ45VGZjY>k$Np-LhQFRRsEbV$B`1M&imZfU!1T6Do())>OM{K>J%e9Z44#ADRk68S zH$3QkIhQE7&*Wq{L>Q5U5J(t}WGaXe@!9g%hT=hI+>jm#iT^^PVAHq@L`DEVE+~1-3L5xcUxQeXj zTui|(g6n+!+H^o%W4mzAA$`n@Xc9Qgo|ugSY_=&C@SDr;5Pw~bH3&2& z12X9FA(IjK{kQswvN06zvRX60QgJ?Z?ChEVJK0or1JfZ12doXHIHWh#%*i#TGx#a@ zkKwW(V5!(+tMpvMJG6~rDn;EG+fRmomKeaFoziv$1W{?l{tysWKx36k+YBr{d^S(T zE(JN7?pdN)lpE>kdXw}32ORVK@?72zeGrS6h?Jd`0d8l4g-|-@bczx_0ak$awKkBf z@DReSWjh?Ju;(?gI_np+-~iMO_dABu8u?$V$A5btEkDwu{oX}Hwhjhc?f^T@V-uu} zoXOqUuhDQWJzplsb~5*r*NrJh7IIra{-i=A}b}Zahp*9uE;|P zY}l3MfxyPgqu!E5l}fn5)}lCxTOU!k6FWrCA{tgPoKu!zxjpO9BUdWyISXEa*Qna2 z^_OXeo3SD%eR*X$ns(2QOwyL@yvE!ISPB)&Amq#ogj2&Q1`VPHcd3?bMql+Wzij%v zmL9vV&(a~ZOYlMe9j!}6oe5Xd25gJ=SJ%EylxVKy-EbyOVOdf{iX4h`+Sh(QyA(>$ z&oMusb|+g*B!Kqfy$7}Cm!Fs6IT++Ne$xV3+)CSjc2^(wYxNS{s3^+zW*a@kEf1%! z6+ht^sajn3QiF7^&)V-WsX*8}DUuU183rT=+;2`b%Ti0jVD@D^3*EO$=Ehj$dJ>6@SW%(TuN2(BAT zPQI$dpI!9))s6tIWDn}-=9Oe_fQm|#YI6Bi(g1|i2=Cp9&XSS|8!Lm!E?cT-@E$+Y zckpBX4cHBRr!3EJZiO9*3o|kSBGlC-(pVE&dlHCAniUd-pM=yaZwf}b-<@qyijy06 zy4L{x@|X0_@hwUyHToZ>(3hKFzR}%+k>?aso2i3!QOe^zWE*Ry;^_lj4eHnoIFIGh z)5dJf`5ezpxqLD{IWWw&y=*VTXp{@(&E8Oai%||asiN_qPmHHUO5*;7uf6h_zI~N` z`)f0HG9U_0fs_tV@eLk*)V8Z;d5zH0*si01z3KZ^JyNc}W)BE_ujt1YmLIkCfd`5B zy3Uz2*7u3Gf9Ud;XOXLP_?pre$TQV^0o6rV`aJ4e>&p9q0qK<{Te4bkvt-Y4x}_($ z_xn1Pzx&!jlJEAtfW(YWoO;eGEI_#6)NN+|l;j98(KGoy#j+8Y+6oDZxWc{Y{ler{ zW23u6^y8<~3`{|RkTg1xu4u-0(z;BKsv`l=E$v;~um5p^?_Vx}$iRR|a_d}Hk?`H_ z+~n$v7SqY8L9);q^g}gz10zz9OZal!<+1ymcW+9>5%6oVW-d9CkUfM%=I)fo_z3>l84Iy>pO>`(UNd z24u~19uLT^#!e&rC*-o7HF8wveBINnx=i&u5*=8IncxJ$a#02=uUdDE(CbPL-kBX? zZBVTYaPmy})Iibli(Ej8&)jjYybQdqvNWb|52)M=F9xD@!EJqpH`lCIT<3$FizD{b z_AF}~f{}z(Q}brgn>p=B;x!xEbori2n8xe$f4N3iZPZYKa(u@~V!Ho*V|u zF3VAmplW3rzqon@=%=I`A^m0Ds=UnjS)>%B!=x+-wb=>gXSW&$wd!eI*+~IQb)vY4 zMK74Hq>6y2q_?dlkhGez&R46P*L~p`!aQBWm|2A`YxQMZZPslAGVLMml|1peb<@(8 zCzy)S*s0;LIQ?4kUqa|c;Y$|w@*HeCX(&mQnkh~GW%g786ygmg&td%2UKHJkgd}Ks zvXN|8UMfR9OM4&R+LTRhDfzDxzym9o-UJqsO)|%=l#>#W)QJ8v3{|Ifg3b`M{m@R0t^$k_>q}=%0Gt4% z*4OI#N(ZXFBiEU5qg1U{0nj;L7i+K0^%&LJh9zB&#;RuV&mY9}?Fb!ZT??SvijnZ4_ncs{(I~;1`w@mhwKu_+`&c^f&R61|OX7vro^rLups?$lZ zz?4gJ+QXR?K5$(sTN}6I;*s0wLl+mRtUxxdb?I%a*y`RI<@2%#nZpo-%xTC)>t=Yx9LWvrvyX4(DnOn~ z<){li#zDC}V{kvwG7#3vKc%lH^9KzH0BwcPwuYnwoq0#&qq~Fj6Qf6xgIEk)VyQZtS8%9?p;N=jj-nsFnem! z*bgh1`m(b&qb&oF7~kpFdWXkPfTw!Ll1G$drFfi5xwrDPS=z>_7#TNbcEsH%H!XX% zMPjJWwleSKip~ajSYx3uH}bh&iO@;2_>7{!{QQb_mm<~B&)>6q9DXBF83J%Fz~Z9n5G(;WbOmGr{g1i7ocRIKeGCQH4) z*Cg4gvi|+vx#Zrcl+ow$E%|+yU2tgn(YGzi3d-Z;JjWD3g6i(?ft{`&CAKX!Uf_S) z(v<&jQpp0W@h`!CN*@ICWl(fTfYR_QYev|J@)x#O;KnJlYz?VpF-7|DC0}6_1rhin zT;@YZ2Is%l%J?2Edk?7{dc#K>w_hfixZ_I|ZGZ-lu}H~_Q0$=qRBJwgtzO(Gxvu9F z6d$?lB4m`OG^GV%Knjc^6~2GJ+Ek0fuA};l&B#_Bg3XN%9Z3Pd4ihY62sjtc`vAw0 zk_ULR$EuL>(l3@&B{b@+EQ`dET)lg8w@ijTw!M&T-|(M1K#yc_gbBpnVA^6(gs3d7 ztaX^8{!-slJ)~7jI5$3Xj-S1(N=>k(xXGblvgV^N6knsV-K&TKt+s~(p9BNw0PLUp zKV7Z?efdbSB*QmBV0@;M#b)&Rnu)XhI+iXo(o`oo#t)Fo|IoGv-F9y6^g6dHudQVF|<3e>I`Mu5$nY#0c!(1kp)V( zoTSW$igE48Jf=mW)rBiKGdDZ-hH2?>y{@!nqW)O=&Uy^nL<|uDAULUDec>yQw=BvFiaRc|zARB42ktEL z-eIqcpTB~$aQ6*}SAFdEJvZq&CF=LLXjyCcs}nn$uADduyuI*?tbiC~Ok3>U?>qgq z{#&q`g2pz%%N)8FT&4k%GGpkbcTlcZzm+`cS=m^*#OznIccW5WHb|HCOMG(DR{f6~ zv))a1JH*S+%_Obj!A<;V=@}RTAHafTBRWTP`a?^M z`+Hip1~n!)vii=DT1`JN z%nu3e@w?z>z*5p*@=iDevfU$}6(6Faw4yr~zVAj`C`j6o6y147X+$4^&EPG4&qZ_i zJeZgOUs^r_0PA(dRCn;nC9DG_82TGC>~JQy?J;>44=7HQ;ypbVSEJbt`+M4YY!;|5 zPy$h(^jzQ8l-(7k`%Oi9g6x{kr0=_c9R&sCOf;HXCO}^nDPJc_z-I}$|KGdkUlvR; z^?x*|t@1@5$4z{012^9#1%@z=o$pGMT zY`WwH7-#1)JNV~!3LS;S1r%wfozi{9kJQ~#bL-s(sP2nhUK}ein}jLQ@ePHIvGWHF zlzFLet%0*wnLLlKw3`dIJhrIs%!2-*p3^@Od{&?UxG4d^kBW3#MU;M>=C%U;VE}#@ zg-#J+Tc^U>L- zP{i}am12E*+z$Ss6zBFB^g#i9PhVhVf5a62G<`6tNlLGAk%CzOm-7^lth6M^lnrWk z89}kZJ+}Xw&u&=kyolLy_5o=^-9U?sFtGV3%+D8Q$a_$q?YW-5xj;^SVMA(A1+Wi5E9rmx zt&n7DDHwdW&m^URyB<*1Id}Q6*ZNK3)z84AnKP~WWnB8Inv#S$4~{l9R(m={KEa$% zu+Gbk8W0#LK7EjI&w98)Hd*8`?gfl9$ZFWAU$TkPnjQ42odYB0r#96)sI< z4EXw?+9hreUFrko9(NGGG!SFfmJl6+mA5L_%}EV6Js%2y5>EQpDK(wGQJO&P`E=al z%(fdQ8mX8^g^Me)9*N6HX;Cxt9r>&3Ot$IU~qHTKf$qS2GDvnMk^U7;R< zGW8>gm6VN6g;6^r388>&gxiQN6KAk~Btoi11isK;4}2UjHXKPvimWyp2u{dYNDN|B%yfLHC+_sUtL|+)MEdL&gSxGw<0Srkjx}QmV5cY|sUf~|@1;h_ zI6f@!D*s2LKKmtt>LHz9$Y#%SoNCHv9VV18qSac!?&6m>Lg?30-rq@>d#{bHmd%ZUXU8WgUv zE#NuN1Yr(mX4Kr?gR{xdZa&jqKbo7rXHu&9@$&k-X;P7jT)3DjLiejFsD|Up3pA6W zE;vf8WnjJj@7~74PO`~2TS<3JS=xG=oK%spppEs1x*-wA?*(myBP-GAH-Se7Pp8nj zox%BfR>Ztgh)_`+H+*L7)LnphW+8^8VavIZqs2-ram`I<{vUamLO^OR`MOP~K670M z{+=4u+8P(xkpd!Zf_}bo8Q(?y@p5a4nkS1+JLH!7Oh|#sM7q3`!_>YtJy4AD|7Lnr zxCxPD^5%5XUJphLbDe_msqQN;-}MY`n4e-gKg&Oh;=g&@s29rwg+fhwUmgR$>_VcV zOE(GJ33d_PT+MIPRUtwF z^6dlsv{BKq`gBg(@Ljaw_a7_XyMCBm)_d3d<}rK231O@7i!T?1$eGU{W?gFahQ&#L zv#&eO2kEtUyTpCO#KtA3x0d}m@{&$A%pcuXCHw4&3bF2sFhU5E5R-A~>*u}`#-mHv zYL^t)o|9K|Ow)q1=S$vO?A^bAe~^SOvB~K0d#4bt&uZ81Q(voLqP;#>l5h69-@%Oh z-tn5E7S)X-ehOso*Bu#8V;{8Hr`w9XE=bKMW$WZk?vdt#3qI|TXUAUU+ZE=$DQjo^HU>#%!t;^$fxnEHC~hZhYm4WFrB zvKcVt{cSY&&r;?89bz7C_#9E5c=niIEf;x?X@f?%%kQZY6_+9v*WrEe5E=U0Y4z6& zZ#=09XG|DSe{XQE;*bVar*i*vI@XZ9Y#SNzs-IP=bO0jLAJHJ-R)1o6fIQ3T^)%^8 zVpH3T!+`G|LP}CPYOgHEuV$aSF@2G1U^uY7wzlZ_awT-A$V`RCFz>Egn_8GAGx=r(mqZV%=-<=zG|A zFgdbHX$kpt_hPz(JLQFQhAosR} z{q!dBE8sQH9FMhg{j@a&3RK7ZW?Xcdk*^qZ%x~K#5f|c+u17zq)}Pxv?f!giG`Zo8 zH?GQmZl*{GK zVNW+6TOUo%I{Ae9{>mB!?^=rp(+m* z=4QX@qFdj8J+ddv`MyTO-}M+yiTo!&iQbkB-j&{c0Cj1dwtw~KJ%9CV*It~hl1t|k zi9;t`JgQWNR#l}(n~|z387dAKgejRj6NAurGxY7=$|{=GH-rCE+_TEVr;fd;JN7h7 zN%5AO!DQRX5oyuqfA!8ycVL5JZx(5N7HP}BWKYDaNB`L4e>dmSQ}DhMr30pdKMCdi zC5kx8`5t+pxjKA4BxPfFu#%;a5w%%oQ}DOIv3D3rlm~K{S>m$aA?Z?D+DJ)N>6Tvl z41MRiKD&_97u4;d&xN1W*ymxm#t@ONb$s@d!^X)c8kO|wfKxlLEjHBn0sc+4z#Q>qx|vH>boJ}maCUBM+tq>&q)Pw7 ztkO%WPa08&G3v)u9#fSA$>2T8qe11`Y)TyJfl>}53a_AkMnM)v?<&AgUKn8X>k9~X zma2R5FbX3a&-d(nty&~sr6?q^IU(zs{3ngr(;ii~YsS|1dsq8}j7iK6ekJA1!N`zS zA=kn;ZRO3~-j6Rs`YL#m2)QM*tYd2AE1W+G_qHDVTM7)mE)hAZ{_`H^f;Bhi>p9HW zenV+)eP!)A{RJ)6GaBwpJ9R;NwC_vSs!$t9xtr^ zNM4eefYd6OytGHqe=Wb&qV?1AZp*>#J3#&g4kfn#V%P3R-xoNDl9)T9>uO}&aQ4>q z;w(njBR0Mxs#CllkCA$UBTqiScgU$06spo>JRkGogoi}dhBrA4z=LeW$T?!J0R@t( zhIEWnc(_sH^v!Xx;d9+066^}Qj6#kdU{1?4hO}jIB%4(Vkl(#=Q$oyWgrCpS$aHP2 zIP~e+L!PuLsm9}~F+X*R_OW zPo0CsLmnXZMMjAD$r-rRb{^3^w<$S4bZ5F_Pw#E6(Qp#=~5Ggw6IFU@@>cc*d z`g0uSla3AqF6F$mUAG@dHpx*JzOeVW&9uCvI}1;=%cl%x#FF(9hhrV6BbY>M?3*J0 z68*px^YdSG^ZUYIAMCol{07!0b|#cTw(xRV$3_01mUH`D-WNLxw868=4~ajFCqOpT zKz$M4Hrvyn$ms$f-b;bx_AEC`6}(xaUeL(;D4R+Q$;>4=xrd3Z-B+;VIp@WQn`%U%_z@dFW#eSaq1Rmx0CXx zUNGQuu{Mss*Ts-rvmp3z`1`BuviZN@pQj)yFG#t(nUV;@#PX>zvYxiaEmE*OZf^Q} z#L{=MfKtE8_CnszQRQ`U|8fB!g_&zId(9oX?~MLzK(`K6G!HN|3r$j6FxYS}1#R_z zY-iSg9wNtm?UVY4?8su8kT(b?hB>`<40fksLjPRZ&ifme4!cC zb3m2~m4*Tis2(Kfgj`+OpsCR(kiM8Q3lh%L$*A*%>~q8|hj~-`KyKC5Jvh z++0}vO@WcQz#Qb4Uu;1t_%&LZ_t3QZFW1(`Z=Zyp;Q`baF*-KY=l7eB9DacBu2xNm zTDIYEDPD~_qI#gKRLkHz4y%*VuAB#%-RfYzM>uocZEN!ng-BO!;t=oqa{WpjOXzXehldYYA;M)J9{!qB=sn8$nm>Z`?&Y;7 zPIK9T&6gLRGzq;TpA9gTJWYS z-;ZJU^Jd(AX8-d2xO_12n<3A~$v*ySrcWt3)+bo&oY%URSwnzIZ24rFagq!y2Zr^l*ey=c zJ+bBIa)CN4`Lxj=Sw=Oy*K#$GJq!PFT?81 zPloF_C0vN+Q@Sa6D}zd(Z!=z(<_8YL&!0jWPCt;mciHi81F#F2`Dqh%xm4?}z{2wk?|cen?g}+%N(1K0kQ3;o&UbuG zTY!t7GUJMH-W5Rc{Hj(H5A?3pBSc=xfUoWBf$5}*YpV{&c>-jgB7GD~s_#}D&jVId z3BjguE1^-JDx}DdBN@q`mQarr?QUXWwVq5dN7lx=(GB|o)vj1kC6$Jw+lvcGHrZsf z_{e0f^vQUgtZ+D!bI?A=K`Gy^Zg1hfPJMR4Q9DNJ;tvQyAXNbons?sO8_Ug9%LNd@ zBF!n2DtaCR#|JBAiA?S^!-!Q@0A3$+W$AuORCZ4T0{B(^{sWid!LebAFdp^?a3Z@g z8BEEKC5bxs$$dFmlvY72SMk(!<*$;Z9-X%fOAp{)uq(NG;&1Sl6~o+8$Mm1A zA|0;9M8|48;N#hS^m+n-IVH3r@)V0=$P2b*()rLY=cr>8_?$}LyQy)HoHjpTb;r_r z&t_i~t0$bvep%A#({f_iQ^+E;;6~{DJc;jbVgvnKw&!OxRJhb9kB-Eu?~#>srzIE@ z!?De0R{9oC1^+*EeRWin>l&{hNJ@tYNJ|SSF?4sAbc?i z7o3g6&t6}*=Q)fNzP26VJQr%X;f`i^lBvsH6yE zRg*z$_iW%WDCozOWc$@1WZHuyh_qZ9ZkjJ9!G0L#z-rU29#&>ppYiAWI-#f@swc2y z#d>jI2YvG?g_s;u>t~{m(#_zYwmg-acz!Wteu$K=*G%*4b;Sq%pTrZgBOb{s*#LRy zylmFE;}0{Do%p^pSwgSaJxX^k>G*~zvGwto&1dh2nl$DtzGp_Vl;udz`Z8@NCM5&EAok{=AyLjjpH$2w5qa%o$6C z?Qd*+4%U*3kFH8`#|?Ad*(gnCrDfi-Pkd9F3VYY?vQei6nh8+*1)=zqI%kP99>nnnEDzrH{$8M! zPeJ9cWfl=3G!wvtT`xmt5cvlqKEc6?^)^lrE7V;+!!F!kp`#10{T#8yn0a4DD93Idil)!aHf<%!f6s5Krf2IWONLVSk})L8`M3!X)Z7)X*eKWk5pdoQKh7GSW~ zIqCWp?4Ktm0bgp|o&DeMF;%&=^Vrk6$GxaWkE9z7L73ehqa07li>J>Ak*?HSR&%+q zU94TBlcIqE+O5@W@|`Q@vsN#pT)Ey&XN|!C^=`3sb*0ArP`6UPg=Hvyr`{<#(`-(S z))B46I~~^^Wg$1W)BaDmGKCj8e4LMtVS&wDf|8La0e>bT^nUk=>Y2;UMebG^MOV`c ztG84p6sM7aK|wj@pP|=@g!&6Dk+x*bM}xCSl#^e+d@-N)=_M?opkq}^o@I9Y2&tzD zjpvg~Vt1Z{fFwYV)A(FG#F{8NPlSH!ypQQ{Lvi5UsQLkNbc3i{rdsG#^y6Rdu*=CB z0)kPN-AEGb-0TK|U!2Zk{*9x}C?L;vwYpLUH#Ht2d;EZsXIU{Hq0La$zIQHtXiUF= z0dB7v9+ZP5Qx>+h9A|RrEP}OrgbHFq4&A5etD=q?h6g{fqHB)}i2AOqgu90u$|KeZ zpsODgdg!6-oR6fMwQPbE(zf^&gY znVzs_uhYNS&HmuT-~2npbGg(P2P|JlEBPJb$30mr>ds2Z1Wja$Yp_Ul{J0xwI-^u| zOyDU?qQRl{fdwQi&b&Vmm=z^R@bmMqi)tW23ui@%rRP(M^;Ud*kEp3#2Pz4LP%`7J za%GDPQ*)t=kU@OH>mn5|GPqi>=6)bgvp&en*~uGu&>h{s$xU}*8KrzUZWr{T-95&2l_nQ|sZ3-p3|zVOb)?9;)|flV|0tq0&dNb~0{KUknoOZWJ5 zzc>(dY1kkqN$r{H?{!1kUso#1iG3Ebvttdo*Oo0v$B%z*#(6SRPOZ(#-}n(tCqS|L zc&9eY^e&Od;@SBq7G*1zLuX|rv5U#-m#FhJX0tG{yMoqkwKuw4U};fdx$!|9#h=Sd zfXvtIFh($1HBExs_}ts-ik&k>5Eqt|6v!Fw`T6Ut`6~t+yny_I?lV@KGoKGq#40_s zlY|ywQT(eHrIeA{oMs};HDLg;hvaK^5$89)q3`wF1Q~n|G6=Smt`7w9Hh#s7K7Nru zhj%R*n1!|DafL*e4zS5b>hDon#yk)FHYVB0eB!MZ5jd`$P#h25a_sxiCX~pY_t#j3 zfp^_7ESQ*(4l-Zlo~8!xx!PDiJpm6#4p;a*ip2hO2wfpO>h(y3#CwwRZSj}fDb$A- zD^3INaDIDa-ev|zzlIi+|FEITTmD(Vyd0pgl&WbdnF{%!(&fPF$#FYOc6YILK(;)p zKmQ?U>3&9z{1|qb{__*`9A4-7knrzzH&%M`6#~PC zt>PZisxCO+vG>4Vgh5h@k29# zYz+vD{Hg>?hfV4#Pcs{G&PzG2T~iAciZad= zzMsY@L6#%j@{R4+;djayhy@x#X~NI!92_~^UVPSX>WN@`Wq-SbQrTOR>jlsr5s>)F z^*bvGx%Q217TH`K52Dj$UDX!?#+N+r8!3NYD_I%0>4Iml4h4~Uc82Ax?0+>bhLW&V zl3XDPSPm02`kX)g3K4LE` zj|xJk`5W7&8|gE$UbE4Offw?lM4iLi&l@5G-6oE?eVTtlSuH}>belE>L=0~tsB>nq zd%A-i2RX9s4?el9y5$@$kancg`u(^LV;rtyp&Jii$tFj#G3mshouGZ<8wF5*aJ&4fr&NleCUsfQ?6BwbH7y5T} zft4zX0V`EFNAO(yzg7wh7x@X}MSRcO)DFf^k~}05^T^oh?HIegs(3!cFEY!OA^rnS zI4m?rE>!!gxE`C~ia}Ffeb7}-ZROttpsg^3D7I_(2Af@2Lc|i57}pngj2ZYeY{%W+ zne>K+3f(_IK(g}FFXkYb#cbvLnz2d5HU4eR$ChZgJ252ipR6wg{|G_MQC|;ElL`w> zSW}g`=oUA{45hcv%*=db`(poCT-(i;&0V?3NIuj~bHOx9Kh9>GMC-@9b_8naSe3ZT z$#XJr`Of@8(tb_)0959Yg@dW8slF^Ce%$v=%gdhj*o<7f9V>Q^2VLBK%hS=9g+~W# zm%sPq{Estt8n`p&kk%XnA()z)mGq*@UvnFC;`=_pl71>!Fy2MO7c9UOU%T@_V%(C3 z#d&l~?;^)FIv=;2NSMZ1TY`~pgdepmmMu} zSP4OwwodsC0z2cdidYN22eqY~O^2t@h1N3j`N=Q|#{d*F{R@w?OoH#oAQRegK&#pj zW7ndIE1V5!_9$!#WS$o$zhMSYg)X-v%$@lp=uVzCgO5et}@Zww#2G3-oe>-FPZBC1IM zofry(+L;+SMKu~UyP&!dkGF?y7p!R4`?D~tvNGnFmRSrZ!@e&E-v0$VC&Zyv^c03i=Y zI49^1NA|hdN7Py}dmtVKgwB`FAD&-_GT@A$s#q=CW0R3bFyW8(H-Dee>eHoeW#9eT zKRCr{*>F+`5K{BC`ls&pV{569s6S8H_7RynUVItLXiABC0zU}1%x7vP#mu5z1FB^+ zyoUIj$Nxe8M8eN!sr7yznBDpuQOeJU)nAbp=$ZHc-0=GyNl-%V!T0Yr{AO}~#^)tR zmG;)b>wE^v_WW1B1^7WZY|;_i$q^%T0`OO2{yAKt*h_qs}G?#0yGE*A|Il`V-CX@#7?xD#%LN#Te#VqtiB5!Zy>; zz7O)zx)l+Kn;uEG2D&Rc&L_ITA&WflS!QW|)K1oZ-)vce^zD|GN#5%?+6%m?>wa() zxnmivE4hCqs=)X)wxrDg6aB>_BqWoI((1#(SxFgfsB-c7{;wc>*&9X^4_xC?*V0T5 ztILk`OO2-7w8Dj!ij_68V`{~a!sAV`AD%7u=$&53ic_HkHzR6`vP9p5zb`2kGlCpGG+h35{?hf+#jwZB zmw6&0;;SGKv1+9(HD=Bl>dt!V_7@AC{x)Z`@dM3wx3tD#co9#>r;8d0z!lQoYg7^j zybW8L{pR?PXE}sZ1qw_OW1L4FIdwHrZOMNGCJyGw;+;+AP(smfK z$QX*`oK5?ILeS8)$V6Yz--!v;hCr~5MXS;jkR>lUj1niiZl_{C^QdI)Vbx?WU2oo~ z4_FX5=!Sl+8T@S}tZt|$=nDV65k1C4V|#%huCZ3#^o14XN00B%f*ixDU%MH)e6kp0 zovR8YEDZ-;kL-CjckjwqtYYQE>a+Q`9@K`7;9kz`FR(ch)0Dki!z&`ebeF5_(1n0+}j^@|?=6Q}|Dw865NPQ6LhZ`A9ThZ@oeK-9kX#M>f_JXO?8 zns}__78R(iIxRN`S~D3l6f|5L97(+?+_(EZ$Su#(Q+}XQj6>D~Ci%$K|Nt+$hM!4ED&v zHAyI+?x6P0xMh@b%aA^{9tX#0|H-R|fU}8FsyCI1Y`NAb46xBk@UF8z%)WVMx)dEQ z1xo$u%Od`={cFvUaPjx1D8mFUo1wG4&Dpaw$>ZX;%bwp#04?U8mqdm#^#TO*nnss_ zISCZ>(iuF$bJDnqyd|rwl)kFJ!&sXftg=cGy1${#u_zM77Y854H$weIUGUlyG&Ikw zZG1{Mwu`5Dj0 ze&kGk2AzUWg&{X?pMq_yJ|`7Bz^^Q({D|wGu_}*#fT6-%e!(SmukOfS z!UQAUjh zP$93A%JuUH`7r=Ip*G}$qd2n^GaV#M?ZAz3Ds4@xC;Il*va5MrH88_4Jfugl$PmVy zJ<%_U-<@_|fUK1$$+SzY>Y*=YZF-ChT$rD+tuzi3qBCpj>C1^7%yuQvcPB9T6FL9L zSh6A;eyAY~KOqI92=+sKQhj`VDTZuLXKDy*71FvlxDJ*G02UW3B7l03&Tt&)bbYae0^QeExKrw^pRvd#a#3&`Wz zmzqq$*a^?=ya$sX7AdreKF`$Q9;7#m845jEpX2d<&s{0)k;l2$;TJ%f^BE@du<>Te zp4{nGFuC2dsB_t`ppJ>R&_!~euvq6}Z(rMuaECM=KX~Vs-nmhGa5T7qmZ}@u#^Hpz zMz4WGv#l<=;6OvEXExjscX&AJ^sV$LO5a?dqV%M4$;tKdQR+ei(m{HQ*LfqR)aEDT z{7N(7jQ(FrSynpK(pv-!cb^FK?BAcpOKqgR|48UTuTQNaD2ikev<^~IbyPq}$#l;hR1BA6Yb8sxazF9!)m6OJiKC`11S{|%zY5*MGY9DnCh@ql$@p%$I^d->%G zE4~$gpXnIZI7T;RevK@05}walYKj?zspcQ-JcL~>^Ru{%;J%c7`Am81KFLq{Fg#xo zYf>J58TZ1QoF7h81AXF-NzC}@fES!oa!Z7m;W=CE_VYbo+C;VDoK)-9hgQ*iCNp1Y z$cD^wBo)5Ctj9-6({3aMa2|{4laZvJ1|Qq?%*zqeL8cGtAVRtNCIR#d0wNS=o%is& zh3*sQX1nu&ZsbbE&0RkXRmrwyy)o9?pE%I_D+Bd8K~M4IN{_`7bN+Yak2I`q#-*i{%j{fg#x5~V za5UQ}HhDbJF5=SFoI^MoaUNBY?!y=^A?5ZL#(&yZJ9#}9E8zNcv5e})K0nT~$0tiA z+-8koVPKY|Jb86~Cvg?^9cK>3iWJ?Sd=KQ%;0DeJF z7hB%JD%zx-eXj>!iz_KmW-Z515>>?0h24*rVt`h9kXya3e7)wdt+O&A=Ng-|Tey9a za<(0&#YBe*9?B&})Y35WeKllE#^E?xA5m?t z_M^E#Rkoiy*vnxsF6O3@4cWbCM5g%Y*6PlpjvR_=UQDBy@H7jNTU(m-qw#X zP(f;coTpag+oF}B=J?x~3ntgRZ|OuwxU@0Gt?s{dStONB`LBD}sO8gCT09Jop3Vul z!wDP+t_(O2CYg4;IA}QjM+<;jmoSc-PK+#lL!Dg+`8C zU7J=R8R5>u!`0)uW#O3ShDVMxc!r+?e=5NFcunhsMOCt;>Ex0|`pM*PM|;^vwP9OJ z_w$OzrWeo#{mSiIC)Bv)NX4e1Se?erpF#6?M&qzyiz#v`Cq=wy3eR4$)r zv^vLbPsaRe7;AhpoOux$06+1ol0R`2tEn^D${>{*sq=-^eFbi%%a71{lL7Qp&600aloY8xrQ15~DB!ep0A_nK z;29c)x%03ATq&8kfE})g-m&tnQof!lwaf~W9D5XQ1^(v_4C?{ZiR2TypWm1fzU|g5oIZ7sEb<6YvUTPMp&Sg zS@wz58$)EliH15yQZGH7DPxegv$$v5sxW`(KD$E+U2qr566RML%koXFt-D{@7nNRW zTE%x**IRAp&uM03SH5Io_)`7$+bgJl-z>cjN1buz9!0$$1fj8hAF(ygnl4R^qSnox4 zhqZFv@k|u!Le()n$~7XPwShADI3Rc8E+CmMKp*HlfarHWz|m)wMQO>jbcGBV!@XOg^~rw!vXjU}8D2hWKD#Re3rAJ1lKV z=@4(#BxIA3!ObNs4P|6O+p2gYOj!T?PzTVPZwY^wLDU$aL~5YJ+gPnAeJcB#>* z%{6uQ#x`3vexpA^*+Ww8dXyJrKZ0^r_?BrWZK?R+)Ka1# zjP!*u|kVUpzflZcvtrXowA}bmx6b|6GH}Y#;&cRjH)_(^xf7 zdhl}{^jth5U3&MES*I=k}rpKvLiRGScU1)?67l1<=m;XmQa_cQ5*NY$4{^6p{pd%IGh!snG z$s0Zhsh2Jz4-mm-;mm2``an?8brB-J#veh-@`8_ZP;%R#Lc(IPlh}G{RPzGA*x)f} z0>wwG^3{@F@%W;8Yallp&o>ZgF>b&}FQ9e0Sl^?1EStj1`|+Jl5uvY-?fZSE4bbYb zQj-rM6LcIf-n13oGx&86AYm!u|a}# zv1lYSS~Q^73TOc3$x($a2R8N*j0S!%fnHFWK*=b+8FDSA>l0(h* zTJue@clD}&856==qa?Jo_LJ{V+chWACt*Ozi54%H$b!jsP24O;Xu)#00a?IRyxx1% z7TO8h-e`PciY|*Iv%ZqJ(W}l^?dp6~nKspBB5~i1x>}qv<~nhpX7iAMllqR*J8U!N zbEdTyy_S60gvpV+g@ihTx7A&XS~`iKk7;NG-%+n6OaXpEtSud3aX{0%_eYS7{gT&E zU#QUq{x_^erasUgvoc^qF$eW1$eNepxgTEb>zKy#2QdYi$I)u9TMWVkh}xWp^p&O| z)?cO16`5w~g18?mvPLv zwkXro^Qr|k2BWl*w`a;}cFF-kvlWB&9qHM$;m%YdxT{`iIA5Mv=MfWkCWyCdG$R>m z&%>aS5_aL0H_{XlZr^~0fp0k{4XG^mobK}6fcU3SXL&~Bi)2R8|A3d40Ff$uq>gW_ z&$}Hg{L3?e>Rg)*_m>W5kX^1$-q7+|0IAe&GQ!Ze7#aLeB^Dwr^tSZvlO{)ab+uMc zjY5O6piz$y6*4AN?9pY8`51UK*^Ik^6UkF1 z(6J@9b98m|vVX6-@NNW0Z{2@4=Sk7}U2;dqvtF3^K;vKC(p2nHp$!r9?JOoOwFJop z)H>s)~bVqM5pM|;qBE;eRjX~AIaR*Q@D`!ni`V<4O!4M@(g$Mnz67c4-L4mNZ@X+e=+xd0w~0u3J(gi zPUbq#r}-5Udpc(zDktzYK3ShGZJ0tA@08g~$+*t^h8;tym4!HT?mA!K0iYRh0Tk~)+N);NmL66N2`=${81DZGxh24?D!kQRil?JX1=d>ud6Kj(&&bC* z>sg8AXS3LGa{|q-%+)(?u4fKv9aCMJ%4s@gN-o*KU#KF6XU{dyHiY;ZoptnMzg7^~ zpssdB5?ZENU5E8_?_KBYtjzu5bnKl*Kzl9?Ln35Ql+a(xgm{d=APb(K2X1;@H?Jvr zzlTE_(E!yOn7lhNGNw67pIzY6RX;DaxsolTf(KP^@Bacm{1$+VlXB$a7_V|nxk&VK zxP2#qSs~^2nIwadM0_j_!lK`hg62lCMI&}JQAogEUYJmtei|jo*b8@~CeJ&W-}Fl5 z=n|xA6E#c_I^@SVZzb9=2kYM(Rr^ffL;cMeyJq{W?=!~}$B%5MZH9_*r4nAHEU;SP zKyO>1aYGs&_U9SzpCw-Kv$9IDEUsGBEKL`?jdCbEHE)*Z;@6ZA?dxg6f7INa$z}Az zWYL$c?Po9X71&wds?V=)jovers|PIAd|K{*WDSOjKDM~#Et{rA#Q?$*g#n-Rz~|Kp z^<``2_*Cz#^$IO1bX}usnnVGJUqyq0G|r!mqtO<)%W@XdR%=h#tJt)nE0Ft~tO=;6PxhYxFUs!Mr$Kw#g6Whx^!#osLx`{p156 z3XJQibFm2r0yrH@i_}0E_MVycpnJ)D(dWr$nAGH%Hwx40o#M&Aiy)VkM}p%I5R&w>P|UoHms~ABNPhGg*dFoV?o6W z-;BKEe)$UTarcM%mASc~B4Ho7!}Duwtxc(eMu5mf(x{%^yhmIt@;{a~!;*YkLwT_P z+4nELAL#aPmc)93g*9EVb}fUr*v=cjI;kB;6;7PARJeX8k*teu4`SxN#DD46FxoXz zOLx39aRSH@sFqsezaK5pWsNkKRKaW50Hlz^FAlk-!?wvy73z8=@>KP2J=-2LD!wP6 z7a)9syT`u%K}q%IaM|CIAG4qe+ZSVN8vo6;0N?GC+tkdGrwUTW#0lI&=IVFn}KknIjESTCy7B*-?z_;c<(R zJ9$6{xU__anH_IjTRq1;B%g5wpQF8W*jChBjD4Sca;-zf z?K+>quUz2oksx93I2I)hsr1NO+gOW77ge-Tr=@sMbg2HA`5{p4Bzl9-y%MSt3u?)+ zT&>B=ZFu>i;U|_&OqM0skxIP&Pzyp#vE+h`C0^I-mp9tHH!{({GV_&;MKs$!4)W=y z`O%fFcJ@XA@%-r{#7CL$cHjT5(3^{)kjJ<^c8Gg_E(ntNhCO+Op_yJW7S( zqNT|RQ+3C$YMptuh7E{v3-D^EZ@b(AsnA{vtNk4PNdv2m7@TZ5U;&M&;6{kF44D9{wnMl3ek~ zs^swWem}5g3$63Klh&esCFQ>Jyhs>^l0yA}woTp5Gwb(xPkN6Es6V*=tv@tX4y(Hw z6jwPcjR+aYNjbk1u$wXspgL~r(*@Df6+@U|`ZyUxgXPA84OZRD^PqvcZ(YK4DjL&C z-$J;0qFf@~P9jmF;9$8+VqAtC&13D3s3t00|STR3O}7;~B-3VTH9){-}_)=M2S$ zDc!b;p{f=(OO6=@j6o^6?1fde`1cX@1?vCG@xg3!-WptyCG9qRYfH% z+8JV2k&Fqdka!XnMl_mnjIYHP9pWFua?}gH00^vp%lfbNYh2oS=m`;R4V84gS?I*P zEPGUX^!S~W7neCp8eS1T)KgfcE09Wm3C*t*^6COkn}YdMGfU1=A%$(&5@XjmN?h`` zO%mk0M(URA7#5_$?(tn3yW-U}hn^)mq-kM)q{;mP4{i3e2e?nysvBG^{2BOpr*3EJ zh5p=Wb@)YWy5NpX|0+z6?Hd%<3%xnCHpTQ8)~|Hr+cj>BXI`1YVGQfwuZv}dX1IFl zHc8uz;{y3EkFf%f0bn75jwtKFaExfJT(YmJyW}@j1%XDS>3a=U8Tu+|9b__tmUv^j z;wVzJ3^)Lc(u4;CX|L|BGo;xm@>6K66;9Ee9it52d!$(y^R{Bmw8N#Xzw#69I=b4f z1^Gj;)i zZ*)5re>6?*MBF3>ytETy(mHGo$n6V#Q|BE?=T(g?#@dsCa7DF7QXKRg$LHYW6J|7} zySDfxa^3=OLI+J;it+uXo!Sn%!Jc;0#9rHa#{DL9F(~f7a(vNw&osHc9%kWl095Sd zqbA5VP>%TsKhqbhCn6DlntWfB3DnMBA8T~R(3)?~C6-o_*R1>*TK$rAaL>?OLEFnGZ z`tqBCnO@8(_v>g_U%GCiKijFukkt;WDa50gbo6d-*g$5vdp=Ml2-+Igl}JT_-(}Q& zd$h-^ojX8Vs~iC~>)20AbHOt#wSZg9&W05nbPe<;q4KL{{YCMu4L;fV>}J3H&3Y%S z+t=19%(}F+57iw#nQzY%j{kNH3c3Ebo4PxyVTo>ir6Ii)ZN-?eAd7EQdQx27);6_^ za_*A{X246MGCWSvpl{t#IC&#V1^f89#fRglEi2kKyFChgG3$I`4I#e?eGaDeFGoK1 zvx?uK--T7aET{NXPIX!i;z#)ePO{87#TTEs-qxy&2q$cGq;c-I|3OA+MA0w;QZ>iREjLRInx2rzijIj27v#nJY&m&xwba*1JQ;+7_dYZKJ-j$bi*C|>K% zU1++Y&VD8A#BC+}g^Is*k>*U~sYu{F0O!_Si0KxC-T|H^c0*-$ap?;=ecqz>O+@SK z0QZ*EeamMC&A~)__ae~+zW^nNxW=T6P)g`qSqQ$3_f8wc^(f zsnU5a%LywKah$}x3cdZp6vG`S-;tv0h0^UdZuhSd`BBw7c90@X$^OdGxy_X&Ne*`v zPZl}#D4?zx`K&Bsbr@GgV^zyzu%5_t3H>jX5UisxELv)OcK!q5x+8TS#r_DP*dD|7 zu5kO7@*0#UV@CA)ON`I6*zZK7xRS~c7K!S7oZR=2X7WEIs8d z`w--jQ(8v`+)sF4m9c>x#~;fZ7s5+FgXw19(6obvKy0M&?%NM&zfz;7_R_FWzUguA zMycJ0bMS~)ls_8)@frp?C6(RkP|^*`Kbhh;f>>>Q)Y&N9MFe@!#2AIAhzB8lZ^nUD zN${&MlL{@FLwBbQxZIzp9~S4$hGl^1RvG`K!Kd`XL928xR6VJ8!e{7@sg*_6BEe$* zK{e6`zj_3~t=CizBp~eif~!kB(>pHu+z?Qd4n5(4CnCqu?wz{cSl>SqIP@kcE{xu$ z(%c6I=K)EuxsAuU@Dx8|cG^x<8slMWa$HB)`R)Y&3B5AzqB|6uq{spbciyM8&**&` zC!|sII3o|M@Y+_NsX7m1Sj=rDLp^zAKPfaOR41TH^RSKalU+$XNDyx$;qiZ+%qS9h z^EC5_U($!k9pV?4iif@_u1;coa(W%0cCh`NoS~kU<5qPgnPQm5_2X(p(;{)JfFFcV zbQ17v<8zC256vF@rJ2BC#f39LG;p!*q~Md(g=BJ}W|Ge>`A;SW7hVLDuSvet?MC8m zl(XxB-URgbeW6>eOZ0t!V8maLiCyu{q~xAZwJMTe;|z7y>)Jf5S>?rl+st~VEI zt0#T}WWfE8FN7k^Nz5t#>r3^&6g|UBJBG7*(-_G(#0Rl2ez))7fGp3aS?+fhF(Z2ZzrHZ8~5{=k{Y%>+ZnNImWC95 z5&SjyANujeboPEd>}9QTz`fLt`Sk9>>X#gz9Sftz)z$TF+qcu%^0fnO;N&J!zc&x& zcTA8qDG~EAeH!N<#dP>58wN<3WuXM2@` zVH(GmOdXOJ%eHtO)PAYgv$(XZq#A2Xq}Z}NzAo$`RM;zYLkoy#+0H-El;KFDcsuNm z?MOXW=)`!phLz3`IYGsj4d$tIySB0z*h9A-rE1m)ACPEt6U$4cJdbJ=p;tRI53H)M zoIT-5?hea{AE-#s9g{{>;ZzTfy2+HkVW5)x@Xhw^Y%vJnDs1v)--SF+cnlG zBXCBNzrMg%&$XQTu5->>t>DJ}euvv6YLb7=QH*1~>MXH`b^4|COCZ~Q!Ax&;B(m9L z+|a~V^SdXp4$7`c&nzK zfIAY1_<>y?sr>vL!8*O*aq_>(e|8y zYL|+txTwuDpYGHl_oJniYAF{rwc45|^O(TYG%Tm(tI|H{c>GSze2VQ8D~m(^NOiF# z@cSWsv}D92(W#^nk;v@0KHzZ7E-<0ky;HA}Nz`>gu<9~WJy*yF@?h5ghcZCJE&dNj zo5nflc7!+ng}a67fgTny#`EGYyb&e@B^_|()a~akq{>=cUuqgObdQDLAn zmDm%Oh$o)6y4|1)*e;}0-IKi0Ls;pG4E)JmL9XC)F%kEq@;?(#eo*~5PjL9X0kuSH z0fbrS9Z@pX6$uF`>-LI%m-<$7$CZbPy~mFJhvJ8k)?OEs+H&mnsr_}R;cF)9U4%z7 z11PQLX3nuCt~ZMtKXY_Agwon6%x+ZYzX<*2>V{9A>GFoBj7= z5`oqaEY&;msa-@wzt_cJB}=~hD+rD3)2+G8$0zMMJLE$j@XZE7WTyNSf}@!9o~|(( zpvLjC`ymJ6l`WVVqQ^G+BP`Q&GSoV? zqxX|Cd}B}z_MR-e*?rTV<93uT@Nl-Xi(+W-q<{V7SMsFf$oAEu$j!<2V}e@_l7utT z=yWzvCPmd++n?wPh@x6-zy6VB^p6%`fr#oNhKhL<#T5jZ zz^UNdlfDs_fJjg7cM=oZlU*OFC5u)?v;?pBc~gh111zIG8^Ay2RGVUd3(x?jKyAng zACCuo+3rE~9HJriFw1a-ji^8&$86?odnw}427^3>oTl^n8aI>mq)rRR(&5Lt zTv_IOh4x9y+T>s`V*nUVt&Vm25dYgiGsOU>inv(Qm!qNXM)(;Bqo~nWl_>Ed?&ys1 zC`Tqfur@6{zGv;Fk%Y>L(FgH`v4NZglr-TVEI0qlU@{@!HtKUwSy;=O)lT;ElSuX4 zi1lwJb@JfXJ;40v2Sy8Vd+Z56qZ@1RW;oW;Q4%fZ0%juVUHMo>x4Qfn2Ru(EF-a2k zX{BRvd?VidJkD9NvS}QEO0{{wR4<>K*JS<vDhy5 z{+!ucn*~brK)1<>kATF;G7{ycLFvK*&Av&WgkuuysQvRZA=#FUXux3(On^!NmFOAk zPW;cGQDgBVfH^^oicAbP;@!nF&xa<{v}^gn%qAJtZfPts{@NEJAxuPSNi$`m>T;A_ z3!p5M7O8ATZWY;Vw%?>a8`h*uGb*wQ@5S`OYUr%=I`BxGE_>C*{astYH^N4wNetyQ z0G;JEnt|X4*~#t4JN_|)JNXr6=m0RsItFVT{=sbsALg(8=SLF-RIiI4>fWiWr$uXw zKv*_Czh;a_n9yE@R`Q$(GkQ{E7oV7wt@1o_Jjz-6<3`wT8LauQYSkTJ9 z3>v)5_LEK>F**{I`plBYumn@f1GT_*wabJ8wKhp(uDm~JHuGQB&Ik*(xH6+O8HXEb zy)iC*LNzr9aaDPy51b!r7g_%LbxTWzC*LoLy9&$V$0W%;tAAUvL>>Vpt}!w|1litX z)yw@|eE-?+9V*aM6`r9Q8^uej(%BFJoW?i7r&KzU2!-deHo zRvvApVX9+|)x~eezb?gcY>(+Xqw1XHeWp-6BIf!rn_K}5dTNP2m_Qq!v8~K@p;ngpaVa2h51n6MrlX-H?))W z0bOdrf)ndV0Q=>~gqj~Q4b^g3yA}1n8NpIRZU$@#iXbmG59@9Mh^VBvl7SGWGP5f!WK+odHk~GJ?GWP z@;}WC?2K8$A8VhsJuH<~iOBS+xzBJ4!WGo7T7w>(AX*b~5&=1SWc;PcO!l`|Iifiw zHcDUPd5yUtevLQHs)Wlw=J0>t3b<)dh{vO|Jtmw4x#0^XxRVSWrsl9KS@sr$#PNC3 zf2SRsJ-@i3!eX>TDhUd_>SM@i@pHL&C~1dbOH)2cy2Xa}E9&u!kXoR*c!ZB=&>e|R z`nTX7RtG;vhRG)@Q~cDd2#PiE!)ejOCg#ZW>OxWi6_$H4R6m*xNLZ;jzpR&);aV%v zM6K_~mn`{BL!}pIe#_S=t#NaL83jdCV~HdflMv&Hz<`}^Lm0)<^COc5b`GboVGP5& z=YZ|{cVr%>T+CMo=xoc{SQBrZJOwR_S;;1T>H^@CbP6=Ll93U^Ae_qSEyFEY!4ySLgFb3NC`GTky7qCuks-W5h+p( zn1uu$wHA+4cDy-hIc)rE7>*Rpp5!B@&R0-jn(SWvpAxKI+f%`}t|6mR;kXxiBP}4M z8fGpPZrW$y{u4#O9+G%(Odc329PcAv?9*bF(Ej#*OwTzE`oUHc21(6M(Z2n&nr~r)sCK1J;Q^)d_mu*VIEjyTgd$i*%ArJ@ zL^FW7>|3Nsaoa@ZL_MN0^=MAgWLMmwtC#n^QWXtM-2h_xN8SIfK{=(D01K%3GXt~5 z&5CEmoY~-41)Xj!>hFex@^4N_R2FW8&_#Za05qNR<=vjNkLt}ndVgCp91Y)~!$Fs`4XUa*$J9P7GX`#eB5=})bV;1Lwo7LN*mn5rXNBOv!0;823`1I z&|@ToFQNaxE!To4OK)krnP@)T>b6SJdx*=0>8)9AoS}W7V7+SnEHw-`$FbnRU4in! z!Vq}?V229#d;TTB!7_0Ptgj%!A3Z3}uKeil)T2Dm>x36T{NhV_n0}RGi4SQIrX;lY zb4ZOJxazow2I7%uY5x{`ZMi5nU=$~8(9RLf&LNm~CSU6REk#18>bPXI^5N+E&^zr1 zFou*IjtUm5;R*C$aiT39{PI8S8(57LM8-p80nLyQb6?$ykOx6lwnwD=$`4erM?K!L z4;dj3k>jQwAs6G>pnw4R9JM9n86i)!mo!3G(gy%5=3q{ATN$<~#;({!eL#V9Ig5#y z(RR5gFg5o`V=Xq}vi=eDXtKeLR_R5P|S z$F5tu{(0ywJotmpO>H}Fm`D5Vst6a?U|i1ZDNk&!g0~vzebvtfZd79R4%i7L;V0z5 zWpz5hto$?RY#jE$kBjjV|CRKBaZ0pDsHSDycndyK5uxTjnh*Aua2<@RcPr62lpiMj z@9GL=BkZTOcs&FIJiu(o=&RB8k0?PhUuE=ks5CBPCQ|-Sdv5~NR2GE^w+OO{fGjG= zVk@E|g3^M3EQ(6oifE&PtkN#1EJ2Yqfe>X;5omXjO+*o835pOPBw(VVA_PPTdx8i- z0wfp`0wKxVhq5R=RWtKf{eRUz>8h?yle~A&J^MNLd+)3=`uT-wdXOQ$H@Wn6GR`@J zH{R+!U2&>kVU26G1~}WwR!TVl#GiX5QUO6}H_Cf3@P4>qO`%XpApJZ|zSN55f$l*{!4P(J()`% zeIl>@E_2E0%`%-&FYEWOmx{`lnkPZnKhhexU*dYZ7c5G>HMnW)d2K6wfMrf1c7HfN z$i~x0H~60vq=j!-$dJj2eoYtR$KxqG3ClbW-&G2d_Kso^n(A5EVictCj%k-ZBg}Th zC^;ges({=4D3fgRjCmsmrj`cpZRz_cMme=kR=WIYo49Slzkli$TIv0_j4gkzyBao);^XJRS}~@ zybwq=e=6`}2!%dc8{}MKdx)K$sfOQ9AdNq5ds-RXih{{t!+WwH)S9Dfq!6@2bu97E z5*w_#%bDG1M7NH7Zb_#zI|oHhDmmih^Oal$J9*-mnElp?Q{2H%9x>`!uAD2dQx)Ca z*ce~SVWb+}&U0o22_Fo$8mxNqHEC)%!F?66M+@*cf(qBtfUb_mm3eY}3oCQI(&Z@T zTviwPj@#Jhjd#Mk&v>?7v{dUXIdVjpkz`EDSmK5CYSr)hth7&7zTKGrdN3zx-+2GV z2+3zlsGR8mou?jw5hJ&b1+JN*02Kjdb#jO|%|`pw@u~5-+J**VBuoCNfA5fF%rcV> z&S&E`t!J?2E)s*8ycoGwY>(x(+qNgd>ltpnj@p#_`n@{A}KWY4ogJ{Ij+KWgv! z?(8wTg=339?l|0IRBK7BR>XLm!4PI3YS@#+h}gWor0@54XPPffZ8*}}1&pBZP0bCM zp6Z|sMhodj>^LANgUGzQ{&&OmDAR!6r~u1|kdp5A9*v~LG$g*D`dzx5w{OvK0Y`nv zM!sVh>rcF?6^lhHAbwewOE_`LSWY6v(er=2gVePcvIeU>^eiw6nDku6a?Ssuv9Sa z9GuTmp0EtzF$iDH8R`PTs~hagot&4WF&dWe{lv!(GXu%2TfkfJpVKnUr-h{o-lX5Q z(G>+V@9k6Wk!}|zf9=X)2>asV2Zz~8ged*av`6**;GK?J2Ds#fVN1gKi#;!&Jw{wy zy+Nr7sOQqcPuDF5>1A53%l+`j&$xA`@&*+Tw;b(AYlQdLR}sQ7oti_~F-(_$(yo}s z;~AlyywstqaySx!^`50LZggshx5;&`{SNA_y}bwBJDYj+z%QQ%MOV2@ws2^j^Ao!Ffg z=IFSmj>hTF=z^{%Nr|?wBJQR=u_|N_^W2f%BH~|kw8opfqOhf=XAX|AQdI@yJ9y3f ztt>42`R*H5jphttQ| zdd0Bh@i=B%y5K=X54$}bGf?2${56Ug+tJ%di+6I}R^nFMs!2O`jL- zM3)@R<1n&tG@5kbn5uO00REU0oNh-5H|bD4*^Y4Grn|u8kx9eWRhz2uXNw9(*6Bq( z>vmiueDUUKmt0Q1!fp4^=mZk3^+Ko|B0XZ_GIQiZ711HlLNg6<{A4!X!lFBi5(P&K z14F*mC)sdbjK5Kj+HBmiru=L}JVE`i+wf-cVRVJy-IoA@MT1}H*_!7{Z($}SDIv}i^94hLio*%Dwo{{0_U8gYH`kwUyjzLU z+Yl#xUO77g%jW6_%RoL57sNnX}ghHW_!OY@-PDu0)aB^n4v6TBE%j^49G z2PSB@-QH~``F)5B7_2}6<4<^g$I-1!aQYj+TzDvr)lBB^oL8~;r*}8V4)OaPoDiCxzWVItNpx738R-L3_ArzG^2&Aqa^s@-3fNJE|(|QKNn$C3t9baFqy#6US;v&~RnBpj8BN=ImC&4@1V*1rT$lD3S zal*IPRuTtV3U7S62fs0<>Z-l|kCXNLao5YjqFLQY_(MT=5vBCB)0x*j1iGVB@uJ`y zN4wE}htf2Bb%a3-p2)YO!1F6Mr{G!mz~pWUht!oRm~VtrOA4Q6|F{$2eigC7Y?}K> z;MsWah%#MkZCquFX#n9dIeBSXX#ZEkbD!Qa$C4wKo8g8++_78y;xvdvdBL;Jlegr^ zvhWC64y&x^UlJ*8v)*zu&$uuM=Pp`p^ zRacne+D=!+6k%E)=8PA5)htRsf=ouXUp~;)?1Egpi)7^iUg$V85$gURFzRCa=CSEH zKv%%X4^?xuct!2He=9wP;D#wBY!-UJZ7`1>n;6dfk`}aSlu@%`qo2z70CP4L8{jhH&uKAWko!vuJ^N-@N<=C zQcqRU*rnQCk(E~BSpp`(|KrPa&D&L(i8Tuu;oNkB3C(9?E{!*skx6)A7&?q4Tt~;r zBPzlNd%D=iD0MK~MuT}`L}hNR<32fI=$j+#hS&(UY}a6$&*l%QF%biolMIuhGm{w~ikHdN8&7 zg;y%oJnM69H8y(HrkEblTek~}CuoI|FAw4f^LQ3Q=gsLOVvhXJG|$qWJN6aNG^7>Q z?4wR-2@IE?W9r5>l5f~ssNCl5k!m=JJnBRmZL?vhh3+o#e5XseyHoYDAHUxlEnR(8 zLmemhgbvpa%ZnD5x~c15gN{(~E9r_Ud*+MjFwQl$6u8{)Na;<(G8Wx&4?E3&8zrqo zIP6kYaR#4khAs}`477AbBM<98`*Pj$j$7DhYyVRLQaFl?#SWDh`kkms4U(x|U-&_< z?VgdYE4*g2=S4Y_6mmDNmz8M2aoWNtXZ2fooO$wykYGNv)Q$d9QfuK7_YhB9M9pUM z!ekge^k)W3q$V=Hh`>TC@A8yBMY4N-~ro zY+oW!71)QkIo*GFjQ#M=PFsY<`l5kNo+Ewr^}Jwp?!KiJVIiCrugp=*zrUfLi|e4__p3|&2}&>$yml`EFpM@)*h<5-R9hAF^cE2&`Z`HG9UI(T{O7ER#uA_g`C^I zW&K2eN19dfS0f^fctEy&sp>N9@qv|WGZf6xRaL1Ej&j{Lu&4hIg$s+$P|eTa>pi0? zF$|$);BQk-0d-E|iZr4MUH(_5@N~mD+lNNrn}zxXgF$W4?;fYB)vRL1XQ?%9M==V( zBU1MbBziY9!+Tr22wGa>$GE=S{Y$kzBioA83k1q(GTv9Y`<%FPd!nLMT?=xWBqp=h z`wWS568Heg#6}aJ03`hoRlOf(Tvf)4fl-8cgJ7iM4^2-3v!0Uf--51a5>!8!;zz)e)F-pV) zb~{Nt#-I-9Kuu0`Eb{psOVex=!@uH)KGQCcHDEK9jnzRj^4fF<5MU0WJD7>qbV&k# zqQ=HVJZ$a1zcce}D6v}7aaNYP2ro`km#?RfflF=iXkM3r=f}5Cx)Normb@v)^9nF$ z4pNhSU1b#4Y`3N+M=aFg$Dk`s_=v%o8OBHbz_dXg@MS1VkP+VAY>k2)Vb#f@++`lh zAaXRd;1k14E=5z0vFzD7Zr{LWVy~y`(q+3wp7YZN_|?oSR<1X*mR_eN8!15yz)xey2+=w<)p>wKBaW-4lX+n z(*(E2O?*rH6q0A>RdY{eHJ+8q)?gYtph>AA?wrTMOG6`<{N3H2mKupyuq$lO8c_O ze)!j_T|_N`|EB=e>B?AP=^v=!9JJycPf_GPK=Z3e)}wYZWh!Ow{ad8x&^oBxLWx-<3>lYL;bts$*nKOY2(g9DKkg6 zz()VCC+@Ic2wqBRC~qj`elB~16!h78rUo{BJ&nsS7PfwQmoc6*j^LHE2r=ru%8k`U zWOwzT^go`sW4rg6M<25sEzPE_2QrVCo zs4t4#4!4SGhf~%$>tEDefP#xwU4ywX>g8f4siCtL{_ORes1t7z27MK=O4|Fc0!`zu z5yyYEo2B}ZU@EJ|lwM9Ls5_`Ak_FCEh=%0WYg4-c+d`quXLk2}n^K626ee38FW5Ho z&3zAv@{gq+x{qN~KJ0tGS7$Si!n8{St)O2>fN{%aC5e;nrZNYNd2aBKMZv-x%xCfp zXe#HgLo89-#VFP2@=aIOO*XV`1%o72n(i59 zSz^CphOWziRMU;wV1DpyCRnSBp9?1jGjJT4JNBuqfy}#vkbmb>ru3&~OAkSo7=;w4 zq`IPUoYn%~!`{?zJD`*K--bZD|&as zhV97y+MArUcCQ4UB#CcelBA-~=}2jO7Vi`?LGJ^r!oPAkQ}e?CC6N zy){c!frLkjDlsGrljXq!&)CZ>1HN4Iq`3usZ3%s9b_myhgH=>}aVZz%YeqgrJ-0K) z$^AxyG3tbW;`CK5+V*U~Z&{A0+r}Qpjkf3xU?~yxBapvHUz0#a_l~_eK{8=ShwXYz?SrDwWZC?0$Bqgum5gNOWaZDdo&T3SlL zzAeMtZtriI36^FErj3@`h6>s=SEUsGT&2yl6F&_m{LcELcHL?eJs)R0V0`-T@P`_~ z?HiY~#z>JOSai0d)$`p45ktU`rIl8%LWhoa z1jkzOzuI>VS82-fh6?R*!oT0}&wHrIIILkiWo&01wrF-9&6+T6chi#g|KVQ}*8Wt9OA{vd&huv{Z9KNCr02E^0S&`# zZVw^KWsDocK6t&;xwDX-5BMoZ-l=+I6^NAEJ-ecpD+Ps z`%Y_c1)s1$-N*2F%ewRV7s&nSDoyzMgXo?4LORH7S0-Aj`SEIC1P6PI&0jPRp_6^e zPB#OW(XX(j*MVO$TwWee*=*gHpE`$deDEoaj>IhuGrr;QHNarDBm0SmPR%vf@Jz_Zs&XlM3#6`sZqH(wGyyEuff{yO~fRDh{ z`(oPsoZz7|haisN+G$ZKEK^+rrs4%vjn zR~tx>$N6kKL@Th7musY_6RAW@;b^n_}AD8 z8NH|@B#R|MAwr%FTaE^N`iB7TM!iQ?g8Ia!3jGNJO%M3dVip$1^6{QO6aR3~G2iya zv>8tU#i{#`#H@HNBm#=Z&`Lvmdp8~xx1sD5-}j@NuHAdi7255O#u2&wDz!oY&xyTZ zZ?<;pcwc6qmF)Tg>n+2w9#U;SSl@2`>FEuF{K^p&gJsJmm(h;$AGu~5H0VFFvFbd3 zFS~NYd`Rk!+qj3D6`cA~G7$RHTHVy;nh{)>n}tib%@;d*ep{oF!TQ?MrXUYv<`t5L zo{|o%w2dY$4?pNgDlaG*M@9;|Ueb_-2AsksGw;~oeJM+^6FT&B&W9`HLOu^y1$WT= zg_b4#SM-R79Nk(D;SM>v*}wK6-6uKgKrCM4L`^5d z146)VADHJxUcm1R$ZTgfDF z3AV})8=Ed1@TzC;y1G;`BA8)OPp7#%N#N;woeFcjbp5b)Ti7EF*ze2nu32#U`dcy+ z#&W?C&Bi!j8FenGev0{OFeb2Tps+Sje_NLm)p*zq9M#rs$N9b; zIv~~vGo%EJc65QzD>vF6U=JE->I8ig%JQd_fmB{0tJXZ0zi5m0dOY{@0iN@$eAYSu zIELPVLy+a6E`TU&pb=9!+Gya#mIDLAg&0My>WKWtJV+O}p?D`hNZD!y9xMTg5?``J z&ByJlqoNa%&n9k6=eauhPJ~#_(%+HGz^LsPJhFpC(3clk=}1)%Ac7SRE#|&ySMvr! zGTb6Ywog{g2MwtG{5LRm&4F}*q7x|4iCM|Ms>T!qi)o+^YqyH0-<+~pK&CTjum3(N zYLvnS=&mf2$^Qh{=R(GfQV=lfY`Tiu{AA^~GOa_X0v;V1{_V-*I%Vww>IK;t5Kf0) zS2VeL=M_wRt6ox2HqHEO`uA_w zYBOt|g7tB+GsGw8U=HGmsRZaa-G%@2 ziyN9Ohf;ueQd-YI*`)O|ki(*2A9|FzGKgbCmp9Mi^%P;}z!`YJnVg-_W?qBOfcQHO zBH|(Wia0M)8^{xh3|8cAAa5*km7*X8#duMK73DUf^gxtV{>cAD>47Lc5TytI8#Qd@ z!_?rRG7JnkigmMcurTCV7{}#!h55|9;ci?S27$!$36{au855? z0T?={U$o_M&(&o{glp;J2OYx`v?{{5AL?xb*&k%%awfKn_Dda>x26M~uBKt=t3lK6i;SwxkRqwjB$5hKvCV3!}g zbgx+N9qBU36Ph7Zls}P8=JC*y#l^q$q4U|F<-te>`1P}AiW+3KoavEl`R3-Sa}DheU4YK7 zbw2^|bIn0OX5Z1@+W@S1yGqGksta}hi&-7=ANH`n9Ne0#c=})H|IYy<3W$50r^~dX zCj|f%*ymd`S8ZB<2dh-CO1%hOavi9{jRVHduT^3cIjeR`;CCffAGM+NzX1E}Rke4qrzSTU(fpTdUorg9c#4t*IGsB`$|CaDLw$ z7SyGH9hkyzP0DjWAT#6QWgmb?l|DoTctVs-{o-GE1}uLV-1@Wa!)*{V-|8E-SB_qf zGpOz8w{C>fUS0MSjL{e&Cs8ol2mdSq-cKX`&1{~3=cf!{g6h`gd6S)XBQc^Jf;9fd zga}X=ZF?K$?`LzcL(1G@M6DR*wtVyO-0Q=Dum`1c>?X-h2iksOpFP#3*Y)op9j4ur z(*{4w8REw_pzMp@KTN#=@%aI`qW<8KB{GP@b0&Z91uBny@RMdtQW?GhEW(<1X7b5^ zk3b0DI1^tRq|D9Q zzaB1+g0-;fHRfKE1jM$9_COEf&8huBiM0g^j{qFDR_BDH80F?Y&RnOmR2i82{k^TG z5TCWdNszkTt-y>*6TRS-uf_541$uwYRVW%*#!~A(XYvvph+nwVS2QH>Yn7`zZKy6B z#QEt*rM{~IWJXy)2|twfU4dky25=0Gv z+Ri1QPP-gVxUFH!zOjtBR&S+w7+apZvfF=TL)`mai!g^@cK0up1cnbxat~K(^RF^`i_oP4mEJg|a48eAPxvDY}sHEh1W`Z3=02(|g zHOOdN0Vp05dAR>I4+lh}pH`e!X_Dtv+aZoOEoz)=DW~FqH1%(sUo@#(ARn{a)$(?i z7-d)U4P_PXYR?za{~;J4O-UbW!X8L4slX+r#{cEMf~g;BW;42aMx}mIg8QaGtpYgf zpeSpd0ZeVXq*BXmfd774c|wdL7W-iG2>xfS`3!FTI`PkokYfDn0uJh3w)$G2V9ulz ztn~ExZI1=q&9UdFuBo)+4Bo5*Jpl z96Ijx`w@6*Dt7AhwYfoY79>{#vX!MUito;{r@N({@(T^aBN;sic6= zGB2S_!orFosaWH`1lyT*_}Wpw3ye}s;asF^WlAK~+zU1dKa7%*!e_*`xb9(gM9EC- zWy)>6a%=7y0AfJlDjk`G>y?4ee#5Py7hri_H17+r$HhlxmvY~!!bnNsF|Hqx5WvMc zDU#~4%k|7{??>vCzE=R22~9UGF@k@bAcDopwx% z(IDfwNWHsYN|(l?Y@huHvaLLls*e0!b`lPViKMpa zyPMlH^VkCjJLcdgL)chy3d-KT4*u}&;{UWN*&QBUx(|rT_R#NcY)^Xzviwn3<#OHynYhU+5tXeLI$_K z#55JMHowF;w5|WCKL9Be3Sf;XE*rjDLF?WJeAdrg9{ML!!_#2dI__=5|G@BD6I0-L#>j zs(|>a77YbMoH`0zVSfDe3I)UsGz*tZg%1t-%muF+>S}XqTaqUs>={5q`aF%vixDOn zVpd9s`HBDh2NWsx?krS6>{)6t7gNl<8%gCgzvNG1@pFNq7aahz+F{=U@xe+65-zm{ z+TN^fgZ%>}KE)J%V-hfV(3&Y{@j(L&m`b5Vl?JE*MU}??KPrufM~^oB_M3#$?j73>idt2oR@GF^ENWGOPK2mc^?zHd z3RS`HL06c6qX_x-qh`JQZ72$sl8781jst@7%W|fBVr3{{#N?2R8r! literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/return_after_stop_line.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/return_after_stop_line.png new file mode 100644 index 0000000000000000000000000000000000000000..1e2b0ea95d3b9cf83ae5996408f5cfef1af1c484 GIT binary patch literal 118102 zcmeFZ2S8KVwm+;W_Kt#uVi{x50TP-G z5epzHs0b(sMCk(3;amG8C?zwacjlJw{k`wa3^_Sx@3mL?t$MO&v!2%M8B1qOm@r|s z_C|Gs2@|GLCrp^UbJ`TR^7KaBIrz^+Zv!pW3CV@LA0|vN%Asm(p}PAyI=eYc5X7r7 z{}RNBIZ?c+f_Qa79L~nWL)6~chU8`A?k!4opu#2i-koCa?C9)Z&%6gGhLaExlM)e^ zF%pvz#H)zQ!oTp6qBvPeGv@s^BnL8UK>{Vf+0D&H5T_|ADh5mayhU7G5U&b<={l2r z{NTTSGE&x35^LZu6%P+L2U7=I9cS2AQxY#NikCu<=xj71=nCT0;BPl)R|oiymV=!u z1wEqXimAY@=>PF*EY`vYvJH@pJt?Sx7nH#Z%BrybP*ubJzzM3#uoiV@F<#S5 z&DPCEQw*o4>*uUvsw1K1;Xihd;ho(5w7hIQoCp+q2RGQx-jBH%9w&p51y}r8go}yc zWtha1yoPsTZHz7$ItL6Nk@Y0W$JyS&oAosFNh*cnMs@ZWebJ6WCOg=%^nkUZjh7dN zHu^S4iW}>Etb05_eMYU0E*OquHM(l*Y)^G!-YbKXX3~PLZ**`bISubDE+xzS#@%N4 zX4Xl(oowtWH0JZzrIFHNa&nlTUK9$fH$s>rzaGBH-A~QI4Y7NekF0$_6~F)4FWm6@ zVoZN$InYAaNA7rcBV27$d*E- zQry9c-Ov}RHg>KgFNzP@UX9{LLAr16;ArFH2JHH>f{L3n37H<1;sIA}ygitD;pps# zKt&bXP-XZk7z*A@%H|bc!IyAubsP{FTq8HMo^Otuy?m}*4}95VYbCy%@$9R)pk)K5!6)t z^juthi0b+zf{~rLu8W4awzH~-nYx&>k(Q>U*_KU?1ZQp7bF-F#n;Dsa{@SP~=3wgQ zw%J+I#dafsN&rZ;G4=B%x=Z@nx*JQ|;SKz4aa1>=Gr^w_py>|#f4Qb>D(+#gW#VtE z+^;}3k1S1k~#no@Kp|&5vMc;?u zuT64L*8uKpl>lx?05@E0wKM||hqvPV0(6ZuoOJ{Kd|fz|pRS854xW`H7@>W&#dKYO zj~hwMebhC4h(=qTwYBuTw{Fo3*lf6o$w@5wOwV5ePjGf6*}2P#F~4)A=@@F0Y_v=~%y3R(h&DK*KkSXS zF*Ojg0gWLT5qt6Y*NZN6&~2ZO+)4zlk=YnuNcevx*qOUqW0@ z?VqI0*hepbjXb`cHc5iBgqWV1N&wMNB0$gZpQH_}(@1~3OuwBrai9(8Q}Nd`as~Y! zNt=cQLCqD`c5<^ZwWru485*K{wMq6kH&=Ttgc2G7x-Qy&NSB#5Lh=E`K>CPmL{is< zg!Fujjc8*wV&`t+Vy~tuX6LTyV}~;XG!m25CNuR9Y)Z_`kmLt;0PAU!2$-JRd1!Ck zPEKN2xthFM>Ns~i7_!0lcK+bKLM=S0YfJZw3Zk=BY_YGX)+PM z`&-n3UTENfI)7c4t^WTcb$ZScID~(HhdQLu1aWOZJ6#ujv44;{&{zpT=)XxFUf0D~ z45$OCXyg7#>X7gF6TQ>&^8o)1I-!kph6d;@j_HUx_8AAr2HxR|=Na)m=862+=nS9+ zrqQETwxj8~*de>bd@#WX!w{r>n6K0ePysAP+RE~kMhKt&(oaf&zrrEha$rj>33$4d zxhGTOC1JlYxWM%5EX?{2>rnx1GDcAovK~KzIsvSW4b3C*`rGjqa0mPe7Ly?ViuMAl zA4mHry!~d{iAE^47{+o9&<%uhe@}b0LAu6xZ8b4}@Ya5RFM@D|cvKtzg|kL>pc#MR z3BQB0Ox^xBa8-RP#M77tV|MgyT>bXAii9wA7_I+leZzy)#Pl#b`sX-02_W9cVPf zcYn`+gO7!Z2%-*r?^cO_kUA`WWP_pK!#g9Sa|Eb6=>L;wfP=Ug#|D$XgEG(y34);t zRFHsw0U9H-SnBuYV|qq_dtWnbblN}6ut!$6^a4P$)KR4f^I>@KSu}(q%xab~AUp|S z0Nbc{VQhpCyVi%|5TFks2(s3Hj5d%biVgo3-z0~# zw||f>RKxZEoAQ(dzGD%>Kg%<1=-_~!{5@S8RZIBi_@+&R8U^id$`i|DA!=jghA5`S za@;ZAidpB-#o3`cDYK^qe?h;D)!c)Iodc`W%cgyZUHbDL=GRW9mIE}_sb0`v7Gtd_ zB`bj!m1OS3Y934A@uD~h<|W$KUaYt{PC|6J>*_SB7b__(Dh*A2)QYrW^?^xWc0yOb zrB@2~uv)Euei}65Fs38R>iPTrA8mtrNT5*0=Fi%pMy_B8vdsHXVNFZi+m?)q@J?d( z8&#xq{biwnYUg7gK=6UmJ6SgXj89#~*A8z+hVThzV`_recb7%3j;5^+EmR{72;{;2 zsq53=`|oX?f`YrzbhoHN>7FEIzh#rRj+!2J%?_F%HfpZp+oP;D>zB5vGtCE*C1_0Q zeQmRjX_x9U8w>#sI5Q7hEt-^efOY`EbSpGCMz>O79S=KAj231i6`r%%qDq4XAO$s3 z#}`MjGmmHhYM>S}lpwGYjL)AWv1+o|DUH!7)&HuAJAPl(Wc@~m(E9K0^M`z4Hta?gkpG&`Aa4|Yvq?Ombj2+H+l?=GA#Ku<^>#3|_qBCarP<=# zeC#)Z6{4X8kQ~ua1+0sJigF~B$UyrNN!cGlLP&Dp8nl4n9zO_HfuoR4kNq3~ZAEn` z&lsu%Ko|p(Q}KiKppXQE4$#s=*D&i1fTA+G?~4@^K)U*HuLihrR0>rAS7Z#0wqd%) zmF|X5sU}O_>_YQ3gW&*OJd9=pNT9(Qyefthu3)ehLSVOM>kFYi^3=Q~$5JsegG|M-2MWSmzd-b8+=^axgXV z-vTNKb0e;1re*=~-{Hv^mRr!2Hgk9LwpI7=vBgQc5%GG^NtX38GorXawE|`Ww8g(% zGZcrZ90NBycjyF~x``2?3rNI^A$4X>{2=w#GI6&96^F?q%+(pQrhT^H++1LNZ03dq z*Z!!x42A}sAZ?Nz8JibC^=9bjjhHuZQ5gv_Fn0nj8J_!d7$4QE`?h`1yv+!gfzA2A zJ_u}B?uzL;*jF`}E>H`)>F#2F05;$bXnp|gk_1y4%FV@eVQxZC3#(1}!QTPkDgZc0 z;_x?|3A;xU`x{3B5OQ(>P=lT&ji!r04nhrr%T{lcvjIJLqA3l)Zfk%p26o`izMUp` zPDRpI9ranzEQA5t2f%LxJudoqUF>_P;i}tHP>#11Dn~?hJ8yy-+Se`s=!7{N8n|+Z z!wpB!W5lX3v8QMB+!Bkg*xVJUpQ zw8vl51+v1z12jwJk8&!e9$;M_)MWr2!TQc$z8h1A9`3G;>S${WKZ#aF(;}?d3bZP6 z_+Pr&U%vZ;Raq_sg_@hOkzCAy{AV17Bu*3$aE}oG%Vg~Etn3JPAr4c?;w*F?=`o~O zvzh;uq=uE0{qPoJW;!OMuTJkqAGi3+=UP$L>7TLzN0TE@&Qf7q{)wYA(($Zo`>%*4^gRL>VuH{|k=-)DZGP}eKf#6Pnd!P$zq)#1n z4@^>G&mrnHNXX*^=;2`27OI6rNJ4bcq?@`O`V8_F15|@#1-oVsNe6fo7eIcP!2mBJ z$y^^24m6vDd7>}(+5i{ER9MD))?p4ZJvc_!Xb+CO0z@DqyzAH5GAt}-RuG}f{AXMp zji_)US1gTWVm?$MSu?swmduU@B(Z-${m5>{D7?pF3xvujvB2hDkWcdelPn6AD|nBsDkg*QI85e&HRKiIP8<3 zGxf`3@b`$P;M3QK(1+n?n6h)QAM+BTH^s-xj`ijo%jJ96e0??VU+t}p&=E|L*`bz`sAj zDLXeCZ*ONi4CVm7Shpc?V&c{ih!&fifL|4ZDQpj|Mx&q3XE24w2PM=TkiWez@Q{bOh<1k zBQd7R_&*MJY>x1SbN?8^Nr{gcN|6~B&i8HczYA$BB^Uu|dRk1+;r;dHeHi>fZ`_ZF z$ZS|I-P=J-glv1<+xYIz_V(!Ae^r{3Gu6S+!v>3QXz;rcaBXxvH@1oE2u)qqFGJvD z;BM?Qix`A@=<^87)6^6blTyQ0{Su_3_>6f9^g9FpzOf}~X^6eWB)*h*SRR(;17&2T zzWfl#h*%7j`G*_8BjYg%8PTy3(0_D%Nt^`$BXmK_Ktn?hA{Ikv|ER#vq@W;dgkF4= zBa#a{NsmyOkzz&i87Ec<(?^K)O9Ve6_xg{CRZ@q_v$ADr<_OsuXh59y-;gXjgZ&R?)l%YrVzT05V4TChS@XXwQI^_`kmxx3 z9RAT2J1>ei3`G8wg^sW^2^87EZ#j*$$S-mm9d@$P_5Tdq;$%c2n8j?11+ubuR;DvT zT9PbnA8CHW*Zw=^_YI?=-(3M=2bQDbet@Boalfe8mpp(O`s0}a{htN@=)18oJc{eF zL_$;y+S;(gmyAGCQkM0Zef{G*GJ^kevA&e73@Yb|!S9-l)L*RVAc2GIo#jzjsxqvn z|Ay#aLRNBYT@g{iBx`uze>wdB59Z^;!xGx&6G%zpN2N8a7-~dVCH`L@R=|AAAN*Y6u;2Om)089YyV$qG zKat7&g7pAIxlpG-zrOgHShj1zgyj=pAl=B%sOApQA5Gh&rHd*el#F_;cHhpaL{(Lc^^kMZRy{7D<_SpVT^UfEz_1PUII`1^L zO_<0rd8w#JUsHPi%LDz-RK?HL){Y9w?jk(}H3voq|$=(C}?v$hu&nT%1%| z)r`@!QMs5f*|J0`oUDCi&+$dDUHMMLm669#jz7c^PF|J&@jSX3Z>e1Tr0*nb6B`#F z-PIoxJN|yNi7M%4p_yE;r}D~)D$?_*+U3*eg11+jnZS1L%f_s~Z9Bpc_YN3;zYFK&3YUQ1$arKWp;zu6wBcU6aK>e_Y9~SY$B7RuJi{jau-pXJ|PT>$?yXEyI`NX~3F4s^R(d)$+8X4n19GV_%BzTC?2@aBf; zJwxM9Gnsq+az=n0A}4-5P?ME!Q5N6#EUy2jNSXfD?nl;x*CzN4be0_m?kZoORvyx~ z#lQBLaM)18^`iR(>57H*#Axm$($KM#vyqB&_nT5pOT4GkwKLo`$90H{#ei2flYHb6 z5m%g$IE2oURl0iW;|{dt^YK*Wz76NRLJ93FuW6quz$+iYZ}~96BZ?ZHbfqtei@1Lm ze}L2N1@b`*HF2Bjds{s77DZ8CC07bDeDi8;N4Vc%Etold8l8XI2-%mdVdOwByzL}0 zRE|t7yru0rR$*A>UWbIfqJcjrl?`;e8I4Ipj2BZZ;4@o=!6QpB89V^uKS}b zeP6w zl#AUT;x|Xd2i7h!y|==8@DoSrfzWC$PlnAdhrIr5?;?>9%Z~ms(>V$fifskN;{kKS z$rrP@$M?sfnIB)?Ix$lLv8g+H8<9~r@YC}Z48^v4T;eX#?$xhIaUx<$S9_d5Gj$U!osmII4^Jv<-dGn|Wvk=pY zdEgwCcFAhR1HENA+&m#eeVp&*t9lB%-#J9(?G;WwA?Vg1@6*LEEn4^Zq+v|x^9%ao z{tu6qG;0)#M3mn7%J|`Jf|oC6e7=3KVkI)K?qA8xManN!Xw7djt`1z#e>&q#QdzC3 z#r%ep+>p}C2NXYTbjz*qZR>9@;^}%iBT}oYuv2Y?hC*; zsyKsGL1W`T#>;#5cgxhrc+a@kM0>eHFIr*^r8tT>6k&HDqCJ5iJm{YA^lZ)Vl;Fgp zeG8~MHmN_4xBIwh)9ArCr*v)TLWf{u3>=r{&{w5b%9+JExd&G@b|j`m`jlBpV=H&p z9LV=ACoc;fXt1`cJ!TqN?)YSH?Q!$u`mWWC&oR%#*)ZiNV9L`g6>DMd-mRdNfxX64 zDy9kqiTPIe*K>F=XUC#IeCtRtZqhv>|DO(`L6Tx2ITU*QbgO_Nz?IlT;dT z_AJ;+isLhP%WxAxDB$aPy3op z?9P}pXZNJJa!z~1%-eiRAD$K~XG z1xJLm8sZ#s%xt>0O`7vF2SqxiYN$LnZ%#SII?LhiZ0Y?vqS-g1(`nSC`11Kj_6;lA z2rjQPP%iHL1);XGHHgyxK*q!P%>0*EJ@aE^Ip3x@7VbATwMcF=Ypl=o?^5btVb+jlHTO+u=!SugXDMcxi>Pyzs&_}0xrwyK0^;&m z2Z@(j1vZ`VygQq(!djYVI=#Xv! zyZ#vGSv6_y!l9sSQ{n1JrRJM{A1@|wTgW*T$1lF#*PJKhWS+Y=gD0glA;dg4C!;fA zAk#0Ocw%#7S%K@mC(;L$6bAh+gXb0Ri?HL-=?)pX8-!mmGG!G3CF|x#w+7PS2B@{aQ+9t#RgYQ(`wbJaml> z>=L)D&IxQ0Nj@nV=zC)&b-i^sdA(#3bCPQ0{>2o4iCn^)0R$67G;K3APOaE|$e!H5 zm7&G!Z!g%IL~KY4scr8sYX~+lEl#r6l@c6lLI91(h*S>C2k$fqb;N@VAO#cgYyVXIsLJ>nRn28!IkWxs0op&@>^UW1vguCtr#;{#uw z*(KUt__~x<7dt3dWf~o@AZ3HKa9!GO5Y1NS`>74~-@1n_Ow@N#oWu(OPO0Cio?LOLkAf&(M;64_nxfsY}U32e+DiJYNiz1!LSI6*19 z_*IZ<`th?~KeIur6r{8ZM<{LK3I;j5v$X9rzVL!zhq#siACEQlP`vr04>AkK5C9~F zm2t!KD@Ht@>|G4ur9({~kM;gVCRtHU@tXU1b)TvXZROb#hocKg+aLU|riK!bVJ(gTXU zPHoq%Gb|FtWoNM=F%PC3`RAasvr?}zSw`~pW_nv@)nM8Lerd7=ug_!g)H{lHAD?$a zu)K&AFyt7WmlD$RsG6jbZer)Pm<{9h!N{lr@92Y9*fWZ6wnxfWpNq2ED_LfN5Akh( zl6t4oyYb}-JW0><{MEq5`8<|>XX4Ehr?aJ%9Xt6TaqBPgF3Pi{RTwWXy7_MBmcXV| z*NKB~;97BnbR=X8XLdgs>UetK{(J2slPk=0^H;C|73%8c4BxuJNKY6)$LO~l#G>-)UV>;#dq`{?H)QR;5Lm46?jDz2LsHt>gVJw2?%sS~qT@O- zC@ntPMc>OMz(|l)y4B$O;Mq}?y1kO zi+1NGZfH|qm)rlzv%Z4HGjzGPbMW2WngXG?{Se}cHs{pGc7Hy)<~vz2IK9H8SfO>> zq-wfrib!P8I}M(^)oQy;_6{;u9k}-(DP6R%wX!QmI;8ck0JnI0XF{hO<@Jrlini)) z?ag-g?*(^Nn)h#T{oJ@%!f7+HNYS(ZR~he*&oz=+Q_zeLA>3@Hpo@P3hpGLHx*loh zl`Y7J?^*@$PGz|f{vLoQ4<0Myk@*EXf>E*3gyKZ{s6)0uZM0$Q&lVG%0aqwnMbzpt0 zdCa@tj}RkI`@YsLPNJ@q8lU?uzhci3-h4R2p9hmR?BOVNC9S4z9#tT;zwM=0`;&b~ za_bdZ_B;~J1$v1??MnHO@f*dwD|sZkFO(Oj{@n{(2esw-740H_O2X7AL^zFr4gw{k{g#=(a{g~dpI>f>;>UmsOx!4jX-GWU{KL#v+Jf+n44R1KP z;encTrOe=`sNCms0zdQ7?rjoI0%t|W%~2l*;L2}1!FtN1y*SaiB~Y9cxI1HVg}Y|t zeyzH~q(z@`kJfQ@DRuwidA{Jt>P4YuDedP8``)e6T&UEd=&1XK){>o9bltHiQf2#; z&JO<7k#X}#dZ+0RBuRxQ`6f-8q)<_0%ZB(JlcTA`vp|%C7S8I zZ>QGG7QVcBN&o&O_`TUxS@)NEK1xdGR+>pa7IF7Jo5hZA0Z!P;QGP<+AO<)QbH4NA z^|}RArM9*M`RlDB6Ur>RkJsJ%tesJykD2Q)ZJTckGz__IFv-AvCHkJ>t_bwu|>SVdmC*eMX)@pN&| z?YZ3LbCyZ1J8$Ws(sn%_qQTE>Oyf!iXj{oLGb~8JK|KJ!xWtuL9Euo?Wx4!3S-ixe z4GouHdL<^U4GV3(J=L!4G)?q#B{{Rnw&X(s4`RjsyXVJ}3kNv930SdKk+K@G!U9-f zu{xFE4Xhw4)E-69kw=ILdbkFG>gCCUh4Rh2uL|^Sx!OerGyioD*Sb|-qotV7m&7G3CckXPf4XL`qORf&`I8pVCxV7bgDZmvkBobIg< z-}ADI@2?mE2MpT$@rdj1QAmTks1ava+(d@af0|V?I=~o#Y=&Gqz3`c*6rzrC5~4Qz z!%f@^sF`*=)Xa7-$uYMh4#)x4`ou!7GhaXy(KUByp0(opgLi84qpbN&32|2aK_vx3`FiqAMtjPHw>LY2R}mO`FSO6w z!ar|O9>mvK&d+SSchAo&$~>@ytE(cA($;?Y)pfh#cohYOu6u1<)sHV4@?_LKmc4HG z%P;W>eOvdBp$0+k5#Z)(!n15-F}G|{q9+gu*;QUasUSnNISA@np+f9l5ebFo22ZBS zL(Zpc4dU@XV2y;H(*J8R$mBFznLsL%RIVPg3z4yD{yeB75z?GaZ*M;3n!KdE<%*h( zXZ>l~{gjrR%zTQE7ZXmK^si%>;O0b+FAe^IvYpf^R`~c}Rn1`? z(KY01zJ|+O!UGjm#vDURMM?sw=wsU=lJ*8yDA(7B(t*RCFOQD5$Xf;gBszKZPY@0r z+y^8-`kgzt5ctP4M^PrktMdh<0Vq3Y{cRrv=!86*G2RYA3sn>XbaL$`bnFM)q^Qx6{L$xriI)Ctkj`>5Y`@@p$uBKe_3SMbqWVzkC1~I@jJ##ty0u z2esdPa%x3{^y{AoA@QB5@%++zngD)vb7ohiZJ&HIUD(9JGw;L(XM?tp(XnvK>0#B% z|68hcSBNTbQeHZ3iR`s){E%$v$`AE#dYbF?V1;Mifl!N>chv&@%cWlX*{P(L?0Ff( zM*4>lkLv0yF&=?)jDB_Nb!0Sj;@WmDtH#F-QawK@!r{4sy_9zu&c$&}B}Al%M{EWoq#g(;5~Wq@8=nqry!sk0?_C>S*= z^5&aW9V_oGw5U2`UaQ{7#uxum0AdyNZWqPG3U2a=+b{0r ztf!`%9MuVWV*A?aBujUjle1H~-wF&o(1PA$i)i7eBd*DN63-LY|3+?j(R+{Fa3nLS zj7>VF^f%I}v&|}9*W>yuf`Y1oXTC>0gJ%i47dgA7BNe0yUsI{>ec&8U8m7gPwZD?$F=eGP24oP zaMBHfH`JO4&QCp6Lm_VT59d=SgxWX1dFlB6LG?P+l-mEAEdPCpbJx47{?&C)qIn*P zq+2}BXfMRtm&;na<_ho=6?^R0Wj0=GD;oN=zU?$6G*c$Jr8w!yZr)$n7?3Nf(aghS z&TNmDHJOU0=j`(>k5cOCt%P!5W(z%W0zb}vV}I+lM=m>p-%gx*&!^1FJjS_?&v&vSlX8EcmxdUaPA|aK5alzFOQbJNq zUe*V7Wr};=`L$ZtH6`1(|J~fspF;+p9th=K=5|GeU1Hv1Q{6q?v+nuDeHPwzF|WkM z#EPE{tQ+5ZR*u((i1o<%4_3$l{BjjORL<3caB5j)>(1`Dp`JL7ZdST{(c~rV@ky@0 z{d{o97cWfq3DrLl4heaCW*2viAsqDq+oO(ad_es(v+0`72JncnM7=$q-3z zC|xRjhBA~Ttuo`STV})(F0R#j3!#81!nS~UWm|m19u#kf6Gwri=`kP(~ zSbl!pX5kuXrt-BwUTqP<=iPFt%;Xver;IEIK5E+rCB)lY}(oZ za8ALh>78bw1D!Ql?M2q_A$`BJ+TI#*atu#WVEiK|=a4Y^B7P#W3$@FE#qPlieAA&} zq-8buliLgZbf4H&bL7`KK0cv8E5tL`#edLn1(Ywk?y`BQ|C9)nIRbNA(Z zd+73r`gzo4ZL{9bqw?_hbV1onBZT6C5Z zH#b7pX3ch|9dEQD-fdJE>I92M&Sy=|GiX-+;egF0F8Gy$>*-k5|I^(TE5>>% z={|i)#0UH#FKs*r9#z@&Z91%fRx_`4{wnTYOKtA%q6wDvz9=l(FhHG8Az9EYAIHdg z-xl(!U;o_f`XX=h+|L7Lj;xrPimowQjpo3`XZcpH$=;4Y0;y8!RUCQZxHDz95g zt*;t{YE`vXlqGl4t-g+D#IB9Cp;51VpI>ka{?yf(BTVyLHj}O(u!oaP&4HQEpWA_{ z9kZIy-b;FtHeSr+0+Swh1L(jw}k z({b_U$tf?`?6fWd9+3#B)IpEDg67$){Vs>5e(xg?CjMd+PUd8!p%NYzcYU?Y;xnM~ zD~>)w+*wXRRpg$YU&$HmT+~OMsd8g(MnHZJa`-6CqCiCM@@4Qqw7$rv`0($1_lwLnO4)xu7G}Krdp*Q@aAUcIHc=;()rUYc1 zPGzHr5>T3Re=bvj^@rB!L2TOh>cS^3`dQlRHT;85C^K$ZR|QfoU%4~G-%hl;BRXR7 z{Pwyh`;M7f$&%yn3H4n<-!*PA-lXSJ%%@-GU+ z`a`s=8ost?t|?7D1JmgWLaEEgaZ_0U)F4>GEgc4e!a@*$#fBVH>C&<8x3!QA4w&dy za4zcp&Sm5i(vIaHpeR0sPpfoEtj--Sfflt8i<@LGveEipu%4!~Hkrntq#aP*itg%2 zoJA+a`Iy9b^tW-o)z9bUs<|J55nX2GP2i=z4a*CyAXNp|0H8H~FU9Y62}C}H%E5#= z%M>@9KOGuUdBQzmsQUKQ{1>Lymi=Wdv4P~Ex03`I-??zQU|H|6dr8)WtjD-V_nxG` zS%3y8vsA1V2hh}}-%#tjr@i&jCKlq3MJKsXkXqD2_zsrLq34GTGAR3*|^Fwk{C zE$7oQY<1cC7%r~-1M3Ifp&+$SJ0Z^MVeoYNxhrPlO9NP^S8>UWazg~&I@hyJFzQ}(Wykq-Hs&?~xxrl#Tk$0B zdI3onBi&fsxf_A=sXAv<#n|W}8WIz;PsgxnK6qxL3SW3Lnum46d)cEt9%o(YDy{pd zE>j)o;~mK7+5OJ*)ww9{d~$GgHyyw^i4th;oW6o_T+`JCA>&twL8ze!?zHch2joKt zedh-IJD=H zb@j}+p`iXol9IVc&Kb2`_x9AnOa<(;0ww7fuhiNGusXw2>R(bn)BRd?E_sFA#Z`;_lG!1y|<<+ zLQoycE1Z($b=Z3bUHgQ)>Uh-O4294$+kMQDpsqla9^J*I52Fg!?U(UI>uf&=Tek$1 zW!lDp20?(34?~xR)B6PmTX&s+6rlg@RHfbWb&t0)X7x3vTl0q8o3C9Y$XH#QwuFs< zK-xQJKW{?%aO*dWd;1|2KK?Pg>kU^vZ!i@~R0=7oR_>`UY-!f|y$q*dIq6Oq2NEGGjaR+Z zfU$&A=L6ACJcXfA0e>Z4pE-1qS0+XSZM9MP(}iN@5&J(7Q}3W4Jm~YbNpSAZd(hD1 z;p@;Jyi(4_=2t-Ysy5|=6w>pzso1d&!pukyy=X(bu5Rw9hc`P*&1<4^yESeMX74RS z2&FkofIpgYRbzjpe?5$eU8r6>^YcQgaBaHmc&^pK@^zD_LFhCL)Q@<4G1;_s0kwRf z*=3-&MrmM8Y;Sv9&BcURGyAs#1+B)_ALl3f>JGg-85+q)3G_PCU~1-k4$U{Uk$&lX zQ4~qao z+K_kkYDj)r**jI0^f`teQ^v1j0i3W9s(*vjs`wZv^di$HQLubkLwvjnv09oX=%J+GF$E;QoO}0zb!yvlEAx9bRow}ZMUvh9=C%ZOU2hk0SM+0d??Rp#^fgD>k&yzA zNttx@g4Iu|2r%EuU=I%`os=X7LLi9WnAFcX|f2_xYNwT$& z^)i3VlAGnxnyO21C2F zPN7wEYDLAaJb~O)Q&@xg>ayP>o}!lTJPh!({Cr!!;pb*QIggNx0 zMw|q{yn9vT)El1`UAKF(y|CfC>5vaN;^+1$gm11>?FZVuQ&VHgk(w-|8vb0qeQc_t z9B&OO5pp`K4@%z3aiG`!bF-eR(DEZ{uC5Vi@lzJI4klghdF3saqnHQ4FvB5mbQFRV zxg!x!Ddh;Q3Lz`Blcih2q-7a{UAv_A4)qrb$?+F&Qpy${EK11z7bxkQU87X=GPh=8 z616F%W~je?E1z{-wW^Brj%y0zajqB8p{cAOlY+=XJ%z4Y5TGSMbxCBtWAYNu#?~k~ z#q!qtm64}1bU{n#9`Mr8df&u7HA44J!s{NNhKiUekpbT`#qs(#`5IIMt}i<|3E}9i z!w})={ALo@)v=OMT2JOyEHG}{vOlt1PO(z&s-y0K`Tr6mcL}xSzZ4I7akXbxjfkgD zR&Gs0g9i-1?OG!XR|DQGjxHl>ruZyZkxulKT{oT^Phj&?v+sGLmE(B{f6~aQ%A547#9_?eXz3>+;R!KzG_%Pch_p z80WyWbe?p;P*pg&H=!_+jZS`qVrZ$|96b#C1tD1yoD`Ln6)(&<-oJb6_@BJortA(T z|2p#iZH!A%K+$^1XDNa}(T6xWc{VNJ3%h_V2V`ZiiL0Yfkvcxh;?pNMviYY~j{b%O~kOTpVAyLG);83~S zvqw#rU)Y5$qujK)Dm-WD1{tXe>NEb96XcBOYN9wU%K-|0&3~uKo$zk~60~6v?&0sgw z6bD}g%lW0VTFcMX-qyFN2Z@oJy2Z@%KDJ$d98&9*FI}(7#!4q!0m=saJZ!y-X1rN2 zw8;Fv2w&VU`xftxw%Zq(LR&E&&?a*Dqk_zrp9Btj%o(zzy?TGYGtinie+k9d6Kga^XVB2MxFA-gU8 zSv5Y=5yo~VZZFz8McHt1xb`Zmz&ymkj9Ywd^^2D(HFS$g?J>613%XL%V95rKwkcPF zJ%0T)-{sz6nKc(*{!ISZEn2y3drk67`ZqrqSpDIp7`d@qbmzVJZlC>)-2pso5O(>& zbQG(6`Gw*K7H(-wu6@R@Xa$Y35y zwf8T})G}=e&X=#8pP(1}9NoDAz3^9ZF~O&^@@nAz2!;C*4IdTS*DH2B+I8>j0mYIR zfkefo8(V@qUt|Upg};he#zV~Z+1%fKk54{iDB!BshQ;O7pn?9Gp)ePVI>gD9>5q~# z?+YoVhMKmV3~fu-+aMm|Ygk`3`%OTVC)fRar8!HksrUJFjaR?0QF%2dM^b#|-3v|h z1wHo$<18-0s~q}TKB-kpNO7q~D(Qa#lp_a(nqAkhWAI z;9_`lf>LLZWfQGYI`^uPN>_=%;FZJya&&Otf~gh9YqMTdEgTxWUKkfe%iGiz%}^Xn zk3F<$mKe()2-0;;cw6$QmCYZBrJ3=*DdSZR|CLc-@IA zro~MiJ(pH86f+*qXzMf2E&VXRX6XLjwmwEPSA9|*XGP>5%kH69nR6Kz_U0X^$vs#s ze`fb`-@V&@nWVmX{ycrR3!xfU_Hi~C##!DDUnm^@a?#PQ_ph!`xFZ-1Q-CK{If!spmg<#f%R$AbgoUWi`0c!@zd?UWI8VR=}xJ8tdrZRpl9|9U%P zB8R1^?xfS$1|A06l%tf(KK5?XjL*z4;}jVfoS0~7WM}+z6Nlv^tA*-gsK7qnY5-EK z;#7JMp!Me&qa~z2t}Ix85Qyz-!M-_u5Tpl}_`>5_n(2c#EIK|2)v3Zi3fKl$?fcuN-i}W_dn~M{5 zLPH*Sh2o918>okCKb;AmOiwGgFy{2kkK2SH8nzUlP31t0zNI~pqhg~aM@5OLIgX=3 zDIoD-j$qwshtYpWQw?6PtO40HG zEkxDswTO;oK8N1(Y}^!|X_v{p-tVyskFoZm8*0Hwto^--C+QxyCYX0N-)s=Ilxp=t z@(~DpKR<%6{b&-sC8RaSEZx~Ian6qU?3mY@3CFG?ooHKuh}o?y?KR)t-rlM54ySn1 z{>DbPRFQK#4h+u%P@a{VR2cSlJiQ=(7D+r7=YK7Eso#zy`rKK;n+JNk(v5|TWZV8CjB4P_BvyuNYg=BzkyOc2**~zvepw@@zlj-MD z(te*zH@}|hRPZyXf%9Q6pHu$|@7IKpebcx_Qu!IDuD+koFgtDV5IgHQlk^A17ZF!X z!U){G8e_bB#IIID#SurVm(Wd2=hU(x9yCX9n{t_~xtS)WMthi$aBd@}KS`VCusd>? z`t*5>)tgTBVMP2yV48pRs$#+7RJzH}yVxMcHs#+yx3~nK1Y<-T2KpLWl%?0NCvJW9 z>fxmm38&4|g=wylN28){bV93c-h+*%nonFV8C*T=vR3WIC6kDs`B>F^4&10*0 z+mufL>5niG-Rc4%49=#e+moDw3r#-UlzN!`d*<_tJ8sYvE~=htDN7ZadebiI#xLhO zdfbc`w;x(dF3{iJvG$V1MT1{tCeveMjO8NO9OCU2(6+m`BrwQ27z7LtokDj_C+qt< zO4jC3Pe0Fa_{6hR;mZ2f=UOG5Mb0UYr(Cj1S{jxdtl~0OUPxbmhZ;S3hAvJGA*6vN z$RRYWx%cvu*Cm&(dL=0SY^+P{6l`v43sp4#D7huDjB=sqyl&kC2TIZEY|OsKD5D3& zU}Y1HPGNxS5e3BNa#XmNr@Q*R)~hWP5Pp$dmz<|bvE@1;qqbyw?2Gl!a#t5e5DuD+ z19+fLk$ZV@XWM(61k(Aic;;fc>Fy*riJWY278retc7WTsPTjc?8z`;d9GuWO&EwGXu@?N&$Ci}#nJQiGb~(h?2W8=BJ0 zd5m6v-zCeCp(&%YDup$l7l}@N*I)Q>nKx%*`7RFQrIx?-DD_`@_z&Raypc7|_aUzFg=Ip2Dw8+gxu?k5hXL!-Q<5VJt z2Y58F5U-5k0*B?$WV*2TwHv{W$`@Onu5%NZ@m$94_xsj}Z_%mAp~x)h@c5dlvOtn4b7Fr6BVJ2Yz& zn^P}O2F`od{w|KKCOu;wV*%rSmgvwHQH6o49ksm9ua-LZ>0Q+4bFSKX+b(XsjMXJ; z;cGqZ{Kp5oj0@5)pAeP2yvoN}u!6et`MbAwyxNcJBqd)hec_$Ck!y%=U1pg^$w$J| zhLa&FO9j^PROSyX-PC@6(=lPqH1U3s50R$fN`0i58>SVEuAfQMIV!w34EWekc`FL2 z%!x6XvIFsYo~UyCvJ8G44ktl*7k+|U+t)Ykb-J@_V)L5dUZ>|Lo~C{Lbq4X|hOMTv zvwn*wtHzz_D_&NjFm%YPeN#(d4ZWnCw(+#t!sBa%i)T~TWQR+Wb2)hQS0@zY4y3T)>V{njxHHqwQDNx zcFics%RWBvURcTYNt;?OOg~)SBoL%dXc%hS`>%7pjc(Jj04{3t@kKM8+h{Fb)IJtAw^GOFs;MbB*x2%ggy$=`Xj32F!bN zMGqbO^y&A8xVijEK^CqbK3^B)x^qf+!@2=S`}fTin}ttPj^v!=>2KaQb-Rjd_Z&+u z{!rY#*A%^cc91-T3H!>Gc8Q%@M@3t%u9rD)yD_9ZZ3? zZ3{)rs6P(OFw6a*@u96Ne1}zrK0Q7<+d9%IEV;)z#8xMuzGWKqcbPg>h`Ql61>@2om@m&O?ExJfNOcAKvtfp<-?2l2{m4$HuH zJ!kgk2V3@;cH9v=|C?3l{59W*dmHVJ z=sNf4l-xb?yLmpRb#zef^Rs+mWC@}bJ0GFETm?*QdU%}_rql&Usc%4xaE*I?kZORB z%a!8iXAZxby^P*Ch3-&ssi*RG>+=oyr4|LV0JIOA%{hEL`OusSVsFoM=lA6$d?}Or zJ{QS2r_dvZ7L<(uyYB3p6WKzh)qH@=hq_ORh+|s|o=QmCga19`z~qKpkE9#o<~Z)UmBp!boBlvYA^-E4aBMYGMuJF2 z0!T*n=GHo^FG!Z{*`*zKeE#LMT>V}j?GIti(yPwtiG;h0Y!yk((0iSxcFA;AcjKE@ z%anpSRDys!SXndiqNnAD^UtPJD>_XyDeRo0ff1OehES}{Dp2B!KcP*_VN;Xb=@wnt z7G~*!TZ$Wh&%S2bwkdZ=kT2BqiiNX0_3k9gXLruFY)sGMb!+H|ERm;ir#0+Urqu}; zM3rw3cF9cXD8Kf$tg)DIE?xKjUN(UC76&*HMVMBBp~!CJn15drmb^pq^QZcfb3|_L z4YeCT+?Zofv9v^K*}0<7V~YLyua7KS_pHn5LsI{832MyM9{;DxWk;nme+ji%d|CS4 z>Wf33w^Qzd)yz4{&%4=IEAYk$;jnGYj8M-89=(N02Xr_mZ=(P_*U4 zcRaA8hT43#783*7;dB3(2__8-j4?|l)46%-LAm9v*35F(x#SpYE`K3iqJQN@1I;Vy zTf>t5D|nv&>tj2!ms}?K4(0@!zMo?$Y)M@UerB+2UkO*sqR-*V zWe@jn#xko>Ac^!t3%263Ij4{DL>hu?&B7^R$9)dx@vePugeLt|+*zQGo5kjtu$$oj?;ksIA5+dZKci%!;l7V{++GN= zuB~OKvh#ihXZ+|A7IC&_V_8BAPX=+y#`uOKd+ZluU^3=ko{IomgoProeC4J-Mp#6{ zVZ}v=Tw^xj)U@TBE#NNWFr>S013_6iEUVUg#mzdXTqeX-AjXcaYDh7cnd&W7LrnEJ zixIZ0OfY!uS8~Th$;$CJ;jTnx+Kw^>h&Zg@D=t|cmP}lI*oGZl_nog5>v6C+F$ zBTPD3r`PB!xnp%n*%R(E;lwnl1yBwmv)l*4IAspYINhJ_jwJ~ZzdI4^(L&aF7K)2* zMPP&-FZ=&!d(W^Yv$YL$jGz=j6cwciii%Q|Dm{uwlio`}L}~;C5_&NxSP-z$rAa4{ zfCP|4ilTrN>4X-F3^nxLIV-5M_l)lIo%wP83f41FEGb^*W1+q%=KQ);Awf7xQ^TA&G5g=~~D? zr1ATopH#p}YCIGDPJo#M(x#^5RFi;puK(HDcjUKJ@N2_2 zFULk6>pj%tJJYfk#+-iAiVQymQ8!j@(A`BzE^OHs3o;VGhVhpZ*hxZ4nnU8OuRnv~#_NX4e@1L-%C(KmgyBl`^!utp*e~o<;+f zD48Pv3=<%?`b~^SEd@(6T_r%~6`*l+DO?<_z1h&Esp_~QP!b_q@__@Vh}BB+K{}7e zd9?_s1zwr&y`(ezHZ&j5Xt82q!BiK0SW%|L~oe*;uZPQ_VtTIBseCH^>cLs?6flFG=tp%hcq7_ksT z{tGmu_v+cLLPi}A@3{3)KczWwpfc187>rRO2DBf9%iqKb4;Wl@3fQVW5}+=sd-tOwl6hj6!DoIDMxl z@dD3->NQ9TD=)vw8?YkY>ZPd8F1-lUTIlV)kEJW?%gtR>+}5s6J_b-w=@N2I;|5+q zDn)m8G#OgF(9rN-p*+h&}{7uV-7JCpqv_PS0$F7)}<;Ano$hMT%M%$`j;n zOn56>a?&7PuI&39|GU#uSP+{pu*s-&+(wTS7fawk3ynXL?huH_b$I^6fv)iu!3Za~( z76l4uWJY)8ZhX;f+1hz|>`!@?m7;>wL6%7NvDneJj%l9ZVHI`Zv|%B|zS$XM%Si5r zM8CN>gu=F)PhEF1yw+UIz)io2 zXGce3@D}0cWoaCJN=0pr^KvfO);wx+!>B|laG{FjtrN&ghP*sg|mFe@TVFQky z7>i}{Do3?gz*BaLg8IXu5_p!gzn8BU;H+K@lnCs~*EfoMGe$#sRSOXx?+;yx})*!q>W+r@l`?~HZCPn=(5~=!pPT5&mTS!Z?@qS9Wc?wpQEtY|>cVkhCl zK&#n77#GRKef-K;2m5$tT$=oRUEH(P`2?Mwt<-oz;FU?TNSZY~a7rI@-cQU-YCdUT z#RqmKx9`l7yhiL@UCW2+Ts@n-_G{}O6N5NQWbQs){P^bpygcj$BMG~DlR!GF9>=Yp zbwtL!i;6ginm)8&^&sQyK1r zdz(gQ|6%Aw&y3KP1&e*foQ`+UP44C}-o8Sm*o*4kR_Tiix9qnf2MU~5FgzTss#3WM zvtI9PSnjUs8zjLKUitvQtr-$1b`^!`g57aH5l8MQYk3r+dUEW^Qj1)aN;*eD&vM9q zT7*~1@6$h@!R`qru;X_j6%!{Vd!hs(t>*BVJTCu38ZqRo`dbIyM`7Hy*@Yn#tAGL{ z-~f8teBlXppUAdwP3U*V?J#gvaYoM5yH9#X1uzSs>CnZt7koSe#$QaU7^(EO*rQ@e z!DG47N}0Be2^#%RmVfs{OtVh`3u>GGBy5*~{sfRGIT7m78rjf&*WY$HwB&ThFjSU> zUe6x!cw}d`AXW@M^3A+OY}bJO^W(Rxl6IeNs$GQDZf$%%lXJ#tJoCS3(XhVYs^70F z7OaYB^K^T6Rh<;tRx=5HeSW1#y<2kKb-Wi-M1&me<)}TJJx%6*MsJR{oSTR6g&1~+U=zyqyuvF2qw2!m_6LC-~4vK`hd4V`HdZu+#a0E z$VuGqBF=mFlmIl4m2yF_?V?)zE{zNmiCr>|D@@b38rJaB%8qvOyQJ0P2T5#<^k(Sj zTVk6ixbPB0&k_oYG?Z`s6CHg4t5Qk$!)cd>A9xRbat8tvc~fXwd|tXB*3|;9G11$y z7W9eZ+uw=!*uJd+KOkd#t*0sW@*e^6y=uxzk2}iU>=IpC4FOlsP ze6=}oQBfH=lXtB3>s!C(_CyfGlxpij#{KnNjkvgBC&bWMs-IP}vkvH^O~k$hQ{fpm zT4jFsraY84m2^a~?w&~)@FA&@{SeX{_#i6zV7A51wtJ-Vm98GAwcA1|2|+5*dQc5|Iyo% zzuQJ93RO^dqv_zTgj56HM~lc66x>Z&!h`+?K2!zLt=-bQfA@&(cdds33+HYYyzr{z zud)V2?=awm;?CPo??w#IM0aC9bV&Ga#@pn7}-Nwa@e`u{tp zb`wHc>GL8kZ|xxK8j8r#bUR+iz>XYqN3;{6vYY&1nnXF2lddzRMP!DO9seHWjUbRD zmEEZ?C?Z!mNLtU|-dZN#F7Nzp|!b;OkP?)hd4{R5YG|KOrvY*8K6q?0_-__q`;a_NyyhzQGt`=$QO(WEgOG zz!$`2i!{FbVWBI;APP$v(;YH(TP3>t;h84Jf|^%;D_%^q7_dH%(Xa#x7YNpLPm}7p zU9uC=tS+TQf4}_$#(cAcz~8QwYXAnMapo(B>`$UMkwzw65pP^>da|J$k#tfQUN?N< z(Le0mk3atouc?@3A6L9I$zc<%p0~raZhPxE3Pfda{q|jHJPpAf5!{p-f4(da#Hvt_ zXje4cY?ijQh+{1LS1ZO^O-7mc^|EvZ0+os)Ua)l)&@`tCF$2tTu7XKeV^Y^c|(Ji&|*QH1r zs*7qX8U346?rT$xPvH~@Psg&71vsorWT=1Z-k}u)peKFt(%xY|j!y27ry&{dQZoka1$U5EKVEG?D7X10165*3dQbvEs-T*VI5qG_G zF?YCmQE#tbddj~N5DU9_JQ-e>GM>J^el`AIeN_Z!UhR-R+>FqcZO~%*SMOTfotYw5 zId3PGjVaSN{8wM)cWikc>*OW+5M5+5e)(U0^^T*qw0eO|Y*BVvmsFpt*Y7K3?%neM z&aPD2W09TWjlhoko}PX97V#+EWv;; zV!F{ubrJn`;U(O^5&s;$u-Gw?x)l2yUXv{5e|4T&WC82J5yoV=x~9!HUmXR9p}2?ErVw(y0*5jz=xmxZ?epJ zK(gV6Pv?PPL!Ux;5}IHkEJ9)V;_bDE$9y`BS=Yw6xlRojqjI}bSl63echDDLrj)`d ze?CvMD2z$IZ%Kdf@RPaMK7C%SQohl{WinfBM!9DB00(_PYAR~~I9XG-k$TkMGVwC} zO>eB#{8k??sk08B;6*ukEoO!Qo$drFs6v!=!Fd!${o)gX#?1^@ePd3eX+uT*CXJ)jx2C#6`F-8#BNZUeNnMD!JA1zs!*I8&c<06xgNUD3S7l8Fv4R3Y$7$9Fc6R zN~O3cUejOKbmXX~-KV=#gqboFr~KNd^Y{KcaH+6@Y>2|s2f3Bbq!R6A6eLc4?WF=5 z4>B+01eLQ*$VRiKmz~th&9){O_BsZBT}?4veIUttAoEeug<~6=?y}m7zB}rzUI*SA zSdNy~*3urYzg)uZX3zp|Mg6##1fb)~DGAV>KOT0S%!EHVRAEb#ETZ=Zq2 zHc^5kB%dnYFe$C9$=BL+dSGTET|uwa)l2>;kS8Z`Ah!i+*1rNDE&~+q{d*Y*$!IB) zQZDun70?;bQg3zczE$E}K6bfK*YU5N_#Z<02g(T8QmcrRlRzVlIy7ajVI3NM~_ ze!>LBEe0#VeR16>Bj!t~BKiL>A)vZN$y@1%c~f>;9R-FqH`_2g={a4MtxGNFi8A-!X0`vu zZ$EO&e%rx*NZfuyFzdRtJs{^d(sdF$T4JVBpNxy|hr0Z7&a)vvKrC!txNr?{qk4OL zqp#~GUk!?$(5BF)ckfp$n56S9qK7d!1N8=NiJz-cr9-GQ@01!%7}m3>M61UGb#S>H~ zE}5*`hI|hDlSNJKWrDOO{(V8I_p4tcjYg0;_4cPb@dsoZsNquoYvI!%r6+jN(AXh2 ztC>DHB05=c;*EFFgx2vrRQzmfDDX!Pa5}i)exd$hiqXe;;W_3 zLa@&80sGH3;|21mh5=u>Ibr9HEr^ljB4{%Uog8HMf zihrP1X>Z#XJB)LiGK94!<4rcYvK1_;nDWkRi8eXv>6*kJ%`q!{BRX?3%a~MC^@bYn zQ6|K&k&_o@Kf0urCg-R+-PX^R)|&9r-`ITByWhRVG|H5n>hnJy4a_&_vB&#ID^}gR z*GSoZ@#F&_z~-l)%=luGJ{4J)n0?(_ljA!$=wv$2I>sog&$^k6la}bLDS4>IEcEzJ zUJle_^kmkDsg}ssAEm6mKF3HFO=<`j@x^bwL2O=WQF*9b&B=b?Rmm?8=duQm)V0Yz zaURk~DJ}VG)~pLQ9t$<}OT*$m7^KXgQ`R$|e?MV*2uRG0uB#LnDqE$q7$mr)v<+8$ zoT;NjWC*4a6_wikpql5a%K79B}gy7_P4&OxFshyIdhcnz;v(8ypP4Y-@A*AZEXHE%vo;wR+ z&&&y(-T~(y|IPMN#QFk-wS24FSaIksmg3V!gA-2OyH^0=dzB&{o2}k$O};+aQutZX zk}8Mx2m^vsP63}r5M5UrUzeco@hnS3c#RIMfLxl#dme^FGozV=m#G_?`5i3(iGzPS zP^c;p-S35ly@0AGfAvZ>q~UsY9EBD$ZM4hEjmuXf9%BhQly^=G5Y`FFJxjo~%0F@|uv^ZkmeGJR-hYW!=&> zb-$lQHhXPRACREiW?kiTXLHrpI zn$zudY|H~6%!}+>4Y)b|KHZnisH1tsKN}cnpX6WI&}z!C^jxY7Gg?UZK2b`->LG{w zyI@AnkzR)PZLT=zN~4%g+{09uPhg6$5?8;+Tg0cDkJ`ce@%=(CrGmGLv)%RWKi}6` zQf<~ZUo~M}HL;Y0kj89Y{oPameN_VbDi?brIPjhY)h6p$g6CBa0rU5rLal#hyDZ9* z`9W_-15Nw|EHu&`oty3uQ`F-$aagQXt+xM=9id2qmz|h~HsH6I4*lw#6E&LPaT4WZ z_Z8TW^xlS-snuoYUk}?hzQnvXTJ`fxg1dLc+74kF1bzK#zO)SVH5<~RoDkfSb}l;+oFzP`R<&NX%dt78xtAFtk7FDW^$FbS>Tft#$U#kD&W6~jTagR zS$8IrdxiG=0(=Ipf<>@s(7~>9wF3#&^`q|Oln3S8A`YGk14a#P2Xe!+3M?j$bD-;^ zC-9|*0U#B*mc(WQKieesIWhhM>}V06gs(Tyep8Qq;jrzk#2S^!E*;jpuiEhWdbw|K z_5@MqLQ$*di_6#-v|$Q{Cb5gd3_8TU@uoDt0k#-Q{a`zy=>!!M=sCvc?4>XP?w`-k z97P>0H1S)6)sq@p?Jp6LZi*CC`w%Ko-{Fu157UwJO%?S~oO^tMbu9KUJyBJ*O1VzF zGqEN%BF%+G*{`PytH$t87s51~1MG}#Mpzj4fCbowov*pN+}uq_)kt>|*WCykvavvD z37>AeaW&e%eu-oRLW&aOQ%wv7h2SB)x-7~(GRD5QD84&u$u#W>R?T^ve|SVOvB@DK zwJto;X6(KZ_8L8ZvpBNZ&?M`1 zw6p9r0Z}7?TbP-mCzNP_2IUl;8xJMwkv9TG$B8vxE(kO+M8uX~_nxXAXs!*wJQu(7 zvOcVTT`cvwSQ>Yn3Mo!)M0o_?{yNU{d$Yse^uiDrLAUpdx|&Z{D6^DNZ^^ZAD7cog3dsM6NoXk9AvQGo5>PjAKPjx*&adYp z3ges+i3*}!Y?Fw6Q#dRhlT_Jmp*_b_cMHuv&r%(B5_--6h|>)9B=T#4Uo;1Jtb9sM z8LyHoKz26(0>5O^FMcD5+>>Q}^DIq{o(5N2JZ8yduFIkwf%MNa)ji>2-#UIBs4?@o z-$$PR4eBqS8yJOptR#@aO43{_l}>uSx-Pe_%*%Xn`3SR7M!b|ofv6;7V;e(rp;l;x z6O4JILbI>5=n2Cm^(E?8M<@LtU zL(n8js-gotkn5)AfW}s`rO8d~i_b0Ns;x0=A24fXpNFe2nX*SZKVfM04Q;ta%G`^% z&j<>d+34I9S{~CN6)c^`5+2~oj7JZENcC^H3#A8ASn5khD^?HPO$KsC&l4mFzzLbU zubr2aCcj8{%T6Y5XCLd#hX<0Z^cwRwn(~k+_3pGSQN_4IKBf`;=}rOGk#ncpz~|u! z6N_uFeoYb+DGKTTWQ+@v#RC-5+wJS4Lr^X`2pXqgQ#@U_&L_tZ*<3qU%imejqets2 zmp#P2(8o|ONZJrBPa0BTa95*uQz&)2mEmMhd6UVurM@@m)xT^R6KIvI3k0TsNC}yp zRL7VgG@dsGj0M``V>1}K$2}Y2yb3(%=VAIb11X^nQvRAwOc$8S)Fd_|9_%MHf9%y7 z{dQvFI(XK~nYLl#ul1cW`~Xu8en}zItb!^+B37jC9Y}ONhseX-253gY3(q|-ZnwIXN!tHW$sR z68Ld>w=c@z$JZbu=le1W_0WafgYj9IMd&-9H>?x4#q`|Tl|4CihJ(|lTGW;Eq#aRh zQz{#6!(CZ$iF$@5r@PMfHD8uDRDbmiP_DE!8o&sec|p&$xT4Ui}WP z8yW%m;IzN}!m62O#2p;8`R*P*@U*&W*-rIqnQGB>Z+>P*{@OUykt0BMKd9K&(7dB` zTuq5w+X1>xhAc$Dm?lTg6ZI=4mD~63nbEeqBGfooD5q%PF)np%QtHIS;Sm!Hn%_vO z1qH%7NS!zU*#=DBQnidQ9k7Ar73_|*?3H)Itol-9i0-R*+YR9DI%@4SzPOs5*BDXa zvZOIb0YQ!U{3h|SR@6laW3?w6zqGd9qX!BNyGV-wEm5ZdBr!e&Bp7;&+P}l5G_zb( zWydbf^{~%^Yj4Bk2*W{7(`*~ANiikKjQOK=f~0r*33CUKv~Idyk|OSZ?Z8iEes(RX zPWbPFpZcic*c9Uf{Kyb2cYZQcL_g~$3zpU|E;~CmTlK?ew(81cXAa`M3;{93I$6ct zcDBAyc=*+?Jt>Jmch`LbPn?99ADM+GZEU=jG=I(5xL5+(_Y%hWI20@BA?18%uHG$` zxY8!;I=`H_xa3lIL%ku{k-m)XXrJr9@rrraY6Y8NQ{Uh!UO4@3K0_f#sCpd5DV%>tEixHz9*tGIqAPJKMC zVKi5+Y$4|?o%kKve%+KPib3-Y z96Jfg0;`I9Qea+o2_THd@NOETqej^HHG;dLeQbw)+_F(_?BU^-qM7=GJ|Pdwj=pu% zv)s^#5gtkTxD5M%b)zc>VA?P#XMVnRxM;AduiJA-W!NDlwe}J<0T^ytw;?&A=&xzN zX-cODONMo3_V7bR0!+@ zrcnPPaCdWouYhL+hn;$c2i7D@dL=*XHB`bta^e(|JSwO=`+^BN3-!#S)F7>6=L=|Z8{tmJCGe)&vyX77`6rwLxae6E{;q^yaY-64M&F?vaD_n;l=bB*o zzFv=uYtgTgVH*-n7@MU+f(mTPNk?ebi`X|p#&@?S8Jxz~$j(!r4m4XR@SLm{$gb0X zb?i2f{zVf|((bFEaF{sCTtCY+3yKLaEVcqAe&?FhG4dWtpo|#MD9!7)ApOuLHX2W| zy&>14SpWX}77Nd#KDc~sW=|8R&5v}?Md+f8r_sudY&91_f0yym`*+b>vinkyW-d-OQd&v)PfH6v5ViUL9!Xv+o z(XAk$N#G{%+WLAuFm)H%IrxwqZ55^sQbX+TnAQJsINKERtkF#PFu)WP3@pL?3A%gW zPiXJ72|6}uP|H6IDAn!iPMPXXaa`jZw1`WLSnPHh_EIfr<03x&_}D5^t<^FElhMHt zPZ>V(gf7P@|LXmjQbUV|=sg-wXhj{`ls)>8QQqLPm?xpH2mg9>2ThVimw$Aqw3?f51)VI52#G1_Fm|-$u@nPXK*K0cytfu@$HXYbNyX2QpuDU zokE)lGI@@FW)XA!M8mT9K=6$2z*tInM@qOn#(QbvYyn&EZW$U_-Foi|&(B(bp9=ec z5!8sF1mWK`5;aeMpxKv{u{P|S`QX@_eI@A{ULSkyC6tlbsw|pZZOGgE?2mxGzZ-S0 zD`KM@TzH4fc4*I*!oj4)oO&sDnnr=f)!ufOhdv9FB8_%L3=Bm;%rq_7Kd@boiq1spz0 zeCR0)<^OT@LE>;~8}KLfqn_rGfo5)%o)1cr!vU0rcVvVmjQTg7wd zjSAdz4Yn4-4KQX|p==TkD;QX|X)z{tx*#0yK9#LtQoNi-egA4j2!zPUntDMu{TgB` zGbOA=ptvvFeX85bMcIYCFgVo%?gyGNrE&h$Yp4#uFE48w8$fJwh7z0XHplz{8D@U8GHq6O1vBn0Q`yV3 zH`!_J*n?_^(UB2{(Xa8{WqyRW1qFrnt>p_iQ}g==9&Xr{a9iY)bKGWQi#OBU5f#ogv|BE!})5& zVD6{u8MK)us>;rrX}PUTle+V*9u~#GaK^?cSOHrH_TXfa*r}rIB;Wx;YS~z z_I5*ZRlpYC;L30?fFurdYY{BiV9 zbGZC+XCQ2OM0pY1@CjXF6IITx!`Zhk4&&@mDhWG(%C;#(a=y3PPVqm z2DjHwv=qVzYBo#?9TZDjr;17G9_Q3~&wI=ae2_|n^=OmMQ>-&Zv9~F8tt*?tQdBa) z*OR~4r?l?=cR{A}Gt<4%fo3Ap*B+FdvbYMXHt0@}^?@jH#EpvCSX)zne7Zy?!rQa; zQSmswNFn0KAo@bzwfPDWIJ1jB)?D^y+_<^(jAOtUbrn! zc6qO*MJ>)LaVj48fZOPQ%v{(gw{hl{UGHAht78`%)i^fVbgB34_-r8y;r((K&W-p@ z=PPkWbX|I#xl)vRpzW+gsqX+32CPB0PN74L?1WF%3F>O0xPY96;io4APwXN61pr=v zST2s;V;W#lYvAtQ%6#{?kJPz3NF|r{m!!w-rsZ(`gYN376gyPAec$OZLpAFJd>AfO9kuOw=Z|3ahC0vd-VHxRB$0;NVm_mi6w%(OT~#j1(oHx z4;iVYEi@-crkYP#hwB^O;MRK!8XYD(^J}}xWG}2}w#UT=Ko>fP!pWJ89I9tm*U4BU zu*fX$<-F^UFUib((mQL_`_m-c0|5;c@O|Lw1sGACmgBns--GfK-0F`0865X?L-3s% zaY8@gq6Fd~A$eMnBh6)R&T>=Xu&bNfUV>eNc6C=*7itLFP+(_>HHYPexX-;fi+a}b zJ|Po5*XOg}qrL;ndD*^S%@DCSkI(qcUKvpCyJkL8>Na2L z_I|hQ`;sS;Q_0QMoWu(muXP;QY*(gC@9J%j+rCad1SZeBvD*EWEX zOBD+^umf(zf`C11u0B_<{z*Uo*5`_a+X{PfyDq^4yJu$1KQ;ajm6zmV4_S#aK)@;rRel<)Lyar zjrvzYWqI0!O~nSE@v|(j)U#@l*F!Ht8~wenO-5Pt3e zplU*oO`JPbFIN3HHYKc~;CO?eF|$-G3Z$lfl*^0&HC9kOP*jsO7Bnt?hBNF{g>}Ra0@9LJ*N0Uly zqA(?b@5fG)yofMbwzq5hg}1&+Ym$k%eD7=JkyGyphFj{Q)cS)9<#HD=w}0 zm(@Fw$e8l7`kNl)j$Bq@&%C~XnNpf3EMUW6cz1!S0=wqZ@ht?84~_Dht5zJI11Nu+ z+jo9yAv6of6+bBS_z}45;vf)!m~nMan^oWMy_?u_6~^1p!%%`#>uVW_kSm&F-kXnk+BW`d^B#GdMw`Y289s73Un#ue%ia<1n`2t> z;9||;JIy9YH@c6;ATZ4rA+qPoEstk#NY{2!mAvfp?=ji$r&BxG>1PL+nOgbCl2pr> zoer7pPAlP^KWfd+=>@=B&WHhlFq%^^DdJy!s3{cAi3KC|x_NZ|GhihTP?PY+kQR_H z1p}N(R9tQ#x&{`#pXODev_$e1r+0SETEs8FeD%Lcb~<1=U6gCOG@2N&FHB;4C|n+Q z^8+M?bOm15Ny|DDbQ_|?TyadsLtI2;w$y9+&Z>yRN|$Y-XTJ%60IhisPtxJw?z8?& zOT@E%m6PWg58A0S5x%nfuy?D(adyW3LENmL^hZ`&vvYb)<_lNe+cTPo1=TB;nn)>9 zh$b}i9T~Q6hWn`pX*{7xNVEZUV^HYwfp$+u+opCyCH7o@^KySy*M7gb_lj3cM>sR0 zQ+gYwduQP@=hWN4oemX;KHDh4(FVEfCFQN5u{+meM|S`zad!5Q6p0IAA%dC1mYLXO zZUC%Hb(Pd)9caSbd8{-{W^*>s_G7s3s%5d7y@1o?`kr31d=5HLXH*G z#AHY}?#{ zX7TJpcgeybZTlElKW%hG_J~y9ESsxhV@=>3OHWH14`y>dAVY4FN$l`_;NBdY^6aI{ ziNwIWJx0M(%HoanVvSp3)nai;mS3IA?ZJIx!b7~?uz*SiRz!o?S;oP5kG|%q;y#nv z?$;%55zn7Le>&)@N#)De^ww)3FkkkP!z&FsX&qwLl{na2o8miT!qxfmlHNGo;?|gq z#FL&vbTFI!6N)Sr?3ZuhbK=oq$eO|626-A*5pP`m;{(Zcs+m5OOGI+3rrd?h1%OD9 z;4Vs~#pSUuj=emR(deAfDJhw2v40VtFF-$7+~S3#y@0vZtH7eBAM+p%POc6-{6v9vvLO)?>G`YX=v`Hs2O?^mPg=2?3g+e)T7MZ zjq|-E8i!?z)S?0t!L$h*Cjecz{2`AS5e+VD)to+e24tJf_H!Vf_4#f%#@ISayBw9Z z>6)zd0~jWA##m$V>~qIhB}Oy1rS@0}XY&t^4I4|*`BrLE!D|n%lEUQWW_!KdmL!+- zWar0H4h@6GN6C=hpU%3M!u5}IB|FokW&*n9iH5IauzHdyqfGYcfh)j1d{pVVYvt_t zelFE@e@XJOp_5~HPrsP>*L#J^&FHr`3yg#sIQzl8u8hcBlcUqw4f6Ay?;~^SHb3-G zg`q|pW39r7x%5;=P~71S#ANPpA_y^Tgq65?=2bN{4N2Zhdc_(X`WUc%4n%_>x}y*! zbnLSZsv3g(jKSxpPb;)L2Bk}Gjb}(=7V%^(@q}%Hu?=!a1O&^aE7Jt(M!4wF1fM}_ z4xh>V&l9mF2dR6VHDgmjU>KI>0|-qpbm}n2n4GM8&h?=9>A9~yGg;Pkkzw`WlK!jR zSMJkwi?4WDf26XQt`(qdVi)rpytn62@^m2)#P{HXlayxKKw z2uvxGH}nS$aBn}QB;>L^;>4bE3VZAqJR~m%nziCuPD7jk_GkDS))fJVkfemvL%fun zn!Pk4pv1}36a83=0nffB>yOpoY8Atg@(UoI3DEJU-d-E!+!FV3ACN4w@yPZPboBHj z$kGz*(0aMq>oGAX`L~8xZSK66?qm?n0%@|Xixi-z!bwWIzd9bq18JFT1D;_vlhALz zF%y97e|Cx*CQLxfudiCQV_?#6;s%w{I}zl|@8y_7O=S!>kha_3tw8*G<~>F3Ee zx%z77a1CF+XoC<*Y$-&D&dCCV*$6i$puA2FAM6jXI30eXn!}?n zOQiBD>II#gq{FK!xh1_1YO+4dZDV;e4fIhK?#4Ie>c#%t-avx8UnFJE;=-Y-v}c5y zwzdf~h(T%=D&K|+kVN&E(*=b7$LKLP?}rSWCzoWuJobN=+;G>UHPMcMkoK6+o9$;? z*jz?ex=S*T;VrL^?@qS@NbenJQ6w@HKskY8Uj>0VwI!t=1#^7(&}eu> zXv9~n*eFeHdM!YdZpOx!CzGs(%ko3_)oX~kJt!=>5#0iU+CZ$r;1e%Wt;j?59re4y z{=M&RRg0U_YSm9q8W-3cT`U{RuPr8dqx<|u<15I9W?pGd_%$0g?ldr1<{Go|ZAt^} zb|Nh^1SXZP#!|Z4qSlOOSs)J*HX7zOEpEiKx|#ZCdVaXKhkA#m`h8=7d9c!|eCoKz z_8Kd@dn_n9;5684^&@UXd4gE6O5wRU*p2Ta-fldu0;MarVo#ibPy=B1RbXHFe*C#> z9KJK9)b~b|mE3Svr?E&laRQX}wAN$Gco&LBj^AXiinT)RO(eI|PjZP9Y$_{F7XW3} zu6BnUuksR-oYB=a@yR-Y!MMO67ussW;y5<(tenvCe&kQ>lyd+?jcHNv@Tb`~LHP6p zNk&lw3^Df^MJi3MlW|^2+eEs|f8inL=h-?-4Jyacq{c$Qq%FZ}cJ75TI3|FEc!_yG z!K?HR2nI)(%-bZ#g@jvuraEi9>oS%gMN%X!waMACIM%FSRTUz7rlIT`gFhCw?{AkgiA`=r%T1!-0mje^9$^^TE zBc!ZJtxwNN1l;gS^A*RA4oC5=ceRD*7#bC=!aw*JJM(qAQ>T4-EupnqlA3r_K(~8^ z4rh@3$vve|+eo7A`q;wjW^C5>SReb7{}38?kjOvaJt!nK>nVy8a{>uecZW2Db5S zp;2sX0!{C~*(y|CLq#5;v*4qQnGx}DI;>=~)p3rAgput|*zqzQAU7$^7S<$E*Ts6f zf9&{px9DP$zyaHko%#paW;74zZ-;I3pF&Ls%I~yg`K=%6T@Nkp(*blQN6gbpDN1#| z(RHEK0y8yVw1+Qmc~mjpT+OeumQ{*^62o|{e~Ozv5Gq~d$O#FEAaF~_xj*0G;GmT~ z{y0A9o&wk&#t*9VZb?4VlA~ipivWfJF+h9kmT&4D<&E~U{c3TpzI0>)T?pFD1LKgB zZ5Q%Ha-B$c7cx}E64Ql*Z$I+4=`V{+&}1wAdM5dl+vYsqP&G?$Nlr>sL)er;rTf)# zK&{>waKwzaW{{uM2?^QR_9X^H!bMFBmAblfn`{>fX$|Nr+qIb34p`im58pJN9sL|& zQybKM>aqY)R9g}Sc}#~0Sl#xCfnGwW$H`H+sVHu4hJ%O(pT}OBD$7fKgqd3QQs;yd zWmeUUF)5qUoNiA+2)3=Muo;JjrLVN!L>8!b1;Gc6_S!gZdBos2Bnpa552! z55LC=wrT4!`fJ!@DACx$M5)4&Vv8Ccf$YcY*X)Jzi%pPsJu~kVSS(y0yFIfM5Hi6j zXB?5#XzT4+Je5G)De&MN(AKAAtL_(7h3vWd@?7cp%uFh?Lrfon8S?V^3@QQ#@OZjM z)-Za-$s-;}0j@wo;!V?|*Yb09av#w>I_|AWbN1OY-^P-c2VT~ein#Ge#O(Mb$h^F* zu@xWpt}f0EBWdGRaW?8mcMN=cuJ=K#jgph7nT?_Aj+$U|dMI1&c;wNO(JMX)F2O~P zJvI@gwv$FMuc>x}*>zGlpQvvImwcBMTCTNkQ>){>vs{1Fj>#&#-=}PLxn^`yGc=eG zE-7{BkzSJN;_*MVb}pynNQRvhtEJOy(CwsG3ovscvr{HrBJMC21n7uoKxyl8#HobS#i=HlXG_aPRRmk;``_p+SO8@11amT9r z(4b>rA2tRz*H|TQJ?NjPPW0C?GkeYFj*`}{lWyV=zx_xK+#ZzjwKaF=B(?h;k5OT1 zL^$5;$Y0DT$j^dX6d(zdGOgYhp8ilUqSxZ|zDH0>*GFZoab|uk>)7^eQ?Awu4j@mMOt+|zbKrA39IxxewyNx!y!Cq-JfhC`oFr{IH4 zOUladkKHYOA_U95*axA6w(ONdAp%2Ky{d|~!wqqa8&NOhw!U~fYwiek%QP4BNt_$a z>*feJgV)qe+T>`%TJ%e~mIIoELR^UYEKgpI zFBi57#v{oi-GKgtrKDN@$T&O##iyk6W{C8s_lVTI@Fap|j+^p;7Efm0C$yr9z;Rdrjme!Q_D5yvL%C0Va8we6WlMD5)jIST*Lm+5v0d9`8hWH zy=_?(w+AD)lgk`)_WHuPIjyE+njGdgAW z=U|DYZW)Y4&PSG!DOaf8P^z6uBW6HH9q;N+ykk#cYaRCe8}Q=m(q`{H^PS#JOYMk| zgx<|wmEHctj9~z-M$CluM`s1)@F7PHj0(I91?zX5n(^(P%`d0cs{drr!cx1zGyh;&Zd0xjKp$`-Xh>+{#S`lZe@5N%D zE$x21Dip;)CZe4a<+h*iymyE|7t}N~=qL7-7J4n%pcCc%HXLf(K!KMRd3JE!?gIqv zSRlPJ6jXMv#jLBg^_aCin$aO->3PJ?#D+J#f~XiS=x&{N$N|?^uwV`0cH@u%6MRdN zN{?kT-mhj&ga=f63uRn+>%aBQKcK`48=F0$Ml`W-_TSX(cGF(1T%~boV%XI}q^(NX z>Nk3Z(!qTJL;b!h@!5cV&jC5OjT;h-91}Zbv7Grpxm3Ot)n!+aXVwyWefzR`=>H6Zhd)UCYP83JC_N=@;f%|anys~1h@4YFbN|wDLAOac!<7(ccuK+a0kDi@hja?)=+DZ3fEGaM$3Xl;;SAx}1f1f3VB?@hmQkh+Uq8GJZ>Kp7Ol z!*QZNyE3&w2A?e`vn6m z-PYo_WaW2NYSJ{<;wV0n&!1FCbZ9nIOz>X$SqosXCVgDqGI0Ii@qwN7@r;BP+&!f~ zdOe3i@k7`Eq$BV=nC6zBb4;#*;#a35f>OHIzu#tIajNS3?0azDmoa`m!^3OtMRHs9 zB2p{w7e0zVeq%WmGHRAlN)|Vs8a4NcY^gFopJACB|DlWY*dZfVt4_3JO|gB|Gp#&k z@*EOZ?jt??`P2Dvbi1l@&v<}y|B0!>!Oxb-?#2#&1nH=u;wf#i$o8}|kK@Q)4rNDc zKS%e`SQvhUcik68+^11Va}7-M$N1307T4aTXLLAr8z~84K_1$Xgm3RJk+fO6zqX(z z6DeuNeWr;a>de$%d6dH_K@Tv!*OO9#8Vl4|VC`F@v3D4-TKt1>4EC z%hD=w33z;yUVVW>g9w~nuwbZt(icf~=%20$E6@pl^R-TQW7%WvVcvKQ{FPV2jGfcM zrr82JDG-gbiX*YgPo36^0j{3}BVBmOL+-LokaXY~+#X7QA$6unc0yR|dj$tblIIBk zem?F=ARtXH0Pm`-(t7ZFs;HU!Zfl<9`eLhQE^WWmtq0fp+~We~eO|rf?3|{jx%2-p z_T5oUF5TBx6hRSC5m2fP6%dfFbV21xla7=CiqsI07CIOeP!zCG1f=(pASD3;p@@Rg zTM}9Tm6}jg2)%q06}|6!zu#K#{lf(=?>zI&GjryYz4wXQQ(-DM!w!V?(w3T@{1AZzl)wzZqK+`?ZTQab&ZB?B6>eQ7UGIvbgSkb?7q3IeT5J16d35z@Rt}dFSv?8=k>rn0mI{x;Q zd7nZ6E-8t8@%c9tEPOwYadM-=M(S|#Rsz+yML9WVjG^e;d<7{_?bcQ3LRhV!%cNyN z8*F)rI0tQKgs#&^urqrSab968e8j$(nr5fPS9+yJ&^d{M4>f#X16m32=M1fMNE$9| z&KJ7-ufw|=^N5u)1Y;b(-rGi!@w&Wvat80I4#DE0*hy`}81!IxOhJiDm07Z6y;YbB z5uKI(>Br^Xnr?sR&eZ1eaL@8cV2)yZe7;p}4RvEBh_hn3N$RTowN&nSbT;RXcf*;_8l{Fb)DvHPtYT-?y z-?H@U?@>`k+uxQ8I~MWE6aX zfv~0s*F;nTe}HSmsfE{UWscv`TjFT>py=D~0Zp)N8P{kQbm9DfkK<8KhD}nTCLasMGIVe$iz>OO&EXBKa|Ao?e zzfiJx>JyCC(L3coj-iXGydJOYOsXoHUp9aB-q}s*!Y|R<7r3~;Y+H^Nw@xH-TVnOr zvE?3}PfF7fo3rx+W)v%2*1Nr2N*C49_Cby~@6p~^jYO}4S_?`tt6-33DAj9#a>{e` zj`#iJ_L3P=bnI5g^$~L*A&f6jXI1WNH7)fd=jCAOR+?MHphFo^YlD_0&hal^zJyE{ zoRl6wYjV!^e_2=Kqa%fvxj$tGACngGRD&Co^4{o{)<0hR%5#?}|lzpd4u%v<&;Bn?HyfBt;dkUFVt zygtr8l~A)g%0R|yQtEF^q?NJ7)5Dyb`46e`n|s%9Kr^U4uJE>ZQWo?5s}gC?LF+0{ ziq4iUH96isM!q+_1}t#1GHPOXiawg1yRfM35NRUUMHGOEA>g%9#~j1p>RWfmhS%qM zMhl8q0_gb<-b~ovMdj-%Pwfnz^soSM$7}p_F@ykW7u?Qu-Py9Xm8eHUqxMb_JccnJX^% zUN?icw^wTn?%SUC`Qf+kSh5|-5F$Xobucx*7c_PY*Q>t0AGbHCqkWQ|IvXv5)UxI- z4u9V7?_y~qKq;sr)-5N+dYIK@Zh5qIO*X$QH4!A{kB>>O1np(zn+a~D(x6}q?aCwQ z!R^mXV!ioB1%*o;AOR}2L9s$ny^QCF2gq8$+M zf=Q(3G`RltMqBw58n5g&5>sRKiV!+a49%Ub{j) zTMb1g^}LA<+T2hwSrd=g3tA4$Uh#tcwTt;|=4_|<@>a@WPNZOQ)q^H!LTs3r31MHG z1%D(-rF>$8zt`uT@Yc6Idp8kHGF6-B$8=S+7;hT6fr9Y67Kg^XH2h1R%Q^4s1=XSUDmCTFkX3yhdR z|6B&<{c@e8oCafS^MgYP2ba}t_bPJ83hh;LU0S{rY;1hi`~Lf}^4NkdNa=>bifxR4 zu;(4w3eSepG8t&ic9K&-g{qMW%vj4MnFZ~Xio->jG-l-;;tqwxk*$h)iXQ~rimKFF zaZ&a0zz5INYWN1FQGF*aoppHWEBdBQ__|wu+R8>$xAG0cfWI#n?z`K@U;<*DR?p?- zjQ&H@c;OcamoA&&reXggRLumJiG$Xo{_W3CjNV|*v`VMBNLii=WhLIHXWB5>cKDvTWJXhd z|KUB&PXHIH18CTMO;@R)BP}W(lY3TU^71>D!eO*wZ&Op4;$`2;sqZe0&*L3xH#m!! zJDf!+78@qytjjvOu7}EXR--sw<5X?-AMlh_P`-k|}tA_X^ZmKLj zb^bzyl)N>~MVcg@IK2D75X79&KJFweoA0}Qc2jNO`^E*qO6+HrJHpem;~K9^-}#A^ z2bGjCEbGr8)WQdYKlmxP1NhNF=II=JVmt>})nmCF`iyYI8{my@jjA1J%BzwMDyjGdK;ce7lwS zWRMx{*d;M0di%@gBi!C&tlHn*J-jNO_T0FA+lHOj+YLs*P|AI~|< z4eacaG6gf}%Ido@j#s%j(*m98i;Js%sJK+m_-eZ`VVhvw3!RuTCBp|C+1*$A;zmkD z%&~@`m-^e7U7k~&muX$vgkhYpXcgI$t)4WT>`J7CT^LH<8`P@gQDx!xOz7VpnwrzN zK@^X7TXUVGcgnj{q=WxffuY(6z?OOv^V-N=J98zPIjuYrwGn_2S+hjjVm1V*EaW z!SXz{KyZX-WXvp2#3Ms0W~z+-2zDch#zA=nA=I0wimm;G;h+{9=Ims{fz5F z66EFhz5v}YFZ~(k*?hKwF|PK=q4SKM!Nj1zG{~Ap75YjQ+HiXOQq~)4;7m+M{+ev9 z`7CUkLOapNu*?1X`3YJXFetXU>%wf*$d^?jH3&D`*bfk*K zz;Nx6qKd`MaFWga{ud4XFX+q{aIe%tw!3QoN^|hBfrrNbm6IuaM&_E^Hz1XAb=bqr zBt=-3A>tZf_PBh@l2x9Zn8b|=L38ZS$wu~zd(Q7(rX;fVipiP~V7;G;YwKz`RORjw zh;Y7qA+cuu1M%3z`YtPmy%opSA>8Sgu#y)H&q2L!c9HHNY@h6HP#?6N7s87*YvlwPZ|QpNxiRNe~4_RE&HfZ)Ld`_;O8(Ym^ zZVf1?QshiYZ+p2lW=4eR&zo2TIaE>+yEJO^tDu4OO58qQdMRb)u6H{g%2Zi?f!hgz z;Pd?~OP^w*+v#W#p3b>)INopC-LK4P6otF39@zNzw|(l#Bp_Cm6=QeacAt-8r(&u7 z4M1pkpYV1{+y=DRA#x@}f`*jSsZ)^w3%D2XhoSD??0c};5h+1yd3`#h`G-Tj8bTR8yu`(byowlk+?9^Ug4|}bPo5S4z-A}g9chiFKqLMNTdj_WNtxgfHg`KQ?Ao=>`{$iw=>v_Dm zjb*u6KM|KCQ|)Q%0_n!Wxp%+^0O`op^|7^vV0OFbxe*KVu^AHSOyFS1-AhUFs z;^A@HZ76c%9ymPow~*WZyXI#f=wxFYUBkvf{Evh{a@rJoYRIgK9|> z$N9TnF5`HgFO3l(Yic$jdB3!zq%2_7J#d-i9TI9eF0jnwl*kzpUW&`gaMpfug}>T+g?QB2hSl;;%7HN&&Gt=J~lxXAGtI*{Kr23bsl@ zpF;vykqP@eCj-ACpu3Oyj|8I7ynS~MbaX~Ml1u^~tNpsg`ShUdo~T%-7*qbeY&}9bT$*#sKKli zGQ-%H%7!@m3Da47*@6Nzf5asxs|X|QHbaQ^f>mIOiHW39OEA*%Ha8Q;`OZh58aC%6 zxRrr3yOy|uOR z$xjbZ)+YiDA^|#2m2G9dYM$IK9}ui-ql)dQT~VcyiL6MyF!YH3ydp_Y^{Z2YV-E)D zw=^TT;Ge0TC?i*6qaKEgvmDxJ7f(a2;%tNL**92(kfHljm~>bi`txJR_ySH$@x$(C zt6w-5ct+1?C*M3w6QGk>*!@@GL(oyZ|$Nc9S%ARaJb+60JJOSh5mPbnFF=s z9Dy5M>I7YbDmebBi50VLU+>kOtff$yN^50chv@1jHg-R=12oaNyH=z9f(E@9i1{FI zl7}%rWxLfqgw_~lBfIR;y*PT+eV#qt1Yt$jSBKf>#|1-S&PIo~(qsiKwa zTSw1HOBLLs03$MY2q4AmHCsUF3NqJQ`3I*sFyWdbMKX~2waZ81}<&J_ExsmIC|`3 z(J7|9?L6xw$!`~D-bI1|ba<~i6K5>f1o*FcW@YWpCsk!_N2pCC!)(Ck$6M|m6Yb0t z9b9vnOe_7a9J=xdp1jqCfSjX-1;*M;N^9pnS9vluZhSnO;sCNk&3mdX=9tO=F1|eS zXd07fwQg~7aTeSGuA7+DOHZ8KUQZ#b`96L?L6N^P$m^gDUKeV!2&>_0Ec>(tX3 ztIlR*AS{pX zj{(P=>GA0vO=oyl`c>>)0(4_O5R}qRD4R<@vd!907o%VI+QRczZIDFpom--%YQr=4 zi}bTL_zqb|%F0x2wedeGJT=5j2_(L`rABeE^N6O#^N+si>wTw<^0H_9i5_Dmk{AsmY+zOG+GJ@^qsYJr z5>54De{c4wP%M*5Urvue`XaNty${9gy`zdS-<=FwUwL_he4k15Zd;E+!JF;(oa<4H zGQ3{11Z|tS$|gU;t<$Lckg{yC1>brPSX*CfSfz|h-{`gikB!q%=HqLTJf>ui2ePgM znT|c#(<4Q-mbq01I+w0)`%McNiH%ougz*LFO4_%Vk!hS+rrq~P?>+^6j~~Gi{*6z& zUds-Dm3%!?l#(1k7VLQAOu`xgG!$XJ2%>O~fS;=A0M&8rUOb*+X_7V0uI@{Z-o$FnqQRHsea@2&{C$3T8axIsvQ;aBn< z+tr234c*R0Kf!Lf%DL!s&={0C1s=n+qRxP#q=GM(zBdA9u{w&5PBhp-&DyMO3G8U zA3;@}N|`Fn%UuT09y##2fvhBXxI@lrz@!eWzuGiW#+9&Lvyy)EQD#beVZ`5(v=x$%($PAV9xB*KRpUyUzzMJATER z@Z;(aYE;YFgz^PVod^a<*`P{3zp>{B%@q9bfMH|MGt(!1+2Q4eiqu_Bn4R6kb6)hV z;j8|Odi;W2HEIk{qO%ShL+gefa*P3lhqH2Cg?AOiWQl&HVvij5F+K&KPWXbGn;Vye zXYRG9Jf;&}sNmqQmvOPR^0H^nTwCBguUl%@=De(S85G9OzVX8gL4x{iw;;LM#(@4< zXdh`6^qyTpxwI?bs%C1H6JALB^@Yn;0b9Ol<2AQF93&|^8A^@Nwf%rwq ztj`mT9xzl56zy|rbL&8K^m?HiB)E!9OS1u(B?t5-5WWKIe3QoBdFJ%#a~(Wwub-zq z2xBqr=q3TKEzrPiQ0nE9cA9#zwJEX;m;y2VHNJDjzFThfUhiW}$n(3>0{R%#A2432 ztdq40Mkcycch#=f-pjDuTqB560o+sXWwtg_`O0HV0f3l*>|A%OhxiyL5wvKxzF8({fmz( zTVoVaQ>?}TU-da$cyT$5A3hY?vwwmgxt`>myxpf|5ZpV}g$3}h*D~W38$*{o7H3L3 z)}plFLn?yottxQW4>U5)BSwPOwTV{#NcQh;SIh5R zVy~ZRj(8V*D#JXXe3vKx(oBjee2FBQIc2=< z&L3S0&FWCINnwuTse1dlW)`durgCcH>rW9GUke=o^` zNqOt0_lTEC+9d0ZfEjT}z()a{gtYT?jC%y%c+XqnHo7$vwwi_C!zp|FPveDNsmud9 zOi!-wxg9LP2Y`?M*2HgBf35xQ@8wvg)tzOt|6v)UXxbEaPMn68BgLu}50A>|;xkyj zR_66cIevbZ5zBP`0%fFVeK%=!VUmK`_~I#_5>R4SyM@ibs0vnlPU|ysOJw$yo}@WA zQeV3@)f}? zd-s+gPQdCX&s0m>4pq?D{Y_`II!&wq$Jf_Gq4W}8B5;6D3R_1$4W6&v#sjmHS5&i6 z(#dan1%7&wV;_R;hJv1=-%>AtD-|rw4yvbXuF-7Wk7|@qCOFd}7BYMPG=Mw^x*)k+ za7x2p*L6$e>WF&V$~T*6)q}UQ<`{Xvq(c&OGjD@2Lfh0mv}%0Kv5d! zKK>FZuM-Dx3(=9AKJ7*B&1;A#*> z>yNSaMhd=s_39>{S}(Z5?j#Rhnt#9w0M;o-xEqX2AX)2tKB*Rs*KzlZ4j@WkOx8HwnX7jS4I}Ez4q#$d8~8xY>eu@rGJpx=BRx92W6uAgivgmc#LW;X zb%AAlh?gD=x(rjtAAsh7oE!)Vy8)SSn!o3BmZp&~ojM=G$ybol^6k|QvuX#uJQ-## zsW*{|GTWU={wr_bub#mtb>dH5Z=ukt_<&60!V9yg4GIK@*UyV$*2J9%7@Zvye36xC zL(9jH#ZOy7#(1cGB*NmLr}+r$ilt+kER!tvWS(zgot z-PZoAM)7!|2&27sVn)Wo1D6Ho5nZuTdB35D`+yFHQLeV$k4{QEI|bk8eGr%tYfTNU26|4f+LI-$WXZt=q%o+yVjlzszP7zCIMT$&c%ghwB0=eRH zLnxu$bYa6(IJGU91u1C1ELUnG20V&>p&%m38~UL$4PL+@92Xz&J9eyQ^%jzSfMe!0 z3EeUPG5`8{BvsyBw-}I}C2* zcgjO&a!Jw!CeZQb7_%xM;8A3W1YDbQXU;UraSS{}6Bg{-LoeP&?3ov$vwV; zz?0}4sVj40ZaV*zM`1}E3cQnJ?KaAzU1?AmS#M&6^q;Tl(Cj%MS3EX8Zra4npcDot zk9{-)NM-3{AU$DP?@+(~JRsRsRrNj)<~UiJvD7!whV0hS@|iop})*oe9WzrYB&4#(;#BPF!^G zkSgm3R1kvu?~Xz{U;7>aDnn@J^UB}W(=P-Lkp<^X? zcX!cEZ&GV{5i4z>E-I^dH0PycLGD7b5TRgI?(6rp`JTJ<*y-tMLaArl^Tr7Yb+L}u z(tu|fT%8k4D~ko(a^5Pn-yJ0DGf{Dhv}BuM4@T?+c+TaKE}SX-sc@f@_T9w9L~bqF z%f#!~uj>^MkofegOe3NL;NYYN1;)>NU!1E*9nAV2OYN9z#tNELW27*WR)c>J%mk@Q z5d86Tme#VJZAeqnemB;|DQnz>l(wE~OiN7iY|^Q?CTJz>vylc-bM2#03NRmJqlozI z?6w3UU;&I*9S(Rhw`Ml+^)PiPTeaqb(kb~xLcRf@*qrsAD_nWF2Wg4c00fuPWW~hi z&(mP$xVA*&p z+t!vTas#CZ&hs~|d26fBo@&q=bYa)g(lP{>Y9XX-BG<;F)eS@;(fZ{mfQ^F97LNbM zue`;5ep~a@a9Vd^f+^ zd6gJNor(+8g2Siw-cPWJ0fZmqe9fk@uyHi*+U!7ic`|yi&{Puas*VipJcA~1P^+&p znNzNu_)pVD^TSflgO{D7HM%=alSG@lyp!g-I;w8#^c+qRp6xCisUd8|Qtxvm5a~#% zXFjC@TrO*iW2$+y&-^g18K94Ge)S}8me{B1|MiOCR~4E>u?tYG{I3T@$EjG~TaST5 zvm_cMqQm*7w(<|)vW>7e@-PZOvsnu`MVL2&5C64lj1@H9xx?q%Xq){i&10@Q`)jkG z6gYTvGzbMT%fg{NA%}L8X5~_Yp%IpNF|$mOSk2^Xecw-XQpFEV4PYVX{yj1utt;@< z+Y9GG-5`Lr7Dzz=aRpsr?wQlk@0#Nr$h(0ysCBG0hp;=9r-O1#Oh$Q`u_Rh!Av&99 zoFjn&F?U6MnF)b9CA$Bgn4%xAaF3>itcW>IYhNJrLv;D4Ojt`3NVjB(0gBbfj zm1L$=DiYwmk#W084b44tNTSwedZk$bu31#7{K|VufHYABO-Si&Csg;RQEX0jqP?ng z|J}z@fz~~=E9BNq;IppM%z?Q9*wD_7#}L-^TK6bSuHI9Uv%MU=2QYbW2n)AUtF#6I zV9g$i#>AEwtX`*fYLj!x;of7HQz>77%%JBWt*^w+N%{4Y!Wr<4V)|Pb!83g6x2PLT zG2ZTculk?eQd7LJKlGl;;{Nj{*qTmJ;cDs2b2_}=PhUHSnA4aoxlepQkPnkfbqY6N z6PVVL#`EKinPaAW+GnZx#)3FqoLzoeOYb$4+z0@8EgfFhh?|z;{Zg?>cH8b`yP=#V zWR%~BqEJV2I<%9rud{&y{?dK@f9oy^f!>`iAy%qqejCXv#-rS}ANEwV#H860pxEyx z4~#kA2`1!)?R}Vs#rN~bZsoGKYjVcoW+-92Db=~Hs@SsIZdTY3lcDcfIdGGomzqH3 z1H`F=w4;Om{~Vo|ziFf~kuwIrrAcS@7nZ#>AL;rCVmM;~CRfdpyIfO|z4i%(^Xx@8 z12ebCd5r>xgLA3m9Pj813sRv@LbfDKBxD~#x!aG@U+sZ5_K$(w#&LSaqI%rIJv>uO z-#u?pYB${ug5*J}2F%#@|I0`Ei_Vfp;~EIRz_+tqkGIm*I=BWo_>aYxuX|l=#Th=G zc)b^E=Z)&m@<$IqvF)NBFB%q$Eju;PCcK-41w0RCOd^N7&4h=Nim1jHd3^9DUXa_0 z_T>@nJ;j)Tv;Uj@_~}5_J+3=3?u1?%51ygcCfK}O7HYa~5Q8o3Q7Ol4XPenisGkP{_d$)tztr+bWLg z0qYtidf<;_X!!oI>t@LNZ{R7$^Z{E{OS|pV>KuVw{6~qo`RS8MMH9A5UlHA&HN%+Z zK4uHp0aIvnTKw8oV8#k!=5oQaQh=6xl6-{3zn^6Uo>hc8@a5O-iO6NYS+E&$fAIc6 z?}(+V$mPJH1vq}ZYn7?Ue9b|f4IRE|We)jUk zUO2Gh9tf4!`SG4}S17q8>RV*&n8IT2uUa{DkWr=+XW5jO

XcbssGVvXxBP&7|;q2H@_)i0mxpQ~Rf0^ll|Z4acSRTC&b z)!ZR@rhI#?u=31H-xIfXWvC3a7wuP8W+3@vO6y?>4J&px6fd~ABd ziG0OX86Q67OGLG!>Sf%WH&k5YW7ZnyY+c(mB|ki?2Ep zpTvn|rg39iQ%QZTw_cRrP6%{&KZ3IJI!iq@t!VF$9V98gV`~u0dfL_oI^vV4b^;@D zQ3l*b_YYnwi;>kpT||{V+Ar5|@BEOj*4M4zuwNvpTV7+&gO?TI2kY+?$NR9$dK%~z zC(lQO_w_;~oqwllyMNYfou#MjP4V(mZfcAK#Kn+Pl%pmt#WIB3;h?g|^raa0jtqrW zeW~Lq^vedLQglTIrG=}|$vs~&-8I2lu>3 z?%pzEn^5wP&Q*NY12LI(3>_`|d+TD z>upT@w7~Lbxtts1b=;NjeX#H83?W7RK1jqKv6mI-?A<4rrVB&gk61w=ott+?YI&Yg zW14SyduD=g%hlMp1^#u3I(71%cGnWK7eA_+OFep2i4S_IC}`1@Ev(@*z@y=vE%1e_0(JAj&%Rk9E5FUss~J(jziYpUHivZ#mEt*3AM zMF(kPNFLCgcczA60tqDD)WXJu^!JsK6*_92hTS!0nFjD7_X>B8Q*Z@Fx8sbJf z33IZ!Fhu>h*gYrYpj5ELEX&*a2aZ~{fZefeiF+(9+BPEhLVERZDt4+*hcOn5XKh5( zZ3zc=Gu-uRDvXh_GCrJCkuPi{zHjD(tI#gIonO1~;hSLTo7I6mv4IVhf=zauJ^ zgv7)4#wWYbJ&*2csI9PU@>MQQ{IpzZed(-N>gbt~`G)CVOecr+w7rh;$uC&U?JbVj zzuUFfBgozlFz`IbjNI^g(NHx&wy+0EV{H|M zDmdVJCj=F_{!PI1%(RMRU-H?^246hIuP8C`xkg_xB4!@dXtmO=5qrlJ0U-)1VUZwG zQICc-`blIw!?)kL(o|A*?R8UV>5W#;#OK{PN*StIyFFlauo}GvHQ5t&!Dg?xih0SRdFBYSh(W0X@mIe5k93s6w33 zyglIju7>G-^MWmc>%#?GD(ejn9qX(5ZIo;co53nF*ss=8*7u?*w6OTM3)|jTW!86e z&J&!7#7hhXXb-CtM);&rxK=7;11p0{0j$a>S ztlXOv%xQ8HQD*30YdzS9@g=B@tx@hy3GR}Pu(-Yh?d>1cRgsKL)?)P zFm{|dY@T_1E*nX@Bs8CWbnNe3@TXn2=Ky+&7eNBDMY&&?&zwAkq?cfyW@lIu$i$D>ArVS2S1^2lNu z1u7T?$Kh$QqUTLpKs$>c(8~*b(})KfAIK%rt`#5>xJsj3N2+zn;-m*e;mEQjmN|Et zI{y?lH}1ErxFjCh5SBK6>0f5foGHVqwfG<(9;=RTCrB@%}>0QaP zNf$}oKxkq`PHINL&Poz?{#2(ck7|QQ%U`5(~8h|re#IZ3#XCTIbjpjY&M^# z5z(42N5X7LVO04D=31^#dv-Fv{tX;Z;aK;~2my||0BotiM%fHa_I#>qH)CD8( zIKw^8x5!wF4-ICky>q0YayAtz-K7ip6~~?S0E!+`Vf4QipbqAI%$4jDlc6gh%*Nn6 zKOuuGk62hCmUUy2VK$E3bB;2sxtJqVfwkBT6UG<1Z|>`JOwKB^#s?#;-yy1NZP= zdJ18IA4DtONN+}Krc(~_Yt@kf#d6PHs)BXgQ=xL>v(va@GZKvKgqUY&+F`2rGt|nD zYu9EY5!eEa(n(~YYVuN8bA3aYC%--jN8n5DtMf5vq>ve~=`#+y1ndXFDC}sJ!2+M5 zlY~5ndj=xC8knuneK`mGXJ`gWm*UsW!Tt`YSmfU_50S)%Ol9%dtzi;KFcxPy=P?ZVtf_O{hrOeH@{*tj*K4WMKp?ty#z}*4F?mer;@q$Gy;ro)1Z? zH=jzCLYo`19aon=`@~0`T_BTR=p#Fc$G%Q2W;H&^rj4sO(mG838L;B`xtb{6Fd^cw zf#TP#uzcsxp$DhXkcQVl`)VO&)k;1Ul`T-NNfM8gK4(IqVdRF*Xg%I%e$%Y*<$;&h5&!l&+ zD|+y7p)jScgTc?+7Cj6NM}xi+E2H_g$CDI*3o34UVI{o0yr(I6eMaf-p^WHPs&~NT zK_AJTKD%Sf(}S_)^1^Dl^QDwk=hadJ(x>rZ_^gL!;GKT?3i0Caue&}y_#|~Q>qPeT zSF)uq5684Gt8+LN9bVt4@#^(IbdBw zc;7x7V2w?fSOu|3Uf8B_10QQQ;Un@Hd7rmsP767ObEJB<+K6-9+c_1q1b^$IXxG3U zqE%r+YC-BG4!or&)pt)IwYLs6wbbT+*Yf&KDWkR{Q^@UbU0R3*6e)Lk=5y$Dl`3_y zgyimz<<}(KQZ|&_XqYM-?QfWdQ(dI7J|pPa?lomks-pbG#aSPIjVCSPHn3D53h==) zdnlhc-dIgUG1T4Ixg9O|qZLACHk<-NMsQ=qq$O0HH18+Ab%{CaRVgoW<-(pMu&!3r zo=CespQ;A$Ec&#*&R@!K(p%5H8?SnkTYgkuVOgG1`&#S3wl|7J(-pWu+#ZpAC<{dk zD1GCaAe>Yto4|X%>}KvA>p-7~L}GbzMMPr_?w~kX@s4tES5{)vOL0q|fQZ+LT6ME) zeFA!ZnWhFEx!D{#ZRxeXnuOjTgFe`_`vmIOj*nxeHcbjHDa)I}wu=jPRf+JWhh-X{3^({1k7t#A1^psPIuZQlY;^SEl*u)GeYkbaZNgJ8ymT z(@0xBCgd^r@Q=-QU`51@fFI&oq~c~98a|V~HtxV` z){iSEXl0$5HEZtVO>^)&CjM}GmgW!l58F<1EKPxT*H!c`*HqWUU+pbaTynBnsJGqQ zwK6S9jZ!f8gmZDhWqsn7dVAC6+x3r)*7dFau0V=qGJRdrD)w!HmcWEr>SM+Z|I2E* zIyqPam5z-hKP?XDq^Wv80)@@BR_*F1?-) zMUzDjQ^$_uT%e4dh+X|*!%lU1i&Jx1DP=U>Y1A&83voqJ6e=^I9%z}gj)-YCZ&XB|{8x*<4y zHorkW+<-jA33|jE?CQE{v$%7(7AfXG&F7LCms6ip>YNa-`>yV8FkJqmUSqo7yBnig zmyUQsfnES{b!KFX7;_Agst`>` zIcTr--XPzeD()OYj`qHNG2ica@Vw60E1k2s7Hz*Q8!q0M$ZuaD%5MGGV5o$y?sOPC z&U&2nTKQ=qB>mM_yj#DYlJ z(2vuWA$`)Ef{DbZBckjT?Au<^>`5bZ1EYQFEbhv!ktx`SKdn?}Zf3f^uUtO5XKMS@ z>6Gm4^`$q>v>qQb-K$S}KuxGGy=`f<(%?=(()J#P%d;C7<5bUO2aER^JvlCJl6^$> z*s}|l-b-0rP7B}aha?orRae9!leRUO-P&e&HZV`|c(IP$)4a!p9SNDL7bwqqUjKOI z`yY*1w+<{2TimJ`VHLjrv_3!VPzCI0{WR&OGPXHPkffHg9`v$|nu4x7C&>}`@d7nr zvlEJIlx&}C%DR-iGL7C+5q~z-=}~!>UmGXUHAap^atgju{#dn9!6C^-^w^q3FRZAW zcHZ3+_oKA?{u`_Ej7~kCZ*tLT&3uXN%92tcTdQm~Kh9|c8ra7=$8)m9wzE8d4#r-!_)77>oO{w@n<86+O$%QAxt3O#=sj%AF zAUP|}Pp#A(36TIuw-F$57Ejf{2#o!_gL#BC9n3xsTn?t;YE83((ZLikC3BOwLhnKn_TfZ=3DmT zp%d#uY;9sYZ_d5dQ1t%M)t!EPan9o+5VJOE_b=Gca-2DyX#iHlTsHP0U zLWxJ?vTDmNJBtKf@~MBbB4y4c9lonnfmJrVp7vuu>}~-rs)aNhXbF4M*CTqxAyA-k z;U4`x>Th;6*7SZ)ka2o@*IqCG3_l5*oD7&6J0->P51; z7T7AwPYzHtTb16jE2x9&ThP^B13JCgMIk2I3+Kd^HjvTL@QKekX+E=`(Tk%E6)HUDav_es-r z+sgO2Tpr6uYR8N<13Y8d39ZIt`mQquOfij8*%7-ymzK<0#8=iSz}%o>!@^z2WFH17 z5)UCiRa?Bd@A&pl7N=PoEmF3>IlHXj@(%?G;?}-Dy}Y^0`1XdD4=2>b0$Tzbj21}z zXp->5**8|K)YO-44|mlc?-7&D%(b|3;_Q!szLe|kxvm#z)f3xsw1mL5uf%U;Pb#?R zpmFi1tn)d(AC0O*l6I9@;$qHx!U2zxAwI(aGt-9nV1=QO}*%;O2^{rjA`eKbeTdg zR5q{TyKCjJYeEKu>Wv z(%q*;Q%vr^tvWZCRoT**-1m-?bLMWnZ_7E^(~ZXKmiNf%T{Ugm5j@U%n*3A(rfS3g z@-PLFH@DHoRLf&OqEmYocYz0yT)d(n6Thi!kz2>J^ye32wCRuYjyL#ka7&XTxb zr*$#f=J06|1w%b%ZIq3jap(xo6omT*i29n;)^$r@$2N+AQ^@UE$rgLto7qLHPVu~_ zO=&;E@VV7K-U!yD-yY==(UPeaS|J{!yZ$Pf%JdH)R_~8(j!M#avSSQzMn^ojK%!AK zZt;?U3tsQ0aH6A*E-qW5e5B-)Z}q{wyNI*6Z;I&_%lQ}r(YFv;#*e@J-F`&nTUA7f z$}*s2X?l%$b^4Wi+C~DpF-Z!qY@cna<|@q)zMGcs(|h=Bd$a%EhDzb*IxjAI-rVJG zpt9+7ujYrcBN0~O+#IJTUH94>Pp_TFUGS3hbo|zKpJ%d#@!$9K>}hFPSe_o2l`3~CH#ss><&9hlH(MlbUwul;1p6k|PL8;zzbB2%Py(&uI zlJ3s(d(S0eFQ(~pD`g8>&t9-izfdl)G}7&j)+AQdts~j(Nj@+3>T{2;6R%(75NE)h z=gIv?e0A$@)at%op*po+l5RQdwO{vCi|Lws%#^RGcwi1@Kacs{UTlx_(H;e&JyPvy z5qLD=cIEoiFqvi1J8siNobN^Z39xX{KfRHi9^P8D{>uCM=ke*!ZQqAB=7lM@o~~0b zdiknhdv%V@MT=t>Q&VSiSG^iOfro@oL? zKC0Vm-k4ss(zm#&)#($`^4`ih*z|ht?p3_UjydmE=1)2)fWY~>z#QrVPS(R(yFnkb}Ouy#|5ikITc7iaY4Vt!sO zflzEZe-zu735@9`ESinPT<7*bJDx`v?#gKkO5yN9Fa z`#ujh&b`lb&mZR*d}rQw@3mL_)^Dx7Ur{xm9}ESu#ik*<1klxLZ`swAO~suJ1t}j9 zzOHi3uW_3>N*2^7(7M~9-jLZbo&(5cM7idwvF7A{5G%;Ux^pOxbXU#*n}&&T5FX;X zDh>R?=#jeFkK{BI#u@J`CDy9r<75(tP7#Y>5qAp4V0KUgu65O?@i76kcl)hpHoH9W zPC`sWngp%iZLHD@RbsT|VvTY9vrw^n#4uzmW5&OE?xsWhdIm}ekp4n#mkWNRuvdtqax3MuK^e9oaO5mMT9oSNzWby=$rs?i9N3U>=4pA zrQs0=a%WMAQ&bit)JaEylw&Zk5!|hs<1n^qf&@MuB7D`s4aFM`!On>(?j1ESDgcH= z16v{wuPp+VzS`xEgWiz?`D>2Wi|cY{ra^9Bzg)Dp}3 zQJ(o0D2U7*{SZ=>tP#@2i0s+-!*1m6SG31&_tl4uNuXsd%jytvP z$0g$Ecej&;dbakvwJhc-!UcVD1(q7Ua+DRzIhE~`6!kn`b=;cl`e9?tTBJ zn|hmRXmVt~=ZUvw?@&)kMm6tBPhPf~C6N?YG~3=fTDztt!=Az**rM^az?Cj;A|~ij z=zo_J3>ceY0X-DH1`tcP@cU7}9k|{S;ic?$UyH6rn2-7Uxe6bZ*8&=048j!{_P#3H zDIS9oFX!>r(9n}bJh3^26HVp}h(^`H!JeyXchdGF1A2FOUY#(Zv5PS|wcTt`F#N6O zYr_xbrCitSc!#)`XC(%BfGfnMte3f&#Y{Vsle<+eMB5m#E_}WDEzV<+%zuBHuBR!U z@%nYEbYB;K>yP8p?~L#vWb#OM{IaL$Ea6DANu|n zY%z=Z&fXaHh9g#c+cHqQ-fhhbxG&W@6B~7?=)o=PMmiEHYGQPlE#t|jQuS)+@2`UF zfeNYDv(j0SzOe_65e0WJR2nK{#`D8?kCRm`Vn9q(wGL8e1Akw_vxWqz>AgP z2}C%8IqGafBpzaZv7b`r9itTwOTxwKof=xxoxuh?mI&~d7Df9nX3ck!r>3`iKP4D7 z?2NJGiJ3e&e=<70_Dbw^Cc6}nGW*16FPTJpvoE&_D`P#Q;U?VnIPTGasI~W)ZvHdV zKYVG9FjbHq0mzAVF}y~OzsfR(*UC&HwD-vU0Ax(!I=Q6Tpb__+^4VmTgl5LHzPoVE z{jTt8;tWI2JF)w`1N~3l1iWAFz^SMEx+{F%omo?Ks{Q0SK6!RpQbHc>n5}(9W!oxS zJ1g1^Q`+OJmE(iSrbEdEV~Efz`{hkuM=IQVJhi|Rdh!shj^jbkG~?y2_Nj12VX>{T z!LZ@X3kfmkW`RiLEhxa$+DPr?)se^Qt79Xqj%5C0D-UOC2qQ$P!n{^YXL^~bxXli6 z-`k~Nf>Ewv<)txhcYp2e*#OO)k{-vVY&hKysf^)S)tM=}x6RyY{^GZC^$jZt4^lUt zxD9EL*s^rF@1SnZ9&!nPP?w4tU~IIbUU6YyL9-L_Iu}keO}|X@Mofl5OgZs}+P43T zwdSE|s`gn$*Hp4+Xdt*&tWuZ*)rK`rGtq@bmNM*&a(c~!ShqIDXm459rH;4F(o^oY zJy%RLTZe;66Pme`jtv=2es^9^jTVu9)GN}nY)pccOHZ^N2@#@fA z)o78(B(~2!(;bnGqpCf-i935o%{aw3-F8gNaOEI--mbudZe~e1lijFX zV+hT^RkuX1x+2erO%Tugf+yf!>M-M|941;X??q4p=3oj#Af>EQzw~W5o^mRef z55tstcu|UUt+K)b5ynC=c=he2+;%QfKbx|(rOL(NTFq>>(kMA*N9>|PLVW!kiErT#zYYlSIc< zj(XE>fHUQ%(+#`!CDFR40vQ1}PPH#RKmentY|cs3`z~c1;?rYWDJK;tf`VW}*ESx^ zBwiwEK1q!B%t%VSLxPW!W3w#bM2(j zOb-cXf%oA41L*`V0Rj6pe7Jt<5VYWjg(D$C|J*g2{~S5?`bt>pRc@n8_G6dm?odeb zRJ+T}^l0TEL>1*ih)6i5H9jQlonVQ`GNlEH`CqB`QOQPvC-WRgWte z|0G6FN>n%FSohWx-Y5WN$qQ-cFn1mG%n;a0965^y{(I9T`h0V8#hwETjHiL~C=7AR z2~YVb3qLD46z*3pK({OaLI$@J(*5;HBiZOJX}*(3O)m|&g}t(*LgGU=uZBlhP=9f8 zJcfd)WXc|)fG}CWC$SkM|2%wBGyt@7F%V&XEkww?PCpzQ=EU=v&oR+3&#C4?H!u9dcTyUCs9XA za``ooWV2AH%i&csfQ8r9(v#}#5f#a!n)=LVwm)q2j`tYXY`_)E5$nV6K8S)-(2NYO z{6)6?sX&ovU|go-i^M06;3*``iwzs7uv8_ z`zh+ndD^3z{)Izbj058YTvloHf|%z+^BDn)_Ma#aQHy+GA9-lK0^l#l zMDOZ()Tukxt%g%jWM4UAEsqmLvjg-b?rV8S-YbGK0^r1xR#2pL=Z$xko0=wPZ{ttgpS3?4OG2^@J_aZoy%TcON;ba>Sk4{#{l+Fw@K zQsj=5S(m--aqNq4&PW9&g1s=wBG4RQ4-s|kt2x8>cMa}yRlkWSlD(h zj#g~ba~T_5Rido~0QwfcYZ@OvAAyNwEVs37s0*hJqRzV3s?*qF0q0m}VvyMKio?Fn zPqx+WPL1cHXxS3l&H9THoeEdx%fS!Y#gBeE0n*@g{>+mjQ0KTS(CjqF8?A@vfE28n zJdVtBa{*yo=NK}xaZbP~eeB!{x~QIpO+`EFW0?Iqnc(73bx7QGW4nT-vCukBC_0pB zt5YU!Xv(h4qLrSKY3)f-{er6Gol)PlH(>NzJJ!AHAEwes>WvQ8=qf&X$rRa_3x@?$ zGQ#NskZ(p%4?agT+*rQZy1;tD(!yfqZ2&Gn5qDYcWxni-Gn~eS1DDcHPk)qEIg+hS z!xu9i1?e*#>MW=r2yd${+os#<>K7RZwkPw8)^M%Du^DSW!rS-S|PZ-vb#}7qtF2R{M2Ou=^lq zeuVnKXhG7a5*22dfVUYqp1#H%Cqh>r$bwHbr>1ka9aZ}yj*>fQRE7%A69^t!;Vqzp z_&OikzpV59zo`xW|MMGDg3)T%siDMxciAsE^^nQIV zvRrCiz|ghaZcwvHq1F;X9d@*9tpWZ8=lOd57n>KzPShjNp_@`ngsxyqzj;J_0*hRQ z4-9m}kkh|BLF6p3_X2;CH~vSc&T%3az&%ZL{Ef(s@R97XN;=VzUpBf1uD(;r`0X1N zC4jf?8+O$VJwm$z|0kEkKj9+%wcO5flfgKv&wa$4xdN>V)<-6x#|Xw~K^U2=*AVZJuFm$V~~`E}=Uept)4!Awh8EnG!ZEx4d+Vng7_O6jrVj`&F9IuoHM z_`4SXm(TDkCOu+Phkh%UJ|Cx7t~!;ERx)r>AIjsfOX}BPEnUW9Muyy+`_%a-#l|RFLV4yI-iFMVE+W4Fg ze^rv^VZmpE!UZ5Dbw-Tl1oyvLrvAiC;vq|Koz*_$BAxDk^Uzz;y#jhOae9J=d2>WM zCI3dPRD0aod+1vc+tPV6S9B`=)lYjjw~dpyQ8sYZ?isjQwZzfwJdnmDV7p@@!tg`5 z0Zb^3EIET&K>q?aYSu8NkY5|~ujZ=2zaA!Z&luxX-YWuk_%}~=>yFsgoV$*ibxq0V zf#3f(KV9px3&R++A{dHj`ee%gmGvnL>ZMIH0|_fO&uKFLs{tDoq^;HOSJc8i-3yW0 zjQ_^dj2pD~8X8!5>o~&0kUG$R^;3E7F47|4FZ3`~dMSrioz1$e0?XLIgw3&i2?`-qmUwZhp&l?XW~aZmdASn0TxGU%vem?Wc~8es<=7 z!bBl|oY`T)>vz?1k!E@%Cxk)JV?Q8^6%goSTBiv}x3qy59t;D7dVhR(%2_Xn@_M#^ zsdzVwAeKBCjhO?IpK%shwB_a&H038*)|xLq=#N`#IpFtbrizd&;# z#psIZJ0qG|gE}Tn8cJ<`M7tj*987Tm%mYmEACbRN3J=f+m30BTBS{C4JNDz5X|%0W z{>S=8(>>%)`FodUU(7wVnQMn@3+^=f|Kd)r+cKWE#S`IvZckFRl>finsdZbcuDr{o z+1Mr>=EH!6vyY_XZ+xPVNhKlq?_5nBG?&d4Q)U@~ zqB#H)P|pPs7_w#~$Y!3RHa8Z1hvK?tt@QeOqJjSJ1<4(SY<{Dba;acB>^gXK-3c5p z`_s$)I^}=g_v_Wjey}+6;6Jah=3Dq-v;Z;!ZHoX!r*dX(a}(2S-5JsL(vcM#493vL zyt*!p0Svh&$%7DTg}8r&MjeBd9gkRJZJ&_DV;M7AuLqETR*8ml!m56YRlUFw4}mnR zd`ixCldKknL2DkA8VyXqi>Td_|0$C{)F}`O69}Igx|$^cg5jwoz<}C0==y>#!Pv|c zLt^r77UAd_xLjbk%jQLL&$KO!!kgu2rz-EZR^Lh*lO8-^7 zakGGz)K`?lDMj^kbl&MQGaSjo1O`?DTB5GpL_6d+cA?LQuMB0MY~>P&FcOL|o;+;Z z`CmcerFj5^x$Wtwf1V(fZlKyVk7)sm^VkbI*eP3(JZuUcx#CotI}@N(Y1Ff7Qy}K{ zLQdGZSYs5;>8V<3bLklLX~$1)xdm z@gBCNd<1)l{HjEF@(=d_#|smYP?E%-E~1&?R#ftbfp2(tcJ>+~cWF$9Xil{qnzAJpT3xw6R>69af?fxWm3W=44o- z{Ac3c0KCz*1-m{8fh4|Hv)i(Smgv-*tIM@2pqmPl%|Zjnfm+vcZTKEhkhnko`=4S(H8s2!e?FRM5%d&!z5(1_(3ly2%F)hAO=k z&u?HuUF&9N#C52}>qTVr4RRTM^a5I+G(=&^;MvxqIyo-MfqM{y`_uiin2Kjgv$}#^ z*6=f=dMbh93Ns8yI@k&;Y8a!=J3XDhG;z``P2ClmBMK8rXz7=?c!=x~)I% zX163}YH2@?L6cRRBoO_#D+VnU|LL)W;hO+P$U!+DPLNg3=Jc+k17o6sQBzrP%ity; zy>e$|xT7l|wgSXX*Ib;UR`>Ec- zi(V<&mYnf(O1Lf)vvDAyLGnsmhM!IT9ax~Co4cl9SU*{HJ*#J031LJO zQ%0KRInFE)@H6bHSMN4V?dvEiQx0;8|)7d){pu)hT`4I z9JpALcU8pPizoAg;Il?LdL%kgWRGRA1om3CDr5mrS?g_$yqT@%rvxkMaHy*cg}5eW z9lbk6{exc=u1q~L3ly2CQD@ZF_^?Veg0f3Np5MOom9bug@SzwCnQ+Z2rCdh|;pTx{ zno{ZL;N$v}9_RqXkf>wZNm3S5e4@*CuKhHmQI7y?Z9J}#<-wymGt`~Q4MzMrSH%W( z{>x{TK(vw--S)~`wOL__^qeow?cb7`3+!Pb0ue6AEXOjguTm^Gm%a-vO$zCCXf<@^ zKV1yJ^)?AhG@1Qo<^sB<;I+`4Q9`p^60n6DodkH1W9Gh0Jn?M0xpqdQV9!4i(W5Pb zdpWkhpwzz%6QPB!sCpO*(IiU6FryVhnp{ngL)(yMI&|D(Vo_(Aka&kWBaK&cQ7j_H zzpHZSoWpjZ!8DRE!~UutH%;y{`COU4k@| zC*w`DxJJ{riTiI8{s|{{@vMD($^%ByEkz(Yg{04#Ahxo>DiU)=lqxatzlQdXxQ)ZW zHBrb-qL9r;yPX``{5cVsFm#4#>aS$2r>d@8op-L&X?UmaUXc5%wr?5AvmyC6H)aUv z%D2+ZSEsi=3^6Sp#17%@^%0|TdQxdeGscK|R#DkD8(`!AO{4um+s%3tPss_QM|c!f zN@*bi*4A*`8i2&I_qtN9N?0Nhkc8_>fj|Z^BXYpruA@DjDp`=V<|run;79oo!XPoy zQ6p_m)?FhEl9VN=A9DF!ufC`XJCm24i!@j3PyZpqJ_u_1oW15VxXq&~Uk$X*@uJ8Ji1=_s_Dc#f# zQ|+dvyIprg4Kdff*LpgAz2w-dcsoZu(obx(8S|wT& z`1}}PNZ*PerLQbbDU;UOx`RwJMmkumja5xryy$DlW_|spPr(B>bH$GqHL zfmqoMaTj4s-@S5)2e}|dZzrBx-`i`UdQzCd_2bFn)kK8GHv8@%zfDFBbuCF{x&@vO z5c$f8=AApYF1oxwYQumEYayjxkt)X)lZ*u=;i@K`+v(O~H#oUQ?21Ka^9h%5Ah~M) zd2eRZtq`f6@;I(}>JP;t-2(Mxtgzwd+ozTzKynzc!577KsY@kW$o1;&ajqgQtG#o* z+VO}A$u8%c>+84K@euL_1bZGgIFv~vC?W18M~AgZDJtPK7=OZArYUSAT?KuRE+*UR z9#8*N$`-{5Vg>m{*APA(L)=5p_c6!(HGRuPP7Qfr?fi1fzc_Cf6tvZ#DbOEn>pFT1 zol2XuZ_l}_Ztc~05RPJovQ8wPqkDLOs@Rk5&%KD&!r&-94ChF*L%Qu_J1ymDK3FMP>R-ER4$<{r|5Ln*$G=1N z{VxN5bsg|<0YGkX;kJnL>3cb&FsJvmTEcO*uT;C_;B?A*dYhL(2JB1fma@v2ja!S1 zd&Yh(SD-FKXf~nqTaf3&G>0AnzjVwOf6z$XF3j71(GM>8r4v!`q+U~u5v5ekGihJc zv!2LH!xxOiVhped<1O3OPv2Pu?i@T++wx`4kFM7iOIUF=wk#YoIJeH6L92I~Tbo2s zr`pL?47OOhEwlO1xlj8q)9ZRZ0^ZN>ag3*DI=?Q-rwv6x8 z*aNeCnxRzTY{7FNlW{rDou6*5U|C0}T2xME0&m1DOt;RmyI(V!Xmzch; zv6@x@Pt1?8_!wR*i3O?8e1303td3D#pSo4P4a>kN(l0T~jS{QG-Cm4Tz}%%q-06EQ zLO9CaC;nyw?E2a%gA70L-;}GzVITR|+e|B`Oplzn$@ixx=E0}wGauFI2@0-*`d~{9 z^Ue_96)Lmxc8Fb4>q`w+>}~P^02p;Z+N*)&81(Xs&h6BAz+?O)$?h*0Pw3ob#mJwX zbot?r7Ainka!Fj?E$7>R0WVy!$y4G?wOySmHv;K;+qYK>M#2b~are#OC+|fFp$PLt zQTF_lwwmC7Y85y`U{rh9xj!V31R!3CH+OihM?tVplWyN}rrEk<=#H+B7a2V}XYnpl z&8>D8?p7#MmCFp+4nyhmxkA)=zZkwgWhvWN{rAX~+6zW6Xq)(9uHn+YNR??#rj&}P zRZLc7p5e@t6unK@cQ;4-3QjJGrf$-?g)Nk4nlI0TWbPXD?8?^UCrOY{yY>w1DsW6* zakQr6e&{3lXWwRHJOG9DBf9iY11s^ga9zM>cq&9#|3_QWHCQqz@L7yyD)l~0Nk_uZ zD|=$s@aoS6)PFtf;@;T>(%K8yWaOTXSh@ar*yfO~4jD%MbEBA3r?y~%0$-8>qhXz; zb%-QJDlxZxTe+r8KLHj~g3;z%zBi=`r}uJ1B{a=i%x>ScT`%vq%@wjO+Bm^PZ2$Pn z5ND1MJih~;p-gBp!FcK{?R4TXY+?CNm?%mEidlUd@Z1cO;PI#H{0>5Ks~_lCMdFLD zqj6rDECf(BI~qB9&2i0k4EuIoWY#sO%S%xgm&&iNrITF*o>t!uI8eXyNA#}00gVZ^ zdZ8Pju2BV?+PC-h$>96(!!4OEr=RQP`@(Fd=>@xf!oP@Efm>9zIl>kn*<*AUdTH&& ziI72Xc;?H3a!%2Z7CaI22k8L01k{28rl1FQnBe{WdA)`RrS!Q?MoYgaf)#T2_Sa_% zbXf)jBTUy@Ks(;Ns<%WJGy@89Ljk!Y7fR>V9{w*5BsvIhwKOhN0x@*>Mk znHqJLu?(dCR}B2ZtzzG3&Kjo=Z=<*TX6O6+5PE6=G`M+0-wJnlJhHzn2lAy_loBU$ z-v%z`E?XOHdAL#Vk30syz1D&glr$ijM7s>rY%LMq00)*6C6l^`jZ?x=Ai=fQ;V6el zR2a~h38|lt&|yq-X}>cvCm_Yc?m_|olsw?4%Kd<;we7HX@qbt33fRFX-2Jr;P^83w zD4%K?r6ms5V*LG@0$dNmPTiPL&s3W4>{3@VKjzXQ*nV_eK7rmIl1}ZdCRf zKWGmc0IBV-qBYC)8+tQ7iprn@aSLw7BxS2QpD4wxJ=R@)uGSRXuQG$}>4j~<0Tn&V zae)%=K9>^SRsI|L>@>4%zO1kRY>)o0lDF3#FcIY%xgwxt^046YyM*hux0U8{6Je%U z@xR&u(hRRh9L+2Z$q(m#83aUig8~Mx^Rv+DP$YLdG_eB zVSY{^p-r+!8Sb!Nw3Myk?U!5`mqnpE1OcM?FIBZ-pR~1Jk%lGbxv@fbPtCLK+-&t8 zwVGUMoy_JrLN?>sK!ak?p`hw@6TcMi=4q&H4(C8%tWKG$p^5H=>6~ZN+qj;udAaZx5IA_2aSb}wUJu{6j zv3}=V&gr*)vfp#B=uV=#p-xXV{4}Yjn)XCC=F8NJRk554)egMGHIshT_5zsoVN2DS z#9p+~KYd0Z4G@ZIJ|7zaDXkLNzN7xg4PTo2LAxb?fgsOas$1%g4kyaY2GPQI$#HtA z$@{>;Xd^pa3mp~Xb!otT*w=M+=!*HzJkbvp)aU+>3*r6r=AjC9M1>6L{q(YcZ+TC??6$g__}qYSRDE*hbX#C-<2#N<-`9Jm)~ zYsdQf%6}l;G6tVE4ciDn?t7Jhzf8o*3`=C?P-~F?Xp3m67!Ig}JaW#-kD5@Om=rCv z1C_@Go9Md`#t1~_OGG(memN&R`Xv`MfiJ=}6=gpJZ}Yl)`W!a7M=-$k2y3g&y6y2CKVXySQUSu>s=Jwv1MJL04s0l1-MaPG#4(8-I9q{GX@r zlH3C(|0@pRC7J!a(Pp9hToKvsPt^+&<+GZcE-c@<0~7}g*@&4(FV1m5D~W3C1q7WQ z3-z}qe_|{U`gx*Sq**B9@)A3|AuFM>4J~b#3l$)Q`PO?NPCOV>mE0hba39w;x|=@!;k6 z^la}ZurD1J9Pv*bY8LQpqv<)^mGeJr!6ROf?(T3~!brW;8d0#tv)?{i4{$ZrR$gK% z@ESlg>E!W5RIh#V(8vuY+TakoI3M0^u+Z&Kt>akNcSej~+p?D@cCgmaLTE{Irm-Q& zBz~kq@2cm#&I`u#ob_UoONQmf`t#gYqeH5#!@{9{ffprc)~`(-+TOKXbo=KK4$*3L z7@W-A(AK7n-F>H^U>jk5cfFVFzrqE|W~lmiFTgK4;gbs3T(JYTpct`_PeCd>89mV* z!@R^Q36fzDEN{|hQ6nzX$H;Nk1gwqE#WCU8p{J921N+zMRB$<$XKJ+F<~qi48K_=Q z_^19)D9?gV{V88MY3j!O+^Kq7mUce)8RP{)U2kvj7ljop-n6lu1FlHLjHzKnL+ZVD zkhkL!ZOR!f6VZRH-Z6q|;EG&KfMU)8C52XAO}+LUf~6UjjgmYAfFj}2;GXIQf`BER zxCq^;Hq9OntNc%kcZv7MVoq;~*?Z=`B-*Fi=O~$KoFb8=*!Zk&knSftyr+ z|72fIDT1Dk(Y_H+-LOCez=zN}2_!eDpp_fS+~;6rZe6rb0-=3fi>l&I>G=!6yU9&t_rEE%uBG=D4b3wH9$UF+|KG#L*)4~X*pDlovh|G2Wh zfnaVrWO{8;z`n;Qr&S!D(265?O6FlML3d%PnLF6yT7NUork2*ao>qXP0OB9*@~|gh zt=K{nUjSD1SKU?)fCU#RmT^khbqkWmqt!z`<4bPbeL{}3YOxhWW@H{ab7v{Lcq=Av zh5_IjrhQ>}k9_u&tppL8`122ue~fzou$tvra)zKF2X-tu+c@0ux|`cF~!;+hY!!LY^J=M{jZ$%FaDi{7x;rkN`N*}K-`Drm&tps9ayr<@Qx~aJPJ-E9)xci0d)t^n=d^pW>oa?Pa;c=To79?!vv3XH2 z4cZw;e&WyG8_R%+yW_2x8{;=C(|>5)@*6PbVBv_K)4$Hp=pS@H z{Z~=5>W(QOq0p$MI*qFd5MkQIXOGAH1UYR?+F!QtK;NlMsWzr&A(%45e9KL}|>7H#FfW{6Er}92b*zcsNNnl=Cc+R_oFVm4>+lx82LM z!kATw7Z-a8j_AAO0J%j{iDBov(@vX%)aOS%_PeXKlfB!kv4~YsQNi2fK@gf{{swbOWM4Sz7 z#feVi&k68?n(k~Y7;LR}4!yY_B;+`Def5CL#oHwPUa^_z{F^4Xd$F8wJydFJkxQad5SH;u5w;!>ceZ5wJ&DeV4HU_5zAUSo`}aZYjjmtnbGRpX@48|z72!co*Ta4s0kh4nd!wWMJbf|tj}uaDSlp0 zimAaK%$dw$5b;W}lh)TbylLJ%{3WkXpa>A3M2L?@Aey4NGguBUM3B=?7QZFt78wKj zRR6A40UN6ES{>UqD&s0(Vn|`&pPJUGwR4-e<)+$Q1@Mc;Zv=Zg>%GCuk0R$dIkgM( z69sMZ&2p5OOmgaeV3AOSPQV`Bw07o$JLNW*ma$_z_I05Du?Si!Z`)t^x%~F(xycMv zZRSS>rkNf(K%o4BZvWK>P77KRTe<(*a}W7KOujlWzH8~p`6(>9v^@7Atl~qc>22uh z)&#I9?~~sw-WjbvpTCFN<}9KU~OZ{z+e|tOFJz%ls8d=l?q_^-}6R+_G9TH;M&mpyHQ*4(%QQEgF7WKF%>P@H2 zro(5mSo^rsOtG~ntoY<05&CJ}*L5n~yME~ayfnE8d^Z;{6Y<9I9Od|D%E)`gncLLo zAd&1GbOfVaA5lN2m?fMJ_7Vkcb^8`}`iC7!Zu|Y!eFA>Xg26k)Ju1^Z(kgs-Y5rK9a8b=!Q^)-D0`R!*IAHuKX9hgG2-gu zxFLC%z61)wYIfGT^-TQe9E>U*pmjH0vfFS*1$5JidmSw;J?0UTaO$xDsoFiZaps*t zE4cgCmyt8S7BLW_1ZqyXYa69rL?iev!w$a;&OI|C=7BId5 zLuKZgGvTGMN`O;M%pUexCr35a3a@9WNoq{A#KzQD5U)4@ z8(+Bj&L!YK&58c_hSP7z5;mg$X~l0*A6b!x6R^y5Rsm8A@l2qic zV_r|C`66`-@15SVtah1Lo0;y0{v=7;nSiEBx*vihMgDz9G z8`eE*>=xA_vN`ey(GJ?9+J(pRt$TBy4%cnIC8@Z5Ki*aSu$deWQ+Y5<>F&1Ok)K9J#AWwT7uSLcbPR} zx&?tO=@;oJnrurgI!<_EdK2d#vij*{d_1JaV_|K&5yqESvWo8M?Zp)P`7VqxKH9t8 z8pkbYv-VK^H^B~j1$a)C!6K_Kq*Z!gRCT^G7Kcl{NdJ7o4S4}bY2sIgx-4!ph{tCD zQklV8dFr$$i$6}nbr5m&2?BRMgs^Wgejl!Iz{pTbWWT^YipkS%PZT7KILTvJVW%nZ z+ikqAk^LMETD5gFXP;a5%-h)yypgt~^p+?AZxu_^j-cRebKN?d8elAA;xDrM(<&_h znXBSmCw+HE`gfl`eg`XZsxp$8Wn2nGhl2$UuEX98#n8Z%-f9PG7uF9*jCfs+&I{?X zo63iXqr5vP_i$2pLo6;bv_070J03dhv)RAkITEG*8t1>KBRuLB)4#i_)>n&v@o#{55 z!$Wrl92mQj2N>7B$H3JyZl_*V-CqG`1HhNiDIJF3Bj!xx7ck zC}sm*gXsVj{p*x8JSh|oP_<}F>o~}yL%{H_+pHaKiB`0L?W#`sNPKFqMt%0*E%9#q zp;-Rqfdl73W3dO(scWwqo0v~N3O9pAe_r!JR06$WBGYO17}xRS-UuB ztjxZ^?HGc%*PRL1D9tUBeBmH|Si!sMW3Z0TP*}>JeFqWk-?)Ua*onwF0_fx5b7j4s#m&5* z8^D7y)hGwg2UQ$er1Wu`-KXywK89VG3qjSpBu|E6O|V))B*9Z68w2L+9llEi54$tN z+Zcb2>G8uvqITYozy0|vDV#RCQCj7V?{HD2e9C~}eI%Lts@MxVrUrYaCVQSz=5Gx@ z<=t8LWkxs0eAOZ-&z;(;b(v^MocXqSiruN^_2DjaFmrMIhK#o=Sr3SI@jJ*i89glh zKsl|7kCVUw&pnON(M%?)SH1yQP8&sp&hSyNiQTqM(6#X#am2plWV#hKtf27T&+ag{ z($rz;hB;VT=Bi4qYugW&T!k0|Hr-FiAsOJh=}+`0eRiGe_WBLK6sx@6*{E6a*=JV_;02^L)0l zjpo3QF%92{f2Ev07af*lQ52=l?&9i@fF&4J-(wqK%#`}-Vunrr zw2&o_))jA&Ixf|77o^r4Y?0FtVZKuWeKIEAa#qRSxvaC3uVxb%#hx{*=G+iI(??Vm zwbbvolj2FRbh2X(4c^&TZo0qQ*vwvLkMJDx6CQa5!A2RzO8*LRjY0T9jR+{oH!gus z{fsNXM;VSF6C-~H`^oD;9G*f?!)i~{x1)^VR&DV8^a9%i>S9=;q^^+P#ZMj(O z9nJl{`&#h{SmMjC5UbH9p56X!CG(Z6>@O zvkFHDSZ&NVZi(Os=LWKQn78%=4h+qkL&>xUYrR(+IYvj2?sNSGd)9eRrMAbLs4!I=wcXfo5;XNlK*PsS zCdO+^q5PeFU3$jFhVY4v_Cx`)$_2lj1-^j&w7Q*Rj&PfiWBVS*a-PQ3wM1(?BW<~6 zSn>F}w5)dSWo7j!%CC6=g9Mo;&vW`-BQ1Gw@7cB6hR-gS-fiuPt8jzN>`P6(dRC^A zlq4WreP?V(d{5M6a%tr2=Jy2=>>%%b-hP&E=yPYxBCmWMlMrz1zq>g!KiIvswP! zG<>eLp96ernnHH^o&H{=kgI9Z>G3gz=%#U<*%e~(j!|8SE=E4D8{rp4E{__|U?_Um z!(}T3a{a-{n1EprcCee_x$CgB#Ba3>-n7jsAV9n5;E=yK6)a>wJR8n0R4q-zMMQie zGoZmAZ6LxZ(+wAQ)b=!hCTROA*QU0q~32w zXsF!UyzeR>-x;u)-LZz1_X!y!H@;IrbsY4Cl#Y|D2NKYx2Qrf1=qhiL`xePDJ`IM( z==T(pzzoJ_G{{L@cC8VjH>z_#9f9OE1k<~y1|cfDTu7H;Ke@bdJUVjLi>9J6G}Y%m z{SRDKo=^I4k@DFm;*yh|05xryu05m(mGq_2_sksP>!PHlXaX;0cbfPyVKg;VY_4#9 zYnDq#eC>ixiEDzGn~uo|53pi?4T%sevwNW2ciL;?5Aj2?mn-6DK7sCcw&bPldJH7$ zt_Oo5(e-vI1hj9|jynsue54v)TNd)GEZVxBs?ypj0OPdJWyLLAJAuwE=HQh0G3t4G zxs?|*rxs|Dym;{f?IiZ?gT_)_u%|+}b|13(>AC4du4bR#YNpOo3LY|c8c1i7=%Pqh zozHsWWG$lw1hwWvJi(>y^lHY5i8dX=LvXoE!gJ$dnD&`-e0JBA;yJQ3=j`I}Qr#ey z_3|ayJRQ1&?le2g!`n)xZNDGjL>+NI-Bv_%uxG`*`G!;DF(`uDpsex0Z{vK+&+V2p zViMx}KeF#sd9UW~j*HZLO_O+0>Nf#M)fm&ftjmYFCb}9!13WJFX|)bh0d(ev9T-0+0;5p_6Jn z!3Iks1k0rR!aVzz-XE%yAK4XF?%|GMis$91JGVYPL`Vq}BdN~-+w_vy*_hi^b_6bSZ26_w~!2J?46dFGYA}QeBX|$Q;U4q-0{I zS2)0!P(Z85^@}T%phpXz?~Ei1i6~ojQ;yx<1g@Tfb!4{oSU|B zxO0o;zh!(+XZ&2|8)DDz3fFql)<3u2BznY@o!;h3^Zh}Uj9!Z1Xqhvs2k1`?q>h-cQJT>7yWcnfWuS`xD>|Kw+~~U8KpyxKdOG1amW4M z-&TM4^saCS(V1dm&lT3i@v~2CtxPYzkRyKCd?ib^=|zdk2{e69d*8iJIm-8HJh;K@ zU|4>voNlAz(tWR-B4*xY==ip|S)s0D-M}*4md?`S_HTuv!H?mw+$1eNa2~qhzpdJU z?$#6Et<#aYh0u_Dc~z!sQCA==JkPPN}!mURsa4cyvpMT{YC~h>~+QS>r2M! zhD-0LtQs#Raj7pFUnUn$x{g3FPE(y1Kc^6WG0LxQB#Q)O;r5Gf!uqvJXfO|1sdQPc z-8hBktlMWBGh~+6*V~0!pZjih)#~$)c4Co+!Seh2KYUN1sXVltM1SkZYi{5K?L>9| z+Xwyc~)Ykf4Z3U zj|V5u-BK^FpU?Rc7U^?+tSnKYusz(@e(z)0!>)ALZYn5` zO*o8$O!F_%e?lB19IYiUkvv3d|EocRL}rnpjw=x-T{|zu-4>!>4&)O5^6arw>w2kw z!Xu~Rt$ad4Lgyl!z#wu6wzvqbxiQ&9?e02I?kfz}K{>35yf~qUGI$E!ZZbVYCF)Et zHZ}%dv)~PTIW_fiYWgMOAn^EW@v9P_I(?vZK6EMI==(jdDI^piHueUqbX#6TyYp|? zosLIjx)OgG{hFuVz&WH~5V$=OePN!{?(hk0BaAp8)L9sYeoz)VVnVIP% zCCX61!2vIGoRNn@p%Y0TK7^dDyw{7`SPbj2Xt`G?AtZa8{8n0HfMTO3X{_|3j<}QL zu~&VmRj0nn7}=1Z zi;IgNeqD-q)qDWeTfO$3;w(?P!seoAcvP0W^rKsI<@R&BcN1@E2=B=$$EEx2Y@84w zh+u9G+~0FYF;bkA?aq{&*gOgH7^<&e3;(ah;cSG&ZxZ2`hKuYuWHV@UtWwjl1Ka)u z7Y^*c-eM{=MH@nd{?;5`Ixrs-9dnwQCin@-ij%Udw8&ZBDj6*fxnn`a8K>NAG4fOxCG6T7S|-_);5AMYjFm#!U&;(9kS z?DfFFg8h05Gt!GZHUIhJ2${h(Cta!Zc2c_!og>-<+_n@RwkObL{(IXSa!%@z$u_Z^ zI&bEt(k|_@D1|9E@UD>P9Vej{o!}XL{rcQ_2dnvx_Jt~oVk#~@?(ra^9KuI~GjATG`%1AfL}_f^Jkfdo zluf44OKWTR%Vrni?t2l+uV-AyjmMsEzQpkNWwhyv2x2-4C>cS%TxbbV_-kHPzVXPhz4pYvzC-7whq zTK8Ntu6bSaE;}!EX>&{3S$MYuf{4hj)$NO!)|!|vJdv&N_#EQY`Ie%HqDwE9T+x;? z!jf+DQZ!n=s(ykW^+;xK?JoF7!m*(!=CT-XBv(rfY2m>0;5*fs zjn@{__MHEI{bpAz)2dfuC+K?M;w4?p*|W2=59h0@@rUm2It0%uUYoMIySoqP>9Ke0 z70i`$_M28|AjFkcjhsBSXZ8#@D(9D-?-eadQd8n~-8}uA-LPes=^loyRdBF9W7v*P zVW?hk`8h z#sUjJ&TYDMuNF@2MU?a0y-%O#)_BJM^toC#P%`Zdmfbh+OZ=$oA7`T-9O;QU1f7}T z+6s82pdcx4H_OK6(7#%k6zZ`lZ6%+(?XAVHRb4A`D*5VrYx1>NM=Y80GjD}j?MzmM zaXr&y!9#KHsUJhBM=Pk|*L{&<>7^Zcj&JU{U4~(lSIt1ju6z0SItInmNt#}NR4Bk( z^J{ceOJw3U%7g`vWJtPu+8BQS>%c-2rZO}zLNw|{EQ3)zd>oj7y*(#epsjq7IyuCK z`5d!0Z^I7JQzpZ~aVW?NxwhTq6jY5bb;l82WeU-F88J8UUTUjbRPWEA$_6@Dy}G_& z#TU3QYS+R#ee&s6WwCL3lFm%q2!Y+UvV=G;apb(p3+p!bxy5cIbcek~Y3PAT_V#*( zHLw4LlYykPF-!ho(KNiaDx38!mS#g-cnf_Dmyv1(*13C<(%nf+wy%!lKe8D1rEZZh z>0bG%Oww+}%IkbimPD)_VG@hYy7qs|(%(u5b36iBknDJa=4SdR0%cIX{O>Y7FBv4Y2!G9&RfiKgk+cZkr{ntmWsmgfcK45qwP z$*z~|hay&<_RozXRnfM(`o1*ccdkr=RC&2>PBsX=$s6Z<@`IxGeNeu!sk{@~x5sIl zh!w+&k*3rQzCHtu_J-kf3EXUZiZfRT$VT6DRO8mW7Pk_}*32<`xRK*{lY1W+?Ir7% zct2Q@S5T6acUqYlTJ-Fo{TZu8`ZBru6ZH{!VS=^&UQ$yJ@>BbJ$w;|_v+&{Oe8&Ap z7zDlgF6io+4M;e>HqU_a&LLk0c;6;mkfT~z6Oe!x5dl)P9LASpkYjOe{H)fo7P(;! z=L9}`ZxIQOd)J)!OxBam@FZ)KK0gF*p;-McC42!mdjY7PSB5`tcSUeKgut3?lfAMs4))^q;zKbLQ^-HwCIKj0t*GO_M1b{ z6L^dzvQlbE@NDNki&%~3B9%C6AvWmN_)V80iP_D*w-jJAasM2pkhK(h$V`gvyg-{8 zk%YbI+-{Z=eT4-z?ckqsu5N~C4ccbQ(@f?y=K`@6v&rL+IFiyD+627v-qMP>_$KLj zXv}0EK>}n%1u~S1ibt>)N^(r3Vf;>@T1!lfOyakv!ID(Hr5tUb?p$AKQjFc=lZ=9#g)uZH5`C784wrP%k!E>$tVpqVog=Xcg>m9Ii_np}n zoSCxSG*J|ZL~PJ59v@zWnS3D$=?AgD#V}XjU6v?lBvyuM#S{N z<00`HQ zf$a6Q-$jCz?dpgkVkN@a@fdHJ^B9}@@xhR9k$F1v16(16ndvn017^Q_&zjX85uNR5 zJ~T&cpwyCRz{A6Hn4Y;z*ZArgGrMUkBGxc|l8Gtda}h2(2@+bcU%MmAWr5hZ7;ZyC zxaz<;UOM9|={=c5*F;gflB1J_1&+5s;t<+auWFeh1@2nv<$1mtY4^9Td_m`3i4G!- zr+SU5M52;fuBNccMIh&&&0zVT&5-G6Pq$DPWKpm#Si#{PI=ZGIHaydp7^IcPkNG+b z;ooe$#;+=H`_jDRC-bEu`?(vQP!;#$xu``sIl4;IJEZ9EG3~1%c61DBe9g*gW6ffp zI1=v>%H&B=@hA`Xy{gn%Rn2vIs+Mhjyxit&mUMDXM^7)3K*sMUJWDA&o_p}X{fH&B z{s4=XmX_=AeABr<16t>1Ir|>TYOK(9k2AuEAEfw;Wpu%H%RasfJ3BE)6b~TebSYC6 z)~k>5b!+Ze^qc$9RXDHqB^26|LI>=kyxSJ};mCgH-vRLE05#*qiynd5 z1;@b1s0aYc^ftZ>sz8(i>k(^@P2UfS<=$Dz3`vw6R-AHnKuhyZ3sY7-gopMjYGOQD zyJvK&x+JMPibDKt+CwldJpd0aT=MaCSkwsyjT`T|{H_!;ems?}Dtv54U!PW;#Ne*c z`QcWcP-r!1_l%d>8)hxJ7jXXczrG}rM8=kplj}S7ddFp^lJDW@;pzE_@56XP0{K+* z^XF39+6g`)hM#?MbSrYLmN-5dE3>m#*D(6KgrE*kiTWfIME!yjm&Yqm17Ocp^1l4H z{^2#tVNv)ue*^)GT&8LH=O?uq;o)ZEm9G)71YboOa)DI!&3Y`F;$*(zIF`^t5D!3~ ziKy+1_{FAh$hBQWF@bhiniwvzb5bln)ZxXeWA+5X3}1PUz1PI;`hoyeA%&{S_^p_U z!RrLohC~r&w4k$(KY=IXw`uxT)Y$G%`oOXI9**XwdhiKVG)WMVLC>jWGr&j6ZD&Xq z78abID2p7v#klfR{R7Nc5I8(6YekSq)`&UCf;l1>UWixR!_Wm8!{E`(2uK0VMsDrJEt}RU_LSjf4gsY&eEv$){w1h}Uo}~MPpz*Dz%zz4H6u+~( zF&kvJ!Bfq232&xb6D2Ek3~2`%hKnA^#E|8AV9+bXL4I(V;m41ui&NI*e_Eb5+LSdS zWHY_PX6e-gRV9T|?z9pJIeShtHk}=A>`i2+t>63h-b{hTumrxau#hip`iEM!!}7XD z@YMmfgrp=*v}k1;eRRlY5>lqRKEw1|pr2|HWt=dQos`E6y6oZWettPRW%o!=&zbF3 z=K~Qu+*?s+%AE7mKRuiAKGMF_wrfK$7yq4iGZ-O(g=#{~iGEkhz-T6M61Xj}XhkQV zO+0*2!ATt}O9MX>KB&a$eWf4k{Y~xw!-cmLhdi_a^)9W(b{90zpGWZfC;yho#OAC2ZdsnPM7)KTZ`XY=2!q6l5UJ3RY+d6t@>P%w`VMacYnvx>`s z{U}6P<%=NKlIr1L$#%oXLV8A^>zs0E(OX`iNhmYZl~K)kipv-7uOyipWAYeMhrUs%)iq%VJRA@tn>K zIXY6WqX&nCEEEJHI06oYVoHQX!ROIzY|xYXa7E2C8N?0zQ*+DSkg}L~5AVj{sPk&? zoBru#=|4xE;TCAKK!IobUB%DyfM`zP^ND2b!3n&xR~(M^Gcw``Zn-ikQ$ov3!N?!a z^!cl`)1~>0W8gvcN_^HQB;dNPUbzr|a2QflR3!3i^TAY)ibekz9_i6`%aGnE4L;WS~yKTzE?W4iCHN9S`5JKFBkGqD$$nfn&^tht3#bb^sAX~0F4i2nj=G;13myU1Kb^v^&H1m)b79) zqB=>ZcSpg8A_5;!>^Jj(T-c#$ep@M5Fcq?Qhkl^YR_~|h66SCrbZYNjC&^#;gbrY~ zid(cvzfoiuW`zwFcvSMJU4{{ixNU82gRsMEMOl79E9!1oVCgALfqmo|`ThVZj{m$lR4^%vh&}0$d^=!>To~v zfq}%+q!)n{YJa@!KR2h?9d_ZLpOK5*FjN!pS>z`k=*z&utoX2?q3|X}{q`sN#S@mo z^O0Y7-xwE?>D%yOx&216f1R{{vg8NNOioz84q<4kwlp2)K&#C~fbPWMKiIR0nh_$mMa()xto{nr%H#v8zmuQQYo1h*`@ zBsy7o7V+`RdqMhpd#H?_);&Fw6sl+nszkBX%wvk;n*X`NbXa?Y>wesOu#qn<0--`~ z^HH7$2h&(&94y6NGrDh!R04$oa*l^;GgFEbMa0Hsot43F|9%RSsz<@vPSaOUi))pn zw!3RiVwp*qk@75bhd;yR9am)c)O%_Ks9sK)GVATlc7LwUON3W^WN`u}o{Z~XDA@SO z5QJcH{jW(g%(H;KN-_H=s0^yD6#$@Lf@H*26ib$(>0fwjxNW(f;idGy_!f8fvY#T) znXE>$PdP{4=K|(;pfca~r4*HpVxT-5TjnbG*Ut(y9c3I$a! zc$~nLtsv`rwzF0Z9=|$LRF{~mE1|4MDUm`|_GCrwoFHbm;I>j%1rk$u(Nnu`9ok_@PBR^1kM5<*zxncK0&Zee7L|Zu?hWZiI;;@ z%J0hydWLKR&^mL>EajxQC0m0G38c478fb-fcDiR8Dy}SyjEn-V`(L*m8%cTRmzFZE z(nhU>0fS(=!JBArZx6Z7=c5+8Vj5?QZVTtQGU_5FN)10vv`*#W2%@xEf*y9XBlh^@ zo6G;)B@Wm@{$#?U3?fF8BDhQD&5Zf&5G@+~DAgt~tCn>D8d+vu(8V##sT%_xd<*$d zCFwppU87y%cS7SeRG|65Rn`@-@=Qcg$`Uk5aji3=9mc*j}tmxrIWs{Bfmn z*qePX6@<0ix9dGMb@FZncjLH=*y(%}`1j0;Scsp{i5fdp1ln}XA5QlXmsHxTt4D6CgU$@!e6`?Vck2qjkgO}?0Kc%t8ijcPOydc*pH|c zV?}#xhcVf-!!0<-V|#6%9o}>UFpmJ9d<8n2;a{_0KlpwRT;$Ao&|j-=hwzi{oxo`o zW5qj=Uw19fbG!8VhuZBg8d%mDqcu0D23s1k>W32<_zY%Md4crbZ=#V3u#SUH9-LkI zwzjwZkg%}E>YGi=&>Lt$Xp1C@?-wQPFpr{p+tASP;*LR$4@uF{dhCzW+H?O?Bm!m) zE?upMftGhoiLOSFYIFrPb^JF+7U)~1iB#pkzSR!>-O>DgL-S!Rb+pdSXW$0`py`~q z?F*IwHLQFD$9h{pA^jZZ>v*)ab_~v@B*W`hpWpB-nWS6$rF)nABh~wElBFzns%BD) z+PFqoRD;$9o`0&SZ61w)bR&S0JF54V_L67I0x^{?I$zPjQZzXQg*WW(+tVZmpHG@? z=msOlLzvx`A~}u??``O7xA%+kR$t2;6qniRc-PjmS%m&X^tN zO|(Le5u3j|b|pEGTrXsZZ?g~Fk=)}!YliMQff8Tw(D9S=$(PkQAIGm_hMBf?Zjnl? z8V;KYoZ}VF7SX)~jE@mPD@eA)r0o{b28zuQc;sj1iO2M3U$R%PULn7betA8UtHGd_ z_591&&TK=}k?oX(K=?-QXJ5|4r5IKbE;n6aP zax?gIGZ-s7`C>AN5}O=O-l}DTKc~9KmOG+CIh?OshWybPwMH>DS)Rb^d<0_h{#2ID z0~xvv??#-O$hwFt45iLR~jRG<$Way{&CQ%7Ft=9>Z+)s>~CeKw@3&)k~_L zXMS>Q3Ot2?&q;BuqraB@_BIgppx{#3e%buc-o+%$78}X)yo2fl-e1DUcJ0o>HaSm++%WHtrpH7d zu1l18PtwU!o0)SWvl#NM>6Tob5q{UPZ&vaSo8!=2yc^D#vXs*7Dt^p1`cqw=A4$u} z$z_RpHy)9;N0Y^yGQ5k2i==j6c}_CX+*4ovsjYUAr1KI5qjQ8~_ry^#Spe64XL?Xc zd~;x?(pN|-J@s(1+89Cf@;lzCDG?D-vWP$BCp)&EPS^Cj+SbIXGOk`JA`kG_99u@r{g~kB7 zhALT`%OS~{d3L#a`gx?de81}*(!O%?4C{L?LvpQSS{4n%``_%VaHh>(3I+CeRUq@9-!xWW zw??WU5rNhHH>_Bf5GE=>{Q8U6TskZAd%|f&fdL(1$#`&ZS9?4{x6fXX4W^4DNN>E2mk_(yMG(DO zql4ltCd`4Ag?NPKk&bFDneLpU%9MHWx5zK+%|7BxmeFo)Cx^g2$!tX@Ot!_;QOr2xsi-Y2EjYh|&ajvEi^7Xmnc8e^dEQ zSSo*sHGlEDa}6qp+X;A}Gg@O3Zznd~MC#J1u|YxJ$}bQ@$`BdlG4y02Os?Hc|INa- z-}Kvs;wz0iNP|#Oiz?Cw@81s|k*ty4D+R#$vlhMr-37ooa^g5WSnW7Y;?D$kS7xj~ z8Qw&za6Bc?zc-l|UBv5%CtI-YQ|6OdV>t-Ub~j)U5p5fWMZfPHSgsY6!LW_;HZ}O> zyYu=rTBGig>)f1yFpeX|`uK|o;v9D2?}gLG#d9fbZb*G!{+j1MPF&?7@Z9pn|BwTJ z`5}lm{0eZI#pHu>tybku+ow~%xd5{M!#%E#=a#t6jHrYcqEU$B?gu!uN|xVmo`GD% z7ZmV3=b02mfVN1DVz{jKrbH2Rrv-_(c>$ZZAQ>OvAcG-ElAT`g|sd`kg zJD$v$t8<^4`qrC!iVz!{{LQR%cbfWYH$uB%CN{}wGLM9UbNPnP&pO_zoF2TTO|8E3 z)4!JMh2St@1aH^2e8I!nkorPu#>oNcsg2q+`N4!$Y-LUiXh& zkU$4-$2z5S8U(+`bL-@ihu8YZq=ob1usZk<^^4iG)--G#&7){8rY0r>XQ!)syT)EG z$7@}!Sw_&^V+$LzGnM&R^xbM#U!x%#ozrtwm4 zb&Z=xbg-yikgECOaqU>q4oO&R?#JchBjPo}0A}RO*BH)e%X?k&{;t~5|A_@F07tO$ zix7bPSpfu20cLcyMz1#guxm*~Rj zr0FRlXhva4u%2Yd6>9z}BDI~u3Tw~-L%KM*0)FOr&KvvuXgfBD!SJ&%JQgL7JL8Md zjll*XHhsCqW57RMoX?Py*|7Z7#M-(4vm)|X4Wv%cfvhfrMJoY;#=O86Pt&g`jIdI%xqYrB9FVlRTYxHktp$Hd1(e+A02uZAN|PS+&n% z897j)oF~6h?S8-u+lbLeJ|PXa3NJ!z51*+ny3|s?ygdE?gNdlp{Uyw@}Wng5V+sn z?vfW%=REh)(3*3A6&?H3N8hpBNgBWW9^?7{m4}mo3ci9ywC;uzEiMcY4BUR4%xnF! zMMYK>fYy--Tm-pWS_pvlJi+uRDknCZN}q9Gn1m+2;cV zV<8Ih^NWk`yS8{7n-MR{ZIf*30{!WF438-Q<;?Of4e8f#&kG$N`?b|qwds7gdvYb6 z#0N8xQVR_h^NvS^`c(I*KiS|4+vsAJP;BUY@TGsDzIM(l98}o#9=Hz8uy_myLvcYK zuKf!;dP)|_zh3TN^F3k)6`S8!G~EqAl|!{D8FEbf{s}vQ3aUY8ymicboA&5gB+I9Z zYo$bu5dwe?n)M zn9vhK)hyNgTmD)Xcoa=B!$vGo6L1|_J**u(KAjo z@OjmMlmE;vnUnImMS1Kgrr?lazwqkjA@}i{gN-w8?^2a_b8Fq6`JTR+kNx#SXLEQi z50jxR{&OVWY8qdCpMK(Zi2eC7We!f#UN@<9wB}MY^a_t@)|&66-Lst{b*Uk4xk1>p zaig?B|E%lcs9`n%|Aq4PT*^;Br!$d0AEFx~}Su+nhQC*U3li|{kd0(MXBRvH)?~CLs*OfH0YlF8zg^#?T)O(K9=MI1^S++ylNKtOsp`WS9AV1^i*kJf zw6(hMTc<0v3&=@B&9AymPzuK*m?iW}xZ^?F^0)8)oyr(CtpskfqjoT(_T6z9=aXAz z{Y@+ezcHTcZ`J-!k!gzdDpvJsbLI`cf^@Ye9ZKJNG9Y=?IX#9hh=- zDV~WA2~&xv!7)k;tImIeR)@8%87MGm;g20FL3H8V^QtX52MGF`3E&Dn_zFE_*#0k! zARY1uJ`vT$u!*w}=jQT;i3S|f>!>n_gE9rqPXucgjh>0_wkYyQ)8q4XhXxiJ^8tWx z=8+7u$cQ7>z9IUX<;M-^i+%O{yXhLN(1yp{Zs}{ebhSGz_uQn1^$MO>THC>~ZV&ik ziCVr`v<$gp8M4S=@}1ZnP!9gePk!Z5^V%R8rmz+fB>Nlw!5A1G;z1?>9T0u0R~0dMqJFSdb(qn-RQoS8D!%2I+e_K?**=Ka+@ z%ruF$P??!n6tG2G?}zYT})9KGg#^k;HjUZoHYT*eQFFs=0W-K zadQ+j78WEnnQQBFDpp=+j?14ygdI+YdET5q*8QRxXvgc3!7ZPOAm0V84oROa`6kc$ z-+b*B(xx6rB7BReWMLTXugx-w3_wPJ60v;ig^-seXE}(T^>6onLIc?)&^i#zKDmc~ zFhTm93vVbbEeTNP;+09UtbF-U-uJxiE!Ecz^g%uK&br-@pgEivXeabm%HnNv6hp|Q zIpr(6$xZFVKMVf#b;+=Fp1Xi=^|y=)5c;5yrNBbQ?iL7t-RSQV`W!Uy?!41)Iv6KV zCoWdkQYQb%60P3n6-&{GJ1ds*R_sxZ0W!Z^3~vqlM}lEAmznuz<_w|c3`}B;0k3xh zlD-+=>;V0~A5Y+tP-;2* znrPuczhEar|sTp#9O}{jv_=uf9VA0_|ooC*c2HM?eGWxN5pL)$Iv&k$JmsgN2~mGM4}Z zPiG-YN|GPP2%DFRR5B@omDeIWtMo`%hXvA#SD7Bh8{G;4XT6&k&__lOo#|9d_UEZFR{JA$slA$CwyItj z2jJ!`wy7JrTW#iGnD?Z*2}TPdDWDCPpc_yGpg@zGHf5u)r6xxxF5y8 zYae{LF-n#XcsU6ShBwluf1wXOShMpGt=RvDac|t#W*oqjAtn`{C=+L=MRP5|eJB?~ zv`<4SIgd;PO`js-RUxOuvAqhc`?ikgl^OU9R{wvl$j4nfv%!*j$C$Ky>oL0b{QlRc zxihP0LaLeGJgtpo=Q*SCqojoq5;|@(XX$s)x{QxDrii|Xi|=p1NTLAFK@KaTT5|(^ zHW*c68HjtV^LqDwd!Aph(7^z9D#IMGZ9Tu29?S+N|Lu1bX9c_q+(x*&pl}fa`po37 zRVYM>LmyZM^$20&y?myOi-`N--V#)rn=D3bSMbpnq$cdOaD$wC8)lmWmt;kmSdnyS zw{wC=!lh~3GelR?-~GZhWYYB*=E;3z^M^61zfaqISa#;FHDAGJ;5NqdsZ4pPL3O6p z*6Z5R`&8zQ>wXJC>_S8r1A~|tedCc7ug6zvt@_lVk5p^Xn=N(o`;!Nm`2GLI(U+QGsm(SlGIl|X>Qpx9{G7NG-8%+%}2-l z-{Tg545P~!;R+z$upZ{y3Ak&0?Tm^&3sNMwGAUm+#shGA+8=(PR(kY-0gd|34nv|k zqfeAWt0~E(5o+q_2xFlA_p!z$f?+Au(?hi6794Vkhxk&&vwXkM7gU#nndgvLH*Qyi z>WT|nVM}QDTH-skCJSqjl3W;Q9ZqI^mD^`Ef22lOv~-)Fq$@J!`Aa_2_=1zqi%Uzd zSZDS?XJa7K`|Kd64F+()gvZ5XmlUN>+!NnFE09KvRr+E zWGLITcYUO^1~8H7PQHI7Puf0jClhd_z3g1)KR;?4juDG9efz8#U15N9X7}wwN|XDAsG*Gz1)l(~n$eV~A>y!1 z1~}|s)8autVi+VSpN^is8Md*|uu)DfWfJ?i`m=leATM_nWZCXOb$*dT2fEouQ0LOy zfYt)7%Bv(tTlY=*Jj8bi`q|rMghilzQEop)xL8&_Sz#a3rV#gCV3^3z1MYgdn#S-N zD4#LNQm-&fKxwNFjs6e15a5hv2}W>0$jDtE`S#sNEt+cK%@J!!`b%d5`_^)aMz@*F_U_SLH9>jANysIO$Ty;vk~d88`l#W1RW&KwY&Jo*r43N2 z!sEUnkZm>C;bd&cQh!z@Fzp71N+$+-L_C7|QMLiz{(BIrWdoJ}2mciI?&BX~-3(f{ z3e8`LGspgPUybBkcAIvxv0+I(Iq%-p)E~-HmMzjUj0Lx6q$~2lw!pKXXE-Dz5o-y= zt?jLV?l$Xq-`awkSv?1*zM)}ZYbgjOEPH2>T2e;hP<^A`kG^Mg06Er@N(T{0wysEk z>d%c%R|*tHto0tiq)=7mFZ!2>1M?yi2bUOMPKX0bue@`@YAo4e)JGdBsc%a<5^p#@ zyz(GTG(saK-BLrWrHWyDQGROw!%as};P+dipDtCQsyw|LCnO=!AJy--Z1py38U96ovkx#ObDs5*X zAL89#mze`lx%F5d5Vl_22Tw>zznL0OP zAbqWcekY~m3Omwn8XF@@sdEtry=T>#{us6!+lXIW3tE^6-$Q3xxqc$Q$+22fVrel; ztAA)VyP-V0!o?RiZP5m%;`|Zi!_;Jgs-g&aDpRNd7 zTzbGRJFLWO1p*V0})~*cj?hRKY`Nx)AuZ z$iltk*q_LTAc6SGT_>XG={1|hXQIRFx;K~Z0msi?&v{#4@=xv`KRdmiQM;OJD_ZGk z35uySdGy${?YcwAG^`MSrUHwq6xO&eqy)1{cO~wtOVH!XFnx1C8ayH4#|c3^_2TrH z=Q``^Z)d|@llevVVz$yM8av7hY;AR6zqHnsg8q!~zEiu(^XWOHYNNe|VJsbM`c`!_ zlAVL+h2Z7+&$J)@tbWMQn$4o@cu?O!Z=D}>VQN1(h`9b{);&%@FUCT_bWqC#lc+rB5DSxc&V4 zLlv-8%d4?C@b@|p&_AER1Hr0$z=Xgtek)a^VuAp!>-w;x9co|d-(cF53(tq`^5#{j z$A<(Q2UM!V*_`rRQK1{Gs^Z+HWI<<~y+OjBQI&M&TdjM&4aF$8<;0G7vlTYirUTh5 z!}cSmf%`J=LUkFlpAJXHBxNY&sT#;#>Bj&Bm{lX(X~Y@B*WL*hXxT#F*a5`HI2VN(e}+wCx@)_g`u!7IeDXY9U+OTKELl$gtXh zW~dyDPz?C0mi1j=M0RhFSiph$O4wId%iJGwi%GMmzNIc}b}%<8o<$rmj42{woKug87@ZY2_{`A zxOG(CjNmX@Ae%kfANL1=%fjCJ zODyhMuIGj0XzFTzQrL2L+z&sNXgGr!D*`6X+z&2-N=*0N@*<&mI_!h?=U5cf(R76U zkpvxFQ$w!jN4C?ouIP(psLpMx`SB$wHMeiyCgyvB8ciXTm3MYD|Am;}&nGJj$R-Br zpQ_FDj}{un$h;t(z$5Cgq6_q1SRfYha>=sL1!hi#cTY(I48*YEVREy+4OilQygF02 zyf?vbKRe9J=yn3*Yn<*cmr3#41pT%C0Qd=58ku!7jU_xv;ZS4#Rhq z;^Ojnu9jAL>{HMo8DCQi-GTEbc4%!dkP@$VZOt@N#WHJEF5^#BQJ{vWBp3bMjPSRc zewpd&?EI!CLoR+LUueES8#Zhwr*9mGQZ<*pJ+Be{VuI0}P`0pB=$_H(~k!deB?aef-Au1}bW) z`!77)lc=VIuc2;F_=t%qzG6U%*#C$bq{ZbVu(ncGVg=4U^*jBhWW&*<1WO@ezZrDJ=sWM^FU&6dN~k`d~{nOWY)x31aj&1v8u`H)}4#c z!;O+vnD&+-P|Gdw`5Uy>MiNg<_r|&M+e4z~ilOa`qa?_Lr2Q@k@P6Q#Yt(k412ZFgZKntiLBpzfZjK6wx8sDiozR@x z2CIbJx0+*;_?Nn3ncs!#0$-i4-#`k+L~;v+V2hpH61%=A^HB;G1)Z7FHuZ^YirYR% zKeDwO{Tj#}GbBQGmqrV6p0q({786|eP{3e`*!5a}3asxm6HL76tO$mrzaE{YvqyGl4JWH3?ptfeP z%v*hL?weJZA?|&ClCC?F>)`Cp|KPp?5snb1a*9u>_jHjAW;osZtz|EKD)zJ@=4fp` zmk6BWq@B+}sE3$PS{(1s(&)loKjl6PuN72r0HT5SJJF7(2!TyY9h~X@{u5;a=AI+# zBbMKH>| zcQNY3YC$6En8vR|IYpH9I_2zecfsa9)tWnlo4nZhW|>nV@CRYUhWCi3PKHg(qhaM;@1r-HFoVO2#!p^jB{x1ypvqG zjn(?~RT%%A&(NJ-Qd`N*+B9KDlPqYBSyx<0QeNI*fEJHI_9F@&%W<5=-~g+UyzYM5 zmp$DdWzw15rcjVjmimXXL4+h;?N94>4Szw(+k8-h$O={=^g;_j9D_$YBu( zN1Yi)jHbW205i2K22}OepSOR8e7-ze$o!<%Ya97LyvG~iMDq?#;5N!mgZ;&Q+o8c|I2+Q7af=xoWNU>Os#)) zy{u)p&=yTWK&Dfh?$Ngld?`%$1f_oRLo~Ue0mwk`@E$)B6aK;_4F-2*ALBXsLz6wT&lz(M1SPWkV72(F&9odQ~m2ZuX zrl)1q)dC~|sSjMy?klIZzH7Xa@bRf1EQw{+!WzlbkaQIjtLauptlw`L!b1`fp8v6o zq(u}@K6M)tvrQK4*qC%NQz~xiRBUqc^Yg*M@D~xUzPNxI=6z=7^4Q|iWQBFL_v)iU zTYOes^{Z$=*3rGnh!)tN9H)N<-Amq_Pp5_sQi^z+fPQj&E~(Gummm};i^dZcx2HSj z%S3P44QKN!wg0D%(*cfsKNWWPjp$)iZiyRIZql_ZT1-wkDcmQbSNj$hL355MNb{jY zs<=u`0=1!xuEl@s#H#1qaHtd#`ZJz&oEJ59JJx^Xo^_O_}Tg~ zywG3ohwp#|_Mxw&FPR?5+TdV&!Uq3`&^;d>xb3Fj!Eg~drb3aHS@Zo7!T@%okqDdF zVp=eALSR;8TriMbD0ZLCI~+=3Q1M|reJVlf;OYv42HIhqv(C{$^oSH+%#E=zC1)7h z(X2ZTOT@M$$PrKho!pJu54SsC$+#0e;6b}@p$;KOnttzj);L8kAJ@7A9!FpBW(;0D zFmP?ID6Q~ay!X$h{E4z&D?VCUiS6kIr)9KODjt12!1et)14PlnXoRiYuIrsM{fj!) zi`XoYMC^8h3uc&|(gJMHplU^6kV3hSkJ!oC*&>iiX7PR5zYzxTIl$Dkcz$FU&ddx# zf(B9IU$$vEgrC^hGL%(LhRG`(t&;ZAvx*Go8Gp$f^<~jo#HwoFS}DgsZ=j_Pm64pY z&v`HZiBDg$Vo0s)PBb7dNsg)rO=`vMlj%Nh)LZsGxOoW@C-Pq1<2?HIyMU3BWezw6IOwLDY?K5zU5ZlBN zIss!pSoxIpY&Pz+MRhL?w5fLM@!7}O0{J2ZNctYvw}=)YbdjzX>eOkv`&2O69&Zjx zu2ukfvZo90|1{LT0}8#J0g_G{h>iggz!K0hdRW>aV~PTrnPA?WfNuJfmOat7Ud{{q zLCr#Wy^CPUY9#yb9r2bCV8V#x1zU{Sb{MI45SEMXl+(`j%p%uujEi4BmYIi_#h)n|Kz3=S80{9)t0U=R2mYbvwGQSet))Vk%9Xz&AWt zsddr>%SQ(9bL$wu4246p4g7)E0hvg(8YReMI6=oM%E(oVUg1yh+tBXPA~_FWEWPym zxuuxg`h;B46<-|njPzgf{12qs_pKl!+w)KJOU$$Y!;@5U)fua6Ye;zA-@+eVVa!aA z(%jHJL>>Ap6Z9kq4yneyK2Xs~k7#V%e%I}vDu@8oA|qbIVpcU^+Wo$Op=p0lMXOOV z;{bsHyZc6H6cKyYwforf%y^i_W7cnjRi_b*m(ebN5ozL693(*ph~a?0|B?fypIS`5=}oZ4J zO&posKy!xjo&}^r1RfUxD?RUmoGtoEUCrP+@WFsd7MbVd5n#sr2oNF8?5AAYIvAaq=Pl=A%> zOsTWMZ&%*VRf2sZHANu;T+(^;o*y7PpM)t;wspaA{VT|+H7yZ-bjpXEL0*6NkR`eG zF1h4Wk43`|JNvj}s?*Zw7pVNz)FkaO4o}jPT2id32YMMi0mTl~$sHwPS1_7goSkp9 zG<~3XZ&K!v0y}4?#@De|NiTpZyR1W&<^1&2xT6r7t8@%d(fx^srjp1rECO2B!{k8+M0#`xPbmmkwmQ*d4Lbt7{ZVRgxVZ&ZBOp z^M7+cU}-%dj;P(=;JKAjjBt*_6l92di>!`#ZH4*+$j?{0VX5dUVKw=kXCSkaL##-P zWpZ1M6yv}htK6DW1(S{Q7KFfMI#{2bJ~VZX9(!p%O%XW)@y6M*2!28WOF>ohH-ndLrm)KV)h*vW4 zAutCAYrqPDVK->RM8%rvWO#T8V5;YGKr3L8VN-C43ZTb1j6#mVBn#^31){OU3hRZr z>Jk$Tn9@@F<==~eWPoECqQU|jJ3?IqcI$vC!Q1z*E@u#aM*Hr28b1i?wuMP*=)Htz zKlyie7U8;#KVH-d2s=>PzsE=W<#a%6&uga`mfq+$0nARti2Ce!<37spzn~`fuWNE2 zY!1PpTI4!R0JED2>*4-~*9SU^-DEJ1Vn8h7_Dr3{$JFGiq&xKT0z2OYozVndHC5zk z^`>s^6EMGguybqWE^9})go@^*eq!Fshq8ZfF?W%|d#lQW zfxBivp-zUErKqlMfWN=LFY$w`Yf@`ECj@=;ABeEkrrC|BhK;Fw%ktwA(}kAiYE3-5%gwbu$4i5$Y)L$Do&){z{mH ztR>uJ=KjbNR|OhF=gR(UwhF0z=;t5AI)x@;TJ%~ zHwOBQ(gipKlrD?0$@Q-8vM4Zl#%g4o{ZE73K_C3N=(@^el0P4%LkMA?IVu3{;B(jS zEDT0Fz|L43!Kzv9yZ#yb^J~Y*VVh{0PiJwH84LlR!QT~PXoieo5k^RU0P;}K=DnZ= zJ5$f7_jkMoK9DwouK}V|q`zMs01rMxd%2m8iU1YTzKit={t-+swI9_3Ub1X%j6ZGS z1Sj#|1^-P@(ZFX+kkTMpaD$9q2}q#{1cKwz&CUg0l1im->|zJtH2=Q1{zuSlJa0mS4QRzVPy}!5Q78nlg z9XMIef-d6MkC9F-t0a!{cqfA|&33Rl1)Ym;y~06X=AmBe?Abi@WkL?dX-^W`l#ctlhjYDhp6-EGv`ZRFqoh48~a+rB4iCGL(#RXj$=p$Bh@ zG=t7wUwk=v`+iTuMbZCh@7trAy0-NNK@n8&foSDrRnUTF4EApm-6ec+qy9pM?$Jbl+fRuq8!b zp!wYn0x#hY!$BW9KvHz$!zj06;b% z@FL%BqYY8&b5yU_qWJ!px8f)CHN@HauCg1F4H` z3a}hg;nU2pQ18}b{D&S0ar^)$$yxZ#@W_qmU98M|5$k6Xclui|6^JN@w>Zl(BDdZV zt`jIdofe)UXh`1)7>B^fbt%$TQYX$_{B z%EXA9_+&RMh%%y{43H4P@@sGEI9tpDT^z&RumJ}xZIB=2SZHl6n2qcQkD1q7unEcX zpZUZ?InxbGt#r+-vY)XzUL^I+4@+0b;KJ^Zn-G1!O{H-@6R&H4KKV3;+id0Li1zysx z45*DmLvQttZ?~R{wiWkfrmJ%O%epQ|m7|G5(Rh%B8 z^dRjx%8z!uzPL2{FQ$L#$Z=Hd)#b(&1Bwtf6+AuaY|=B)lM1glA4hxAAY;VC>QthI zt0FMo?~J@V07h4N#(eR$YYGr(?UxTi-xgx3_Xp2*y-apaJLP6h#=2;_yd`!>1tqZUbG_X$Va~FN_{cV%9LgY6BuOuuV7LF1#R8^8XRQ^hm z6TgFrf)zL0D`If}?6=@NR}Jrd!AdcpZo1>*5jTbCWF~4Nqzouu_$W)_twyhliW#eD z_)5Aych(g=k+%(h+9XTf)6c&0Pns%f*_fI9F~>4wcRz z-Z0tsBUwfl6Byi4F{QMq*@B%EMq@t4t!i4L#LBih---&Cyi1jSTPEL8s4SQ~A>-U7T zQ~fE=QbzxYB7W1r1Fu8Q)iZqrYIOz^ehvlU6p1 zMkE%(k`U=Bai|>|gSvFm68DZor{3DamXB9 z4#!!aMM4f$IfIsMP@NboiEAXqBPo~3ykP>-DA zTtenm9oFa8`u)D2R?5Z7e#6MHz9qM>i<)K!(mZhoICoJ^$^njddALkK%Rkx8-YFDG zMwatJNhh02P?Wac;KvhD?Bn36r&#H#P9`wJ`-HyK1%>r{nkpo9$svwZWx--aPjZix zi|NbbaRiZ;(1Kg7*91;;@~ES~mA9-PxhSKPilpr-3wcStKL@-Ihj|&*_dult&zs`- z`r=D=O0wiPk)IpxD_~|h%m;` zDip)i?ymBxr`&?-11kmZCQ1J_j_mB0V2Tb7vGm#$bW``zB6KrpKnchdE2dLW61t2- zl{I@Q{E(NrijLN{d56DLwH!m;&n-QbKHXh3y0#uBaA4EytEb0`>~j6_jn#;^ZcSD*vS+et2G9wpibR#qrp?GG;T zFuDL@A!lj*KiIKNeGjeyfnTMBawKtE0DJ~jCZdHq_mUIXMzdYZpkWWVJ_8SmWk=MQ zH`-)%t186BjqKg|(Jv|xA%*Qfdze4Vqf6N3B@BfKOCcdf1^OUT@xfaGYLDL+RO`x& z&9WjyI08ArD^C-EN0k}TbR)qRFN!x}r}NOS+xhVI2w)EQfGnF``-8r4qZHO0CehI> z|InEvhyrwUVX+;Hg?AFIT&0&=>tVbK|H1Q)#kQ_}7pLy6w!E?Vk0XJKcNi%b%Zz0K znVrq9*{W{FG)nsG970kq;GVomrPMjlLT{(TF?Fjrc{C9l!$VO@yTfQDa7kMciowO8 z`U81q>Q?cU0g_sR%gFVf+lm`{_1jxA+JcI7)*|B=GSQnA?X6$ewcZ5X-xwsUb#@?da(k(?RRRKyn1#FeiC8#lIfrWf0i z(9hdy#1tN0xYO2)@B4#IQ?ozTUse;6chWZ?>KJXLE8VK^XH3hX#PaY(kZKs?j`vG5 zck1?ZF0M2hSvzuE5|RWjjUA~A%<^-c(Lqqa2y4G(1^yA0yJSrCUsqZSnljRTz>Wh z7A|8nOIlonkQ9_N)8tPFY7l)FCBFwFoCj|#_}KdJAsx5o%t@W;8Q8~HC3L(jJXXhc z_S$%lKALu9!K;)+!sBH>Av2!75tk(u}bg`W9@0?o_{d@X_kkj96uFWUd-*rd)EQo_I8e zpcLHZfTL6HN{=i#ydb3tCj`#6%o~4w_#pus`e*i5HkyN?aC@<@!{|dzDAm;2`+9j- zWRJk*v6Z&wgcy*4VF!~_@CsCT2&4Z#W8-s9>-S?zD;cKaMxk891%6n!#(obvrJKU= zIosb@V};;n%)-eZd&@V=>V3RUPPaVQ{+DFvVWSy%!2t@Sda0tEK`@QH^OmTS*_qxV z#xrs3`*;!mE@6uE*ia47cGd!nbF`z^gz3~X*x}huh<)cHyv7^NO^lH*K@6-FURatO zI^Fy<5-0DlLgePgioP_8QFI5AWVDM2Nid-a&=7SNsgjG~l&nPzW=rIJ1mOyHFybSQ zmS0&5sB=Dkf4|ZYR~pFc5UNNV569yuCE+T`AyOsS%#?s9byF-bE!il>quHqbqAF#l z(eHkgJZ=;}bFp&h1z|J?Q)7X3=?P-=UShPoM8CfH&lu$&8Dm3XosT1Po}|&2O)|8f zmiIn!#1|+;Cv!@=^BJz)1`_{eM8)3UPl#ihX>4d1+em^V?}dZzeeWq;fflBTYQKb7 z3qvsaf6g!VtQ@?9sa>909FkW_-KnhfCmi<+s#`?~m01D69vTI#mgZX#-uVQ}s=UAo z@Lr+^+YJq<>7D!N^CwBTx?304c6t+JvYdL=XueRw2`3G8U?M8P;}c6Qux$mxih%}H zsz2tW_x{R?OH#?zaZrm^SqmB@F&U5>JpSY455y#}<4Z~uzZh3~jj@4S(om33$L~N- zzI{T=XnUYSE;0F&RcHcORiQ=()FQZ5&eDkpPHdTc1ZaK7D;#*0_vhsKfc|kmBrDTL zclo2STma$7dW#7nP3RinU;#R}Fy`I=NGy{k66$U>2l&;Y%$m1<(>3s$_aRxrbHf3d ze+zHx0uyvF&h_I|e{R&s8W0Src_e-JcY`%}S_+&k&OpS*zr|!D=+N1+(%1HL9gT?^ zR0?LjH7mJs&S!={ej}>@m`z_VeItN0dR~h(3emckppqp7;*#OgP(sAZ@&pp0H=#N2 zV5^ej$iM`I1V;U}TZmFAgaZePl&=~Qz0-w{2>rGL2V{NTv4uiK8^0l>el(FFdGLs{ z6UP1KoDjo7H7mtD6}O#lC2zkBd)X4u_dK;eM98#?Ma$~3SzqU`>$Xz#+Ob6bLWQMvHppUg@j28znv zuj(~(pqA15W`(CUvnh-YLh+F#I1t%o$Cwe0j~ndp0En6vhk)d40r3;p!LJRdh*83N8y?FP zt!muL8e(kzjA?fQzA0B?ASEHr(bw~L!~Su09@^@+WrEq|>$1jI`H$MM8V(pBy43Xs zB*gI@NYHxX!R>CoEQ>SVE}O!h&Cf>W<&)s@t7wNR1c$gnPZ{Gv;vw zEaXSFbJY9Q=kJHRd_G#AyF~hU?PqMRdaen&=4z=i)bTHXF+jVXD+GqrO`?mzpW%cb zms<;xmZPkoj<yWJm$o8|ygYd2M z_2O8lV{8BSz`JXKhvr5LyjJ5u@JUNGTB^~})pERcaWyc}F0NXy21L`f?j-QHweF8?7X~d6O9pcgbSQR` zRLXN-6%ML#Fhk$@*2^-CxZ!irzWD+0d2FHsl7pomL0e5v`bPkxC7af8?fuHWCr&vqe^ ztW~R*d5j-fk8gcH`9Sst5k6))E<{6;PrB1H1nE5b-*;Y^EbXV)7z~252+0O)_|A{< z1dUKh98w4LSM`(m70rKr{DtTW;$p6RQSN6#CLcqID?p%S!NRLc=YBFAjjmZaAb7@a zqpzDF>c>Xj->VPe7`mIzZ2nsiM(3NLWf?RI$do}!b!+6$9pSegwvvW7OI?d*_ih`I z71+8K#I_GM1}ldBNn(&%5+*(;;}Cv%_=7?k9`4fjI4`!sMN2XFz=m{?Yy> zkx}dq&Vh|_(qOo(RVZgFj-}fC958wV*VDQ;KS1$dDdY7YOZB*mtU8woEc+WBhp*(g z^sNeCfDVqqCymFl$HQo=D?#9*vfKi~GH4nY=%R)0?FR8-Qyio2k<(qKa5RbDLCQZFx4m9-Yk;oI!&@KRL-2Jd^C_XHYa1`qXyA`}jW0sN0 zz^;>hqzzD0?Y60xc)$)sQ}q88eA*XNYo{87ISQuf%u6+*UK}nRPu3b&{T0CYuA8TC zf+iEW2g$l@*p+97j#MlKNoI54A)1C14YV1TLB*<@LX;nr&o-c*oxVcQl$n{LsS%xk z05*s)5YEJ-Iy}}+OXO*s8_XcB>>z9BV~VDAA-99^b+(wRr}7pU`<~TUIyt@Ds@0!$ zS+L(z(@<{%L+$vBz7~RRxc1F!ERvP$j07O{WMpXQgS7{eRUbjIgDzfXGz?yiFeRR2 zM0Klr{3br^%gWCX$G2dTme+K#ApA{0n#}F^@@{?ZLDe6k_^{2)1DYyo31-+bN0bRc zSLN+s#+Vu(#?>*To(<-AYU;xVFvKL9KXkG6{wf$cWx7dQ0Be@6je{9_ULQ)66L`YjrEL(_P})CGlY7IBMjG(q)!#5D5>iokXQM4PZ8Bs_h zFMd{ZU1JK!9$VFc*^XUllg)ZK>5x|&!qZnHKgF2a;tu1vk{1vU*YO=FJzTyP5~UuFx-pl3~6s1 z>7WCCI$)ov^U>W64Yiv3e+JN+IhF?Dj4Z5jXJpH+s7794YEvt(#f?q(ow7SdPvdsG4@B9q&$h=}Lx}A$0jE@v--1)GhGT2ImkS*3-erENaf`qWP}`wD zU#gc-OB-;y*mVcG&*4(kS8muf>tYvZqHhc)*Vspr1c?Y%&2pg2SKRcIRtl!|+JA;T zfo=-V^aQAlH)a#o2~4eXdgT76J~OD7?!7GnjZBg%8c2>yE5t&+1~CzY`HP}ff}^dB zy2DxDvix`KByG_&_yl0^kFL>|Led&gw}^oH9Nk4cVo23-@zk6zDo_WSIW1MqS3Fi` zJs|Xku7e8(_QZ=0pBlA?6l;Q1L`yKkmUny93t#&o=qxe7&<*RvFHFmsi#GFV4Awk# z8wB7;Rv#0qb8-PhppONM_Oz#g)sp!S%^n;8ML5)m?m*H4n-3lU99py?^@+>RWLnxy z*Grlw;0#-fdOZECO5&U&Pikp#ypSU=V0)$B)R zz_`5sB?gNB4>L4*2DQYI2nY!OFA>s6=?mKQg-`VX`0D?c(igN|(4@%)2h`edv^E?)$t%!q#Qq1u(Kx$}*eO%y4{qP= zw&#-rBeFK3Q=8EFi9To#=(Pv*6AzSibhQWc+MM!FC?ZaqQ?AV^pP&!_#*{^EnxZ_5rw!po3m*rEm_oVCl zvImyI3iM*EpSo;hLGSr6^Qy9dY-io?I}EudJav-%ryMecn4)XQO)1!*u65X}b6)gS zOM@L6JhhtUj(xUPvreh^R-C)^$zSlXI;9RV_#PH#$fdQGYt|`|=j;+ViAvQ~Cid+{ z-1Tu0ba$-Y%odRG^oJ{Cp{Yo+mz9{`R)Oe8TE`(6j*A9 zHiH*wHtz@o4&1?A`=K<+RXKYFT0HGn7Ck+)P80Vpbk2u$gsE%W9_v=JE>B(9Y=`!! zI(;yE@oPWLO0v`cKxX5~hsn4(#z+5QVKhohlM zP~*h!kl8fD(g8zm6QMPa-}anP)4JE1q9 zdYP6B0c>J4><*h9bTFS~q4Ox>eAtC>%_79A?Z6yrTg=s%-H&s}nuhXCsky2`|7@Dz zhGyNeOQ1j3<*rC=b&cMsFrB7L<5vuOEmx2iAFA0b}-ChMkMPh z8%C4$I;B@we1(kRE@kHPlq%Qo%?_GHp~FXY2|5I`Umt8;vNL81_}jk4Yjd7^Q2hS` DTZt-j literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/shift_from_current_pos.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/shift_from_current_pos.png new file mode 100644 index 0000000000000000000000000000000000000000..bcc1298670ebadd57fefbaa361b61e96f04eb964 GIT binary patch literal 119341 zcmeFZ2_Tef`#;{IQ%?K72rZ{o*0Co0mKc&{LWsfG$1)6KOPfliT_sDYoEB7y8e0om zglVHN6k*Dike&Z^KQqcQ=bU=a`M&S_d;guKW_#}Yy07JPt{rVq#2m<8lw~;eWfBtB?(QPCj@BekYgaE3H#-V^1mC-oZ5{0$?QGef z7MC>=lU;^W5tD#Fq+~@T#U#zxzqcmYxp5Z6lWC4FF4oH=G^IquV5yax#l@H5RN}+%#VP8!toQw!g8eO8Z-UzR|OhOG_yEr=A!CzW- zL}xO(M9smI>apLSxY{;Ir zcAo5yfE3`2#xgM#_$m4ir^aC|ym7Mzvau_dY2cR0;+Dy&a9*gYVJ{?>smgK|b>uMK zfk^NsXyDzPBnhfsb|f8=ois3Z=pF+*x%z5(TDv>o$+mVbu$`?hdo!GbEJhZ5;>RIe zObjQ>CZ6OuuoGuv^nsxxZQzKUD@optwsu~etJzml$Yd9aqx;YgiDWl7J0eF9I4fFv zdXlL_e`Zg1;hc~28+TBjA*-Vg3`ejUeM)e&r8uyED=Q(xrUiYz-p-NaFtD?@v>f{z zSL=Zvb57#rU~NmLvaiQJ8Z0d~CkOcHNhZU3gM>Nw>wzD+`l{KvAa)P%k+Tn|;*VeZ zl^dR4jp^?!2l|ScfwhbGfa0-rnBq5}!@v$q%N<=Y38;d}P#l5py4E&!E*r^Sjuf^5 z*^ns|vMX4z3;IIUn&?dOBzwErs*zpDNcU~+?5(|BfL&i#P;qf2A=9If-QiPfFL$Zj+yl1jR+)5$}hmX}ZGxUq90&h`ZZr znfTdgxlpV(8%X1gRAlT8IqSG_*5P*DW?Of&^_$50PO4Npb&A|Zbe{DtUS>v;vbqvq zDbpg7tO*8k+AbS>ObMH4+D?+Pu#>l$p{f+#Nz8H32_?~cJtvYk-iQQTarWJ4sO^h) zGVsRxX_M^KHGn&&lE4i~;D(cpmL?5x*i^!orfa0(s7w3vb>URLx=zj#aIF;H2<@va zrt1WJTu)-}qpsntZ)EDIt)=H>x>=95(QpHslZM(p8=ZW;tO-&sK$9P$Nsnd>G#aC8 z(R)cfLrJP0qR|M^sNtulCP{;RB+)+l>hN22kTUmm{mck@V%qCB`I!==XlAZ*el~E8 z?fMN4Hg1THO)fg>8j`Rctgj-b=O>B7J35nyu5x1R@0_VRhT0@+EfaS$2?sGm8=TP( z_QqKgHi=n-#^81Xao9G{Pc{R zLB9vnrXh(}bB47YT&xMUWLqRdL-bp1lC6Y`v#l0F2@RUAleRC?Wwwowya6$gJ|Y{D z(sd#sJs)Nx+L(MGv)AX7Z(vHm|PQySn7*f8LU0}+Rp z({|PKBKnB|tq_O+zHV?a#Tk$|mg#DP+du(?;Be8`!B)$d444Y1bC%Lp*OmYY`05y{ z`q|(%Vc+Q+skpH|zC)hG2R6M%o}THilwS^po_%gEiY>=%j(x5`$|b5yBu% z)`#!@7ImN(8aSZNPuI!R@1LYj&rwnW;osk(4rw%ATpQ3%*U3QaAEXX6RuT~UZ&HWT zbutzM>Od;m68|K1$anmS-f8)|gZ~Dd&_+5#1@sojbVMC{F9FB~-r=j~8T38oiF~=} z44?+4(L+`yQgxk($SyG-j5oqC1Zf}UEA?n9fW=5#Ilj^e;nQFGNlEZm5(u~KxKc|3 zo|>}vWNW+>>^BS-*nXXZSwCPsDxgiqC~891F&xJtR}9;z5EVfbHNrB6;~R!O zrhqlXZ+K<|F@!p3EgR3kcS+(9iVpK%TvsB22QWp^JsTN^u7o0W2`*?pu+n!#5qj#{ zAP*8`ex?YMaf5x0uF;Ri`^Ml+wFkHlaX&kb9CpqhiE&Vrr0xvV8AFU?EcH)P2lC}6 zg&(30;k*W-4(!ojNCfsbc_#@mj`&|k5#MhY2B1d}QE=irEP@)Tfj@F~s2J$c@Njkm zBy-w7C>a!eV*c)L=#3L(b4JF9Iykq=kofLzN(P}Lw>amAc&FiwrZ`43Wu#gAMt^hbDSgmexMbq9lg5)C9EE|%be$v;3D=!GQS zPz5STz(1PC;4GH%qxqPg5#Zjp3>%&H4>Rn+)h#_5XqGyv6k$FL2R@66P=sC0G6sYv zAq?Oe^$uPKqD-(G?6;WT8T1~jGU*NYq3?^z*%ctHT7{x;cAklPwFZ8*R*alIk++aIp=p*RHSLkNPb^&g`R{r;vrrGW2Pgz(SuOdC2lpeKJ%*M`&*{yDyBQ=vvd{hRW{@>q!4IJqH; zsj(b)n73lrIdmn6s7}i6X~8S#mvNeV(6F=Pbb7h853!H_yodR%lc{9~jdhBrA9OQ0 zD@w}B$%sIw8fzPJy2p~@GMuI)^;;`eTwFp@WT5HlFr*bLB_kpOJ$=-PwC1#dNnbZY zpMFoP6n?|$wEp>F(1gRVhAfAApa0P=sJkSJWUT+J8*1bXb|A<89jdEoiF?_&p&Gn{ znC*HMXd-+o(ttP~ zyq~%O6~6z`&MD}(3srZsDpc-C(zcs7c9T(9nmSUwAy#%OAF1x=#vy(7$x6z_XYtyu8c!DYPH->gnVI6m(CPoXpj|$gWZ&sy3|BsA% zsUvHn*qI0Q|1?ks87dH11;+bNa#%Gv?3BjnlM?%pW}x~jih5DC4P?Q= z5XhlNM!R@+Ukc-`sxx#|DD3Fg*$X-<-g*QQ1$??6ezPeBPe9SCwy&*|rnQZs80uw; z;SH%&Yc(#1va;kEv=`}`qa*!{Y}_2a+hGsqi7-(2!es9dqD|HP5iE~HIba$a@>TOS)oRjQ4I zi?{81utGGG0Fu);Q~~S4qnaEE+8k{Oj0a2_S-LRo3G}-a*@Kn-b;<6%A;&NaA zks9i>q{XF0WHJcIwb{czNY%AWT#2CWFocA;J!8(`&t?f1 zCs-dFzu`c)A8Is%(Lqy4n?!WOMh8&o8CrXTMh~1+2Ez@Epn!XZ>;4?lhqUd!Zyz*z zGst~lBR{YY0v?X*V!ILU1rD}5)PlyktC%kU54Z-ZFTlJMo z;M%^QCb&*T%0?ZvT+mp=CbSO#;UIdP3~;*G_fXDNw`$#7+N(5UrCY(^YzsouoeW~ z6%W6GmaLHhWyo(}tP;BpQLjNlK8L0!0fVG;{sT0wAkgpiv8l*1RXSR@n zfKPD(?1zC2@FP;}^&$O0gG!h$`ubaI;KHzS%Shikz(KYT$LJdB!;xQr7-W!t{WfTZ z1?lW^BD9?UjH^R26;9-gC6#Q{hms^`U>C`f-QIwd_7A8Z+}ap|_*is-a2cf;*bofz zN`8ORQrFURCqhaLOce zOAcfK12``u1NVh+5PdMvOX5T%B_ue|It1!*A~+e&=l>D7=Ty^v!u_zh{-5c=plSUd zN<)682kdm^XL^8Afd7}$15Yx=nsbkmu-w0^*d!$>DJ>$)sU{8h5u6lMm^jcp*pK`- zCJdZZ=g&L{(c9ApyZsa0yJ_cUtAcLhgZiEu*$r+cQ+1%g9a%Va^d)v981_@de=mwB z+4<{TdeGe&_-No(v1JlCF)>X|RnEGaaIYvV#QvSNCuP_^a3h?j-)7Daus5dYjffPi zi@jAxttxai`yG-7_RiOlf?XzpgQ}#e9lT{bxrHcy-b7<}1i$qKHPKY&zh^V!dk&6+o4289`?ab3=htw4 zjrDH->X##0yqsG7{{@@@^8FD)5nZgkyc~&uCSIUp6wc2Otg$hW8{iE^M{!UgHg5eb zgphuG;Nb?t9K5vLHwQm}1^+y(Nl8H?YxveuG9$PCZ^tz* z#~94PAH$wML^oiU)QAZcsX>zZv3)QY`me+|j;9-haeABwRd{{7ogYSl&^`Erf-`H* zZTLh8k5D`_;{JSBM_XI;GyqkqgCoVx(A^q~XsGZc3HWSiXg9pCYY%;1&a)yUWZ~D? zdk!%O2GRRLAgHM+CMKQ2i1HTv4MX$qf!GNQ5q*9BFo|MpjZnP z`v)4qgX1kpS&`xK&A)Y|Nu1-*2PuQrCJhZe2vQ884Wt53PC)_0AjSA5NF*3;q8_9( zgXM|@G(xTrvJaB$*JyrFF7|Jet0ZJy(ozFr6&og3Dcm>Q94yy?5Nohd2co0_X#e+0 zltcI+iEh$>koG?zPi}VlZ_KTwWd6)j|EOB~-zQN{^e{-GBdl`Z=_^D}vKNd-{*_%0 zvM)&#;lV?l2HW9RxeX0JISKo}2W4d?M1V95eZFF=wA|O6Y>*8~aWsCg2@ZVrpE1Gj z7!>{CItVwI9GU}w;ttLMM9`zP*g1hIDrJb^*ugz2gM2GkVDAuvzh3;EC5!*LNL^A+ z948|4b?QrQSV2HW{G0L(Xx0Bg%npy(f||!SDu!ABHzNM!=>6ZARu6Q=z6ZkofAs(< zcpT5qxq_c_1!!*J=Uf4Met`XOuK$|3f!H(YSAc|B{%Z5tY`Y& zw($1*)GNPe`{pIjFCTB!_^7;B-+VOw?&!r5ysLjZ9IL9T9Jq1%tZHGkbCVYH8qR;P z^-zkfa>&Y~+s3Y(kg`Gfx6O;s8Cxx$_1-{o)ka%d(k+1_%f;Wwb)UHv?A%+_cc!kg za+H5kMTTN~Wm3~E>TZSpo|eK;!7)4&rY&NOA4BHP2wc|{S<&-2D$^@Isxqc_%k%ML zI?F4Ady9i}q=UPu&gmhK#|tiuQR=%LKu(;xJd5<~+`O#9*HYylZhm+{?B6@SHDtT_ zZ_3+7jm8%J`a(=L#Cm(<+qdaq=$p?or%_r;-+bOXju}8D=!&pvGL&A-T=ezVoEI;J z7O{%znkZ<&$F!KF_FRmDI#qR`V zMnZAL2ekX4jmixC9*bs!?QS`-dqr2Umj6OsI7}jN+$%u4Ny3YKbU@`5aQ2E?HAX&_ zn)80UTX{E5VdNDVz}}2LJ+ynsPI#?azb||SMd%lNfSihq`0c6@yy7uiwuqJD6y>%X zoqa7YoIz1=yIW?O(DJ#ImhzYnyu-Q6^KtexN?jXuE!zFJS<@&pZ3qF!V$H=JD)V^h zd++gUjZiMeYLKCE9R-KZ&d^q7 z_18_W=&F&a>g#R_x6_Hp6+9s#+~4;!xzHqY&t#c0vEAew+LMCc#9pj_Ubp*bM$V%_=PYUX5 zQR>GD_}5?G{Q2z;kE#PQxd$q`OxAV2KYC?hYDG|Y&a;OCe4>FLbo`}q7bFR>mRI}C z8{9m>4yBw2z0VWEFB?#ve76J+7!Y&t;xEjk3U{>tw~sGFz$$l-D+4vZSJ`^W;2jZ*=l7ZC_4VGNLQ%0L{hH`xofT z5bri8qlWa+XW6mx4cRlRbRsP2W7^u1f&&-I+g%zp`{TeYz=rf*{w9Zot<@10b4XEs z_C0;=Sytkut@Cj<6}&T#JYCINZtXK+2Vs&8ELxHq0ErI?`{PAaKPFJ(~x(SiN z6_o3Ed%G#K`-!PlPvzW))f4Bm_S8j;W9BL?_+{jvfCH#k>D%gg2awuahEDL6HeJ74 z7kQZSb41oCRd>}V7oJGX>K5?NzLRW!;rzVMruyre)%Od^O9!=Gu{vH%%Mr4iPOuF0 z?rgX0oj}hx;%zZfpM$1NqjX#6H6BKrY(RbQ@n?Be+CRj{92A#tTG(IvOiSlcR&Qz6 z0Z|Jd)6P}JWkCV~pYF|5a@(?|_krM(Xa4*b$1%&Ir?t!&!6Zp&Kf6AceyWPPz6x*v z|0ks{!ekb+3L@oY>~&)-%WJLDD`z*~s!I%u$m*$9$Y`>(>`6>(+&6ZG-hNWF-}2p) z`Q}(;kGHE7mBzI^A7J4r+;fZTIx#%1k|a$DKC+iZDXv z=i|pKPQ;qaU79$OJ*|g9zFK)cS3sRu)X`RV&NR&gx)nYr#~i3jN=xKf_mLG>^+2$5 zedft4_@IszO7msPeTki9ec9&hj<=zTMx7bF^y5eAi$-!p5IXdMH(gTUOd&yYQS*Gv z$4T@;#cmfDB`2d>AMtf~eB|>2fDHfQ;*y~5hP?Kk{37#* zpWZ!43+jJDzFqV2N);>a;Oc(kq)Z=E2LJPY>8Fs!uu+loBDN5WPBC~?nIe49g=P<^ zrQW|VfyuR zpT)&>WR%9-Pnl4pal3r$j>(mYX-y*imet|0<`*tHkHq)ZNZ=!xkD7(}NJJ`JT|A#6 z8l|M9cUn3jJ5tPA^^7D@lW=GvIZHt=S`OEk)|8o8E^~5j6TL3cqyFV3ahvQtiRFFe z8DI9r^!LE3wayZgI@GUBzVXpMX7xCq`n8M0l1!pKpNe0n ze0V-PNq9-)`^QI##Y~^Nu9-KZrmVT&Y)r5;?Yrgj=EiJM;mjbvnpN?WSk5Q)W&1jA z*XLP@RLIx$v=CF7KIXLwJ}qNZQu&0FmW{ysMb|EGi>=#>U?C(E$ZE0hj#6p&GK|k9 z%vrOtS>%+wjL&Q9(1VA(YM<^sB@`&!vOLmdMks%fudX61Hd-Wh&%>NIwfU!SRi3Gw zdABwyxNohJhyS~AbF<}0F&3Fk?+x`<_3M_e4(4I5ma@QxsfMa!1^Bg~(%aoYnzGFR;`vc3b1KE8Y)14 zLJ*Ik-Wyjx*E=(TdSAW~XzHWtuSNnWEuPxN~v~27O{e!Cvm zIDM&RwsG;6>Iu zR8l*5>Jyu2#ru-XEDhHr9I|Fan8~f3E1r7Nt6ETn%D7p+emH$_###XO!oB<$>3Go1 z$QyebYaN^zQC^Rid3=6)s(SK)1qy3x@?$D`^OyN*O^<%qn5@69^?tExl0fu0CXbFg z&v5huEmwg!W5>=GX+-@aeZW65DQ|_F6N5jsP|+aZf=9F0E2-k_M~9d4g$2AiPRIpa zFf5?Heg9b8?&HhZ$-mMMSVZ0%qQh*`cgEH&9?Z^}I~tEH)3J#VCvJF|ueEA>AMgiEzluc>NCL+MKxLR3(+`F%`(J*m08J)M*jfG}fLFfXw06gT!A8?!xe zd2d8b; zP-e6#Bc)fafT*K0kq!(5LD)P#vP@{>)XvurE0eVZ-fVuaJ$~UdYMIBweVsmUyo+V~ zw@-W${N;GwA4s@kXCeucb(a>Ruox&bC*OLtI@a9vmhl#UruPALWGMAwG|IZ}`edOR zJ}DaIX{3@B!}WdcB#n_8{x+B=K(+V$F0JX{)cRB_xdLaa?vjoi z(I5k)b#`hsBf)AB!xSXCbFf4|sI(`L1DylqQ0Tlnw(5&uPwbi6j+uIUX6nnH{lQhM30tmLIv=2dFTHKsSf;sEslCkWdP8LS zEPaJGqghrHEdppAZ+A?YLE*d3uf_$h=beN+R%}HQO4&l@Agva;4m_x6%8*Iv?9K{D zk+^h;L)_=WXBOm)HmC7c>AoKOnf^_l2VGN3MHE|36=sJVUCv9tMb72sTYeE)#F|p} zL&ia@proUS?0V?7NPtJh>@~9dGBg zBvR4BIouYe!|Zfg%V#GHZ#N^u@ss0W&VLdAFnw;OlV3^ehwG38znT*C^qJPfR|E^= z0*^0%LiUla%UMO4v&VAb1xrtv(NK_g1*4T6Ojb{$BxNJWV zW%&pXzDUe>vDH!lPn|NT)KqtB33}-+?0Gj8;uqHk_l7b71HWHHLC4AqeBf^`9Q(Wqs^ACFx;PcHQ0DuSX`UEx|Ycg!!*@ zZ{Y`bxbSQDBH-8PLUW8?qQI}Dz=Uq>slF}tym-}n$2AM{$XPVb&X~E z?RB(w{M77E5gEFS1mg69ktK^oV(Oqbd$yHhy4s1Lq~57b8}vpAgjcltm69M0IrKU0B9>eF0^c>HJ_IN^j^l)1R((Ow>fd9CfJP9IVRp--9g z7p0b8>C7fQMnm~ic`osrqyZE{DovhZN~ZwfrvLrZ@6T;_Ykvy=+m~Y*aoT+X5%UNKR+FFv_ns$JQH}h+$~2JQOlSK;IrbY zw#aIhPvIJt54nba=pir@I}JChNP7s`W6mWSG(y1|?`Z(21(h`pat*@?2Ix@gUUTu8 z=<`-}z++zLBVph%g6gXTMfroeODnJpGPoizT%oeeH2Fx!)encNRoXQ~X$ArB;{=7R zJ~Py&<`gGpr1S*7WIYon_w{^k53?^k2nE`>p1`jC^RGAU2y%CLxrdozL~AL0Mp-LbWccnM^q&c?n{Y{PzCw zM@Je&YXmH1)$NlC%d(u2cW;{r#^BaT5P`o-{l*VFATpcf;8E};yG@aH#m0lG>-+iB zJb)#ZKc*C5bvW20lKUo*jp57oox(Ojl|22;N4FR;8lp}A`|Q*KkTnKVn$ohOp0^q?j6X9 z4D+XxETK-39z{iEPi1>xzWqdV$1-rI!l`951eM+&%2g3fZz-6k7;rnb^mhKdJs2rN z*11auu<_>e8;21IIFL_0e20e#rBRWCJ@q8M@qsPEso7U#Dz^NfM@PMchl12CyuD8d znG({aF3BZ~h&84&@=gc~6=pSd)m62TeRsr~mr5_x9d;}raO)>%)4Xj+KZ+=p0Gq;@ zzur& zPW5|Ibf8cDtzyetXOq_D$<;>l`KNa?eI^_3YY4vm@I@M?r!B+ay%cfV7^Gh zuESmv=wWk&_f6G3xlymDfSQRDp?6f4+)FLBkMynFyP^_uMUS$UrhXAf5T8s|xUBgAvv%yQxUPQ+#T<;fyv%4NIg+HanVD|42+@ID+zp}9ZqjS=Mgw%5S;B;-D z{^X{cFZ8y%HJFQ!wB}JEjS!PGrl+6A>;?)0Ef$uL6K7TUlU-Wcg9QuMwdlIsez&_h zP9w|)pydjG02D>VeVQ`z~&O0{gNV;~$R9|%5$i=Y0wP@#Q`OZP>Y97BDD*~rm7&19WB8Splw+NEz2Q}gPh zX(M%?r)bq8R^rh|6ER;R40~lpy3iQCJsuBpv|n62em6$8mC*qOf5~6EW5-V2FWB>T zeD%5)dTUo5?Cz<}tAG~Y)kllCth*NUQeYaA0gDg0PGcEyR;KgQlc*mvqYbqXt<5Tc2F8PZau=as{YpUobI7pxmz5qN-=2$jbiSk#6AO*V~f+6*q8t z9%Tjo%slFvEt}7|UC)`*TxZo!@97Oy>M}@gy&&p3>B|6|dqz{!tN5EUngWx0dapg0 zD%!s~hzCxc$L-X80OoBQkwy;`(LSh9@6@AW&Fy!56%MmntHPB8$mKqzo)`0_OV7zc8N#z<(B0h5VY!(hk8@l6Rrv2E~w#HBN!a$UqIpYjE>0Oqojf@ONjcG^^f3u<*j~UnsYUkuc`96c=J!;eOaQw@`cAn!9Au&qkW-d@jiYm_De~czZU)*S&=eW7H|+0^`Loo77ny(j@JRG*ldQ%ja*eOA9*2_8Ax4vIJoOYOs-;+f5pBx zxd-{?LW=xxU+^3X-yLZ+E@AM>aXc1N#~^pydH|u#<;Vq;!gW>qKNrRb2lah^m2}WN zvzw{81Qno~sr_}qImv~J<^|Mp=-EJ9mu_RCl6u$~Hw&#W6wg97fe0537U3lo>WAkS zs;8Rfhz-mF6pM(Or(DgBk|$g4FAwU@RY~fp?LEk@(`P-|4{5oHJ+~^P5D$<&b|~2s zpS9TMuLdR6Jh*T^l384A7%ROlt$cP)MOciK21zB=KnRE3d_0U&W3(EEjRQ&pgV6rRkj*w+k>Ccmw-B^oiQ)jXD6r<- z(2x}#^YL@cgDFbu_GNwSSfzN%AKD#4Hg0kiQpLxtcrz{vs-zwimcyc(p+dTQ7qm4* z&Tls2w?UKLySVkzYfD!mRKz`ApAAjyI9&}LJfYYy z)1og+Szny^5_Lu*_*ND~RgB3NSeae|Qe>Rz%LTblm$Bx=6`m1aT2pW;xl%-P|Gep; z!5#3xk3}{QT66s??11h{3TF_}eZ!SF7ub&h1sP_wACI?x3WqY-f#?vVI z;6Ae~dp|pCfa-o3-H{bJMi69gz4AVxX#Y>!k&(n5GG_>%Z-Sn)>=#xXYV-wXC6ZND`GTHopT95Eq^q@_Az9Sdxa7S+P{+IK_>i>D>6El* zpUp;C;OH@q5N_Wr*Fz6r2w4EH7c__ZQVLY4oe33`7kG~s2V_oIg>MOD&}M8j?qaIB#oo1c%cQ0^K|?DIhv! z95bZC?=<08y5pHBE(Q6mVxVAKU#5qmC2v5Mlf1=T?q+OhDU+9;(dO;Vg&}I7hN0(b zGZ2Fh!9yq_U(rqGn=l$08hM!IU3BcJ48y?TEF4koS&JoF?GZq6zLUjvxBK3_@R$pJ zE?t^f9Z(k?F;VOx5&^*T0BY?_dImEpw$$8;z%8hq1wrjfS~+Gxroaf(1n1+{Ax-v37pEhqF)T?GGG@%B4$W;)>)uLA?W95lmttVxuZgPe7qCw(5C64g{i;E>X z(MXro?N9eVXGQycd2_wk(%+aC-oD0cR#p4_v|MMsNJWJ&F}}(dYVVAkBO4VW4FtKC zT=d7Jjhs*B)b&v@jHupSqS>aTXw%Ak7)_f8<2bbw@0@t7B;)NAV0Ul(=d1$Mi9aA< z@j>BN`f*SC$fcEIVCBFR_f$A{NDzu0nL$x1)O*{MDBdd)ln}y)U${WSKnqV1q@*iC)yT=Mp!^>ILJ`ZEX5p+ z7G$ANS8+5@tm=BdyFyT@uQ^=jZeG&uCFM8sr8{jBr8|`@0zA$Hl{i*sDX`w|s5(gu zPx!I5$1_p9c_y&PblKaE_ADj)=m5{mlS25uGOxlMfwYD>FaxOENv_S05d_rwLBhu~ zwFCnt%Wt(5G`GIcf7n%*Bxu#2D`OK@oW9(OF?V^^*U6&~w~_)OGXKXjLo^jsM9+FGcl@4m*|Hc7pS^fwAiei_-!aX17R z8EZFh7g8k}JV)qDQECK%ynzu2DR$M4?uNNay&v@RN&}g7mUAOSH%|-xLJBU*D@|%G zQA+FYdriK-b7kX&4!{1)?%e&Sa6$^iwlH40LbbOCLb)O46mkOeQP}EQDdt4_0Y6&; z7o46!nRu_ig%v06Q~&yNQ%<3?Wy|S~TJWkcm?A0AQPI~>QE3>;KW7)IIXOS2G`B}b z^uXKfFv0z<3po-0Ta+`B?LnB9`g0Q#u%-mC#2MH3-eB zxAW+O;PZEbxCLSBs0C+E$`Nz-b*7Yg=H0frx83uLWj_o?&hZHxc@k+jiEDYHKXwv` z`Ji>M2PPd=KhMqT(CBFj5BTlG8q-bp6Jfd&n;VYlYK^a|77g|zUJH}cUkej@FsYhl za}ma6A9mKp#Qat>Clm%e{1$TQ79T>7-Ff$XKj!3jKuKwQZP8Au6a?)eI{lwQWl?iX zzA4>n+zS-B3-&$Is&s{hg$qnz-TI`^oIUfp`@8!c1*uv5ge^gxt8r+4N)|%L^U!$F zzQeCMBHUs~fZws3=q--~h{o7tD&pfH;=aR*5Xq1%P^dlA(c2WNS@XWEkba-X^ck5bpvoOZV~VFADQhrMqoig$U}1>`>weeL@$ zm=e&-mr}CY2ZlA!EcyP_^lIVj_kQ7{c=ukmTEj9C{zx0H=cC8;LNNK|MG8|0xed_9 z{Pxk0Rmh(S)ZrB91u@wo_Xm|FA?YqT z&e7o+X|zD5=p0I2`L>pkl~_;kmR{x2Z_qcfLcn;TM9qxN3=41m?QU@b`VWR0FtVp< zEC?)14K3$lQ3<T(#TxMJ^M##n8H}?)T3F1bi^8)TeDsw3!Za*$Ukch9XU9wDkEkvLwwp@J zVMGtbAvXYix14nB8D}?O@;KSTqGM;{<+PaqNGI?k<96j(b6}0RcoKGI7r5GmK+tAH zwTSl50OS>2uve_%yn#i&cUf%{>tow0%YdiXALi;vm-`;jVkSEn?5`lzFX%7j)a%aA zdp3Wh%5b92$g`L<+2QEv=IGUmXU%z-NA=DW?dLOd-PhmoO3os`jV`Rjd{t+d-tn-# zPo04u-7sk+L}da}bh}l%odj|80GUdvZ zdZCCw)l_QXHhtEYf}-Oi^{2}m>J?4BY5uT(D++>}=z*%ROXp5_>er3OBQKah0aAQ~ zYT6J74#Ad@4IcwkskdJJ2wgKN@Hjj{OD^rEY4f0KDX*?f#v~PhfZ69(*ZE9OKjY~! zKcEj$`mDs1wV-mOH{4W?4oZ_Yy9Ilc*&`FMZy)dNiE#J_&YmL#F?x&|Lgh5J_5HIr9gk(Zb7oWwHXAi)$j!3^OrMZ{<`FS*ndC_6WB(klnvY)MLyB zh4$s9&|CKaTud9CfjwyNGxEf5UVS`j(tJEGd|i(_adh8j(YZcSr4OctHzIvr7try^ z_i-*?QuFWrP#EDh8)`6IbEB^M z?X&i9B~&R0`cvDw=m4Wd8KY}QI`a2xKyA|%k};Jeza0O2Zd>jo|iN-{8_{hfD07TC@YY3u1!JCPD>qQ9E~gE z98e{qCp{8vECK7|%!-`ieg*W))KB83@00Lw^wTj^>{2LKaN*DDEnKVpNiLZIxQPIFQAyVC%J7muOIBk8|K)Ah+$Uae?5o_A$m z$4}(>20{PNAWzqmYGaK6)gQoH#j|N8A5s2h$IT6}0F)a{p4MSH3(i}n6dVkyIB>U7 zn84v*5}S(Is3O>?VwzdtCaXK?m-p!Z0Nxg?pb*TXzzuw_U9VLkfIYmE;ufPU1{6@^ zY4t(Ee1yh+NrWrg2Tk3 zlje+u)_zNms=od@r(P}8su_D z%SwbkRl>DQ4Ms09T~r!|xw@5aLUhbS2tgDnFrM>;a{d^;9PehMbuw>P^~sm> z@#WIS24&3UkpA@=^x_aa{1l#qGEm9Ass8qYN8q~Yg;P4*1j5_1bFcSpvufHk!QKk5<|Qde&a*Lm{|T z(xt+cTP6VRnWl=E94pEb9ZHE49xq04K0F{+FJ%|P+Zs@%eI$M(z zzU=7^ruA~ga@WyY1ixRsU=p19Hr9=KhG8PdTHR1Z%lYt*xz>Bx90eR z@c{>xUH5kp;G5jhmS=UFS&_Bsgowr3x9zTJOrPs-pCnD`XcNl%R36jw+n1n1|1?_D z3PnGMg`HFT8L#})QNTV-r<6;<-=&aW_hOB^Rg5pO-JPop(@I)*&CQ=fDPCm4!|d;U z7f!MByMNPB?N_?h9UGON;0h)2Xur0LV-?$rubcNMH6H;Ubxs_|OnjVl0^+z*FuP#+!4IXDmU@E9i{*H+wG0p_GXN%KWVoYH4wk15wd12nusjRuiszngS>P#5?*CMzX-XoOt`}x~r zLHuYawQO%x7C2D?<3TZD@u>khXa%p}`WfUs5x~hjE7nZ9#Zf>vS$_O#5_W zR7he3A^iGMSYyKLIg1#}7`Kv5XUt(`Dw;&@ZoPraR?eSWq942|v7u}0;uVyo%i~6m z!FC+>2k+cP41C87u~CT55ML;3>=yD;P3^OY_+6Qr)0%h7BSJByf0p8_%n~)flsaC@ z(u?P~uar1_5yLxwlh`!u#4E;4pzu-}>XUYkqbF^-ctEYYWWG(Teae?-mQJKJ#m$d+ znR^~PAnFkthWw#?AFiF5$ukLK-Xei9JoI-@&M*>!iU*YVby&6wy>Ow&B9N zk6Zr^O<$HAZ&0`kH2Ih4ES*4c^*7iv>`d6(Z4q#=jC9(5exwz5Q`q$69|3y8<3%@q z$Sf^I^jI`p+VSd{PvEsfGwIWhJ{ze*NK!i|PGc<(;GKspth^2${{7&%+*$MfM4bww zw77v;fX%Vp*`2HT6&XNVX^C3g%f~;)FE>vfy7}tWk`4@I3ooX(fonWDt5Y+z!pB_Q zwQ!+=*?2+E_3EzMbEYbF#M%da3i+I*xPgz_;G7n&z2LmUaU^KjuKhS;Gc%hsi~iAL zCEwLVx)z7d5iw2QT)f5GI3Z=#1|7Vyrlw{_pr!k>T?^#hwiva?O&_Wd99{;^Uc_jt zdmmNzt>@0il#>U1er57$-xCGH+N}bxo ze6wT6Uj7;`bmjc3U6)s{HqI+bcquJqXew;x;;I?TH(TleH|q`n>#l1VXHUa4`oyRZ zw+_8eIc&@oq3hLB?ehFpw)$nZ_GoRm)3)rEUY^mz6DFhdW9xS1 z5cdzU2F~G|!Nw1y%C@T^by&X#%)fsOv*(=Z>|1%8s#^#f(x$&({(kC}J2Jw|^Dl8t zhPh7#UoB0W9OCAs;26$XWAM6fbw-b|uo4kEs)`o;T^PttQck^gdwtzn+bf@wOE09G zxcG)oJb$Kp+YM4c0xvPClAkVMrL&vcV$=LV7_TFrFGX_OHW9SEcP8s}dznaY;4aB_ zOGkI|+(zl$vkoYKEQqM<7_HWJKTK5f#Tn_r1bsz;4wG%l#i=@Z*%*IS*^4EvTD9pJ zYwY<_J>t=B?YF&6FTb>oH~Lg67<78JmkKu%iG2gcpTGP(8-+yy*t%9QEYfSH8W*Hl zm0V1on<7Bmue``PKCi8*`=TQ}CT04~bF)UkH6kJyY^}>b@Dx8fp7Jf=z0w#aK2oNx zea`I5Th<-VXiy7z*{tuRT593laI3h>-A9*~+d?5MFw;1%xY-z+9>Sa6>8umSPB^t4 za=YBqgcm3cnN)n@F0tu@X!69i`!`p(9yi>{MRwbiCEz&AAFRe{VOTqz)wPtt+_>qS zlz*FXb={e_t<^DYUdfbf^SsvFWYI29n(nV$>2W~x7{pD+=&6M_ycC60$D zpy^4>37x5Z=3Srs9X~i-a!GzENBGFpUhAX(;pMwcq0;Y|F}|U#_aC-ZNG!#FJSNnD z+eoi0e15G@%DW{(XRPQAnU`6OOBIv~E;o46Z(ff5;A3AVbfrR{Z*8t()cH=s^K<6E z3oQGxkCJa#)YRvz`te9{tHNnRmDtjS3MEUv>e@Ho(_sW!7e6uYCZ=`B13gd>IMa1a zQy{?IsPz5Q7kb57$@XvDB2S;b9249NsL^mgq<8%9>FMh})!oigYcGm8Ul((H^_2wz z!Nu!7ymCITkaFdc;~K`~hE>AGw3=T(WCtcxEMLu#YLBMSCHr1~@|(fZ%pf~*^%Tli zK^Vkk+De#(B!cZvwh|a)!B^`2r1ZJQRP$Y{Ry`N@Umse(q&nqTkhzdT|KZkGOX|G5 zRNHIEgXtC(o(*YK($Xny|NV}2(Dl}j@kL5rr}|9RiB#X5FqIPe<*1wDg?AyR7x}HX zs%v@6YvI*J&Gnv~D!#&f>bxz~{WUVKUgvjB)#fiPy19aJ>$<^8t~Pep6huo3{J{2S z@WdMWyNST!?A$f0kJDm=XCK?VOLYIyz8m_!ahF$rc&>F-OQ;5SC1~nmC5J{7X%iy>@U~-fD@a$AQ%! zyZBCOiN_noyq%nIZ6?dI<4~KMrB_B!0_EkkY#zFN>yasC+Vp<>Dg}I3qoU*1w!JoE zEZTdt_8(H|9(l6E_xU9zLM^VU)m;3rBF*vPWzfYXy?z2n|=4RQ0w75a(~=AX|=AG>o&=? z?rfClKbE3Uxb|>BhuibWV)MXhEX|ZgBP{s)Mg#lRTbTVw9Q!+EFJjAEc*Y3xlhk5{ zt4(;cXKHJGsL8X?)D7JY8(+NbzVQ65PMy!za*}+lKwbNR3^gkAmk+zb&(F8oe5-rX z5yjIEfr4F+sxS8KFH$091Q&0)r<{68`bE;=zI3gQd1F#lCJUfLUsYH`~7rZNZei}Cublt+i8GhLGKpJsV{ z+L`Fs)}!@Yn`+h|n6cR`OGRQ%%@W3~+6~+_R2+G8@s-TQ2#IbRB6YEt0O}H-6tLt} zY|)nSO-nLL*I%Qz*gY@HnLM5zQ!dhQJ?d3)rSbEF5$i8Rp7%-kt);PyVVJac3MGGD z`@9u_eaSDS^y!rjV=SnBD-IZ7D-Y9+-wuNiW(Z3gY9J*wMZ30vl6E+Yg*Z1QU$~`V za#l{;zkIPbU+*>D1wjeM#lQlFa&fDBvGeoe;pTz-8ELI070zAWYO(U&D;#64B#2LL z6wWty3M}Mh+V<(M^g`-CJT6)v3)_xqz9WUnz6X%)K>{zuwLarv|B5JYEBw26Y1&$o zkA61O4!#=ECqtms30*q({IVSQg5w_-Np{E*Te?d^5--WbZ_P5Zz2y&B`o1@zNo_3i zZ14F<@skffe{ufp(un-3NYa*K-$;vY?WmFsZ3>=pub-dMla4>8CJN{oxqHS4 z;!xsXgA~Hwkfx4^cRvf%cAT5WDk(cp)s0B>yS)5nLeeQea>K4T2tOhuUL@?x9b?gQ z$4|Y*jd($L_PcP)DU&G;lRSF8Ho4`URxZ|y{7}3;xIC^|xjo|e^Scu-eBO6j0CFML zrX3@o3I!BT!5WBq8$vO-a+`(VYW5iB1fLJvXFnfH))9Pq^hDwb>Ek;5CF@JQBQzV= zMA5drj0^M)#gC(3>}t~2nQ4_$a_VSSk`-T&YH`7|s9!1h8KN=EnYcLnSv+(flbs8= z9~)v-KCew{*~gAU$G$v`MfZr1Sgs(Wqm_P3m%Off$vlj#5r1rih%wIuOS{(p3SM9g z^ZaX;Wz26OiN%CN&D@Yl7RqCFqgGpBHh5cqn{tG5abVh!>8}8w?F@&hD*NsK$Jtvz zMY(l$btW*0>?@%>cSClP$=(i5L18{m6p;^{Ylpx z0WE<(sfGNxrnI9BYuEKEQvnm0Zq6UG#PkU8zmgzWy`^V6!a&jYv%Gws;~fQ4%eQ+;{W6ke31@u1!K0%a@x{Cdq|L)Q1?N-{_*ypw*vn?$Yoqc1! zhZW}l&8xR%N)eP4vM)_sp5~4}ZTw*0yOj$iED$novrbW1sw*DbSiH`v3F{K=K?u>&PS$C?`-t>qpTaZrDGolgw?`udDql~RYu63mAe z8n;xPpP#?8jW)4Gqq!~*`1!Ye`gE#k>^~40EjwzGMOavnO=cf&yq&#v&_c(dA~afH zeGPBl90A+lL=k_YT3H#9%KkW`aLJkvc>a>@B}+H?dSbkl+j4u<#^&dFLZDbii^frDSmXQ@dO3+z2LzYO%`$Qb@1L zN-6G-$uE5{)YgkrI=2#^-%oi&(^Whvfey--DvhGpzqg652;}w5c1i5tSbHxymrtDi zJiLE~?10(m5S<9`BZ6Uuj1xuKyeEKTh-_d9Z!}R6}l>tUCKL?iaddX9QzS@ zDeK5OelrGn(5O3_ZSau!DVXz>T&y=hlFjn3x;gf&qrwkgih27cZ=ikNoMmac+OQd0 zsX{rI9EeES<-a_u>VA8t#aU-pv^x60Il5O!_*D}wN48H%+z#wH5jFehMonU8Abh#n z2r4;A*`ma}VN-_wSfa)#sb1?3U0B@QkRtyk4_e;K3)mm0SeHNzsRjEN%X*#8uI2nYcsNOl= z{90w?&MoUN){|~my29W4+035$!=z5YUx57ZLvjq!k;0C!0IS3io^5}3+USJqe3sf)xU z$Kk_w)4f_?)_Y_cHcvKo$uwpR=VIy+mf|sD|rkkK0=dIkWtyKuTQy)FdZeF1l%`RT-@fF_U**y-n`A$(d(bt#Lbv)sN3(X z5fe8p+wk4YiU<^?6<6^57L5#i;Tyg&BU&_m=G163CO)-JQph`CV+*ZeuVg(b1+um9 zv@V((vOD&VH*3EU+n4X~ItwFrcJ;^*K4 zYR(L>>TtYWobj%*C&plIiVk6-6CyCs7`pMzNGH$0gk)zyF@M}cCu!d;#zH4F@3nCz zKFn`VWoS<0qe$lVm$$_&w*_F5m{4;7mF~LTj5OdsSy}h_<$=#dW zK-YgbFhu{!5>`_ITEz4}B|VB_(hOifBLL$w$$TT%WqeyUaW$Z_Y^R}Cmxg83Rev8| z;-O|Y9GzXjp6}&ly=^uruxD4Sb@%@M^1cV^#XM$<-&GRbn<_5j`NIgCOC0!GFPfnY zOcX#YpH|DSYw1%{h&HzNe(q769jm68FsDNUw+~7Rc=*Sd{RPO2n$B|hh|!EP#Yzm9 zzRT``6h*A!f`EL3a381sOZ|DTh)u6`)loHOzRN*Gjaoat`P$HVWgnk-L45De(hJc! zkkP(iRP~Gk^L74}t#*5ch96Gu=}^h9Vl(oe`g!+tDLnzjk<*a(XY~T?JrZAHChllU z*Rbj(z|vK0No+sBy5v|+9^~2)OCiEq)sD~28)?iBFQ^Mx$+2U_YuMMGD_|)e0>(f$ zV%vb>-x$(hFcMQq+>6^B&Vd+dI)73^xpdy$4D?c3j|(}2r1Rw_Z0g?`5wY3sot(t* zMn=iX>N8@8DooR- zBU)q#7gQW-tdDul$a$AxbRS9Xow(4iiGW5p+`{7=WZkze+R$`qz<=CH%SO1&WXDw# zFhFUkq@-)GU)35V)~GUMXRt8Cm8(=pkbPtonHJ5=Q8bQ?l_E{kZW)n=VwNvAX8npg zr^h&!dUKZ_5ZCG?Za2ilT8p|4;-En;(dCP3&*j|<^=meTzAA4_O+qk@>E{Tf`tbCN z_R#$yT%UlXVmZ)76p!OkkeA0|=_))J^?)dp06~g2xCb>u`wGjij9KAkhNsx_MOumN zP|Vd|4ad|-anC&qdqekWcYy^jGYyzDvrsG zz8%}4t0=uQ!JS$8;w9s>(VmqK1?=BD0sAkIbp&F53v>P}K)^mt@03Zf4zd{=;a0E? z=YWgfK91H)&2#gn_1Jmq(bH^v?>!B_claQh7MW6R7%D1N30cppzyC&#x_J{3Z=p1P z!2XR=Z>4dmUvQCD+xZUeTBGJR z)nGD>z0Q>nc6f5_#+wo(;t#d{#PQHiXaE!z&vowY5$X8|o3q!l!0l}@lnw9Y{mGC# z0ol}lGCOg6Kmc0vC7i|Xi9{gKelY?VX0fpC68h!vKI`gYsL=N%^2D{pb>Czf=c9-J zZaDPpz*h4Htd97+2|h3nKO7{2`cq|ru7S3%Qz*KceyWOTweymYgF-be65}h}*Lw`E zVWoZqgcZs^Dpmg|o6W#42Y9gdYrY(uUDI;h&m*X&%Z*wcsmTXw^{kgvyI;yQ6&TdmoBk=S z{K<)O8JzqNga+&{MZ9g-&{$o;-h4^+K)u4vk4YxI5e}SPuhg296WMO6|4Ga^i$HOP z)H6>XDbYH1PWZ5P<+ylq>z)B7#9E7|ufvU#3Kf3OLre+_OD`5aj%L1nn zja=d2K#Zf=%=?K^VHL5l&+>_^Ib#x@U3x(PFPYJaIr*o|>)maT>Jzn&{LFFIuyQ4Y zwSQ*k;Hb)|)H1i$w&`Y<8%4TB+Vt2Bl-=ftD}9t_H`9?4n-ov2o@Bb#CazOZR(405 z6Qw;?leHxFGA8H1#v0UiYON+EwY9W{?Bi2X5XKE&!zIL=BehOhaa?*-WBf9TY6{w0 z(~937SUM0s43q)1uX+#OAB5XH1EwTqVww|*Rd7>aY#}Q_XL7}go`E+<_if!;uk6|E zF4C(W&dJG{pE2<(H!`VrG(9}Y&dpsj>RZ}?L1}i1LF>gTR|7HQXhF;Hh`gn6GUnNs z9@X$Xm9ii6Yg3!w!?>;2tBp2>z0d>8X6gEKax_-h6)dPqX=!Oas2}C3UoMC@_5sAM z)nugjUV0XhIAdlt4wBSK9gB#6-?^wOV9p9JyOhbmg5+JXftUugM<1F?u zpa&0b^5r`F_2XeH!jOMc?gUBumfjo4sPR&jZ9k!F$i=+5!pr*wfwt%~XMqp?|5eLX zsuAJb|0+A|M<5zoY))lepDH16pPlOWbsbsK1Qqa4=xeyAj#ytujiX$><3RCl`fy!w zoUhpH4w6%RMzM%-@@?TL!3=293&}s)vmrn$3yBC*`XlkF0$TR`?9iaeV*(h5P-Xw~ zQu}I9r&f_Ox2YnkGNQW%K=zBLr;mvmJEbdzK!qojnok^&OJA^Dcr*R$#c zwm*SnAk7u9pPp_@7X|;ajvw;$+BdbxUwbR3Lj#Ps{-_Zot2JN)n$Yose?=01IUN02 z6+0coQn!6CsZEB~@aBa-#%_Oq0e~?Y>g=EX$_%}kyEGi~waBY2t8RxDB2czy%|8}X zPC&*0skS+dh)E6&ujtb{DhWzqE4V zCY;DqZhOeqO9u+e6JqUg6%GEQ!qQKu02^{Bq0W;1>#1q@u3k_DkpC~GaKI{s^XSDRvKOr7hq7tZ7+P(} z)JsQv_5`5@^#43}FyFFh3!Bs@ww*R5AyAg8e>LCwc`2Vl$>E9}#a(FL(9plx;88v$ zlf34wBC(#vAtTW9@-LR^;8Ubl*#SP+8khn5Fq%iP*n|cz~ z)C~n>!+)7N*~NUd&D8#Z)IPt;T-k!GfAi5>%4u`s`gUGA4%TioIUWCItrJ#08JF~} zy>v>gUqt9o{+n%eeAU>?vGaDT$QWfWWIXz>#H6sJ-w6#~(i6?i5K>_KHboxm+$40|JzKPxL2!aL{ zyfavW(VWaSV406M@m=eQG328>@R~39W_leI4K?8?lt%mRvT#~Qg!SJLf0PJB%5_W+ z{EJX~A%S+fZ;$m>cOlGODL1xH-nvZE+R@SfD$N&`Zi$qp_l4-r$&HrCR6DpQot|U2 zgVv9!1v7W~Jeb!KSNX{2Y&~3E+?XodvgJ;}ZCte8DTw~%OXHfSRgyM_9hzSMBV^H1 z{#e;P)Eu{~cJijcK}L`{V|zQA&x5uzdlpdfwN&a{Bdb*vpQGTc^m%*OvxQVWWsBa; zkCH&w^*v?oqVZ^kcMv{G{R6K|dG;M=7mf4URc$U;Q!C)m{h_!!cEf7%PcNBydE+3f z^BK8*q7$wQwF+lpSrh}bgM>q>0@lLAo4)KIx66NHI7{cs?vaYHTt}`qZjJJ*sw~nWu-q?l8bhoC_7w7m_(e zkAZssLy-CJ*W`Q#aN3(0gs4>9t6eUg`q!V&;x6}cQ{~dxx;X~#%yBK5Vx^9Q>?mdi zkE`A|4rLF>Kx`aOya6V*ngC+67e$N&S`_+PK9jOmt;yzTW6kL6_w$9jd;_ixX#`-A z1}YGv8QZzz%^`a%U?NR?=CVMAZi3*4xyA|}*B|gqntL@WZWiKWSs&=!XFv>nwB#vH zetuS{Cb1g_scR(IQFpTYCJ2QSW^hq(sc5{3ApiBZyUTSgEjP_={uW(-=uY(ZsOcIT zr%sV6PtqVGsIeNbntwFwxL>n=kz+1o;0)Fu;yLfMbpO}-EwX_Cm@N|PvV}*WMkN3#!cziJ9w%!g7Q$^6 ztlEpNZgCAj&dDrU{F?Fq+A%z74gi0PFE3&1Ja_;UG2w)z11=15P0@(sx{=@PT_0;N zZ@I!Sbr7P}c*y-K!m&*$r>-kqs)ikGn{)EqcFCF3h@M)X>7hHTiSl-Rl*zEJF zwu~+2jh%Nqidqsu5T$+vpF`3ys};NKNN$JPtc0_OQ_F?hdx&n-ny`RjlWEn)9vZc1 zg1{}z-b85V)%6wx_uf<+stbj^BSP^=Wk0RNW0Cj;g#VjU{g44l!_Dzgc~B+K&FFA1oNSoozkt| z+w)d6$wEK{rPDJ2hnAe;ml6}LS0f+{UykHJ1TM!Pus(UftD*RWcT;-Kb}WVF(&fH? z>?6<;cdQ}oLR-&~tfu(m!_;nV)jpbb86=Ni_yTSu$Rm6YKHxu$L)2y4uGP47Po-NG zDdF=o#*^alUYJefvcGtB6n1yCBar}hwku0n+^n%(5SH=16inHBpUw)K#)Mom34ikO_FwZKeV9O!ATF^OyZZCX00D`XqJVC$k z)P{m|O|7(#OWJ9<-jMq^BxMYDguC`<%2C$!O8XAa`?Z_UuIN-${8V=Dg~GQVAfxr; z@gG!6>((AiA^cMAnbF7m*JOS<&6n5)=UpPx1H9ThV7%b4H&LKKZx8t^5!wC5%IT=+ zCS3J$Gz5?jMAZpSQ;w)$bgtv4zAD$ zA#%zE>!7NupuU7b3Lp%|imlf%fe3?$BH8%gHg?u za{xSix#pPM*ju>6lv!_FdNMJ6iRtG88M^@Co=CG6wb4(kb0)zWg+VJ8KFRi3$)DRe za*77xXkV@MZefMe6iv4ig-;M;0zrq3nHo1(0s|>oV1vltZS_hlVB0k~1)^n|sUg0E zu(M~+Hk6;Br7<6_wi6Y47!odF1fQvtWLa2vWQB^&oTJKN>J`j%HNH08l-p54btqcA zWyjvN?@?7bRSeny`AYWaTeF=*(3~Z1c>cChIKUA z%!AT9f7TK8`S0W;Y`n{LRC5dvbuGQ1~7Y2ppjQCET4wT@8 zpVzh$-dE$Opql9Gz0Ru?WMS3|mF(k2M?LEmn@b60t>yE!75da-aS&=z$0 zow_J&gxuXv%nPRA5`2rMTO@}-Ttzu1UWS5XU=sIg{Z|DCH^EeFaF zNg1EdFrf{QRB4Ifmk%oGNw>U~7n7T>Cgy(Bzr03Rt*yk_`{>cINB&7HRFp}lz7J*T z;=C5Uqn3wnT{B0&kF3s#2K`%mTm6Uf=tlK*56^;)fsd&Cw^YWxgh|=XhgbJGzV?c- zz*2UZ(vKk{Lr}?Hcq4O99`8y$*t?f2{;e~BTC2OnIl{eKs94!#0rd#V1w^u|W=UhO z?{eCM7$yLc&v(e)gp8705r&tr`MFoad|UHJ?#v9q?LS&9lz$TM^_1IcT|#IcTv_VU zZu=NT(3ZVjm>uc+%s7Q3Vd9oMB3qs=;@Q@crI`%d@upL8;N^Gjktdvjh+%Q-V8Dla zLO)C0_@wT4m0*pHVe?~h1r-)nn7kom11S&;hcs3&0$qHO8e^NTbM@pdlsT^HPulEL~ z5d^0qjk!>9dG?})OPi@%8i^X2HY*=wv0$G7ZvV&*^kP}NE@q)N>L$Z_?tr!e{WAR> zv~GV^te-JwF-Pp@$KyoB*&W4*QBMV?)AG~LK6?muaEkmP+b9Il&8R`-91;90VA51N zTpT)zK;vMRoB=o9NQMkmDP0m@Z)8>EmQKCJ=49Ll>=bbRN51hl^xDh=bi2jMXP5_G z;t(JAI2iA8k=mw7v31e@cT+K)QjimgSHW27PTUI zUqeGSyW?t|aF-JvzfpgXS(>L6sRwihGAzW^zWD2$3#+i2Muee{|;;1 znLW3;5yJ-_@=503uagk(-Hl$pngQLVQ?HlDdq>Hp!3sIa{!dd9KZ7jPDS7yrb5J-H zHbe7KwRtaEnZ7@xWRg0A2yTjgWr=Q&$A_Vd4Q8epJUwmqFugsWS|*MIp-=#X#0<4^ zg8b3AdsLv^%;+L$H>*`^etZZ0`THFg6z+UhR_}YCXbb7F^X^}qp|30#X`7tVwx3q| z9sU@*>02?S`g_2jj|#$qyV_ahODAgp7(n_2Uj#+*T7~8yy#zTPy2276 zS))FKL7tT~q9ks|NMFLD{fl;4hUUCYZ|`oIzA+>#NnBXd{6bcixQi?G)qV74oW(}) zKO*B1=J-!53L1n4q`ksL5-^zI1U31*XFGcM;dJ@3pyDvqVxoWiCs7D4yDnWr?gfQ- zYibNmea1ces84hLe7v8-(W0Xj+4*oI3kGnuUTf#o|lB^a0->$10;l$)Gk%?>H zCpntFU2rGXOzKje4xFr>d4Q(Cuw_}QWeeB77gP;#;iso#?B4{A?z|b9fF%>SESz;t zY0TZfnt4SLOwK^s$gID7Sfe- z9pnxP@o?1ULd0B!@4dD+yJzpXS5D+Y4IYnVsV6;Nr+b8L5xrbq2U?m3fOS;ONMoCu zyQ2I-1xR&1k*t2Lc8FbSH{WMs+_4I6pF9$N#%n-S5{%$Wf;L5~zM#HrSR`pAe9yjU z$pwakK2NqV}=Uxp{gk&sV;Ov*x z{%~-b-)pht8lmnPLd}v8HttnEZRV|SHYF08xiG2SNRKjM%R1h@#veh*c6?{ch-VKg zl9W`uj!{h#^d&%kPT!_2Kou365=5Nm12UF?LDsb{;JMPFp3e$7ruTJ8)Ebbj5@|rs zEI+?&G$e?iW+&}26`;-Fx@Z5;_JPH(^3#8}2is?9iwAsc3Q*mJxS*2^{{FodHozX)rRdX7Qh-E)bk6!9J2!w6L*eeH)-VH$p)s2lsJ*EA}oUyx>2%4UUZ6$?(&fLZJ{OQLW zV3FG{1X^hgE!&OI8FrX`)5c{(is$9UD!ke$Qa!jcwqqlPS?EjFL}oCzd$!nL15-C_ zvR9uz?t(~xM#}ojU^7^`=2G}F8F<|rUGtTOPnRrHVzY08)aw?@YB<3u7T5MBI<3W# z@bkUS`mw!@MT$$GvRx7V=!wn@6Efac7NgZyq=fvmLKMwl@`CfGHG&z-s|Tph!Ow)x z0Y$yc^vyzUEbeD>;D0w6{B(45�F596tO3<=;^8a~}_y1ivFxyphG^(*tIB7Xo^I zBL;)&Wrm(>UCYNsC~~lB+uVD+>9Wu{jk(Gvo-|IWFP`MbMjngrqVG1yTHLhQ^&*0y z06QD|>@1eg;aX2UkE!sgKhTUb6ptAgqinIhp!!RD8aLd2opA2t$$Cf=)NJD2@?oV; zMa)V*W@#wJtY}^%On|+rOlX6XT~kr7PU90lhxwERA}*HWy|+oVUOx50ZsVH1uvw99 zbTOjhFr%%%Ts)u3sf;@EPW*LrM|Jv9v&lcas0bGKzLqg-#rt6djA(`9^6ob2?1!-! zTGBG6GWA$b6DZ_$$u=gxf7n`9GRsU~H|IaG1e=bNAMXLib^6QA7b#z44Cp3;k?F23pMf2bBV7?Ows zuJMPSGYiPqL0uI}_T*(T*0Y=jW!5r<*d48f4Lz4uXyeR#iHGLCBmL@m8K9wsEu!xVB{vWE&w7`LEwo39S<2+XY+mfIo%Su}6 z)2DZtd(G31Nm$}MFnQ+Jj5lR)USVncDsrVgcYGLG)9I(+Fg}6u&-9Yd@zeJ)8m+OK z=(d`v!8};V!-e3=Zxjz zi&Uea%M^vtbyad53Py71=N-pjAbmO5&BvQF%Xsv6BEg}GVMfqzH!A-=Pp)|w;tDYm zzBz)bv%A|2g^WKW+dC~eE}~uCQQbqxSA{cA_)sNW^Pc_cK@f6L=9pq1ar|nOan=kI z<|ms@Bh!3#^5f&*Z<>vpb&48^%VHbC%SnH93a@;~$zt{#OlBvy)XKjlHFRgcZ|@aD zR{6L=n)ZA1pk<^&;O&x2IXwWd1>8X!B?WXJXP&@oyI^K-e7 z?1enT1?>_ScHN9N?Sd!8hi#IL#0QOy!0P9BeGs3%e31L>56T9^EU*rqk!8c-hGGJOW(FHdTS^->TXN9e0*J8 zz(KlfLwH1Ro~wg(UD8bv{JAa-dWu|UCZdNa1kU&_W_5hCXOD&JV~+gu-VxD~e8FmY zZX_?jFc*w##8Pw4=NM4*|Ab9>8zs&W!yjN%-VfTA9Y=C5KmTY8X5V|;{?!{W=eu^K ze_Ag-uW*;BVp^dVIc*aETX5P=;OqrTO6Zu|IwRHnPUD8&3d_hxLsy_{p0Usu-+QI> z09T8O$<$)|>a{MsFw@mpEVR41SykmrIpp>h^SG#gJ`}q;c~`iV>I^?eE8hgJIcn7l zQOChJMTas<#BO3lQA&Plg&~!18i1yH2F{&=x^n#?zdBz2M&;7KhVbCS#=8n|)B=Zp zE}Y~XB8g0P`0R_G*i2glE~C=|H1Q?WXMA;~NPl5HQ7oXzj0RXcd>T*sp-|1>ZTndX zCPEjWo2OT(t@EhEy!b7htit}0?;M$xH1P7&S1-38Nu9(|l3wI1Az^s&>Mj1;58X*p zNN;7e18;6jS>`1qkaOFfHF5NgK-}vB?03w@j_kd?V-_?4t_U;g{@zkUC;-Ax# zNSCFTv$n~CRjJEvqKC$ZcZ+aYo(}5Z<(2o;IpIHC3PP%$E+h;_s*Xkb9Ca%GjFP{W z{SF%u`H_R$Feo>Nj5#^~tU~12PZ3qdN0JwAJofZ@65UzHo1Ni)aJ# z-bDcr9sl_>cSR7=G(WvJ{maWXv%z5qUZ#sBg61RobE<^Td<$`zM}^eK{ltkQZQ$C0 zLUT=Mn%X|5tV+XEhYb?Lhr5>MarO}db8|DPVYMm^gaIqPd~_XH@Yj+v{=pMJ1nD#M zekHY|^NH|pV}q38IhK9jK5e@5*Sts!;1}4KUzZ7re)bAkFrg-!6}#bLV@uibwqgHZ z?<)JSnE`?#K7Xl_ICghH89@;%!H+G{OD#|T+Rwj%I(RJ>uBRkZ|0l?=kzQZ9!*|<33SNruzpy*9 z#Dm?f^x-cppud zaP85|UB%_2W%mNb+z~1af73y+t&h^NNdTnaNa~bvKYvwku z3|HC}>J;m<33Di2N=Q&taN0c-eN)#UeY~Pf0dd!q-|}4+`rAH!RJX9m0k@|lx^Pn+_l(Yb%9B}(eTU(okr>9V^-&CXI$nSl5@OOZnVeUv3{_nJ;*`hRzGkOEg zBgkX)P0+f2gnNbsl>yI-O{Bz?*oH5EqlwPadwCiOMHh7sX30Sh_O>^)tqxWd1C= z{WZD@_VIZcf1A~hQ0c2)-~q@s9G@xW zzn1?)o!)#sZr-t`mU*_A$oo{r%KVq+8D<>SL5)d|fCp!>EMRW*!HzDc5fZjAl+Z$D z;@&MIH1+u=jaR9ixjCZ0)F5}yWx)nwLblhxGw5wEIXT_C4fTyOwsZCVRW*{FImR;Jlh z7#5?iHLc$Orq?NsF>Fs3bYAe>SniQi6WxbRbicPpJ_!pu73oHV(+KVF^=@*tOCfum z!=D-09T-hx?5ZoZ`nvN;UkDM{5U4I3xk8c%04J98e-B&&QX%~=O zzjl0Uvh%sQxg1xoUQLyn`g#8KzY_r+8X#U&DZOp}ufuw7MDOGC7=^yTVP;p3LfhWi z8JfWKnV=If2NWE3Z$G@alR&Zr9Q1uu{IIa#+&i+(C4q6A5bJ=q@g^QJ!i%+8!=W@i zYoK){KRun^@k>p{3HR6fBPln7tP(4hP6W2{UXz%FI zv9Mr{^sNq4Ji0OGSAYck0`^ug(K_36zgl>~WZ_is%ZU6i{k*W3y;VD)AYJ&-2i5lZpRbK?;- zLO8&_tw;4a4FI*+lzb4rfO5R~PZ$iphzB6uep>$r(~B@HNbSXY5lv5K|B8q4`Ba3s zDtPg>t+d_qD)$nCDhcXdbxy7Pf@bmcGMRMl>%Y6J1 zT1~fxtHRT3%2&|@0R|ima~&f3Je!lDE*K*>JDUAPH8J&FBAW9;Nrw%XRIvn6gEYT` zItotx-r2kQRW^vNrQyOX4=pF-)S)VeQX;U9#>6i4tEOsTV{oeVi&N8vZX>?+IifpO z>0$7|)7CrC(!pi>&G|l;u{ChctJJuP{Td0s%Ua{-dY@1tngW_L#QhVm1NlJrh`H+S z!{6icge=_R4AMUNf*G(3hqEtQ=u#aQok&%_yyW0QzmGSjQm1~hf7SHMh$)_(kKHYi z2<9Ln!Xklu4f6uLz2Uo^80u4LdVE`rH8$@8`6hn*eb0CvJa}+-(ms?3?vKW4e7$n&w&U)W z4v8TRK`sIj96ps;Sc2M^>p9hg?a<$xt+bAK+LJsxx-)CJjyF3`)->(YT&0E+9~UQd zBScCr92GnD0e5Wa)9;*ue-eoCqm@)oaZlnvuoOkm1M-2QHqTRELIS2%$CIjcT5aEa z-Dxc4_U51Dr37)f%MiXpiy4s`oJZJh79Aw!KAj$8wpel-a+0$fdnMR49xgDNO{ONq zX5llu)GD&IjXjj|E#73v?tDCw-);yjYIAOUWv0DnrRk8i7E^ZbE${UAPcm$Z-{09RD5^Yca^WVHU zKG0gIq%p^AJApT0NTVKsIL$nc1vqKudhwPc6x}I;Np>B!6JW9LGfh(yTa%u6)(N5x zK_O41hM40!yzq-WjH|SF*X6%07F}yk6E}I?LYd@`3W}=={PbnsZRvvxqsBx-)oVG? zr0Av;Ar}pM<5ZXP1Ic^EVwY^EpXYrFYMf4K`oKkkGcyC-{{C%eYuI7)EjZpIT-0ru zR_rv@!eY}pLir1W{gvOq!L4vc{5YU+gYAoQQF`M~@~BQCpIxhn6YeMTGrczQ$l^=B z5wZQfivfa9HkKZYjiqAkNc&MCyTO-N6NjZonXg`zsRMu^ zN?=31^WMqSG{Yk$$1b3gsKBn|y_^{+ zDM*5i!q?sbl!!27TD@yam2g;4@0E;*{!oMvA86$QIazo}BYD$a#*{1#ZEe2CyEWZ$ zZ?fT&yj{cXhZsN4>ABpuVhuB6UM{nF>Jj6IRdYQcjPCWQiSsRhGiewd@FrWx3YsrB z{1dniAtgHNOC}>Z1w}z+(Y008VQE9=UP6&E!LRC_0M~Q_E#r2E42cj7b?`y^uNiqy z1{;i*+Xj50H1X97JVRXFlYHzlmCM+QLr|Cmv9^TF8ZegA9V%H}dc z>G~UYm(Y9oe5gQt$3x%EzILLAOf(M)`-}T()aYUz1~Z>-zyM;$eKXb@6Vr@u3hwYS z(@XfAmG-Hvjd4k=V8?fVXRdZCl31jFD0$Uxap(IdZkPFwEDoGJx3``OjGqe{Jl0Wn z1#E`^>HG*d)ka0mdbdf8J!9n6tGuCZ?76+wfaVWTa!P0Dcp6lbs&tZKP4+u?8ejEy zCTVA|b1OgNVI-l1_pf;8+Q*BL*Xjwp`V3y~{8g~0TKZ8~UwXUhyUAuZa`fGfV z{>$AJmJ?q=##T}B5;Da-R(AU;HGf`uxuG+19S7ap@mX3K1*^}-r-U-^IW-g zPj$bc-&;bV?HJ9=MmL3izceNtTm)^jb^4dPoN$IiV$o!K`jZZ$5(5N}1e_QLX6hL| za^o>y<>q0Z7Ebzq2|Tla`Isvg+%1_uk64tI8t+#`i?1{q5Q}eg^?Mn@*4`t(qLi|b zxudeopBuoNxfWtfygy#0;OP1)%}??zs9N*4@w6{ zuJsp-Vm`ZAKn0I(!eZrDyKYNERr>L1rJK08`VF2g6T2XbNT!yLYt#PEAK=}5`O*qM|i>Gs2R=Yc< zWjBNC{HXYqYg7_1xH1apMDw#)&FD5I)#TN>FJL~!bI0R{w13-}8#jv()oHoxteleW zIr!2%aeb*KQPit?Y#TTvoL5qzM14#>IczK}xyBK4IjVg|Zew+u6~y8@@+rb@5#%)c z|IJi>{$y$Z90x!7-%ekJjYUWPabS_-XqDzcu;d zh7FPy`*Dj80`s2VoDFslr%Ix=VPCoKVHOICWYuH(kRS!Ra zsMQ$4$(s5i;RlRgV;ojDO1Eu63aL(rPL|+5oUg|QjiqimzHcWN_CLOc=BBu!rqsmp z<2Viatt}+y0*OQ%7gkp4Fvc`OHdVW&}%cfj7ndGxxtyj#ss>dwr=jmDsCcZXgE){?qU1h~HCCE9A% z(@W*|v3OSW>T*_vKkU^N9Lm|*?O*_0hqH<))vFPTX<4D|uAU}%i-d0455CD#LGsJq z7hqORr_K=dMyrVz14Pp6RqwGrJ@;n4b9_hDOcOS;)^din$#A@CTx=JIcG9-wW~YcI z_MNcVJ?Y1CHw(bG@FztPVPT#ZghRKaQdeGE3j$p1;{uv+5{Ze!L1E(AyaLX1hioxH z7w9wOS5$DanPeoR8I2?mI3(nAj}+D41zeE1V+|3rRws!alZj%-k&#H;IFS+jT$aGv zA?0R5l7f64xQTgF9NM1vuyfEWZN<=I{d?!w@B!Wk(ubPZh-|HyPaU)PJnEp~$H@B$ z&-qtZvIoX3E|m}BYZdQsMP=4g+WX!-p}qu77!BopksQF@sqC*5P;y~A5Pgbd%bulT z_j^#%1&{sygYaQ83XUzWNbgf*vJt_x%Xv&cT1ktH>M0h`#Y#2rlch%u1ROH`ntVwv z)$Wx4s9)*IlnGx&-dW|OveiV_#&P}?=qe|Pyf%avU`vVFuNa)7pd^0 z{LM&Th(akSJ}a3_cb2Fm@3p45Y@#B}`U1T=5DzfXO5-bJd!_`)}kYjwUTb3^QkaTC=j%Xa22)OasL!Fr?&6|tUm}Sm5tkXMsiKSjZNQjCtX$!o$ ztgX>&V-|kzZK&l(2CHw1*9@wa>%{DKV7#^i*GKmRou^qZAsak5-y}(ePPfLA$x9Hz zKgDxRcBBZea%Z+T-9CAGKdtYbnUZtFWieZ&$%`~fSs%i~jmKZ#t@ur`*4v2Xc#!o>~ zd2AYPD!ZPIyp0Hf76#b{menn6EU@Et!OIvgC%UJ63_*6!82Ht6opEC-E`q@dyl zIuW8PQV+6cTx(_D(RXg{wmL6~jocIo>wFfIY(QyYvJ%%KY7}RuA<3wrp=4`0{aMr@ zu{HI1azOUGcd(w3kzWMP z?NOE*mk$qo9P^YzW4`H{mS&dxm^vUX)YT(4<`Rwe;W{~eUvO{+V$2o){OA`C#KR%2 zM{P3l1@RG7H>t8dJXIGR?`P(>?jpH&?_Oe1l{01~jub{lMmDId9Lgui3w2?+1jnoN)ZJm;sTQ<&eeTfxmVp^MkrQbG> zUb^+=jfenkx@4jCLnzy_{VhL>9E;&=J0FEE5D2j@we)j_LJQ@rrVGE8Ay$W6^oJs? z?~As#X`}sC;4H_zcer4>HSBp0dE4i6}? z(UMimPKWZ|;G#cS&m3iN8{_oGENJXia8vggmk9^-wU-13ezyXh$hjH5d=Vh36W0`o zJ?tfnSz3!VOuaio84upG(x(-%p!ie|f2Ek^>#IE1&WY()&6m+HgkG2VE$=^Da&&kg ztf`VfRKub>2l0NTBwlW$ox!#kqZn7HcblDdlFz9o#atL#k ztz1?l+*Xw(#lRGTil__qq!GKEL6&7DY0w`WDvmQ#sfpVK`rl~YR}UT3CE{kG%33G* zKF?~m358u7?+Rrvejv)}!}je#f>Bc6_2i`F7eNmKuNl6DUaD|&rny2G=Q=^ zp+|sZzioZJJ#|piuzMopj`j0J?EsW1)gbhQHbUX0F1})*^#vH8e*x+Wu2F3It#BN9 zf1JzDfP)+s)W)ul;%N}hwcGRp0rvOrGcJ$43eSrXm^^KCNn4J_kNyI8-HOEP=Q7_Y zq6xed?g^AXB7XkFJ-302eQcM$JdgN!*bd`IjQN~tita>W!M zQb!77%F60qgmd@jz{;fabTE@E-^DMmPKJssTZ_t6oNYs+DRnhh}ZliImEcEXKBb`m0W4`|S++fm)c4ej3 zF=cv{>rz|H5;uF!6Cf=h)&W4?%o0=Qu~@Ibh5FbhWhKHem zc}$i@Dagi!uCuZi&(<=addQ!p+Plww zi`bg><^R>e|&T_sw~BDT5A{=@c%0n%gD^TeC6rR)Tyw?%s0;<_8% zefQmI>w-}Gl!pBXe*`P!Pg zsB*R0&sq6u{I1J`G_Q~xeR?m=kKcS#L@UPY%;c6&KDd{m@vSZIPDX&m)@FzidmN{w zgLo18G64)Vgqg|(4_ZQ+jUG@?#wX)70xcSC0`}SVs+}v?vEyEZ_Xqr*! zzS$&~a!!scR@rR3^Aq2&?MjK;6^zV37$*C=|;i2i{92%sZ^Jbc~hdg+V}XC^@>ZH4ATN_o{je- z!Pqn(x{}B*-!=?PUInz4Z1!^T*%*Jg(W>kEG?Z1a=sjztt@snw;q({Pap?w*n`x|D zlckE6?>9~ECowcWbo$!hekM48h+Q=JeRh3x{p7tv3w`=${1xY6H-%u~K2O`KSlH-T zxIE92L#VRO6P!p2DEAtf`JPx<$kCDfNw28iR*F~opI{O=jEP)xV&gS;$ z6Zm(ZU_qt4W>;SXCug)j=lS&ihq1qa%Cg(K$6-Z4y1PSZM7q1AL`u3ux*MdCPU&tz zlm_YUPNln~Q#$|q_VGD-&ifnR_{O-0qM}~A)|zY1x%QP=aHqU0KB7{Q6ZqnJ4;WU{ z7OUqfS|D}*7G0H+_ZO8#g@uKSJ7hky*W%&kIU879HYB;QOs^-j`L1ZA-TA|+a*TZL z=h6;S>XlxGm%N5jb{p z7Ry%}5$5UtZ`nZhFpvtwm8{5w6v~GfrB9(mM#96wzUF=)qKl6dkfOKTdPTTu1X4yi z85#8aRE=6pkHxL)qks(hZMLTgy1m!DD?G}=dm5F>Kg&0~eYdlZnWFw*^U&UJ;%uT`T{^?D=EI z?}(K)_WRxp28A&8s6i8)Jan8$Ap>yzbZ0`PO7Lh&Lk#Ok`Rba$=;lY2pThFNd3H~j z+?eVcW?iirL3P&MUm5=Jsp+DIZ*fl@+=;GzI zExo2$rkWgKss%r(ip1U-{)K(LZb+i3f^&WDnsRn|p~vaVM3S50`a9AVc4=w{NvEPf z5P^>ULO(6sJrqc}kIJCNe&!t-D9GWA7s6ken}3V5>wB*{yI$9Acx$^}4IdI-&fhF? z=T*{wo`ncYQ70!ixH33UNoci~;^$s8- zzJ^aGxgTB9J2{w?C&*X+jKN_&Z&p`E^xE^Pm->R7=EcyLvHWN6ic$^9F19-tx%gUE zwYpzb_VI=wn{?XTQsgjZOhgoJmjVoeC}TCDt`~51JA~m2&RM$0pf6d^Wx1#wBR( z+#nMC&xa@!#KmqN`F&6c{O1qJ2thhbJ3pJMbEID&VU>U~naW3hU8waLA4yc0lUFzL zgWrHO524YG1O@Xf7c$Izp)|31mBOQT*W!7}OO%ZEr{q$XY@LJH!SdMOgR^N((}H6f zk5~JuoDIG7ivsj%w>LTDDIHofWwqn*8Zj1TU-p<&JW_qTvMm`$u(}+bKO0#DU&n1r zk1DV1P2HFCpkwFjc{)vBQzQ5Cs^kBzMkzN08|}ZqLxbS{-yiSS5QHs0Vdo@T9H7^m z{Z*jQjBleq0rhErY}W>>gNF{VoCHnldgK~?ma<2JnGeCHf74%ONi~fgN<#54;SeqX zJ!bh5T?7qL6Wu|)Py`Pf%Je0r!>FFv#uq~ztHoZBXho^9Iuzb5&g*>0(Vdo@y7^iz-R@5n#^ zNl)Zjh)FoURy*;G;m0^!He^~_+Gw#Fu(i7PcNcocZ*wg0STF0J$~@l*Wm>~fRaH&B zIM-e4jp@e2{PKf}0*1XnS>*?Z#w9HUL0tFKjwKcna#+*p@-Ilq`q3LvGBn4XIBSBg zd+_FE$aG}8^Dl#nlqQhU%Q+Ru^$3pr1U|%+V>~ z;~O@0#FNb*(7JCA35-s*#TMBfa(y~&c=>;$fG1d)!QogO!0P;GcUi=O9Y@HIN7=@r zGScXDOK^5Dd1^z<>ckMxbQ+JY6Q1(!WK-efU{+QAq<^L|U%evFRzi8m>QxB|1TXHQ zQ%d#)dd`VxQ6)9j$u9B+scyA?HBE0#h`JYpo1=L1LAgif>{ED=<`A0!RUylORug{? zD#bgtp6}ARurbRx==3G?x23!!XXbReZa0{|EFM4T%u}UC2H`pTxi`duCjWj|$Wyo6 zfUT6ALCYBZpWOw@OBw)>INm*%@H709dEMRA2-j#U`tAzcZF90eKMPmVB^MqVDmu^O z_#riw0oMpiBfKL1cK7b~YT3l5H1&I(9N~a&sZgBjXtSzn-(^(vXuO<*jy1iAm%5;UQY8|%$>Y~k)wTXtjou6rq!FJll^a8~t?ug9c zbOOuYZk?d%sxH_pbw)IUO!HGz4?nfja9rYE@{}bqJ=>cs7OT#CZZW{s&pkWk^PK2^ z&Tu_BKrvPkAwGXk@mjn$KVsddqX+gjS`-&3Mao%to0X&we|AwkfBtIR-7WELNG31Y zb2P!?D~0KWkU09$QUyx6>U!gIs|I$5{1t=!23M2W;poS2LLb}>|#T5(Z`#PWL&?GX7ibD8B{m{=j+aq?^4-wb~~?&Y<7OgnP$J~3{h*g zr958iHTcrYFo_?p&0!p0OzT5M#{CUr=xS`p_6194p@KOA<7{O1H;x|m-i1rs<%7>j z#Z13Rj9RCoP3jlNr?Cg2p5-V2YWGbpGjX=2$-g7Oeng#;Aw*J>iNvRXL!!9Em_m0# z&@}Y;r*UhF7xmY_)7vlf)rFavY0k%5{C7GmRRU*x?_>$7jpM0k^}Y8)waRyKZ#pr2 zi*2e5e;S1W{=2iJClwq2>kpE8r@giy{dTMh%bBmO;I&x}gTyi~&#Wl+gTYXuhn&$f zzS*fvhDPclFFJbl)@J)1pJrCGXm8Y?(S*ofNI4I7!rb4U`?HjEB*q;syaV2Qw@;WP z4d|JDoYd+GLbhxD5+|oZ`fHU|-Y5Sj8c~6mYEHrR?C*45DhPS_g8>!^i;zruzwf$} zMdDh8#YBfE_^cz1lBl6AXd(q@TBoZ8CCw7RiZih9c2TN-G2aq7l`-{+Kb+BttSaaa;vx7+eW zT*h~oYHDWRQ4w?cT+qh*2@qXOHG)yg1^pM}agI2sDF1UrFiOQCY3@iF4-?dHq8Mt= zt(!#m`(JagTXfiH!u#8T^KK$b#(AG!e6?tY#JwLXr2LIb`ezDf?%Hv|r4yxm$vcy` zV$Eur_vhc0h0k|uE4Z9?6ZsNJ_}$*joNWCN{3y$?(CkG@JX0C-8rXcF@J>tJjg+h>DHbSRW6vKcC9h8ZN> z!=r2JJPTP$ezQoIcUQ+*L8gkmg&X1qRZ=Z5J#6ihr2`eza~7;F65@Xy5lHbi0s=12 z$&sBsI7d}tdS`{|J>hWrGHzv+YJ7ZrhX>QFRX8}Sf`dJ|J9`A@O_ z3EjaB)agxa%ZF#jik}YgKR7aCu?MeEt#P_-7ZF)qeO#yfS&>G){Nv4>PRC*}CY9d&Ol6;^zYD)t zt1rX3*GdQc$=0|`t-#xT<3rCZa*~lJq?F!R(G)?TMnSaooWXBMb`)f_p+uy)j0Ypqb(w8j9%d;r?oB7*(GC z6l7(xrj`QAoA9KU)$K`}i;Jslvp70MHEgd`46l#J^jdhHcXx{3 z&t4ZMnpJ~oX{fa?dvj?wZf=)MQ|{iV#Og-KVUaI8d2Vucd={V75>J$sm4)`k>M)8j zMAO>Z`liWPzDm6(hU#ULaQzynufA86Q1=|9t@EN3~b7IZ0ZUMX;f7{ zJ(txT5^h1t=tKAVD4iR=-UeF`at~@wcCi$WI6aZfi=Wcr`zg+dcajdG<7p^zh);($}D4mynj(|Dcq2IU2pOPcTc!ap-ihR7~vcZOtTmXu(*Vv-0-*hz=D zpE108pb!=1a(GA%;Kh4;<6#ZPm|XoFi9V8(>1Giuj)4noieegSVj`lj5kgL~a(m=J z0%p~LgWE9~F4yCaVkBi2QIOCUGF%(KB4! z#)ZCUvY{meg%5{kbed;)lQ(=f_*m8M*XgOJdVcy%9{sD`I;I=i9=q9iarg>&&KINE zHja+zUI*DZIb{}GivGPajqkEtj#ivJhA1v#W3evN?uPbexg4+9_805VJJQ8uVuthN z125drA47mI7XpYg5q8mY;8)&*0JRj%qXVGzoBFePBCKlOgyrDqhYX{AbT^VEipOW8 z$8)n1sYxjr9^GhB#4ILXz1kfqdh(9fV;jpVM92Dkf4TMjV;n@uw`?8V-IN?0udlGw zE5lRRTHjxvFE4Mw%cG*EHrqUOotr<}9Hk5eEEBXaTzR%}F`7>W;XxQ-;9v>|tx|He ziOPQPIM?;Zh0f^u_icymR3%`kR`z+^)9$ z^*pR~NozED7_K1G=0gM@WJdk|F>>3H*PRrns`8S{&p}Rw&vxrXmR#F@v(;8v>pzF- zXRl2M3BDIAbuU-Boo=hpYC#OY^9yvUpM4Gc6Z*|Keg*3#I7qf_qqRc?`_M@k>_ew+ zF=18Ss;{z8RWDkSV6@4961B*&Ny4j0iVCX+(&l8+3-nLPtD=6DO=2k*OX;y-RLJ%# zjx5R`^_wy+vc13a*d!IvYIHszArWw=Va4p&IIj3^9Cd0Q93|-Gnftwh=F#4dAFxpm zV^UMYx+6*ZErMpNtygW``R3RM?idxypGZUy(Yoasa<05FV0PSAzB&Fm+{Z?KXEj}g zEFOX-Rqb%~)l{v?BI%}3CgIt|TqaS))2R?79c^0UTYHUrov6!xVW;j~_W zfGA7>l$r;G-Ax8EH1kkYJ;-RKj{qvGs4^I7slkn${Uqbn1+heSzJV9Dkdn8qrhOtND>@~gby zmUqltf@(jeabAWpfAIFeytpbTDYa>ZGQ{i*!EV2geQMu6`DyHBB|#8 zQ?ZBN=foq6X0wWIdtyL(1Y1HZscAUxWoJqA&70W4RI1QI6>_~RT-t0*UsiN)|C+6h zgGhh~*51C1*`Y{zjnE8BaZrEIkaO`xAtzv$mAW|8H5=@efTb*B$_^d!>5W!NsJfuHeV+Pwj*+8*D&b7XXSBh zc5;Zx`_V#IdzHnMPW+SI1^)TS%MR2_0(L74CQaj1NPhW13&LFk^DnYO1d==+C;u_e zP$Jf$yM*c5q6;qZ-3ie|v!0AGAfP&k!!SsAf637gC`M6o@+~I$cwsO*!KhhkyDE{& zZx0(!r_FE!_%eBfdht-4xZJed#H1@U{1z5OfFyHoD!#OH>PPpiSf0(<_eqc1%btvk zqaJnlgh7?+bDMblD7j!@VHxv-lhvdUvnNkXJ`QTu1$Rf-{`P8)&6nM}yMg+>%M^#kN4M3gJtq%M3d|)@3Ivc1 zCH$Gn9QeA(D8C}OD2ja}EnzJxewOPTIvr8uY2L|1K{cQ)&9|CC&+qP^Dt&s{tD}`| zkw!D?c6;TRe9sVHX@-}PHC1qMR1nkxa2XN~l=16q!`E)u*IQ$?6?U$xKL+y^ zb3=OXkw6cGB<(@rFcePPB@h9|;(VLj&Wn2mzCSxTIq5h=r#zhbKtBBppWB_w^Lmey z`;%Q9-PBjt3JqK*ekOQY{Bk${!xXBEg?5Ab1=9DYa81k}|xk;`r~I%o8m3$eKv))FOlyn>?8J=bg!$Rt?!Z zY8f=^lxrIdXE~G$)kf`v$3QLm06sAZOcd**T<%{GKcuA>lNwG^6spo}a$4pPQo z_{`n7@fglQJ6!Xl0|(Mc{LsgLrnq7z=SJ$=(DQ|~iu z(NUwCV)rU&d>8Wlf-jVw-C{CjF^3Qm+j|W+=JS*}^F%$PrmVU}T3Y&i+8%hmG#tg=cv;R?b>@%e7{=Q> ziJlB%-`bz9ra3Qmewfr%-RqB{mLNZZZ#|d(vP93~X~1$x9zywZX<;|T8_mJLv;fy7 zG!LOsz46lni^Yw>P2!lAWOnnnnlQIhjmD_bYBk@>^R`;tnG1m~HDx;VdasjF}IL2#FTVLqbIzcF+Kg z63kx9BFg!%$iMBZTpRS`FvgPVMR;6WHgG%SGg@RY|JvqKAV?(pg@^tkWtrdTSN!V* z_)XL9Mzyr0myqf0@#jEmE1X^M6SWZ$d1XVFr~9Be3rZ@52{Gm%2!P_mx9nL+CN*6) zCtVJP`})S!4xkwSmEd4uXI5$-e#JO=$-Xv<&wU(lEH7Hic~z$|t6K^qJv zIeJ#_&l}>K+>%nBdRTT=Y#JI3l6Tlfof6(1l8XhDpuO|A@nm8^Vo&!Z0FHdIB8|$o zs0Qq!Q=8uk62{Es3TLZ4c>TzRqF8-+gN79ku?^Fe>^NHSpXgOU(>$2n9ew_sn(FZC z19`}YD~tI$z)n?)n+6@2S~uNYVXD`z1il6S;x2o+lx&3@32ub=E?CBLpZD+Im+e$9 zuANIr;(=aW$sG>MHPMD4iy+cF7*hTaOU)|1{&>c%JU9gx2$echsGesYh)M|CDu;A* zdzesZPW+G%;&NR22*Flct@aR%|NFBP1}%&3(7pV?Xtjn;D7Ku| zB9c|Wr?EKYyv*w-(vp}CDvJyc#F(B(wGud;7h{oF&()BN%SO493skS!*xHVsUbE92 zF|hiGH!psV9=Idm>750OITK_OpI4D$Z(W?nidMxp~(hpL= z`%Tf4IIT%KDkvlO`QPbv^hD7l$yJ>$G`bzNev~S=3-t^tT!lbcHl@kuDVpwH{Pz1q z9jw0)`4lBcQD-h@VM%|KfEO)Kpt=z1sBK9r%cQUR9&1y^aTp<6Em&y^o(Pjut=Q8acqL1oHzhk?*X&`=`DOZ~Mh>D|9?n{g$N(#5r zbedcDYYwZ0hG27Ya+Yh=pqAd=-mb*{Q>~+Jxpt&Q2M=#V+?SZXx3|kX1^urk-+lb} zQSbDNN+PQBdk-Bmujb2}XMdJZ9-oZ@KiR;lzjJ`$p^?=T%ae)NfSHeiS9Df)2|hkCd{yzTOz> z(d*m3Xz$pyx2NT zJcqt6fi}8wi!vI1hCcj7wA_pmoz8Wcgs^ROa}=Zf{r&PqOCzY#0XUq=lcd(WI~#j@ z)|tJeZ=a4@ACn645uzw;TLYYVSoR^`0=x;fhKwM%CP0mLKV-u^h}osYZ7_Q1rHcXA zWxPiguFFrd#=`>8euUT}f@j2}N8M~nWOBVyFOB&AxK8l)hShAcxabmPb!BB_CpW=n z`Np+V74-Bx-`FWp$P{{5aUB^J))BPa&N|qKy&gRK)ilPEs$lxjSj*CMg>f#88ynXJ z{0^wp+pL^c_m~Yz9d}+EN<;FRtMt{u&C28Oy_qVN9~M(z;Z+J=kLz)=NkPu)45V!2 zH+c7J$|0Ezg7(oN8@ z5>ClMXMG8@m#CGJO}7GEU&E~p<>krA?#Ik!Wn9i@3@@J3>xB9DiE{>3CB|q_DfDfX3 zLOffoT5P>g4iiVGI*~e6$kf#0EE7-TDfYUw2W8?795ZLBmls^?H=7{4jz>_Bi1+J5 zHXrltRSd`KRA2FLJlXE*?p}=(@K|%^y`6GidJuxc_@x2YQYzhiPR+IX&AK$3#rGGX z203z&c^gRu2w@QY+rvMq)Ccb(wCAr!7=t>4S_~K@36X>gV@r zdWJo*5Qg(?@tO)N2$EFf(R5u7aB0Zx6M)esrb4LuVud?MmBwW&l5p#`5m9{dv(mig z-6>tMPAyc_-kZJU?d=fI^t!xfyGmC6o|`DLMfAx>qtk7ccaHeYrX|*GSLa!)3L6nb zKHi%wNmMsRX}3Fpd^ACPXi4pLfxL5SI5X&04^!saL7VW%XVJ$`tK?ERa{$gt?xHLA z)vUA#?hu@hmrb!AU( z1F7{J^^k?n(`;8u zUB6L1O=WMs@daJUrglR835@M0rr)q;SL*vhGRXq_`vwuxd!$K5N_2S?oaY0Or$eSi zb=;62pB*GnnNJkbx@~PghS8R@QX&9+UnvI26t6+k&7YJh1Qk!MSD3lu>&nt&x#@dG z6Jyz;0aq7*VogRMxYU5!>ASd5fP}0|Z#C)x_Yx zVT*goNzQ>`_ur7M&(`n}kJPJ2_6zKg|W=4KQ$QKC1!7S_Y5 zS4cxI@g_oBuNd@E@fHo{eWG{XczAP^lCfec~3d^(`fO}YlU3_r#sAdjpwob*Qg|7Q5529Zh#&i z+i(ZRL=)oWikA;8i~38wO^gHW5Bp@wlGs=S9PvNlx)nFCv_21JvhVz0VU`e91?IWp z3Fl;wsmO>B--POF59ofHy$B(OXr!z2yn}VOM`dv0L>)vBIjJAL2XPW9sdb;`!I2HC z%S7W@-x@3PFnznbd`L$;ZwmvTy2gn1>1yP~MNZ^fwruwHp+(R4G(Lr$iJZ>QIz$Ci zYZnWc8N`BrfI-k_U(dPz9I4Xg4UY0H#&M>z1Prel#7$xz^+^|U=>PqMVm?N z>AP>H^?c%M>OBixfrccYl7fAUzs&l_02InbWkVX7Tk7`67ETV^_4G~29qZ^p09uLQlS_-4I*FC;uP?>$RO6ehkA4b+UNSFW~wYhYkzJOgnWyY zDtZKkMnFK9z+p0lM*rSdmU$J;Tr9qPDeK_VEKuI3CAkXF4{v^!YX{CY$a8t>d1x#BOyASiR!)Q0RdlX05&rnt&t7eYw;`fC1 zY#UmK{BFD4?R0o$hOtAFp6?3mWpFnt4J%`L$j@AXlM>cz*@0g0DlyBDDGNh2#SxE_ z&8UGJS?MtqwZz~04ZAS;yKbk08I>}A>sF{~lD4GoufqcEA?y85p-4$dq3=&sQnw}h4&NSf16)2BF8v@|~Z=|{TjoU`C zHs}NjqiTw0(hS%FjeS+aX@Vueq;4$93Ts2f(2h&q54r3vO6PQbCE`A;OF&uhr*Rp8 zS?dXY05hKocf|8|wrGcBi}81>fwsJwxcfGp>Uh z0R>JVxOMtFGPYe~>rPPDlbc}DLsCV>A{Albfe!mGdlhTtC`7Cd_8z=r5SrmVMv#z5 zT~pK5?gAS+7mmKmZf5;P6*vdGao)Mm^Wz1tmvg?$$_ok#63Oo67Qj^hHjc2RDK)Dx z-WVI%5AV-URXNhXOylvNno^6U(I;mv zN8~Id`-}u<*V_|N`UO6a%!~DC*o^^G#3a*szFUF+|h>VuJj-S zto<6cHSV(xRr?=3CTUV5>;q1N`}s{*SLR<2M#vLBCEeOp`aWZIVCRP=0CFM#r@$bv zMurCqR&e!~=z;&o?`$I`>`Yy(PlU3fY?h&g`+zA2Auk8MuWfb>z=ZuE zmJcIpv~V%nU8DGQ^Tg9@I4PrZx%Uus@=F`opnR`7823cH zd0O;p`DjkJcf1`$MX)g1MLlEBz=QBZY!{KAx)MQ@*^P!UY7yao7&S_Gh{5Mzg{+EP zOn9E?>EYAltcM{#2m}Gd69H0jQ=G{!>lnjJGN@qb*Cjfe*?_KyLxZG}L)-PF1FnYqkh%NU+8@+CPI2T<+neW=a zsN}1bEMN}7q7wLtK1S^uCgijVGXyu?V4?wxTr>6@OqvH|(lR!>@*$J<0WxVQ|2=6} zB#pimG!=z0PWB`Ljcyewa>A;TfxcEl=UB$S7@i!^aTr3ezb(G-b)#Eet3I+jBEs*Q z@?kx27pSJ>AZpZNC<)#w6EJCfr8y(!`tUjDX(;Y$zk0=5C9oWU3oCACpn(d+S`0DQ z>tz5MV`ih4*$hMtUQm6i){6oc+HW;>Dc`r4xsVo+^su-v+Bqh+EWhHmH@J5kMvweN zfcDJjDRjZDJ`OyX^fjPz&(9t8o1LNx3tybX$gdeH7`b|x;aGKDhBn>e*c%PUlLEz` z$ZL1@lbjIfeOi@<#NIP00F6D;33I5xMi>31xv>4wT!4oFlH|xqAW4o{6d((HNO|z` zAAcNB=-swD7E}F~#KtSR?eOsuV!Yo2qPJksXMeF8wFDJE8&9{+ojaM$^w_Tg*gnX) zxYRrszM3lCSZ^s>LS<(b;Hwfq{$qLYAMgE~!(#_)L=4ubU_R@QtXLY5new>UCQdxc z5uX?SMSRK6RypCf7qv4;8bz0iBjf0KnFXh564zif;FE`jcI(ATf6w5juW+n>??R?a z-E$5RXUnT%O z$uJ`LqaF*S%|+5y$%r1Al7=g~Jol3*_uIo|Q8v@>FVxE|IuY2c=F}=&OcNn-@GE3n z$<%$7gG>%AM8t6B1xNL_WLx?%Qh#czoNmauaF;ff7RRDNK#oi=fy=Nk|4i#O~# z-aR<4c@wh=C_9m~E1i)x{=v{(6h4wKqA5zAedA=D<>a+hdy5K$)glbNfZ{6ZpItj8 z28#=g+&t<5DQVDu|KnEZ(k0Kipt+}(Fr zI&>L*6`?H@cH0_*`N`tQkK_29a8Nl=9N^m!-{Nh}08H?2fdRe{!ayr}l0NVNC;Ko) zy#@V+7#9XvI^_rNCugufv_CRK!Wh&`S=o-Y^TqBu#~l_& zlP4hY0D`fvd6*=CimBHPNmB;bD7*_kmVr$Mlh#$lWH~@0eopw1e6x6XB@&UFyVjK! zI)ks!Ur4#%^h@s~irJ~k*UH)Rzfu2&X!+D=jQ-kgdl8 z6LBe5{f?s5j<(z7h@|X@p}Rub@czBs{)_KzswOC^H8j5a%`PzP%Yolqyl2#&vg&}; zN0pgQcm0Q}{*r8s8UvzSJ1w)sZv@>#>~peGl0{S455Okqa2zF@R1-1x-mEW5S%*MA)#dudp z+KoU!-tlFe@}nQyuyRl`%P-7yIA;PA zq9I(36;FW`39|aK<#&Y%W2#Nh_n3I$x8-xk$ViHg4*(aINVECnuK~Oudkke8vY7%M z1(RASBwMD|pVF)7yPqW*_}oQLV?C|CwUtJ#G?Pj*wmn{802qbji!$mQksfT{ zV$T81(g(m_+UtM_V)fQre0mV8KST5m>4+W3G5q(l8{u8%YeiVteNf}mVAIa^U6>fF zRe!EaD^-jlS^?3MD;OX*yTewBuVTEh3Y}C;IAjldFW~n^3FBhfKPg&<91mq%7vq`R zpnH^RcVR?UD^Gs{GCxR~<9lsV{{&U=mPZ9B0Yg8=B}cdBu!RH`4{Z zNVIj_6@vA*j@M1bJ_b{9O%!Q|0&5ygmDgg$=iR zGoHKpcLTuX)pC2F$yk2W8-wW(Y?HZ~vPLq!fAnC8m23g+KhFTZcqt0#;YrlR<%cVW zDCwQJCSPm_-rrsjP{*EI*+lW%e9C4(Ck#Sc(IeAJ%=jL&rjCWbMG0}d+c&(`LsJ#?D!Lyis_ z9}h3duuS~Ro~3Guh(JN08o2sqop-%MDu(SSj+s#90)0_G%~cjpkObVQ5d$Y3%Md*8 zcJ?+n$Kd*`#{IIqLBQ<91c^{Ut0^yYXTTZl{N?{IzKnAq!K>y9n|S0AHg($M#xgYjtd%hrh z1mXQWn10n9u!gb!kbYm&z4dJZ3#1Aq-;n-TexkKZ0W+Ttn_ZSA?BP^=VS#0~YR;y* z9tnvIFxo2Bh}3_$Bw&Op{hC?-+m!9!e~e8(@**d?5hQ4#6W{U3R595U!9p!)lPOHq z#9mOMo0!mOJcg!O@YJY)t=#z@bwIoMV+E}S;@S8C=~}6!)ED}Dk7=Nfh>Xa!!o{@n zhd<8uS7AY%g887{qOI`IaG6oCJ_zn6EOaW^d@PV=&mGo70R~3p^5g&G#5~da2@NPV zz%S=G7QC*(#i5!GIvyhAu<|P?FcsV!fLw-kYs1E+mc-%Fh2(HBO8LnU#nA&?`lt_X zRq9KZ_=P>pfK-hIY%d83{Cs>iyBD@KH9_~zp!+(@3TSN5FF@>Z#e_iRe?MHv4>d6z zU@qisu#{}X#_@v$nzA!WW`qH-26=pjH{j=gLdT1iDtI-G5p1^CB^v&bd9n&EVQw45 z4R>9H$=(>b0gq310`v1}Om$hDb?`$X?cCNJFhH^WY#rp2!mhP~lQ z=0hKZ{?1A#qTqD-h)4pO#JFyV^zw*1S)@aM0ARfwFhPm+0rtNk3y76~fKwA4k&~7d zxpvya8XXxNL>4U837@GnH-|Cfx0Pm&lO9m8O4iM7&0PBgvCsqdl`oG$MPZ=}`|2scmM$l^yK<2s| z7VLVq;ZBc9qg}_w(|AFlvptRo3`XU4Yz~0v`Gujk;1lUK3HnE4Sq7q9!We5pa%w{B zgW|MZLt8P!6^Mvm;iTJeav*`gMV^ysep1v9^Jly2#XyUIYikhqW@yVSe@j1n6FHKR z*;s9Uo8gMfUM@yyfhxvNz&xV!z7!7vB61uBcP6KK%90t1*#+UBGdc4wvs5 zigTQx1cQhZiwY=^+_FYXv4aMMpyNpqaP5$cSZ@lj?({@Y1yJfXxtEs&(IB_~+cGmj z1;G}KFO#s2Uwv1u+<$IWkepx}-7}-Y3ZgU(U^DHjZBYIk;i<89PWd7y)&e|ds#5}z=KX^3DtyFzBz!JwScnQw3^i!~& zpOTA`b!gl|4CNOVGheCEh+HZ+Q3Gr%tU>@c9i24h^#q4T_FF01wJOtZRI{%GOf+yeT`%6VXji+8QViT3%eW2>52FGT%(ofMTrWs=e-82V#EjbNTfqlm^k|UfDP?bL0|(4#tqiWw@(-NSxXBDITPWZ`?=Cawj(q_!mfm~Z^8+c+Y<;tEHJv}J za$N_QCo3I=cEHKw5M4T6@2Bc!@w_l;sNqKeMxb(J`)A)ZMu?YcQ7Z-ZBS8SjN2wR_ zNBFX#VesacuV;FUW)jOGysfkMue19N+Gr@zCwI|{$pFhsX0Fn$x^tBs3jsN8GGF1* zFuP?4m0WVBTG<<#-HpIDf5a3<0flU}px!IR&TNOW#^45#hVg_D94M=lD$5E+Vn!A_ zPOB+0%oideB4cIlK(#+Q6m6K0s zc zxIz?(e_{J98QGWiM&`Fc7-3JZHwiG%dXbc<h?Zuh18V!j7vrbwVMm5Ai`vSx;o-xyzQJo*2Kaqb7e~ZI&aCYwQIA4?moIYdS zd+h!M1BeNI1#q{g=JG=wC2O$Iu-U+2UW;(uakPrZ?9SEJ*7h+CRJ(7)Uwz~{1@$%eb=e!xm?WIrb<_x&rKA(U)Jc*mf z_{?Ii*=v!GnJY!fb|FV1T;!Y4VEO#jp?>?}b+NWxgvnO*LCeFSW>QGw)CccINR?Vb zZQN}eTBsG3RzSKqkVfyeu3=WFTa6;}3MZ*{Ivf_6(2QhEusfo6K!w~w0Juhf+(pO4 zpkw0)9|pkzRh3deKqpR~d@};veXH8GA5O?QQY3>bCMhYCp4s{{6;R*vn3GM6*`=k1R1|#6d@H2itNCr$Uutk3rrK|P4(n0&{g)Tg zr9YyB~{UFaCDwt!c7qb|1+Y;weDbYcSI1Aex+u#psL zYXn2)g0P=2T{b7?%4xP{%f%5py1M$FcievnxfibN2nq`m)4RWujtt&)=P(%&LMU|H z{w~~jbxPicYQ{{!ZbH^igv+3Y7Wn>srHzl*{Vi_y-5p^z(O~PN$K@x>>+AkN3eIv! zVyOWxaIxvFFn+EMQc>!c$#3maB~eJbmW1Dbh>d+>$)Hg#=80|}4^UQp3+N z``BV{SRyiUZVpMtJeMk=KQY5zqd(G~^%dy}G&FhtjHcvD4J3hAAPIQ%+fe+K1dx4j z29uZf=j){#LYuEq7&X3@24DDR658z%6zkRpq;Oh`JW*GB7xXd2P$q%SN*CaY&QRQH z2Ry3lpFe+!0=Df{rI|{Set}aepDPB$nu?*`F(Y`kC+Y(Q^F4Wq4|0e~r66Scu^JI) zKE#mRhfTi*s|gFeG%Fs;P!59pur#x3P~DY6lL$;rZQU2TS}kDPQ>Usi8cfbt`;0-S z`UP6h>t3td%1ZcrG)Gdg0dfiG;iRtD@>(!vP-tjB%aC*&eGV|Bm`nh7S+kX9wG(5W z$C)~hzUmEv)xymsnuoI-zTo{0D^>G-la@xVGYX5&zdY3Rpo; z?=ypP8JW$pY29j`^S zEPCCCgC;qlSUnt3<(3oy16UsCt!UnMl=7>yB25$14=>336hrMgBlu8u7nur>x^k&7 zgYW7>ahN3R3DK{JllUR6Et!xDW@cFP0+pe%JB~o>N*_jhdV2bCfUhvZUn3Khfpl`nsP4sjvN;(%rTUT-S7X zbpVP#n!dQxuCG60MOsQ~v@fu0*P=#o)2DY{!yO5*U{qT#c7c7GP!xVcLgE7Y;zj^q zrp*^T{jS8luXKTa8?Z5$RxnVc)5w!InE3F>qHlAtgft@0=*jTKjlILp#2^-{Q#H6? z%t;cc?*Dd2L_yD2+d>+Y-*}QdJ$hW%Kj~3Q3@CwT4`4G1qCfbO9%f*f?*3Io?tO#GxmfAqYW;KZd)H z4g1H^rn)oSeFd1BExJGTj6h%?8HAu*K*pgwTrX5tD|ab7;aoeNJQ}J$Fx%IB`vamQ zA1M`Sun*|gpaD8zVB#F~9lUiaKy$sn+bJRPR~+Pgll@46uFh$1=6KTCac5jKhDuKM zEA;M6B_il)Q!RJ&Ppo%emyQv;1Wkqdhb=xVI8moJpevuM+fW{;$7aqN|J|hoTVR85 zJ_?&#hC;mT&!^aM+KwT%#2m1UKM+{V-}?N<$Dhle=dfGw)wv`*aH{Yo`W7?ZB@86~ zRa)^uS6R-7lo@pK>C49A?a$S+Lagp2l1@gQ_|WsK_c!lBTork8vZ;Bq6}i<;t8{3# z*yQA7hV+k|20RoA&Vik9&|fWrf$3M;%kA#sk$fCY)@SP|bcPNskEHbp%bA{X`nRld?HXN+0^Opi|x7u z;Y77>p6K5DF96#5_|!;C+}I)j^_T+6I-f@#(#whEpfdj~^{+_pBqOBkOL+Aor5uAK z&>j=e>!e1*Nso@I^?r2*+dKjBhj@$4(uGOnX7_v6`>lhkQYW8jk#|MKe#?E_kVkY7~em9XAX zws_+0dV<}L(&ct$KowyZ$YxMnHEz2#Av`=e=XV=;_QNR5YCKYKWi?VDnp8fOP3ms> zRRK9mz|O>H%0blZ3fdql=|JwZH#-Q=1Am67A!`a%Rd$=a(L2R4V$J3-q<4uGtP6X>O|8(vCpOr=t zUINK#s@xC}g_tjBiBb}cl=J}YdWDLGdZfnIfX#9OiI~@suci`}_0(S1nT8DSw4s+bSjo#O!S5Xy}gm(o)pP}^CS^)1#jrAbave5d}FNl?47 zjt@rxmiMBh`Ktg$!7N}b=h6SjERfE)MNwyr?NwH`uBT#|RGwl)(TB_gK(l!jvBY@e zV{I#q&@A%c_5Zv6;-c~i#eKGP7>3kpn^P-+MfTt|BSO$4zfGx z+FIV!2ypg?!kyIL*3%(AuO|>*tA5*mj2kSBl3CYXQ@$Miqp@;?-@fik`iEDyWf)zG z;;~sRlkOs(!dtnt%?e;8$S;qg?V z^uWyka?{z<*&*9Je%W;9YXkAwBD>xNzHJY!-uTSVdO`1{M?H=86I9LfFJTE{=2Lf7 z-c2c^WN{0ll5PjF9ZQWz~kLPMwbBJ>2PSv@`wp zXi1;FCRNz)ENg|1tHqJO3y~=r5gM>Df4ZZ)!gs0CfBO z(2B)QD^E0QiVyn5vU;`>e97pw$vaNHdRv(@!|4Q0&{5fy49*IvPICFTR`$|CvZ!4v zc%uqWk1BHTa>)Snzq4rU*^_;CMYIZ)#4W82hRui2*mKjU{Hj|*tWL3Zz61DJAKcAu*{fj1m>?%(lYci0YW zs$o`E;UjPi>`twEjZ3$vYj3B0%G9IXW?TP90zH6$y6wPlz{)&Uh z?pd|^2dSvw$KT1k4k+95L+--|*M3*l*1HfHthevD<-XQkdcoU|Y;%3{K-OxF{z}7< zo9s1RvN0uWi*q%VtB>fFkSAZTLk7#q6v)zs%Q2oWObD#BAM!;Ua7O3VMT@1RWfe6n zuh#u2Elv8ZM30ge2&jo)zAkVa zhgTL?{izM$L-}%9ba_ZfXwKCfQ$?ncvr-^E^h~_CM2fW~{sok-OA`urx|p=bGM@A& zP^rb~!&zxYBjCD}58e3qF4qL9D5mOV9f8tfD-_dPan5U;vQP7l&wJo%-Or#|rH9K# zS)j1|0em6-lA*ZF&uWXUU?Fb9hr}J8)7EpV6$6{Tf8L1Q1Nx^iw|~^M3cam!i%ZL1 z-)D*6*s?`MBoEqjRhop(w%ZKKL{hk3$7*)119fXBdGSp_;U(XIPV6t7 zY9wH5y}C*^d0=vhgTLv8zI+u?uAo`+NXj>uL|=;F#@d?J@TZiScJg`(YSsJmlo40T z16pFD)sIh2S0U*UUZRMejOOUM@&c_;TxrInpkg2~x?L-F49q*iC9z2L7bB8sIX` zM7I?XPx!4qm`OOKKRSxZ&(ox};X0e8&#d|R7+%0GXxUjrtWiCt_Ui5ZQ_%K)`-tjr zCXt(^ObJZ`h=Nl#wPKWl~An-_eSkFqMp|CN-r2Yetp3$#4y8m5gYd zT~o{#7C0MrkKanId88^-!Rn&~4y(}RXgPEM=DS0vk{nFnW_JA{-IBj@!X|qvsQ3cb zDRSvqQSQ;+%N=3OHqeSw-HbLEbF!v2#7*{8-9 zbL0GR!z@x5X_FPZl&6jli%|GxzKj~Tj64s(Z8v2;ZtsO&N(yMR2y5ttmDazKtESQJ zwp<}N*`sM=F_7BJK5EuxylzObpi;>;lW5Vt&VuDDs>}pe#w8)>&u!uUCVl#eX+$BU z*Kbcq{h!uHIw>I4QwzJg`T?><4_jT$vGGm!!ip9zyLsP?y1gdRzj^!pn{m3;eq;PY zi6(jc30qMh3+52wmtrD^9?t;Q2kNj>>EbchtyU;rb_HdcJ$4_$JRz@Rikc4TXq({M zSU8bU?>sMLc(Z!KfZc&4FIzBow`$Xv;nVE`yV}RT1u}k^SvV6^yUbYg~RuK}&uI)Cf6= zQ8p>w;EY4m|49wOA>b^q{E<%@K)2D_4!@I;dMIPJA+Q)DKls!v3K3E0*&zATrO8d7et_{SLbjdU_ z@5|*oxnAdYp|{^m(;-A~azsLl!s z2F(Z&R8srth)aP_>{BYJ#|qlEL3}W$PnUPt8AKp+OqEh&=Ls!xt1>WCe5vch0SCdZ-a z#UJjO8a>_mR3en4siJmkvKqTdu z8l)-DtWckgW8~I#pe4c6=lBy2f^~yt(LQYJ)s*kliZPd*x=Y}-h>6k05S?@Q8me!X zJSU#^EKEO91kRZrKf19pFUPd?g@bh2iq|X9B(}?y7lzdQg5n)G(s{OjSIn{$>zl}* zn*8^iwr|rB*^w*Xzw&qH?C<6?9mFQZ9}km7M|V~4{b->7ox0i&ujXLxMXS@@t%aIy zY#1%*b}8=~Ux#!-4oy-o@0IC}hwc&j43toMv)d6R(j=35`Je6Z8?U}wD|JoAV<{=& zO#ew}XlhiO3;axA-U|}=2ka@E5ba@$N zceWu-NW=;~$M?%000w-W41BslJq00r1x+1hmO8~X1!&H)x}hr=LVRorrkAQ~j#LwN zX_``eV^=k}ur(v$QUyj%PUyaF!CrnRLkBS)@XR-13S8drdG9Nm4L9|5v77;#UU)~(Ew&}#OriiJjwG+7k zM9-e5Ec4;V{vZ}&D=gH#C#WxQG3O9Y!*!qZMU7>ju+6F-!^fIGG7}8hBB_&Z+2$jq ziNg^okXqp+)!WznHhWx+p{GHcLXB;S)R%2Fpe5A1Z>4C^iuU3#3sz8$tXJ7>UWYMM z`knSj7Pvo(!FynB6I4YcG3|sx=(#>Kl=)PmkoL~?$z-QP>IqxZLPlAO?x{-tJ4o#@ zUBO%B7HGt195pW0`AktQ_x)I*Z$v>LrCZ=t+3l7aS5$#Ov${N9q?dK1IHUmE8D197 zMg$9}T4uMsFvFG9dIh*&NLPcpg?=^x_mBmLnJ~M~`8o^D?`PRfg%50YCo^fvwIzIN z6VxJvWmp{HZ8F^#?e4spDCbhkZ|P3Rd|#~)+_&U-7UAr2#r3*U=y&%T?U z9`;3G!r#cb-1?OmFAD8AW&c9J*xB7z%dYVq6828TnlsKOAtIjbQ7ik4>H}vN`i2}D z5_V4q^m;mCW=QU9U;`oY$WK^$NJv=l>!FHsM9Gnhy8ijlkQRq#QE+enJNVN}$56b@QOMEj?uUgJ2XuR#!$gZKFiB8_h>KM`5(^&7vI*<^GckB?)w^`hW+zrC!Cxq&+*-Y#o$=J^ zS1=zdlAvQ%a(^p31)t^c2cZaz=as<-KoLrfV3Saca#n4UY=i?;-K78eSPGPrxz}+gUesu$=0Qjv8ddj^cW&MSe@n8<=ZGM0u5cPn#49bv1q!@oXg z(s^>SXrKKL>cBA~ElOaV!>K!6(ioWWHq%r#qHoDr1j0jk8wR^%s>ic9i%TMUqntPo z!^q{J0ofPsZ-i;HiDzT0xMuV;oHkHt(g3(7q8*w=cXkoHx7R}a8ptMM>>V%vMkm?qb%fZy2C7x2l)uEvIf)8(eB22;XFbmwTo_;<53Yp#uRWq@5(msW2d zJ7V=tF>IhK~&kOR{a`{N?o z5Aj;g*>7k69^}M5f5zpe!i!FNO7mUcPa~FMWr=r+*$&~xv&^VB$9nn`v7A7nSGkSJ zo4=K`u%(#ak#fRObuFT^U%gCR7yM0F5CZDMZrWbl9ZFv-C~ZdZZ?M7#O{rDF($sp4CGc`TVkDF~(Aj!hXf z7jdX+>?cjXW5auqodP=_HhV2H{MEr+o((M?O7eYI%T*BheeVvPJ9u-dgn_*|x%5vh zuuxUS>FMJ5!xUYDW5A2TpwQlab(bk}7;EfzbGEiAt9m@s_ADoPMYxDZ(G!g*h>lu> zz1&Ata?d(d3oHcL<2faa)6&u|Z|apx4F38kmYf8-b37hHO00RGU(lREnaCRxw%Z~@ zpXs1_%NQm72^X4xPJ?MyLmBZpf0H8YL^ZFqchu($hEaIr*C&Q6fNMZ44$s|2dDf~L z{WW!YwpD}nE}cNL<>`sW^r%nHCF&q8Sk*5P^e$*g97_-W{7|!Snd+`7+sTNp3MjG) z;1B_KD@J~juI0r0-VA_FK0MeZXd1`qLHTbK?8`D?OQg|QWwtwvQo|_6Sx}Gh7$?9z zvZykUk9;-D+iH%qXVR)hNDAMbH@#6LBf7gWm1(>zCms z+8SeBCjYQ+<&zI3nB;lYa^4wW2{pUUV{fM*jp>iZ*a$YvAZxrH!#ED7KD5mm%8FOO z4o&*r;?(TP=HDx8kT-4RJ3ppwO?5nO!LL_n3v9!XuMqtQj_KVJmqkuYp;C(x0=hvB zZ`x)0w=x1b3^$Q5e@7=C;p?XXCN&-yp(6gLR~s)wLLvs74X&9{5dxe)xGQm{wV0f+ z*MC~KO)yo+{JeTAwh0a%WI`A5ClB)?-jpFWs0ON+^dAvhWC0wT$z^u8g-%hzJ^b(_cNS8Q0vzBl1SMK+B4^Cr{e=-d zJ`QHZ#%r0CvYkoMI6)TW^f5eeiwLccDPbahL=^MzFKV;V%MW_79w?LP)N-DMcsy>& z%A!S+-^rreMGc#1M3s0pzYsAoH0M^z?=fb^}sbElHwW?$w-tyq68940L-YwMoLx>i4sVb1BoS&EC-V1 zK(ad!Z>=Ogfy5`6s{{aRxSRNcM_xehU@cpxX(NJvnB^5deNLTo(S$mXutUTx7W5oud83E2#IOT<<|SfylFZ9y zw@xti)B=xklJ8qw$%7eL^vaOr^s4>xV4~?l-|eQ1l7_>ql@$yCk01rzIW@Xf1AmQi zzhzA{Abb+VaLW3}l!LyAFwR8C;EM_7YCzfO_GHz#hc-2Q0ZM2DplU)0x^{-IG#gHu z4I@Op2B6XVQ4_PT;%j2)?Hq`3H<>w6_WuVCch%AZFlZ*HRkQyS7Sjh|hI83PzFz<{ zKDSGw;%ZJtXt?};;$3yO0HmjHOF;c6c6Q^8CEmu|BKGS695D&36##6v?$e216Vr@z z4(Mpm^3;$G{|OH6asx5G*7iy7FO10Nx8DN-J&}leBPKPtKB%*9GwwHXF`vG%Cq|cE zvnXkpUk(?}+OJ|`2+a<+#0Kcb&PM(fQ)*dFA$OT%l>#SMOE2(!AEYPZ>y@RbB=@b_b zqX>1C|3?;oh$~?pu*BDFz8xfrutJf#Crr|E zh}O>yzR-90cN#SGD)A2`H-XBLOXbiZ?u0ByKs1NmUpP3w1N5~2#V{ZeES6dYu(MSw z&-SgBCPn(iS8LLYzLy2JMa=zQ9hfa{Z=k~ zWH)Gi`Z1GjpbFX7YZL=LJsOL)(i%evWWbNq@i1TbM5%b@B1>3eIYvGdk73*<+Pf?# zn7kGNE~sbDDqiOe9vXH6gyfpE*8aUwOtX`P2NzT`XNlFIX`+ER?wlqx|? zM)`ypq%~cWCWSos!qPj(g8&{!;4*2_-i9;v$7D!r`$Ce%mVB<++73o4R~3^u6F0)% zCXzRTS~8xS9oa%_+tZOgx3pLUb9^uqSc5BJCer`!q6LPL2D*JMrXuR@3iQsp@g4J< zbhYj{kp3Z)AoZD%h3`St0P1xmBq=2G06r@=-*Dk_ILF2GIpKN{FK9`Oxc**MMn3eZ z64P%|?8vB2(**Y|V6R_Vr*6*XWtuuREQwQ63{-aab)P2`pf#C5>)NVJ48@ImbQHYM z=}o0`F<3n8EFJs4iDF8PdN0(w8^?jfO^jk^^e!26V&_`NUS1UQEyI(c4fvjqmoDt< z_aLO+vfG<7qb?Azw1wzJOBPwlB0JZ!0(v9y-^7zg;=f6@29m9TWY;;%8I$ZfwIsVv z37{bXG$dHr{M}ll1S^xkuo4(n0>erW{`ttu|3Vm6j6%(YUM0aJN$^M#mz)!01oK!D zmz2aMB_VG~$XmjuSg_xduqnjApoFON|4-D(!8Lj;TBJ%jxYz2WgtW7O+$G_IN%&wA zKA41RD4`lIFpUxxtAxcWAxKNOTN3V;guC^Lo+07he>`|alGY(f>yTs&%^{xyp7sCD zj3H66xoP9td%xe__Jaz?;p~sDi#3jGN*`AYv%DdN*_XWf-ix zRVp)yeIOOf)OC5{W?6Ki-yU#ye604<^$VZS2T!!-ubd&GCxg$qZmiQ$KE<#}?`|L>#kTTO0qpXWShe9yeuv(eaK>ZJLTMvNFS z)o`8erV%5?Ge?XVvva~YxbjTf^9laoXSp`|2y<39@))bjyZy=0u~V3OexG)6K&L{xNW& zcref{I$L}gG`ONKFE1~PL;r(|W@J~gkK2GH&>5I6KE7@Yy6^~!vWl|ucmcI8eq^fP zvLBwwUPbd~(X8;)jZ`NSYpRpC;5&Y7FBidgs0;?x6Lv&v`cla75@Vda;EEH&$Jxb4 za0y6JSc=zMiqnR#qW|M{gsg=(bTW{Q-MLf`zf=XkR8?E}VyzDLLSgAz72%?8LdFL= zds}Z%X1e(>+}B!fboWsRB*G~N@6o>#Ex^Es?6rl+aCY&8?VJMyo8c8yFtXqZTSzz# zhgT60Pxa~FNw_h(VCELse?;M(RDU;T7hmDsf;;^f3{O8dufZ273_9I~BGd!niew)j z25a!wTp6Ci^9jG>1?n?sb#%dO7^~4$lAE*N7QuH_6bJ%Z(DijLZqzOPJIgDp3O=Ec z`@bwaiSHJ&GlM0#AG52)go-}{jp zJ|B(g?<@!UikSh~)4yNw1Ul@;?$=>p2d3q2G)w|(!DRg0fbT|RCl}9+3|}`tfdM%& z{QMX+uwqa2!CErKgX+WZr#tH~JQ+y$on2hX{+__Dk1J?1qo`7ylUD%sadpck%g z0SHvqVjF7rUj;)ETtQ2b{m6hW0*Vy$eVNpy3Tp#sz+;__>x>nw*=rS@NCEzoK%5(S z-6kAGm%%i`JL8?%N_Zk$iAkYRm_&DN7Ewnv(3wVYGhAowWo_xK}9=f6T`%PEz3pMPjw?Y&pJ;2!67>$f=3 z5gnU6H|Xjq!g{d2HqMx>h$p&vP$@K3oZvGL)&?^}D%oJOm$kwc9HI@*$cDY~WYQ)a z88n7yPV^_b>mhz3+5%uLC1V}LPsD3Ie`9kIw7Fqt{w&%|bQIafZrV5^TT$Lv=bxm_ z!rwShggicCPmM9IjViu8Pl zjTmA!LZNMTch*^pqtNvIDGJtrMmSYNxrV(^>GD z(ihWaZYtmvMjHieP7mqlze*dMsH^R70x~6n9-I7=G7SXW0UHK9*+Rh+RSjvzz7#eN zXoWxo@O8bX72cF8v`m^4e!U+cgpi8?TbvCn7=Wp8Iu9j7T|)(sK)?pGwQMK+ChRj4 zb8Rm;HN%?ZNhhxZGz7~tF*gK>2{06sB3qG71Z#G|&`A%ig@bz(5yBu%Hi6In7ImN( zdU&9YZRBpn{wJw3c2iV9`1g0HLmEw#Hw3gZayP~OgVce>Dgr|PP3rJQ?iM(p4y0nJ z@J~{Qe8->Yok4&X_;1h&L!>h-KyP_WM|83G3V>|j9X@)V0iR=@C_seH0BT?wJ!oYL z%gCLA>=N_AL~{&7koIA|(l}5Xuo!8p&{vuxeELg2sR;f`0pXU5NNTCTQ!Bxq0*zOK z{f6Lzz^@B2>kF($8??y+MNP-Zc?6h_%tR1I82(J7J{mI=sXIF3cG7`Cw>DuO6#m}LybHw=5M0Bb0p@XQ=y z2wl)x0iJ>HQp6(^9pb-4u0#b7V1=T40WuC=2}SA(BG9~lrO${WjCBn`9#qKutPm#S z2l^T#^Dm9}Ex?-^_H!TNenA{L*8`}tfEdR@>7S$yH$)M;H z^LKwkZ`>i9Gq*t0!MU{u#dm*GG6)?-#W`QZJ3W75pcPO@#B!&9kawWb5a0bh{|!DC zDk6wF@V!=w{~&c({3rrLzl3+@Nau)9cQE}Y(Le#>Vg(VH`~{SOUMLdHw4s6o{0r0@ zn8o^iX+CCb4!HLz!$zn5!wh?1b;~#qG)os%iZCCB2cN}4C?cq4SpdRQ5eA5idIzop zQ6|_8_Fc^H40w-KnT-4W(C0Rn}e}`!r zRwFexgj(2NWH_Hk8y+xC-gr>`_KRzMC=LPo5P~3U{l{nnd7{|xZ}Cm3KYRNJ=|VMJ z_TQAJ67U_15dK-78A1mK^yKg9+Mrs(KgTyi7St$Me^Z`V9t%;MFgHXoHJ0NJ@m7L5 zhmisW)ky_CEqDd}GGTKM8g?$iPOpgeA$IA{dzha(nFcPJ5H=-QpIWi<@(PNw{Y}>`gIcjl1X%*~^ie00ENlZ)KW>Dseom_tz9a0k z{`q0hgu{@AtdM%<|Isd}mm-Q}$bZ%iHTM8JP!)U+)zu8-eVyp22EPU8yiQx$h^-3! zQ;NTHAkiNx?{uR;usvOECIxRzhv-RxOxlb$rKuuM$1>D~4yw5x#PQ($bWK_C`ImN1 zLBBm&MwV-#a!*xuwp{PKLB|-oMu8p(S;u2|cU0JA{n#~iWBEg_1bs>4PhHj_-BKe# ze<9FC!P?8ofTe60Xc$N&SwVkea3>Yk@uKKsvEJfQ!l zhdRhmfxs#-{(q9g>ZoF;v_PlS{i`1C@O@E_@nbgw)n8H6i>hrP3n7L;4m~{DB?|gd z7;o2lKv%_25Z!wCLPy2lm_+phpUx&)TKN%4C|WfPaCX-xJDK57FB3;JW3k9OIKg!{ zTmV@YqJ4LL1>$BeKj;fXjAj~Oq`Q`3gt92OZe*^{5Uv+MqTygKQ-5P!Jzt{1e|Mih zOytKOgj*w7?7NH z0IUafB$#u6jvl&(S#KcJl+pJ-S}_r%YYN}h122v$q1xbyETGTUPuH-@UH>U{ROuVt zSxjq~4KTvPWJaJOnybODg()CEvKt*6ib9he{|Qf}jFVTERgzcz_(y4w)50sl#{>o3 z$3H@^Fu;WoRD{z+1KpQ`vZAaKi1feay%dGa`#p=Loe_lrDE%XW2G*4eAT`zwp1tm`tyfO5bReh|@8SYTSfJp&E`H$Dk z zqnIytECZi#10e|&Sy$q{W5z!uh zO&7=tiyF{`6&qz*0zJTbKdAQrI)ZhhKYli(I^ExM8Pw<2>%SANie^ZJ6BlSz6bF3l zaew^m4^|a=78HSQ#0GUSzw)2(BT6_W1zDWX69_XNyt0D4>~M!657Wx>LVO|Tgb|sUHnUK>V?V5Gq;9$ErjKpVFncQ5g5Lk=u&+FgQ07K@Rh2FFyBOX3)YPw(unXK=+2s(`VIOH zOju&~A?o$0$mawaE5HmcR1r-eJ265NaJm%q9^{JyT!SnIyXFkp2>29tzHqL1Gt0~dx=UWWVDehvzJI7ZiCACCM2#2^Fw>!+DBEM6B>7NPt6XIveO zsc<3>EWZ?>K2#@#v%5%^f=&lyw|_wWz%Iui#K)owgv%)7z~*6)S7QH3ciq6)ivrm( zOcrBPy4Y$4#z@Ps=^RYMu$X4Z+0={C$|%L!s!2P8YhfHhQ=Zs(y3^9Ud`TyTuQl)57bb53$F?u&*Ni`}+AXJU%|V z2R)zuOZ^X!EmgqdaQgadh3o3W6Qr<^;Co~rzajg;<8eN0OW_x=H&*D4tP-q?z12kx zEOfWv9g+t2F2KzXyG<64$D>c-z2Hto6)0X}??2rNAL%tGEN9sU$z4tp4QeEFynI$j(r`TS?=!z z|M@+_Z)3gPzxw8|7O?Pq{|;aS4E!UkqIi;hecdPkE54v(e!{OIfD@phDCirElk%WK z0tEY8SVzE~zaM~gN*GQec>4&G{~oLp>e2r_tW(A-LmoKT)hnuga`pXK@Xy1Vk`i>X zhHi}~4Bz^H9M?o0V;~2=414|r-Q@8@Cs^?K0h0Q%eg1bbPUz_dV4Q)83G%$)nS4Jz z@DIa6=qddHff`x(pgsjcB^25WdxD?l=Io4qFJLWei<_T|nHL!gZdmYJ6L4*Cm^ZZZ z>k6G<;jc+3sKB?e_d;S25Tf^@U~oYEj>0yVjEwCK#$5rl`#QWz~15N0}Orve4E}v>5g6%}FyacTPIJ_`uJ1M$cBw z^r-()aSz$2@KsP~P+x0sU9#n?8~1zdx_oK9o$<%_1=L-yj-9MIX2OicT8>&{N>($A z11gHLd(Ut}s;8;tYT5_?zIAy8JG!r}ueX%@KB3Pw>XwP>+f(h`Ne;K0^T#>A=SZyD zJ25EAp`2$NC%>dM`dZ)Cb!o&=*os?6jQsQ>bK<@k%%F&7S#;^PnHKkfFC*`14n2z_ zvrK~7ToU(gA`mg?mND-oW-x0?!zUv07N6dl7(Ihic4j+oueO+jF_$={PUX|`!VSZp zPn^KHY;!^KTUaXGcoeK(xGOQbzHaZG9lVS-YT)oYI>&D3b+Q~sp-Y8{fX1 zoa*!__ox_CEJAJnz*At`obrctYc{{%iRe0Y2XmKxxjbDbi7``1yT+82kU=~wm95GmxOps42N8}D>u(kAJ zehU3p`ffz=YG7T5hSXP)d=<%8D;a=XW4>C+SK#{UOTPM&ukQV8#5Kq>evP=k2EkwR zlCOEm*HrOq_C7FS_?o?cEvS4gsC=z)eJwkFEjtcM7@%DIwG#ZbIRCXc|FvK8wT1Py zg*B)lC#tLX1BDyX-B?f_UD~eyid7nt-i7LIiVqn_?U;L(^w!loH9sIExG2YQFYn-; z#`>v)dXlSV&0yMGGfG{Hu6jTNxQPDrDM?Y4uhDR0v^?$o)3n;IQimP&a}omd_>Hk` zxzp76GxF*sv%4!ROS@W{GY2VP>s|e+Lq+=~B(?Z&Kg#D|l zjs?8i;P5g*{&|2Mnect;twCbIh_Qw~aEjLj`X0nQdrN3mx4qlq&h0r`lW?Gr7%hH4 zy_GxZRc%VKtOon-X?a&Z_vOt5PU}mR=6(3G-mZEF`FpO>G;!*K*o9{d4j3!PB}VUi zsV(BLbKtP)mZ^GMN383mrS;DOz`@05Fq=aZPRwPVlL`y&ZeDuyl2%Ahje}HyQOtZs zSb^I7@gXmMJ(@r7T->7UE?)iS`^uE6`&?>S?sr!waSV?w#Mn1z!$(fggU-9>?}4s1 z6rk3)iQbc(x=Y9Ll)5~Lgb^Xd#U6t)Tcp7j z4P)nFO8px!?_!G)JNfK(Ua^GiO3jwe`}o42QnPF5oV*uTspo!~+iG<{vp2wKuBJw4 z$32H5MS*!T_A^Pg{uUi=p*<5gJwN)}4T;a7b*?>g26Md2le$Al`0J5|SrRy19MTKNzgPo!wiLy+17L!{a8igzG(PkZzLeGb!)t!yNXP)N8HcSG8_Gc66BS zopJ-dKT&pCgtmQq5l%xY$+FLwNM@D1x-RdVzpqK7k3T12cY<9IEu*_quD&Lut+|X< z!lo|3xouk0^WllSQ||8e_lHUOlBMnWSqr}Bx9)hRH+*zr+&V4p!c#6B3$#(g9^T2g z@bp`ChfFl)sd;9Hbl0)6W#&aDILK;Lp6DtRs=(3Ir1Jf0`4Vzzr{q$<`<#VmFnvSE zy`RP@3a#~M>|5lmYuJ9`0pUPGSh-~7Ia}Ypj+TV5g=$ff5_v^N5}K*OZJfrtq^v7V z#W0p2?XNwY_anuC_nvR)h;tFLuP+{J4jBdO8w9sr_2wlP9ocHI$lpA;eTmc^3E$*9 z)4M99%XdoBm-p3r7f4A-bwAp*BAY-?_1PpbTzBT;Mv_@K#Os*AEZkd6{k3AqZO5sx zduRpw_Bib+DLiIzlX_Tk(Girev} z*-eu1S?_;Sd4GG!y|8Bq2^4YWuHpCltgo}Te$=kgr7g(d*U{!D43-SU(I{l=hF%^kFv@sV3I zO9E^1Vpu$j-pspFRkTSLfJ-*koGr? zdvvDFo8>&yC-RidcHXlvdv$m7*)y3PMavH?RAa6yvQ782S{bS_LlX=t$?Hwd9EW!q zO=I_(G%UjVzdx9Lw&V4IP(}Ln$|Fs)e5)TsCKZM~Yd*MheoiE~oyF{lgZY3UDty|g zocMwW#Gy|D`1Tqa(KlSI!~*6t>DH#WQb1WP(eq|6@a)&cLej{p!lHJxxdNwLR2md&PA*YWFRzH(VA zu9rXfKaiwdGhGnKCCgXd7~Pe=_1kYHsB!q9*1f)aO~%Ce)?N4L8B^C$9V0=FVY_x@ ziJ7dv(2Wne*gcbZ@u}ac;nt-+8?4K_rtUbfWAsWGDdKdmzEyYaf?4@RhmQ4o2#ntD zxli7B9Ev=j?qj*iKB$geJ+(vThl|{ejT1{u7Wv#>;qZI#Lw5CHho0`WniBVqi=B&O zT6e@z@1LC4WpvUqZ@EnTH~h_a-#H;4GgvQ2gG-(E`Y}%dNdolb0jmpQgtChV52$v& zopZaqtwhaubw`EuqezqbMSyiH?K9HWWVct;G!i>Hk)y2F7c<1hfxB9naM;XVV`PZox$xSlVbTE) zcR2b?PBW(@xlHC*(QKlO^V^P1G6mJ&z8Ck6?_R=hHL8gkE}bzyPMGj9Y#@RIjJ~p` zt{Os~%=Vun%W|!*-j$q>XL{a`*39mT-q5iBTdf179ti;r9SM>4>ROXI6OX)}AmZG& zX3Svj3a`G5Har*yTr7Qf#N^e}L{6K1kY1xjL0;iuk^>5n=qsBJlWb=eEC}&aEforE z^ZgZkWhQOh@Y%S<8)1ZQ(ZB$fAkRmT&74n&*9~boZ`xQJO?OvpxZAvczS4@UEx|RITDFGn#ElUc z$D2t{H)M5J1~f;PzOt;Coc-a~_AWD%IZR2;HxV<3m^3U9KpsghdZLXuIC?1pl)7a* zc`^A>kxMrmxum7uPLYZ%gs_0}gEaWNSD{_CGF8QH)iLF-njgyay&%aGK3~4{>v`fA zx6+gH#JwLR7b(wTzqsO(#N#G4LeO{V7~?)SNgnX4DQ*W(KmNhS;oKav8B}}`W}W?6 z&kW{dUj3^;kBs*g3GNF%v=li=#i@5USX9koN~SIwE$Y15aNb)3&ug1g*B^U8O#bu- zgZyVCyQO?(I)2=6&%79?2(EdHu{{L*BS)+;|B|T(Ts4EW*BP5Jx^>9VbrbFhXi<%7aR~ z>?a1l(d^dApmfzrMyPl3ua>{^efWL#3y2}g@5&^s43l6=Ui~&=DETR}`o+zd>;tZR>bLPL&~=lbMUoy$>&tg@Q@so+x6w$#1Schm%8lUkxn zW}9eqIL~&FunRuXeroje*-Xi#g*qbWotwTjQO!>#0mYKx;-EbpvPnR1Y5jHSl+NPp zsB>|ltChKq5lw|J?5HvR?&BRY0=)N?`WE`^znuDFnMU*R!rYOEq``AB@<)h}UOEK3 zoaQEXB){9Xh|l4`=g4}FoCeO@X{GhG^SW78FFh!ct5VJ{?0zg4rn+CPmFu%VV%qBE z`I$9#IrLf^`Qd(HM0gztu9q~QMer}a?XIb@p^cF~`=hg(W77Ia*|V4)rF%yXRx*riKe@$xCZlR0;>|&bjiT$Dd?s+( zO2fkVSDqLzZK^44*qPRvUgJJCjGt6c_P~Z=_b{2r384Tq(- zfWWm69&pf}i_IW~dy=Q8JB^(BD5T4#bbfZn1IGHd#bFH*+%0FK+;y_S3ztD)d2LNt z5sw*pm0Bpy^eEmLAtHjCVghMZY#a;ispSgT={niQ?G<1^s8qM(D|U5EWd+GT#DCu+ z^>pPA9nDpF`^1cw7itP|aC@RnvGM|=q47FI1p%XS>KeK;q7hpZKrQe#-1X%EL(@BQ zrOS#-J2$I#gpXe|H=*NR_NA#kYJ}1Sgi=2{)WY#0?YDC1v|=wDGT6a-9R3E( z>{fF#9g~|8$jy^16BWII8>8&+9^4}1;I`m{p>*5=2)}H&v{$ZEbVU#cuBYzN$&9^- zIO}f_%HM_)Ux47b&+E;OsEFROld4JOY2M%*l_`sd(J*q94xDILRfPqj?$IoiQR~6k z-5h!_AY~^E zuTLv11*tcU)Ga%aYqX z8u+F*wcz&AOe5}P%FKtubI-*a!?z~djQn{6l8%-J=#2))I^;2Mae63dVV{oFiUO(Z zwi55hcchDUYS0T7mTO7{BfmbgZKb_!Z^#>3Y92tzQGC=qHRY-YaSpwqH&3d1cee?G-moj@M8(fJ^tSu( zpKA%`W(UjY)CJ(38G(X5Me;Th>L(Jpp#OED|YvCn$XD4y8MKJ9u?am+FVr!KcwO10J5G z=i6c$E&+u$xl4w!EBMU9l^+3ah~GM~VliLYA76z%sFDTFC4@}$F(s!4L3u3*Uq9p! z*t+Jh?uBT12}I-vJwUk09zRAZtMfzoDE|7{?vVa?scmxA{XI`i)Gl|25z$R7~`%q zv&e>#snXJsVAcD=By4{5n!c7t8cD@P2G8?`(=x#vB+;L zIG#c_RwTz~W^*bX@{m$gV_t8lQY-_dpe?CFK~8uU1a~2owKaLb8utI7=7DMBCv$kw z?D3e@4AR)}vp_tNx9>W#lT&hFv<{YsY|Xi~u~uIO2G_UqAh0B~mUtvQuHbR%7g1yV zH_wVwT6pDFYjMG?>6!~_60$>AcK&|g?$MR~GHHXFS$;-G^Sx5JV|Zy}&Dv{CZ4jK~ zYlum2Ufsrv6wlk9nV-;j;tBQs?w)0}4)55q`orX>b&3XL7c0LH#m;aBY3b-6H*hnd zM(Xr9wCnIAC>==^EDQ^#y%ozpZ~)b>D?0$L7t~z3y8nwkJtM25s=fW@c*3;6Hw#(0 zw|`gyX(26NYcT#{RPF>VnfBn$MU1YcKx9_r{iS?+R&BC(E>*KwHsF zz(T>yBuf^91DGn(0mOm>Sfg2w zilE{50ch`wr#wyr0fwbDxs{Nb>sdNB8##+YENW0e#{OqH#@0oN}vfS}{Xvx@NbRYR7bVMDl1x#nR-{rBFfj zZZOcaj_r$W%aAr!E1&Wus~*mO@aE#NxPY=f+)g56#kmr{C&coz^}**hH}nNJ+?<KROlRo1hmj;SP_ zY>%lArrJVimmI;k`fPJ!d-;KaNKo&zuF^g`?&Xjrd&4>l!dCuZqEY!1*Q5J{j_ci3!J#j&StdGavn%+%g;7VNprvxwcI(x_LdL{y z4o_ij9`jBCQ^Z}Mhy}6F6&sGJ`P_SXQx59Fx2TUi}&&!%KnT<3># zP{mAj5>>_IL94ePqMfmlZ^qeOyaZcsJwBeic4GJQ)GVdmcV&^1;XP2K&wtJcG+WbA zaR`g|PEMBH{r&g_8y{8`a%s7Hr-+Eh9M^%9J9sPudw}#MmK)rG^$Ww^O!m(C@NQ{? z^fcA)P~ku7rbffo(Pf}Pp{j)+#Ef^#1@|^r*5}YEo1L)&#t@bAfT*o#eZ^QzwU(ij zfu=0a&+>Sc7T|T~$5}0?mFU2!I?>do>d?8VgZe_bvid&$;cmIuuu#>9KYedjR#vS^ z%y{xpt>Aif45_zkc$l+4>~DoR@_gf1#qa43X^FZ#&#Mp0P`k9FYkFw=Ev&sfmmkf@ zQq>4;xLLWTKA=FYj8ob}@8~+cYvJZzi|z@WD66B|B6RGMDYQ@=5d_{4wou-YS=ad< z4qY$PdTSgQvp-M{sEae8xZ`sc0Q$SouHw=o*^@a@)`!RT3+knFGD{WU(L^Zi`)z-x&%V-r1w zqCC*}_9{RK)$u4+&~}By^}$O6!V|@hrCs{rVpI(%YheWF5K@m+Bp-_RT>6hnD%*zxwN@b@L7`vCI^;xEAwE&1*Je|p^tq~Pes*QntDx@{{WR|pL&AA#?8dR_HuHq1>8*+x*$@8#GcrdqbOhSc0ESwuH zD1@Hf$-~0xX1B;V%~HQ7X&q{%Zr?RsE!2<+ z4i;ozTrRfb(<}gz9=0&Nu>1xZ33Jhf{zd{6)BWB(ZmKzk+6HA0V+eBjbPlcj6sfm) zYr(#SlFe0x4lerSRBsvljA6cOM7YHm=yHrfAM|%Q<})Y%?(148+qWWA|G=V!sGM=; zRAhSwv=rv#l}5%X9of;Y8?m-s+SJqoE-H=#viA$9B;x4}v&Tp{VNgt_4@hYK}(w?oHS!>&iY2 z?Ocaqui*m;BS$@h^zfNV`XofVGk~n?mGesbj&I5chm&>s4^J*2~ArhoOrxV~); z*%?<7AyDpqN5S(JpmW+NsUd;@XXIxw$H@B4rgkZbi#$l9GjDcHZN zuLqi;#m}7fnv{zd*{48X7{YstEFX5qj(pJT>R49E!O>R|i=R!(5D}GW`M~n3*GHqR zP8mZyVBGU2CWgYb3oXby$AaR4N3GjmK)z3+ z)qX$>atFoq$d#)4U3C|)GBvb3ijW^gc(pN<=F{j_{97pMX(N-aj60(i_~C7=tPH<3 zw~B}~qu-2$FMb4!yK{aaR&yglPbNBXM~Uke9j;x+!+Qyv?9&y+Wo@})>l&-8#b>gf zI&|ypo3HfSIgd--%g8M5cG)4Tq4iHC0LD46?JyCa5M+}&ap!1c)>~F=)!`iaeCoMj zWB~F)A*R;iVHa9r@dn`Bz2w6>lQ})Sn8acS2hwm+F2>n{EYr4?m>@8dS&w2<5!?v`js$5niz92hO+qDS z79{bdyosEi7Jq*cHh2qShFvmmd(c`34?}$REPeC5&D`4hy6wE)&h*tH0P797fm?Gv zgkpQ30S$M%sEHgrLbnfJ02f(+O?2*TcT;~GEFqx6$3UO4^R}F`q(b_i{A-x9*bdyt{^W2ZsTf;|%eEe#@1DNU#ntiN$jHhWFUwP%|!8D5Ru(C{VrJVbj|7#~YYvN@zE(f*pUnId?T}x#w zDxjt>A7)E8MgRzmzUG;_9wEX^$hl0k#d7M-9MG6w&g6ar<8r++sGeP2cw9`aE{&3M z9?g!};;6=|eMfBQ^GJ5S#L_xFZms0y$-}{8%5K1p#gWWtWZMm;D5W!5E0#k)-PU$4 zcD_XDyA4Y#U=YkQ|Iq{G;+1M#NvQLy@E_@r?)T(PmVN8-i#YRYknWV>t(QkI6_!e# zEI$n$=mVfkZ306xq2#B;u3Ryb-0?6l8rpOy?x)nQ^rB2zS)0Vgy%i?Czr>|Fyh{!X zgn``p+&!kRHZ(T(hP3WEe$~|?F#o-T7_;kcP1$fn8@(9nHaC9ceT(+$K7a~JPagf0 zXfvTV&S24=#`1!rVRE7N%_oZBhnM_J5!N@}=xb&4iN~$}@M!s($hgZXC9A6(d<-+* z>dC#Y;eSGUgxgqY2)%F|fo#C?iVfDc>_biFkohNOGbiVvys=lRbK@GouBGpxU$OF` zdVR)RysHuAhidy^@B1fIee;4LZ(-YJIclp0WruC&g-+(6nTA0-Y}G0Tm`P!9dr-J~ zV+9h&bloR8^lv&~{&r1on}Nox4M$dfPcE`!@vs?UlaS6QjZH_hGvv8>C#4sJ1qas$ zmD|R z6Z0-u$hzeC((BgL@>^0J>oRI<83$-7FV2c*6-b4x0WUhYwD);xS<^jP8<(9BGtPxE z+7o`VUpD<~C)-(g)OHp%&VMtSpX^#vL4ZzT_>+V%qRt(H1Ci6<^trz7R3} zElSzDwnI%_{7PP2YEUn`TCb7%Li}{{_nLY}y&vA}D#(Re3Mva6N!re{<}Sp{Z;-ei zeG4kCch64-T}@%gshUh`v;=0|;07hozk+hcQHszeulKD`uYOuDFlIluN&T_4k z@JwsaT%FZB)y8us%q)g@_B~|f+mtjNv1DYnq^E~IlM`oN6!*vGeFx|tK#vKvn; zuR~*;Xo{t(YedCtCW#bUwny6O9n7!C6>$7sTnVUpcdl>COlZ)zwsV@I>6}`Ni?)=W zmZAeu`uq1mDaIO{5KX*0ba zY_v})Q!31hwad(^lYo97<3@*wCBQ{oXFTdgpFDz)p?D7I44Q9Dhi0+qfpel#>JN4R z5^71Kkwu&`1l2#3@;h&3PJCi9Pptge@GZu?gnTf?Bd%^I@>b7LjihV$1n6^QnIwp4 zjZByVKjXD9>$D6qX)S$NU;myp&74d^Gw4dH!%T5R_!~IGErQ=zq%XJ8xW*Q%9D0FE z2OjMH2yu90LhBT2P)R7&V_gPMuw+k?ghmqQJ%mZYaW033qwkEjsN1CXAPAj#u?@tB z#m_9Df!lj7Y;Rm&cXgERvCy1j@l~BU)r|W0E#KP*e~>T8-Jtx+E6RYExy957YHjoT ziiN$Tb8~;6CxT5^AbPuM7jqMf*f9!|T{F(@HQ|es+qRdVBb4vl99^av%HB-!&7?P* zuv$82%k}=Qt|`tm(^4Bg#^Sgb4i;|9i3ZrX@fyOsjyij;oj(isUU)?m-#?&6-_KR* zh_r*30i0{!ujpFg8po|I#lIHg^j!6K8480S(2wI|g6Uq2jloWYQtFEe5oZhpFb*

|RiZpmr(K?ra z&IfHXXEJvH3fPN6fw@@_gazx6Fj?+{_4ge~et8~a^b?VczJ-b+jJK08ef$CR@%Jm+ zdHe4*QNKX9WP_bp&miafeDxJ$l5Ao?_*Xqe2|p8rpLw1=9Ua+O25Kps)fl$E5s9sn z;FObQ*lk0cZbFgNi)Zf-b*`wg(EDoS{b~np@c$PhZ?U+4ac_I>7q|e>zT{_LrhQ;P zQX=i=ycYaG=ZN2zVqR1Vyl9-=WsM67PWBeL(qG`KtHn4MFB^XecqYn#!8M!^1?FP` z%*XDQ#acTZU>Y5K_ZGvDInBR)tC92tCKSiDqxpY{YXwvylCp1k7zTHtykY7U~TMBdlST zB*ia@j*SitfM$S9Ej?hh-a%Q+Z^F^$?!S@Vm>i&N-+u8dDZ3Tlm}M!gKc#wIy>O{P zcQ0N7>TJF3} zp1eSK$N)+|{Rr-sJvVNrX&lLWqLUTOn9)H}5WSY0Ai z6a{^QaQl;#-D%~Ca`4HpqX(gB5+VkUD0V=zq$MW9 z`PNiUs7d2a`-dw^ifY*EQ&sm7T71H8T~B>lJvHKNb!sm=c*&yu(!08QcR8g7SX|Pq zD3S{!ufJ#i@b0_5i1^0L@F6Z8D7}FLA4Go5mO&@4SejS>^R*$G*BQ5U7|`hOu4(I~ z-A-`m*pb~+%b@U;8FlY7QM=__Y^XJ<-m14uuCH0M0J?@X?=z`!LB{+mHSu-=Wdh9T3u0;(47+$+Fj0VR3a5FyRyDLN2heO+;dpYXA-NX4p*Qt^P#V%>@;;J(v0xgP*45sZcg2axb&Af zb*uwX=lYxuebblF5Xn_lK2Vpv!j`*GAxV@zZGk6+iqHGc#ZtXa7$u#=(P3x3pTx;d zubkZY)HQ7NPc!cobsO*(B+Oy%;#ckvLCV0u&+#@S7>Q~>?fNw(F{rt^?7{;Fd9=bS z3AH@QvR`#VdzvIVbLmCSC7+z}$EfhsOaPoE&mFM`bJoEDFOyMnD#(F2A(BfAYkI~qoa?0M{+{q`{uz1s6mHfD#?!bYU5b&X=^1&wGs~Xqp80*b(^TadlHyu3 zZ;sk@^h#n^(5vG-mvPJ&YFF`B+e+BH0*cg1HF)$+wb1v7W^hoQUDmVLI31&B8TaQh zPc8EcF*_~I^j&r}eAJ}nr?w9L>xUUQZd9&<%7n4AH)@4%nlP8|Dih?CT4`5AzFDUk zcDIS9Jgw(q!?zUf?~a6PM|X%?V^Xf&4M#$q%-i-k8?{D`T|0R$e?EWbi*;qTJ_GC8I<>n;TulV6-aeL8GTtc#rf6M|pnP5MJ~Wwa*{Klrc3 zn?{Y}{9rw8{26rQjYcCQ>>_x$u8X&}@i@k=FN|;HOp&)}Rt&nLR6rQBO`d8E++hxjGEOextYz3Hc&F zEOX)Vhcrk&V(RMu|2o!!Ez&+N9Ge?L3@z#_l1d-pzSA?}D2U-k3p z)8F`UjAK^+4i6(fYB|2+ru9mzEBd=_OGik_og$N0sRy?Fa`wt(UOJOTcTJ3zNRAq2 z1)ykmwQe}3P7#0c{R(9KzW~iwS!*|KLdR0!X z$tLgLOW!`bFnM&~FA)I|Je8HP6!Rh0h2FlM06MsTV_Pf+2@AhTLD9RbYFnY<$tikiJM;ub0QOD1<7HcMTZq3|VjQ630ZF z1*9Mgw9D>Ou$a#_-fQ)=`Vf`L%lgKpESz|?G=6;PWTePt z#?HiXS4}t*gTX_tHfW6M&AJaJu4bB*E4Y3=DxT^E$0D>+YmMJHWM}S4q7+m;y1QvO zqu@k8$^pB(m6$s*@}huocP228CRpCwWk)jA>>1a_95r@DVfzw^r~KQh)h7?#c%iyf z@1QuIIUJQ<@pUC+o<;a25(u17_4-dSU=9hMQ3_bKG#+uBnYV=OZd7sE3 zoEE%YE&*Kev2v@vfTRcPR@lbN+i;}ePTj5Z*@a>;d%BaeXrsn!HfZ#vwLH`{E;Rgp zxHp=#{9ppyn&p#XhKVf(!z7qLSDnUnOkF_Ysmh4BX*>9^so~Ch5YM#~#!O*OWgbd8 zB&IPrg122R@d>un5M{ef0_HoY7GpHz8sBg%awOCfyYk0-@v>jy18obD>Fc@V(!Raf#FUsau1Hz+eZ!IfpPcQFXfiS~Y>$_m(=|ma z7hKOf^7PrWUqfx1SbX~rg!UJgH(%!-?OW>-SI6$yrw&CacFzjvYGLFQx4 z+VhTtw6KBrp`17c&HS?#<9UBsO5$R+%1_Nbfl0oA!OWlp)8M*B@>5`JZrM%O+5lMG@eKXloeF4s=R0lQ<OP4X@tXOf^j5Ol{PJa^9b4C&w;3xPJTqRE?jIDv^E$Fwq*`xu2C}{# zU7U%@(hqd>YEh13YE))N(Zq&YhhHPNwY@Fz-+XWCHUmYHV(i-omnMkuV;eXhI6)CL zS-!6i+O1y33+R4eZLzZsE=%MSp^9A{9b(pz+-q5 zIMWCA0KUqteHREf6Y5PQdfqv=m!!Q4CBK9-J;{nwn`-YF+}7Yhy0ux73L;@llaMOu z3@M-=n&uQC(`DjY- zy93hSHaci|txkD&SBYy^bUEb}ZsE`4>aS0Y-#>+UwCLt;F~|IZMBc`Lj`i)8Jg?Tc z$CT)h$y46jymF{2Ugp&>y1w~h9#|KQC|L2MEZTlwymZO zkJxXNL!Rv6#akru>)*Uoj9Ecnog{fJy~nWqdF8v->^}M6l)0lKUn_8@R=Xb-A)~FM z^Z-Uzjrz?F3lwzCP&{J?=)^t8QXj4DC~4buVB4;unTd5?3P!Odfr(vwIr4`FKZhrp z+i1qyUsfjCn@lLV9L=7TawdZ3xbKX~uD-0Xk{@=MO;_SZRcX5IUoV0Ur|yGh-1EE{ zgSfEqA!5QsMq+V3LuW?Dv<{8nbe!GXlb6)%wkAtvwrcECm$oZxeRe#?>}|YrrCZet*B@{z{svc>`JpYAyQ(^DZ45`mX|=`!xH20?1q5L@ z@fc*`YJ*@UD6D<@f}Y}MJI2>e*~K3f5|qO)e64xtO}K=kMM!#;4Ckg@RQQ%Bl>HHL z3G?{lT5ew8N|YF;b^)Bm$iJ({NAO~lBPM5a>cZV9=&hzFdeEvgCbyIw=TTJDNV z9A_Ok+t=*g>uWwi;(-! z>Qp7CNoLkLw((SPO=Hg6B&Qp|<@D#n%oUmN#@PT^KPSGtfS9K>8-XTqw87I+^mL3X`CS8mXD4{7*LW?QPGie(Zilq`?zaC#wEtOjG z{Z0`g1*)9^?$Z}y@yK0$Bbsk_sd7y{2& zh268IcAdeKpCO2n)DdBPTHyl-aDjN)Bhf}VTK%CI7;N)Ai_Y%3UM*n%JdWdSuU-%@!eMOGMc%UPWiqCG z*RXqZ>Th?BO9ME&7jR5*YL)DILT#y}K5ddg?Pv#Hh(C)FI$}xKPrY3u&%8d}e1(zx z|44i5xG1;o5A-4f$1QwQsdh++lVBWV9L|XG;T7oa5q) zVic#3o)5d7lLZWCl@Qp$uQ^3TCV+{q~K&Rl6Lht9z$j>op;H&e47p&eU>*VxS&ch0Mly52buhk^UU#$@1#{jwy;4J%KS#&w=ry3L zwt!s5cB<*HmM)8xMCTL!oCG^=KesqaI>85Z zvk4LW)U&eBYTzMVc_QVmI|~fz`vI+$u$OmFDc^0I7q4pbpxT}`3f%-#&36Odr{RWz z`YGB`$ifyJt#ztI_*4whQ)(WgfIb{VS>CG~e_9Q|CZ<<_P0tf6kFCCFBk;aPd2r-1 z|K{WYc{e)sz+Tr;(dLO0B57r*a@?0)tix)qLxbS1&(^$^t^4kp?NF_LaEPeY{Hl3G zEvzG3=$Tu)f8G6buhDahp2kG`Q_8%v5a*S9v)!jh4==5wE0@U;LkU=Utq(-}cUHCE z?Ga5onoMkwv-wvRKNi9PiHoCv&u30HS1*9Q)Ht@6$L6Xq;wu2^Io0;q!+RG6_iqVq z@K*>hB9PC5Q9IhHbtB=BFQ#@ng%e$t4Hl;-pmjZITHo;c#gIc*Y%S% z1U~G2-OF!#K8L^#(IxSoMG?qdA>F6JVtnCc^OvSq?Ys*$@FUd$a>~D1T+CNGPoS!+ z8k`c@80!<74p_+@i?n(Pz0O;?*C}m-ytLvt;bzyd&#d{xxdp%gnxSaxJL0E_mT_r^ zV?FAk5^BA#&Ls$OW6PPj=b_8x7IBIiwF&!0h~fm0S*l1=p1RZQHOB@p3vJt%fa*f@ z2{l&<>9*4*Nzd5FfvsX{pPZncr?90ML6E_3jy_J2bs_Qyh?m4=`IN#MMB+HP zu-g;*RE`$AGe`lagtCttqV_`xHCgCXbD#3Ws#F$U>iwy}?u3sNi=GvKaf^_6qj;US ztQ}NK*D@D%c<|l?&=8`%x;Cw0(+2>IZWf50z#maK2{5`#bk5dU7zQc00()#>=QBdN ziTY-kzY)?6pWXG)nRig=7D8}1GuV-3_*qORXob| z1~4Uy_QBD|937sFo%%7a&oHMh8u4}%C;#~>5Xf=m~F{Z6DCjbzl-;(DF@# z#<|f2_!CBcvKd!R25!?O*?MfK2zjCqC zdQ(qxXLV3*2CP!@`~)#tV2rY9uBL z?u;&!H&JsBh~bArVAY<~{WQ+!Km)Qp#CYcIiB6(P8~oNwK;xKEpJa{~vf>DgDq2%t z-J?ZbMtrh3&p+%yz^ZX4eWR*n4=tl#N6d3h`XrNZ3LBFN93eTD3=Fu9iPdrX^19xg z{~hTD`~G{2O>1?T^;&_!X?UiL%jQl&WbT`j(%cGkn8c>$$Lt@8&D-(DAzhd}TECrBuuP);Z~kiAlw@`O7BWU7gS5aY&=N)m=?%><4Mk8%zA zl3lXPx7}=N&$k%SGCoP}kWKwoLrB$G7R}kt8`mu-BJ`@;{^3bNPVi9zzQ}aQ>^GHXj`y>ki^I11@vSqi2EI2U}>`HEm(2OD$UCGwc!$xLf}oi{e2$?Vsta^2HnTVI0ZEbf3x ziL4*G;($BrQEz~iDr_WJ)}II;mY`m0F?eew2^h+tMzQF7yjYq_c_4{o{aJsgCK z;?RSWC?oR zv8Ajh;ZY`fAg;F_Tcl$mmA42W51S+$1C~2H$tj@z@o{-CBmuhHf15XFk8%%F)w?~= z7S)P#qG;X4fZ4MxD7s^1l>+7z1bapa4r=)bNs-Zn6)#=?$oJIuozgy7&+ev)0g{?6 zeg~q*;gTo=U?lwqB9b5SbPinn;OF=OOP78JWl+(ptE$*)bpd5v?zHHwLH7TTW!(*P zXLR*>Ov%#dbouJ#vTFK4azxVe8z(FE|0oXw9;qC--JI|vtONC7&Zlhdt>?wSbzE4S zmN7bgqE24{e1SeUv>`j@VJb+XwLRKYY`uXlCn0p)vo~&d7bt$jyq@~PMT3ObzeHXL~n@A|zt zcBW)T%WZ1-nh6=OJJ|T_r+sPkGJv_aT)QG3V$ME^KLtCK4lcEvemP(V3u#5R;(B6^K2h{LrlMQj z(Ej(LdRIEbyb8Q`J5yi{Nc+@V|ND&E;Edb3arFN=BmO$-l$kn(>!U!vXEgQ%FzY0Y z4LR0^Up_uz3Q<+&Gfh8hm~^@jF2N?TNB;4>?j-O0-*;|Mo(LNfMco0h69~tbf9JN( zUh7N)v;BnBBBGSam(E#e(!+_)Uia{tXQ zdta2}{oMP)m2tN7c^Q61Y^^~wg`;$+oX zSHhoH@EcU3s{)e03KNj{J5z;EKJao?Mpt)MUDk+o=!?L=k&4A8@`_gP&O%rC&BeR2 z|7y=Ld>I4JS#_aCtwpJ^eFV7R?`Q7zd`~wL@~bqhTe&&){Tnuu8;aZTx#UJ z{ckpnZ9120C`|65l(nY% zWeAtnSc<2Wxd~wj?`oyl%Ok-%Wq2f&Ui4`0Z{2>_GOh#CA4w44$z)un!hGA?P5)uL z6@(!}=={?otIg_dvp(nEL`er)r? z{%a?(v6ZvM-(=-T)~WwK z)f&sEMDkDT@~o_eKI9-kH^%DmYjsdc^c{@Bn0QQW{M!;1_!#_ZH;2_eMeKNC=*%y<46nE2ok#C9mR>zmEKI-srNOBhdDc%y8RuTjwpa)j|Y zLVuJCM89K6(Ja!G9vwC-+203dSQH;ij(^I)XXGqzK$#!Xit4I)GMmjAYdaEaUz%xk z3uJu|5#ScUc;9l;kXEY}OX`0(-q#=%6jQul>^6MpC;WMS z%P3{;2~~?rfAc{0m`84;kz&>Z13@!fY>pxBzgx6VSKp0{*AaP9ykQhg|P@8`VsrR zyZa&M{!*CgHRm+B`Ks$!k_?-!5;|9 zPjN*y3_FCwpZ44nB$EVqUkC4;P7&*8%;o+xLVbUP|kiAowN7>AVt7>}k^=o-x97`QYvHF)3 z+$x87O`j&2N$otn&keO@5%ABIe+Wt$tB<rjqO)_3yk^FyC73IzNg7W{9B`UI1TKEoRD#AoDUK5KAxjZo_} ziy*D5d%&${Zi83X@!lDxtBT)#@vh<}e2MA4Q3Q+XJ<*y4*EDT+!;JGlwt*PMt zy0?#0L=CWMQ1m3z)k%#`bf;ZHzhD%C3Jbw=aJVHI{m@{#D@&DKEB4|ctm74R>FE;+ zuxHtTFt1=cy8gr{WVCRvHGJF^i`i3XaW5Lft$$Ub6VUDBX;XiBgj<~YJN z!+jhFBr}l3f>xYm|4JHNo=rp1fhP+mW^NSd(lGG>j5i=hv-o8c0-jBs$E*-t$4V=R9Ez&%Zl&KouSg0vwh1aBl*@kR=h6F7Do(YRO242Aq~sJr9H)Z8`oR@hwcHvRALUZ!m3|F=ht+F z$N8pL&$L8!NV#@B_q5lQFxwV9*x`nL32e{VbYoy&lQ1gYc41_ml~#FQt=N;#xRAO_ z=sA7d)btN65ak2f6TUVt;DmjJ6@b<8dRr5aS5}6nI7ewb#us>8zM5&#kT+1Cp3#jg3h}YAKsdP;9rXTdxE_7gipw+)Y zI&E_{@0QRfC2Vi9P0ixTbKEJ(escX3i^aG7m+ik{`9HZ#KNl@tI&$qP_V01Srw72S z+z*^mpkQJIX7_FMF&6BWVY?MaRF>H?=q7>hx zwJ0jv=j-#P9KiwiqfWBw?D%3)3n!8h>T|)~sA$$Zti{E;Y%{&Vx61(+nk#O2K2Uut z(0Wbp(bBHHtPqYT`);aOAKe4b_#MrTAmyW|{^vv!B^EIog$WaSavvsI#D?5$cselu=%z;tbc% z6f_)Q$4}@ATOF#eEDr|^1fN;Au=V6w6K=c}wHstt8u5Wk#ISIBw?5l|DkROjFU?#V z$A%}teDzW}i|GR)t=+AP2#1d6i?U=Fd0^%^2n?7j`Che>71=H+)69Rvonq*_zJHkg zNJZ4|?)4IgjfcLlpbh}7fA=!HEv%v34{%aD8%^iDWng3GYEkRSj!FsUq4sboz4=WOzKVH|k9!LDq+EHql4bi}mf)x@OXE z1OofZ-a18#TzH^r^ucQ_<&9U}ZMo^*=?)*IY9%UZVwIf7Imz%!muTZ#qpJubvN-8{ z=&(tfElC=bbFjL8Ym3t3OywV~;g=Wy^>rHmk4y&fGqqIM8r5nZ0TFP?p@?HFBSq?0bi#r^3vkMt!o{xCSkF#bSZV+U5OMkGv zu`|Mx-0inY51a&aw=HqFS_8+r0E$u$Ucig<5w<3BZ_IXU=6c$X-)kTfbnOK>>tq%i zZ1j^0d0eC`F+|gOi#^MyXdCV>>&w}R^cTS9FO}-%dbs!>t(e-)QCPHH4<5IqJ-kQu zo*S0O`SR7eS>X`>eCD_|Ya5=P4E`-e$8&N_%b z1c|se1+Ux1;l7yqfyJG;mk@$U))kfb87rfio@HZ;X6&G*AMAS!M=4v{lo!u2_n?=S z1)B@q`-ah8192VQB0ZCyt>r)-4ki(Pxr{LFoK-n|G?%sBn7EJj9p@D2<)^9WNR) ztI=So@FzAJBV1m>(TqFR_Xpes1Xe|e+cj8-O_PtA@188D- ziRI#RU8XK9F4rpw)>lkh(HQY;8jCU|lRNt@M1IlSQ{tYuRcv&X*nXV$w!wNqtdDp# zsWS`BOmI;CPQv2nJHba2lETPkTbXH`QFEF$zaZ4bVj?byKU%sUfb_rB*+*aam_kK? zkHKOydzEgGuVJ8rK$F3_}(sg9`XJYxs`+?!)Uji%lhi z898%1f2XqklVW=g`p9HkAM&5Uehr$GVzM__>n(^JrIQwgq;7BoUkw^J6>eJXvEpct zo2y$}gw0=$So8##Gld%jOqQK%cZKy;<1MNriB($lyj(jo+o0g_$h_grZ4Ob$%7DNYB9W<7kJJb$D(_^fLDt1fKLAuKN&TdrXWg&cR2?w#`v5hO-dmhh1_(Er* z7y42NY3)SU_FU|U9evWz6HUF!*4ewXsmtm5k&lw_cU<)V^dVS1eAMN_6v_dv!1sm; zewu#12E@Sn%VkJEr_Y4T)jT(^=Nn}Sur)L2#(fM#zl?$CI6}DTRz6NMp08~QxbdWX zYCh(GTII3^s}WX+p%C}Z*kXgHrQpjQi&50sQLCyA%5_vu5c!e$Xdx}kIn0(Q**vQ* zCmmy$(>ZB~Jy^v{;Y%??lNT0o;Eo*OX)Jj0K7W1vz2*jg0*u{_^j^nYf}i+=;#Cr8 zb2GSn@xCG!a2Lb%ixs;hP^zh37hLXJ12<@@FcK5vS_MEy01p^@iz2WxIya`#sPA{a z@HH(*RQ0W_GT8L<5mbQrp~lUpY=TX*J@|*=xgs~;q(r?Xh>6LK8Gxq@zS}_~Q{M7S zDGIkbKdG6StvelbZPu%eWp<%aX55Jyy_l2y`g)KduTV^j9lm283MMyEl&vw+F1JtW z6IiV_dgr$|7LErD<9(Bx7hgaKvccGg1J5Kg5TLBc4coJkpS*kMqs|xH%F_)=r41=? zTccN4n`h7q2E8^VbeNFEa^3|$Yak52q9Hju20Puny5+uwEPHwP^PTKTS;|$0wbGbD z*2LVhDu}bU&_JMPn}}OT>S8OoI{Fi_*hJl6Bnnm~J}bAfJjA2kn&Vzm=N{{Dw6cOyq@fr?*mHkW)3x%q0*wpa1ZBCaPnjq7iD|x&XPq!dcupZ`Y=?rFTDV zdek2KXjIndGS7FdzCACWj_Rge!O+h1Gv~avTyTF)I>31W;%#u*xQKw@V}@N;zEPT* zfv!dGqM;@{%?5#3%p`L+9+^xeS7C5f(;#$5)$9KGhk6A}8 zgVEgs*)Wg0NuVWu^$`*i+?sC+Mo`4ou`dRr;y77Fu@Lj{fa@KT4$y_G5=3MeED1^f64WihVx`?drTJ@24~ zY-O82i*}V*7AB%|R<>Kgo6PUG zb8mpTH(^b$3KzAeusJ+&{0pWO;x-y_DsyWWXA92_d!jsqZ$B`^CETS|*Jb|9mph_@ zkyb&;{yu66*6$AcTor~NtxMlGV84Zv@ zm&C!lr?6kJhfeBjrSQ>G(B{jaZNMyI*j#IzV;R9Y{$b*aTS;EbDB{sN=oAZ{<4jx3 z`Kikdt`@cjTlP3b`~IfGwXHpK!<$+GH=n&3xJ|KsQc3C;pbmeBgJ3HG*Q8(q*Yian zsj6#4J)0CrbQO{UEW8NLY0}}@%8&OdCu#(N4ZYgKaVqL-isXOQa$xK5FqN_B&j7

^l>(&dEzdK2gEd@;;SYRSa68OjmY=J%?D5JvD{4}&rYhCcdKRMWuK}dq|S^Vp4tj3y;dsE$*HBKx@Y6v|GQ@cJY&MNRb;-a z1idzsApD3SkH7@MqTw}I(`j;O952c}{-^NFr###9@)3Gt?S~p?O!$jpc6gWH;Z!K% zImCpIOBGATg>L>1d_f8kQ&ra>Fhqlv5KPYDXO)>w8c+$19VV7r3IFy!=|$yS#O?)Y z5ywpi>+1uB%dcF_c-DLvuqzY^9Abim$~3;`EEE5p;$hMN94UagGUkeY1f{~1O5vAs zpfE~LR$<4(TM4c3DS6v(OoxtCwg~2PTFO!ph8tT-SN%2mG;DNMZqsgA=*}! z`qazeQ+cs(epl+mNuUW=8MnZ=7#V1`=Lvevg<%RW9JN|e{SB6Dh-0UICRg!P7Bd~i zcTYI{V$-gLJQ}iTr5XjviTm1?{d@s`l&*(ZZt?yqfefv&6Bt&1QD-OfU-|j@f1zX; z_`~|HTY=6LY$>UsI0J^d70H|L z5^S?5B6kYiT=CgDvQH~MxtLUJB!XJ0$8F#b#7OYA1l+PqUUi`=T>;qV73=~oNV?;b zMb_3T*X#)x-8JGCNEI9Hy@P(V{-Sl@8+Ry2y5q#T6`XW?pYC$oQqOjqc75lI{_|A7 zUxfmlKUnal=IwxNQ9jTh7hcCK0OH136Zp(FtAp!ShkNH2arK2mp}AO!bsR=FpEp%n zmV}c}%y03XXV%c$g4BX&#^PfE0F!> ztS?$i3AjS#h&!!KPalNWx)#le#2m)&7$+^Oe)bGkMy}#MQq)NFNl7Jf_USHM!dDww zdoZaH*{oO*yY&Q{(Z|PW>HqckAZFIG-I>w^H7{(tf|OoJZ*Q-R%Y=jEIR!9#vc)Bw z#)s!}zM$Zl(+jQsur>3!+tuNpv8B7bxQ~RkcV72;k$P6q9c-bp^i(_o}UquVsdy`BBbh8H-fTlMee!(X^XcZdh~zy0*J!J0FI`V>hc6M zBm(Kjo?;Db2klgPQE>)$v4joO=dsXU+i&q(gM0U!rDfI1OsK;MFVv0sNoT4(mYC|I zPzGIoQ(gSb-sp(j#3$;~V|fVfR?T@g)wR)Xk@PB6hsf`-W-q8$if3-Nif0&|)hGP^ za;Pry!HUT3NxK8MB0xkZG7b}`ynS~7WaSPpi-e!mDdRxvb^R@YW;_Dcl=#MN25@NY zj_>MN5>cI(bKc7*;N@CBI2v5v>gn+AxbRRU3*8&M8~rWr;*I+?ZtQm3x5(EXmx|%M zU&4{Oc#EO7{F&HlLyw!IafpCC1@+B->58sWMK>I@r8VsoL|77 zz9rNlF=uu`1TKbCF>^C)Eh?H*48))_HL*iES;$uvt+Y{5b_x2kjn11*WpTuRx$skebuG%`n)*m8KJ?~U2u%F;N zr%*1EOeh*nu2#+JVYjW0;=la!F$Lc#R=~5`F!Sl~WXvd37|*LX=;E~}>Tz!&Z4lbR zSd>Sl^#=xub>Wr1mI_#zFGU@WSh`fI-W3ILikX|SZwBq-=wCk0UwA$eX~7ZjJF7)& z0ei`-YUJeMrI;=qhbexmVI0IIV{{zFEFK(FABS3(UUpb0zkHAhE#m(32h6j(4 z8cgAM@avh37GlHcI*DtCQ7pV=Lw#Y^`3nM$L$5bLmEt#t@vIPt0!L30~FBRw*q!x3RV{rXe>$ON$4vb0aSM__qv8BV#Z z4`0yp;l|k5Mn^2D9bw87tCC!tty=-?oHz4?!St|}1@|9L1O5mjr58?+QVful$%js- zvGnIP6S(@IO4#t8Dveuf&%3Dv%r!)FVSOjIk16L1$&BsjiG}%e*Cg2Lv@iAbq8?~X zhqShqb=+Ln7j&B(ZpZmU7!pOzfp9HjoZ>sthdv`S@gCf-M z4w~Q;5lwul*kx{*8?V68JHZG90gmg1cRgncWyQex=Eql!j~`Ey&j#P=S*3PpO?ipk zquBC(Ixm%ajOU;tH32)JXnk$>S$%^afqjhN5P1epx?_5wb%xVUagmRY1P5-2Ui%EQ zK}~GOf#va1zsP?x$VJPJM)T8Sp9L^8=9!`W*<+^MJBtVU95dN399it{ef9EubAE?C zfx?i%kHnr6m+!5Fb4aR7@E!+_Eh%EMw>VSLO^z7X18e-dLV1Zf5%=#v5TMvwKx#)w z|8t!f6b@kXv#1(pVZ)0Z=iGbhiR@!=+-~K4ho(&lZDJfq=Ae7-rhoZRcZ_6E+e}~a z2{qWqpf||D4j5_%usnSkE6MQ$F`W_QP6pH$;a4toW|lj+NGL?#YF;1LtTdp*PnZuX zD7@#M_QX&CGKCub;l#y03>`Pg|7saRG0A!QKNi0a@e|C^_$;}tn#g!0jRe&D;{pSHD>qWqpL&lwgZ1QH~+U2f&tS)d!}WU;aL0lf!#@W z5Mb`K)MGK=y|hkUvBtf9LAtu<#Mv zNs0U8VGQK(O`POQmu8J_ouBWqx*pDE6Z0vuGsKgvKC&X<_rRWj0W^&B@R`raoO|#V z$YXMNck{8;e5*z`)?Ka$wep8A1P<{(&D|+P|ojC=_Uu)ftR7 zfpr)n>hB!4=6n*RO91N-*>h(4IE@|po4)EBiyxKIvv}7yi~8LNDbS6AMOL*$B=SV{ zFs2VA1dhjJ5}P1pv3kO(3n^H)j~ymZciT*G9;)YCs{QU^3OKbAL65!C~B zioEcx90>OTj`0N%MPIOfVodY-3Tr3Uj=RjmTs=3&akl>8&f7A;k|^uH((^#iDhR&H zZ@oN@E9u@t7Wi|ZTcSMg$8(dcl)a!ALHPZv*J=jHR(86ap9NbFJmm$tch&yKzqm?i zGWXHyHDn~i58+>abrdxU;A%i(_E#s?hP0!eSEMDZ<))HTdxqDsJgjKsr)pDOWGjAjVtvlCl(=2~ z+BCMY=XHhC76?M5ijzoHF5Of?|L!=SLJUC>Mq?UUGsi-v0{mG} zz}SUTkr~-+d)eyV5{Z3`Ymi1hG)REA5@VAjj41UHH~l?h8*Li8s+kUkj)&fVH5dO4 zaTT6`)nC79JoLvwe9#tSOca#^;*wS7ty8kFQ21Rq331K+qR&VgUu$AG3JZOsm9+_f zRGj)#vxQk=Ot*FVAN6x41y;BMavANCpgy_9RH8>b>`9?OHwXbQ{hn?I&HtvaQ=Eo^ z!D|b+(z#RFJU63^BYAE0zE~rkq--RfavfW}*ux|0;j!{?qX7-gFxgk1FZ55VP8Z3` z$df-{9bua&^xti8q)tekpD#4`NpPq!%pW>6JNgh#f(fB$JY#)EWWwB{>YRmTJ!Fk^ znetHwV8Ce@wZMV1(=?@EM){A9yC3dFG!sh<7twe&VapJ-`1k0}Bl>_@%brmIi5bLS+i`FT854Bct> zS=Z1vy!ry$FA1Kp&U*^c1-e%!HKi5Nqr>Bbukov%9jo0J;0A*GTzM~Ggc)!o<0AF;p5xmhto=0#cD zO4zL`Z2>Hjd4BRwO(3`Z^Z7=WC7c76LrnyKs!$?5FgXHZBW}lS-)}2LtChE7NS>5`4$jqdS2%QdvV`V?~Gn2Xwgl^uPUUbWw>0ell+>SBqG;ve?qoO&WlSmskF zyb)?ChqVM*5vWYbm5`ccif5Q7ZLRjzV^ZcPC02i#Fj7eL!G51%0-*RxiE9p-Gx>V~ zXWvmR_&2Z@Wh2*Y@BeKTx^Iv$WrNuDHX^Sq>O1VT8y8nM?3{B5fo-rX8D&;HgT?Q( z+#2|Xks`?$@mnXx@j*>O0MTyi7RLjhiK4C8y9$_opyXBajjhUzXFJ0etA4kuKh10? z1JGZFoHV;1hyzHpMlsd)rh!oTxfM3Y-#dZ+V+HX?Pz68Y0z1c0qjr$y2yK{1z|5FGyCX33O zdFk&Nh_spqt{*tL)OD?SnD708tpApQCQMTfF01rUu}I{A485xzU4K5BCX$uGBr~&_ z{GXHk(CNRw9ycw*1LuEE=sioR*<9CRS=`XHzNp%D^N&u_m52{CAXMcjKmSf!-~@bk%%X4CfR8Jou&em-+qWNTt|_NOMsKbgllJLj3AL!z zW&V#%`GEL`cbf?uKOyB5_StLsmq#AnL65HMtM1-<5$)U7Id_7>A8!L%bYV{3KLv#0 zzK%zEn)fK`OB@+)_k6sjOeJ|pU^H?*%BV=~^KWOVq8f{fXa z`sS)%L_OvM8$`Ot&M(Z|OnFj@e|}azqK7`l2V{l`YDeSk<+iiq;!hS!21PpM{FqPA z1sIPF(KkF+LyEb)-JXP^HZSdiLN4=yg|4N7>b^yD2U%Mq-8@N(S#gS#xfV|%9c`Ta zOOnDDv<%e3s~HQix%m0bbBM)d|Vb!_54WXu0M{H8JDy>hyZpfcufqjpdA!9+Jd_ znH>7A(mj)@Mh3*i=-Oo@8cbj@LK8`Pv&0{HJvVZD0VMX*esnVayXIRJk!a zJqwJ$3%}1xPDez9K=1Ubj;E=(fo3YX4=I z&9U+8d5zMI!=ip+?Ndi>&8oQvOCPPPb*qF-67n?nhUy0oR~u=}MMPPIh^YDB%JPhS zG&wMKw8+;uYh;bF7MN#829}V2JGbbsf=9C!OX6x?2pLOT;n^+}zQ#yU*Um@cpg$YI z-;5ABJ?JNFOZDVRqgsZJ6EfMa$FumEIkdqBi(b#V=mk#uM75^+4nZYuwuD286<^2o zejTUX^|?hJw#VbhBx#&NZOfsM8Eq}a4$}ke_Q57hC@q4nxPNoW46*;an_!JrTz${*JSm^W;Lkx2%xh)1WpZs))+@rQDNrh z5|)L;+EK@7+|xNVHqVPkZF;l<_n3TVo5FL%`lJH6a;S2=?tXb8=kS<{z~S>*X7kjx zt}AYr9&TQ}+m(D)y>TGo=Fx&@YXz~93wYb(46J&~p^Zy_T1#XrWn#Mwo&Io#fY0R8 zKpN?m%U#l~Ir0I?NuBkq`QHBJ5rkc*__XW{n#j=bEDN=E|*VgNo%BCDY+@5=uG(yK|ApYy%az`s<2;Z?# zB^d(2^G*H>X{F;7tixk-m}DW}bhdN`$8E9l42t%)bINoKcaoKS{zA-5O^jA8c|p!SXX48>hR=4X+Do%VRSsbwMfRMhYl9az||Do8eJ^6{;Gq9 zN?5yI9@x0w#$$=+=rQqt9gps*=mSEsMVyY!GmHFVfhkgb;XR>SGP7>iR=8;QoU8Nf zI(sOm!p6wIa}#&hbednJU<$lkmC$~Zj7O2rgn2p%1o5d;f? zEKI^eRE-3V@Q>rWbP#*V&wjMVC7c+&kdZO-e%kB>;Y8T3mnk2i6izaU0`x?IuL#@|abbisvstC0y?S`o$gt`kjkIbo#yAR%2ei^REgh(vp0f zdirtd-6L7LyAo#Rm4REWDsA_|SnjHx5$tZ4%#X334ZX0$l5KiD$H({%Tl>4aJwwbk zindcPf{VBakhwRmF<*ZA7v#?I3X2Sn^Awm#9#rrisX_bUJ9Ud`)sD7qO+cnrHGADt*ogKU{AP)s zoLgL$R<8Ex-N-QWo1Kr7-TOLA{q^BDUxLXN>#QUm@LXv2s{G!PYGxJnSMMIZaWoJZ z4tMptoo7C0v7mSgY-1y?)3H1vB_o*F$5XyW8k~zbbmd7~iV%*t0h^Do9lr2s-_I_C za`AMD-GDwi=dYu-)kkbIOZgpTNhLx$=p4=VA-{ryVLrPjB%zX|Va%$J>R(X67DPN6 z6*WAEUw7@6FYMo<@}UDf7{3O1ASfUOKHOe;Uh}O~M@zGWDf5JN!o?otHN4+zNzgYQ0fWq;WU zvol_)sInCJuf`aO`8zn?8M*-n>lA#)k-`m$4pUw9!=-+nuUQH91GIHGBUCCB#(s!v zlU%CYO1I9_4HO;OlPwzQ-pe;Xx|4hj2r!1=|9)U;0=YzK)PR-gUSrAR$Gm-ePEvYv z;qlR0EurV75aclVK$8CBWRKnZdmq)@iXP(*Ls{|MsvfxHutdu?X{cj++xWv1UgJB4 z&Ltwd^BMW>gmSH-ynxnvHz$7SA=zeMrb&*jNwaZ-L$yZaxQykTBUxXwi0BY#={RY(8pCD1*63I(fK zWppwAyc;Y{ohru`_tx&^e0K?S5p%9{SfOw-1%(Y-AsV<4rls%*yQ>2mXI~oq<1T;P zDp@PW?o|l1691H1_bd4ipFe6c7p61`k>4c>mov)=27u(}so%x3iIX)*Hcq1$952#J4*T?2ybjNbTMf~FkNETdYL38yhdjo2|6WiL zE@FS13pJ9NSHyT%^)iKW_Sej}6f4mov!Sr(PUNIhI!-B@b1FGSl!xKbLy%d@61BGb z>niT<6*;>}3eR#*R?nP6Ke|LR$fc?n`!(Ia zV*0K%!&?OsN8<&jqQ3M#?$nHkoTV!RZQhx7LZ(ktHC`%<{bpCeR|v+J&0f-R|N8)@ za3v|eh4<6?{Fe$AOy8gFlN{Y-&It@-H|T#g@(JK7a)QGIJ3XH5t!LDK(uu~iK6zYUqiP%=)j;0)ib1yFQh+vU3y#=FKMGun^~`s1>lCCCj}eG zE~=;o82Cyn>AFR1*G*TZJ*ghi8hJ=zku>>wfN-ayNbqbsN5uQ5fFWGW)9rLx>(OtH z;;W7}?~YU#=YLb_4SaQa=o4sdMSm_-DC37^f*@`n-aY?l>#a`z=A(ya{*d6>2S9>@ zxZk7#l(j-gM9Z(thfnYAv2JCrX*fpwKM6`WKmMtKZ7E zzXhtKN>QAbNHPC;dH)gjc1pT|sppul`%I#sGR%$4bt_(9gu;XQBQLBR<_htT$H<)? z2*h{M$nbrf@$LdPih&)O`!-ptIQ}p15!Oil{x{d0il$7`yTGe)xom5(+F}G$7y9!` zx_$XCvndo9NODF@F1t^u|+TAfMs;1#!#K%Z43FO zMVJTGBAaHu=xJ?N$)S>f&5eb@6h(S^xMtZC^>M3^c%d*xd798aXt@Vyp?Ji9572T8 zaK!=L{DYQ}GrSo}@#Ga*4mELiAf4v6Q=ppPrXm)mTob15tCSB-J)=bpe49kR+qX~n z#Is}C30|8~s(TMoR?e2bb9V{8B=BgO6Z?0`(FRhx`}pl4paaf|1q`Q~AowUuHQvI$ zmRjYr#j<4U#UT>XDRb2TqGgx7#Z0j=IE#gd1*Y}(3UV2YcCLGo3MR_NaK~*}L@=vJ z-FRHAT<1^huzEEj!#?vNvvO&ENBoh(tVwH(^?dJmT~6i&pR%=SzuJ$MZL8pg*CldB zdFqvq$Jo@9!&p?~d)xP;3}*9n`#420sQ91ksfhr#tE%T6JNQ#NC_qkIG-tqv#oVA5 zgtMrdzg|FGV4o+0R$@1TAl|{y?o_?AkSn+%CzF?|BuWmIIgSL-Rmu1xjiq4 zC)FxsN|BsGRfs~-gW`({bDH3bVxcF1%Hs1&hWCIdqn?m0ZZ3WipRO!7O}*Rv+I6F- zAMg9aJ6Em`a7m9=dsXj>Y`m>H+%@muR4ld8ZHwenN@Xu^Y8k7%E&eN2q9_Z%qI(Ctiqh7iuMYD)A4WPtkv?39aZZ98 zG2E8#c^Y39jl{qB-IW?#70qv1g9Ajhtq7PZ1cE(q+k7h!g#9porMcW{uIfV+<75E! zT^44p*&E4ODy;;rElhdFlMjd-dCU^hW+f`qZ|uTw!+@P|^w!}ayvFVgUZiXQ8+#vi zxW6W!HBnm1+qS>R8FpQ%q0h5a(R4YMuWxRAXKiMoGfCWv=*$<7Xc7I}CIbqWtSiA- zT+!#QD_5`9yQ04*-wPDnxK_Q###lzbi?6r(3++$QK$AR-CFQ}NiWURb51w^_!H?0U ze`t+qs)?Ri&0f)_Z)d9qXK#y2r(Lwu+HA;e%O<=$e&LS-isCPOR4U%P_Kqe57cb{-6ju%+m_nHg8BXkj5}W#Zn0Zi&9`tu^+F#36Jk{oV)73|+ZT zRonY(yHgR`nzM0ioM%l2@{@3`F&I!!GG4nj|Ft35VSn2;EARrB*=${i2+p}*740wh zMPL=CBST3r>bD2z-^_{aV;FE?zJH)_ep^N$hrEJzAx}a3MgLmJNK{4zi{+D(hG(W-ts{N*gLs2w5_=86#VaB`PZWI>Q*WSjSKpG7Qf(^{#j2b9|oT zIgaP|JHEf?(I2HT_kCa2d7am}yw2Bo-C8PJS*L~?b08Xb4L^zM9dnlrARdX}m#Lke zwkU97`j)L4DdK;}i^E|2Qzp!4E^r4hpPUKbcjH!%V9%mv4&O%8M$MSLz0q(#M60I$ z!MRxe_l%2Unq!2c_~yz=h25cKZtbqa?gcfy&9t0I2izm5cicq#U>6?VXxfR`RPC|T zXlp1Ly!<6wA7gopK#iX|o2)$6T7V{FzGzicEiYNky{>ce)t>8t<#ozN@LGtSZd|ax zvr8JwvYzAHrQY=PbQywDa{@X&bYl^tS)~ZIfJmO9HtRRUbUVC{HBAXw-}&5Bg6XlY zbMPp5a^Mlvwx&cy+N;_K%lr%1nQJ>eR(|~QQx9s#p;w~`#d_`QtC|_ZDrM7H{9>s| z?O%Ztn>xs!j`W(uhOJ?#miWRbgI6n-9(imL5ik47j_2^&wUeyHBlmc|RH9YDgnbEG zkBh~xid)7+4w^l?SehH-8P!vUS_6_mD7t2!f%jkM~e}-I1?*+U&h-SP= zo}`Y{tYz?8OT1&m#0v%@>Qmt!8SnYQMo1Y^cpjQi^`lF zk@_oW4p1#8?>-J{$^f&NxjfnDG%F&mt>V__hMLvvF7Zt6DRL3^dT<|YwUrlrgDDfCmu~UsTmLW(az+&4UHLxt9lLCxnoEmW1#m?PE z!kQ5rwGJ|3fB4Qd!CcHVEv4~7_D@T7jeD)vZJ#oP<=V-sRG+rvxfCS#xN?T)ach`+ zY5CI)NDZ1>r)*4H2uVNt()F4M6MAk=EIXnZz1ak(=rDDuV&>zWt}yL~hqF9m59e1j z%VT`~(fUq_JKf=AIPb|zH=D7R`YI}3)T?>n0&PX=cWPh~Ztp zVobGZn8zx0_}B~0Lqs?bSocSqZmFcTBK7R@IYa$nhun?h1N0v<`3 zeTl0qg!S7DorWFUST@Y@ST>&f-Ke`B|Fl5gsEm{2o(cVAIX%V#ZQ6VO~smMG|x>fQl)mB-sLbNXAm@^fyyvez)WOgTi-A8<3<(F`g>0L_oTWj_?q>LekRA! zn?8GXoFilwep31*K6Lo)kHFg96+0kn{x#mH$knv*+l(>Ey#n*Xxplvi?=mB4XbZ1g z$2WHFOMMuM#%Ry8dJ8dlBRjb|bYp#axSaJJcHadMvdDS%ja#I$2vGvUjB7yP~ySnE-PHI#qi zui%?J=g|iY-r{YvwtX5nPLxH%8?(q#WxCNF;yUP!g@&G^8=)DgJ-K-PxbN|d%k97p z&7N$=@RQu8yz|h!JDB!zNKOccL6SNz)6>zLnJRBwkpo$5v_akrn|=<9kXG} z-b^iSF=Tw)7i8PRLl#Naa0Lxq7ep)ukC+HBdqJvH-zc(K;K}I2#>&SGEeUm-Knr(L z(ez@x9pt=Eg5RIBNRa@uDD$st_?7M_vj=1(Ce3{nXwgch@!jQ@2Ypt~xm!oVM6;ij zWxK}e&{b7Nw>I8qx97~k6Y5n`E}>G~k>)C6UW|-S+R8b3y|-Jh&~Tk9z%}Wf68N5W zDETiIG+*pT>gdHE&o7$PmvHZ|gi6NCP9K*MgF9XF;?HkC8d4Fc@nItUU39@oOmDvW zM)zJ^wPlZ_d(TKrin>xgKsaXkodW-rKllk8D+pk(zNDiUf7+LqvcXl}4Iuh9#}^s; zd!I#H^GO);D{eug$*K(~knN;?E|DtNrhpi!&kVDL5Z??7gGQ3w zoPen@56`>j(~{a9zV6S*zKy;1&`(jUMLly7w$%RG=f8#)f68BIPLy=Zc-~`@K2KhN!YAKR?&+lf2P>wzpIqWCENsO_Tdk zYg_`$0tVmT^v&~dd_1J>=p_m7$s*fS_}2$qGU>utp-GDH_m`8|5Kuqs(LdwOo6aCQ zx!D)EGwSEU_=XV@GM{4*eW1dnF#Ei% zJ7u!;)EAX~U*^|-jVl}aL=09(dM>h#dTWo>xt#H<)IWzVI?Bt?>T`4YW;Gn-GWywS z2j<`zovh@v-0AmDl|Hj`D)V2|B^T#lW>u!(aN4^D&DMCT#vVn-yEi!b9O2MnH;YEw z7cCL?xypF&iCmugM^?6k99!FHwC)x6T*Fb~lNwp{6}_Y8MhV9FJuzMeib3DL)@7ed zyI~q*2Qfh;`2C4Hr3i!lui*bi_vii(e!7F0!|imvTxI=yOk?%V@eC+!+}n$~p$`14 z07XM+iU!>&@1Sy*NZ#7RZDYquk;Sw&ag)XA%&W3Nwe)AC>WMqeDtX|5HUe)>C!8=E z(J}X;Cn-1dwrP&Z*NzDlyK5iuaIY4HlQ}=V&0&w}Sjjz7-os6au083uhMgu260<>W zcD_oKxTV=C)bvlA6%4}YE$PY^f8o-Ajds>w>D1%}>XtGd1#lvo$?RHtjXUE~{=xe| zp+s<7NeG#P6eaE>v&@RGK+bk7c5tVakP!(szM~@j>d$5$D-#os`#m3nI1lukM<_1Q z2(~op0}=YCD3u)mGM7GoPX{x*7NL+QyJL3K9R_uy8e%{cyMrymu2bn z|NK}rY|~<Me4Q_W{ZTGs(++H#bHm(J!YFw;UnwUg%Zk+Ql;I>-kFt)7h(l9@8+fqp^AxiSb#vG@1v0=Y!2Gz1?&uhL&YoH*u@y zZkOL#G1>DuAfSYspmW7V9-232RW|T65ADb!tKkw#AA%UA0sHATY^Ja?g(QX$K1!sL z&{367;IqlmQk9>#^Q#0}2Th(_xP({fTd#|Q%~c)i_zUFt@(4gLRq1;+f)w`Nr4aHt zVT}tPLR9|&J*8%J9|1VlAXr`D*_$4x>lH&BPTaEs1eav}Y8PC>?ABiCP7TP&1(?({ zE!@&2g9fLsfq+BapBv3Y2DZppW>mpnkEujmn7QfddTlHlcU7@ih}if9)TOPEb60rE zZrBmNsynAumx_f`x-dCTN&fnepoq9mWM6M767WF_gO&p+1dznF0k33?wJvp=nSk+R=ADgiA%s=QAFAdZ zZ|a;x>gp8kqbZf0doW?hBQhcmO%1V;j%;pr*caKU?7zX(mYcTGo@y__vOmU9-DAfM81Hy45uGb!8$USuKoezU?z00C-Qdi5DC zI+9<})lN@+j+;dvWJe>1J??(Ts0Fr=#wPGGzxW?CK?l%uXc-h*6pGaqZItOz8& zXw44lXUtJbyO>Mir9997Y`n6tL!ZVqj_o!qEC=PVB^#;~?SS~vr z8=?=&Z1bEIVc<~(*?M3{MS>kg42~AJ0EDFlbh}?f5*ZKsP;=ev6%1Rd;Ta_uWFz+O z-Meg`!5D?BpBom?8&5I{%WCTs1sfbUg+LPwP5$0q31F1{nS0on+lz?~bNoPuSwqgf z^uQ&w_Ht4U+U}(*oZ2(4kS|JXw9c7+$RFS9pkDk0NNoQ`gV7p^1q;U23lJ+CO&-y^ zf_c@WSX+Uq_Y$t8VyXpdGjdc!PaDOVH(y=Xo{@#5jYZa8F#?wA)=v0O_xKMuwYU$c zAg4nu(~ug0vJKgP$FH#nX;x26oZcdD1aS@_Lt;>C;#vi~A62N{;l{_QRD+SIh3jW| z^M^noO9?p7eq|`>MZSL0$~$fpuca@1+h8CTwnY2@_ZB~5+u6Z z&?|3vipP*vx9kX3@;!h0Vzw6m7p24=W-!BwJzykdbLYWd0NG_@O;Z&LfuaHXNB>QL zc|RuS@ut0cX5H}sHz#FH`}6*YX<|pY)^qG=!F_nuS!f{xLEF>xa1@23>weoy%(UwS z6FOtlfP+a2iGk2rzO}wg@`sU9J;L!#hA8>Wr+hy#%b&l9guX~O)haXEb)M?#GUi8> zHnrF5q#Z+tQ+EO%D>Vq-;$8U(4gbnxV99^=0%3xCq`dDokHm48kEa`xAqIyI9WvW^ z=Jt-(#**IDg$cX?6VdiV+Z2LL%n~8`m+-MnkN;y$UUq|VO(<;xe|5LXuv8x$Xa-J> zvaGKNzoTsK71J4BR?T}%Tlm=CvOHIp7rfm`JHci)0Sa+aOg|?84q_8(Phsm&V*=)# z&t$7QiauLZF|04{!OWG~5(9rmDCwIBV@V2dZN(+J&e8n*vbP5I9z7T2+-rE!^@ z(`$l-wjHUSc+%|^a!Kw3Btm|A_MPj#ndG{0xsYc(qXrl^Z{Ypk#PfF}iqjjM4hYD+8)l3sgN3MKR-wQOHBmVcTL| zDBk<)Vf%Ri%a~-g_~|G>h^U}3lTNI0UA88U@4dkquRqHnA)uTFIWc$L;$O9Wai9hB zDbZEVJ?fL)oE5djje%8H$a*iHs%TvB=^}6g`{ikjzWHA(6Q2NWX z(tgFP_G0?hE^UvBix5%yGcnooVnozpe%;KxQ?kYD#&`%}1i*q3iYQ#d5no)7&j^S> zQ`){R&QEvd0B`6G@$7!^p@SWv?w}d>lW*~3Z*U0!efy9fmCN#vQ3Crv;~J#e!vKY8 z?YZ2=c0IwX@aOuJ_y>p!5J{qJ zKP*jpCN8k3);beWOrQLP6oT@4Mw`8e)1Jj7{>{lPR}#C}6N{D6%L!HIsF`+K@UdG*BYFav zhM+M4E8g!}8{#~$i*D;*y4YVfJM|U&nh}4(C3OeC11kM=Tyv{aWn^TVd%e+dL~jG4r@M$*Y?Wm{v%=ER(-!FngW zsHga5-V=t=qWXpL@st~lMX&DLH28-%E`;li@(SjyHBd?1_by6hDYLkw_v3u`Bd?)M zfU|eyu_J^Thb}OFPW5|maqTaH0I-Xv4g;jgJ!_BUQ73JwBp*`M;A7PElNk_Gu_M*hXx^HokU9wvrwesBvHo3&4vLGfAd?4d&Eq}erA5UKCd&+xpqHy zxY54OVXpBf7r=I^5mGkU=dYwLEX#? zR|*gGQ`{**$*!QHrfJIVGZvF?QQ){X)l#?SLR_sS;Y5_N7dfxKz-=x=E;GC`wseES zInEy5P*9%B5Za1p%$)>v01ULC*76$Z)YWOn#u@W5c2h4`AAl2fjgrqwXlZGgy-h?| zLULe_BN{+$^U z*Xu?VLDddcIfru{t8#UNon&$*0N|#Cq8D1)22~WhlN=>e0W+Zsk7#^n2+^kBYn$<8 z(c^a0(3XdEG)_D$l>gBC{LH2})UiPj>2{#z`X@i^Cq_IJ3y1%SZY+UVmX<6l{IBt6 z4Zg-#?Qt9FSMeNJa9(7;0?%F%3v>u6J5}o3DT==pTosg!hQ@qgo4p37Im@g}O-}&r$EDGRIONnVv6FXR%mLW=Qkijiu>ea#OoQxeYELoE`kh;RoKO8$-jgTB z^Bj~R9kP?}62Fe3#f>v`Gmr+HyPp~;FA=AwrH32Nfkf;iz&DEK2hRQEzWrnGUNWO` zcX9E5=MomGid&Dbomr1*@v?NhLnt36lur^o_7NM^-rM6AdUEo{8e7vaTMHB$U3`MZ zJMK*OnAXQi(Mlp$<~RY*|sFGfuC9`cHR8L(Hu`z#2oj;s$>T?&{t!5Qx3kuo`Z z<_?eXr`ib90yB)z<2}YdtUVwKfESSan^1F&pIbf5{MvH~p7b=Q>EZ-hg1}ZNn=qrWoph7@A0)l)-)Kxm%^hjWsq^(cix_^M(4%O_0k*Yx!cl z2d;H$y1C`v*vgl|XIU~^)||`hxML!o4i>`bPON0-(^H{`4W5@BJ0yrG14U3tt76@u zikczH%$p}2iN_tZV^bzT1_Q5egus@U7)gvH0N^+69<8S=Gx9Vd_PU^QuEvPd$ETZ7 zFF4Bns*v0~4PeEyy)-V%=?|~MF_dA)rYBiNur5$_kIUY6B&ZbL-Uy*|=_i^1fY0!U zSlKv$AfV{zxgq4xfy9kt9{%=ETw*j+|)$p(b=xWw)X% z8pnNO^Sfgm3;=j}dzN?{OKyMvG>jEKLi}1TqO>p>M0v%jQdk*8>olh%vU7)A>26^E z<(a?xXrVBsdv-3^?~*NMkks+;knwTH8D|k-2iw|SUBwKUyrY)%W0N?Q(m#r5hYj*t z>|mM?)e$yUFC68@eo!mO-Wp2w+$r6~m?IC5e(CkeF3S%ZT?iN)d_6V_;hgp5<`HYUMk3&_POM$J#!sGWG9;(hbGYy(n;ll_~@}@=v488e#&J_bf#80op-dxSUD0$-h|Vw|R(c z3Roq^_xGR4jjFl6NkUv){6T4mBX!8qjk_j6Vl;4R-l;KBrmjp}5%n%wEK0!l%PER< z)4?B}n^pTIsP|rCGthmMWJ8C=b$zg2F>@j|3Sl5=9?G8doJVD4~JAaw%AMr#GSTn|_ zhJ$kJ`*do_y#+l_#rMccT3bx8-NZRgTiZBk8)=*Pl>$+@jJd+-h<`3r-#Fo!b zU2nSZBNS65vYpt1Alvvp)bN!JBj+T6+SLGj_jr5~vxeR*p~gb%GnsbE4fm(D0f`=i zT4xzOGs*S6!gJ8@WzMh!UIP&H&P`<*$C;4;y{Q2otoJTau|(V~_c8QQ;Jlx%Tkh0w zv!{RV77Bqf(wa8hISJSea3h6+s}sw47GFBe_c3fPknFxUUi@Z|E}H_Hj;W18iG&^2 zCh+6eI@yJKX(hb|MGHaDltOOH*n+-FRomcF0jG4ioK*`k%d?@zrOe-HDe3pq++}_F z)V-#jM3=8vXCLc!B*qk9j9=HH$il`N@lv{K@gvPT2|2Qjd~)IO$3c>DM4$d!s$B_e z=}h+5fL-vBmg?CZp(0`RZZ%A1@lL%2$Fij2@Oo#W0N--Lz!{vP$N2dzdhvmp34 zDHv*WC(*M%g0xN6_48TOx9W|RV-Et|*d9vT+C-_$r&|`g#ksgoFT2MdcfCZubW!{1 z(%NeggNA<*=!9M~_n_OW8h9D!+=M%noM48n`mmwmn0F>EZ-HS^?Aeb61q0Ypxu3Rz zZwoII%wBq;_Ok96p~bXx{22d<%c_rTkXat3gF7kl3bqe@(7NYpo}N;OL6*G=n`_T7 zFi)wuj%r1nojDpXVi>`D^w@zRUf1XbP%!QCr0?sb? zucmvnu;P72l2z8pTQr+MJ#&!g%x+7Q!{^q2`smgP$tycwoLD#RamxLq`N z-w;G{B!}-*usy+cJJ`^61b15y&xBQ+$cG^ljs%u(5If+j;L-6SzqW#A_R=%18)qL{ zX;Dt3d&SOcBDFSd9dX`Ckj2lBQ@>H98S}%*U0i-sL#7eDvb}qo(5Sl8nv{<^Qu#~w zKMgL^9|6vv6Mp&nrk$BiQ36SHCcf(kdi|-he`~+0kOY%&7j=!}arFA3LJvznMg%0+ zXOy1P@K_ltdR|TpULZ~zBlw`SVP<*7`p@I96(AB7uu-7J&V^rB+vsEPI)!_WGe6Zu zk$BsgRTJ9#b1z{_5AvW1atff;N7gZ+*qt^dKWSDh8^@J<8i2$Z+kOE*2iD{Ly>)Yn zbo_Rt(aQ|yKaUHlgAnyAtN)(ycoj`}B?VhxBXdQa($$shw21nodt_ZiIM?i2QA(ZhKIwUl(3Cz~^U|YC3%g~Nf z?V@_#Gb876P|e{2&-=0{Q4bzIO#dbYEp%zma0{1NR_kZQ6uEY`#lR`=tqn#rTnzJ) z;LlS5Ezq(opp;MDnL(#nR=CFOl(bA2=?{n=-F@ZCm9DJYS9jUwD*4ZzC!7=1t%z5^ zocqClxki|_F80ovs2COy5figQ-Q5GxC)oI72#o96>OeOTx4$#KG=z4quaP7&Otp|2 z^(N|XXz5Gy8*M%noC`cztWvyjKBV6_jW%3T zc%hG$1Rw%&6I_)_G33~5aSbCJ3_BR;HRB98XhXSBUIn+un4AQ4H&~q1pO#*A4M;iG z-4q;E=L`TCXVUR^7o2-?)L5>@UHJK_7bn51&$GBSnI4w0;WCxF!rO&WH_v^ycCf59)57? z9c|BWX?YpUBy`VA+`KRB&{t2a;_O+*5hn)_Gk2a} zU>@KPnnEn(#;2BT%T*{h%Cv*K~u2SDQ9Gj>fBuc$hw{SZ0V28$Yr)ox;J8 zpzv6>+~?oCAY(>CP`ydi63Tmtyv?=!%7Jml2Uzj`h{-Ooi=FgNr%$Y<$(z z_fkjTsC_nD?UvLqj*aoz7CEtF)_%{hWn<#f{tt$llk=7glm_K1U~1%B(PI8QO+gFP zlClyj2ux~d#|*&u{gm3P>;C&4yn=FG0rvOq62Vpy3ALAu1b zyA8P<2Qg<$@Nq^hGv??n^*b3;_0nB+%__@>y?CsS@NgH$`>Z2mTC^ioF3(R5q7;<4 zANo*xySXRgVR2%5N#mWn0ox|JTi6(2zo`#Ibda3}2af~Y@O<=d+2TnE`9wskePYLU zct@v#S7kq9q&OF6nK=>N+PP5vhhfU{^R8e06 z9Td!qXK!eK*k{+5)my5wi%c%{@;!Xh^ekAbD0gq) zeo(5>6Y#kyS~H49h0&l{Mj{mpOACScvB}=cC9r^Ucu`UNu><=~0bf=UuQWYgV9$7T z0aPWDw=U4w5mc*l+`*T*fa`{62*WK8^D_ks^Hnx@pUJMu3V-;wx7(~1&O95~`Id(- zClz#@`2OfP=}bMdiLiX%_41t~ihroWnzccojzBj~$Uh8tkoMm|%K<@25P6nUW$I?m zu^|-BWim|m)JRBP<&;ma`N)|emO$^8?=q=c&%Ea?cS~|)B3Tpp20^j z`rSPqo1l-XX3p}Z(H=1xD+e5naLVkNOq`9CL1W`!&v%5=_)@AM6^yd788-O{m(tk z%q<2CLGZnAcc+)s7r-oyS9FT(Y)!aWo9R;EC_i~TTA;y&9NU=S4{Ds|>k}kG$x`=s zjPusdd?a|LGDYvMgxuJ0!qJoh=kcl^4jd2VAsrKxN0XY zDe{m-b53xQsZ#UKnHB=lm@jt?k+mAZ0TN4XK-Cb~H};nrg5>ia)Aqd6INf&qyZHoE z8l5Bn)^v5g^@y1XPAlE+_c`;N#}>F*)%~60@oUKCVgzeV_uG)Qbnv#lXBGZ)mQ)Di zTUrCW{lj@?9BBG`99R;ylTu~rbkyARoIAmuzk?lQFK~2r&Wp&gho-|Wl0{he3G5gz zCZo9c22+Pxf%pkb{KT3%W9q4yPdXDM+s~xDq~Y zmul=4ZNb!^Ap2{=KNLFGg3lyR)AG~onpE{?QweDr;qOhNXQ?9x z>~Yf?S(1+B3n^uuhq1n;b5ZqAbSEGp@1FE1rAIr-;-N9JrUa{g8MLp2%X3z{Z~cXM&eKCwy##zvrZlXRV(ewxX&e z%j(34n_m5t|MZ`lLC22*j{(R$9Ca!?w<_hnu}mY2r=A>3*XGTDnW&cL^2?yT8}YtT z5*EVV7-VJ{HF5mkdIwdm+UC9;gy?f~{$J?uXVu}K=2xd!7LbveU$~HJ{vnyW2VfDd zAbl{4URt-|V5JpAtkKH^vON^KE>`&o9LYbOhN3%no+ICWxufrqd?$myd zKDLQ*-35kJ^zj;q<({fYyPIZ|4ba^9tB9QSK!2l705;0RoXRFbMb?Sa| zYTgq|90*d0dk#R`Ewq=)Z*&SM1TT-X$Wl^=8`?n6@N(#C08GEX+>L;_mQ(L|<`|P9}uv^t|6mjXqzvwPZO9i~c zhSA!v=|a%TgU5pkIxQW-oJH^#@G#K&3wUz>wg2}j=wwV#f9Vwuq|z1L_g#x>Yysdk zGe=~_H>=E9XKX4Rdt{9qNGR`?E@bw+62>Y2p*xw2jRnkKh!}P@fu$Pj>GQ;nP?9ur zgDDxVC1yRcsxJPy+Ssu}3)i=gJ9?h}#R>nVyKKDR22Z}MUba50CKUf@$ zSjG2k9aaT?^KBBe<+F|-)%jchg;;?0314nsS8*u>+CKp>c~2$sg!{La6m2c7EB=pf zQkV0^l5P@<3NEwm*Rvx^d4)>Ud&`rD zCW%EAgcaHPn&1{d655hj!I2OL^addTrbrn@c#0DFWiO+2HHiDnh*~UrL@3mbgLQCB>PUBa z93$DrWapkW%F$AM&hMd9p%zal@-C)jGNtiipWRYb?;MO^xttsm^1FCaBw9q2ZO+`; zNvj8K{EV6gq0#lg&cuJsHp{xO#R_97tCuX_o|nJ{jBSQqLPw>$RXwOve$tHO#!oQJ zK$9Bi+hyinPgwDF22buSDQBwa*KPdN7NCHZ)HX>R;WW+eJyX0u1BU~2=9W^I80Ye- zACB=BqY=gGjfZj2sF?H7?n>gn*6XMI*098}H(0$;W!Y<7?_N!vL@=iUPeUn38P2J3Fxv zK>#|YQQPars+d(b_7AEtp!hKY-c43?!?UZrQ~^GA$zL4sGK$SG)-IisgsLj3%5N7) z?(3kf@0I{3sl@6R=LM_?Ay;fPPYF4F=_0)4S@nyP$&I7;Gv6Td2IP38EMFs%nWq8$ zu%&5gVy6k?T(*HJ0yBu_EcJxHt>r_OE2*7z=x#k4C1bJ zpL(p1qvWAw0_wm?4gD1k4s4eW+-tWZ%=lgQOdS(El-;b~zXS2M>X24MDw=Ys^`!Xj zUBk{OR(#}(%)dy5Oef3iI{Cn<`a)Vo&OG-=@{!1QMY%9yXEN7LFgR$&iT(}Vk+ad!(bHE34-i8DijlRLN(S~l&H7mezbvz z#9$%bd_S6Mdtd{8)SwsXrPh<&d|f&ydD}Q0w1uI7mu`saVhfAEmKOpom|$$&>Kybj zkajyeOX`rRiNUTLyy1}&7U}^?@;|u%n`mf_GoCH`8P5XVY&s+rv^K8`kWqQ~B7P5r ze#FXZOoQ$HN!X!#>13QsAIMcSjTgaNP})MEUX17Lj_tQ0llrqHEf2wE4PhefsPon` zVPfN20ljT(r`FnTz&p;P^%L7tLcy`{^=IV6J2>s#i2TrV?Iyx z>jsTJgvcxUjUOj6rlV9snhq|{2%3!FZ!SnA+@E~}>ksm5Di+{j4iCZ_DWH@s2wBd2 zu{wGTUc3}yV7z$cwj4vt&{O{bvH%9M5PHoC zD!G1X^FT#6$%_P1MzvN53j9-h--e5gXRYl<{3rp{Q(m)AUf$&3C7VlJd<)Ggxc8&4 z6MvYbJ@La5}C-Nv?YEhLnD`OCX^yfyoY3||Z?#0u7( zr=zzbu2U5PuYfr;#ndMN4)0EUaZbgpH#34y?%>g*=M;S=9$KIe`AvPk&u)u?HYj}L*lA)N%+mAR z;ZA48{2iiIPvN=N)H9}_BaKN#JBG;7eRAX!d*}wgvgCjI3VdJG3Hs|Yk3s14_);&O z1H~gE7uaGpsJPD`GRfe5Fr91t?CRO31TEof*Syv)`H%HBXl(-joW4``uhswg)3u+K zyJ0qO=l(tpHN8E+yvLU~e<*7OeLAjyOWk!sbO-;@tLdM(rT`MxMW<0PYarC=CB_0Y z*9zFkd1Yy1ffOHo{jlJD$ntGlWltY z&K<8_&MhnU-LKFN#G{wNF%esa$y+`ap%z;;>2m*5zv5*$$6@0SnfKg4N6c_ z^_2|)339LuQN8#~K)^8DooEqv6jj#e%b*pw0iHBW)%EP8cN@UA&F%~}V%p1ETU+C0 zJd;4@>Tn_7*orLT_sQ8y0|P#5wYPlJqW6%l()?@gE><1TJqxOhr=MxZOx1@iDA6A3 zo*hkpJWv7vC9Abq`9XRfm<&MI#Gscfn2iZ$iFxNMt#i!ty2ea%atC@?d*eWNBA?~H z$s&SHj&_WM6?~V}d7)`#GRRB);^PcStYv-HRc;DL(b1E)q6mO=o2#s+GQ=wTS0VE^ zg<@u-0|CrZ*6nNTPn1!X?jDsERwW)qLzhRNJsJy*Ql26$nCcn2^lbxOc-5P?XvZGT z+N2X>1WGuj`D*K-MwR6`W@Nk%;e&d3E-fl>TF<IX1S-s+j6Ul?udX+8$Z3r0ppxq+a3o_WQy z3Ukci{pU&|Pw3@aV#xLR+9>3Hr?zqj@An&s9?RP!-#21nWk zkptiY-v6pSADBVNgyP=)6#rpr32o}$zNGG*;0zvN&8TAiFB?(;QMZ8?0gQU^ZsmcC z@pHrRu-HvI#UG|oV%xz{NLVPnYNNmjic-apQsu?kh)v&+alb3)irvUH4klS$slM%a zRkJd~WF38u0H_ui(}X!JVx;9%g`nSQX2G6SD~w>&cnCVJ{HdfiB3gb=qFI9$d6zBn zU5^vTe_Oe0s$Jj#C-$>P0P922D3mrG=`GpvGI7)E zXF+4oWaWZ>jya|c^v)Oh&rKAFGZx~UIsocD^54wkT2?oZ$@heTHzKmmPWI;!Y*41) z)QtEKPXPzsaGrz5Bt>mKIC&3c<^JFfX61eeT&fsO3xe{6T(St=Q;nI zTn2W5jaPL<=Bz#|Vv+V}XCN(x=Zln8nTckUK%dC<$hTKd;dLMK6>_R7ol719*&Cl!3ZJf#Wrfs+UiiHL~g68OaL)IUSF0I~l#sr?o})(?D=i~j4L0nbxC3jpUEujP(v{m1+KCa{~A07i1Q57ia< z-)7B>#P@+l6u#}G*9ZP$GyQh6AL}6WfEgV7%~=2r%YVoxfBWozxiEpv!Y?gZrD;TZ z_jU%^_*P%xYaeLeBSV|+!bJ9%<$7oJ6vKuy^(+UM!SMy35C*i#yny*Bc@HOEUzwzm zSg+xR))JlA6Y)-+uASa>i9QOh(Ps0VDX;dHz=B|!G19huR}_P+0zs`Te)el!g0%!n`y&mzcVUJ!w=@iK44NARoB;cA7@^81DH`OB{Te39ZfXJEFeJMqn-XxDEMf zitv5?lKzaaed>FQv~t`+$eIf?S2_?xSRRspT)87Hd?-Mk)apxtFb3c_t5UTy&(hP0 z0(tL>2xE!2xZMZ_wymsqrR6+)TCudq<|zdt>g)Wj<5w1aH9s{j(@+{=`7JAjKsCY9Cx7cXn9xmD zrVbGuy1v7fcA&E|X;}yyuDO^HYB%S$D+IbE{Nn`6zf??h04U13s*Mfb?+H$dV+D94 zLQpmY8Un>PbI?|37V~?*cRs2L4g7PB+Uhle{|{s^uuLjRj$JNze(lp-%~QY4A{^_f zIcGeKPMuZPyI#WQoDN>XrWDMD0(cSj+%eDsNmM*n`o!pm_ z?VC`61W>GPhADalHJ2*qQO5fg->(mY+WXM9ao}qv#;m^ju(ELpsa{*NmgV0cp0kFL z54+4UKUXcihLae_Dy!L>6QL-HrN}?N`2AAV*lV~15h`dwVdFZuiwkj`+^KnRoCBZZ z`KEu{-?wJtdb^zqQIJknXFhU}r3Q<`)7h>wM}+yN_}dtMj>>|i#v``SpZVXX)~ZAv zgt=e}b3~OqL7IP#n)wwW9aUoE0|X~?HV-$kF{dcJgE^v-kCQ*|`0qT~F0r%WE!rmb zf%yktUHg5CVc$n&w#fgxKz>{re0Z%rM5jlIc>_Z!A?6gL44EV9zg;E#mk7aE?uiJE zJ8I#>nG#zS`oGd&75b{CubP)t^RjBwfAd7&eeJ3vU3H|Z(aUPcxEeD471^(bjQ{V4 zjMnyZo#r-v9eY(~KdCHz@lRe}ObeW@6%3;0EPwklY`Zj-7PxS$fARAxY1C)oD0(Ab z&|;hcYV1Q*)iOhqFilXcFr1?ECh~cDcybzhkm*wph^b+np+Uy(VKQLS+f< z894nRuWBj=T(C>!TXlHU@>rho7{qh&D-UA%lVZPLhv)K_sO6CliIV}tX@LbWKgNVa z&@{x#2Q`Q9M}1>xR*ohw#U-P@QOyILD3vPy)S~d9<=GNJ8p)t)aq3lb1qB*Kk5Ca^ znSg!iT^~jsuC(v}4~gQx3ii@>t-a482Wn+v`}-%&P*oyof^Qb}m(TwFJFIMXLHb*l z*Rql6&Hwz(Z=b9V>mT9#F0Gf?m*&eK1p8*tg7YJqK2bD0YcK(nWIj|aO{-9)tLcZZ z-yQ{R5pw#;1@J^sKKS=9^if--86!HJRbPVVRNfRd9at&&BbKT}{tD$+++a~&-eFtp zFaSEu8Tci1+2^&U%4~kP^kVfc+t1Ebs0+aoMV z+xtvRVBcLQcQ42&typch?#jmw>{8DguM5Vej@X2Q3vi0N$DU9rVZg?fY_5|EF3Fpv%mbpwN;OgG+edA4JvTP|% z(LX3dY{dr2+{T4~^^&!j-`@g+wn2xu_Y{#F2Ah(xFL}5B?x_{)eMB4Vs3NIX-({PA z4ab)i=O2qppzxy-aD0+uCs)pb8{C(>c$|;9Oao@B#KeUoK&|k2(On3q$>y1r%Pk9F zzX-e)^ZQSOui;2`>MCgQD$i4`jCOdIy+xH`bTke%@OzL7S7CxnW) zMGB33)X2`q;YgRZ)vmaJYd63pBP}1aS(U$~a8^9KgH0U%t3^1HrW`Az_-diCQbnFcr*0>;0fwAH?(Uq9)>e*3vYCW%^q ztu&a}9|29x#8ZgS_*ToVO?Sn|E7v3?Gq>ZPBijoWO8}1))MtLa^v0tKTrf*|XRLc* zT={yo%u1t~gujMc=!J|gFg0^P57?W)D0L#WBpUtrED^a_A1Cw+hsEcGPLF&72c z<&iCH_|RAyOBx4W`r0sh<<_nP@~Ol2g)?>eT2MY|5?sJQOzq%i#~Y-K=`#249}@{4 z23WiD+?EAp=C6E>fi3U<1f)g%d`NUVB3Z37?(ZwsviuRQ0U;sR0ckl@yv(eb*fcPI zXr+qhgT=_tnft)J)qw5ztpB>^$<`g@$Ri399`UFBWP>wx84^SVYjjI0)5zH7-8uBA8e8f_?8RbT*dcGs=$AG>%f*?br35SWYt0Zk982MQS53I`==3Kjbed! zT#aJ?Cq=QVMrzeatr{t2n7JBBtwvI-c;G4?_%pW;Ud01f@xaxh#Y+5bwP*p5w$-A= zYSH3vFz)|=qQz>u_rEjUD;#sY{F4j7Ofh~deXLelnFWf~D(h;M^^a`*`@C(`<)mfI;dHcrk V7L6TCTLb=RozXvyRkI8EzW~T!v%vrW literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/traffic_light.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/traffic_light.png new file mode 100644 index 0000000000000000000000000000000000000000..ae566bf8334847db1630bfb5f2cd3739d1dd7c73 GIT binary patch literal 114927 zcmeFa2V7HU`#-D}_nwFYv{q4(8K#I3rYHfG4FW>gkgx(_BU*8=Y#pd5;2sD_5sNbCo7-5C*$Wb!yzLwv&DV;lN(hO-QtJ&wMc3jK;gg0P z+1(TV_LP=1lN8?opYYDkj#m0s7CY?VxvCO4DIuIBx@E^U9fHPMF(vryXy;%Bf2mm! z9h}fDO17>}BsiifDk>@@g8qer+UC~gu684qKzs18a&@zFBD1$3E(G-ASkzik%xzeQ zttFHxB8H0F9WC+7j=OL=1kK&9tZOJ<&Q`2zY@D2I9N~#*O*f)Be8d!wO0yTWV>4dF zaJQHt#o3;yxy`}N!9m2u%L({1`WeGdB6+I0nmgMPoGh&z;c=FptcT&mq%pGKh!>l1 z5fPj;i+CH?;U}>lj1Fkqc@J-qeW#7Pou!o<`)<~q6elM~ik41NMsM zuC7kh(U(~}IkNZ1zQ!5UXVmKGfc7|6qoewEmK0mowbEizELzarm6Tzf zA(;rPY+*2@>H^NMC=~sBl|g^ir;?k z7jC$IF{Zz>9Ox@%2Ih|L!-~h!VT#wV4g)(dEw>|K5>Nz_q1XZ6HOwun9Ctdo*-=;q zWZ^`iIFZ1L9nlFzbE1QdtCKs~Qpw5D3F*G2m9@FMBe3hs3V2658)SMECucZn?&i$W z3u`-11S*Qy1M$O0!BAL7&{F0Ub3hjsMPjOM9yV*m6g^46W2K$jG{ua(6vZv{J>7}k zB6jB6c8d^|ojf#fmN-i<2^_&o!h=X6dJydKRDzO>war@qa|*~q|B$pU91qi&D4 zAt>QJHSHbTwUl?+5Oj#58ulup>UN6GM#>^~I%=vCMh4rh33lr6%$;hx9gWBY^l6)> zh?Tyl<4!vXdy8!Z3IQP1T;J18izMM;LDH2X;&yvkh*2E1>j}6?ZKiLpyafO*caWP4AuB+gY5{R`=Lx@9Ac)FX0F@c_ErKy>)>` zU34${F0QF9PSr#->L40byfl@>z2Q0H=s8--aIG>(ne)0{M*5l}>f3gE8R|=T8Jjysf9#9=*HA1|WmC5|K5IoJ?MG9s*V4%8jm>Ne(Tdd@~-wjzi& z*rOLb8)vS+Tf`hRhM+@mC)leXej?gDVJ!(wCB#p}YZZ4*9S*eFVSD~6+O(9!y)^Cc zA_OmSQB9?Pk~Up;O>YkJ_8(phzV=3n7V5x>sLd9FdUfmPvGRsD6+yOC= zJ|Y{D(6F~bdOpTR)G-?&lJx8?l@vvYBvp5!m=U0nh>SX!rGH>kB1YOao?r*Cp1KVI z({rM;`nK&JmaKCU-%Oj%E*7sa+K6CtDo8*7Roc7=%6NAzkSPK5SnHpZsW;#b*f8LU zEfGhMQ737-5xqo!RtQ7@U$;9N;&$1vEt6z{+fD(5U~|#a)>2K^2{09Q=OCf3tS$x; z@Z6!T=w*T1jh)ld!8^mQos9Gy$>!St4Z-rXbksp&EDXh@=q2t&0Bg3w&`AZYB?9+| zBZNVktOe)(7ImN(Dmb9dOT*sK>z|}f(@tCr;osk(4rw$&R2|Sx!+w{@KS&*DtT-U_ z-=q$wVXrF!)PYpg#r{d^kni{ty;Jja2LBB@p^kKh3g|70>4-A+T?~*7yu%mIGvYkv zi99*z44?+4(W6!-QZ?*}$SyG-OwhqF1Zf}UD>c3GfW=5#*}hT-;nQFGNpbL3VhFda zI8ti^JT+uJlcn(z@Vqg&!1C*C%=!lF!GkvGqNoX3k0(Ky0M^EV=8<^)^>_=o1O5by zNsxa<&jPC-NBbze{c75^bWm(DjO8kz8wltAp7yGPbaip+N+Mq1tv&x<1mOVjs5v8Wojh@w*@Gb|Gj#c&*pTrq5;LR17%)Hur+ zi*FeA7y{N1f5$T&h#{0gYgu>(zDpd3P;`v{;<%CxcmP8b-LsH!^hzjF7vq5D!z+D7 z6rriC4)U;p%+C;EGH#@=(a`zUcwZO1sroSYA?|0zkz@AxEin#?l9U~QI$elybS3^t z>Oj7nr0`ADA)Hr1)PX(j8Wn;4P2Pz^j3fHjQN-8V#V*hzh$z_c9Tq{2*T8StJ5&rb zy$P`QT}bBM|Da@0^ojYqzo9qwkj?4nBI;n@_)+oQ-;@kOM^16hH}Ouzo#1T<)Df`U z=^x}BXf(ukf6sq|kA;c|q7Hnoq4+;Y9Tq=wz|e2uoet7D0@NLL{gY@Q263?%2TcA3 z%0Mr~3EFt5AOZipRYqp9lyA+)G<5*?e$TMcZvQaD9$DSe^ajmRMwKGWhvC3yQ4xx; zs#&^#@HPkoI7YoA*MTS#>;}6Q^E)HHV^t>2VL$YBQ8}vugjK6h6wb;sQMKwX*7=%> zkSFjR<#8f_8lw;xbod*qRik1DR5AIR8bQ!O*(E|D#Q9yL^0l`5TFks2(s3Hj5d%b ziVgo3-z0{!w||f>RKxZ9oAQ(ZzGD%>Kg%<9=-_~!{5@S8RZIBi_@+*U8U^)l$`i|D zA!=jihA5`Sa@;ZAidE;(5F?^GDXXUipP*mHZtg+D&WhdX<1sniVwG zDXw17&1A1AEC(1633ek{A=@9}@M3F<740vYo^YliALfEmcJu0v%tHBmPU zGAhB_idb&LOKNz@K>L*FZs|>Mhr&Bq!y8Ob8Sg>F8Id7)5;ND=!|fu;AV)`4SB3_v zjtYeF;QW+#QQ`czHcmmk9jO`yicq+>k+d|}?zTfo6FWwP7Kpi$!}#VXyUF^cX=+Dx zhg1pLlA6CaS;sU>HCXKhZ!0k)XA3o|q`J4dH$mSJ+8d)Asj!YSQ5B?QQEbm6+J7pjfeZx*tN`QwCn>Cw47N*Mv`gi`YT=H5E^0A;X=b4ED++p1 zu?=Lwh7d@h#|OIvR$B_=t)c@oRVb|B*1-)LD(;&4HWYB_UIYU}3PB$QtLmPX_NwL< z+9IfxDMHYuQq7e_SjX)|Jk6CM*tb^|Bj`C(pe+m`+AdEGWkn|qltjUC4INb{_IjTB zBoTPlE_Y336*q#~fA=|m$QM?-Ze;oRulWq}M!`3Sv=a(ftl~d$e6b5@lbVd1mA<8i zg`FbRLd?IdqF@5DGnTi1~6RX385-*6q4z& z-@T!!s0_s!ZM-)GF(5g-C#(l$Bp7pmh8{YGS+6&gl+krxte61O-38aGfD=cBP&_yy zU1+ln(>1PeH@r(F8S+khs)rGb258`5FvD9Mjn&{3VF-v~Zb!yuqR?Q+f5K5oiin7O zaX@TeB`qZ*B*S(+BYc&VG<#}jq@NO#6c>^J*&&DYUvX1xpZb5*P5sNWIwH`G#`?C{ zl#7F>t(Cr>mjS3COpQ1g=^J^&-@|h;Y`35)Wkhmxvru++w-A$X)WT^(A6drLNXN+@ zY85aMpf395n6@a)1GTis)Fg~hN_jS)f z(>5bq1~%mb&p}|rc2_Ld!MUcva)D~lODBnV0@#2%pn3wdOAz#_C^Hw)fT;;hHLNn_ z37@^eRRD0wLDtFm1P3N?3P1G$(3`A;|u2^kR?A#q8WFaNL}Iy@mOD#9MT z9N{=bVLDlqjngB2ha~&b|BBy`U^DCgXnOOn`wfB@o>jH__7nyD$#xHOFQEu=+AU$BrpwCqhdmrwUCj{% z?>a2X^sLSGH9a7SLtcJ|miz81ovTFtij*#U`0>iRZNF;vu z3Y?OdVHDWLN|n&8tc4CXQv}!wRWcnTn9o9(t_L%pn6JQaUQ5}=4X_xxGze#H#1Zyu zDcfS*2Lg!z*FZN`XBTDEH84?$-G``Gu|dAaTT={XZlP+Z1?h+ens`$tqVFJI5x_S{ zTd-r6kbZz~u?HUjvl!q{Bv|W1>VamIFrW10T65sSm`cldA3MxJmM_QX8tu!Ge}GtI zgrEI=#taM4S(QZSHvbt{M`J7O$N@_zS?CYdNcOBQk|nFN0qN`?P(QM(F$(#yCr6k3r*c0)?C@+HEH(^KpBY|EVCnPQg@3>&;z$mE43E`yJ$NwvE&rWB)rwL<5 z`e8u&JKTSVd*n{O!#xYuS+7g{{|fFUq(r5K#AW^f?q!Ap_5U}Zo?WH-4)tT9{(D8} z_jj_ssq*x_BE+gteXj_is?YyR6(LtAiaGmDR6&{lR8K)dTufR>hW#QjJ7thW{c6-C z80ka)7wbaotme9-1HXlUy{^wr_?*pue=Yl8ovRq3HWF-28kt`XA9J;G1bz1y{Z2fmg!9kG zAy}gwtUu9c#7-wW_>qP$(;X5J5edQXIbaHnSOlM-@W~z{8Gam#IqX}%ZeZgto-2tH zg_wWez^R0!6i!G&9Hx0#|FC0` zVQrC-{PGh{BO)o(m>nM885vE9OAGy1i}e8RSZFmu7u0sEsAxh=q7AKkJp8~Fil;{C z#qV-Na^WQD5h^oMtVllN#0qiu2(f+%$wwqp|1q(O2Jd7zLl9LxnUa(L&OS<)tLr(|JrYL0YY*V*DEg6gOUtBtR+GcZq^n|rm zDeRkoEz17TCoG~sZ9@uN2Z51|`O#HS|4cJ4(~ z(e)MRh5hH}QQ8^NF_En;8k*y--+Z(IL{4}$e>`hLVb$g7MsrmWy?(&7jGF1+Me$t}EGznM72mDmJ3x&=O@;4P z@!cxETg7*)V8vhGBdG7e?DxE4Y{dNCD!yCAcdPhr6_7`MFMNEjL4B`5jjDluw~FtT z+3%Iv??v)2pzyt4@x5R1y>*0Ik0YB}|A>^oyqdj`Jn;H-0+ zUL~aq-N{+7BS-9qsd>NsFm=h$9=AdX;=#pw%s!cc%nLD;~IGis}$*-OAw(7 z#nYzIyb?A?#8e)QIPR1s6QA8eJ1t2v%J}$T=HoZq#*T?g#VofuWFG5^h@QKMQ0@h)|pavoujs-wH4rs zUj%(D+#$I5l4|JD;^uUxjLtZxI7=aX>H?2L3r6w}gBNjSSm@D@a#K(fF(YwbOn;uL zd)CDweD`lVghREpWY+Qqd~WNVHg)#0MSPXkkv;hVpYuH{E320{1@u?e!T&fXDwJr!Es-<%!LH1Mj}W8kwC?Lthys^Vb4 zxb01xlmPunZ&@Vc7#r00)i=qHsq9;xX12A1e)rue9FO+O7ZrA?0Rs-A{avz6^M>3XOur&`D8_hM-171L@Q!`3 zgCBNu9meEB#nj+JLri};F+8`_n9L)b@lkQ&s~ItI^UgMwb;!0H&g`nfnR234OQhd3FV$rWr(O08BSahsy$z1LfqN{Hr;Y2^|`ME8h7%P}^80o9$DL#$!%i^+c zR5lCaQ!6jFjE67!4xn3@RG9>H$K<1qzuCTx2U;Zb%~lcz2Wn>C)AIjxye;&&=9A@a zQ6KnMQ1|Tdygxa2=+hP90GY1ds(RX><9>3PI^)=Q+7BUt8l|Wq+7mE&PSl;k0E=5B zRpaY6(R1)1cV6Cdrz(kp^p=dIIv+phPzj6I_X1ZARqgkGt)Knb$}yYakvo*!rM7iJ zgem;r<62}}30#c$cy0f|S4UHi^J|4Yma171zO~ObyG68hZnD4Jr`zFvn}TNX?EY+0Gw4sE zJzm!q5H8RA!<1QvE3avV11`m9ry9L3o=!7)N5PGQwLsp5^C&)!Z+IhsADNq0G2dqn z+}z)CVD8qX52+P5?k%Ui337Rsb7UocYkL7swC!T>(V;t8!i}+=M;LOdp&JLEf4D}? zrZ6wKFp|rbTsrU9l9t%}K9cILflrM+N5%#-kp6zLPdX7Po?ulS5?}-pV5*reJ+ryg znAn=xweh0|pXiTaTN>-wnt}MpOP`}e*NrHWmJ1pQqj?c*=?bqL?!x5GHh7)F)FRt~W%Ya-QCn)_jDG34sD8X+Ms9?Ee`VWAeZ|hx zi9}+8{-myp1(L1BGiZ!oDSYGQV7dt8;L;d%2IL^O5y_zkJ`=TM(o0U!kES0ATvo2U4=BUDWt|{+#LDZ|^#0HmpgZ^z#=}(w}^=9;F+YROHsJVs@23kP`xv@iqk9_UU(@3wDvT#W6PSeO^^*%_F&i z5M1@g=ZRL1S74h5=1A{tsVVonq}4EkX61Na4rDnj-{B7wHJI88yOfT(oGBpZDLafF z9d@5Xi#uJ}XW4SjEGZ*znL|!aurRr?wd_>#$x@9t>R`S6ke5r&gTbruF~+4!s*s6{ zq4(ZJz=>coa}GLw><9qqV!aR;A&xY!nHN9aG)0ow#*K}x?V#bWE1)GvNnzSCSFz{a!t2uv&nLf z2Iu_qc))arwx5m~C!!cNgzAQO@-a8PelUzldQSG6ox5EiZqf6WyDN7UPHtFAF%FPT z?UbSzo5g9>gZsZ;deq@ombYlly}%#piqc!7WMj3MrQW0VU{=YCG}>pH?$|W@M$*_#Ke?9zCW}~kQwFv{)|h>5&k9D2HI5qQtxqi#&!$ja*pY6aAyDlNlB9h1lHS7-m3X zu>dnLR$@Ub!l$nFLD6o0DkCN3k$i9T(2-)_zUOZBm4KnADQ&s?$s{Rjk#X{$I4J-e zV&-(DqI4WW<=A**`brrKoi8?k}O zG20#=YqsFKNlre-Rp3NOzZ`1KaNE*z?*~MRB_~p5E&)<_Mv~$~Cw(w=d3Q1q0=t)U z`cPI88Z_s;lTb80j&XL@_<&wvZ{Vc;@!SUxW!|cY?Js4x7+`2&r2!3H?z!(G@R#(N+HL#{;3S}he5drNnT?f_|9|95Ai zZ~WvA`k!ZL6J;3E{xZQ&FwFOz(}x)}_gBYc5Pya#V}IDR2NI2-(Ms8UE2%hapt~|* zf`4m&HMf-CP=E6MYPWE?+A!Ic_3zULgO*#QYx!R6F{Q^99-TElVN%$80g3bH5#j_- zvXGx}w5={bKf%BE>7?FxpOzz#Fkf~37-8zYq14c)*|R0B-r~cRh%ld)bm3A1KX-iU zr^2OU=*1}Q2NCz{#bbbllIjd@gYKAqMytP6{N2x=CiOPC6^9l|)nvGSJjCn0-UC7b z3s!9IHQ2kK{LWZ(j0IpSPy{eol(C0^9>@dm$|EfNV*@XRueaH$?)sXr^~dIJVaD`) zUVTVsj{mDG5qZ1Rcnu3&==Z1QGm8U&6TSjd#&H*{^9-ownTS~Aa#s;SXm#(b=20Si zDl2QFQ){vmsy&YrYCq2uy1v4Yi80;#^u~cHZ(@f`qo0o5?nYJ8`lnlrNfMU+~3oNW;68Y zq=C$e(waDu-+7n!XA)nQ8tVrQK93$0AGGTESo>KprAn-5bAMB<4?gv`lhWg}%zX;k zAUOZT-qpx19_<3~aB)Z|I;TV*$eYfeBa`s+b79}M;6(R>`0gx#?ls}k7bjHN)t@Im zfQSr8_8Rip%fZ7|qp;tpJ_d@eRa!c%s_`B%8*0$c?adG2b|Kt*)xQD0bGsN0+)p_+7ChOZQp~zN7f5Db9cfEjmPF$mP zfeJcq0PAkB=0^-VmXfzy>zkl`Nk@JMS`+cHS%PEK=jq zhOJ-%JEM{F_Mqc*ceuUrvbxiHrbnJ2)8qX+`?1%<3hwYaLL-gG4Z{HxYsDX5hYGPg zssHYclnOFi?n0fGt~7V?6tlih5yZ~9{vxOtR31>{7d%8dsjGKnIhnTM#lkw(<-K>Zp}_fOr)n)Gi0BnZ@tg--+)R4735jRtO?W$Hqtgee1UEXvI+9d-9-@2U z?2g@gK0iqijepKhK_O#xUuo(R*|Xv<7HwM5bisj>?&GCCAut}Q;wI*lg&2t70YuDq zB*+sXq<=JjO>Mkv>!vAD(ssLNf!{FoZOiSscK<-|P#kRU(}@jWkTR)s1>-*_30P3)epC(cUQYK-m%La z>Ns#in@Eqr=XRr1uB~`>(5xfs+-7@x<=vm0kls5q5ZtQPoMscUQYt>yt@xY_ZmYOw z;pA$!9Nsl`%(l98@2E&*$758)_E!jaE|a{MAoVb~j?(9uzbeuFx?b53Gu=x!#FTx$ z7I0J`fp$}@4eJqq6nf<>#DTf54MiM`g5if$GbHkJM0F_N^YKEPK%1vHOVDi#dG|q8$#EdZi2rj5VhO=5;72 zsg$JaWTc#^CsXM23#2g7pWpJgoiXvav9e>swWwv4zMt#9(cxEnG{z-%oBAxKr$c5a z`u_IAjY`?5Ve&#-b3>6lyHrr?lkJ-Jt?|(yK`OT%iWx!GQ2441KE!Lp(-&aos=mUl z<5_MmyPozNit-)T&Ox!}7{j9rgQ1x@`X5FoT%kPYR#g#;tDi>^&Un55v~!h9E?v#< zoj_t`OS*p0)?uY;?;dQjsjJBk+3>9n6!@8VXyp=A+7Ru4vXI3i`h}AhhFYlE!6YaZ z6xC3Y3Trc*{FD9#l83Y0T>A4?n!qU&k5}8D$wQwC^>z$gau?T~vU`5ikc+Whzjl0Q zZ{nntkT9$~-itBl5$dJ5y9Gq2x8SJ*vn3DfDfqoP$c>sM;gv0SFS&kv18u3fTYL73 z=AXN_iK&;herP`YG#A15u_Umg_O1p#N=@Q}8EubAse;F#bd=U95D_~F z&Ma$DnSXbB?$YBzS<;eA#d7#5v8G4cIYcHDh#owqy?4d18@<#>rN%vO9GuSJkMjI+ zu=$wMjJFK6ki%=jH{W#q=vK5PK_0ark>OF9JDooYx}{l*IWhnO)aHVxFEIu{V>7btlh`yGe>7!x zm0PjgMFEkNw1~X35H&HQ`%!7r6F!d`NsozmVG< zmwm0WFP#>ba6|iQ&cyy!Ghcc8VmV^dT^Ez{e(wv;v|YIGAoMY6P1jN$wQ#D_a%vKPxI>zbt{&+_Du=> zOd6`C>zldj2GZKrMdpxFtBrgEN@ePEmKZzkTHa*#xt6=FxYEh2AgKk)B~XAf_7!H9 zTB}UqP{FwkE!MJ`BkLrz$xs@XlQ0^x^NYJ%d$bKo&1pS@QINrbU!zHu1K96&yj|_x z)|6D7_v;QJo+O)MA?r%-^4ro-{65+`Fq=_v>*=cTD!^q5g&6M*Sfs#iQ`g7Hs(G*j zz#ATPpVs8EDy@0NJT1^Nxzx!ARij2RPF15`E~q_YZzm7eo|jPgwW3x`<@0>)dtG)e zA8$SZ<%*~auPNVrr}zCbsO*PSxM{(Xm7JG^a<?iMNkNIJ4 z2SCisbZ^q;Hv+@6 z01uE3VD-OYwOTimlJg`Thi%)aD_d=f)$!& zTlvk6hcX+kR~}8PnX)IJ2%m+zoJS8yw6YTOnloKvnHU11DR99;T5E_N!^Vf z5DQ>F<00e5=d`KeyelDn zZ|M8cXmvN}Kxk}yhHI9Oa8uc)VjsvwJ5Syn-;9Q=2Rw(#CCVD4uh-Kdo9dn|=$i#f z+^B98{p(6uYmI`_qQtDJ4wD(?eEkNqc*HLEyl4VDYFPg%WpG`K5^9wdm-0|Gqj^z- z^1UqajMb?lE{FI`mEU?~aWOnj?BUQpidhCR)-vif)BsVK42+x1G}$5s>9Ti+o-b)Y zuCkQhqd$ltR8l~VExqPy9L+_}t@X%;<*w`*KOCU23Vx*^vbyRB;?T}tU>Ea!Bf<(r znMGb5dgY{n?Qcu3*#!(fx#p0bv%BhQ=Y|?otG+JR-NbyJi3MxrdG~Kj|)ig*L4->>Z*5O(l0#gd-){JtR~}nK!iTM zxp>OwSz|&=gjV9P+hsP_Fg>0P&T`o%^ZBZ_+vz4;`%CSD@MsIM4D#mSDJ zJeg+zIVN@2LuU9PiB1T;%A<+X)GFVs$5GT?ljTC%VVY8 zSFrO}w{Gg;yJ0ltr!bj5ro~mzHC_O>lTvRdT^$+@{s*J|x+{gVJee0v{PND=Z1N6G zNl3fr6IM>NTp{Q0t6%IkekNk#BmxxWBJU82F^@eHxfOr>&Ay*o2vXHc5BUzZU&$@n z?D)>Orccke^EC13t~twPCA+E|65_+wGCfW{FGQw4I-l@H(O%*~pFO~g4v=AFcUSBT z8nwoc8d6S5o#fPWZR_HEUh1CeV>3?=zCEsa6jv;LsV6|QCr`>Ey*ahD0XO5D1~?$5 zTTn?(A_S(wG)Dfb`lv|67Wvwb59^LT6&4kF6q1BwOyb7cCXpt5AK~?`n;Ce{)?#c8^Ni9%{88brZ}5nD}k|ra2JOje*M5 zhjK!ts&-D$JSV;(Xx7TJQt!7sA8JX>4kc~vN~{eqq%z#=esu~+Z!BKN^f>=w_IQ;? ztfv<`L_kT47isqKFkii zj!D@n`_}!uu=ZS1u}~E80OVroppqMke`20`&~SCU4aq^BzU$FNxpl~_m65lbtUHw< zKh#?+3bPd!T}`hhza7rwUtO$*UTb3g^<8bX!NPg_CjL-c(U=ep-R!s%_46q^%-yv) zkdEqjmd|*PBlpF{sHzFPd4T-1_3}ckkffq5Niln1k_pL978{AP4d{QgrtQX;k+_dq zejCH&TJDxaDg6Qbd4of34qWS_j2_*Sj$Gitx))F+>8^51tjr#C*z)mt^pewY*_V8J zsaXrb4?dZa+S%<&?R{~r78*N#qU}!v5?1J&`nk_qA$|Lf%{bq9T?T7Q`rhZoM(Ip3q*>mufMR^KyCxt2O<%S>m?^yI zdN4qkhV)=h`J3pWG-##wJqxd$d1%D~m@2I~%7aFArR%HQh%kgH;0JABipA7%2sBOH z0HTqPu5!ze^b4>mtLlpl%#@#6p=O2(Vs$sJMV*}~>sWq!DbB+&13HfJvppIY=JJ28 z56F{%bW}L|v#V%XWQ5U1P3bp3mqRl0Z9}DGeCm}~eJ^wS{af7Ho|=8O*jj~V7Jzz{ zTd9M6ZSSSB(-!og=@Glc?41e%shHR9wOs1Kl-zXk6RB;~`(3(p)(m9=pbc z_amJWRUFeGhk$mIK;$L&+cCx)vLB9DI58+W^}H=CZ>K|f#C0xEqN za=TSg{_oFtzW;CyvJoCsAS(M9#ye0Q_DD;nIaT!aJN*F5BWq6`wwf|0#A@oCO@qCG zFZF_9K<~vfxu+QhbV2R1%<+#si}c*@VHBq4@1eTyl|4&l3QS9Khdb0=Iem?ub$@PA z*veXhXbhuL-~T)eM9ttZ5Os`IC<(!Spo&%Pc-h>rZYpDKU4>`Xff!kVl<+)25U&=ySMGhcp>?&#vj(UZ$aSgC>O?-t()!UeK${xOeVD3uEAqPk99W!YppS1Cl zru!6%Aowe)#K|IMp+M8bBS$wqIC2Fg;z(<*S>3^u!ssxqyn6;0n;T=Z=uqzZHX0m# zg`+;KVs7P$KK!nhkX-q!arRFrggY>P&gjKX=%l^b9fA$5yo0Ff-QBA+hvNrYKDj7u z;VDif^hT6Ro(f-EnU&Qrb28(m)N5?Me^huAcn-=t=TdDv5RS6yda)kd!uIq`Qbk-_ z&cc8j47cPd6{O0;JS#h1IWd-sI(uaDzLRV9bMp0UPUeBxx6`9wnvb8 zb)N_J&cG-fR47J6x2djkp$!>WjnKB*@6v%56SGim{iWqy`>UniJ~H@RTztpR?j8DI4+XH!_G9Vt)IUl zYisVo{p1-|Hluifal7Lp1n$Ac-34f4yHMbsD<#7mY{^&4ZEyAWshsIutd^f2>E9iJ zIC~)`Qt=fw3N_lOGNJ6+Ra+{D0|t5PpyohZ=p35-X0fP%R@n+ux=%_^xaadV;i=!q zRto*RtLK*NhNC25rkt^#V0FjG=*n;3P4?qDi!S?CM-UCKhvTN+*!*v0$!4a1fMbEF z-<1^Zjuz6ooL{qhh?Qm6?(U=$E;P+TS}{sb0yzxxs!nAr&(CR+sD263&1`N@hxxqL0 z)xMD<)HTelZEqJQEBB;^XRXLKO&NHmNwZSO82Zo!B7Wyn-5%BRvBE+46wC(!J%A?ip)!#CR=s}fqMwL>4TLd1VIQ!@mHEJoLxbY3bk`_xHHu4 zcP;m7qWY$q6qA?SeLs_5E_dFF0mDcY_(On~UzVB|UMEb7tXUA5W8K!3l914+h)->p zEgd}`{%pV?>zmJ6F9N7i6^rsbevbg*RtG zPk9U}JC#5jK|4ejpyMYXlRs5=wjq9hOKi!0^3BvDnX#%1m)(R2A+{!PI#S0~P(+EG zM!QVpGQp=_)_+PG@7brlFaj6S={*ap$1tEzmVV>Rpy~ejn8?96w;#vQgYx|bU}^(( z?<8b5+ras)+b{HCDPEs0_~E6i@i=3eI4K!bTrzndVq+Cja5LHdYIa170P|`<t6w62BG zgAX;E`N#XrdDl&0$Np2-A&CbngM$6Y{55PoWisPeQ^C~n0mrJH4zOlvqv#6642m}7 zFjuYne5TX(llxMOuwvC{JpC?$?;;qjqF~nlVJirP?q5brb4rzcESdM6>Dp=HUI7^H z^z5j#*Cy7L|5*JDfv~jO`+~c5U6lj<`kg;=n7cf71rX$2#Vl;_6lMq1V?N+h)zd#= zb30?yem4}jZ{(gIF6=T7@uHe-387RJq*3#9gz37guCeALM|E)83*P$=`pr zcJ}-p&#L(~;qs{i;!?RmiG*9_U7Z{sxC;GzZw=$jITk6lhwt&%h26byAf`XFTx9EN zrle&*?|ARO@80iS5`f_ti@=o@-g~&iVTZ}0;wj41crp>+v|{M%Hz?#n-7`PHw%<-DytB@% z)`Vo%s>lJ>xjvx)oN@j!Yaf9@)0&o1^RKMrVmRgZwZVI&t1G*ga*)LmNF}|MkXpp> zbIp0Xw6Ew#?-8Vnzqu^tmI44XWZJtDqHE#if1pK=hB&6=Fx$36N2&B^tuxZ zwVIeVQdPEf(jQ+R*xYwUhMTXSZ)pDW*3;F`iv8;@FRUAgjVpat+)?&hr(4;cGWn-9 zLxbI--}*4((co;)K^kDfV5YusGY z6CFM1lzpIu-dP%+{rR0RDLS?EP^r=7nDoZ%rjjnhxS82KSA+$3(@6&(X=ahn`ntiz z@=mFK=+y=iU+RMy0y)i8#;dN*cGL11G-F4ap_+Vp|D*ZAizvo{pNsj!LU?2oYP!;n zTQHW+7fAIRI5*Q6-`$elLhi3W1#^TwkAILS_4j!RJ5FXu==CeW-JQ41A+)j(8b3P2 zoDBYsJEe&SNfx|a`~u=tyD26)%n1HUo|(qGRwaRl9PN(|M9lE zPvIT-)^`FTnCV=e_i;L-_vB>8*~yHdDnaWeu{+HHi;Kd;b4;HNCfF{aR9CLAL<^tto zDY_0X6U6yW#^&Gy7s34V=OyZv|Fuws?Cy#T=NtrjQpc& zlR`}6d&VUX?8Ng)Tr@74^_(3AlNf3VCDo=jksF?sS)bD^F|prE^NU$6MG-vyY~siT zhSv)`J#!v2&v)i}Z248oV5JLBs^BH+7r7hh12%6@Ry^-t@jPG#@x^XxqxAFU=@db2 z&MQsKhtzVjwZM8V^qhN|Ft9tx1XnL$9oX{mX>$G5_JR{khxUs`w)?`Q7+dMbmeWo> zX6~CXY1*o>e<&18o<<>NOH`KX}wWDe|_q73c=^uJWkA>C zd39f3iLvO;gg~Ld_%ja|#41qh2Tbn7wjQ+J-jVFJr%+ruR3mk+_}id(E3wVv_=9*h z&keY8+G*ls?5wiVJ_RYAGs|gS(X`W(Y2EH6@&4Rr2DLqP2%Wc=MUu5*9L^k_GoI71 zlCn?=@6XL+25mek zXsjoommsDT5lgVQzj;>jPM1tJH>K(N^o3?K9ky;>&2c?lSTCVvQ==l%^J()}(bv)? z+WGOUW$9BmNh{D6n4zj2nTFYl#X1%ZALnBX;=h9*Wsq!pT6Go-=-CTvA!L_D<@ zUy`89`My2eb%poY{Scii&2ra6PP{mMUSge)!Kw=yzivMvaLIMU?q1h-Cr=+c_A*dS z$jy7$Hb)WlNKhf>=?#n>hiAfOoTkuj*x6P5;=1$D$@mWc^H+j3Pn~^v{K>l9+%yly zkGP+j%hw3jT>m*WTeq*j=7xRRjGH=%7o9e6(c&w2%~0h){Neo*0?CVxotcE5yQ&K| zQazIrYMf@=-Ky6YLoWH~U=i@>`aRmcKFhULT}QW*%CA;jd9sjc#C>@xCo5h7c#wC0 zU6L|}QAZTYj04Hr?T@B3_33|D*z&7)O8w#VJ*(c(>UH{JU(yCkTF#2JNkk+BeVRWS z>sahKd<&?vl;fF=sJnLoQ8$Bfd~WN@H+YjPc*aWa+VxLwDm=K+-B7SQ`Oe-qRK4^P z-ccMJUR4W>(A(R`a0Mb-0je%#vVkpu2c{-x8vR;Q7V>VNkNVy=@3rpB;vUL&d)n#V zn#^gLz#n0mC1;LJ#K^0HAf@rVLU+Q$ehTw( zEJh6S4>nwd7_@IS>?~BFoB8b0b|KKT8h+>7nd@)69&hMgmOv0F^>lH+HJ#Hkfwv(C zerR!NA+|~-e3?#Rcv#o{W;%&+x5{HlC?a!=t?s-HkjRfYkX1t19d)%a>3+X((a1IU z1~m>!dm9hDo1zn>jLtbnAw(sYUvq6<@*#VO-!Exc?*D)#y_Lb|?88pG&Nm=i=XZAUM$m|~=Idq;HtTyqK zztlo<>aCnyRvr^{hkWjY&X1H3e)$tYmj0$~rRuxmo*XRRbz%t@P374o;qklLw@(dZ zDo0D)G!rpul@5UQi@Iw3ffx1U66A;HA(tf=zlOm&aQ{gW84e_62b@{R88W#{UKNVg`L z5L>Q!@0h!Xm!=8IP_*ehM=&{j8I0*C2_B4|dx^;D8!N>))Lswk*JzNvUvt|)^hW=O z5*7X(C!cH&7+jN?s$eu2JLFdv)Dkqb{p8c$fH`w0W_MNWjih`Y1azz8vbqC!gozn% zrLKsnUkGfu!N2X2&wI1$^M6X+Tr}kWIw;u!F!gv(Cb{T$R`-@Z&Bt*cLLGp0jIpb<(^`xR1;9Z2hr(HYXS>z)|!(5`!jT+y87 z6ThtP3@9A3eb;_=$AN?sA@fQ-Cr_o-$glMFkrH`wX72Wyg!ZA1PTK(bGGC>#Y2osG z<}JeO=P{QBHoy7szK_d(OA76d`?V9luIv2pQ>Lq$N5CW#w^Mg8e=&?47?2_OQ3c~# z?!vPSiSwQeVxJE_#`w`I-)`d%wEEAXA;pgeoSmyzhNy{hKh3zmyy}5QOr=f6P?A?@ zS^ivglghkxbdvuq%Ak75=~uhkl`(J#VGZgx^h;;eY!_UNdOruJw z(V8*liGAIB0H(-hU!QdZ3G6jY4l(F*tLcJoL%MuTz5AC3Tyo-#C?Z8M%wJmHuo|lR zVQI8Ye|zv?4R;3*O}2Z-^CjDoPW4qr`CYv8diqfI0lu_7<9Wo{blFj|B z=lnuD&uc_Hf3xJ2)MXp%?Q=CgWp}?@e}gD6iSb~I7avEoSr6Vub>f)~n7&&GE5t0P zP358;Jok9H>4~ca?NVpEPg_<6&Ca+rg*KV+vS(?4r@e1jT-#Br7@wb1>?_nN?wD-8 z5!mrOxa2wR^6KLQ$)xi?y}aqz%GdscaI?lCLo&{Q*t#VojH8+cgJzoCF+6b;ot>8j zlDfV!ki6RF0|+qA@DoP6Z# z_}eofX?iBp@6E|;$t*@@u! z>Kyq}zJMKqed<%gx9L9Vm6w(3DRsE@gUO}5=dBT^9FN)SpK8erQ7Ahzq<(4Ruq}+h z)7aa@XA6O2h+c zx`e7{%Njd+oDRuK5#S#4l1-tWanw#Fath8G-SSmHG-a z>>j;sqDv-_^Xf~x(v-b_OV#=9Zng?OFupCT?eKfaZuJ{>7s5>eZwpV{ZCrU{_p2s_ zGL7gnN|(vkxK}U-Qwa8@YTMPH^8TVw79vFA4EJ|IBXiVwu%zVP5rkLiiZKpvPQ+`S zGVRqk+Z}wzE1mL_3e4Hr?^dJTPJR)4Kqu9nxeu^Jwef=XW&W%E{X9|u^8V{Pg5u9C zXr4g{O>6Zs@pjSkSPY4$$Ip_S#4=5J4~U}n@+?+FqKu%zWHsHrcEgo*aaEW5GV>gs zAC=h43GG0Cu7WRD!*bStJrsy<*Ic{!9cbmdogANX3~)3;DG;+-ZeR-+&BcYz$l5l^ zB(-%_CnxwThd|HahmA^D)*=n67NJn)b?w)qt`O?GuII@8M{6N+zwmqH4&je9lWg`= zV0lVjMqqJ=0Ua<9H|`65g%(pJpiVBQnCMr^WH5p7*cXb!ECTRo<+ zYvpBsPPZ%vib)Dq+pu%>z#~X5x1RjKQ{pr8@{RT@(E$;IjQUoixc!t*Z6yTmZTjcV z$W>u6*kH8qX2U*TWu}gr_5iW4$Fy&QTSm#+D-|cNq=a5szIj`H^ojHgqs%MW)c$~g zLYb2E1ForQo?-VC~IZ8O2SLf~#l6zTMb2VmF zM=GhrDqKBwNdKc}s@YGWnMxafIn4m7li=tw`;~k7SBJIsX?RM87j1Pzf$k?%UM1F zo>a&B&+8f8SLIg->J*3oM>K2XvtfzlE8=m zA8lVA4)q%TT@yu;D1UOxBdzMuQMyRHP|qQppH@?-qwBGpr$Xgr}a zy$KpLnoNZYY2SW`G?d=s|Ek|`U9RRW6Hxf+J=pClzuQ}qCNRq=tt85QG=~S6SfT6{ zR3e^TW=Y2817=rZ7-NPe%(OkVkPDNA2{4nx?m=nh-k@`IL{&(3IW>>NqSYWafDxtZYk?&1_aOnZy2qY9Uj z8)?3Z6536W+PId0C+xKp9QfT7?TN?lWM)XafBc}v3#WMkg7ezFTHh2-s2TSuvgfjC zn%x~JC#_ndxDq|cVYksZ>;%wTBf&lRP54}meDpFc8FC(dmGB^TWtnxC&As_1Pv+wq zXL&!wQcXuenR2}~q~^Xq(n%?^p0cA_p<{$Eg$qFz`x+Xthxk1gq72Zc5`yB|KC^Mv z2yC%#DA=}>YYoHNowB=17nt(sR#R0qLS8g5$G7XEjAUIKDj&AV97$Ed5(XI0&e)rK zjoY)eRV6;Ud6qH%y zNcNq0=6Z$S2^`xwU?ix`@0{4*!}NVmf5H!OkjtetiaL!>xQ|VzLrt?XkP-(#4_GEnZ!Yw?6R2zmYWw#XQ@0XInn3WXL=@jVO=2F89!t zJ}T|h!jAey?UJLU!)q$WPhFp?o-cjJYoe>c-- zI^YN|;oQQB(dLI}qB_4kIZ3xf?=YFM(tg{fMWe$No-$ne#O1D$fzeuwTvsz6*^YNK z@;&pe>_o|{aqFiUep>Izk=SjX*e)|+mUb^!>%Gy0WlSQ5;G-S*V7Ko@13%Nj;zeNu z3wDx&LE@QxjdD~QmnVz_y|@;Cttap|fN=z5>0uG~PFe1s_bGKEU5$=Vmw3^yU^;BB6DQBW{W^?10A1OqeCiS z?|M#LvUz_d(=Dmk_62g7sUy8HmD4%Jd9-li^kqYj>AHvXh7~czv;3KN9DSrAut5KZ z8p?PyJhN0y18ov9F2YqK4Cm$54*zUao(XCcvRlk3W&E*?}_e$Hri0UP^sYge4=1)#4?#Zb& z?W35VBO+gNaFi#Nzr#L<8lr%)&`gdyrRBM4M=e(ETi%1P)HLUm+aFU_KX)v%ZavZ% zU3C+*`4qN!B=N{`)pQ(JPV+tc#~;c}xl8V`F{>{gDVP@w6}Mjxj?leAn7f{-uCUiy z;-Ts@AD&B84ttk(ifjWLH*6Yf`f4aZBxh%l`rM2#Y`pjesr_g$aCYI9s85(KDrK*r zQPF|<%w(L$Ls7K#uFnRu5dj~x0w3e-o)DZ{*Y07Y>Xw4C8!iKis)> zjc9TLfywDCvIs`LyXezv)P^4%?}(w^g%&47=hU-D33{p-Rb-AV0vA)&Be7D@v8M?XH{7bKwSskjzhZ9CtRK0?cWi zlU)PYYTOH!-w9_NJzLxAHeC^PUt)-)_sSW-!Y#NuZe*;~o7mLfo{CWKXxY)eBD6R9 z#+a3B^^);)pQ(!40+n`ea)3?;5p+<|smSdJ>|n5aePs>0uUl+6o$c^@mrX|L92T+? zpxBL=L4dmDcE{(b$&f(UFeI*UyvM{a6x5Iw~& zdw84{v=W)D*QDF`BX@|dP6ilM&+60sS0ICJK_|}F{pMF>Zr1^urHc7%v=1bgz#trL zW36?hz}gD*o>$pdg`dcXXQe>qia$nD5zzn}C-}=DPlm}ay^0+bOV>E>wX7p*+y7^B(KlVhJ80mL|%=_FSj6IxD26H4@j=CrE8a{kr^IA>-h8lM>LxgL8`CVZ7L`KuuE&jNSdlhn&R7*}t?QS0Q z^YJ>-&6Y$o=wLe=`>g$UQ22zyYd|*yiU(@%fBT*&05=jmM@HoB^1@SA#4PIMPOKo~ zYQL?jOp6-%yUsb9+UY+2ury- zN+#uOx$=2yO4w|Ot+Af7dRF;w0v`YHB{LAMyryTr6GQ>9Va}U}wPlGX;R{|V44Vgv z8KB+SQOrJ;aGVb|wIiiUAA3P8iz`fB*!ALFTA1Il>(Xn=jS{?HXYIpwcU@6Nxes~u zvL~}1K_$=w@9zEXF>@edac+>++SdjsHBsIV&NGWDd(X`=g-?$rE8&Bl=NV5+ThB#E zC7LU!dP9ORE^|p@SqAjI*zz2V;OevERw=x8^YWG{DNn`dV`u1Z2TnS;H2n&i&kMrjILo$g-UDNHqwp|NQU z=ePA)lME-A4riq+$`UeCW&P?EFCs|(sK=M73mP)AE5P_mBpA({y7i2z?^R4auxt$P z4(QGTxj4kzs3=q#C6nPaNJKpktpD96IGzI@i;JmQ7>KH$8`yYCnS&&t70xv<8#KV@ zTRxJ8a=$Sbz9&JH6q`@cwQommVTj>dZlr?Z|NrC^G1cd_pF3_L{~xFW5QZZ}OCrBB z*H*y15EIR;`!jU9!t`6uokZlD)a}OixzlHn-YIJPa{ylb2S+d+opswSYu zq?BGTT2=(Ne+9ya_t_hm!AsxQWm2`claZCW)-D^7nVHGB{7p3+e#~|Lg2vS&zg>+9 zI92?cpd__Fzg;MW3K>$2)sZ8s_&F5=>z{w0n7_N61lx(?SlCcQr~gl_}MjUEYtp{H8jv{Gz(h+aF=^EWB|i1@H) zf7Jr)dm?GzB5)PSx(-~vM*7?fX#m1qGzlp{9k6!(gpF(gQXdiXjg3{lZNjTnn$I?S@ep(lnEcKuCPh%&etOTfT+T^KKUD$tGE9XwibwcL~%G3ak z%eMGWsxVM;CC{d4N>5#r50^{$PZKuVNpd9At)S{NQs;Uc|5rbCNUWVPEGl*$5U1Cl zd-+DN;t!hc9D`QokJ=m%cd}z$yj3Z~>I0Ptbc`9J>SgQNbqt;9_~BUTs^arXIjL}L zF3K<~JlQts^siQeEe@#4sQbF1G=%J`UM(5&$QtX3Zpl%b!cB^5j<%q5%JmVWc`Tz$ zmYI6q3=b$k>S{xJ3W|wBa7PZ~=2JN&ZTTtaee8MKn8jDlDs^iJ0nPShA`uoAUKzs7 zqZ4&)f0Q6U2#G1fo*4{uZ7yY^p6tH?t_*>{Hv?{9C{#hPUS7Mr6JcPW)-gULE`vY+~=i5qLCBQ>gEs?+M(ZWk;7Xa_X_ARpd4`3IX{L$N#+Ja#JJ#XveE?aY0^WPhY5K%{y7&2%+s5JSae24 zRxFtlG*>Y%I~=S^C)o4mqiXHHGFB1f$12xZVtYz+X7%VtMUbFxH-zNGLI&_sMdIO5 ztl^ftSPv}_ z9uOKTUl%?O__$c&sHHJ~kBZk=?a@e+UekrCxAUY8cxImU%dNuLh_#iJF)IG9`h&aF zqZ@VX^gjN2fAUg+yHh8#b!$|r-_8-D%Y}mz>#4jud)aS2G#kG9XzIPkwaX_ek#6|xIRu<$V&<`?X4yv74L_|iU8jgulz{rsNx7xd2Ls)IIa=U~(OPqE1 zn?rZvTg}l4+~Qy~`e-QD)a-Y2%?9S!h&EXUc!U!~O#Rk@69Y1akCP%TNM+lHr%@bf zczj9}L3dW|uk8%^UyW6}G}c%*b6r9NQexYqi}P4*5>2IqygcZ>JFdK^6R{@ow{i;KLJA{y479*#Q%;$}C!%MMe^!c{S>^Q?j_a$usyTQSSd=Qx z_&Ns-|0xZfe-8T3PYVHH)dntaoY_Xs`mL<2R%Rg`4a<7-%gU2c2~j;Y4wQJ zSB&uDsP9{!&;80Q0X`T5ThG@`yEAvNnFI|lz0TaAY`kv7mvK{QsvDkS+*;fd-1DQ} z?Z=iQwg9~u*t33QA5kYV40C*0R}T2SCq=XcMd*yZ8&dbsa2b)b)PF+ru|pY(|0l*DS0x>Lo1aCw{t`-Blm=w{2~^6$5J0{2j3ol z@-I_LT)HDDCS#%>XgWvj5CJwEvleJe4Q0Czp|Z(g!76qhV#yOGs55`}^EXd@Vwmi? zAh=W2DyKX}(}6bcCJoPN{Vd3|?~!`WMpAUWx?R$dvl z@->H!Ucu>?Lw3jl&op*@iKbovb!NH#5)r9qeW8Ak(UR+~HmMw`8eKPFx}DmrjO@O? z*Zn}U%OXOhPA*KlbLWtWcfiV!dg3G6Qv zOe*y8+$HvZP=&hxQiKXMA!g`4iWe!941#cQUqH(Y0q&GgHU$63qFcN6L`=j_s!pE)$TvrCSbFHpS#U_7d}-T*|%)wgj$&k8pkL8N_T!p1=h?2Aswh# z+eh?}L#!w;BTv%o2QPEAD9ZpWIH?$HLEKIeT#7usvPJc4f=268_gSN<9+4e6`csp~ zBROO?EnRBN=~a`Z8iX#Y{%Yz$^B%NS=-o#LAX*@p4dRsuIqU0NN1|_=XJk`7hAK~m zN4_{tc1nP#8D38jSzIY%1KSp-gKrFNJkw3oedmX$p}N9~-M(Wm^^U>`TVR)`yOsD5 zzxBuQOx3{mSm>`Q2!|>lBKWdbq--Ogxi4&fmWL1U8E}XJykZDz7B1zeilw0sqQ1yQ zeB?@8kv`hZWbIOYGi>y*y}SgHHI83KoD0+1wx=8ni^9->VzMm-zMn<%+g0FKZiq)& zo*N<7Yf8-0m7MeSWrm0p>lxgQ97~MXa-!@Y58onI+%HjcbGM11kqm;~=>Fk~J4waU zXQ$??IwS?Hs5aj5cZB8a$W3_ZE?aV4XT^nkf|9B0tE}WZ-bUyHt^ zvmpTUFlv=$$PJmJUa(D&_UyS3PaNdYgg*DRD2t=(0d+%BJc?7Qf4d zA;{^@J`PZjrz)X38`u0G@3sw(d$Dfmov*5I%azfyxEU8vo)q1_Uwi!HEQ5jCc-&z( zJPa|VS-77doxgWL&@L>wN7(0G843DjKXm{Ps28;)MsBly)&@7+@o+eWf$u!~rQ?+Wv?0|DY_WCLRs&nu+R2|C z%O!x1unb#JS^#d&gK8H?GGY?(j2NL@e&i^B=dm%e2WoV(nhki;l8b%)GR zHnSp7=EOaw6Bn+}IWZIy1CHk#mRY-@pkq9?N218@OJCsGA2dAqlqF0-2QpYG(8VjDg3It(EjA@b) zHf|T%;v=~}{s-+OW6rJ&+p4=+)NV*4{Xpk0Qb}?d+(^Jj z=G-|;_Gg5^&>Z&tvOp65MK!#r5!3s)(l;uT#<8j4s1s|aZ%ivEz~>PsCJ%2Kkt2f; z5gMUZxn#J6Z3qsUwK|aM8nMNiQ)!MVUQW0(xRIlO17&Dx>y(X@xA^RK-f2vD4I%rB z4EXx8gUFD%g8$SLs251V*RSvTV>}=@hq1|t!+tv|-F<``e8pwTW7Q~qwEAkG=+l!@ zCqaZl@jpZ;Y`65lDWXo#QbTK9fOri&mytZ^m&;Wac8!$0GV2a3oi*Uz{i2uM7Pe_d zD!fZK3mC!Qo4WrUT>O-o$_L5<*L$%BTo0hMb7w!q#elyL8TgWPpX_unOq`|0qzn6; zH?N^f7pIHKQ23Z42XtlTzt3*$?81u&-G_`$Qb!|DsnXq0`b@>E^?^NXU?>%^VtnH- z0t?iJcq1h1b}{fZ17I8NxYqt4AwkCt>eGb<*Ph-<+$C__mNl3_7SUck%>Iy*#fGl7 z*RC2osG24`#1-jsB#kP1Tx4$}c3w>Jx2#n2b4^#*X*McZ_-Qxy|I+~!B;_iIKNJS3 zKI7UfKLO7d0ApP>y7gwaOP#>eQ8&%WjQ2d{WULpk(R=K)H3UO-eOW>UcOzivz0c6M z_$+7KWb4n|H-JN5ooW>7! z>c+n87bm@TMwwEpPO?VWJ+5Fj4S(Ug+8oyrGTctiV~laNh|~%*;OrI=>mGy0N5P|4{VlfCsyQsQXR3gTO`Ho>5TJV zi+*d%%fr`OrP*y4^~AiHj07Ry07(+K`%QU%{>&sLwUqPml(iES2i$#0eBi3Wa_XdLqm{^1LzI zMmQp0Rre80#2k@OuKWc31Uzn&%z4x4UornaDxn7!1nsuW&3y2O61c0zBa%Dg6fVKM zGPXKQ!RF!*VWarl-I^j{!Tp1am$gjGkjacQM&wTHw9`?PPUOy`n;MTwesNaB8VQYi z?19i)(Dng6)UTlr7Fj@hGr?yy^g(wzL7MYPOvY06047#fp?+eXF7P_-qL9r4FgVRj zsn2!7xBrht-*tK#P1i` zk6P?c5iDjm(ix9RFAvyc`Fzi79AT^%zL+uo=5n0m?Jccde%#3ObGzJD?6>Up3X8d3 zv?59wr=K#7Gak^N2XIsTjrE*s8tkAnHNN@?clR;+aRovqs_QTQ`=2Af22!c~5EdA)!o-Zc zrwIcsk%6FdGdA{mH|N?v#r?KJWregd-EwF|?BNjM+hVzu#OE*kFyn_XX$9DOlcEM+ zmw$%)^V5hB7%SM0yHUQD0-S+q@3kHfk0GevrpS4}o1>Y%fA6zcSc;C`b#>hv>Usir z%%Z1h1!?wBN03`STq#5KZKKvNsNC-o5X_*_X6q@kOGMX^2_6rw1X%iEiw!$Nv-8d@ zaa)P>gz3JgUpVYvsjfS;?j$5~$gNntybQ_CIHM@s#nH4nc^#msf7I#wr(619xa?E2 zzy^W$ub{P(t_=ZVu&E9q3Z^B_z&r>nL`HACO_`tUqFHSC#p;E?EVwaa^?;?$3&PnpN;(KHT&gxw8`TjcE+mtn3{d6|+$ZPZf#MqM_j5)VBB@ zBKq=jp3uk8N(wizwpbZ>_+dcw&JVx`2or)EfO->$9e(NR*DMvvFo);@h$XrIB>OTIavZ?MOxi?!>oMEhhPkc zZ7W+9;Y+#%WY|SkfFL%FVCf;&hu`^Y>&~=kah#Dt-S&U9JG<H$nX1E!y3&BFU6) zz@5`f;m=p)HFYj1#K5}o9isRO?ET=gd9g#kR6jyzz*H=1j_883108ITk~Ck5nf+u% zR+0eDd=refgv%i_OsID8!6|0mSK)J1K2)jPU-K7ndzO!DR8$QLijh1rFqOuIy@8F` zdF#=tW5et0%`e;A$DQp$N>0u6Gf&fu_m{RFBYM$)Z$tqx%*>H1V)uoz00}%32%5$q z>$H-oAg@m<>pZRQkc-MQ07+U30*qo5(F))YwVc2 z_{a+c(=4a;pZ>DtXNmhv25#}i0FX0U`hk{|dJ=s*nw#ceBZR5gj0p+Fdk^pInL4`p zyM*ytxnGd_V46@iZS&?vcmVJW;WT5K>z`h;8x`JpPRDPOLCdFqw_$Czzrrc~ILjX* zNftinb2{>%97M0gRTH)Cl#5P3DkQJtOumT?v%w zAMXdbpQ0HU7(9IXMP>E|o%)NcgX@qy4G2F34n5`f?vY-q3N0r6w%5p8H z*OR$=6(oUJPa}P*EmC_jMkw5L@VZ*lLSbP>4SQj4Hk}kRX{a+F$seUBBflRs{u&(_ z?PSYjKfN0klYMXp^ba?Cz~l9;xb z!I31tuLcw(-;@&ap=B4J7o*0u&GV?22oSTq8gH`(T`i-q!Y7pPww{pvarA!BnhSs$ zM)$~^vDv0M#)xV|jLYnol5h1vOj!?h2q-;FDX)I^X#?wT4Xh8^lCA}M!E-eeA0j4k z11Iqs*RQwtnpsB?Mk;dTV=gidlGL+{ga-~fveokt)^N$5J&crG3a`* z-0rhz?-y%VFlG-brhBsJXKje3aktq39RSj7C3fSXH01rTf|Rvz!9<1Blg|0bq~l>K zU5OnZz2&y{?6zgMtdpq(d0N@9z6H`vlp{(PyI|E`6$s229kUdY8xB_u6Uf<`uQ3Df zd(7nhVEBy5tD38NEh^4?oMAX`x+f>A!pvv(^XMLE---X+z=|cT;uU(Z$x2i~j57Tp za4W5!R?tF>W5=sCX(5jMBi&GmT#2xcLRT99py50rOieP4o4wn6RWrDxGIj zH>>@3rDa-&ne1>YUnD+>(NX7IlsG`=rzs&RX^0cVsCll>HTOR)o$a5RvX0ZrF)A4> z7Ax&y6!b$Ju%CG=BwYQ_OyTKqy?G}4;*SyXKU=F$p!%XQ5@>b6_srao?V#LX}j zrqOFZ*2I>-_UxuLn8cd-G)K)1k;cp&`>PgUYYx1tZ_wPsBTwQ*85G;AF)9+ewK|(+ zH&D12$EhBd-Kimm!w)nQezJmRKyfhMS3Q9QAR}O@$F6?2-kQjRqgD%!QFzSRGgAhM z^0`9hTJHy;Z15NDyJHzo(XDdpF{a>^Xn`|x4|eW&eOxNBY^3uRvVJ-51TWj$DFdC6 zN4KQBHXJTA-k%+;w`MWOG13!*_jG}-{fR{_vc~*I#oS1ldL?U<_A1PAmdlfHPqkPn z!u>fD4o*(G{)odr9WL1^P&-@3?Xd!=H)CL8?aVDTiMr-@>EwQ_(bl?qf!8mS4g2;y z4Z!HVz*t~h=k@)UTN(+2gHA0n26^f+H+4(%w|s=*;ilfJdUk{PXJ>>a@7_qz8m(s( zvkko=I~EF&Zra>-qMRI-%WBS0V$}=I$`h9$&-rQ7PLP3O9tpKeXuzF%17o|^CoD|# zdr&X3s|1(aDK_j#(4DtTy}8^^&^nwNJr>DITUP4I%55{PvYm?!tgNdFMF^Z!&>5jC zayuIqT@x?Y$@9?DyfTDd3sT{g@+FlVlZp;(8ffMlwYk`^*i!%V?WTJGFqSa9{R*%x z8W?$J5s&ZZcH+W`%z=vVhbGAfq~8zLzE3(aJ=B&J5iVf(Eqd{rsz7_7VAZMBM`AmV zs8$vfsKzAiHs4_yxD4Vs9$UvR_u^? z`1onII*tXY96Mw6NGY+_v6XqOhFMeOsAry2gn-A~=0t4iz3HC<(}h<+O#H<|QrSjm z!T#pWoX77&j%TIN@-nBo2%z6CA4HU3I~ilUQUt9!uVShkFrSUgf!Zlw8m* z@{{}{#^75lTVMEW2L$$(tu8APN{tciY3k91yz_lo5iBg?7qBYzFB#ZJ8{KG6ZA(4# z)&5D>Oo$D7zBMN!Nh*n)ad)gG2#tVMccHjh6>Izln?!yB&i_1n7wq-kMDDneXSq4z z7F$+gF7=<8D&&;5 zx0ov;S1aCa={kdi%d+QAk%d3n6+gZegR8|?*>rXh{s>V(pANQpK*&t@s)4s9_{r{l z3na_-J^RxtPkaKcD}c3qQ8r z5hyraGg`l?i0CRWkd2g)=EV#pdVAXK;01?GQdPn_im7BZLpas%MS9K+R-iE&@vjPk z*viam9*_>1l%&4pK4$ABo9~GC=<7&5TSQAY4dOQy1Cl4z)^YA>L!TD!PJ@PacUO{w z3H3QfIZ<>1MyH<83IVd|M|}TRWK)D7IYT_Ck>*6veF)TW^le2fT=f;xh1;B6LAqe# zW%-)et6<`^fl$|uX#45UTydXhycSaBWJwT@Em8GbH{NVihs>%#2d)>{Jap~)mmpF zz8?_&-lXMO0o1(A$&Tv&BdnQb2Gi68c4 zPA!_)D`1G7~Ci5mjDY0>uDpaLSs{KlnM?~1NdIdSvIv)jw+*RR)R zeHqe)Rk}s==k!^-`x%%y1=;qXEGx`%kH1UI#Q{xRf@Z+CFW1y`No`SAJmKf=_d~Se zb2~w$g}3GEWV=GLVz5B=hy3B11cf6E@m%oAmzg?BX06fmYc~<|y;;_+*{xk-hzZ7E z?G|upXAxW*Z*Q#6a$EdnRAQyxvjiHUJfO+=cOQd)65^n}kKhsXp)IOsfif>Xp4$)p zCFmBKoN6&P_WGr2f9McO@UBMvBqkHQy zdY}0{ieYJF4${QB83Mj^y!{w*eWouNI3hho#iw~)HmqI=`Z-31rl`o{P7^KNIB&uo zv7j;~{s~c#H++tm>~0Kg(2(2B0BJtXtl4$d@QnLoU#jEDkx9LLc<*3X>8R!9o<6tAqQ!vqfr^8}2pGl|hjy-JrSRBZ*%P<#@e!!J z2sf6E5>r)=7GDJt3~#Wp{HsiR-%S9ZwN3QTOn>|5=X^)cwK;zj*E$cO2BAZ<)u5}T z^f1-6ir3LjI%LRH#ULhpNM8~AebZ&eKVJK@_5i3q?}`6#Qlslduxz1S?nncF1KxUK z`~&6jil7F5!Dg=&=N1=fmzg$6>)5bWeCB**vbbIU#)B4y$zALAXoBJ%ul&b5m$xs^ z&-cyKHrj?5Y_$#3QZR_PZjBVs=&7ZKzS<0X+v+;HbCqMWpS1tZUQ21+r`mtns{;^o z;vGwMB_+UNg931@fT4XbxD-CSW9dvr0>0|^WC4i@DkKp*gSR(yl)avnMz(E`pS(BF zl@`Qg9W-0qz|Sh<(Y4-JOitbxzju%6YFn)&E2a`r_w;gl3FG9;Hp1Odd;A&2OEJt# zR{mAj4d2<{JupKRtng^`C~s~6Z{l`!M3_ujyWJCWhksj%dSI`Fh7P1D9q=0jA7cXk z=1Pcl#wD)9`&09T`Ba7T8;=isVlgnw(F&He9Y{NT1RavDrZwQQYm6)Kup6p0wAYA5 z<<$^Wj7vA<=F0(+M5pL*;oLgac?}CwW>Z1NvL;GG!+E;vvzYzm!|2jcRbd3Rfv%&T z=5w!V`ZHu(kG_55{fePz-me1u8}~e;0tC!PueJVj-z*>yuoBoy9zdz>_dV+c*QMct zLVmeBeh91ptoZD*{v^zsaJRPB4*-(>5_tDcVPj$aOXmb>r}|@*z?Ke|^yHbDX~^sp z8^wDS^0WBKhlGS!UJj62_|iHS&n%5}X=9HVey|P$FQUk-Mu096eH0Q%yC=a5BdKAh zX~+z;$@TQE>oqQhExXnS-8TK#S^E-OCE-dfx&onpcF-EgzY5yTXfn_o^aq4oKSl^Z z_akVSlxt5OlLSG$P-D1yTJDxFe{|F`r|pG9xYoV-J<+xgQbC}<{oW(0u95Q5dqU*L zY{$oi!7OkO-%^_1_~=Ah^Mv#rM+N1XqMh5fe>~6yAW!#cK*6IUILwy=GzO=xCg20? zl9Wl#5iht<*Lxi~3+|-_t&oez@?p!V;Up=3SW;%`=@pTdwyz5QUh!O&_df`lhXvh|A-B<(ttW8#%e>yY+0k^?16qc!p~l9S-$6ZM8o90bV$O zZe+P9UHlk9=n1MMA`VgincSO6tMdMaN;s9dLn2buvR-BiYuVQE1=`4j{NytnL|gW_hh%4B(fJb%jeaj!{Grt zTkH52F0-L;-hA_%|7u>>Rb-I&_mhv^yHZ>JF`Ah`uwOg;eyDccNJUtPM*W8+L)lD; z;M_9ZkP9LJh&ktWE6EJqKlA*ziokwU)e`UDyp}bW$*t7pGss<`9N4O75(94$yqrGi z*sW(6Y+60mW9+qye+oNqIDMHNX!Dd8ne761-D-xzm`AY0J=)#Rt;PQw|JPQPWCLL@x@-7 z_lNThRwomcl!9BF0#q@`_IgStuX&t17RKn-D)U-^1AZCgk?%5G3V_txnX-?_$Xi}{ zXv)5j^Nwc9&CI)0`r+I zF|6?%@3VHc!RD5BgWG3J{D-8kCd33xFsvMgjF8YeDW``1t15^JfW7lTPMOu}6d)g2JhvV7vUNYN1HNkW8kOvV?}NSBvTSkH zaDirz;f_0;Oegn?M6F2~HxR1?R@^-=s_H3YLypTB1l?al6Ct-TfND6jQ&*6$Klmh5 zS#e>%Q{I8UY=&Y2oCM=%@c9i#H_92#EP4Mt-pT3EJgz%E`0%kacj59R=+Y(O@M7z@>#wx@nGF3L`)2wgZSm!qS2j6+&F~p9Wih^1hFO6#xT^ z072Ndi~9qcd4bD&j54;N@5_JUkjdE~WjAg9p zUzYzIQH~{56+xLJ8KAQi$=;a%sd3*6T~X&GOaNhAZJZB{max}<{_SIT#`Tjhhj*m5 zT^U-h8^om#NFbY4+K>A!kf`tpwKj-j^)nX^r|kC!`E!Pj#C{tSM|{WFM?jAo7}wlU zvG0OCV&`}FF#0cD^&3KVs(UzmIx*nTOcGJ5KG)_KAz+xq5?~`1cP=}BITiF^MQgYwOFt`Z?}CR8d+|^rU)lwd7u+~xP?7XaOW1u6%rKcj(#~4nMcLv#5iZ{pmx7cU%!;N0Y>vxlEU zob^=fbS2ME=48{{xDXcggLQlcN^}vrZzI9=*=(}Yesf7rC~}aCB~=S@dj*63e>XP; zF)CQwlZklj>(X~m$hL;hzQy8+uT zU77CTy9W0QTjtx&;;X1+w>3f7u(H#{9)T+y=$hj2d&-NaaC^jxHBotPYIF|%<2Df8 z!tsA~!2D1J6+MKLjQ7a}gu8WQjhr|7hSbz~gx%!Ly*%5(*qswlG;y;4p!<9f# zKU4tL64NY_Tt+|GU|(Q6k{BjgWW8?IC%@9s*7izrkv%GD?b}yip%la{(NZUExX^J} zZX-c9N>U_COa5S)V^LpuGm~46DMtVK^W6boAU#h4=_-c0$da87zuO(bnkaigZNRO+ zSp(EOW{;1*p*8c|C6^s7$8AW9f!JmZ3V%$`#jEPn4>#3(8NiN;s1*OO$p;Q`4ZEF&!WF~;k29!r_& zOO|fC6%#AdkIAcv*#S52wap1byQevx4xH*w!U?{12q>J z%t>?7>s~Ln`dgoB_ljIuN3`@dnHq*qsc3=ooXkw|H$`KI+b5e+uU^_bz! z82sFqMoGZbRdNG8{iv60^&=i5LqRhR;qvyj%yyCu1c%SeVfG&2oY!&ku{sEAaD}x; zsLsa5rl*YN3t*e{$-VssVQ%$M;9=c&~GLd(GJN>yyG$IN1b_d3la zdg60my4q~pySn&8{c~H+pvw^UP*1CqPdJa$D=`DnqoI1{d?R+5_tBb`&VDM_*bh1V zb&nHV2T1^;bA&$V&5x-AwsJ_~aisbxOxm?4fR-=&`6&UDo1NB8nz2&O52Xw0s+hL~ zaCeV7H@6JRR(Uo)MiVDjVS3T0+GB4yzIshi{VfPZjkg|XB;Y?;Fc#i$qXLQhPm-2$^WyH&q3<+1pLey3*flT?=igHjVswITO;m>$YRlH1!oGsJ-eJxokz*;jmQ(5<*{*&HQfoT@7Abbhix zNibRyOA?JkyRLU=Z|Y^ao6U(RJUvq)vaYMdAAK;lVw%^kH~$@DmP#0}(Z*PWQVhlOs(&$4aMc6c!MP12!EPd(#Q z=WF`T-MUHNXqk$4V`n}+KDMV5B^$I8U)?&C`1k`2uTJg71$?S%l5kt>LWioygO$7R z3cw>~2FvYqeNJ6o-B}rVC;au+Tz9^?Le&}p&l~k>sQr-r@9WiXs1EuK}2 z1U#cSGGjFdb^W?gzC$9mFGEflVkMDB?pYSYw$M!ZP~_5@r1G~G7acQ>ZWGJw_4!gQ z(n#hilYc^|p_8AyNnh)PMO-lK$jtTLp_!Dr(R2WO4+VikZjlD)HeFP`^3pe&t@v^2cx4Mkm>}t!`C$cM{>l+%fbU$DHSTD6qPtmcK!n0HB z=cOuQ5xwcT`Q_86J-5N6YXKQ|o`>wIuI;Yu^cT72*%KTc9eIt>O^#X(%hZz-`p@xTN#^likZ?h<^lYKaIIpuMl#Lf8I zW_bo*OMJ$R2SaV_vuuj2=6D8!RZP8h-K#dXDIN@d%}rzS+3JRoZfa4kJ-9_$!LufR zcr{siW~cV({mz!ML6oIx#Ni5T8`64LqG#Ja$3SqVuIxSzM3~?5=%ux50g-_0qm7X6 za2>iqj%4PtA~w%rBi@bcd|}8b(Hb`O+jc#a-a&7$C;!p4;?7VKdjyUH?U5MPX54 zcFDIZwd8&;Ive@coj$GOkM^t=27ZthI`7?oihF5xp4W=B5+9boVLc3*Gl?H$zN?sk zKY(f$C@3QzgNn>BLreNnBWB5I?F0%BHRrn?=(dWWrk)(?o$?5-WNR8nwH+fCV!eg} zmRi(m`_e!%xH*`1G~=uv0(x)ou`d_tL+Z)7zBk!h$K$dN+Kya*q(dtsFE_ooLCYJa z`&Cyxc+0)`Fq%^>NDz7cjHK4935kqmrl#E9nBZbXk%d=02h;s@* z!rilo;6FJYHxuwY=(Xdeo}r^%MN3qEIo4wfMv(~{x)zrTTvndfCVoi`eq1H?lB9-n zrkQuDsbDr^LQr#Zow*u^3GtB4a0#k(_aMcLy+WB0B6(5!zGT?e=}Ne`P2Or>hIh5uUe0!~iITu22#2r*(%r-oAB(ZmHFefK zcZu0Qf&P8i3AXrKWHSX+#D>enB~Dm+UitVi&nH3V7HfvdyLt9D{_?XjL>4m+B$1u5 z9iZR@E|YQiAQy3!b3>Kt^Jma%cDl`O2UR82d z#znG~H`2nV`K4Cw0@)oFDP#w8yL+&)IPFusBzf@hWRGhjTVisVHw$iWhDWC<_}AgQ z`!lMH(nWVtM02#F)&fTB9#z#xpkip}O7+~u4Ek=lvUcr~(LVYzWnkUA^^vx#zV}F2 zXI@MGdLUm$5c!W^kf7zqQbdSHMXaoxGZF-s^K*`LvyG&HCK9+u3=Cg-3yqBnJ*5nj z;DlUyX}wI^qkM^XwFbnlIf0j1v@|-*b~MAXEe=@?1S;40k~FihWLC%X$>Tfliyp+^%kW(czP+dpl`1YMT=2>4HaK>;**!7nTomaB*#^+qSbbh&_2|z4j2-U?S5eUy>@n zjM(kC!@Q|*T|+FYuqDDLPl@b-n50aU!^cL0n%x~4W7)N@#!~yjw%0;VT(`LyQMnch zcV4}FbSQR>XC6LS{#*d_ZAqt;@9v}1Ly5+kSLOg`dUs#;KqLLXWshcZ?uNQn1T1~Z z9ro?c^V})V41JqB-;Ba|E#zLUNVGXO-+83_X})GBtr28R zeN%$7OTDkk7^9;dTJ7WWPKsh-E_l4DU3$LK0tZXHLK<{NjJG!KicfT(xiJc96UJw( zKlUY}4CY%Om$Uw0mhQ^3*2pod8Iox2cb=ZCn(EZ+3Lb4@XMFzo ztiucFP=aficCi}fPIZIxeLtFj_1S*0gZ9)Pul&fMaGVISYuWs|4=5do_vQ?5gS+0| zQ_Ke?h&6j=ln~gKenV+x4QMwSD~(;ZD=JzJSetbo_FkVV?$n^F93?9kF@oS$R*>o* zc>c)EsMz+32+1_}o|!%r5JZw}P8}#45;A~i(pyn$|xhqD)O#z#ri z61E6gd8DG9>NUHl<8t(!pJoCf=wY}-By_!`vkc{elPXp9nQfNP&Ae|pFw0)?_0amT zpi|{S0jO?hc7`>)L>cGBp>%VzKWNXnt(#}`oO^Q!wtS;gZf{%1Nsgc#@3mb3DrB5a zWl7#9tV#^M>Pu_{W$&c)H}hnw9k7op`ARS&v5L2-f^_?jx;9Uka43!(i=_FRU#!gp zr?0{Bq4l4z;hf^FjfJl&5ALC#T8aj}m5jZ2jK}uX8JTHH)m&tArerc$eu}D$$R-W)J#Zu-tN49H03Em!sZ~_xqw?aNARFWp*&< z{g#WukyhouAR_cFAjaw{4;%~ryY%pc6ySK<43#>Rfjo6&P_y5uzJDzqS^ zl6@`vGNiqPHrbc#>qwTd)2i(I*k+KdgAv9sWBHy>h2Hn)_jvsN>G4YUZRYvBuIs$c z^Ei*=I2+__y9?|m1>RKKF&saBe5BSOUn|AUUR&kL2NXNF_;4)JRM^CpYn|DYo!AZ< z4EGHFql*CwbZam0KbmvUGGpA%8NJc?^FVy!7&0yd{`nv6y?VWD&gyCYeQ^mJ_o=tn zN{MGJa-GG46v7$iuH6=2+X}lZ;Ju#``tKhnx(BLoNxQVG28q}XU9BjoK$|I55c{_v zZ_)qzu6cE9gUsmmst2V_ZWo+c373YV+$Y3_FAaV7NDW_W?q2{u0f$xr3Fh@mH6EC$ z;%C~+eWP<-ruxoxzqaH_mJJ@!fD33`W5>2`tz=Gi|+eaKR%gXZqAVnChN+QIU-Vga#aiK4ft zsh@#zhoWVtK{W)}U(^WOj?~=+UEWE%LGG^eOcMD&5E)L^GEYVrm%jAPzb0W?XsG%1 z7^=8-o#{079O@^_x6jV6{q{|?+xZZ#CG*m|xd{8+w=#kSw$tE_aN*zC5^lfSjVy8{ zFKs(d9md(cyntWyUa*B=x*p^eMZ|7_c)genXDk0xkP$rE9s6$MSD)vHXEAV0xoGwn zt@&Yg)iLY3E{Fcs;O*{yL466~4cAT^zk6nrvE3$N`xUKHW3H}$jsf^5ieGx+vaw8k zh?5>U`(^ZY@D5o8<{?(Tp$T|1&frm@afj#e&QZNV?Rls7hIop>eY0?dv4-n^_xmnn z_(W65TQbnN}jg=wpB8@(ZYp#N%Tn8=(o6XpT!l};ST3QE$t`S`x* z_gbHsL>cUx&K(eFbRSuEu~i|B_BOcDr9`_$@M)v%N>FFPaO9Cf^y$@?N3&Zm*;wbj zt?UqM=}Vt*c`R*7k&^ICJMNN+{m|Mq_YOdM#{9DbK#pkLUK=iBxJ1Pr&YyAj`f2Ku z56o}tTNI_r6EwofYFGuPW&SuDx0K}6Zgh+26_%|oerFxGi!`DHZwFop$*C|K0;m9< zsHpMzs)l7(4h_3Oi5o_*e{v`5^A695r{M`<&hC>D*+Z#+#vvgr(*OJ`;Wcc=45-3i zDurNeDhd}JuEr6>4~ld2>BHZ74N-Pky-r#C{n4$9pN1ktT+;=F5B{~Z=U33z@utB+WQbdeR)O{hyYL_9st0=4qvww7bjMgdb$jSBJGH|-t$HEI z+yQ;2pZA`6!o}+VJ$5Y)$6f*47HwSeCOrJ0sB`eIr~8G}&kt6=)&6=V#0Bp;%zO0c z(N`%oJ;*^uOxw01_H5e_JImZg(8*JprDz=XJV}%nzi75O{seSX8Am?$bFD@kT?U_| zTfOzTz%Ig=!F_E&Ii<(SN)*3Fy5BcHT(^|DFv_hGBdtF(T&D^6r-b`xZh-Uh;W{Z8hzvBSlf4zw9(N3}y&i z4LU~0oGx{iU&od@i)%kN(g@Er*V0zE9Y%M4^nO>JE~q3d#lYrYmXe%oGn=aJW!WWS zZax@g_j#W&IFPh8_oc+P(=i^pfc+9K00#uxh7MXMg!eRiz1E<}zS zK=g?fp{xpwoUZf>6r4g&rqMpD_4{UNFl1kpAu_I`egW&(SFyrZ?R& zR<^4^V8u^0o$Ex}oun(z0)pL@J|0cKNlMo)H%qo{%}m?AkMDuiEz8HJt1KOH9~8ak z#(%iSNllh&GD*+Ja)+9=F9#R6V32&t8O38 zy|;}ySjJ5&B}qB-Ej=kh#6I1*K}NiAvsWtSBIBX?^9?DFcQi4I<44|&sTq$2O?2l& z_O0Salp)yS5g_M~uv;eJx@x%H0?3ClA!_*RFL`!vqCJL4t~*_iuP>>{mg4a0cIhQG z%{&ufQb4myXx53NjdeGUHRh8F8&^5pl?pVmR*`^^ANf(Ly;WMv)9Fg!OP_wUM0``6B z4An(~wI_3QT#_2>T#jE5GLLdw%7e9q4jg7n-I#TBsA=yAx>Zc2-AkpVfnrGYsd1S|LsXUyeyZb98$il&SUZ%9kX1B`BvghY5 zIFHYafWwhhN}#iQh8=wb2DQ1=`Czk6vrS~Y`8=z3_Hs5RSgJAl%->+6N8-#3e5)AK z^IQ;mO%T0+TN0cGQj$Au&+%QO{*zouR_S6^&%~_C+*p-Nm6GyJjO_&I{T+5P`=hg} z9$s9%57_=>x$c)`SJ*!dw9I5IzIujL3id<10%iASNVHbgppQ=Y z@J!cE{(>Vr{wXzWx$!9Lf+6+c-i-Eit{IfGKog@)a>`zPlfZcVwMwj{HJ}Y#(1B=0n6{i`r6u7bLav>71Z7_$gkD7NXMX+ zc<4$ENg%tps-sF&>htH%Uj(xUZhp(7ex5u>%&s>s<`J9wvcfjEIMNgWfVpfu zy--Ew+bjb`&V$e_@kgc%2EKTB>k#C2zMH`Rc!?}VW*KYRE>!XJ4&3>;gf>kvnr-u( z0M#3pxKW)0vM0D>ebW!+`nEZT*DV#V=q8Qr7HFb&B|ew_m_gcli7y?Up5d4AbdPpN zwy&8;I~M=oQ`VcrNG-!?mq*p%Sk+V{t$SPX6<+$`Mrv+;S85}ST&%se4Gi<~%Q zq9(nN=s@U^`1RFiZZyT~=kKa~Z};UDhgV@?R;&k&%6&Y)MjiKX`7qU%q4R^bZzx?o zHweOeHxe02Y|K_em@ITH$d6zFm7-NKj4my9r6+_R;2KOPUR@XV-q2=Ph3~lK- zfw%P#<@|RcBESE_{~;Uq96bf1j1zKV#-GnbbP0YR|6X>LokxF^yDa6=9#R_mrDs(Z zj$izJ+2wqZE1^7>zXlhJLT_&xRVQlKx~=4dXFMwy8N7XZY&BIfI{E&5395fmt(sn{ zFo=cYm+P?R?@u!ggrwgCSwG>Mv%sk!b6d%veyXUFFx!mK{Z#2pMPy!(9{%7w2rI zsPKBrHr}MNSKhs1=jaiYHlgZ;`>%fT-I|CO?YB?4TOLnDrL&HMTLaPRIHOg|bnzMg?EFBmVU?WJ?Lb!HZ<6hu z8Ji~4u3io6&hmCAILBYd&gQsH7|3|6EOq5szs|0CbwYV;>7cMn*Juj6cn=E%=5~cq!duIJ)DM1joQn~r#XvamN zCCXfggpCB5&mb=~#_zXczFlYYH{7!L=}i`~_%alcVXk7UBksnh9?M5N^W7$5M!GPL zu@o{PMbYy-Nw`5;lUTM=p3fjoB$0dl2+hiZzfrbbQp6}H@oY?DDh&3GNBjd0=|)Se ztLD}D`W)lDlVn?smK<0U7Rwy8cYht^cb5+@mT$?^DQP{gO-hnnIAQ1ZpIVcbO4F7s zEP7zlKDoNM%?mRbo}Rp?fXaq$I|d15{!-JY=VmZmJ|O0p6D&cI)~3whMuGEBqa_%ialeWmvWv zF=fDD-59KUv6^Yxvu6Y$(vA+7hXo)h>}^6)iJ&p=iyF+@%^EnX3_nOGlZRNuu!(7! z_Tf#diw@+zAeMOpDN*9or16X`x{}r=qtGVf!JYD<#p0l6hC7nU|R-@MYZ;JhPf?TDPS8 z&YL6`#3k)7`0;$hxE>G^zsuT~MXJ~S4X$(IS?n3_eu{pfr2do^lrpL28= zF;t5)8k^7X~Ppv)rkDPrf6QMb>gY)>X3T_?Idd)-?d@TDa_ z{Arh*w$5B~1Uf>>)tJnWYBGZ@o>rCrktkJiN1D1yJ#!^Zyt6bkHBn2ke622tFHX4@ z`*fbcwUm(6t4=j6_T7KYCKOFB`v%QfgQW=!pT@86a)-g1)ZpqP#sB={fFHXh`pwP_ z%%W$N>z6$&HleE+DJ8ni#rYTXI4EkzU03VY3$O0dI|q;V;JBFQ?nv;zNS$Y%92ZFW zRKJt$8(!hyh=qkkx_Q9cwnK$O5+vaxSw3je@8{*|c8WMbb{&{p_+fc0R_M060V@Wr9m z-m4(Qf-#qiV{4rM9I;_R`S@mbUp*PGxmi&dHb%A4WCv|EbU*U>71xk9C~_JYXb+80 zq;8k^I~c3{#@J>oNxBxevj0y$zU?g6RKA-HzW*+EF`~wpW=PLc>SMOGroqEcCO$j} zZmm1xpzFL(_*-UY8-y^1kPS^w2Eo zo!%zfjN366-8P#+91@{1_KQ6Q%vA($?u)wHnH5>$jeSsJE%~eG`s@)G|6|YU#1{q9 zJi@Pc_&j4>j)>DEU=?Q;@r%;KD-o^4hHA~pDQ*0nQ{obuZIt%q%NHMIVoM38R=sZMZ?=BP6sG7a-;KX$ue{#Rd`d_}V$bprHDr%#fI_u!1;)kxAI{$9N^Bbq)6}RanvU@ z+20TF;bL_*U77mAWee?wn6 zu+QjUqQPYuVvs{AdzWlk+t@iAHL&f8M0@8EVw87Q_xq18Zu|st_ohZs& zzU+eW{jH46Z+IoLbFEubUvjBMkJ&;UlCPZtqN=k1`v^8{Sx;@`Ter<09>K?}2}C|_ zyEdFwN+K}RVPZ#^^5seg+9!8*F@GdpE8b#V#5JO1EA6bUOD~gUF_vCjz?96{Sht(2 zF)+gKOE@5gKyP_KznJ7A(7LmCC!YA`&<){RlK$Hs@HH-tRE#g2a&!8Lp=vsi6bi=(iP+f#HHAk14rkghNvKJF5DsD36gHDjW<3| zPeAnLFmZr)77Xv*%kCo&LRRBHWjSXjU{cyq!tCTZSVk;TYD?F3_Y8RhGlf3x3OkJ| z_Qg**%NwH>+K#oY*hOBvWo$)Q?s4z&&9rrSsG2(&p0bh_E&JX#TD*|)Vw|^p_@M+M zDNlz-Q9@~ZsMZa}Ye0LO35oMCbR8Bu<3GvG@^y52=Y)MPHbGYnNLih3R40*4)5n~l zpZn{>{_KPYhJEf67#h6dm4YBklWduO!Kc4JbL>i&Cub-IxKvGGs21}R?!9SN=kIX} zyBV%ZI%LFs3f(4qJbQcyAm8_AlFPKHiYy zuIPw(hZ0pRkFgzL`P!CZqIJR+s~lgM(wXC`r;Cj(3B01(iga^Z!DZqP$jWPPTb|s6 zRSt#jV|)DCfQAQ}*I&;WY$BdNL9jhhLtAe2QV1T;eYw=LIK|zOeS{2Ztxpdbq-e&I z<;f(hNy`-T_=7sBh1)`9i6Bfm`}1XYnlX#ph-C2&7Z~p(hyWr#&R>JQc>#uO0sIAM z>|gln5`#78m)s>SYa`*Ym=ItFZ2-hHaTGZ2Wyo z=cQ(oUXd_6J(AtF=ff0U+urKlw>6;xni#ZkaB-GRTY9=)PQ33DNjE7mao+bWCgxXvBGE$hL{F zO2|@tLa^J6GsV*P?*)MV$VD1loV2RTpRv++hiQGa((}E=Em?>=Cv+YS56OS5f@@ro ztkvUM#Y&m35khU2{{8E9ah9`XFR|`)ZFU(Yok(`ap)d&DvI-H6J%1Yny7l{jSg;w1 zT!9`FGAvNC#Nl5&Q=ELsa==hIsa3TtU-$8wwDH%k)O4f_mCwTq0}lLJdjte>Lf7#{ zB^o6&J{oV(wNGN*6IH;GI((lfv8L?3zOdV$_!_4Ra_jB-~hBngwLC+3?XN2^%z~2PS@+O8`jbPZ`9+X^VR4&eU#|H zD*4qE9dLz*MFj@thJV#7x|3Ag;})4cv%s*QC#~x@_g0j&J9@H)c@|9>I=oNFq~~Qk z7{%O3(u5C0Ou>~{f<{%6qukH%r^$%PabUd*Wv&d{pjPIPw#z z9~5$(Hd@)fC>5Z4oVfC43ODt3+DHU-ybFhWlycbN#X>RE|0?0q`dfD% znOa&5(KXc$*e`H|9~w-j4J6^UHWf1O0)oJS!E0%Mk_{p<~_Xr}E;DpUGqAI2G0gt2oK`F->6Z;TXGY zQA-O`Sm>QpTD|N&frPZ41VeEFsxizlmrDG9EXUV&f!;+z& zwK#}+1}+j0MB-^kP|SyIeglEgSwKGbmt+aQ1X>dNiYL_{?JI4U`na?;88a z6~kMadHAkqTeL-b=E|7YSKe&PmO zjI6NWo{oR8vgaT(VduBRG)*C_?v5xYV3HJ234w52d= z$5Gqj6^jSvx=}MGNCBvm8OFKO?Y^?o7CFTfaC1UjoT}gCtQdq}ZJMvdVGbATa{j`SB8y2Xu#_@m5wDc7t}Mg%)d}oK!z2-2+tERb zQ-2C}1PgK6zJp!X=tr;$_WkqZg6dP7Y@Ag>C3X@!2q!~c(i^=FL6>A17b)GdDDj^> z=%rl2r>&Nnvt{&>3QSy7$kPb6PP5@ruc*eepAVB4Unn0sBxds8mC4hGI*Io43@qY)9|(jIk=jcoTlEwJ|-+qsd3 zM8A;MzUY)Y255VOB>Q%EEs$R{~Z)`Ngvuy>EJB#8g;BtopW{!^>lLym$D#Md{mbgA~^6G99Fvt)6Vb zWRrdnAp~|+Ye0CQg%EuB$szIvKINeS=mjPM-)J$>20fJ)CU$4LxiOQJU=gW?Afx+D zm-dm;4G7X982i_UM^rVWK;+I{Mij`>bg$!V41r#2ckqGrv046c^ifviY>6SyiVpxS z1^cKjQ5RJ|=4jfb(im$h<0O@qn+M}kVw&qPJvUP>RCJ#-Ex3v+b|c}$XYMm;LDQ>( z`ZV#dm?J(@EX!aad3L<<-B_4ql?%Rz&GpyxX(i!Y1@Tug+lTJSyFku!kxUWxUfXUQ z>B!13SeNePB^0ve4WWu4-kMvw)ygI%k7dv7OF2*>?Hp`0nX%FmU~{|Ko7hNGmM$u( z@U-j8%bHRJY&LfwGN}M!7KkpWKtVfvX_xfP+8I9aAz|C|Yrs;+FSK2+Nu-$l2Z|#W z9sTY3;o%Owz{6r%1_lvrewaxd>3c%3q}W>)$ruTjxnZ_IEcL;5>ktPW z){uHkWJp(X0I7T@k7l&%Tds`gtp2liBpyHI4BaRaAz_g|dX1Qw`zG4HzV5bcBkC_B ztz8eqq6k9t?CEc!(Cse8GRVN|V#OP59PZV4GVG5!RhieF651V(E3ya$2?$gd`nk@_ zOZ*iX-WUgi0+%#Wf}um1_6nQGckFX{Y>nC`Fi({?fsh}wF^tYXb+^;8#yXwYyGzqs zJ`ZYZsii+fw;cqaw_2ybS3Moya*?s=3V?v3^*+Wa?dcY_S0Vr9qSYO1C5Z3ZoHID`J{MwmGV;W+x9+YXc}IpIC3fPguebN#Sx!ZN^n6g_}&At}Ay*$rQh4BH~$lB8Izh?0<6 zl*nbU7<9gQ7E7`o>MgU?O-fFt*a#CpixR)eG?BiT1&;zNAm7(0&q_T@FaOHJ?fa%h zftP_hqY2hIw4nbw%y9&>!D#YO%k)67+}I=4XrF=B zbYnweIXMP0{Gsn1o44+0%nTO}9xJ)rlI%7AQt6ljW)j+Jr12L=&-gpw3B^IIqAnfp zUsLediVE2nDJ<4vEYI4eG47)}`4^)LyWdZG*U9FuFGUmJOUhST!`VrBIJ)7jQYnfw zkuW1IcWq*as=OUGAF3PzvX8_yxUSd_M6ADQwp~{3iBH{#czf-!U%#uWG@wzZ2#C%! ziW=oy-((Ao5a94i#EZGr9tdy9(FL(nSAi|}Ok0N1>BwDVME4A0+FL>TvU4AphsvdI z+`AZjXt1P>mde#9Hz!$QB4ci0VbJUA@MW7Zv?YTwS)vg%TotK81+K1a>{aycDPVXP zPsMxj#vN@YsTl%+e&`fPO}vb(*82k<=liPXCi1OYxH8%`S$`ZJr^j_?$I34KVm8GL zbqr#-)PT|*a$n|6TdaidLikaIH*en#U0QJ%Zyi5BiBG7ytn58F7@Bnod*rdbAhSb5 zl&JF4ss{w19N2Uf=45A!bE#^<-oTx;w?Tk1Rmjr4uN*tHaRXj>2FD(EAdvA%`=pc? z6qp|LE}Ok-3+dOkhf|U~l>GUCt7jA};={*oHEr|}kM*8{Vow(We_O7u5IE;;LCv?e zYVo(q%xxQrW7<2kvku);zC_XQAAbr2D>wc9?Da9IH!I%6ifrNfvjc_QZ%^vS$KXn+ z<#NLb!MB2HhLCUh|Eeeb@6z_{AJJ(iY^pQM@ailMhN|JI{J-gfd?ho@=SMr+4rdQ9 zu8cf*K$~S$W&pVV(X6F3P^r0Aze)Hea>IeTlQokyE;P^TDD&)=nKM;;8>oxU0;c6X zlIdsnpued^=)Loq+}+F_(ZUY)Y}PHw`a`3mqvaMutlw5VCqzZBeWM0G8N26SW4oGO|8lzml6Jn%6kIg1M|6m~EE(V-8 z`Ao}8Z{9RxO(RzNZ{rvfk{KEO0;l^b{XKqkOhGQ{OCnt~?fki0M4wn&Y$z$4pkRd$8 zv=#3%pD3!tOO?x{0wsN>mZ&7L8UfKKu81W0j2(G|b0WKGv<` zV_x>}($<~so*V;kx|J*N&;p*{utb%$Zh1=K>z6MNjBX5k3#2sgXOG<1&pj{eCc@+a z)>j!|Eyid1?i2k%e2k>_{pBUc-iFx2r_X~el!{31Y0zCx6#~#v#qwerfDWnEnttDU zO^*<5;&5Fl3X-OSs8(yq)Q<*fD`P_Y)T0Ek){sGIYt03}1^}f0)?;+!GJW#?wGbKC zM>9|r*b*RA+DEWz)KnWCGIZeesM<6)RmJW%k|5!n_m@($Y3`FfH*@M=P7Sb5QVsHL zxWAq$xszQobZ7}|Ms-T~w9`jkH^^$fJfgJxAqJO~ zq-;@*-c(F|o1U?aI#K=6A%bz1X8rH$MY{ajEz-srdY#=Ud7xz}{X@$_0y|IPUC*U& zgMcy!_<{A%es=ckr?0u9r;O9-*qeNrq}(T4f#OcU^!m0SHid|AU}(PA$tVL%8Z9i6 zMO^|TM78^mOBsAt@BQ&jL`esmuB{AaK1~ZOMsbP9y|Z7QZun-8>4|6eTWrEE%?Opo z0jJTudvDrS`1C2HEEW=k@l5~G_(R;>;$S(f`lpe>afTKkCzO&LVL!@7;Hq~tx~STd zj6IdrE-z5;{*fy!x_IQIVZi18h2fyU=H0~H5#Co%>oLS%dr*rBxPNB<|hJ0z`?9_Qe<0>)z*UrS9pOD$KYBTpfYmRQ{v;CWez zj4P@a{AZW&HcrGbk#c->@BI`tVo48PZitsvb0m15$SAl%5H?P@YEHOP*W@+PteyUj z$u;EvVeTO>e=6#(#L&Dyl_-}!NoDttcgMSi4iEjj@DZ4G5qJIi6qtULV$YIodJ><4 zbLu#)01CNajv{lYB_uWP)nF3*R=NFZ^ch7p#zQVz6GPEyIPckORjSci=~}#M_524E zl@#KrB)^pmUd?1ZqENkewD)9@*F>QBtssZhh!o zrZ%|-Hp$z0b+)#3x4#0)&Hr<68(gnblN&AS|D1p8#~!tY`#(3c@E8~8O;U#C+Hx%$ zDy8~YnbAqGfdq{YRD*5Fcf_XCO@)4)v3S|vVe(~7EKIOLw`7{VZD`+{)h0-~CR6rK zOqN1VQD13gNzc656>n1T_QC&q-*FtH1;e)_a*7%j@)fWu+OymF<{oYqE9hB4LX%?X zQ1sBaNctp@^K#%z>@LZ>3bNN8E(E4~wn5H&MT47*$by#rSlaU#EoM|wg@~%0UXP}0 zxPvw;0n00yI^@-`-K#sjSQeZAf4|7$9t38Fl1>R+WD_(rG(+A-qytHk(zZ1)dLIv< zyd=E*OqwAEjV`6wfctK3=Q$8zLD>*~w=d^OV}#$@bUd^2#g`K`v1RsUxZD|zWOG&N?2A{}kMQHi$DEK0Fc+YB8;ep3^$ zk=4rfTT}q9tgETN)_S6bWK0Wi?xw-Y8xG^1Q~r~X?kb2F%redpQ(`po$J!Dcf7TxG z=h+MY)UDaO(`ty|hmUiU+t<9R-;(PPH|I4JA7w7fRw+jZ@Tdy6o?~?>CY5QiYVnrc zT%t&aV9(%qTE5kr)8L-wyQMA{&Cy(M8SeN!fatuWaF4T8){=lK?mtPu^u9}KYS=^! zzL_5wi+Oo@16{}8@+F-~QqHg|y7MeJSgDDQCj9YEeW_&kiLMah?F2>UJ(*+%yl)jN z5+oV;lK&ArL3b0G@!qgufdbvle=sa`c&?}8q!L9XBTvO#TML_-tg8DXVN6QJF+GQG z6iO}6efh>E^e(T7w&)uP7dy(U7#Lx=`ui)b2Y8Vzr4hA6wFM{la^8Ic23i7wWm=)8 zw;uxErtb7(K~p>D(vf(fidG<^q8ntXS4XMNsy?T5N1Ky?p?b;K=f?@bSh~UWG#|D# z4z_hu*>Wv1*mJd9dBV3zd`q$0{_DYKw9Y>q7m-P41VDGIl*^K@OW~$X%6&j^6$O+J zN#HBQ&p80a-gP+Iy?VTQa5|RPV(a+?E#3athzPq4}d1VRf_S;55mJV2>Gn${nk9_3G74 zUZj~LljO#zUi*(X<{(SV_7U=gkg|%Ag!^oL)Wy5T}rR;}J$(Jqv4t^mK zW?YDHZ?PsQZR$)ZLG%`#hZP6&_}pkq)pietJ7r|Nx7T8m63Tc7tJqbn>$u(v!J_p% z5PAN4h%oNfwc?E-iB1T~-y8cawi=|UP4NOWb9CV5mmTR?stzf8y9%cFHW+7ME5_Zg zRlYT=dY<#ih*Cam+&*l_BSZ7vo0gI{jmM<^DE?HA)*(cJa8Ebx0IBK5*-E; zQed(G{`#FVaaG-G1o1Fvvo9EMS=5tjx^y;8&PA zvxOV6OB;bO%S1>GvW6h~!xjz4*rIBQ_dN$ukEa66zKwjS5n{3+Q+ijHE$P1XqNrI& z9^>5L_yUMWso*}1&|A$d&8_jJp6$cgWPhtyxRD{c^vG((XI8-Qfhj-Ac&4I^>`-;W4QVCvY~D-x90|4Pc3>V zFHfYmp@ckgW1^k$*Ogwd@z1wSfm5cBkrVZJ?@+ujBwzfKZR6bo@bLj2>BYIxo$H4Q zY!RSlGd}Fc$Jt0y0?LgUysxcl}f97jgA!y-@4i;Ex~dW(K|(V2DRFKs^5}Opk_xku9Lm1@y{ z(D-X4_o7l9!A~zkH@n~-9=cw!)3O*59*x8&^|Dkug#RoF{%~2@z*a; z)Ca}hs8m?BPn_4?Jjz9H$BWJn0PPZXh?K$i9Ad5LjY-4T-2C9=(s#Qqr?$ebD^caK z+)&|=%3*On2?>cl+55N6+Q4WK=YlghQthFik}W_nEfu9g0cU$@RwQzvj}(9c#<51?=`riO+pc;I_RV zy7u7$y$p3cH)5v$u?`tw8%J$-n#ow{h%QFBf<3$2Qz9@Dl3gBfd!+-WWl-uedO0{n zR@-lJUDt>Nn(bg>XXvEhwH9=s-av-UDeZrD29&|KXe_vGAM>N%e}m&YQhyJO`SS`*l^2I=FPYtx7=rv-c=xvy=vEYcT>6hn3#2!7FR2Y zJl2&IpmWmH0XH`}J4&foq00G{#36IBAwl}{2Q9*heiF7yjs5e}J_pF&+_Rb5K)E&m{yarb}3n-y3GU{ERGY0Ql(8mmP?g%8~fFv=P4ERO&(iY;hLdCAxxFL92PQ4O-wxAjb}&AzGN#T%4VRD z+?R>*z;&w09}VT-#gv}{HtK!HE5Wd^^5wAa>tzqD*PlF>;v!!~q({1OTN}+KIYhiN z%iqy-B~aBUr5TK854N19F=06Xo{x~0e2n~#R(iZq@+ zeX6>{*(kQ@(1@(?tta@1vrW?;fFrk-DKT~9mEWFJZ4@?I?Wic=^2bJGAOV~ijnc|Dhv5{(A$L&`3Xr^tpYp!s$t-8ojtu7SpOEm@nE^$)*-&nlvn*B14}{K1Axj&HduA=2A^0)Uex5CCxHQ)c1D@n zT0`%yLS7)DaUFmA!x`a_kkQ(++T4wP$~QKjJJE7!a&^b^J!lbA|S> z{^C2s_TS`O8khZatG;~W5tPOANx?-4_CB9Q>AtO}2!MjN(F|~v{u;TgRP;I+9Kh*& zEA$J!=y{Mk_iX-MxvDR_M`F5iIRs!7QG8Vy5F}u2(BY#oSwFlc<%M0_^zjjev2DJI zy{(+S@2;HCo+1D+R8eU4{O&Lv&~75+MO%+rg89hzfFN+CDujL`<`iDz zxb?>XNnuGyLvS|vIGnsnNB=oiNvqoV+XY}2l&`YyngR{(ZU>;;YTNgUG~$5o_tR~> zg{Y6)n-L}VE9eU$ssoc>W|w(oztALh781;#@u$HMbDMTtq`2PkMn;?&bE=e-ivs52 zKV1JldkAih+3ao5``e4;dbTgYA%4vwhtWmF-rH@wJ&DRc5}jESeNxm8MGjif5Dr*= z_j6y(yzyp#bnmU6yLVHNC#B?Sis%(K6)TWaNhC8%5r2pGG18O`pOz;spmx1vdSeJU znlZ>lkKF@ifPYPoz`rVjGPhi&$-X(^+at~8j=}n=5)YTJ{jN4gRoPKA z;a-q4$WyGO!ruC5svusb5GpS|Pf$iq`C1JB1-$M-Pb63w!OcQI(?KU`HUC%LPRrjY zDw=$Ps8fr-f9MTP3+MXw86W;fGb=$#xf4`8UdP;unghP2UZ7iX9~#;ZAY{jxrqine zA;#qofcy2nVcQ_z@A@;=UH4HjL`u-PKx*c-cf(@n;|>>rT$FfSczC5kkYOSO5mJRi5H=znLnpPCKmpC%tlC09= z-s@`{h+G5dI$2$}2h1%k2_Uf5g^nj{mN^)Go?&-3_MXT`d@M!rNayS0R(3sm0yaAv z+|s*>ga61+|Ge1?k(D93#!14qZFhXSPUqXS){3nh`?y+Y^~J)f_?f6;V7P=q*z#_t zVEOl(aXsPTa#M0nQ*k@Z*D$a?RsWdXz^s(KObvSY%Z=+a(j*Hm!bgZ)R*4YHcaD53Xq?W5E7rGnEMBmXflND# zy3x!+HckDuFVfW67o2`Z`#6b<{UO3^vtwfZ%rdW+eS7U^;$xodJ}_@p-#d$OuKQzK zV4K2gPXnVe8UG731S;ZPO~_Rw?wN@BJ2YM%-L**R z%ka>AAj?cnN_uEhn0k2l)qVjm(;=lsiZfs2I7D|f&bzPD-zv)M(oj#a%3;I=^0?XQ zZP1A^h3sVB7V1hLO|OkgUY?^1?z)5}dgM2+9|PpS)DcUI#UvO!{r95z`|rCZV6!$Y z)1LDC=aNS@aVnf0#^q+_|J~_NU@SAv%8w@O|70(4v$n#`wZ(6ge(kE=cv`4k^5izv zZuCRpKtjT7gIvoMvv7RHlVGO6deRqf4A0gT``^%pN6zY_?8>JB;@Mwm!HaN9aM2p~ zB4z%rU*822z&3_H<81qvr|mwye-~bq48r$xC5(ekcO=Y!Q)6VaBgk&xv+y47u0rL7 z&HVr7W5`QGvuuNdulD}Hj!LVYE+uZG@%w5*4WBO;!dn^mk+9(*0yRG3@hq+E^@q~G z`hcr{RBF<^+wM{YV|r$Oi|g&!!sYLv8dm~zpYA9CiqowANd)9CK^dg*sg~n^mTp_2 z8pjd;$u%+e4$g?pIA|>Kii(EFi{DZ^y!oG6st@r=5k}8GTYLL|cfnl(-T8eZf`3Rm z`O*kra(kfaaV?j@W*9kzO&`d|8q^0yiZmtucx@k^^{p) zyPvxvP}%>o4&z>A?z{i*Zk1n#Jt=+ge_z9ev`RvDS#tm9NBX&bHdEJeE;DsOmv?i@N5@$7~;LCftc-W2gq1pf(vtyfkSP*FDzzAV64dp5u6l zOTy{K==q^Yueor`lZ0Ydf(_Vi`DPK`{CF)opO%v8&E`3)?n=PpvZ>bVECHLxql2&A>PSC{Fv$#UY+{(?=HQu@B8=f*9IOjhQ!36!@>?A zi8ZiBT=J4jOI#Fg&rVO`O4`PqIP~Gx3WRns)c4!Qjs$QW*W2X!W6z1%@!SR*x2P~iUUs4b{q5Ai0ERjU5vAc z$FXl`-sOtL=>V}oUtFR3j~_q$-44E?!p)lwvwJcq)+wX+7z7(VhhvF)m9}n!5xAlv zY_7uNbh8vy-v+b(dvugxoVy{}xHrbY2BE{8>_iusUz z>w9DEa}SR#_qbwJO2pmd+A46}`9xoANwRzSOmvGB{&&zQ6MmuIn!Mj3)Q?<7L^Vhf zAC(NB#|zEh6XFqA88)FbTa)F6mr*mqF{hVW158U(+?T1AGPV?)-$KuHaM_4r3&xj# znH-gQwrv-O{N4XH(a>(&)giaZe{xyhi+S~L>p!;QeowW=rLf6LPvGz1mfUe9teTo{ zwWdyau-Z;ncgK3tH~NvucS;7#8Il{$dU3wg6eBQEd?ggVlT}hg=J!*zC^qtZm0$I6gUtKx0dBva+>?uuMI|fL zlq0gzW#h#Ji;4j>Q~3-lF|2$>s(fI4Wz1Q2*g09ee4);=Zjp2C$vNaX_`za>LQwtt zD*itFPa5&kx%?J}n3cs`!hEyPQu8Rrmx@VIqvoj@0&89YN2KD3(aY09%RlQ)f+=I! zG39f%6?5amul-i+9V2CD-!au0RB^JCQb(JWg`#&JIeW_Z&S+AL0^9Tpeb-^{5ldf6 zN{Z?HLaZFjXwDWwjn1}mD$OmTai82Ps5n^c<+)tUv)(ySG_fyFJrJu zU9|;QIrmCgP=ZRf5<<;?Zt(r&A-6K&9!LFQOP!HhnHe?qo7&o9*h^{8eMgcY&rI~+ zVDj#mo#&Rm;nn<3p=GvVMY?R6lpSlbQjAscyB)gA2jh_KCrmbKDDf@uw6(SMTB;LQ zi~W5tHYYX{ueh-!m27mh#oiAzFK+w@*}0P{G$k1Gika>TRPjKNRJ{X1ZmE*#YOgb? z&9?ieL)?72DJ4m21q}!=(RZ2bEJt=u@mtc56_pvitQH}=)B@afg2CMDnzpawzUYO` z?DLhgDN<6F_q+TStNfyts;i{uax5KNCVfr3vR8a39vw~|mLqyv*0?M5Ap2cf=I6`c z9s;5DpLhGdfrbW$+Cq{<4%WuoZPe~_&GyF4MiHsyQlS--*WAeklarPY{CXfKMx0Y z`|YxbKj(PuA6%F{7T~PPQD24j6pbf@n#wK>$1abK3d_w1V~ay@Y77-5vM+I*`w@{M z?uIRX!e~49=JVr}D%rW5mj3J&%4k6ONWhg0YKk8vWwgp~yeb(dPwuH8E>99;VyHrX z%0;txzW(!k;~975-AyIRp8wzPG0QS91RvSbQ1Nr0yTh-V^6{Ev_NCwKv205tN>ySQ zZ*Ovep<^IPP1Lv2($8(wxq8@;%)Z>uuF7pP|7oo3!qpp+ry+nu#%H%Eqz2Wh>Vhm1A7r!V~kvqFQ*F_8zued=O zsgf-&@KqMqSPdIwo~gqX%Y@b7Fp7NJdRg}-MHZEY`L~YYz9U5qGE}nN5`lZ_Ww6h! zE=GbMNi;iL7KvH7%E?|%-^rO6abwSMy$VMC)9cUVe~y;6`2LPA7&^`&e?6j{vO74+ zVWqnwTIKfC?%*&J?}6+(-(@t@OLBKt7dX1#@tT`)M>&Z%%J__YNU{lLm6MGw{Qug!@~Eb+ zt*?whL~ttB$WW47$r=R_o45hqP2>aDYQx+D2O5= zi2ieea@$=e^WEpqDZ)A!J2`E8P*>YnuYoQ5!X zn87)ycE*|_{j6?L+qH%(?q~vVH9eKHJE`n6>AjJF4o68hEYzO~`eGJAwM__S6VzTL zaF?~an=L4XA5V`w^kjRY9qIKvL6|{zb-iZJTTSOof=^|7u2`miS0Z~9zt)FQUY?jK z>uq*qJDT<8JkWm|s=l^3yX~T&I7nFBly&600WP-5%#csvU4{Ql)iF%_3S98MErC`T zVy?=GFjW$2b*b+B5^fR3R0K<#1ZLUq&Im5Kw5KerwbEX!6DYY}yBobZga3r(1 zyJqoiWTg{CrW|+zsF{A!0^otg&8_NwTD4ZzRCHyjw5ylf+f*c$PW9^1?s{hyAJ<)D z9N#lFuP&swF7moRV@7{`;%_Ch$^!zwa74(LPax1#IerBZWM`IjUChC7xc0kdVCP+f zxXOL4PX#HNl~zG-!whbZj%KEk=>-~-MPq1nF%t_1V3_X zn?C>*GMrrO<5R`nYfYd*jzuhv9WRO5pBwiADXVd zdcdAo9OH_dK}op$hEbG3tlNQ}cE+{9S5JM;#rYRGttpD@{=?vWcEjU2QOPal{R{4Y z!(^m~k|mW(C=5hUn5qEoFPS%ABof)m>e}M^UtIUsh_3T^HrxYiSPa`smrm%#S9T{_ zJiP(!#fZdy5A`gFIiLMzj@g#vO)T!Ds3QnchN!KP3tL#Vigywj?II^I&&B66)Hp6K zf+Uv;zD-qOIGMiwzLwCwM{74laZ6{7W>QzXxg&$w3?m_HkYVNGgF%AUL@0tNQ{r8-s~y9LoQMTf5w*n3A^)qP)6_Yt34gO@lr{>J1ZIaM zUCv72{<9`r9JBEi{6&j`tV=L>YQghp3`p++s)G60Z5X-vP|f+mKE!nN^ziibv{C@f zFGQx-U=Hl<7mgzJ4W2=6HdwFZ__GMiGzDP35feG`E%e&!Jk8R|+sCIcRX9Q9#(!MJ zr(9^Upn1wRAHud`&{!TiU;u_;H|&v&b5Ij8=kpHkvGOm|61MhC8v{@fOd3E2i(nH}s6@;!7auZn+MmV6!CvO#voMB7d+A)6dQ zTH6F6e6py(l0p@ke#+EtlO-=x>i?`4Fs#N~TU!fWEQ^}!#AxhnslT_-I4apvl18SV zvSlNsGs3Y=>x}p!Mjn@&4`*v6P*PwT%*93$&-P3MU^V!N+}^TpgQTgSLDK&1`o{9J0R2)aOmU3SENrih;}kvIFwGRKoO7Wa-D2K^ zQp*$()!Uv;wdAqqr=_RQ*IP;}-H`F%gh9N6tDkSuuYTH^G~Ln)zECi4!}mjA4Ml@0 zaCzy9`sLWF>k$*s5bhHk7cj%rB@1rIX;Cp%gJ!m?)<H z+Lq5mPQLau20nGUpt~6s5E`cr8yaKbEB-es*P_9QGofCk#?ke$XFEu1-gO0kjrME* zGWy-%{aeQ=AO{MiL<6QO+WTBiA8>g-{bX^y;bPU0sUYdXXO)C}_h%)vxqdH)gW-k= z0K;px!kG#JhT>sN@qLIc0=9&vcHqE)#JfjKU6MQC?4#iCdmK!i{KVUs;_1;u4#R52 zz|w>qK^mh`!1{)VA?_jy3Rnq5DrdjdzPHtJc?a&F`d!e`(a~5omnl|F=|=V)vWz}5 z$Ax&F0*Eq~DvE2aLp-BhdLDDLK~9)!1Kt#?jg~WIMW6eX0NkyAWE?e8TljR9rRF3s zZnrj{&W~8o8&2(ZzK9ve;K}Vh2b#I7_M;_c@Kz9+&G~@Fs+{>D*Wo2$$&jQOz`*<% zeC6Ewa`>%u6^IaF%v2&o$@4jfRsJJC50p4~Ofbr_f+3AL*D8uFbd~%g%F)rrcL%}? zcmKxDw$~OsuLDiXbtwyY&C1R3J>3+8C4R4;v^lvSdbABO{!9L(rUTe-zQYB>ei=$VmS~{73#FGfdXXPN24b#i3Q&LrO2SgoCVlkz!G1sG zdos)VAiC|Fb)FdvCV<}v_cCte*EVz~+2hciC~VpH0~Q^}IUBz=IN>Bn;txb-=! zQm~Y0Fr^V9t{%}~hx9P7kE_4%TSj01NK0tR&KoX!KtzEOn__{OPHs3jp&Ut;W(8&& zXjss6ogf&bxyPJU%neYsk!R;I8gmVZGbpp!^2y>bFN{|MNnW2-5^Um$3jG50@MvnxxM@pnvaeDG4%o|z88jT z1JnRBha`_0sPYAN5ycslsV;==Ia2|d=k2+rhuF3OTC)&cuA+GTa14 zcKkAMrs8H#1zQ-cB>5T+t1Ly!@tD%*a@!=2YM0N5ca0n2=KMcYhFDKw4x~AV&b7Fo z=`)T&Mu$;gE#gs(Tx0eJnIStL5v-9<4WQHQ*1}k;pa4hXAOB@`sPWhAPR+aN#~n=z zd#}DT92_+e6dD2o*s6I)qcxhtv+uyf;*~$y2{5YN@~F18XC=yAUWSXqdtP3jrm(FT zGheEtiHrm*&>(yM70hQf6^P)%VTnC(5%HV7Jd8{&S_|ZMEUiaNsM)&!B&~e)IVGWr z6g>Ym!irRh7LC;LM`VH9gBek7R=kcp_h>{9ZZ$o3ffh~g^^3c&1b3vf4Fbj5bAhP7 z*yH{#U66l;OHC@1wdC~Hp{RdxcY#eHVxdwvuV0#>9ayc*-k2E^hX$%BEj@24d(Sp? zk~YV6J&`A>@KX^sJ!dmbGM>9sNgk}R2@$`T?^&=m(kiXuNqk`EEJ1#1POxK7<-t~B zqNjUM`-Tj&#VvOS)>elY#Xg@ebVQZW>^(lnCUhn)ZoL}WlqBg9hsbP-W|fgfrubTJ&T4hi!P`zG zk*)Ubo4;Q@yEizfF32&xTzDovCp$gESJ5$xfWbSzdXs|oJne;&BPpPZR_>iC^ga`{ zwEG48#aI`Sm>rPMtx0g77u5aAAcuI*B2ZxAV3yUfl}t2ABZ~9`x+fNJ?=;IIW!nM@ zBq1`jE0xa>eh(q5m)#*!1^ek?%u^ZSH_`lWcP6NCRB!D|B3mpO)uc#P%Yd(yAAfQf z`w9uZB275QfS;)JbZ;`@r;JH99x6j;iaikGvU^QY5OY)t#t>)>0~IE2l)fZ|DwdHkkdGoeip-Ewa^g zCUv>vTm=uvJqiNGv#EthLiOqVr-h;9%;r(5oFGrnT6Asj3cdttl1Fhy+eFa3nLyMh zU*(ZA2~$jTMQSY>sQNir!me3{d~eG|5m;R`8HS#HE=5aMb+{CE;|BG*=e!Uh$B& zA=1c2m_lud33ewLR-Wu}!;KZ)eubth+SK-^qURs`1~|h0Hyv2PV`)}J_gDf=I&K}S zoPJ=_ke)i|>Lk?6c2@YK_69R8l*oB8dQ!P2Eh6-`FO#a{zDLox&%zYWZcpEZ?)(#0 ze(7*&0F(MW=NX0N^2f$CL$zsW{u>aUdr9S3s?%BH+dAKn-(*b&11jBOIau?cKQbip z(ffa^uD=rXHE`1Q)Uq_IV1=Y`^7tEtzwGVUze4r z16o>7)f{l}17_BYUN61i3 z1uuKLWD>l@v`5%@!w#)bN3_Ti&~RqhY?F;Fm)wo372)9mEaBnR@&#xKz(UV^ zB4zoN7CHfA-zeZJz`4o_81;ntPYkTm!-Z&O(Yg*^{7j`;vzg-H-2u9TTn4lmnoB?t zBXMse+73W>UnuF=t2u2>Bxi=Qe^Fe*N?5|l?U`O^36PD>hX6yLUw1A368yO=JCUxK z;~j%h^|n3kz$(^s)Kqz$fL=zr-yZJDLXtF{G=nppsT;R=p0IAIr0W--oPLH-?pO8J zzG^YArfd)CC!V@5tS5$7fR-cQ+`cz9V0SikJB!erb(2aOw1hvp)Jh@!6B<9v-J`-8 zO`AJR0EU*HOJw0objRZg49$D&y&@Kt{5mbl30h~rC8DwEGH1}_fd#o>PDfOi(~&cernCf=69+fx1Y zSiGl+_cY}tb28r3#2ext`!sk%96wDVZ>BNv(-ino965!=kK*9xxcYNTyh(~50+bh> z@I!$33DN<;fHz4$W0Mqbj1I6gXn^32(f`WE=nv5|6Gx5GR$BGF?GN&z72fB<`&@F$ zf%m!aK39Jr!24WypG#h(fW!3o<5&3OSMoD5c%KXJbK!k1Xzt(-e##H@%OeHe=feA3 ze{r8HS5_RScX|{$#NJR Date: Wed, 19 Jun 2024 14:11:24 +0900 Subject: [PATCH 016/217] fix(autoware_behavior_path_planner_common): fix redundantContinue warning (#7578) Signed-off-by: Ryuta Kambe --- .../src/utils/drivable_area_expansion/static_drivable_area.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index 87e7d297c65c7..b045304d56b41 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -357,7 +357,6 @@ std::vector generatePolygonInsideBounds( // Here is if (!is_prev_outside && is_curr_outside). inside_poly.push_back(prev_poly); inside_poly.push_back(intersect_point); - continue; } if (has_intersection) { return inside_poly; From bfbe80eb8aebca40ec40befb7049fdddc121facd Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 19 Jun 2024 14:36:15 +0900 Subject: [PATCH 017/217] fix(autoware_behavior_path_static_obstacle_avoidance_module): fix duplicateCondition warnings (#7582) Signed-off-by: Ryuta Kambe --- .../src/debug.cpp | 36 +++++++------------ 1 file changed, 13 insertions(+), 23 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp index 6b28e33759b6a..b5c64ec9959aa 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp @@ -573,55 +573,45 @@ MarkerArray createDebugMarkerArray( addObjects(data.other_objects, ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE); } - // shift line pre-process if (parameters->enable_shift_line_marker) { + // shift line pre-process addAvoidLine(debug.step1_registered_shift_line, "step1_registered_shift_line", 0.2, 0.2, 1.0); addAvoidLine(debug.step1_current_shift_line, "step1_current_shift_line", 0.2, 0.4, 0.8, 0.3); addAvoidLine(debug.step1_merged_shift_line, "step1_merged_shift_line", 0.2, 0.6, 0.6, 0.3); addAvoidLine(debug.step1_filled_shift_line, "step1_filled_shift_line", 0.2, 0.8, 0.4, 0.3); addAvoidLine(debug.step1_return_shift_line, "step1_return_shift_line", 0.2, 1.0, 0.2, 0.3); - } - // merge process - if (parameters->enable_shift_line_marker) { + // merge process addAvoidLine(debug.step2_merged_shift_line, "step2_merged_shift_line", 0.2, 1.0, 0.0, 0.3); - } - // trimming process - if (parameters->enable_shift_line_marker) { + // trimming process addAvoidLine(debug.step3_grad_filtered_1st, "step3_grad_filtered_1st", 0.2, 0.8, 0.0, 0.3); addAvoidLine(debug.step3_grad_filtered_2nd, "step3_grad_filtered_2nd", 0.4, 0.6, 0.0, 0.3); addAvoidLine(debug.step3_grad_filtered_3rd, "step3_grad_filtered_3rd", 0.6, 0.4, 0.0, 0.3); - } - // registering process - if (parameters->enable_shift_line_marker) { + // registering process addShiftLine(shifter.getShiftLines(), "step4_old_shift_line", 1.0, 1.0, 0.0, 0.3); addAvoidLine(data.new_shift_line, "step4_new_shift_line", 1.0, 0.0, 0.0, 0.3); - } - - // safety check - if (parameters->enable_safety_check_marker) { - add(showSafetyCheckInfo(debug.collision_check, "object_debug_info")); - add(showPredictedPath(debug.collision_check, "ego_predicted_path")); - add(showPolygon(debug.collision_check, "ego_and_target_polygon_relation")); - } - // shift length - if (parameters->enable_shift_line_marker) { + // shift length addShiftLength(debug.pos_shift, "merged_length_pos", 0.0, 0.7, 0.5); addShiftLength(debug.neg_shift, "merged_length_neg", 0.0, 0.5, 0.7); addShiftLength(debug.total_shift, "merged_length_total", 0.99, 0.4, 0.2); - } - // shift grad - if (parameters->enable_shift_line_marker) { + // shift grad addShiftGrad(debug.pos_shift_grad, debug.pos_shift, "merged_grad_pos", 0.0, 0.7, 0.5); addShiftGrad(debug.neg_shift_grad, debug.neg_shift, "merged_grad_neg", 0.0, 0.5, 0.7); addShiftGrad(debug.total_forward_grad, debug.total_shift, "grad_forward", 0.99, 0.4, 0.2); addShiftGrad(debug.total_backward_grad, debug.total_shift, "grad_backward", 0.4, 0.2, 0.9); } + // safety check + if (parameters->enable_safety_check_marker) { + add(showSafetyCheckInfo(debug.collision_check, "object_debug_info")); + add(showPredictedPath(debug.collision_check, "ego_predicted_path")); + add(showPolygon(debug.collision_check, "ego_and_target_polygon_relation")); + } + // detection area if (parameters->enable_detection_area_marker) { size_t i = 0; From da61a2fa7dc9acdca248b7d1f995efb2a9389805 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 19 Jun 2024 15:01:33 +0900 Subject: [PATCH 018/217] fix(autoware_obstacle_cruise_planner): fix unusedScopedObject bug (#7569) Signed-off-by: Ryuta Kambe --- planning/autoware_obstacle_cruise_planner/src/node.cpp | 2 +- .../src/planner_interface.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/planning/autoware_obstacle_cruise_planner/src/node.cpp b/planning/autoware_obstacle_cruise_planner/src/node.cpp index 8acdfea013e12..031e58797364e 100644 --- a/planning/autoware_obstacle_cruise_planner/src/node.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/node.cpp @@ -409,7 +409,7 @@ ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & planner_ptr_ = std::make_unique( *this, longitudinal_info, vehicle_info_, ego_nearest_param_, debug_data_ptr_); } else { - std::logic_error("Designated algorithm is not supported."); + throw std::logic_error("Designated algorithm is not supported."); } min_behavior_stop_margin_ = declare_parameter("common.min_behavior_stop_margin"); diff --git a/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp b/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp index 5ab0ba237ec78..40c48c78ab021 100644 --- a/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp @@ -143,7 +143,7 @@ double findReachTime( return j * t * t * t / 6.0 + a * t * t / 2.0 + v * t - d; }; if (f(min, j, a, v, d) > 0 || f(max, j, a, v, d) < 0) { - std::logic_error("[obstacle_cruise_planner](findReachTime): search range is invalid"); + throw std::logic_error("[obstacle_cruise_planner](findReachTime): search range is invalid"); } const double eps = 1e-5; const int warn_iter = 100; @@ -175,7 +175,7 @@ double calcDecelerationVelocityFromDistanceToTarget( const double current_velocity, const double distance_to_target) { if (max_slowdown_jerk > 0 || max_slowdown_accel > 0) { - std::logic_error("max_slowdown_jerk and max_slowdown_accel should be negative"); + throw std::logic_error("max_slowdown_jerk and max_slowdown_accel should be negative"); } // case0: distance to target is behind ego if (distance_to_target <= 0) return current_velocity; From a4432105e3e1f2c0bcb02f7c2184f82e752782d7 Mon Sep 17 00:00:00 2001 From: RyuYamamoto Date: Wed, 19 Jun 2024 15:03:24 +0900 Subject: [PATCH 019/217] feat(ndt_scan_matcher): change from TP to NVTL for determination of initial position estimation results (#7141) * feat(ndt_scan_matcher): change from TP to NVTL Signed-off-by: RyuYamamoto * fix(ndt_scan_matcher): fixed typo Signed-off-by: RyuYamamoto --------- Signed-off-by: RyuYamamoto --- .../ndt_scan_matcher/src/ndt_scan_matcher_core.cpp | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index f392ba4b3c19f..a6e46bb4919eb 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -1068,8 +1068,8 @@ geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_pose( const pclomp::NdtResult ndt_result = ndt_ptr_->getResult(); Particle particle( - initial_pose, matrix4f_to_pose(ndt_result.pose), ndt_result.transform_probability, - ndt_result.iteration_num); + initial_pose, matrix4f_to_pose(ndt_result.pose), + ndt_result.nearest_voxel_transformation_likelihood, ndt_result.iteration_num); particle_array.push_back(particle); push_debug_markers(marker_array, get_clock()->now(), param_.frame.map_frame, particle, i); if ( @@ -1101,6 +1101,13 @@ geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_pose( std::begin(particle_array), std::end(particle_array), [](const Particle & lhs, const Particle & rhs) { return lhs.score < rhs.score; }); + if ( + best_particle_ptr->score < + param_.score_estimation.converged_param_nearest_voxel_transformation_likelihood) + RCLCPP_WARN_STREAM( + this->get_logger(), + "Initial Pose Estimation is Unstable. Score is " << best_particle_ptr->score); + geometry_msgs::msg::PoseWithCovarianceStamped result_pose_with_cov_msg; result_pose_with_cov_msg.header.stamp = initial_pose_with_cov.header.stamp; result_pose_with_cov_msg.header.frame_id = param_.frame.map_frame; From fbd61e2f5cf0d30bce14ee5b2f9f2087f32008b8 Mon Sep 17 00:00:00 2001 From: Zhe Shen <80969277+HansOersted@users.noreply.github.com> Date: Wed, 19 Jun 2024 15:18:28 +0900 Subject: [PATCH 020/217] feat(mpc_lateral_controller): signal a MRM when MPC fails. (#7016) * mpc fail checker diagnostic added Signed-off-by: Zhe Shen * fix some scope issues Signed-off-by: Zhe Shen * member attribute added. Signed-off-by: Zhe Shen * shared pointer added. Signed-off-by: Zhe Shen * member attribute (diag_updater_) added Signed-off-by: Zhe Shen * dependency added. Signed-off-by: Zhe Shen * implementation of the MpcLateralController corrected! Signed-off-by: Zhe Shen * typo in comment corrected! Signed-off-by: Zhe Shen * member method argument corrected Signed-off-by: Zhe Shen * delete unnecessary reference mark Co-authored-by: Takamasa Horibe * rebase Signed-off-by: Zhe Shen * correct the include Signed-off-by: Zhe Shen * pre-commit Signed-off-by: Zhe Shen --------- Signed-off-by: Zhe Shen Co-authored-by: Takamasa Horibe --- .../mpc_lateral_controller.hpp | 15 +++++++++- .../src/mpc_lateral_controller.cpp | 29 ++++++++++++++++++- .../controller_node.hpp | 5 ++++ .../src/controller_node.cpp | 3 +- 4 files changed, 49 insertions(+), 3 deletions(-) diff --git a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp index 1f16bbc39bbbf..09399d1fa2dce 100644 --- a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp @@ -22,6 +22,8 @@ #include "autoware/trajectory_follower_base/lateral_controller_base.hpp" #include "rclcpp/rclcpp.hpp" +#include + #include "autoware_control_msgs/msg/lateral.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_vehicle_msgs/msg/steering_report.hpp" @@ -52,7 +54,8 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase { public: /// \param node Reference to the node used only for the component and parameter initialization. - explicit MpcLateralController(rclcpp::Node & node); + explicit MpcLateralController( + rclcpp::Node & node, std::shared_ptr diag_updater); virtual ~MpcLateralController(); private: @@ -63,6 +66,9 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase rclcpp::Publisher::SharedPtr m_pub_debug_values; rclcpp::Publisher::SharedPtr m_pub_steer_offset; + std::shared_ptr + diag_updater_{}; // Diagnostic updater for publishing diagnostic data. + //!< @brief parameters for path smoothing TrajectoryFilteringParam m_trajectory_filtering_param; @@ -87,9 +93,16 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase // Flag indicating whether to keep the steering control until it converges. bool m_keep_steer_control_until_converged; + // MPC solver checker. + bool m_is_mpc_solved{true}; + // trajectory buffer for detecting new trajectory std::deque m_trajectory_buffer; + void setStatus(diagnostic_updater::DiagnosticStatusWrapper & stat); + + void setupDiag(); + std::unique_ptr m_mpc; // MPC object for trajectory following. // Check is mpc output converged diff --git a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp index 6aedb74e87c83..0661b439a3982 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -35,13 +35,16 @@ namespace autoware::motion::control::mpc_lateral_controller { -MpcLateralController::MpcLateralController(rclcpp::Node & node) +MpcLateralController::MpcLateralController( + rclcpp::Node & node, std::shared_ptr diag_updater) : clock_(node.get_clock()), logger_(node.get_logger().get_child("lateral_controller")) { const auto dp_int = [&](const std::string & s) { return node.declare_parameter(s); }; const auto dp_bool = [&](const std::string & s) { return node.declare_parameter(s); }; const auto dp_double = [&](const std::string & s) { return node.declare_parameter(s); }; + diag_updater_ = diag_updater; + m_mpc = std::make_unique(node); m_mpc->m_ctrl_period = node.get_parameter("ctrl_period").as_double(); @@ -152,6 +155,8 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node) m_mpc->setLogger(logger_); m_mpc->setClock(clock_); + + setupDiag(); } MpcLateralController::~MpcLateralController() @@ -227,6 +232,24 @@ std::shared_ptr MpcLateralController::createSteerOffset return steering_offset_; } +void MpcLateralController::setStatus(diagnostic_updater::DiagnosticStatusWrapper & stat) +{ + if (m_is_mpc_solved) { + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "MPC succeeded."); + } else { + const std::string error_msg = "The MPC solver failed. Call MRM to stop the car."; + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::ERROR, error_msg); + } +} + +void MpcLateralController::setupDiag() +{ + auto & d = diag_updater_; + d->setHardwareID("mpc_lateral_controller"); + + d->add("MPC_solve_checker", [&](auto & stat) { setStatus(stat); }); +} + trajectory_follower::LateralOutput MpcLateralController::run( trajectory_follower::InputData const & input_data) { @@ -255,6 +278,10 @@ trajectory_follower::LateralOutput MpcLateralController::run( const bool is_mpc_solved = m_mpc->calculateMPC( m_current_steering, m_current_kinematic_state, ctrl_cmd, predicted_traj, debug_values); + m_is_mpc_solved = is_mpc_solved; // for diagnostic updater + + diag_updater_->force_update(); + // reset previous MPC result // Note: When a large deviation from the trajectory occurs, the optimization stops and // the vehicle will return to the path by re-planning the trajectory or external operation. diff --git a/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp b/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp index 06873c31cc6cc..21d58748d31fa 100644 --- a/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp +++ b/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp @@ -30,6 +30,7 @@ #include #include #include +#include #include "autoware_control_msgs/msg/control.hpp" #include "autoware_control_msgs/msg/longitudinal.hpp" @@ -73,6 +74,10 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node double timeout_thr_sec_; boost::optional longitudinal_output_{boost::none}; + std::shared_ptr diag_updater_ = + std::make_shared( + this); // Diagnostic updater for publishing diagnostic data. + std::shared_ptr longitudinal_controller_; std::shared_ptr lateral_controller_; diff --git a/control/autoware_trajectory_follower_node/src/controller_node.cpp b/control/autoware_trajectory_follower_node/src/controller_node.cpp index 7876a38247bc9..274da6e9a5534 100644 --- a/control/autoware_trajectory_follower_node/src/controller_node.cpp +++ b/control/autoware_trajectory_follower_node/src/controller_node.cpp @@ -39,7 +39,8 @@ Controller::Controller(const rclcpp::NodeOptions & node_options) : Node("control getLateralControllerMode(declare_parameter("lateral_controller_mode")); switch (lateral_controller_mode) { case LateralControllerMode::MPC: { - lateral_controller_ = std::make_shared(*this); + lateral_controller_ = + std::make_shared(*this, diag_updater_); break; } case LateralControllerMode::PURE_PURSUIT: { From 1d3a0947854e1385033e0e186e7172c403b60fcb Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 19 Jun 2024 15:38:15 +0900 Subject: [PATCH 021/217] fix(autoware_obstacle_cruise_planner): fix assignBoolToFloat warning (#7541) * fix(autoware_obstacle_cruise_planner): fix assignBoolToFloat warning Signed-off-by: Ryuta Kambe * delete unnecessary file Signed-off-by: Ryuta Kambe * style(pre-commit): autofix --------- Signed-off-by: Ryuta Kambe Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- planning/autoware_obstacle_cruise_planner/src/node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/autoware_obstacle_cruise_planner/src/node.cpp b/planning/autoware_obstacle_cruise_planner/src/node.cpp index 031e58797364e..b40523c6a0d10 100644 --- a/planning/autoware_obstacle_cruise_planner/src/node.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/node.cpp @@ -1209,8 +1209,8 @@ std::optional ObstacleCruisePlannerNode::createStopObstacle( // NOTE: Dynamic obstacles for stop are crossing ego's trajectory with high speed, // and the collision between ego and obstacles are within the margin threshold. const bool is_obstacle_crossing = isObstacleCrossing(traj_points, obstacle); - const double has_high_speed = p.crossing_obstacle_velocity_threshold < - std::hypot(obstacle.twist.linear.x, obstacle.twist.linear.y); + const bool has_high_speed = p.crossing_obstacle_velocity_threshold < + std::hypot(obstacle.twist.linear.x, obstacle.twist.linear.y); if (is_obstacle_crossing && has_high_speed) { // Get highest confidence predicted path const auto resampled_predicted_path = resampleHighestConfidencePredictedPath( From 4da27a86fa9e340158aad27cb9649e1b28b989ce Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 19 Jun 2024 15:41:33 +0900 Subject: [PATCH 022/217] fix(learning_based_vehicle_model): fix constVariablePointer warning (#7575) * fix constVariablePointer warning Signed-off-by: Ryuta Kambe * add reference Signed-off-by: Ryuta Kambe --------- Signed-off-by: Ryuta Kambe --- .../src/model_connections_helpers.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulator/learning_based_vehicle_model/src/model_connections_helpers.cpp b/simulator/learning_based_vehicle_model/src/model_connections_helpers.cpp index 09f7359af45bf..bbd8bf7ffb546 100644 --- a/simulator/learning_based_vehicle_model/src/model_connections_helpers.cpp +++ b/simulator/learning_based_vehicle_model/src/model_connections_helpers.cpp @@ -32,7 +32,7 @@ std::vector createConnectionsMap( std::vector connection_map; // index in "connection_map" is index in "connection_names_2" and value in "connection_map" is // index in "connection_names_1" - for (auto name_2 : connection_names_2) { + for (const auto & name_2 : connection_names_2) { int mapped_idx = -1; // -1 means that we cannot create a connection between some signals for (std::size_t NAME_1_IDX = 0; NAME_1_IDX < connection_names_1.size(); NAME_1_IDX++) { if (strcmp(name_2, connection_names_1[NAME_1_IDX]) == 0) { // 0 means strings are the same From 0a2f1e34bf69b8fd466a2edba55df31860563bfe Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 19 Jun 2024 16:17:14 +0900 Subject: [PATCH 023/217] fix(net_monitor): fix cppcheck warnings (#7573) * fix unusedVariable warning Signed-off-by: Ryuta Kambe * fix unusedVariable warning Signed-off-by: Ryuta Kambe * fix variableScope warning Signed-off-by: Ryuta Kambe * fix unreadVariable warning Signed-off-by: Ryuta Kambe * fix Signed-off-by: Ryuta Kambe --------- Signed-off-by: Ryuta Kambe --- system/system_monitor/src/net_monitor/net_monitor.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/system/system_monitor/src/net_monitor/net_monitor.cpp b/system/system_monitor/src/net_monitor/net_monitor.cpp index 0b5bc4c1ee7ec..db2e23a44215a 100644 --- a/system/system_monitor/src/net_monitor/net_monitor.cpp +++ b/system/system_monitor/src/net_monitor/net_monitor.cpp @@ -156,8 +156,6 @@ void NetMonitor::check_usage(diagnostic_updater::DiagnosticStatusWrapper & statu int level = DiagStatus::OK; int index = 0; - std::string error_str; - std::vector interface_names; for (const auto & network : network_list_) { // Skip if network is not supported @@ -282,7 +280,6 @@ void NetMonitor::check_reassembles_failed(diagnostic_updater::DiagnosticStatusWr int whole_level = DiagStatus::OK; std::string error_message; uint64_t total_reassembles_failed = 0; - uint64_t unit_reassembles_failed = 0; if (get_reassembles_failed(total_reassembles_failed)) { reassembles_failed_queue_.push_back(total_reassembles_failed - last_reassembles_failed_); @@ -290,6 +287,7 @@ void NetMonitor::check_reassembles_failed(diagnostic_updater::DiagnosticStatusWr reassembles_failed_queue_.pop_front(); } + uint64_t unit_reassembles_failed = 0; for (auto reassembles_failed : reassembles_failed_queue_) { unit_reassembles_failed += reassembles_failed; } @@ -452,9 +450,9 @@ void NetMonitor::update_network_capacity(NetworkInfomation & network, int socket // NOLINTNEXTLINE [cppcoreguidelines-pro-type-union-access] strncpy(request.ifr_name, network.interface_name.c_str(), IFNAMSIZ - 1); + ether_request.cmd = ETHTOOL_GSET; request.ifr_data = (caddr_t)ðer_request; // NOLINT [cppcoreguidelines-pro-type-cstyle-cast] - ether_request.cmd = ETHTOOL_GSET; if (ioctl(socket, SIOCETHTOOL, &request) >= 0) { network.speed = ether_request.speed; return; From 8837b1fa9fc61506688801d857462c2d58df05da Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 19 Jun 2024 16:33:01 +0900 Subject: [PATCH 024/217] fix(autoware_path_sampler): fix unusedVariable warning (#7584) fix unusedVariable warning Signed-off-by: Ryuta Kambe --- .../sampling_based_planner/autoware_path_sampler/src/node.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp b/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp index cd67a07260949..0d68ac455ff94 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp +++ b/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp @@ -523,7 +523,6 @@ autoware::sampler_common::Path PathSampler::generatePath(const PlannerData & pla std::vector PathSampler::generateTrajectoryPoints(const PlannerData & planner_data) { - std::vector trajectory; time_keeper_ptr_->tic(__func__); const auto path = generatePath(planner_data); return trajectory_utils::convertToTrajectoryPoints(path); From b284599e61d2824049ae76f907ca698abc9bccbe Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 19 Jun 2024 16:33:22 +0900 Subject: [PATCH 025/217] fix(autoware_velocity_smoother): fix unusedVariable warning (#7585) fix unusedVariable warning Signed-off-by: Ryuta Kambe --- planning/autoware_velocity_smoother/src/trajectory_utils.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/planning/autoware_velocity_smoother/src/trajectory_utils.cpp b/planning/autoware_velocity_smoother/src/trajectory_utils.cpp index 51a2be57ebe02..94fa668fa576c 100644 --- a/planning/autoware_velocity_smoother/src/trajectory_utils.cpp +++ b/planning/autoware_velocity_smoother/src/trajectory_utils.cpp @@ -300,7 +300,6 @@ bool calcStopDistWithJerkConstraints( } double x, v, a, j; - std::tuple state; switch (type) { case AccelerationType::TRAPEZOID: { From 51045e9090d3d68c2e2a3defbc8c4dbb1e91873e Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Wed, 19 Jun 2024 17:04:27 +0900 Subject: [PATCH 026/217] feat(autonomous_emergency_braking): add predicted object support for aeb (#7548) * add polling sub to predicted objects Signed-off-by: Daniel Sanchez * WIP requires changing path frame to map Signed-off-by: Daniel Sanchez * add parameters and reuse predicted obj speed Signed-off-by: Daniel Sanchez * introduce early break to reduce computation time Signed-off-by: Daniel Sanchez * resolve merge conflicts Signed-off-by: Daniel Sanchez * fix guard Signed-off-by: Daniel Sanchez * remove unused declaration Signed-off-by: Daniel Sanchez * fix include Signed-off-by: Daniel Sanchez * fix include issues Signed-off-by: Daniel Sanchez * remove inline Signed-off-by: Daniel Sanchez * delete unused dependencies Signed-off-by: Daniel Sanchez * add utils.cpp Signed-off-by: Daniel Sanchez * remove _ for non member variable Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../CMakeLists.txt | 7 + .../autonomous_emergency_braking.param.yaml | 2 + .../autonomous_emergency_braking/node.hpp | 20 ++ .../autonomous_emergency_braking/utils.hpp | 88 +++++++++ ...re_autonomous_emergency_braking.launch.xml | 2 + .../src/node.cpp | 174 +++++++++++++++--- .../src/utils.cpp | 150 +++++++++++++++ .../launch/control.launch.py | 1 + 8 files changed, 417 insertions(+), 27 deletions(-) create mode 100644 control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp create mode 100644 control/autoware_autonomous_emergency_braking/src/utils.cpp diff --git a/control/autoware_autonomous_emergency_braking/CMakeLists.txt b/control/autoware_autonomous_emergency_braking/CMakeLists.txt index 7f38e4387b452..85290c6c66730 100644 --- a/control/autoware_autonomous_emergency_braking/CMakeLists.txt +++ b/control/autoware_autonomous_emergency_braking/CMakeLists.txt @@ -12,11 +12,18 @@ include_directories( ${PCL_INCLUDE_DIRS} ) +ament_auto_add_library(autoware_autonomous_emergency_braking_helpers SHARED + include/autoware/autonomous_emergency_braking/utils.hpp + src/utils.cpp +) + set(AEB_NODE ${PROJECT_NAME}_node) ament_auto_add_library(${AEB_NODE} SHARED + include/autoware/autonomous_emergency_braking/node.hpp src/node.cpp ) +target_link_libraries(${AEB_NODE} autoware_autonomous_emergency_braking_helpers) rclcpp_components_register_node(${AEB_NODE} PLUGIN "autoware::motion::control::autonomous_emergency_braking::AEB" EXECUTABLE ${PROJECT_NAME} diff --git a/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml b/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml index 4233f8b6bebcb..344d076197170 100644 --- a/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml +++ b/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml @@ -3,6 +3,8 @@ # Ego path calculation use_predicted_trajectory: true use_imu_path: false + use_pointcloud_data: true + use_predicted_object_data: true use_object_velocity_calculation: true min_generated_path_length: 0.5 imu_prediction_time_horizon: 1.5 diff --git a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp index 1096def70d483..2a1156adb41a0 100644 --- a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp +++ b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp @@ -23,6 +23,7 @@ #include #include +#include #include #include #include @@ -68,6 +69,9 @@ using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; using Path = std::vector; using Vector3 = geometry_msgs::msg::Vector3; +using autoware_perception_msgs::msg::PredictedObject; +using autoware_perception_msgs::msg::PredictedObjects; + struct ObjectData { rclcpp::Time stamp; @@ -176,6 +180,13 @@ class CollisionDataKeeper std::optional calcObjectSpeedFromHistory( const ObjectData & closest_object, const Path & path, const double current_ego_speed) { + // in case the object comes from predicted objects info, we reuse the speed. + if (closest_object.velocity > 0.0) { + this->setPreviousObjectData(closest_object); + this->updateVelocityHistory(closest_object.velocity, closest_object.stamp); + return this->getMedianObstacleVelocity(); + } + if (this->checkPreviousObjectDataExpired()) { this->setPreviousObjectData(closest_object); this->resetVelocityHistory(); @@ -243,6 +254,8 @@ class AEB : public rclcpp::Node autoware_universe_utils::InterProcessPollingSubscriber sub_imu_{this, "~/input/imu"}; autoware_universe_utils::InterProcessPollingSubscriber sub_predicted_traj_{ this, "~/input/predicted_trajectory"}; + autoware_universe_utils::InterProcessPollingSubscriber predicted_objects_sub_{ + this, "~/input/objects"}; autoware_universe_utils::InterProcessPollingSubscriber sub_autoware_state_{ this, "/autoware/state"}; // publisher @@ -275,6 +288,10 @@ class AEB : public rclcpp::Node std::vector & objects, const pcl::PointCloud::Ptr obstacle_points_ptr); + void createObjectDataUsingPredictedObjects( + const Path & ego_path, const std::vector & ego_polys, + std::vector & objects); + void cropPointCloudWithEgoFootprintPath( const std::vector & ego_polys, pcl::PointCloud::Ptr filtered_objects); @@ -298,6 +315,7 @@ class AEB : public rclcpp::Node VelocityReport::ConstSharedPtr current_velocity_ptr_{nullptr}; Vector3::SharedPtr angular_velocity_ptr_{nullptr}; Trajectory::ConstSharedPtr predicted_traj_ptr_{nullptr}; + PredictedObjects::ConstSharedPtr predicted_objects_ptr_{nullptr}; AutowareState::ConstSharedPtr autoware_state_{nullptr}; tf2_ros::Buffer tf_buffer_{get_clock()}; @@ -313,6 +331,8 @@ class AEB : public rclcpp::Node bool publish_debug_pointcloud_; bool use_predicted_trajectory_; bool use_imu_path_; + bool use_pointcloud_data_; + bool use_predicted_object_data_; bool use_object_velocity_calculation_; double path_footprint_extra_margin_; double detection_range_min_height_; diff --git a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp new file mode 100644 index 0000000000000..b046acd9153e9 --- /dev/null +++ b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp @@ -0,0 +1,88 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__AUTONOMOUS_EMERGENCY_BRAKING__UTILS_HPP_ +#define AUTOWARE__AUTONOMOUS_EMERGENCY_BRAKING__UTILS_HPP_ + +#include + +#include +#include +#include + +#include + +#include +#ifdef ROS_DISTRO_GALACTIC +#include +#include +#else +#include + +#include +#endif + +#include + +namespace autoware::motion::control::autonomous_emergency_braking::utils +{ +using autoware_perception_msgs::msg::PredictedObject; +using autoware_perception_msgs::msg::PredictedObjects; +using autoware_universe_utils::Point2d; +using autoware_universe_utils::Polygon2d; +using geometry_msgs::msg::Point; +using geometry_msgs::msg::Pose; +using geometry_msgs::msg::TransformStamped; + +/** + * @brief Apply a transform to a predicted object + * @param input the predicted object + * @param transform_stamped the tf2 transform + */ +PredictedObject transformObjectFrame( + const PredictedObject & input, geometry_msgs::msg::TransformStamped transform_stamped); + +/** + * @brief Get the predicted objects polygon as a geometry polygon + * @param current_pose the predicted object's pose + * @param obj_shape the object's shape + */ +Polygon2d convertPolygonObjectToGeometryPolygon( + const Pose & current_pose, const autoware_perception_msgs::msg::Shape & obj_shape); + +/** + * @brief Get the predicted objects cylindrical shape as a geometry polygon + * @param current_pose the predicted object's pose + * @param obj_shape the object's shape + */ +Polygon2d convertCylindricalObjectToGeometryPolygon( + const Pose & current_pose, const autoware_perception_msgs::msg::Shape & obj_shape); + +/** + * @brief Get the predicted objects bounding box shape as a geometry polygon + * @param current_pose the predicted object's pose + * @param obj_shape the object's shape + */ +Polygon2d convertBoundingBoxObjectToGeometryPolygon( + const Pose & current_pose, const double & base_to_front, const double & base_to_rear, + const double & base_to_width); + +/** + * @brief Get the predicted object's shape as a geometry polygon + * @param obj the object + */ +Polygon2d convertObjToPolygon(const PredictedObject & obj); +} // namespace autoware::motion::control::autonomous_emergency_braking::utils + +#endif // AUTOWARE__AUTONOMOUS_EMERGENCY_BRAKING__UTILS_HPP_ diff --git a/control/autoware_autonomous_emergency_braking/launch/autoware_autonomous_emergency_braking.launch.xml b/control/autoware_autonomous_emergency_braking/launch/autoware_autonomous_emergency_braking.launch.xml index 75b1a9dcf822d..fe0df41ca89c7 100644 --- a/control/autoware_autonomous_emergency_braking/launch/autoware_autonomous_emergency_braking.launch.xml +++ b/control/autoware_autonomous_emergency_braking/launch/autoware_autonomous_emergency_braking.launch.xml @@ -5,6 +5,7 @@ + @@ -15,5 +16,6 @@ + diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index 29ba9474b6e8e..e898ff4788da4 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/autonomous_emergency_braking/node.hpp" - +#include +#include #include #include #include @@ -21,7 +21,11 @@ #include #include +#include + #include +#include +#include #include #include @@ -46,6 +50,7 @@ namespace autoware::motion::control::autonomous_emergency_braking { +using autoware::motion::control::autonomous_emergency_braking::utils::convertObjToPolygon; using diagnostic_msgs::msg::DiagnosticStatus; namespace bg = boost::geometry; @@ -100,7 +105,7 @@ Polygon2d createPolygon( Polygon2d hull_polygon; bg::convex_hull(polygon, hull_polygon); - + bg::correct(hull_polygon); return hull_polygon; } @@ -124,6 +129,8 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) publish_debug_pointcloud_ = declare_parameter("publish_debug_pointcloud"); use_predicted_trajectory_ = declare_parameter("use_predicted_trajectory"); use_imu_path_ = declare_parameter("use_imu_path"); + use_pointcloud_data_ = declare_parameter("use_pointcloud_data"); + use_predicted_object_data_ = declare_parameter("use_predicted_object_data"); use_object_velocity_calculation_ = declare_parameter("use_object_velocity_calculation"); path_footprint_extra_margin_ = declare_parameter("path_footprint_extra_margin"); detection_range_min_height_ = declare_parameter("detection_range_min_height"); @@ -172,6 +179,8 @@ rcl_interfaces::msg::SetParametersResult AEB::onParameter( updateParam(parameters, "publish_debug_pointcloud", publish_debug_pointcloud_); updateParam(parameters, "use_predicted_trajectory", use_predicted_trajectory_); updateParam(parameters, "use_imu_path", use_imu_path_); + updateParam(parameters, "use_pointcloud_data", use_pointcloud_data_); + updateParam(parameters, "use_predicted_object_data", use_predicted_object_data_); updateParam( parameters, "use_object_velocity_calculation", use_object_velocity_calculation_); updateParam(parameters, "path_footprint_extra_margin", path_footprint_extra_margin_); @@ -298,13 +307,31 @@ bool AEB::fetchLatestData() return missing("ego velocity"); } - const auto pointcloud_ptr = sub_point_cloud_.takeData(); - if (!pointcloud_ptr) { - return missing("object pointcloud message"); + if (use_pointcloud_data_) { + const auto pointcloud_ptr = sub_point_cloud_.takeData(); + if (!pointcloud_ptr) { + return missing("object pointcloud message"); + } + + onPointCloud(pointcloud_ptr); + if (!obstacle_ros_pointcloud_ptr_) { + return missing("object pointcloud"); + } + } else { + obstacle_ros_pointcloud_ptr_.reset(); + } + + if (use_predicted_object_data_) { + predicted_objects_ptr_ = predicted_objects_sub_.takeData(); + if (!predicted_objects_ptr_) { + return missing("predicted objects"); + } + } else { + predicted_objects_ptr_.reset(); } - onPointCloud(pointcloud_ptr); - if (!obstacle_ros_pointcloud_ptr_) { - return missing("object pointcloud"); + + if (!obstacle_ros_pointcloud_ptr_ && !predicted_objects_ptr_) { + return missing("object detection method (pointcloud or predicted objects)"); } const auto imu_ptr = sub_imu_.takeData(); @@ -381,27 +408,33 @@ bool AEB::checkCollision(MarkerArray & debug_markers) const auto & path, const colorTuple & debug_colors, const std::string & debug_ns, pcl::PointCloud::Ptr filtered_objects) { - // Crop out Pointcloud using an extra wide ego path - const auto expanded_ego_polys = - generatePathFootprint(path, expand_width_ + path_footprint_extra_margin_); - cropPointCloudWithEgoFootprintPath(expanded_ego_polys, filtered_objects); - // Check which points of the cropped point cloud are on the ego path, and get the closest one - std::vector objects_from_point_clusters; const auto ego_polys = generatePathFootprint(path, expand_width_); - const auto current_time = obstacle_ros_pointcloud_ptr_->header.stamp; - createObjectDataUsingPointCloudClusters( - path, ego_polys, current_time, objects_from_point_clusters, filtered_objects); + auto objects = std::invoke([&]() { + std::vector objects; + // Crop out Pointcloud using an extra wide ego path + if (use_pointcloud_data_) { + const auto expanded_ego_polys = + generatePathFootprint(path, expand_width_ + path_footprint_extra_margin_); + cropPointCloudWithEgoFootprintPath(expanded_ego_polys, filtered_objects); + const auto current_time = obstacle_ros_pointcloud_ptr_->header.stamp; + createObjectDataUsingPointCloudClusters( + path, ego_polys, current_time, objects, filtered_objects); + } + if (use_predicted_object_data_) { + createObjectDataUsingPredictedObjects(path, ego_polys, objects); + } + return objects; + }); // Get only the closest object and calculate its speed const auto closest_object_point = std::invoke([&]() -> std::optional { - const auto closest_object_point_itr = std::min_element( - objects_from_point_clusters.begin(), objects_from_point_clusters.end(), - [](const auto & o1, const auto & o2) { + const auto closest_object_point_itr = + std::min_element(objects.begin(), objects.end(), [](const auto & o1, const auto & o2) { return o1.distance_to_object < o2.distance_to_object; }); - if (closest_object_point_itr == objects_from_point_clusters.end()) { + if (closest_object_point_itr == objects.end()) { return std::nullopt; } const auto closest_object_speed = (use_object_velocity_calculation_) @@ -419,8 +452,8 @@ bool AEB::checkCollision(MarkerArray & debug_markers) { const auto [color_r, color_g, color_b, color_a] = debug_colors; addMarker( - this->get_clock()->now(), path, ego_polys, objects_from_point_clusters, - closest_object_point, color_r, color_g, color_b, color_a, debug_ns, debug_markers); + this->get_clock()->now(), path, ego_polys, objects, closest_object_point, color_r, color_g, + color_b, color_a, debug_ns, debug_markers); } // check collision using rss distance return (closest_object_point.has_value()) @@ -462,9 +495,9 @@ bool AEB::checkCollision(MarkerArray & debug_markers) // Debug print if (!filtered_objects->empty() && publish_debug_pointcloud_) { - const auto filtered_objects_ros_pointcloud_ptr_ = std::make_shared(); - pcl::toROSMsg(*filtered_objects, *filtered_objects_ros_pointcloud_ptr_); - pub_obstacle_pointcloud_->publish(*filtered_objects_ros_pointcloud_ptr_); + const auto filtered_objects_ros_pointcloud_ptr = std::make_shared(); + pcl::toROSMsg(*filtered_objects, *filtered_objects_ros_pointcloud_ptr); + pub_obstacle_pointcloud_->publish(*filtered_objects_ros_pointcloud_ptr); } return has_collision; } @@ -577,6 +610,93 @@ std::vector AEB::generatePathFootprint( return polygons; } +void AEB::createObjectDataUsingPredictedObjects( + const Path & ego_path, const std::vector & ego_polys, + std::vector & object_data_vector) +{ + if (predicted_objects_ptr_->objects.empty()) return; + + const double current_ego_speed = current_velocity_ptr_->longitudinal_velocity; + const auto & objects = predicted_objects_ptr_->objects; + const auto & stamp = predicted_objects_ptr_->header.stamp; + + // Ego position + const auto current_p = [&]() { + const auto & first_point_of_path = ego_path.front(); + const auto & p = first_point_of_path.position; + return autoware_universe_utils::createPoint(p.x, p.y, p.z); + }(); + + auto get_object_tangent_velocity = + [&](const PredictedObject & predicted_object, const auto & obj_pose) { + const double obj_vel_norm = std::hypot( + predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x, + predicted_object.kinematics.initial_twist_with_covariance.twist.linear.y); + + const auto obj_yaw = tf2::getYaw(obj_pose.orientation); + const auto obj_idx = autoware_motion_utils::findNearestIndex(ego_path, obj_pose.position); + const auto path_yaw = (current_ego_speed > 0.0) + ? tf2::getYaw(ego_path.at(obj_idx).orientation) + : tf2::getYaw(ego_path.at(obj_idx).orientation) + M_PI; + return obj_vel_norm * std::cos(obj_yaw - path_yaw); + }; + + geometry_msgs::msg::TransformStamped transform_stamped{}; + try { + transform_stamped = tf_buffer_.lookupTransform( + "base_link", predicted_objects_ptr_->header.frame_id, stamp, + rclcpp::Duration::from_seconds(0.5)); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR_STREAM(get_logger(), "[AEB] Failed to look up transform from base_link to map"); + return; + } + + // Check which objects collide with the ego footprints + std::for_each(objects.begin(), objects.end(), [&](const auto & predicted_object) { + // get objects in base_link frame + const auto t_predicted_object = + utils::transformObjectFrame(predicted_object, transform_stamped); + const auto & obj_pose = t_predicted_object.kinematics.initial_pose_with_covariance.pose; + const auto obj_poly = convertObjToPolygon(t_predicted_object); + const double obj_tangent_velocity = get_object_tangent_velocity(t_predicted_object, obj_pose); + + for (const auto & ego_poly : ego_polys) { + // check collision with 2d polygon + std::vector collision_points_bg; + bg::intersection(ego_poly, obj_poly, collision_points_bg); + if (collision_points_bg.empty()) continue; + + // Create an object for each intersection point + bool collision_points_added{false}; + for (const auto & collision_point : collision_points_bg) { + const auto obj_position = + autoware_universe_utils::createPoint(collision_point.x(), collision_point.y(), 0.0); + const double obj_arc_length = + autoware_motion_utils::calcSignedArcLength(ego_path, current_p, obj_position); + if (std::isnan(obj_arc_length)) continue; + + // If the object is behind the ego, we need to use the backward long offset. The + // distance should be a positive number in any case + const bool is_object_in_front_of_ego = obj_arc_length > 0.0; + const double dist_ego_to_object = + (is_object_in_front_of_ego) ? obj_arc_length - vehicle_info_.max_longitudinal_offset_m + : obj_arc_length + vehicle_info_.min_longitudinal_offset_m; + + ObjectData obj; + obj.stamp = stamp; + obj.position = obj_position; + obj.velocity = (obj_tangent_velocity > 0.0) ? obj_tangent_velocity : 0.0; + obj.distance_to_object = std::abs(dist_ego_to_object); + object_data_vector.push_back(obj); + collision_points_added = true; + } + // The ego polygons are in order, so the first intersection points found are the closest + // points. It is not necessary to continue iterating the ego polys for the same object. + if (collision_points_added) break; + } + }); +} + void AEB::createObjectDataUsingPointCloudClusters( const Path & ego_path, const std::vector & ego_polys, const rclcpp::Time & stamp, std::vector & objects, const pcl::PointCloud::Ptr obstacle_points_ptr) diff --git a/control/autoware_autonomous_emergency_braking/src/utils.cpp b/control/autoware_autonomous_emergency_braking/src/utils.cpp new file mode 100644 index 0000000000000..81f6afee31172 --- /dev/null +++ b/control/autoware_autonomous_emergency_braking/src/utils.cpp @@ -0,0 +1,150 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +namespace autoware::motion::control::autonomous_emergency_braking::utils +{ +using autoware_perception_msgs::msg::PredictedObject; +using autoware_perception_msgs::msg::PredictedObjects; +using autoware_universe_utils::Point2d; +using autoware_universe_utils::Polygon2d; +using geometry_msgs::msg::Point; +using geometry_msgs::msg::Pose; +using geometry_msgs::msg::TransformStamped; +using geometry_msgs::msg::Vector3; + +PredictedObject transformObjectFrame( + const PredictedObject & input, geometry_msgs::msg::TransformStamped transform_stamped) +{ + PredictedObject output = input; + const auto & linear_twist = input.kinematics.initial_twist_with_covariance.twist.linear; + const auto & angular_twist = input.kinematics.initial_twist_with_covariance.twist.angular; + const auto & pose = input.kinematics.initial_pose_with_covariance.pose; + + geometry_msgs::msg::Pose t_pose; + Vector3 t_linear_twist; + Vector3 t_angular_twist; + + tf2::doTransform(pose, t_pose, transform_stamped); + tf2::doTransform(linear_twist, t_linear_twist, transform_stamped); + tf2::doTransform(angular_twist, t_angular_twist, transform_stamped); + + output.kinematics.initial_pose_with_covariance.pose = t_pose; + output.kinematics.initial_twist_with_covariance.twist.linear = t_linear_twist; + output.kinematics.initial_twist_with_covariance.twist.angular = t_angular_twist; + return output; +} + +Polygon2d convertPolygonObjectToGeometryPolygon( + const Pose & current_pose, const autoware_perception_msgs::msg::Shape & obj_shape) +{ + Polygon2d object_polygon; + tf2::Transform tf_map2obj; + fromMsg(current_pose, tf_map2obj); + const auto obj_points = obj_shape.footprint.points; + object_polygon.outer().reserve(obj_points.size() + 1); + for (const auto & obj_point : obj_points) { + tf2::Vector3 obj(obj_point.x, obj_point.y, obj_point.z); + tf2::Vector3 tf_obj = tf_map2obj * obj; + object_polygon.outer().emplace_back(tf_obj.x(), tf_obj.y()); + } + object_polygon.outer().push_back(object_polygon.outer().front()); + boost::geometry::correct(object_polygon); + + return object_polygon; +} + +Polygon2d convertCylindricalObjectToGeometryPolygon( + const Pose & current_pose, const autoware_perception_msgs::msg::Shape & obj_shape) +{ + Polygon2d object_polygon; + + const double obj_x = current_pose.position.x; + const double obj_y = current_pose.position.y; + + constexpr int N = 20; + const double r = obj_shape.dimensions.x / 2; + object_polygon.outer().reserve(N + 1); + for (int i = 0; i < N; ++i) { + object_polygon.outer().emplace_back( + obj_x + r * std::cos(2.0 * M_PI / N * i), obj_y + r * std::sin(2.0 * M_PI / N * i)); + } + + object_polygon.outer().push_back(object_polygon.outer().front()); + boost::geometry::correct(object_polygon); + + return object_polygon; +} + +Polygon2d convertBoundingBoxObjectToGeometryPolygon( + const Pose & current_pose, const double & base_to_front, const double & base_to_rear, + const double & base_to_width) +{ + const auto mapped_point = [](const double & length_scalar, const double & width_scalar) { + tf2::Vector3 map; + map.setX(length_scalar); + map.setY(width_scalar); + map.setZ(0.0); + map.setW(1.0); + return map; + }; + + // set vertices at map coordinate + const tf2::Vector3 p1_map = std::invoke(mapped_point, base_to_front, -base_to_width); + const tf2::Vector3 p2_map = std::invoke(mapped_point, base_to_front, base_to_width); + const tf2::Vector3 p3_map = std::invoke(mapped_point, -base_to_rear, base_to_width); + const tf2::Vector3 p4_map = std::invoke(mapped_point, -base_to_rear, -base_to_width); + + // transform vertices from map coordinate to object coordinate + tf2::Transform tf_map2obj; + tf2::fromMsg(current_pose, tf_map2obj); + const tf2::Vector3 p1_obj = tf_map2obj * p1_map; + const tf2::Vector3 p2_obj = tf_map2obj * p2_map; + const tf2::Vector3 p3_obj = tf_map2obj * p3_map; + const tf2::Vector3 p4_obj = tf_map2obj * p4_map; + + Polygon2d object_polygon; + object_polygon.outer().reserve(5); + object_polygon.outer().emplace_back(p1_obj.x(), p1_obj.y()); + object_polygon.outer().emplace_back(p2_obj.x(), p2_obj.y()); + object_polygon.outer().emplace_back(p3_obj.x(), p3_obj.y()); + object_polygon.outer().emplace_back(p4_obj.x(), p4_obj.y()); + + object_polygon.outer().push_back(object_polygon.outer().front()); + boost::geometry::correct(object_polygon); + + return object_polygon; +} + +Polygon2d convertObjToPolygon(const PredictedObject & obj) +{ + Polygon2d object_polygon{}; + if (obj.shape.type == autoware_perception_msgs::msg::Shape::CYLINDER) { + object_polygon = utils::convertCylindricalObjectToGeometryPolygon( + obj.kinematics.initial_pose_with_covariance.pose, obj.shape); + } else if (obj.shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { + const double & length_m = obj.shape.dimensions.x / 2; + const double & width_m = obj.shape.dimensions.y / 2; + object_polygon = utils::convertBoundingBoxObjectToGeometryPolygon( + obj.kinematics.initial_pose_with_covariance.pose, length_m, length_m, width_m); + } else if (obj.shape.type == autoware_perception_msgs::msg::Shape::POLYGON) { + object_polygon = utils::convertPolygonObjectToGeometryPolygon( + obj.kinematics.initial_pose_with_covariance.pose, obj.shape); + } else { + throw std::runtime_error("Unsupported shape type"); + } + return object_polygon; +} +} // namespace autoware::motion::control::autonomous_emergency_braking::utils diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index a61f29014dcce..1cf3cb5b44656 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -148,6 +148,7 @@ def launch_setup(context, *args, **kwargs): ("~/input/velocity", "/vehicle/status/velocity_status"), ("~/input/imu", "/sensing/imu/imu_data"), ("~/input/odometry", "/localization/kinematic_state"), + ("~/input/objects", "/perception/object_recognition/objects"), ( "~/input/predicted_trajectory", "/control/trajectory_follower/lateral/predicted_trajectory", From 0eefe2d4c0cbd33931bfeaabf76e194838d29aba Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Wed, 19 Jun 2024 11:19:35 +0200 Subject: [PATCH 027/217] refactor(behavior_velocity_no_drivable_lane_module): prefix package and namespace with autoware (#7469) Signed-off-by: Esteve Fernandez --- .github/CODEOWNERS | 2 +- planning/.pages | 2 +- .../CMakeLists.txt | 2 +- .../README.md | 0 .../config/no_drivable_lane.param.yaml | 0 .../docs/no_drivable_lane_design.svg | 0 .../docs/no_drivable_lane_scenarios.svg | 0 .../package.xml | 4 ++-- .../plugins.xml | 2 +- .../src/debug.cpp | 0 .../src/manager.cpp | 0 .../src/manager.hpp | 0 .../src/scene.cpp | 0 .../src/scene.hpp | 0 .../src/util.cpp | 0 .../src/util.hpp | 0 .../autoware_behavior_velocity_planner/package.xml | 2 +- .../test/src/test_node_interface.cpp | 2 +- 18 files changed, 8 insertions(+), 8 deletions(-) rename planning/behavior_velocity_planner/{behavior_velocity_no_drivable_lane_module => autoware_behavior_velocity_no_drivable_lane_module}/CMakeLists.txt (85%) rename planning/behavior_velocity_planner/{behavior_velocity_no_drivable_lane_module => autoware_behavior_velocity_no_drivable_lane_module}/README.md (100%) rename planning/behavior_velocity_planner/{behavior_velocity_no_drivable_lane_module => autoware_behavior_velocity_no_drivable_lane_module}/config/no_drivable_lane.param.yaml (100%) rename planning/behavior_velocity_planner/{behavior_velocity_no_drivable_lane_module => autoware_behavior_velocity_no_drivable_lane_module}/docs/no_drivable_lane_design.svg (100%) rename planning/behavior_velocity_planner/{behavior_velocity_no_drivable_lane_module => autoware_behavior_velocity_no_drivable_lane_module}/docs/no_drivable_lane_scenarios.svg (100%) rename planning/behavior_velocity_planner/{behavior_velocity_no_drivable_lane_module => autoware_behavior_velocity_no_drivable_lane_module}/package.xml (91%) rename planning/behavior_velocity_planner/{behavior_velocity_no_drivable_lane_module => autoware_behavior_velocity_no_drivable_lane_module}/plugins.xml (70%) rename planning/behavior_velocity_planner/{behavior_velocity_no_drivable_lane_module => autoware_behavior_velocity_no_drivable_lane_module}/src/debug.cpp (100%) rename planning/behavior_velocity_planner/{behavior_velocity_no_drivable_lane_module => autoware_behavior_velocity_no_drivable_lane_module}/src/manager.cpp (100%) rename planning/behavior_velocity_planner/{behavior_velocity_no_drivable_lane_module => autoware_behavior_velocity_no_drivable_lane_module}/src/manager.hpp (100%) rename planning/behavior_velocity_planner/{behavior_velocity_no_drivable_lane_module => autoware_behavior_velocity_no_drivable_lane_module}/src/scene.cpp (100%) rename planning/behavior_velocity_planner/{behavior_velocity_no_drivable_lane_module => autoware_behavior_velocity_no_drivable_lane_module}/src/scene.hpp (100%) rename planning/behavior_velocity_planner/{behavior_velocity_no_drivable_lane_module => autoware_behavior_velocity_no_drivable_lane_module}/src/util.cpp (100%) rename planning/behavior_velocity_planner/{behavior_velocity_no_drivable_lane_module => autoware_behavior_velocity_no_drivable_lane_module}/src/util.hpp (100%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index df8673cd68724..1a6ec09d88d02 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -192,7 +192,7 @@ planning/autoware_behavior_path_side_shift_module/** fumiya.watanabe@tier4.jp ky planning/behavior_path_start_planner_module/** daniel.sanchez@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yuki.takagi@tier4.jp -planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/** ahmed.ebrahim@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/** ahmed.ebrahim@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/** fumiya.watanabe@tier4.jp isamu.takagi@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp diff --git a/planning/.pages b/planning/.pages index bda94919fc352..3c868628198a8 100644 --- a/planning/.pages +++ b/planning/.pages @@ -25,7 +25,7 @@ nav: - 'Crosswalk': planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module - 'Detection Area': planning/behavior_velocity_detection_area_module - 'Intersection': planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module - - 'No Drivable Lane': planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module + - 'No Drivable Lane': planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module - 'No Stopping Area': planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module - 'Occlusion Spot': planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module - 'Run Out': planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module diff --git a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/CMakeLists.txt similarity index 85% rename from planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/CMakeLists.txt rename to planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/CMakeLists.txt index 265b5b637e7ce..cee9e8ca039c9 100644 --- a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(behavior_velocity_no_drivable_lane_module) +project(autoware_behavior_velocity_no_drivable_lane_module) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/README.md b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/README.md similarity index 100% rename from planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/README.md rename to planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/README.md diff --git a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/config/no_drivable_lane.param.yaml b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/config/no_drivable_lane.param.yaml similarity index 100% rename from planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/config/no_drivable_lane.param.yaml rename to planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/config/no_drivable_lane.param.yaml diff --git a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/docs/no_drivable_lane_design.svg b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/docs/no_drivable_lane_design.svg similarity index 100% rename from planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/docs/no_drivable_lane_design.svg rename to planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/docs/no_drivable_lane_design.svg diff --git a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/docs/no_drivable_lane_scenarios.svg b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/docs/no_drivable_lane_scenarios.svg similarity index 100% rename from planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/docs/no_drivable_lane_scenarios.svg rename to planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/docs/no_drivable_lane_scenarios.svg diff --git a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/package.xml similarity index 91% rename from planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/package.xml rename to planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/package.xml index e03a05cfc57c7..81e3e54539bb3 100644 --- a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/package.xml @@ -1,9 +1,9 @@ - behavior_velocity_no_drivable_lane_module + autoware_behavior_velocity_no_drivable_lane_module 0.1.0 - The behavior_velocity_no_drivable_lane_module package + The autoware_behavior_velocity_no_drivable_lane_module package Ahmed Ebrahim Tomoya Kimura diff --git a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/plugins.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/plugins.xml similarity index 70% rename from planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/plugins.xml rename to planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/plugins.xml index e3e9efb254fba..26635e8e24bc1 100644 --- a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/plugins.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/debug.cpp similarity index 100% rename from planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/src/debug.cpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/debug.cpp diff --git a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.cpp similarity index 100% rename from planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/src/manager.cpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.cpp diff --git a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.hpp similarity index 100% rename from planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/src/manager.hpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.hpp diff --git a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp similarity index 100% rename from planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/src/scene.cpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp diff --git a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp similarity index 100% rename from planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/src/scene.hpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp diff --git a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/src/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/util.cpp similarity index 100% rename from planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/src/util.cpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/util.cpp diff --git a/planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/src/util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/util.hpp similarity index 100% rename from planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/src/util.hpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/util.hpp diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml index 0c5088d7c4e1d..24d11eb9d08d5 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml @@ -70,6 +70,7 @@ autoware_behavior_velocity_crosswalk_module autoware_behavior_velocity_detection_area_module autoware_behavior_velocity_intersection_module + autoware_behavior_velocity_no_drivable_lane_module autoware_behavior_velocity_no_stopping_area_module autoware_behavior_velocity_occlusion_spot_module autoware_behavior_velocity_run_out_module @@ -78,7 +79,6 @@ autoware_behavior_velocity_virtual_traffic_light_module autoware_behavior_velocity_walkway_module autoware_lint_common - behavior_velocity_no_drivable_lane_module behavior_velocity_speed_bump_module diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp index a6cff987e30f0..29cd7a215907f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp @@ -107,7 +107,7 @@ std::shared_ptr generateNode() get_behavior_velocity_module_config("stop_line"), get_behavior_velocity_module_config("traffic_light"), get_behavior_velocity_module_config("virtual_traffic_light"), - get_behavior_velocity_module_config_no_prefix("no_drivable_lane")}); + get_behavior_velocity_module_config("no_drivable_lane")}); // TODO(Takagi, Isamu): set launch_modules // TODO(Kyoichi Sugahara) set to true launch_virtual_traffic_light From 8dcddae12bc027d50893842be3ec9e4a7d72108f Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 19 Jun 2024 18:28:17 +0900 Subject: [PATCH 028/217] fix(autoware_behavior_path_start_planner_module): fix duplicateBreak warning (#7583) Signed-off-by: Ryuta Kambe --- .../src/start_planner_module.cpp | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index 7c5030a9c69d3..87e956f51fa1a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -888,20 +888,16 @@ PriorityOrder StartPlannerModule::determinePriorityOrder( order_priority.emplace_back(i, planner); } } - return order_priority; - } - - if (search_priority == "short_back_distance") { + } else if (search_priority == "short_back_distance") { for (size_t i = 0; i < start_pose_candidates_num; i++) { for (const auto & planner : start_planners_) { order_priority.emplace_back(i, planner); } } - return order_priority; + } else { + RCLCPP_ERROR(getLogger(), "Invalid search_priority: %s", search_priority.c_str()); + throw std::domain_error("[start_planner] invalid search_priority"); } - - RCLCPP_ERROR(getLogger(), "Invalid search_priority: %s", search_priority.c_str()); - throw std::domain_error("[start_planner] invalid search_priority"); return order_priority; } From fffb14946829b5e91171880445237979fc796403 Mon Sep 17 00:00:00 2001 From: Kenzo Lobos Tsunekawa Date: Thu, 20 Jun 2024 10:05:59 +0900 Subject: [PATCH 029/217] feat(lidar_centerpoint): accelerated preprocessing for centerpoint (#6989) * feat: accelerated preprocessing for centerpoint Signed-off-by: Kenzo Lobos-Tsunekawa * chore: changed includes to quotes instead of brackets Signed-off-by: Kenzo Lobos-Tsunekawa * chore: fixed variable name Signed-off-by: Kenzo Lobos-Tsunekawa * fix: addressed the case where the points in the cache is over the maximum capacity Signed-off-by: Kenzo Lobos-Tsunekawa * fix: fixed the offset of the output buffer in the kernel Signed-off-by: Kenzo Lobos-Tsunekawa * chore: reimplemented old logic in the pointpainting package since the new centerpoint logic is incompatible Signed-off-by: Kenzo Lobos-Tsunekawa * fix: eigen matrices are column major by default. this commit fixes the code that assumed row-major, implements check for data layout, and updates tests Signed-off-by: Kenzo Lobos-Tsunekawa * chore: fixed missing virtual destructor Signed-off-by: Kenzo Lobos-Tsunekawa --------- Signed-off-by: Kenzo Lobos-Tsunekawa Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> --- .../CMakeLists.txt | 1 + .../pointcloud_densification.hpp | 72 ++++++++++++ .../pointpainting_fusion/voxel_generator.hpp | 22 +++- .../pointcloud_densification.cpp | 103 ++++++++++++++++++ .../pointpainting_fusion/voxel_generator.cpp | 26 +++++ .../lidar_centerpoint/centerpoint_trt.hpp | 17 ++- .../include/lidar_centerpoint/cuda_utils.hpp | 2 +- .../detection_class_remapper.hpp | 8 +- .../lidar_centerpoint/network/network_trt.hpp | 4 +- .../network/scatter_kernel.hpp | 4 +- .../network/tensorrt_wrapper.hpp | 9 +- .../include/lidar_centerpoint/node.hpp | 4 +- .../postprocess/circle_nms_kernel.hpp | 5 +- .../postprocess/postprocess_kernel.hpp | 11 +- .../preprocess/pointcloud_densification.hpp | 27 +++-- .../preprocess/preprocess_kernel.hpp | 8 +- .../preprocess/voxel_generator.hpp | 13 ++- .../include/lidar_centerpoint/ros_utils.hpp | 7 +- .../lidar_centerpoint/lib/centerpoint_trt.cpp | 14 +-- .../lib/detection_class_remapper.cpp | 2 +- .../lib/network/scatter_kernel.cu | 3 +- .../lib/network/tensorrt_wrapper.cpp | 2 +- .../lib/postprocess/circle_nms_kernel.cu | 8 +- .../postprocess/non_maximum_suppression.cpp | 7 +- .../lib/postprocess/postprocess_kernel.cu | 10 +- .../preprocess/pointcloud_densification.cpp | 40 ++++--- .../lib/preprocess/preprocess_kernel.cu | 49 ++++++++- .../lib/preprocess/voxel_generator.cpp | 48 ++++---- perception/lidar_centerpoint/src/node.cpp | 23 ++-- .../test/test_postprocess_kernel.hpp | 18 +-- .../test/test_preprocess_kernel.hpp | 2 +- .../test/test_voxel_generator.cpp | 49 +++++++-- .../test/test_voxel_generator.hpp | 46 ++++---- 33 files changed, 491 insertions(+), 173 deletions(-) create mode 100644 perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/pointcloud_densification.hpp mode change 100755 => 100644 perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/voxel_generator.hpp create mode 100644 perception/image_projection_based_fusion/src/pointpainting_fusion/pointcloud_densification.cpp diff --git a/perception/image_projection_based_fusion/CMakeLists.txt b/perception/image_projection_based_fusion/CMakeLists.txt index 0f4cb7112f74a..b6dfbaf402cc8 100644 --- a/perception/image_projection_based_fusion/CMakeLists.txt +++ b/perception/image_projection_based_fusion/CMakeLists.txt @@ -127,6 +127,7 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) ament_auto_add_library(pointpainting_lib SHARED src/pointpainting_fusion/node.cpp + src/pointpainting_fusion/pointcloud_densification.cpp src/pointpainting_fusion/pointpainting_trt.cpp src/pointpainting_fusion/voxel_generator.cpp ) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/pointcloud_densification.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/pointcloud_densification.hpp new file mode 100644 index 0000000000000..03609eb18e689 --- /dev/null +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/pointcloud_densification.hpp @@ -0,0 +1,72 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef IMAGE_PROJECTION_BASED_FUSION__POINTPAINTING_FUSION__POINTCLOUD_DENSIFICATION_HPP_ +#define IMAGE_PROJECTION_BASED_FUSION__POINTPAINTING_FUSION__POINTCLOUD_DENSIFICATION_HPP_ + +#include +#include +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +#include + +#include +#include +#include + +namespace image_projection_based_fusion +{ +struct PointCloudWithTransform +{ + sensor_msgs::msg::PointCloud2 pointcloud_msg; + Eigen::Affine3f affine_past2world; +}; + +class PointCloudDensification +{ +public: + explicit PointCloudDensification(const centerpoint::DensificationParam & param); + + bool enqueuePointCloud( + const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer); + + double getCurrentTimestamp() const { return current_timestamp_; } + Eigen::Affine3f getAffineWorldToCurrent() const { return affine_world2current_; } + std::list::iterator getPointCloudCacheIter() + { + return pointcloud_cache_.begin(); + } + bool isCacheEnd(std::list::iterator iter) + { + return iter == pointcloud_cache_.end(); + } + unsigned int pointcloud_cache_size() const { return param_.pointcloud_cache_size(); } + +private: + void enqueue(const sensor_msgs::msg::PointCloud2 & msg, const Eigen::Affine3f & affine); + void dequeue(); + + centerpoint::DensificationParam param_; + double current_timestamp_{0.0}; + Eigen::Affine3f affine_world2current_; + std::list pointcloud_cache_; +}; + +} // namespace image_projection_based_fusion + +#endif // IMAGE_PROJECTION_BASED_FUSION__POINTPAINTING_FUSION__POINTCLOUD_DENSIFICATION_HPP_ diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/voxel_generator.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/voxel_generator.hpp old mode 100755 new mode 100644 index d0f44b9d58706..4cdca8e49ac7e --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/voxel_generator.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/voxel_generator.hpp @@ -15,19 +15,35 @@ #ifndef IMAGE_PROJECTION_BASED_FUSION__POINTPAINTING_FUSION__VOXEL_GENERATOR_HPP_ #define IMAGE_PROJECTION_BASED_FUSION__POINTPAINTING_FUSION__VOXEL_GENERATOR_HPP_ +#include +#include #include #include +#include #include namespace image_projection_based_fusion { -class VoxelGenerator : public centerpoint::VoxelGenerator + +class VoxelGenerator { public: - using centerpoint::VoxelGenerator::VoxelGenerator; + explicit VoxelGenerator( + const centerpoint::DensificationParam & param, const centerpoint::CenterPointConfig & config); + + bool enqueuePointCloud( + const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer); + + std::size_t generateSweepPoints(std::vector & points); + +protected: + std::unique_ptr pd_ptr_{nullptr}; - std::size_t generateSweepPoints(std::vector & points) override; + centerpoint::CenterPointConfig config_; + std::array range_; + std::array grid_size_; + std::array recip_voxel_size_; }; } // namespace image_projection_based_fusion diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/pointcloud_densification.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/pointcloud_densification.cpp new file mode 100644 index 0000000000000..9edf6a73cd59b --- /dev/null +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/pointcloud_densification.cpp @@ -0,0 +1,103 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "image_projection_based_fusion/pointpainting_fusion/pointcloud_densification.hpp" + +#include + +#include + +#include +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +#include +#include + +namespace +{ +boost::optional getTransform( + const tf2_ros::Buffer & tf_buffer, const std::string & target_frame_id, + const std::string & source_frame_id, const rclcpp::Time & time) +{ + try { + geometry_msgs::msg::TransformStamped transform_stamped; + transform_stamped = tf_buffer.lookupTransform( + target_frame_id, source_frame_id, time, rclcpp::Duration::from_seconds(0.5)); + return transform_stamped.transform; + } catch (tf2::TransformException & ex) { + RCLCPP_WARN_STREAM(rclcpp::get_logger("lidar_centerpoint"), ex.what()); + return boost::none; + } +} + +Eigen::Affine3f transformToEigen(const geometry_msgs::msg::Transform & t) +{ + Eigen::Affine3f a; + a.matrix() = tf2::transformToEigen(t).matrix().cast(); + return a; +} + +} // namespace + +namespace image_projection_based_fusion +{ +PointCloudDensification::PointCloudDensification(const centerpoint::DensificationParam & param) +: param_(param) +{ +} + +bool PointCloudDensification::enqueuePointCloud( + const sensor_msgs::msg::PointCloud2 & pointcloud_msg, const tf2_ros::Buffer & tf_buffer) +{ + const auto header = pointcloud_msg.header; + + if (param_.pointcloud_cache_size() > 1) { + auto transform_world2current = + getTransform(tf_buffer, header.frame_id, param_.world_frame_id(), header.stamp); + if (!transform_world2current) { + return false; + } + auto affine_world2current = transformToEigen(transform_world2current.get()); + + enqueue(pointcloud_msg, affine_world2current); + } else { + enqueue(pointcloud_msg, Eigen::Affine3f::Identity()); + } + + dequeue(); + + return true; +} + +void PointCloudDensification::enqueue( + const sensor_msgs::msg::PointCloud2 & msg, const Eigen::Affine3f & affine_world2current) +{ + affine_world2current_ = affine_world2current; + current_timestamp_ = rclcpp::Time(msg.header.stamp).seconds(); + PointCloudWithTransform pointcloud = {msg, affine_world2current.inverse()}; + pointcloud_cache_.push_front(pointcloud); +} + +void PointCloudDensification::dequeue() +{ + if (pointcloud_cache_.size() > param_.pointcloud_cache_size()) { + pointcloud_cache_.pop_back(); + } +} + +} // namespace image_projection_based_fusion diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp index ea10cb1237436..cb3fc33d3e022 100755 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp @@ -18,6 +18,32 @@ namespace image_projection_based_fusion { + +VoxelGenerator::VoxelGenerator( + const centerpoint::DensificationParam & param, const centerpoint::CenterPointConfig & config) +: config_(config) +{ + pd_ptr_ = std::make_unique(param); + range_[0] = config.range_min_x_; + range_[1] = config.range_min_y_; + range_[2] = config.range_min_z_; + range_[3] = config.range_max_x_; + range_[4] = config.range_max_y_; + range_[5] = config.range_max_z_; + grid_size_[0] = config.grid_size_x_; + grid_size_[1] = config.grid_size_y_; + grid_size_[2] = config.grid_size_z_; + recip_voxel_size_[0] = 1 / config.voxel_size_x_; + recip_voxel_size_[1] = 1 / config.voxel_size_y_; + recip_voxel_size_[2] = 1 / config.voxel_size_z_; +} + +bool VoxelGenerator::enqueuePointCloud( + const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer) +{ + return pd_ptr_->enqueuePointCloud(input_pointcloud_msg, tf_buffer); +} + size_t VoxelGenerator::generateSweepPoints(std::vector & points) { Eigen::Vector3f point_current, point_past; diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp index 8cf250be0c049..55157f70fcfc3 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp @@ -15,15 +15,14 @@ #ifndef LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_ #define LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_ -#include -#include -#include -#include - -#include - -#include -#include +#include "lidar_centerpoint/cuda_utils.hpp" +#include "lidar_centerpoint/network/network_trt.hpp" +#include "lidar_centerpoint/postprocess/postprocess_kernel.hpp" +#include "lidar_centerpoint/preprocess/voxel_generator.hpp" +#include "pcl/point_cloud.h" +#include "pcl/point_types.h" + +#include "sensor_msgs/msg/point_cloud2.hpp" #include #include diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/cuda_utils.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/cuda_utils.hpp index 5ab26d75a0a41..efe3bbb9a5482 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/cuda_utils.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/cuda_utils.hpp @@ -42,7 +42,7 @@ #ifndef LIDAR_CENTERPOINT__CUDA_UTILS_HPP_ #define LIDAR_CENTERPOINT__CUDA_UTILS_HPP_ -#include +#include "cuda_runtime_api.h" #include #include diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/detection_class_remapper.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/detection_class_remapper.hpp index cd1a0e58e115e..d961dd998af76 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/detection_class_remapper.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/detection_class_remapper.hpp @@ -17,10 +17,10 @@ #include -#include -#include -#include -#include +#include "autoware_perception_msgs/msg/detected_object_kinematics.hpp" +#include "autoware_perception_msgs/msg/detected_objects.hpp" +#include "autoware_perception_msgs/msg/object_classification.hpp" +#include "autoware_perception_msgs/msg/shape.hpp" #include diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/network/network_trt.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/network/network_trt.hpp index 639aa0ba8bad3..1bf77248efe08 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/network/network_trt.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/network/network_trt.hpp @@ -15,8 +15,8 @@ #ifndef LIDAR_CENTERPOINT__NETWORK__NETWORK_TRT_HPP_ #define LIDAR_CENTERPOINT__NETWORK__NETWORK_TRT_HPP_ -#include -#include +#include "lidar_centerpoint/centerpoint_config.hpp" +#include "lidar_centerpoint/network/tensorrt_wrapper.hpp" #include diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/network/scatter_kernel.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/network/scatter_kernel.hpp index 3dd00c25fd9e7..ad5e222ce01e8 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/network/scatter_kernel.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/network/scatter_kernel.hpp @@ -15,8 +15,8 @@ #ifndef LIDAR_CENTERPOINT__NETWORK__SCATTER_KERNEL_HPP_ #define LIDAR_CENTERPOINT__NETWORK__SCATTER_KERNEL_HPP_ -#include -#include +#include "cuda.h" +#include "cuda_runtime_api.h" namespace centerpoint { diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/network/tensorrt_wrapper.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/network/tensorrt_wrapper.hpp index 7f55ab6f5e414..4af5aac7ff7fe 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/network/tensorrt_wrapper.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/network/tensorrt_wrapper.hpp @@ -15,10 +15,9 @@ #ifndef LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_ #define LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_ -#include -#include - -#include +#include "NvInfer.h" +#include "lidar_centerpoint/centerpoint_config.hpp" +#include "tensorrt_common/tensorrt_common.hpp" #include #include @@ -32,7 +31,7 @@ class TensorRTWrapper public: explicit TensorRTWrapper(const CenterPointConfig & config); - ~TensorRTWrapper(); + virtual ~TensorRTWrapper(); bool init( const std::string & onnx_path, const std::string & engine_path, const std::string & precision); diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/node.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/node.hpp index d96eb1ae3ed94..032627861e1b3 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/node.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/node.hpp @@ -15,13 +15,13 @@ #ifndef LIDAR_CENTERPOINT__NODE_HPP_ #define LIDAR_CENTERPOINT__NODE_HPP_ +#include "lidar_centerpoint/centerpoint_trt.hpp" +#include "lidar_centerpoint/detection_class_remapper.hpp" #include "lidar_centerpoint/postprocess/non_maximum_suppression.hpp" #include #include #include -#include -#include #include #include diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/postprocess/circle_nms_kernel.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/postprocess/circle_nms_kernel.hpp index cd2d71d33806d..5b55636a3eec4 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/postprocess/circle_nms_kernel.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/postprocess/circle_nms_kernel.hpp @@ -15,9 +15,8 @@ #ifndef LIDAR_CENTERPOINT__POSTPROCESS__CIRCLE_NMS_KERNEL_HPP_ #define LIDAR_CENTERPOINT__POSTPROCESS__CIRCLE_NMS_KERNEL_HPP_ -#include - -#include +#include "lidar_centerpoint/utils.hpp" +#include "thrust/device_vector.h" namespace centerpoint { diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/postprocess/postprocess_kernel.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/postprocess/postprocess_kernel.hpp index d790e896dea9a..e15d3022c947c 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/postprocess/postprocess_kernel.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/postprocess/postprocess_kernel.hpp @@ -15,12 +15,11 @@ #ifndef LIDAR_CENTERPOINT__POSTPROCESS__POSTPROCESS_KERNEL_HPP_ #define LIDAR_CENTERPOINT__POSTPROCESS__POSTPROCESS_KERNEL_HPP_ -#include -#include - -#include -#include -#include +#include "cuda.h" +#include "cuda_runtime_api.h" +#include "lidar_centerpoint/centerpoint_config.hpp" +#include "lidar_centerpoint/utils.hpp" +#include "thrust/device_vector.h" #include diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/pointcloud_densification.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/pointcloud_densification.hpp index 209fc74e6c58f..c1d6a6b060955 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/pointcloud_densification.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/pointcloud_densification.hpp @@ -15,17 +15,19 @@ #ifndef LIDAR_CENTERPOINT__PREPROCESS__POINTCLOUD_DENSIFICATION_HPP_ #define LIDAR_CENTERPOINT__PREPROCESS__POINTCLOUD_DENSIFICATION_HPP_ -#include -#include -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif +#include "tf2_ros/buffer.h" +#include "tf2_ros/transform_listener.h" #include #include #include +#ifdef ROS_DISTRO_GALACTIC +#include "tf2_sensor_msgs/tf2_sensor_msgs.h" +#else +#include "tf2_sensor_msgs/tf2_sensor_msgs.hpp" +#endif + +#include "lidar_centerpoint/cuda_utils.hpp" namespace centerpoint { @@ -48,7 +50,10 @@ class DensificationParam struct PointCloudWithTransform { - sensor_msgs::msg::PointCloud2 pointcloud_msg; + cuda::unique_ptr points_d{nullptr}; + std_msgs::msg::Header header; + size_t num_points{0}; + size_t point_step{0}; Eigen::Affine3f affine_past2world; }; @@ -58,7 +63,8 @@ class PointCloudDensification explicit PointCloudDensification(const DensificationParam & param); bool enqueuePointCloud( - const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer); + const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer, + cudaStream_t stream); double getCurrentTimestamp() const { return current_timestamp_; } Eigen::Affine3f getAffineWorldToCurrent() const { return affine_world2current_; } @@ -73,7 +79,8 @@ class PointCloudDensification unsigned int pointcloud_cache_size() const { return param_.pointcloud_cache_size(); } private: - void enqueue(const sensor_msgs::msg::PointCloud2 & msg, const Eigen::Affine3f & affine); + void enqueue( + const sensor_msgs::msg::PointCloud2 & msg, const Eigen::Affine3f & affine, cudaStream_t stream); void dequeue(); DensificationParam param_; 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 9488b67475509..3abcd89cb5c55 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/preprocess_kernel.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/preprocess_kernel.hpp @@ -15,11 +15,15 @@ #ifndef LIDAR_CENTERPOINT__PREPROCESS__PREPROCESS_KERNEL_HPP_ #define LIDAR_CENTERPOINT__PREPROCESS__PREPROCESS_KERNEL_HPP_ -#include -#include +#include "cuda.h" +#include "cuda_runtime_api.h" namespace centerpoint { +cudaError_t generateSweepPoints_launch( + const float * input_points, size_t points_size, int input_point_step, float time_lag, + const float * transform, int num_features, float * output_points, cudaStream_t stream); + cudaError_t generateVoxels_random_launch( const float * points, size_t points_size, float min_x_range, float max_x_range, float min_y_range, float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, float pillar_y_size, diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/voxel_generator.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/voxel_generator.hpp index be15d51e91715..3ade5e677cdbe 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/voxel_generator.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/preprocess/voxel_generator.hpp @@ -15,10 +15,10 @@ #ifndef LIDAR_CENTERPOINT__PREPROCESS__VOXEL_GENERATOR_HPP_ #define LIDAR_CENTERPOINT__PREPROCESS__VOXEL_GENERATOR_HPP_ -#include -#include +#include "lidar_centerpoint/centerpoint_config.hpp" +#include "lidar_centerpoint/preprocess/pointcloud_densification.hpp" -#include +#include "sensor_msgs/msg/point_cloud2.hpp" #include #include @@ -31,10 +31,11 @@ class VoxelGeneratorTemplate explicit VoxelGeneratorTemplate( const DensificationParam & param, const CenterPointConfig & config); - virtual std::size_t generateSweepPoints(std::vector & points) = 0; + virtual std::size_t generateSweepPoints(float * d_points, cudaStream_t stream) = 0; bool enqueuePointCloud( - const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer); + const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer, + cudaStream_t stream); protected: std::unique_ptr pd_ptr_{nullptr}; @@ -50,7 +51,7 @@ class VoxelGenerator : public VoxelGeneratorTemplate public: using VoxelGeneratorTemplate::VoxelGeneratorTemplate; - std::size_t generateSweepPoints(std::vector & points) override; + std::size_t generateSweepPoints(float * d_points, cudaStream_t stream) override; }; } // namespace centerpoint diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/ros_utils.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/ros_utils.hpp index e33d86cd0aba7..484fbcfd36657 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/ros_utils.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/ros_utils.hpp @@ -17,12 +17,9 @@ // ros packages cannot be included from cuda. -#include +#include "lidar_centerpoint/utils.hpp" -#include -#include -#include -#include +#include "autoware_perception_msgs/msg/detected_objects.hpp" #include #include diff --git a/perception/lidar_centerpoint/lib/centerpoint_trt.cpp b/perception/lidar_centerpoint/lib/centerpoint_trt.cpp index f7b0fe5e0c58f..6f379167b0e71 100644 --- a/perception/lidar_centerpoint/lib/centerpoint_trt.cpp +++ b/perception/lidar_centerpoint/lib/centerpoint_trt.cpp @@ -14,10 +14,11 @@ #include "lidar_centerpoint/centerpoint_trt.hpp" +#include "lidar_centerpoint/centerpoint_config.hpp" +#include "lidar_centerpoint/network/scatter_kernel.hpp" +#include "lidar_centerpoint/preprocess/preprocess_kernel.hpp" + #include -#include -#include -#include #include #include @@ -130,14 +131,11 @@ bool CenterPointTRT::detect( bool CenterPointTRT::preprocess( const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer) { - bool is_success = vg_ptr_->enqueuePointCloud(input_pointcloud_msg, tf_buffer); + bool is_success = vg_ptr_->enqueuePointCloud(input_pointcloud_msg, tf_buffer, stream_); if (!is_success) { return false; } - const auto count = vg_ptr_->generateSweepPoints(points_); - CHECK_CUDA_ERROR(cudaMemcpyAsync( - points_d_.get(), points_.data(), count * config_.point_feature_size_ * sizeof(float), - cudaMemcpyHostToDevice, stream_)); + const auto count = vg_ptr_->generateSweepPoints(points_d_.get(), stream_); CHECK_CUDA_ERROR(cudaMemsetAsync(num_voxels_d_.get(), 0, sizeof(unsigned int), stream_)); CHECK_CUDA_ERROR( cudaMemsetAsync(voxels_buffer_d_.get(), 0, voxels_buffer_size_ * sizeof(float), stream_)); diff --git a/perception/lidar_centerpoint/lib/detection_class_remapper.cpp b/perception/lidar_centerpoint/lib/detection_class_remapper.cpp index ecfbb4360ecf0..9805fc7a661d1 100644 --- a/perception/lidar_centerpoint/lib/detection_class_remapper.cpp +++ b/perception/lidar_centerpoint/lib/detection_class_remapper.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include "lidar_centerpoint/detection_class_remapper.hpp" namespace centerpoint { diff --git a/perception/lidar_centerpoint/lib/network/scatter_kernel.cu b/perception/lidar_centerpoint/lib/network/scatter_kernel.cu index 09cc83bf606fe..f139e230426ca 100644 --- a/perception/lidar_centerpoint/lib/network/scatter_kernel.cu +++ b/perception/lidar_centerpoint/lib/network/scatter_kernel.cu @@ -13,8 +13,7 @@ // limitations under the License. #include "lidar_centerpoint/network/scatter_kernel.hpp" - -#include +#include "lidar_centerpoint/utils.hpp" namespace { diff --git a/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp b/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp index 91fcce9a80f78..bdfde42a12a02 100644 --- a/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp +++ b/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp @@ -14,7 +14,7 @@ #include "lidar_centerpoint/network/tensorrt_wrapper.hpp" -#include +#include "NvOnnxParser.h" #include #include diff --git a/perception/lidar_centerpoint/lib/postprocess/circle_nms_kernel.cu b/perception/lidar_centerpoint/lib/postprocess/circle_nms_kernel.cu index 398e75a55c44b..c208eefe135fb 100644 --- a/perception/lidar_centerpoint/lib/postprocess/circle_nms_kernel.cu +++ b/perception/lidar_centerpoint/lib/postprocess/circle_nms_kernel.cu @@ -21,12 +21,10 @@ Written by Shaoshuai Shi All Rights Reserved 2019-2020. */ +#include "lidar_centerpoint/cuda_utils.hpp" #include "lidar_centerpoint/postprocess/circle_nms_kernel.hpp" - -#include -#include - -#include +#include "lidar_centerpoint/utils.hpp" +#include "thrust/host_vector.h" namespace { diff --git a/perception/lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp b/perception/lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp index 81f620018cf04..533d04eebd433 100644 --- a/perception/lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp +++ b/perception/lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp @@ -14,9 +14,10 @@ #include "lidar_centerpoint/postprocess/non_maximum_suppression.hpp" -#include "autoware/universe_utils/geometry/geometry.hpp" -#include "object_recognition_utils/geometry.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" +#include +#include +#include + namespace centerpoint { diff --git a/perception/lidar_centerpoint/lib/postprocess/postprocess_kernel.cu b/perception/lidar_centerpoint/lib/postprocess/postprocess_kernel.cu index 34bbd2811041c..12835bab038a6 100644 --- a/perception/lidar_centerpoint/lib/postprocess/postprocess_kernel.cu +++ b/perception/lidar_centerpoint/lib/postprocess/postprocess_kernel.cu @@ -13,12 +13,10 @@ // limitations under the License. #include "lidar_centerpoint/postprocess/circle_nms_kernel.hpp" - -#include - -#include -#include -#include +#include "lidar_centerpoint/postprocess/postprocess_kernel.hpp" +#include "thrust/count.h" +#include "thrust/device_vector.h" +#include "thrust/sort.h" namespace { diff --git a/perception/lidar_centerpoint/lib/preprocess/pointcloud_densification.cpp b/perception/lidar_centerpoint/lib/preprocess/pointcloud_densification.cpp index 66c348fda50b4..2859d58d8f669 100644 --- a/perception/lidar_centerpoint/lib/preprocess/pointcloud_densification.cpp +++ b/perception/lidar_centerpoint/lib/preprocess/pointcloud_densification.cpp @@ -14,20 +14,19 @@ #include "lidar_centerpoint/preprocess/pointcloud_densification.hpp" -#include +#include "pcl_conversions/pcl_conversions.h" +#include "pcl_ros/transforms.hpp" -#include +#include "boost/optional.hpp" -#include +#include +#include #ifdef ROS_DISTRO_GALACTIC -#include +#include "tf2_eigen/tf2_eigen.h" #else -#include +#include "tf2_eigen/tf2_eigen.hpp" #endif -#include -#include - namespace { boost::optional getTransform( @@ -61,7 +60,8 @@ PointCloudDensification::PointCloudDensification(const DensificationParam & para } bool PointCloudDensification::enqueuePointCloud( - const sensor_msgs::msg::PointCloud2 & pointcloud_msg, const tf2_ros::Buffer & tf_buffer) + const sensor_msgs::msg::PointCloud2 & pointcloud_msg, const tf2_ros::Buffer & tf_buffer, + cudaStream_t stream) { const auto header = pointcloud_msg.header; @@ -73,9 +73,9 @@ bool PointCloudDensification::enqueuePointCloud( } auto affine_world2current = transformToEigen(transform_world2current.get()); - enqueue(pointcloud_msg, affine_world2current); + enqueue(pointcloud_msg, affine_world2current, stream); } else { - enqueue(pointcloud_msg, Eigen::Affine3f::Identity()); + enqueue(pointcloud_msg, Eigen::Affine3f::Identity(), stream); } dequeue(); @@ -84,12 +84,24 @@ bool PointCloudDensification::enqueuePointCloud( } void PointCloudDensification::enqueue( - const sensor_msgs::msg::PointCloud2 & msg, const Eigen::Affine3f & affine_world2current) + const sensor_msgs::msg::PointCloud2 & msg, const Eigen::Affine3f & affine_world2current, + cudaStream_t stream) { affine_world2current_ = affine_world2current; current_timestamp_ = rclcpp::Time(msg.header.stamp).seconds(); - PointCloudWithTransform pointcloud = {msg, affine_world2current.inverse()}; - pointcloud_cache_.push_front(pointcloud); + + assert(sizeof(uint8_t) * msg.width * msg.height * msg.point_step % sizeof(float) == 0); + auto points_d = cuda::make_unique( + sizeof(uint8_t) * msg.width * msg.height * msg.point_step / sizeof(float)); + CHECK_CUDA_ERROR(cudaMemcpyAsync( + points_d.get(), msg.data.data(), sizeof(uint8_t) * msg.width * msg.height * msg.point_step, + cudaMemcpyHostToDevice, stream)); + + PointCloudWithTransform pointcloud = { + std::move(points_d), msg.header, msg.width * msg.height, msg.point_step, + affine_world2current.inverse()}; + + pointcloud_cache_.push_front(std::move(pointcloud)); } void PointCloudDensification::dequeue() diff --git a/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu b/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu index 218aaee125c02..4e78176739c26 100644 --- a/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu +++ b/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu @@ -28,9 +28,11 @@ * limitations under the License. */ +#include "lidar_centerpoint/cuda_utils.hpp" #include "lidar_centerpoint/preprocess/preprocess_kernel.hpp" +#include "lidar_centerpoint/utils.hpp" -#include +#include namespace { @@ -41,6 +43,51 @@ const std::size_t ENCODER_IN_FEATURE_SIZE = 9; // the same as encoder_in_featur namespace centerpoint { + +__global__ void generateSweepPoints_kernel( + const float * input_points, size_t points_size, int input_point_step, float time_lag, + const float * transform_array, int num_features, float * output_points) +{ + int point_idx = blockIdx.x * blockDim.x + threadIdx.x; + if (point_idx >= points_size) return; + + const float input_x = input_points[point_idx * input_point_step + 0]; + const float input_y = input_points[point_idx * input_point_step + 1]; + const float input_z = input_points[point_idx * input_point_step + 2]; + + // transform_array is expected to be column-major + output_points[point_idx * num_features + 0] = transform_array[0] * input_x + + transform_array[4] * input_y + + transform_array[8] * input_z + transform_array[12]; + output_points[point_idx * num_features + 1] = transform_array[1] * input_x + + transform_array[5] * input_y + + transform_array[9] * input_z + transform_array[13]; + output_points[point_idx * num_features + 2] = transform_array[2] * input_x + + transform_array[6] * input_y + + transform_array[10] * input_z + transform_array[14]; + output_points[point_idx * num_features + 3] = time_lag; +} + +cudaError_t generateSweepPoints_launch( + const float * input_points, size_t points_size, int input_point_step, float time_lag, + const float * transform_array, int num_features, float * output_points, cudaStream_t stream) +{ + auto transform_d = cuda::make_unique(16); + CHECK_CUDA_ERROR(cudaMemcpyAsync( + transform_d.get(), transform_array, 16 * sizeof(float), cudaMemcpyHostToDevice, stream)); + + dim3 blocks((points_size + 256 - 1) / 256); + dim3 threads(256); + assert(num_features == 4); + + generateSweepPoints_kernel<<>>( + input_points, points_size, input_point_step, time_lag, transform_d.get(), num_features, + output_points); + + cudaError_t err = cudaGetLastError(); + return err; +} + __global__ void generateVoxels_random_kernel( const float * points, size_t points_size, float min_x_range, float max_x_range, float min_y_range, float max_y_range, float min_z_range, float max_z_range, float pillar_x_size, float pillar_y_size, diff --git a/perception/lidar_centerpoint/lib/preprocess/voxel_generator.cpp b/perception/lidar_centerpoint/lib/preprocess/voxel_generator.cpp index 07a1a2de725f5..e90474fa07327 100644 --- a/perception/lidar_centerpoint/lib/preprocess/voxel_generator.cpp +++ b/perception/lidar_centerpoint/lib/preprocess/voxel_generator.cpp @@ -14,7 +14,12 @@ #include "lidar_centerpoint/preprocess/voxel_generator.hpp" -#include +#include "lidar_centerpoint/centerpoint_trt.hpp" +#include "lidar_centerpoint/preprocess/preprocess_kernel.hpp" + +#include "sensor_msgs/point_cloud2_iterator.hpp" + +#include namespace centerpoint { @@ -38,35 +43,40 @@ VoxelGeneratorTemplate::VoxelGeneratorTemplate( } bool VoxelGeneratorTemplate::enqueuePointCloud( - const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer) + const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer, + cudaStream_t stream) { - return pd_ptr_->enqueuePointCloud(input_pointcloud_msg, tf_buffer); + return pd_ptr_->enqueuePointCloud(input_pointcloud_msg, tf_buffer, stream); } -std::size_t VoxelGenerator::generateSweepPoints(std::vector & points) +std::size_t VoxelGenerator::generateSweepPoints(float * points_d, cudaStream_t stream) { - Eigen::Vector3f point_current, point_past; - size_t point_counter{}; + size_t point_counter = 0; for (auto pc_cache_iter = pd_ptr_->getPointCloudCacheIter(); !pd_ptr_->isCacheEnd(pc_cache_iter); pc_cache_iter++) { - auto pc_msg = pc_cache_iter->pointcloud_msg; + auto sweep_num_points = pc_cache_iter->num_points; + auto point_step = pc_cache_iter->point_step; auto affine_past2current = pd_ptr_->getAffineWorldToCurrent() * pc_cache_iter->affine_past2world; float time_lag = static_cast( - pd_ptr_->getCurrentTimestamp() - rclcpp::Time(pc_msg.header.stamp).seconds()); - - for (sensor_msgs::PointCloud2ConstIterator x_iter(pc_msg, "x"), y_iter(pc_msg, "y"), - z_iter(pc_msg, "z"); - x_iter != x_iter.end(); ++x_iter, ++y_iter, ++z_iter) { - point_past << *x_iter, *y_iter, *z_iter; - point_current = affine_past2current * point_past; + pd_ptr_->getCurrentTimestamp() - rclcpp::Time(pc_cache_iter->header.stamp).seconds()); - points.at(point_counter * config_.point_feature_size_) = point_current.x(); - points.at(point_counter * config_.point_feature_size_ + 1) = point_current.y(); - points.at(point_counter * config_.point_feature_size_ + 2) = point_current.z(); - points.at(point_counter * config_.point_feature_size_ + 3) = time_lag; - ++point_counter; + if (point_counter + sweep_num_points > CAPACITY_POINT) { + RCLCPP_WARN_STREAM( + rclcpp::get_logger("lidar_centerpoint"), + "Requested number of points exceeds the maximum capacity. Current points = " + << point_counter); + break; } + + static_assert(std::is_same::value); + static_assert(!Eigen::Matrix4f::IsRowMajor, "matrices should be col-major."); + generateSweepPoints_launch( + pc_cache_iter->points_d.get(), sweep_num_points, point_step / sizeof(float), time_lag, + affine_past2current.matrix().data(), config_.point_feature_size_, + points_d + config_.point_feature_size_ * point_counter, stream); + + point_counter += sweep_num_points; } return point_counter; } diff --git a/perception/lidar_centerpoint/src/node.cpp b/perception/lidar_centerpoint/src/node.cpp index b65c70f02bd1b..5c0931196675a 100644 --- a/perception/lidar_centerpoint/src/node.cpp +++ b/perception/lidar_centerpoint/src/node.cpp @@ -14,17 +14,7 @@ #include "lidar_centerpoint/node.hpp" -#include -#include -#include -#include -#include - -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif +#include "pcl_ros/transforms.hpp" #include #include @@ -33,6 +23,17 @@ #include #include +#ifdef ROS_DISTRO_GALACTIC +#include "tf2_geometry_msgs/tf2_geometry_msgs.h" +#else +#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" +#endif + +#include "lidar_centerpoint/centerpoint_config.hpp" +#include "lidar_centerpoint/preprocess/pointcloud_densification.hpp" +#include "lidar_centerpoint/ros_utils.hpp" +#include "lidar_centerpoint/utils.hpp" + namespace centerpoint { LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_options) diff --git a/perception/lidar_centerpoint/test/test_postprocess_kernel.hpp b/perception/lidar_centerpoint/test/test_postprocess_kernel.hpp index d0c9123da9e77..8f35b98119afe 100644 --- a/perception/lidar_centerpoint/test/test_postprocess_kernel.hpp +++ b/perception/lidar_centerpoint/test/test_postprocess_kernel.hpp @@ -31,17 +31,17 @@ class PostprocessKernelTest : public testing::Test void SetUp() override; void TearDown() override; - cudaStream_t stream_{nullptr}; + cudaStream_t stream_{}; - std::unique_ptr postprocess_cuda_ptr_; - std::unique_ptr config_ptr_; + std::unique_ptr postprocess_cuda_ptr_{}; + std::unique_ptr config_ptr_{}; - cuda::unique_ptr head_out_heatmap_d_; - cuda::unique_ptr head_out_offset_d_; - cuda::unique_ptr head_out_z_d_; - cuda::unique_ptr head_out_dim_d_; - cuda::unique_ptr head_out_rot_d_; - cuda::unique_ptr head_out_vel_d_; + cuda::unique_ptr head_out_heatmap_d_{}; + cuda::unique_ptr head_out_offset_d_{}; + cuda::unique_ptr head_out_z_d_{}; + cuda::unique_ptr head_out_dim_d_{}; + cuda::unique_ptr head_out_rot_d_{}; + cuda::unique_ptr head_out_vel_d_{}; }; } // namespace centerpoint diff --git a/perception/lidar_centerpoint/test/test_preprocess_kernel.hpp b/perception/lidar_centerpoint/test/test_preprocess_kernel.hpp index 57ff51966a417..1a3e850026886 100644 --- a/perception/lidar_centerpoint/test/test_preprocess_kernel.hpp +++ b/perception/lidar_centerpoint/test/test_preprocess_kernel.hpp @@ -28,7 +28,7 @@ class PreprocessKernelTest : public testing::Test void SetUp() override; void TearDown() override; - cudaStream_t stream_{nullptr}; + cudaStream_t stream_{}; std::size_t max_voxel_size_{}; std::size_t max_point_in_voxel_size_{}; diff --git a/perception/lidar_centerpoint/test/test_voxel_generator.cpp b/perception/lidar_centerpoint/test/test_voxel_generator.cpp index 5b0b3cd112e6c..6bded105536dc 100644 --- a/perception/lidar_centerpoint/test/test_voxel_generator.cpp +++ b/perception/lidar_centerpoint/test/test_voxel_generator.cpp @@ -14,9 +14,9 @@ #include "test_voxel_generator.hpp" -#include +#include "gtest/gtest.h" -#include +#include "sensor_msgs/point_cloud2_iterator.hpp" void VoxelGeneratorTest::SetUp() { @@ -95,6 +95,8 @@ void VoxelGeneratorTest::SetUp() transform2_ = transform1_; transform2_.header.stamp = cloud2_->header.stamp; transform2_.transform.translation.x = world_origin_x + delta_pointcloud_x_; + + cudaStreamCreate(&stream_); } void VoxelGeneratorTest::TearDown() @@ -117,8 +119,17 @@ TEST_F(VoxelGeneratorTest, SingleFrame) points.resize(capacity_ * config.point_feature_size_); std::fill(points.begin(), points.end(), std::nan("")); - bool status1 = voxel_generator.enqueuePointCloud(*cloud1_, *tf2_buffer_); - std::size_t generated_points_num = voxel_generator.generateSweepPoints(points); + auto points_d = cuda::make_unique(capacity_ * config.point_feature_size_); + cudaMemcpy( + points_d.get(), points.data(), capacity_ * config.point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice); + + bool status1 = voxel_generator.enqueuePointCloud(*cloud1_, *tf2_buffer_, stream_); + std::size_t generated_points_num = voxel_generator.generateSweepPoints(points_d.get(), stream_); + + cudaMemcpy( + points.data(), points_d.get(), capacity_ * config.point_feature_size_ * sizeof(float), + cudaMemcpyDeviceToHost); EXPECT_TRUE(status1); EXPECT_EQ(points_per_pointcloud_, generated_points_num); @@ -155,9 +166,18 @@ TEST_F(VoxelGeneratorTest, TwoFramesNoTf) points.resize(capacity_ * config.point_feature_size_); std::fill(points.begin(), points.end(), std::nan("")); - bool status1 = voxel_generator.enqueuePointCloud(*cloud1_, *tf2_buffer_); - bool status2 = voxel_generator.enqueuePointCloud(*cloud2_, *tf2_buffer_); - std::size_t generated_points_num = voxel_generator.generateSweepPoints(points); + auto points_d = cuda::make_unique(capacity_ * config.point_feature_size_); + cudaMemcpy( + points_d.get(), points.data(), capacity_ * config.point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice); + + bool status1 = voxel_generator.enqueuePointCloud(*cloud1_, *tf2_buffer_, stream_); + bool status2 = voxel_generator.enqueuePointCloud(*cloud2_, *tf2_buffer_, stream_); + std::size_t generated_points_num = voxel_generator.generateSweepPoints(points_d.get(), stream_); + + cudaMemcpy( + points.data(), points_d.get(), capacity_ * config.point_feature_size_ * sizeof(float), + cudaMemcpyDeviceToHost); EXPECT_FALSE(status1); EXPECT_FALSE(status2); @@ -180,12 +200,21 @@ TEST_F(VoxelGeneratorTest, TwoFrames) points.resize(capacity_ * config.point_feature_size_); std::fill(points.begin(), points.end(), std::nan("")); + auto points_d = cuda::make_unique(capacity_ * config.point_feature_size_); + cudaMemcpy( + points_d.get(), points.data(), capacity_ * config.point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice); + tf2_buffer_->setTransform(transform1_, "authority1"); tf2_buffer_->setTransform(transform2_, "authority1"); - bool status1 = voxel_generator.enqueuePointCloud(*cloud1_, *tf2_buffer_); - bool status2 = voxel_generator.enqueuePointCloud(*cloud2_, *tf2_buffer_); - std::size_t generated_points_num = voxel_generator.generateSweepPoints(points); + bool status1 = voxel_generator.enqueuePointCloud(*cloud1_, *tf2_buffer_, stream_); + bool status2 = voxel_generator.enqueuePointCloud(*cloud2_, *tf2_buffer_, stream_); + std::size_t generated_points_num = voxel_generator.generateSweepPoints(points_d.get(), stream_); + + cudaMemcpy( + points.data(), points_d.get(), capacity_ * config.point_feature_size_ * sizeof(float), + cudaMemcpyDeviceToHost); EXPECT_TRUE(status1); EXPECT_TRUE(status2); diff --git a/perception/lidar_centerpoint/test/test_voxel_generator.hpp b/perception/lidar_centerpoint/test/test_voxel_generator.hpp index 8fb7d8dffa44d..48355b8a331ba 100644 --- a/perception/lidar_centerpoint/test/test_voxel_generator.hpp +++ b/perception/lidar_centerpoint/test/test_voxel_generator.hpp @@ -33,34 +33,36 @@ class VoxelGeneratorTest : public testing::Test void TearDown() override; // These need to be public so that they can be accessed in the test cases - rclcpp::Node::SharedPtr node_; + rclcpp::Node::SharedPtr node_{}; - std::unique_ptr cloud1_, cloud2_; - geometry_msgs::msg::TransformStamped transform1_, transform2_; + std::unique_ptr cloud1_{}, cloud2_{}; + geometry_msgs::msg::TransformStamped transform1_{}, transform2_{}; - std::unique_ptr densification_param_ptr_; - std::unique_ptr config_ptr_; + std::unique_ptr densification_param_ptr_{}; + std::unique_ptr config_ptr_{}; - std::unique_ptr tf2_buffer_; + std::unique_ptr tf2_buffer_{}; - std::string world_frame_; - std::string lidar_frame_; - std::size_t points_per_pointcloud_; - std::size_t capacity_; - double delta_pointcloud_x_; + std::string world_frame_{}; + std::string lidar_frame_{}; + std::size_t points_per_pointcloud_{}; + std::size_t capacity_{}; + double delta_pointcloud_x_{}; - std::size_t class_size_; - float point_feature_size_; - std::size_t max_voxel_size_; + std::size_t class_size_{}; + float point_feature_size_{}; + std::size_t max_voxel_size_{}; - std::vector point_cloud_range_; - std::vector voxel_size_; - std::size_t downsample_factor_; - std::size_t encoder_in_feature_size_; - float score_threshold_; - float circle_nms_dist_threshold_; - std::vector yaw_norm_thresholds_; - bool has_variance_; + std::vector point_cloud_range_{}; + std::vector voxel_size_{}; + std::size_t downsample_factor_{}; + std::size_t encoder_in_feature_size_{}; + float score_threshold_{}; + float circle_nms_dist_threshold_{}; + std::vector yaw_norm_thresholds_{}; + bool has_variance_{}; + + cudaStream_t stream_{}; }; #endif // TEST_VOXEL_GENERATOR_HPP_ From d677314be5430ba36b284aca9d85a7fce4351f5c Mon Sep 17 00:00:00 2001 From: Zhe Shen <80969277+HansOersted@users.noreply.github.com> Date: Thu, 20 Jun 2024 10:29:18 +0900 Subject: [PATCH 030/217] fix(mpc_lateral_controller): align the MPC steering angle when the car is controlled manually. (#7109) * align the MPC steering angle when the car is controlled manually. Signed-off-by: Zhe Shen * update the condition for is_driving_manually Signed-off-by: Zhe Shen * STOP mode included Signed-off-by: Zhe Shen * comment the is_driving_manually Signed-off-by: Zhe Shen * align the steering outside (after) the solver. Signed-off-by: Zhe Shen * use the flag input_data.current_operation_mode.is_autoware_control_enabled Signed-off-by: Zhe Shen * correct a typo Signed-off-by: Zhe Shen * correct the under control condition check Signed-off-by: Zhe Shen * undo the space delete Signed-off-by: Zhe Shen * unchange the unrelevant line Signed-off-by: Zhe Shen * pre-commit Signed-off-by: Zhe Shen --------- Signed-off-by: Zhe Shen --- control/autoware_mpc_lateral_controller/src/mpc.cpp | 2 +- .../src/mpc_lateral_controller.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/control/autoware_mpc_lateral_controller/src/mpc.cpp b/control/autoware_mpc_lateral_controller/src/mpc.cpp index 309704596086e..23235fe445e24 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc.cpp @@ -244,7 +244,7 @@ void MPC::setReferenceTrajectory( void MPC::resetPrevResult(const SteeringReport & current_steer) { - // Consider limit. The prev value larger than limitation brakes the optimization constraint and + // Consider limit. The prev value larger than limitation breaks the optimization constraint and // results in optimization failure. const float steer_lim_f = static_cast(m_steer_lim); m_raw_steer_cmd_prev = std::clamp(current_steer.steering_tire_angle, -steer_lim_f, steer_lim_f); diff --git a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp index 0661b439a3982..83a19cbe86acf 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -287,7 +287,7 @@ trajectory_follower::LateralOutput MpcLateralController::run( // the vehicle will return to the path by re-planning the trajectory or external operation. // After the recovery, the previous value of the optimization may deviate greatly from // the actual steer angle, and it may make the optimization result unstable. - if (!is_mpc_solved) { + if (!is_mpc_solved || !is_under_control) { m_mpc->resetPrevResult(m_current_steering); } else { setSteeringToHistory(ctrl_cmd); From 5aa747b26c325db9ef76d5b26ea51723b00904ff Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 20 Jun 2024 11:04:04 +0900 Subject: [PATCH 031/217] refactor(universe_utils/motion_utils)!: add autoware namespace (#7594) Signed-off-by: kosuke55 --- .../test/benchmark.cpp | 2 +- .../autoware/motion_utils/constants.hpp | 4 +- .../motion_utils/distance/distance.hpp | 4 +- .../factor/velocity_factor_interface.hpp | 4 +- .../motion_utils/marker/marker_helper.hpp | 4 +- .../marker/virtual_wall_marker_creator.hpp | 4 +- .../motion_utils/resample/resample.hpp | 4 +- .../motion_utils/resample/resample_utils.hpp | 26 +- .../motion_utils/trajectory/conversion.hpp | 4 +- .../motion_utils/trajectory/interpolation.hpp | 16 +- .../trajectory/path_with_lane_id.hpp | 4 +- .../motion_utils/trajectory/trajectory.hpp | 224 +++++------ .../vehicle/vehicle_state_checker.hpp | 4 +- .../src/distance/distance.cpp | 4 +- .../src/factor/velocity_factor_interface.cpp | 6 +- .../src/marker/marker_helper.cpp | 18 +- .../marker/virtual_wall_marker_creator.cpp | 10 +- .../src/resample/resample.cpp | 62 +-- .../src/trajectory/conversion.cpp | 4 +- .../src/trajectory/interpolation.cpp | 26 +- .../src/trajectory/path_with_lane_id.cpp | 12 +- .../src/trajectory/trajectory.cpp | 4 +- .../src/vehicle/vehicle_state_checker.cpp | 8 +- .../test/src/distance/test_distance.cpp | 2 +- .../test_virtual_wall_marker_creator.cpp | 16 +- .../test/src/resample/test_resample.cpp | 84 ++-- .../benchmark_calcLateralOffset.cpp | 6 +- .../src/trajectory/test_interpolation.cpp | 12 +- .../src/trajectory/test_path_with_lane_id.cpp | 12 +- .../test/src/trajectory/test_trajectory.cpp | 374 +++++++++--------- .../vehicle/test_vehicle_state_checker.cpp | 10 +- .../autoware_test_utils.hpp | 4 +- .../geometry/boost_geometry.hpp | 14 +- .../geometry/boost_polygon_utils.hpp | 4 +- .../universe_utils/geometry/geometry.hpp | 4 +- .../geometry/pose_deviation.hpp | 4 +- .../universe_utils/math/constants.hpp | 4 +- .../universe_utils/math/normalization.hpp | 4 +- .../autoware/universe_utils/math/range.hpp | 4 +- .../universe_utils/math/sin_table.hpp | 4 +- .../universe_utils/math/trigonometry.hpp | 4 +- .../universe_utils/math/unit_conversion.hpp | 4 +- .../universe_utils/ros/debug_publisher.hpp | 6 +- .../universe_utils/ros/debug_traits.hpp | 4 +- .../ros/logger_level_configure.hpp | 6 +- .../universe_utils/ros/marker_helper.hpp | 4 +- .../universe_utils/ros/msg_covariance.hpp | 4 +- .../autoware/universe_utils/ros/parameter.hpp | 4 +- .../universe_utils/ros/pcl_conversion.hpp | 4 +- .../universe_utils/ros/polling_subscriber.hpp | 4 +- .../ros/processing_time_publisher.hpp | 4 +- .../ros/published_time_publisher.hpp | 4 +- .../universe_utils/ros/self_pose_listener.hpp | 4 +- .../universe_utils/ros/transform_listener.hpp | 4 +- .../universe_utils/ros/update_param.hpp | 4 +- .../universe_utils/ros/uuid_helper.hpp | 4 +- .../universe_utils/ros/wait_for_param.hpp | 4 +- .../universe_utils/system/backtrace.hpp | 4 +- .../universe_utils/system/stop_watch.hpp | 4 +- .../universe_utils/transform/transforms.hpp | 4 +- .../src/geometry/boost_polygon_utils.cpp | 36 +- .../src/geometry/geometry.cpp | 6 +- .../src/geometry/pose_deviation.cpp | 4 +- .../src/math/sin_table.cpp | 4 +- .../src/math/trigonometry.cpp | 10 +- .../src/ros/logger_level_configure.cpp | 4 +- .../src/ros/marker_helper.cpp | 4 +- .../src/system/backtrace.cpp | 4 +- .../test/src/geometry/test_boost_geometry.cpp | 8 +- .../src/geometry/test_boost_polygon_utils.cpp | 20 +- .../test/src/geometry/test_geometry.cpp | 216 +++++----- .../test_path_with_lane_id_geometry.cpp | 10 +- .../test/src/geometry/test_pose_deviation.cpp | 6 +- .../test/src/math/test_constants.cpp | 4 +- .../test/src/math/test_normalization.cpp | 4 +- .../test/src/math/test_range.cpp | 12 +- .../test/src/math/test_trigonometry.cpp | 12 +- .../test/src/math/test_unit_conversion.cpp | 10 +- .../src/ros/test_published_time_publisher.cpp | 8 +- .../test/src/system/test_stop_watch.cpp | 4 +- .../test/src/transform/test_transform.cpp | 6 +- .../goal_distance_calculator.hpp | 2 +- .../goal_distance_calculator_node.hpp | 4 +- .../src/goal_distance_calculator.cpp | 2 +- .../src/goal_distance_calculator_node.cpp | 2 +- .../spline_interpolation_points_2d.hpp | 2 +- .../src/spline_interpolation_points_2d.cpp | 2 +- .../test_spline_interpolation_points_2d.cpp | 6 +- .../object_recognition_utils/matching.hpp | 20 +- .../src/predicted_path_utils.cpp | 4 +- .../test/src/test_matching.cpp | 6 +- .../test/src/test_predicted_path_utils.cpp | 28 +- .../src/path_distance_calculator.cpp | 2 +- .../src/path_distance_calculator.hpp | 2 +- .../path/display.hpp | 10 +- .../path/display_base.hpp | 16 +- .../tier4_planning_rviz_plugin/utils.hpp | 10 +- .../src/tools/acceleration_meter.cpp | 8 +- .../src/tools/acceleration_meter.hpp | 4 +- .../src/tools/console_meter.cpp | 8 +- .../src/tools/console_meter.hpp | 8 +- .../autonomous_emergency_braking/node.hpp | 20 +- .../autonomous_emergency_braking/utils.hpp | 4 +- .../src/node.cpp | 90 ++--- .../src/utils.cpp | 4 +- .../control_validator/control_validator.hpp | 4 +- .../autoware/control_validator/utils.hpp | 4 +- .../src/debug_marker.cpp | 16 +- .../autoware_control_validator/src/utils.cpp | 16 +- .../joy_controller/joy_controller.hpp | 4 +- .../lane_departure_checker.hpp | 8 +- .../lane_departure_checker_node.hpp | 14 +- .../lane_departure_checker.cpp | 46 +-- .../lane_departure_checker_node.cpp | 10 +- .../mpc_lateral_controller/mpc_trajectory.hpp | 2 +- .../src/mpc.cpp | 18 +- .../src/mpc_lateral_controller.cpp | 4 +- .../src/mpc_utils.cpp | 16 +- .../src/node.hpp | 4 +- .../src/state.cpp | 10 +- .../longitudinal_controller_utils.hpp | 6 +- .../pid_longitudinal_controller.hpp | 6 +- .../src/longitudinal_controller_utils.cpp | 12 +- .../src/pid_longitudinal_controller.cpp | 16 +- .../autoware_pure_pursuit_node.hpp | 6 +- ...toware_pure_pursuit_lateral_controller.cpp | 26 +- .../shift_decider/autoware_shift_decider.hpp | 6 +- .../controller_node.hpp | 17 +- .../simple_trajectory_follower.hpp | 4 +- .../src/controller_node.cpp | 10 +- .../src/simple_trajectory_follower.cpp | 6 +- .../src/vehicle_cmd_gate.cpp | 6 +- .../src/vehicle_cmd_gate.hpp | 22 +- .../src/control_performance_analysis_core.cpp | 16 +- .../obstacle_collision_checker.hpp | 2 +- .../obstacle_collision_checker_node.hpp | 8 +- .../obstacle_collision_checker.cpp | 19 +- .../obstacle_collision_checker_node.cpp | 14 +- .../collision_checker.hpp | 4 +- .../predicted_path_checker/debug_marker.hpp | 4 +- .../predicted_path_checker_node.hpp | 6 +- .../include/predicted_path_checker/utils.hpp | 4 +- .../collision_checker.cpp | 6 +- .../debug_marker.cpp | 22 +- .../predicted_path_checker_node.cpp | 38 +- .../src/predicted_path_checker_node/utils.cpp | 60 +-- .../control_evaluator_node.hpp | 4 +- .../src/metrics/deviation_metrics.cpp | 9 +- .../src/metrics/deviation_metrics.cpp | 16 +- .../src/metrics/metrics_utils.cpp | 2 +- .../src/metrics/obstacle_metrics.cpp | 2 +- .../src/metrics/stability_metrics.cpp | 21 +- .../src/metrics/trajectory_metrics.cpp | 4 +- .../src/metrics_calculator.cpp | 4 +- .../utils/marker_utils.hpp | 2 +- .../src/metrics/detection_count.cpp | 2 +- .../src/metrics/deviation_metrics.cpp | 12 +- .../src/metrics_calculator.cpp | 28 +- .../src/perception_online_evaluator_node.cpp | 8 +- .../src/utils/marker_utils.cpp | 24 +- .../test_perception_online_evaluator_node.cpp | 2 +- .../src/ar_tag_based_localizer.cpp | 4 +- .../src/landmark_manager.cpp | 4 +- .../include/ekf_localizer/ekf_localizer.hpp | 4 +- localization/ekf_localizer/src/covariance.cpp | 2 +- .../ekf_localizer/src/ekf_localizer.cpp | 12 +- localization/ekf_localizer/src/ekf_module.cpp | 10 +- .../ekf_localizer/src/measurement.cpp | 4 +- .../gyro_odometer/gyro_odometer_core.hpp | 6 +- .../gyro_odometer/src/gyro_odometer_core.cpp | 10 +- .../localization_error_monitor.hpp | 2 +- .../src/localization_error_monitor.cpp | 2 +- .../ndt_scan_matcher_core.hpp | 2 +- .../src/ndt_scan_matcher_core.cpp | 16 +- .../switch_rule/pcd_map_based_rule.cpp | 4 +- .../pose_estimator_arbiter.hpp | 2 +- .../pose_estimator_arbiter_core.cpp | 2 +- .../pose_initializer_core.cpp | 2 +- .../pose_initializer_core.hpp | 2 +- .../pose_initializer/stop_check_module.hpp | 2 +- .../src/pose_instability_detector.cpp | 2 +- .../ll2_decomposer/ll2_decomposer_core.cpp | 4 +- .../src/graph_segment/graph_segment_core.cpp | 2 +- .../line_segment_detector_core.cpp | 2 +- .../src/undistort/undistort_node.cpp | 4 +- .../camera_particle_corrector_core.cpp | 4 +- .../ll2_cost_map/hierarchical_cost_map.cpp | 2 +- .../node.hpp | 4 +- .../map_based_prediction_node.hpp | 16 +- .../src/debug.cpp | 4 +- .../src/map_based_prediction_node.cpp | 102 ++--- .../src/path_generator.cpp | 39 +- .../include/cluster_merger/node.hpp | 2 +- ...tance_based_compare_map_filter_nodelet.cpp | 4 +- ...approximate_compare_map_filter_nodelet.cpp | 4 +- ...voxel_based_compare_map_filter_nodelet.cpp | 4 +- ...tance_based_compare_map_filter_nodelet.cpp | 4 +- .../detected_object_feature_remover.hpp | 2 +- .../src/detected_object_feature_remover.cpp | 2 +- .../object_lanelet_filter.hpp | 12 +- .../object_position_filter.hpp | 2 +- .../obstacle_pointcloud_based_validator.hpp | 4 +- .../occupancy_grid_based_validator.hpp | 2 +- .../src/object_lanelet_filter.cpp | 12 +- .../src/object_position_filter.cpp | 2 +- .../obstacle_pointcloud_based_validator.cpp | 14 +- .../src/occupancy_grid_based_validator.cpp | 8 +- .../include/detection_by_tracker/debugger.hpp | 8 +- .../detection_by_tracker_core.hpp | 2 +- .../src/detection_by_tracker_core.cpp | 12 +- .../src/elevation_map_loader_node.cpp | 2 +- .../src/euclidean_cluster_node.cpp | 4 +- .../src/euclidean_cluster_node.hpp | 4 +- ...oxel_grid_based_euclidean_cluster_node.cpp | 4 +- ...oxel_grid_based_euclidean_cluster_node.hpp | 4 +- .../scan_ground_filter_nodelet.hpp | 4 +- .../src/scan_ground_filter_nodelet.cpp | 12 +- .../fusion_node.hpp | 4 +- .../src/fusion_node.cpp | 4 +- .../src/utils/utils.cpp | 4 +- .../node.hpp | 4 +- .../src/detector.cpp | 5 +- .../src/node.cpp | 4 +- .../src/lidar_apollo_segmentation_tvm.cpp | 4 +- .../include/lidar_centerpoint/node.hpp | 6 +- .../postprocess/non_maximum_suppression.cpp | 2 +- .../lidar_centerpoint/lib/ros_utils.cpp | 12 +- perception/lidar_centerpoint/src/node.cpp | 6 +- .../include/lidar_centerpoint_tvm/node.hpp | 4 +- .../lidar_centerpoint_tvm/lib/ros_utils.cpp | 8 +- perception/lidar_centerpoint_tvm/src/node.cpp | 4 +- .../lidar_transfusion_node.hpp | 6 +- .../lidar_transfusion/transfusion_trt.hpp | 2 +- .../postprocess/non_maximum_suppression.cpp | 2 +- .../lidar_transfusion/lib/ros_utils.cpp | 8 +- .../lidar_transfusion/lib/transfusion_trt.cpp | 2 +- .../src/lidar_transfusion_node.cpp | 6 +- .../debugger/debugger.hpp | 2 +- .../multi_object_tracker_core.hpp | 2 +- .../src/data_association/data_association.cpp | 8 +- .../src/debugger/debugger.cpp | 2 +- .../src/multi_object_tracker_core.cpp | 2 +- .../src/tracker/model/bicycle_tracker.cpp | 18 +- .../src/tracker/model/big_vehicle_tracker.cpp | 22 +- .../tracker/model/normal_vehicle_tracker.cpp | 22 +- .../src/tracker/model/pedestrian_tracker.cpp | 28 +- .../src/tracker/model/unknown_tracker.cpp | 8 +- .../motion_model/bicycle_motion_model.cpp | 18 +- .../motion_model/ctrv_motion_model.cpp | 18 +- .../tracker/motion_model/cv_motion_model.cpp | 4 +- .../include/object_merger/node.hpp | 6 +- .../data_association/data_association.cpp | 6 +- .../src/object_association_merger/node.cpp | 8 +- .../object_velocity_splitter_node.cpp | 2 +- ...upancy_grid_map_outlier_filter_nodelet.hpp | 6 +- ...upancy_grid_map_outlier_filter_nodelet.cpp | 6 +- .../synchronized_grid_map_fusion_node.hpp | 4 +- ...intcloud_based_occupancy_grid_map_node.hpp | 4 +- .../synchronized_grid_map_fusion_node.cpp | 4 +- .../occupancy_grid_map_fixed.cpp | 6 +- .../occupancy_grid_map_projective.cpp | 6 +- ...intcloud_based_occupancy_grid_map_node.cpp | 4 +- .../src/utils/utils.cpp | 6 +- ...dar_crossing_objects_noise_filter_node.cpp | 4 +- ...radar_crossing_objects_filter_is_noise.cpp | 24 +- .../radar_fusion_to_detected_object.hpp | 4 +- .../src/radar_fusion_to_detected_object.cpp | 22 +- perception/radar_object_clustering/README.md | 4 +- .../radar_object_clustering_node.cpp | 4 +- .../src/data_association/data_association.cpp | 8 +- .../constant_turn_rate_motion_tracker.cpp | 6 +- .../tracker/model/linear_motion_tracker.cpp | 6 +- .../src/utils/radar_object_tracker_utils.cpp | 8 +- .../radar_tracks_msgs_converter_node.hpp | 2 +- .../radar_tracks_msgs_converter_node.cpp | 18 +- .../low_intensity_cluster_filter.hpp | 4 +- .../src/low_intensity_cluster_filter.cpp | 8 +- .../shape_estimation/lib/corrector/utils.cpp | 4 +- perception/shape_estimation/src/node.cpp | 8 +- perception/shape_estimation/src/node.hpp | 6 +- .../simple_object_merger_node.hpp | 2 +- .../simple_object_merger_node.cpp | 2 +- .../tensorrt_yolox/tensorrt_yolox_node.hpp | 4 +- .../src/tensorrt_yolox_node.cpp | 4 +- .../decorative_tracker_merger.hpp | 6 +- .../src/data_association/data_association.cpp | 6 +- .../src/decorative_tracker_merger.cpp | 6 +- .../src/utils/utils.cpp | 4 +- .../src/node.cpp | 9 +- .../src/occlusion_predictor.cpp | 2 +- .../freespace_planner_node.hpp | 2 +- .../freespace_planner_node.cpp | 10 +- .../src/abstract_algorithm.cpp | 6 +- .../src/astar_search.cpp | 10 +- .../src/lanelet2_plugins/default_planner.cpp | 44 +-- .../src/lanelet2_plugins/default_planner.hpp | 4 +- .../lanelet2_plugins/utility_functions.cpp | 8 +- .../lanelet2_plugins/utility_functions.hpp | 4 +- .../src/mission_planner/arrival_checker.cpp | 6 +- .../src/mission_planner/arrival_checker.hpp | 2 +- .../src/mission_planner/mission_planner.cpp | 2 +- .../src/mission_planner/mission_planner.hpp | 4 +- .../src/coloring.cpp | 2 +- .../src/marker_utils.cpp | 10 +- .../common_structs.hpp | 49 +-- .../autoware/obstacle_cruise_planner/node.hpp | 12 +- .../planner_interface.hpp | 30 +- .../obstacle_cruise_planner/polygon_utils.hpp | 4 +- .../obstacle_cruise_planner/type_alias.hpp | 4 +- .../obstacle_cruise_planner/utils.hpp | 4 +- .../src/node.cpp | 168 ++++---- .../optimization_based_planner.cpp | 30 +- .../pid_based_planner/pid_based_planner.cpp | 56 +-- .../src/planner_interface.cpp | 84 ++-- .../src/polygon_utils.cpp | 12 +- .../src/utils.cpp | 6 +- .../path_optimizer/common_structs.hpp | 6 +- .../autoware/path_optimizer/mpt_optimizer.hpp | 4 +- .../include/autoware/path_optimizer/node.hpp | 8 +- .../path_optimizer/utils/geometry_utils.hpp | 8 +- .../path_optimizer/utils/trajectory_utils.hpp | 26 +- .../src/debug_marker.cpp | 48 +-- .../src/mpt_optimizer.cpp | 48 +-- planning/autoware_path_optimizer/src/node.cpp | 36 +- .../src/replan_checker.cpp | 18 +- .../src/utils/geometry_utils.cpp | 22 +- .../src/utils/trajectory_utils.cpp | 28 +- .../autoware/path_smoother/common_structs.hpp | 6 +- .../path_smoother/elastic_band_smoother.hpp | 8 +- .../path_smoother/utils/geometry_utils.hpp | 4 +- .../path_smoother/utils/trajectory_utils.hpp | 16 +- .../src/elastic_band.cpp | 14 +- .../src/elastic_band_smoother.cpp | 26 +- .../src/replan_checker.cpp | 18 +- .../src/utils/trajectory_utils.cpp | 14 +- .../autoware_planning_test_manager_utils.hpp | 4 +- .../src/autoware_planning_test_manager.cpp | 2 +- .../src/path_to_trajectory.cpp | 4 +- .../planning_validator/planning_validator.hpp | 8 +- .../src/debug_marker.cpp | 18 +- .../src/planning_validator.cpp | 18 +- .../autoware_planning_validator/src/utils.cpp | 14 +- .../src/test_planning_validator_helper.cpp | 2 +- ...emaining_distance_time_calculator_node.cpp | 2 +- .../src/route_handler.cpp | 8 +- .../test/test_route_handler.cpp | 45 +-- .../autoware/scenario_selector/node.hpp | 6 +- .../autoware_scenario_selector/src/node.cpp | 2 +- .../bag_ego_trajectory_based_centerline.cpp | 4 +- ...timization_trajectory_based_centerline.cpp | 16 +- .../src/static_centerline_generator_node.cpp | 33 +- .../src/type_alias.hpp | 6 +- .../src/utils.cpp | 16 +- .../src/debug_marker.cpp | 12 +- .../src/node.cpp | 12 +- .../src/node.hpp | 12 +- .../autoware/velocity_smoother/node.hpp | 14 +- .../autoware_velocity_smoother/src/node.cpp | 42 +- .../src/resample.cpp | 32 +- .../analytical_jerk_constrained_smoother.cpp | 14 +- .../velocity_planning_utils.cpp | 4 +- .../src/smoother/jerk_filtered_smoother.cpp | 8 +- .../src/smoother/smoother_base.cpp | 20 +- .../src/trajectory_utils.cpp | 20 +- .../src/manager.cpp | 2 +- .../src/scene.cpp | 6 +- .../scene.hpp | 16 +- .../src/manager.cpp | 2 +- .../src/scene.cpp | 196 ++++----- .../fixed_goal_planner_base.hpp | 2 +- .../goal_planner_module.hpp | 8 +- .../goal_searcher.hpp | 2 +- .../goal_searcher_base.hpp | 2 +- .../pull_over_planner_base.hpp | 6 +- .../util.hpp | 6 +- .../src/default_fixed_goal_planner.cpp | 2 +- .../src/freespace_pull_over.cpp | 6 +- .../src/goal_planner_module.cpp | 84 ++-- .../src/goal_searcher.cpp | 18 +- .../src/manager.cpp | 2 +- .../src/shift_pull_over.cpp | 18 +- .../src/util.cpp | 52 +-- .../utils/base_class.hpp | 2 +- .../utils/utils.hpp | 2 +- .../src/interface.cpp | 6 +- .../src/manager.cpp | 4 +- .../src/scene.cpp | 46 +-- .../src/utils/markers.cpp | 6 +- .../src/utils/utils.cpp | 68 ++-- .../test/test_lane_change_utils.cpp | 14 +- .../behavior_path_planner_node.hpp | 28 +- .../behavior_path_planner/planner_manager.hpp | 4 +- .../src/behavior_path_planner_node.cpp | 46 +-- .../src/planner_manager.cpp | 8 +- .../test/test_utils.cpp | 4 +- .../data_manager.hpp | 6 +- .../interface/scene_module_interface.hpp | 8 +- .../scene_module_manager_interface.hpp | 14 +- .../marker_utils/colors.hpp | 24 +- .../marker_utils/utils.hpp | 2 +- .../turn_signal_decider.hpp | 4 +- .../utils/drivable_area_expansion/types.hpp | 14 +- .../path_safety_checker/objects_filtering.hpp | 2 +- .../path_safety_checker_parameters.hpp | 2 +- .../path_safety_checker/safety_check.hpp | 6 +- .../utils/path_shifter/path_shifter.hpp | 2 +- .../utils/utils.hpp | 18 +- .../src/marker_utils/utils.cpp | 26 +- .../src/turn_signal_decider.cpp | 56 +-- .../drivable_area_expansion.cpp | 40 +- .../drivable_area_expansion/footprints.cpp | 2 +- .../static_drivable_area.cpp | 93 ++--- ...ccupancy_grid_based_collision_detector.cpp | 6 +- .../geometric_parallel_parking.cpp | 24 +- .../src/utils/parking_departure/utils.cpp | 6 +- .../path_safety_checker/objects_filtering.cpp | 14 +- .../path_safety_checker/safety_check.cpp | 86 ++-- .../src/utils/path_shifter/path_shifter.cpp | 8 +- .../src/utils/path_utils.cpp | 34 +- .../src/utils/traffic_light_utils.cpp | 4 +- .../src/utils/utils.cpp | 101 ++--- .../test/test_safety_check.cpp | 22 +- .../test/test_turn_signal.cpp | 58 +-- .../sampling_planner_module.hpp | 8 +- .../sampling_planner_parameters.hpp | 10 +- .../util.hpp | 2 +- .../src/manager.cpp | 2 +- .../src/sampling_planner_module.cpp | 24 +- .../src/manager.cpp | 2 +- .../src/scene.cpp | 19 +- .../pull_out_planner_base.hpp | 2 +- .../src/freespace_pull_out.cpp | 2 +- .../src/geometric_pull_out.cpp | 12 +- .../src/manager.cpp | 2 +- .../src/shift_pull_out.cpp | 23 +- .../src/start_planner_module.cpp | 68 ++-- .../src/util.cpp | 8 +- .../helper.hpp | 12 +- .../parameter_helper.hpp | 2 +- .../scene.hpp | 4 +- .../type_alias.hpp | 32 +- .../src/debug.cpp | 2 +- .../src/manager.cpp | 4 +- .../src/scene.cpp | 32 +- .../src/shift_line_generator.cpp | 8 +- .../src/utils.cpp | 74 ++-- .../src/debug.cpp | 14 +- .../src/decisions.cpp | 4 +- .../src/scene.cpp | 22 +- .../src/scene.hpp | 2 +- .../src/debug.cpp | 26 +- .../src/manager.cpp | 2 +- .../src/occluded_crosswalk.cpp | 2 +- .../src/scene_crosswalk.cpp | 59 +-- .../src/scene_crosswalk.hpp | 8 +- .../src/util.cpp | 12 +- .../src/debug.cpp | 22 +- .../src/manager.cpp | 2 +- .../src/scene.cpp | 6 +- .../src/scene.hpp | 2 +- .../src/debug.cpp | 38 +- .../src/intersection_lanelets.cpp | 2 +- .../src/intersection_lanelets.hpp | 2 +- .../src/manager.cpp | 2 +- .../src/object_manager.cpp | 20 +- .../src/scene_intersection.cpp | 38 +- .../src/scene_intersection.hpp | 2 +- .../src/scene_intersection_collision.cpp | 48 +-- .../src/scene_intersection_occlusion.cpp | 17 +- .../src/scene_intersection_prepare_data.cpp | 24 +- .../src/scene_intersection_stuck.cpp | 6 +- .../src/scene_merge_from_private_road.cpp | 8 +- .../src/scene_merge_from_private_road.hpp | 2 +- .../src/util.cpp | 18 +- .../src/util.hpp | 6 +- .../src/debug.cpp | 18 +- .../src/manager.cpp | 2 +- .../src/scene.cpp | 26 +- .../src/scene.hpp | 2 +- .../src/util.cpp | 4 +- .../src/debug.cpp | 18 +- .../src/manager.cpp | 2 +- .../src/scene_no_stopping_area.cpp | 18 +- .../src/scene_no_stopping_area.hpp | 2 +- .../src/debug.cpp | 20 +- .../src/grid_utils.cpp | 8 +- .../src/grid_utils.hpp | 6 +- .../src/manager.cpp | 2 +- .../src/occlusion_spot_utils.cpp | 13 +- .../src/scene_occlusion_spot.cpp | 6 +- .../src/scene_occlusion_spot.hpp | 4 +- .../test/src/test_grid_utils.cpp | 2 +- .../src/node.cpp | 8 +- .../src/node.hpp | 20 +- .../scene_module_interface.hpp | 14 +- .../utilization/arc_lane_util.hpp | 22 +- .../utilization/boost_geometry_helper.hpp | 6 +- .../utilization/util.hpp | 6 +- .../src/scene_module_interface.cpp | 8 +- .../src/utilization/debug.cpp | 10 +- .../src/utilization/path_utilization.cpp | 8 +- .../src/utilization/trajectory_utils.cpp | 6 +- .../src/utilization/util.cpp | 50 +-- .../test/src/test_utilization.cpp | 4 +- .../src/debug.cpp | 30 +- .../src/debug.hpp | 2 +- .../src/dynamic_obstacle.cpp | 46 +-- .../src/manager.cpp | 2 +- .../src/path_utils.cpp | 2 +- .../src/scene.cpp | 84 ++-- .../src/scene.hpp | 2 +- .../src/utils.cpp | 40 +- .../src/utils.hpp | 8 +- .../src/debug.cpp | 16 +- .../src/manager.cpp | 2 +- .../src/scene.cpp | 4 +- .../src/scene.hpp | 2 +- .../README.md | 2 +- .../src/manager.cpp | 2 +- .../src/scene.cpp | 4 +- .../src/scene.hpp | 7 +- .../src/debug.cpp | 14 +- .../src/manager.cpp | 2 +- .../src/scene.cpp | 2 +- .../src/scene.hpp | 2 +- .../src/debug.cpp | 32 +- .../src/manager.cpp | 8 +- .../src/scene.cpp | 48 +-- .../src/scene.hpp | 10 +- .../src/debug.cpp | 24 +- .../src/manager.cpp | 2 +- .../src/scene_walkway.cpp | 10 +- .../src/scene_walkway.hpp | 2 +- .../src/debug.cpp | 24 +- .../src/manager.cpp | 2 +- .../src/scene.cpp | 4 +- .../src/scene.hpp | 2 +- .../src/util.cpp | 10 +- .../src/collision.cpp | 12 +- .../src/collision.hpp | 4 +- .../src/debug.cpp | 10 +- .../src/debug.hpp | 2 +- .../src/dynamic_obstacle_stop_module.cpp | 32 +- .../src/footprint.cpp | 20 +- .../src/footprint.hpp | 9 +- .../src/object_filtering.cpp | 6 +- .../src/object_stop_decision.cpp | 4 +- .../src/types.hpp | 8 +- .../src/obstacle_velocity_limiter.cpp | 6 +- .../src/obstacle_velocity_limiter.hpp | 2 +- .../src/obstacle_velocity_limiter_module.cpp | 10 +- .../src/trajectory_preprocessing.cpp | 6 +- .../src/types.hpp | 14 +- .../test/test_collision_distance.cpp | 4 +- .../src/calculate_slowdown_points.cpp | 10 +- .../src/calculate_slowdown_points.hpp | 2 +- .../src/debug.cpp | 49 +-- .../src/debug.hpp | 2 +- .../src/decisions.cpp | 25 +- .../src/filter_predicted_objects.cpp | 8 +- .../src/footprint.cpp | 14 +- .../src/footprint.hpp | 5 +- .../src/lanelets_selection.cpp | 2 +- .../src/out_of_lane_module.cpp | 24 +- .../plugin_module_interface.hpp | 4 +- .../src/node.cpp | 22 +- .../src/node.hpp | 20 +- .../obstacle_stop_planner/debug_marker.hpp | 4 +- .../include/obstacle_stop_planner/node.hpp | 10 +- .../obstacle_stop_planner/planner_utils.hpp | 4 +- .../src/adaptive_cruise_control.cpp | 8 +- .../src/debug_marker.cpp | 24 +- planning/obstacle_stop_planner/src/node.cpp | 38 +- .../src/planner_utils.cpp | 50 +-- .../src/frenet_planner/frenet_planner.cpp | 2 +- .../autoware_path_sampler/common_structs.hpp | 10 +- .../include/autoware_path_sampler/node.hpp | 4 +- .../utils/geometry_utils.hpp | 4 +- .../utils/trajectory_utils.hpp | 18 +- .../autoware_path_sampler/src/node.cpp | 26 +- .../src/prepare_inputs.cpp | 2 +- .../src/utils/trajectory_utils.cpp | 20 +- .../autoware_sampler_common/structures.hpp | 12 +- .../src/gyro_bias_estimation_module.cpp | 10 +- .../imu_corrector/src/gyro_bias_estimator.cpp | 8 +- .../imu_corrector/src/gyro_bias_estimator.hpp | 2 +- .../imu_corrector/src/imu_corrector_core.cpp | 4 +- .../imu_corrector/src/imu_corrector_core.hpp | 4 +- .../concatenate_and_time_sync_nodelet.hpp | 4 +- .../concatenate_pointclouds.hpp | 4 +- .../distortion_corrector.hpp | 4 +- .../pointcloud_preprocessor/filter.hpp | 6 +- .../time_synchronizer_nodelet.hpp | 4 +- .../lanelet2_map_filter_nodelet.hpp | 6 +- .../vector_map_inside_area_filter.hpp | 2 +- .../concatenate_and_time_sync_nodelet.cpp | 4 +- .../concatenate_pointclouds.cpp | 4 +- .../crop_box_filter_nodelet.cpp | 4 +- .../distortion_corrector.cpp | 12 +- ...kup_based_voxel_grid_downsample_filter.cpp | 4 +- .../pointcloud_preprocessor/src/filter.cpp | 2 +- .../ring_outlier_filter_nodelet.cpp | 4 +- .../time_synchronizer_nodelet.cpp | 4 +- .../vector_map_inside_area_filter.cpp | 6 +- .../radar_static_pointcloud_filter_node.hpp | 2 +- .../radar_static_pointcloud_filter_node.cpp | 2 +- .../dummy_perception_publisher/src/node.cpp | 2 +- .../simple_planning_simulator_core.cpp | 18 +- system/default_ad_api/src/motion.hpp | 2 +- system/default_ad_api/src/planning.cpp | 2 +- system/default_ad_api/src/planning.hpp | 2 +- .../src/dummy_diag_publisher_core.cpp | 4 +- .../emergency_handler_core.hpp | 8 +- .../mrm_emergency_stop_operator_core.cpp | 2 +- .../include/mrm_handler/mrm_handler_core.hpp | 12 +- .../system_error_monitor_core.hpp | 2 +- .../src/system_error_monitor_core.cpp | 2 +- .../src/ntp_monitor/ntp_monitor.cpp | 2 +- .../src/process_monitor/process_monitor.cpp | 2 +- .../src/reaction_analyzer_node.cpp | 4 +- tools/reaction_analyzer/src/subscriber.cpp | 10 +- tools/reaction_analyzer/src/utils.cpp | 32 +- .../accel_brake_map_calibrator_node.hpp | 12 +- .../src/accel_brake_map_calibrator_node.cpp | 4 +- .../autoware_external_cmd_converter/node.hpp | 6 +- .../node.hpp | 6 +- .../src/node.cpp | 2 +- .../vehicle_info.hpp | 4 +- .../src/vehicle_info.cpp | 8 +- 629 files changed, 4210 insertions(+), 4170 deletions(-) diff --git a/common/autoware_grid_map_utils/test/benchmark.cpp b/common/autoware_grid_map_utils/test/benchmark.cpp index 90545135b3e18..a63ed9985fef1 100644 --- a/common/autoware_grid_map_utils/test/benchmark.cpp +++ b/common/autoware_grid_map_utils/test/benchmark.cpp @@ -46,7 +46,7 @@ int main(int argc, char * argv[]) result_file << "#Size PolygonVertices PolygonIndexes grid_map_utils_constructor grid_map_utils_iteration " "grid_map_constructor grid_map_iteration\n"; - autoware_universe_utils::StopWatch stopwatch; + autoware::universe_utils::StopWatch stopwatch; constexpr auto nb_iterations = 10; constexpr auto polygon_side_vertices = diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/constants.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/constants.hpp index 278ea3fbcae80..9c1f7c876e73e 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/constants.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/constants.hpp @@ -15,9 +15,9 @@ #ifndef AUTOWARE__MOTION_UTILS__CONSTANTS_HPP_ #define AUTOWARE__MOTION_UTILS__CONSTANTS_HPP_ -namespace autoware_motion_utils +namespace autoware::motion_utils { constexpr double overlap_threshold = 0.1; -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils #endif // AUTOWARE__MOTION_UTILS__CONSTANTS_HPP_ diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/distance/distance.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/distance/distance.hpp index 4b4aec2f5b398..308528954eccc 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/distance/distance.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/distance/distance.hpp @@ -22,12 +22,12 @@ #include #include -namespace autoware_motion_utils +namespace autoware::motion_utils { std::optional calcDecelDistWithJerkAndAccConstraints( const double current_vel, const double target_vel, const double current_acc, const double acc_min, const double jerk_acc, const double jerk_dec); -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils #endif // AUTOWARE__MOTION_UTILS__DISTANCE__DISTANCE_HPP_ diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/factor/velocity_factor_interface.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/factor/velocity_factor_interface.hpp index fe8cab2b7a070..30eca6927db34 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/factor/velocity_factor_interface.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/factor/velocity_factor_interface.hpp @@ -24,7 +24,7 @@ #include #include -namespace autoware_motion_utils +namespace autoware::motion_utils { using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::VelocityFactor; @@ -49,6 +49,6 @@ class VelocityFactorInterface VelocityFactor velocity_factor_{}; }; -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils #endif // AUTOWARE__MOTION_UTILS__FACTOR__VELOCITY_FACTOR_INTERFACE_HPP_ diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/marker/marker_helper.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/marker/marker_helper.hpp index 44cab2ed8b52b..4679e3d9aba91 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/marker/marker_helper.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/marker/marker_helper.hpp @@ -21,7 +21,7 @@ #include -namespace autoware_motion_utils +namespace autoware::motion_utils { using geometry_msgs::msg::Pose; @@ -48,6 +48,6 @@ visualization_msgs::msg::MarkerArray createDeletedSlowDownVirtualWallMarker( visualization_msgs::msg::MarkerArray createDeletedDeadLineVirtualWallMarker( const rclcpp::Time & now, const int32_t id); -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils #endif // AUTOWARE__MOTION_UTILS__MARKER__MARKER_HELPER_HPP_ diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/marker/virtual_wall_marker_creator.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/marker/virtual_wall_marker_creator.hpp index c2ceaddd16871..07fcbd9840c88 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/marker/virtual_wall_marker_creator.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/marker/virtual_wall_marker_creator.hpp @@ -25,7 +25,7 @@ #include #include -namespace autoware_motion_utils +namespace autoware::motion_utils { /// @brief type of virtual wall associated with different marker styles and namespace @@ -76,6 +76,6 @@ class VirtualWallMarkerCreator /// @param now current time to be used for displaying the markers visualization_msgs::msg::MarkerArray create_markers(const rclcpp::Time & now = rclcpp::Time()); }; -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils #endif // AUTOWARE__MOTION_UTILS__MARKER__VIRTUAL_WALL_MARKER_CREATOR_HPP_ diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/resample/resample.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/resample/resample.hpp index be0a9680ee378..19328179932c4 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/resample/resample.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/resample/resample.hpp @@ -21,7 +21,7 @@ #include -namespace autoware_motion_utils +namespace autoware::motion_utils { /** * @brief A resampling function for a path(points). Note that in a default setting, position xy are @@ -234,6 +234,6 @@ autoware_planning_msgs::msg::Trajectory resampleTrajectory( const bool use_akima_spline_for_xy = false, const bool use_lerp_for_z = true, const bool use_zero_order_hold_for_twist = true, const bool resample_input_trajectory_stop_point = true); -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils #endif // AUTOWARE__MOTION_UTILS__RESAMPLE__RESAMPLE_HPP_ diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/resample/resample_utils.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/resample/resample_utils.hpp index f80088645243e..5d622c54da452 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/resample/resample_utils.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/resample/resample_utils.hpp @@ -42,7 +42,7 @@ bool validate_size(const T & points) template bool validate_resampling_range(const T & points, const std::vector & resampling_intervals) { - const double points_length = autoware_motion_utils::calcArcLength(points); + const double points_length = autoware::motion_utils::calcArcLength(points); return points_length >= resampling_intervals.back(); } @@ -50,9 +50,9 @@ template bool validate_points_duplication(const T & points) { for (size_t i = 0; i < points.size() - 1; ++i) { - const auto & curr_pt = autoware_universe_utils::getPoint(points.at(i)); - const auto & next_pt = autoware_universe_utils::getPoint(points.at(i + 1)); - const double ds = autoware_universe_utils::calcDistance2d(curr_pt, next_pt); + const auto & curr_pt = autoware::universe_utils::getPoint(points.at(i)); + const auto & next_pt = autoware::universe_utils::getPoint(points.at(i + 1)); + const double ds = autoware::universe_utils::calcDistance2d(curr_pt, next_pt); if (ds < close_s_threshold) { return false; } @@ -67,27 +67,27 @@ bool validate_arguments(const T & input_points, const std::vector & resa // Check size of the arguments if (!validate_size(input_points)) { RCLCPP_DEBUG(get_logger(), "invalid argument: The number of input points is less than 2"); - autoware_universe_utils::print_backtrace(); + autoware::universe_utils::print_backtrace(); return false; } if (!validate_size(resampling_intervals)) { RCLCPP_DEBUG( get_logger(), "invalid argument: The number of resampling intervals is less than 2"); - autoware_universe_utils::print_backtrace(); + autoware::universe_utils::print_backtrace(); return false; } // Check resampling range if (!validate_resampling_range(input_points, resampling_intervals)) { RCLCPP_DEBUG(get_logger(), "invalid argument: resampling interval is longer than input points"); - autoware_universe_utils::print_backtrace(); + autoware::universe_utils::print_backtrace(); return false; } // Check duplication if (!validate_points_duplication(input_points)) { RCLCPP_DEBUG(get_logger(), "invalid argument: input points has some duplicated points"); - autoware_universe_utils::print_backtrace(); + autoware::universe_utils::print_backtrace(); return false; } @@ -100,23 +100,23 @@ bool validate_arguments(const T & input_points, const double resampling_interval // Check size of the arguments if (!validate_size(input_points)) { RCLCPP_DEBUG(get_logger(), "invalid argument: The number of input points is less than 2"); - autoware_universe_utils::print_backtrace(); + autoware::universe_utils::print_backtrace(); return false; } // check resampling interval - if (resampling_interval < autoware_motion_utils::overlap_threshold) { + if (resampling_interval < autoware::motion_utils::overlap_threshold) { RCLCPP_DEBUG( get_logger(), "invalid argument: resampling interval is less than %f", - autoware_motion_utils::overlap_threshold); - autoware_universe_utils::print_backtrace(); + autoware::motion_utils::overlap_threshold); + autoware::universe_utils::print_backtrace(); return false; } // Check duplication if (!validate_points_duplication(input_points)) { RCLCPP_DEBUG(get_logger(), "invalid argument: input points has some duplicated points"); - autoware_universe_utils::print_backtrace(); + autoware::universe_utils::print_backtrace(); return false; } diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/conversion.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/conversion.hpp index c28f76553f71e..d4f88c17c4d70 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/conversion.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/conversion.hpp @@ -23,7 +23,7 @@ #include -namespace autoware_motion_utils +namespace autoware::motion_utils { using TrajectoryPoints = std::vector; @@ -115,6 +115,6 @@ inline tier4_planning_msgs::msg::PathWithLaneId convertToPathWithLaneId( return output; } -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils #endif // AUTOWARE__MOTION_UTILS__TRAJECTORY__CONVERSION_HPP_ diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/interpolation.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/interpolation.hpp index 18dbefa85918b..5272478cccd78 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/interpolation.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/interpolation.hpp @@ -25,7 +25,7 @@ #include #include -namespace autoware_motion_utils +namespace autoware::motion_utils { /** * @brief An interpolation function that finds the closest interpolated point on the trajectory from @@ -73,24 +73,24 @@ geometry_msgs::msg::Pose calcInterpolatedPose(const T & points, const double tar } if (points.size() < 2 || target_length < 0.0) { - return autoware_universe_utils::getPose(points.front()); + return autoware::universe_utils::getPose(points.front()); } double accumulated_length = 0; for (size_t i = 0; i < points.size() - 1; ++i) { - const auto & curr_pose = autoware_universe_utils::getPose(points.at(i)); - const auto & next_pose = autoware_universe_utils::getPose(points.at(i + 1)); - const double length = autoware_universe_utils::calcDistance3d(curr_pose, next_pose); + const auto & curr_pose = autoware::universe_utils::getPose(points.at(i)); + const auto & next_pose = autoware::universe_utils::getPose(points.at(i + 1)); + const double length = autoware::universe_utils::calcDistance3d(curr_pose, next_pose); if (accumulated_length + length > target_length) { const double ratio = (target_length - accumulated_length) / std::max(length, 1e-6); - return autoware_universe_utils::calcInterpolatedPose(curr_pose, next_pose, ratio); + return autoware::universe_utils::calcInterpolatedPose(curr_pose, next_pose, ratio); } accumulated_length += length; } - return autoware_universe_utils::getPose(points.back()); + return autoware::universe_utils::getPose(points.back()); } -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils #endif // AUTOWARE__MOTION_UTILS__TRAJECTORY__INTERPOLATION_HPP_ diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/path_with_lane_id.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/path_with_lane_id.hpp index 43c8a14d0f3a3..0d875e636bad5 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/path_with_lane_id.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/path_with_lane_id.hpp @@ -20,7 +20,7 @@ #include #include -namespace autoware_motion_utils +namespace autoware::motion_utils { std::optional> getPathIndexRangeWithLaneId( const tier4_planning_msgs::msg::PathWithLaneId & path, const int64_t target_lane_id); @@ -41,6 +41,6 @@ size_t findNearestSegmentIndexFromLaneId( tier4_planning_msgs::msg::PathWithLaneId convertToRearWheelCenter( const tier4_planning_msgs::msg::PathWithLaneId & path, const double rear_to_cog, const bool enable_last_point_compensation = true); -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils #endif // AUTOWARE__MOTION_UTILS__TRAJECTORY__PATH_WITH_LANE_ID_HPP_ diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp index 3c6539f027216..da37d04550f5e 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp @@ -35,7 +35,7 @@ #include #include -namespace autoware_motion_utils +namespace autoware::motion_utils { static inline rclcpp::Logger get_logger() { @@ -51,7 +51,7 @@ template void validateNonEmpty(const T & points) { if (points.empty()) { - autoware_universe_utils::print_backtrace(); + autoware::universe_utils::print_backtrace(); throw std::invalid_argument("[autoware_motion_utils] validateNonEmpty(): Points is empty."); } } @@ -72,22 +72,22 @@ extern template void validateNonEmpty void validateNonSharpAngle( const T & point1, const T & point2, const T & point3, - const double angle_threshold = autoware_universe_utils::pi / 4) + const double angle_threshold = autoware::universe_utils::pi / 4) { - const auto p1 = autoware_universe_utils::getPoint(point1); - const auto p2 = autoware_universe_utils::getPoint(point2); - const auto p3 = autoware_universe_utils::getPoint(point3); + const auto p1 = autoware::universe_utils::getPoint(point1); + const auto p2 = autoware::universe_utils::getPoint(point2); + const auto p3 = autoware::universe_utils::getPoint(point3); const std::vector vec_1to2 = {p2.x - p1.x, p2.y - p1.y, p2.z - p1.z}; const std::vector vec_3to2 = {p2.x - p3.x, p2.y - p3.y, p2.z - p3.z}; const auto product = std::inner_product(vec_1to2.begin(), vec_1to2.end(), vec_3to2.begin(), 0.0); - const auto dist_1to2 = autoware_universe_utils::calcDistance3d(p1, p2); - const auto dist_3to2 = autoware_universe_utils::calcDistance3d(p3, p2); + const auto dist_1to2 = autoware::universe_utils::calcDistance3d(p1, p2); + const auto dist_3to2 = autoware::universe_utils::calcDistance3d(p3, p2); constexpr double epsilon = 1e-3; if (std::cos(angle_threshold) < product / dist_1to2 / dist_3to2 + epsilon) { - autoware_universe_utils::print_backtrace(); + autoware::universe_utils::print_backtrace(); throw std::invalid_argument( "[autoware_motion_utils] validateNonSharpAngle(): Too sharp angle."); } @@ -106,10 +106,10 @@ std::optional isDrivingForward(const T & points) } // check the first point direction - const auto & first_pose = autoware_universe_utils::getPose(points.at(0)); - const auto & second_pose = autoware_universe_utils::getPose(points.at(1)); + const auto & first_pose = autoware::universe_utils::getPose(points.at(0)); + const auto & second_pose = autoware::universe_utils::getPose(points.at(1)); - return autoware_universe_utils::isDrivingForward(first_pose, second_pose); + return autoware::universe_utils::isDrivingForward(first_pose, second_pose); } extern template std::optional @@ -135,10 +135,10 @@ std::optional isDrivingForwardWithTwist(const T & points_with_twist) return std::nullopt; } if (points_with_twist.size() == 1) { - if (0.0 < autoware_universe_utils::getLongitudinalVelocity(points_with_twist.front())) { + if (0.0 < autoware::universe_utils::getLongitudinalVelocity(points_with_twist.front())) { return true; } - if (0.0 > autoware_universe_utils::getLongitudinalVelocity(points_with_twist.front())) { + if (0.0 > autoware::universe_utils::getLongitudinalVelocity(points_with_twist.front())) { return false; } return std::nullopt; @@ -182,8 +182,8 @@ T removeOverlapPoints(const T & points, const size_t start_idx = 0) constexpr double eps = 1.0E-08; for (size_t i = start_idx + 1; i < points.size(); ++i) { - const auto prev_p = autoware_universe_utils::getPoint(dst.back()); - const auto curr_p = autoware_universe_utils::getPoint(points.at(i)); + const auto prev_p = autoware::universe_utils::getPoint(dst.back()); + const auto curr_p = autoware::universe_utils::getPoint(points.at(i)); if (std::abs(prev_p.x - curr_p.x) < eps && std::abs(prev_p.y - curr_p.y) < eps) { continue; } @@ -299,7 +299,7 @@ size_t findNearestIndex(const T & points, const geometry_msgs::msg::Point & poin size_t min_idx = 0; for (size_t i = 0; i < points.size(); ++i) { - const auto dist = autoware_universe_utils::calcSquaredDistance2d(points.at(i), point); + const auto dist = autoware::universe_utils::calcSquaredDistance2d(points.at(i), point); if (dist < min_dist) { min_dist = dist; min_idx = i; @@ -351,13 +351,13 @@ std::optional findNearestIndex( size_t min_idx = 0; for (size_t i = 0; i < points.size(); ++i) { - const auto squared_dist = autoware_universe_utils::calcSquaredDistance2d(points.at(i), pose); + const auto squared_dist = autoware::universe_utils::calcSquaredDistance2d(points.at(i), pose); if (squared_dist > max_squared_dist || squared_dist >= min_squared_dist) { continue; } - const auto yaw = autoware_universe_utils::calcYawDeviation( - autoware_universe_utils::getPose(points.at(i)), pose); + const auto yaw = autoware::universe_utils::calcYawDeviation( + autoware::universe_utils::getPose(points.at(i)), pose); if (std::fabs(yaw) > max_yaw) { continue; } @@ -409,7 +409,7 @@ double calcLongitudinalOffsetToSegment( "[autoware_motion_utils] " + std::string(__func__) + ": Failed to calculate longitudinal offset because the given segment index is out of the " "points size."); - autoware_universe_utils::print_backtrace(); + autoware::universe_utils::print_backtrace(); if (throw_exception) { throw std::out_of_range(error_message); } @@ -437,7 +437,7 @@ double calcLongitudinalOffsetToSegment( const std::string error_message( "[autoware_motion_utils] " + std::string(__func__) + ": Longitudinal offset calculation is not supported for the same points."); - autoware_universe_utils::print_backtrace(); + autoware::universe_utils::print_backtrace(); if (throw_exception) { throw std::runtime_error(error_message); } @@ -448,8 +448,8 @@ double calcLongitudinalOffsetToSegment( return std::nan(""); } - const auto p_front = autoware_universe_utils::getPoint(overlap_removed_points.at(seg_idx)); - const auto p_back = autoware_universe_utils::getPoint(overlap_removed_points.at(seg_idx + 1)); + const auto p_front = autoware::universe_utils::getPoint(overlap_removed_points.at(seg_idx)); + const auto p_back = autoware::universe_utils::getPoint(overlap_removed_points.at(seg_idx + 1)); const Eigen::Vector3d segment_vec{p_back.x - p_front.x, p_back.y - p_front.y, 0}; const Eigen::Vector3d target_vec{p_target.x - p_front.x, p_target.y - p_front.y, 0}; @@ -599,7 +599,7 @@ double calcLateralOffset( const std::string error_message( "[autoware_motion_utils] " + std::string(__func__) + ": Lateral offset calculation is not supported for the same points."); - autoware_universe_utils::print_backtrace(); + autoware::universe_utils::print_backtrace(); if (throw_exception) { throw std::runtime_error(error_message); } @@ -614,8 +614,8 @@ double calcLateralOffset( const auto p_front_idx = (p_indices > seg_idx) ? seg_idx : p_indices; const auto p_back_idx = p_front_idx + 1; - const auto p_front = autoware_universe_utils::getPoint(overlap_removed_points.at(p_front_idx)); - const auto p_back = autoware_universe_utils::getPoint(overlap_removed_points.at(p_back_idx)); + const auto p_front = autoware::universe_utils::getPoint(overlap_removed_points.at(p_front_idx)); + const auto p_back = autoware::universe_utils::getPoint(overlap_removed_points.at(p_back_idx)); const Eigen::Vector3d segment_vec{p_back.x - p_front.x, p_back.y - p_front.y, 0.0}; const Eigen::Vector3d target_vec{p_target.x - p_front.x, p_target.y - p_front.y, 0.0}; @@ -672,7 +672,7 @@ double calcLateralOffset( const std::string error_message( "[autoware_motion_utils] " + std::string(__func__) + ": Lateral offset calculation is not supported for the same points."); - autoware_universe_utils::print_backtrace(); + autoware::universe_utils::print_backtrace(); if (throw_exception) { throw std::runtime_error(error_message); } @@ -724,7 +724,7 @@ double calcSignedArcLength(const T & points, const size_t src_idx, const size_t double dist_sum = 0.0; for (size_t i = src_idx; i < dst_idx; ++i) { - dist_sum += autoware_universe_utils::calcDistance2d(points.at(i), points.at(i + 1)); + dist_sum += autoware::universe_utils::calcDistance2d(points.at(i), points.at(i + 1)); } return dist_sum; } @@ -772,7 +772,7 @@ std::vector calcSignedArcLengthPartialSum( double dist_sum = 0.0; partial_dist.push_back(dist_sum); for (size_t i = src_idx; i < dst_idx - 1; ++i) { - dist_sum += autoware_universe_utils::calcDistance2d(points.at(i), points.at(i + 1)); + dist_sum += autoware::universe_utils::calcDistance2d(points.at(i), points.at(i + 1)); partial_dist.push_back(dist_sum); } return partial_dist; @@ -959,10 +959,10 @@ std::vector calcCurvature(const T & points) } for (size_t i = 1; i < points.size() - 1; ++i) { - const auto p1 = autoware_universe_utils::getPoint(points.at(i - 1)); - const auto p2 = autoware_universe_utils::getPoint(points.at(i)); - const auto p3 = autoware_universe_utils::getPoint(points.at(i + 1)); - curvature_vec.at(i) = (autoware_universe_utils::calcCurvature(p1, p2, p3)); + const auto p1 = autoware::universe_utils::getPoint(points.at(i - 1)); + const auto p2 = autoware::universe_utils::getPoint(points.at(i)); + const auto p3 = autoware::universe_utils::getPoint(points.at(i + 1)); + curvature_vec.at(i) = (autoware::universe_utils::calcCurvature(p1, p2, p3)); } curvature_vec.at(0) = curvature_vec.at(1); curvature_vec.at(curvature_vec.size() - 1) = curvature_vec.at(curvature_vec.size() - 2); @@ -997,13 +997,13 @@ std::vector> calcCurvatureAndArcLength(const T & point std::vector> curvature_arc_length_vec; curvature_arc_length_vec.emplace_back(0.0, 0.0); for (size_t i = 1; i < points.size() - 1; ++i) { - const auto p1 = autoware_universe_utils::getPoint(points.at(i - 1)); - const auto p2 = autoware_universe_utils::getPoint(points.at(i)); - const auto p3 = autoware_universe_utils::getPoint(points.at(i + 1)); - const double curvature = autoware_universe_utils::calcCurvature(p1, p2, p3); + const auto p1 = autoware::universe_utils::getPoint(points.at(i - 1)); + const auto p2 = autoware::universe_utils::getPoint(points.at(i)); + const auto p3 = autoware::universe_utils::getPoint(points.at(i + 1)); + const double curvature = autoware::universe_utils::calcCurvature(p1, p2, p3); const double arc_length = - autoware_universe_utils::calcDistance2d(points.at(i - 1), points.at(i)) + - autoware_universe_utils::calcDistance2d(points.at(i), points.at(i + 1)); + autoware::universe_utils::calcDistance2d(points.at(i - 1), points.at(i)) + + autoware::universe_utils::calcDistance2d(points.at(i), points.at(i + 1)); curvature_arc_length_vec.emplace_back(curvature, arc_length); } curvature_arc_length_vec.emplace_back(0.0, 0.0); @@ -1078,7 +1078,7 @@ std::optional calcLongitudinalOffsetPoint( "[autoware_motion_utils] " + std::string(__func__) + " error: The given source index is out of the points size. Failed to calculate longitudinal " "offset."); - autoware_universe_utils::print_backtrace(); + autoware::universe_utils::print_backtrace(); if (throw_exception) { throw std::out_of_range(error_message); } @@ -1094,7 +1094,7 @@ std::optional calcLongitudinalOffsetPoint( } if (src_idx + 1 == points.size() && offset == 0.0) { - return autoware_universe_utils::getPoint(points.at(src_idx)); + return autoware::universe_utils::getPoint(points.at(src_idx)); } if (offset < 0.0) { @@ -1110,12 +1110,12 @@ std::optional calcLongitudinalOffsetPoint( const auto & p_front = points.at(i); const auto & p_back = points.at(i + 1); - const auto dist_segment = autoware_universe_utils::calcDistance2d(p_front, p_back); + const auto dist_segment = autoware::universe_utils::calcDistance2d(p_front, p_back); dist_sum += dist_segment; const auto dist_res = offset - dist_sum; if (dist_res <= 0.0) { - return autoware_universe_utils::calcInterpolatedPoint( + return autoware::universe_utils::calcInterpolatedPoint( p_back, p_front, std::abs(dist_res / dist_segment)); } } @@ -1209,7 +1209,7 @@ std::optional calcLongitudinalOffsetPose( "[autoware_motion_utils] " + std::string(__func__) + " error: The given source index is out of the points size. Failed to calculate longitudinal " "offset."); - autoware_universe_utils::print_backtrace(); + autoware::universe_utils::print_backtrace(); if (throw_exception) { throw std::out_of_range(error_message); } @@ -1223,7 +1223,7 @@ std::optional calcLongitudinalOffsetPose( } if (src_idx + 1 == points.size() && offset == 0.0) { - return autoware_universe_utils::getPose(points.at(src_idx)); + return autoware::universe_utils::getPose(points.at(src_idx)); } if (offset < 0.0) { @@ -1236,12 +1236,12 @@ std::optional calcLongitudinalOffsetPose( const auto & p_front = reverse_points.at(i); const auto & p_back = reverse_points.at(i + 1); - const auto dist_segment = autoware_universe_utils::calcDistance2d(p_front, p_back); + const auto dist_segment = autoware::universe_utils::calcDistance2d(p_front, p_back); dist_sum += dist_segment; const auto dist_res = -offset - dist_sum; if (dist_res <= 0.0) { - return autoware_universe_utils::calcInterpolatedPose( + return autoware::universe_utils::calcInterpolatedPose( p_back, p_front, std::abs(dist_res / dist_segment), set_orientation_from_position_direction); } @@ -1253,12 +1253,12 @@ std::optional calcLongitudinalOffsetPose( const auto & p_front = points.at(i); const auto & p_back = points.at(i + 1); - const auto dist_segment = autoware_universe_utils::calcDistance2d(p_front, p_back); + const auto dist_segment = autoware::universe_utils::calcDistance2d(p_front, p_back); dist_sum += dist_segment; const auto dist_res = offset - dist_sum; if (dist_res <= 0.0) { - return autoware_universe_utils::calcInterpolatedPose( + return autoware::universe_utils::calcInterpolatedPose( p_front, p_back, 1.0 - std::abs(dist_res / dist_segment), set_orientation_from_position_direction); } @@ -1358,8 +1358,8 @@ std::optional insertTargetPoint( return {}; } - const auto p_front = autoware_universe_utils::getPoint(points.at(seg_idx)); - const auto p_back = autoware_universe_utils::getPoint(points.at(seg_idx + 1)); + const auto p_front = autoware::universe_utils::getPoint(points.at(seg_idx)); + const auto p_back = autoware::universe_utils::getPoint(points.at(seg_idx + 1)); try { validateNonSharpAngle(p_front, p_target, p_back); @@ -1369,9 +1369,9 @@ std::optional insertTargetPoint( } const auto overlap_with_front = - autoware_universe_utils::calcDistance2d(p_target, p_front) < overlap_threshold; + autoware::universe_utils::calcDistance2d(p_target, p_front) < overlap_threshold; const auto overlap_with_back = - autoware_universe_utils::calcDistance2d(p_target, p_back) < overlap_threshold; + autoware::universe_utils::calcDistance2d(p_target, p_back) < overlap_threshold; const auto is_driving_forward = isDrivingForward(points); if (!is_driving_forward) { @@ -1381,31 +1381,31 @@ std::optional insertTargetPoint( geometry_msgs::msg::Pose target_pose; { const auto p_base = is_driving_forward.value() ? p_back : p_front; - const auto pitch = autoware_universe_utils::calcElevationAngle(p_target, p_base); - const auto yaw = autoware_universe_utils::calcAzimuthAngle(p_target, p_base); + const auto pitch = autoware::universe_utils::calcElevationAngle(p_target, p_base); + const auto yaw = autoware::universe_utils::calcAzimuthAngle(p_target, p_base); target_pose.position = p_target; - target_pose.orientation = autoware_universe_utils::createQuaternionFromRPY(0.0, pitch, yaw); + target_pose.orientation = autoware::universe_utils::createQuaternionFromRPY(0.0, pitch, yaw); } auto p_insert = points.at(seg_idx); - autoware_universe_utils::setPose(target_pose, p_insert); + autoware::universe_utils::setPose(target_pose, p_insert); geometry_msgs::msg::Pose base_pose; { const auto p_base = is_driving_forward.value() ? p_front : p_back; - const auto pitch = autoware_universe_utils::calcElevationAngle(p_base, p_target); - const auto yaw = autoware_universe_utils::calcAzimuthAngle(p_base, p_target); + const auto pitch = autoware::universe_utils::calcElevationAngle(p_base, p_target); + const auto yaw = autoware::universe_utils::calcAzimuthAngle(p_base, p_target); - base_pose.position = autoware_universe_utils::getPoint(p_base); - base_pose.orientation = autoware_universe_utils::createQuaternionFromRPY(0.0, pitch, yaw); + base_pose.position = autoware::universe_utils::getPoint(p_base); + base_pose.orientation = autoware::universe_utils::createQuaternionFromRPY(0.0, pitch, yaw); } if (!overlap_with_front && !overlap_with_back) { if (is_driving_forward.value()) { - autoware_universe_utils::setPose(base_pose, points.at(seg_idx)); + autoware::universe_utils::setPose(base_pose, points.at(seg_idx)); } else { - autoware_universe_utils::setPose(base_pose, points.at(seg_idx + 1)); + autoware::universe_utils::setPose(base_pose, points.at(seg_idx + 1)); } points.insert(points.begin() + seg_idx + 1, p_insert); return seg_idx + 1; @@ -1539,9 +1539,9 @@ std::optional insertTargetPoint( const double target_length = insert_point_length - calcSignedArcLength(points, src_segment_idx, *segment_idx); const double ratio = std::clamp(target_length / segment_length, 0.0, 1.0); - const auto p_target = autoware_universe_utils::calcInterpolatedPoint( - autoware_universe_utils::getPoint(points.at(*segment_idx)), - autoware_universe_utils::getPoint(points.at(*segment_idx + 1)), ratio); + const auto p_target = autoware::universe_utils::calcInterpolatedPoint( + autoware::universe_utils::getPoint(points.at(*segment_idx)), + autoware::universe_utils::getPoint(points.at(*segment_idx + 1)), ratio); return insertTargetPoint(*segment_idx, p_target, points, overlap_threshold); } @@ -1645,7 +1645,7 @@ std::optional insertStopPoint( } for (size_t i = *stop_idx; i < points_with_twist.size(); ++i) { - autoware_universe_utils::setLongitudinalVelocity(0.0, points_with_twist.at(i)); + autoware::universe_utils::setLongitudinalVelocity(0.0, points_with_twist.at(i)); } return stop_idx; @@ -1687,9 +1687,9 @@ std::optional insertStopPoint( double accumulated_length = 0; for (size_t i = 0; i < points_with_twist.size() - 1; ++i) { - const auto curr_pose = autoware_universe_utils::getPose(points_with_twist.at(i)); - const auto next_pose = autoware_universe_utils::getPose(points_with_twist.at(i + 1)); - const double length = autoware_universe_utils::calcDistance2d(curr_pose, next_pose); + const auto curr_pose = autoware::universe_utils::getPose(points_with_twist.at(i)); + const auto next_pose = autoware::universe_utils::getPose(points_with_twist.at(i + 1)); + const double length = autoware::universe_utils::calcDistance2d(curr_pose, next_pose); if (accumulated_length + length + overlap_threshold > distance_to_stop_point) { const double insert_length = distance_to_stop_point - accumulated_length; return insertStopPoint(i, insert_length, points_with_twist, overlap_threshold); @@ -1749,7 +1749,7 @@ std::optional insertStopPoint( } for (size_t i = *stop_idx; i < points_with_twist.size(); ++i) { - autoware_universe_utils::setLongitudinalVelocity(0.0, points_with_twist.at(i)); + autoware::universe_utils::setLongitudinalVelocity(0.0, points_with_twist.at(i)); } return stop_idx; @@ -1788,7 +1788,7 @@ std::optional insertStopPoint( const size_t stop_seg_idx, const geometry_msgs::msg::Point & stop_point, T & points_with_twist, const double overlap_threshold = 1e-3) { - const auto insert_idx = autoware_motion_utils::insertTargetPoint( + const auto insert_idx = autoware::motion_utils::insertTargetPoint( stop_seg_idx, stop_point, points_with_twist, overlap_threshold); if (!insert_idx) { @@ -1796,7 +1796,7 @@ std::optional insertStopPoint( } for (size_t i = insert_idx.value(); i < points_with_twist.size(); ++i) { - autoware_universe_utils::setLongitudinalVelocity(0.0, points_with_twist.at(i)); + autoware::universe_utils::setLongitudinalVelocity(0.0, points_with_twist.at(i)); } return insert_idx; @@ -1836,8 +1836,8 @@ std::optional insertDecelPoint( for (size_t i = insert_idx.value(); i < points_with_twist.size(); ++i) { const auto & original_velocity = - autoware_universe_utils::getLongitudinalVelocity(points_with_twist.at(i)); - autoware_universe_utils::setLongitudinalVelocity( + autoware::universe_utils::getLongitudinalVelocity(points_with_twist.at(i)); + autoware::universe_utils::setLongitudinalVelocity( std::min(original_velocity, velocity), points_with_twist.at(i)); } @@ -1860,30 +1860,30 @@ void insertOrientation(T & points, const bool is_driving_forward) { if (is_driving_forward) { for (size_t i = 0; i < points.size() - 1; ++i) { - const auto & src_point = autoware_universe_utils::getPoint(points.at(i)); - const auto & dst_point = autoware_universe_utils::getPoint(points.at(i + 1)); - const double pitch = autoware_universe_utils::calcElevationAngle(src_point, dst_point); - const double yaw = autoware_universe_utils::calcAzimuthAngle(src_point, dst_point); - autoware_universe_utils::setOrientation( - autoware_universe_utils::createQuaternionFromRPY(0.0, pitch, yaw), points.at(i)); + const auto & src_point = autoware::universe_utils::getPoint(points.at(i)); + const auto & dst_point = autoware::universe_utils::getPoint(points.at(i + 1)); + const double pitch = autoware::universe_utils::calcElevationAngle(src_point, dst_point); + const double yaw = autoware::universe_utils::calcAzimuthAngle(src_point, dst_point); + autoware::universe_utils::setOrientation( + autoware::universe_utils::createQuaternionFromRPY(0.0, pitch, yaw), points.at(i)); if (i == points.size() - 2) { // Terminal orientation is same as the point before it - autoware_universe_utils::setOrientation( - autoware_universe_utils::getPose(points.at(i)).orientation, points.at(i + 1)); + autoware::universe_utils::setOrientation( + autoware::universe_utils::getPose(points.at(i)).orientation, points.at(i + 1)); } } } else { for (size_t i = points.size() - 1; i >= 1; --i) { - const auto & src_point = autoware_universe_utils::getPoint(points.at(i)); - const auto & dst_point = autoware_universe_utils::getPoint(points.at(i - 1)); - const double pitch = autoware_universe_utils::calcElevationAngle(src_point, dst_point); - const double yaw = autoware_universe_utils::calcAzimuthAngle(src_point, dst_point); - autoware_universe_utils::setOrientation( - autoware_universe_utils::createQuaternionFromRPY(0.0, pitch, yaw), points.at(i)); + const auto & src_point = autoware::universe_utils::getPoint(points.at(i)); + const auto & dst_point = autoware::universe_utils::getPoint(points.at(i - 1)); + const double pitch = autoware::universe_utils::calcElevationAngle(src_point, dst_point); + const double yaw = autoware::universe_utils::calcAzimuthAngle(src_point, dst_point); + autoware::universe_utils::setOrientation( + autoware::universe_utils::createQuaternionFromRPY(0.0, pitch, yaw), points.at(i)); } // Initial orientation is same as the point after it - autoware_universe_utils::setOrientation( - autoware_universe_utils::getPose(points.at(1)).orientation, points.at(0)); + autoware::universe_utils::setOrientation( + autoware::universe_utils::getPose(points.at(1)).orientation, points.at(0)); } } @@ -1908,14 +1908,14 @@ template void removeFirstInvalidOrientationPoints(T & points, const double max_yaw_diff = M_PI_2) { for (auto itr = points.begin(); std::next(itr) != points.end();) { - const auto p1 = autoware_universe_utils::getPose(*itr); - const auto p2 = autoware_universe_utils::getPose(*std::next(itr)); + const auto p1 = autoware::universe_utils::getPose(*itr); + const auto p2 = autoware::universe_utils::getPose(*std::next(itr)); const double yaw1 = tf2::getYaw(p1.orientation); const double yaw2 = tf2::getYaw(p2.orientation); if ( - max_yaw_diff < std::abs(autoware_universe_utils::normalizeRadian(yaw1 - yaw2)) || - !autoware_universe_utils::isDrivingForward(p1, p2)) { + max_yaw_diff < std::abs(autoware::universe_utils::normalizeRadian(yaw1 - yaw2)) || + !autoware::universe_utils::isDrivingForward(p1, p2)) { points.erase(std::next(itr)); return; } else { @@ -2068,9 +2068,9 @@ size_t findFirstNearestIndexWithSoftConstraints( bool is_within_constraints = false; for (size_t i = 0; i < points.size(); ++i) { const auto squared_dist = - autoware_universe_utils::calcSquaredDistance2d(points.at(i), pose.position); - const auto yaw = autoware_universe_utils::calcYawDeviation( - autoware_universe_utils::getPose(points.at(i)), pose); + autoware::universe_utils::calcSquaredDistance2d(points.at(i), pose.position); + const auto yaw = autoware::universe_utils::calcYawDeviation( + autoware::universe_utils::getPose(points.at(i)), pose); if (squared_dist_threshold < squared_dist || yaw_threshold < std::abs(yaw)) { if (is_within_constraints) { @@ -2101,7 +2101,7 @@ size_t findFirstNearestIndexWithSoftConstraints( bool is_within_constraints = false; for (size_t i = 0; i < points.size(); ++i) { const auto squared_dist = - autoware_universe_utils::calcSquaredDistance2d(points.at(i), pose.position); + autoware::universe_utils::calcSquaredDistance2d(points.at(i), pose.position); if (squared_dist_threshold < squared_dist) { if (is_within_constraints) { @@ -2231,13 +2231,13 @@ std::optional calcDistanceToForwardStopPoint( } const auto nearest_segment_idx = - autoware_motion_utils::findNearestSegmentIndex(points_with_twist, pose, max_dist, max_yaw); + autoware::motion_utils::findNearestSegmentIndex(points_with_twist, pose, max_dist, max_yaw); if (!nearest_segment_idx) { return std::nullopt; } - const auto stop_idx = autoware_motion_utils::searchZeroVelocityIndex( + const auto stop_idx = autoware::motion_utils::searchZeroVelocityIndex( points_with_twist, *nearest_segment_idx + 1, points_with_twist.size()); if (!stop_idx) { @@ -2278,9 +2278,9 @@ T cropForwardPoints( } double sum_length = - -autoware_motion_utils::calcLongitudinalOffsetToSegment(points, target_seg_idx, target_pos); + -autoware::motion_utils::calcLongitudinalOffsetToSegment(points, target_seg_idx, target_pos); for (size_t i = target_seg_idx + 1; i < points.size(); ++i) { - sum_length += autoware_universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); + sum_length += autoware::universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); if (forward_length < sum_length) { const size_t end_idx = i; return T{points.begin(), points.begin() + end_idx}; @@ -2318,9 +2318,9 @@ T cropBackwardPoints( } double sum_length = - -autoware_motion_utils::calcLongitudinalOffsetToSegment(points, target_seg_idx, target_pos); + -autoware::motion_utils::calcLongitudinalOffsetToSegment(points, target_seg_idx, target_pos); for (int i = target_seg_idx; 0 < i; --i) { - sum_length -= autoware_universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); + sum_length -= autoware::universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); if (sum_length < -backward_length) { const size_t begin_idx = i; return T{points.begin() + begin_idx, points.end()}; @@ -2419,7 +2419,7 @@ double calcYawDeviation( const std::string error_message( "[autoware_motion_utils] " + std::string(__func__) + " Given points size is less than 2. Failed to calculate yaw deviation."); - autoware_universe_utils::print_backtrace(); + autoware::universe_utils::print_backtrace(); if (throw_exception) { throw std::runtime_error(error_message); } @@ -2432,12 +2432,12 @@ double calcYawDeviation( const size_t seg_idx = findNearestSegmentIndex(overlap_removed_points, pose.position); - const double path_yaw = autoware_universe_utils::calcAzimuthAngle( - autoware_universe_utils::getPoint(overlap_removed_points.at(seg_idx)), - autoware_universe_utils::getPoint(overlap_removed_points.at(seg_idx + 1))); + const double path_yaw = autoware::universe_utils::calcAzimuthAngle( + autoware::universe_utils::getPoint(overlap_removed_points.at(seg_idx)), + autoware::universe_utils::getPoint(overlap_removed_points.at(seg_idx + 1))); const double pose_yaw = tf2::getYaw(pose.orientation); - return autoware_universe_utils::normalizeRadian(pose_yaw - path_yaw); + return autoware::universe_utils::normalizeRadian(pose_yaw - path_yaw); } extern template double calcYawDeviation>( @@ -2487,6 +2487,6 @@ extern template bool isTargetPointFront -namespace autoware_motion_utils +namespace autoware::motion_utils { using autoware_planning_msgs::msg::Trajectory; @@ -77,6 +77,6 @@ class VehicleArrivalChecker : public VehicleStopChecker void onTrajectory(const Trajectory::ConstSharedPtr msg); }; -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils #endif // AUTOWARE__MOTION_UTILS__VEHICLE__VEHICLE_STATE_CHECKER_HPP_ diff --git a/common/autoware_motion_utils/src/distance/distance.cpp b/common/autoware_motion_utils/src/distance/distance.cpp index 244b894bad473..d31e7ec709810 100644 --- a/common/autoware_motion_utils/src/distance/distance.cpp +++ b/common/autoware_motion_utils/src/distance/distance.cpp @@ -14,7 +14,7 @@ #include "autoware/motion_utils/distance/distance.hpp" -namespace autoware_motion_utils +namespace autoware::motion_utils { namespace { @@ -269,4 +269,4 @@ std::optional calcDecelDistWithJerkAndAccConstraints( return calcDecelDistPlanType3(current_vel, target_vel, current_acc, jerk_acc); } -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils diff --git a/common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp b/common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp index f9ae98801801f..e405cdb655c02 100644 --- a/common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp +++ b/common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp @@ -19,7 +19,7 @@ #include #include -namespace autoware_motion_utils +namespace autoware::motion_utils { template void VelocityFactorInterface::set( @@ -31,7 +31,7 @@ void VelocityFactorInterface::set( velocity_factor_.behavior = behavior_; velocity_factor_.pose = stop_pose; velocity_factor_.distance = - static_cast(autoware_motion_utils::calcSignedArcLength(points, curr_point, stop_point)); + static_cast(autoware::motion_utils::calcSignedArcLength(points, curr_point, stop_point)); velocity_factor_.status = status; velocity_factor_.detail = detail; } @@ -46,4 +46,4 @@ template void VelocityFactorInterface::set &, const Pose &, const Pose &, const VelocityFactorStatus, const std::string &); -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils diff --git a/common/autoware_motion_utils/src/marker/marker_helper.cpp b/common/autoware_motion_utils/src/marker/marker_helper.cpp index 5cab196e22329..388c7102b825c 100644 --- a/common/autoware_motion_utils/src/marker/marker_helper.cpp +++ b/common/autoware_motion_utils/src/marker/marker_helper.cpp @@ -20,10 +20,10 @@ #include -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createDeletedDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerScale; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createDeletedDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerScale; using visualization_msgs::msg::MarkerArray; namespace @@ -85,14 +85,14 @@ inline visualization_msgs::msg::MarkerArray createDeletedVirtualWallMarkerArray( } } // namespace -namespace autoware_motion_utils +namespace autoware::motion_utils { visualization_msgs::msg::MarkerArray createStopVirtualWallMarker( const geometry_msgs::msg::Pose & pose, const std::string & module_name, const rclcpp::Time & now, const int32_t id, const double longitudinal_offset, const std::string & ns_prefix, const bool is_driving_forward) { - const auto pose_with_offset = autoware_universe_utils::calcOffsetPose( + const auto pose_with_offset = autoware::universe_utils::calcOffsetPose( pose, longitudinal_offset * (is_driving_forward ? 1.0 : -1.0), 0.0, 0.0); return createVirtualWallMarkerArray( pose_with_offset, module_name, ns_prefix + "stop_", now, id, @@ -104,7 +104,7 @@ visualization_msgs::msg::MarkerArray createSlowDownVirtualWallMarker( const int32_t id, const double longitudinal_offset, const std::string & ns_prefix, const bool is_driving_forward) { - const auto pose_with_offset = autoware_universe_utils::calcOffsetPose( + const auto pose_with_offset = autoware::universe_utils::calcOffsetPose( pose, longitudinal_offset * (is_driving_forward ? 1.0 : -1.0), 0.0, 0.0); return createVirtualWallMarkerArray( pose_with_offset, module_name, ns_prefix + "slow_down_", now, id, @@ -116,7 +116,7 @@ visualization_msgs::msg::MarkerArray createDeadLineVirtualWallMarker( const int32_t id, const double longitudinal_offset, const std::string & ns_prefix, const bool is_driving_forward) { - const auto pose_with_offset = autoware_universe_utils::calcOffsetPose( + const auto pose_with_offset = autoware::universe_utils::calcOffsetPose( pose, longitudinal_offset * (is_driving_forward ? 1.0 : -1.0), 0.0, 0.0); return createVirtualWallMarkerArray( pose_with_offset, module_name, ns_prefix + "dead_line_", now, id, @@ -140,4 +140,4 @@ visualization_msgs::msg::MarkerArray createDeletedDeadLineVirtualWallMarker( { return createDeletedVirtualWallMarkerArray("dead_line_", now, id); } -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils diff --git a/common/autoware_motion_utils/src/marker/virtual_wall_marker_creator.cpp b/common/autoware_motion_utils/src/marker/virtual_wall_marker_creator.cpp index 658aa66208133..4fecaea1bb838 100644 --- a/common/autoware_motion_utils/src/marker/virtual_wall_marker_creator.cpp +++ b/common/autoware_motion_utils/src/marker/virtual_wall_marker_creator.cpp @@ -16,7 +16,7 @@ #include "autoware/motion_utils/marker/marker_helper.hpp" -namespace autoware_motion_utils +namespace autoware::motion_utils { void VirtualWallMarkerCreator::cleanup() @@ -55,13 +55,13 @@ visualization_msgs::msg::MarkerArray VirtualWallMarkerCreator::create_markers( for (const auto & virtual_wall : virtual_walls_) { switch (virtual_wall.style) { case stop: - create_fn = autoware_motion_utils::createStopVirtualWallMarker; + create_fn = autoware::motion_utils::createStopVirtualWallMarker; break; case slowdown: - create_fn = autoware_motion_utils::createSlowDownVirtualWallMarker; + create_fn = autoware::motion_utils::createSlowDownVirtualWallMarker; break; case deadline: - create_fn = autoware_motion_utils::createDeadLineVirtualWallMarker; + create_fn = autoware::motion_utils::createDeadLineVirtualWallMarker; break; } auto markers = create_fn( @@ -85,4 +85,4 @@ visualization_msgs::msg::MarkerArray VirtualWallMarkerCreator::create_markers( cleanup(); return marker_array; } -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils diff --git a/common/autoware_motion_utils/src/resample/resample.cpp b/common/autoware_motion_utils/src/resample/resample.cpp index f0874264aee73..baf1c534a8a00 100644 --- a/common/autoware_motion_utils/src/resample/resample.cpp +++ b/common/autoware_motion_utils/src/resample/resample.cpp @@ -21,7 +21,7 @@ #include "interpolation/spline_interpolation.hpp" #include "interpolation/zero_order_hold.hpp" -namespace autoware_motion_utils +namespace autoware::motion_utils { std::vector resamplePointVector( const std::vector & points, @@ -50,7 +50,7 @@ std::vector resamplePointVector( for (size_t i = 1; i < points.size(); ++i) { const auto & prev_pt = points.at(i - 1); const auto & curr_pt = points.at(i); - const double ds = autoware_universe_utils::calcDistance2d(prev_pt, curr_pt); + const double ds = autoware::universe_utils::calcDistance2d(prev_pt, curr_pt); input_arclength.push_back(ds + input_arclength.back()); x.push_back(curr_pt.x); y.push_back(curr_pt.y); @@ -91,7 +91,7 @@ std::vector resamplePointVector( const std::vector & points, const double resample_interval, const bool use_akima_spline_for_xy, const bool use_lerp_for_z) { - const double input_length = autoware_motion_utils::calcArcLength(points); + const double input_length = autoware::motion_utils::calcArcLength(points); std::vector resampling_arclength; for (double s = 0.0; s < input_length; s += resample_interval) { @@ -103,7 +103,7 @@ std::vector resamplePointVector( } // Insert terminal point - if (input_length - resampling_arclength.back() < autoware_motion_utils::overlap_threshold) { + if (input_length - resampling_arclength.back() < autoware::motion_utils::overlap_threshold) { resampling_arclength.back() = input_length; } else { resampling_arclength.push_back(input_length); @@ -118,7 +118,7 @@ std::vector resamplePoseVector( const bool use_lerp_for_z) { // Remove overlap points for resampling - const auto points = autoware_motion_utils::removeOverlapPoints(points_raw); + const auto points = autoware::motion_utils::removeOverlapPoints(points_raw); // validate arguments if (!resample_utils::validate_arguments(points, resampled_arclength)) { @@ -144,8 +144,8 @@ std::vector resamplePoseVector( } const bool is_driving_forward = - autoware_universe_utils::isDrivingForward(points.at(0), points.at(1)); - autoware_motion_utils::insertOrientation(resampled_points, is_driving_forward); + autoware::universe_utils::isDrivingForward(points.at(0), points.at(1)); + autoware::motion_utils::insertOrientation(resampled_points, is_driving_forward); // Initial orientation is depend on the initial value of the resampled_arclength // when backward driving @@ -160,7 +160,7 @@ std::vector resamplePoseVector( const std::vector & points, const double resample_interval, const bool use_akima_spline_for_xy, const bool use_lerp_for_z) { - const double input_length = autoware_motion_utils::calcArcLength(points); + const double input_length = autoware::motion_utils::calcArcLength(points); std::vector resampling_arclength; for (double s = 0.0; s < input_length; s += resample_interval) { @@ -172,7 +172,7 @@ std::vector resamplePoseVector( } // Insert terminal point - if (input_length - resampling_arclength.back() < autoware_motion_utils::overlap_threshold) { + if (input_length - resampling_arclength.back() < autoware::motion_utils::overlap_threshold) { resampling_arclength.back() = input_length; } else { resampling_arclength.push_back(input_length); @@ -203,9 +203,9 @@ tier4_planning_msgs::msg::PathWithLaneId resamplePath( std::fabs(distance_to_resampling_point - resampling_arclength.at(j - 1)); const double dist_to_following_point = std::fabs(resampling_arclength.at(j) - distance_to_resampling_point); - if (dist_to_prev_point < autoware_motion_utils::overlap_threshold) { + if (dist_to_prev_point < autoware::motion_utils::overlap_threshold) { resampling_arclength.at(j - 1) = distance_to_resampling_point; - } else if (dist_to_following_point < autoware_motion_utils::overlap_threshold) { + } else if (dist_to_following_point < autoware::motion_utils::overlap_threshold) { resampling_arclength.at(j) = distance_to_resampling_point; } else { resampling_arclength.insert( @@ -260,7 +260,7 @@ tier4_planning_msgs::msg::PathWithLaneId resamplePath( const auto & prev_pt = input_path.points.at(i - 1).point; const auto & curr_pt = input_path.points.at(i).point; const double ds = - autoware_universe_utils::calcDistance2d(prev_pt.pose.position, curr_pt.pose.position); + autoware::universe_utils::calcDistance2d(prev_pt.pose.position, curr_pt.pose.position); input_arclength.push_back(ds + input_arclength.back()); input_pose.push_back(curr_pt.pose); v_lon.push_back(curr_pt.longitudinal_velocity_mps); @@ -370,7 +370,7 @@ tier4_planning_msgs::msg::PathWithLaneId resamplePath( transformed_input_path.at(i) = input_path.points.at(i).point; } // compute path length - const double input_path_len = autoware_motion_utils::calcArcLength(transformed_input_path); + const double input_path_len = autoware::motion_utils::calcArcLength(transformed_input_path); std::vector resampling_arclength; for (double s = 0.0; s < input_path_len; s += resample_interval) { @@ -382,7 +382,7 @@ tier4_planning_msgs::msg::PathWithLaneId resamplePath( } // Insert terminal point - if (input_path_len - resampling_arclength.back() < autoware_motion_utils::overlap_threshold) { + if (input_path_len - resampling_arclength.back() < autoware::motion_utils::overlap_threshold) { resampling_arclength.back() = input_path_len; } else { resampling_arclength.push_back(input_path_len); @@ -391,7 +391,7 @@ tier4_planning_msgs::msg::PathWithLaneId resamplePath( // Insert stop point if (resample_input_path_stop_point) { const auto distance_to_stop_point = - autoware_motion_utils::calcDistanceToForwardStopPoint(transformed_input_path, 0); + autoware::motion_utils::calcDistanceToForwardStopPoint(transformed_input_path, 0); if (distance_to_stop_point && !resampling_arclength.empty()) { for (size_t i = 1; i < resampling_arclength.size(); ++i) { if ( @@ -401,9 +401,9 @@ tier4_planning_msgs::msg::PathWithLaneId resamplePath( std::fabs(*distance_to_stop_point - resampling_arclength.at(i - 1)); const double dist_to_following_point = std::fabs(resampling_arclength.at(i) - *distance_to_stop_point); - if (dist_to_prev_point < autoware_motion_utils::overlap_threshold) { + if (dist_to_prev_point < autoware::motion_utils::overlap_threshold) { resampling_arclength.at(i - 1) = *distance_to_stop_point; - } else if (dist_to_following_point < autoware_motion_utils::overlap_threshold) { + } else if (dist_to_following_point < autoware::motion_utils::overlap_threshold) { resampling_arclength.at(i) = *distance_to_stop_point; } else { resampling_arclength.insert(resampling_arclength.begin() + i, *distance_to_stop_point); @@ -450,7 +450,7 @@ autoware_planning_msgs::msg::Path resamplePath( const auto & prev_pt = input_path.points.at(i - 1); const auto & curr_pt = input_path.points.at(i); const double ds = - autoware_universe_utils::calcDistance2d(prev_pt.pose.position, curr_pt.pose.position); + autoware::universe_utils::calcDistance2d(prev_pt.pose.position, curr_pt.pose.position); input_arclength.push_back(ds + input_arclength.back()); input_pose.push_back(curr_pt.pose); v_lon.push_back(curr_pt.longitudinal_velocity_mps); @@ -512,7 +512,7 @@ autoware_planning_msgs::msg::Path resamplePath( return input_path; } - const double input_path_len = autoware_motion_utils::calcArcLength(input_path.points); + const double input_path_len = autoware::motion_utils::calcArcLength(input_path.points); std::vector resampling_arclength; for (double s = 0.0; s < input_path_len; s += resample_interval) { @@ -524,7 +524,7 @@ autoware_planning_msgs::msg::Path resamplePath( } // Insert terminal point - if (input_path_len - resampling_arclength.back() < autoware_motion_utils::overlap_threshold) { + if (input_path_len - resampling_arclength.back() < autoware::motion_utils::overlap_threshold) { resampling_arclength.back() = input_path_len; } else { resampling_arclength.push_back(input_path_len); @@ -533,7 +533,7 @@ autoware_planning_msgs::msg::Path resamplePath( // Insert stop point if (resample_input_path_stop_point) { const auto distance_to_stop_point = - autoware_motion_utils::calcDistanceToForwardStopPoint(input_path.points, 0); + autoware::motion_utils::calcDistanceToForwardStopPoint(input_path.points, 0); if (distance_to_stop_point && !resampling_arclength.empty()) { for (size_t i = 1; i < resampling_arclength.size(); ++i) { if ( @@ -543,9 +543,9 @@ autoware_planning_msgs::msg::Path resamplePath( std::fabs(*distance_to_stop_point - resampling_arclength.at(i - 1)); const double dist_to_following_point = std::fabs(resampling_arclength.at(i) - *distance_to_stop_point); - if (dist_to_prev_point < autoware_motion_utils::overlap_threshold) { + if (dist_to_prev_point < autoware::motion_utils::overlap_threshold) { resampling_arclength.at(i - 1) = *distance_to_stop_point; - } else if (dist_to_following_point < autoware_motion_utils::overlap_threshold) { + } else if (dist_to_following_point < autoware::motion_utils::overlap_threshold) { resampling_arclength.at(i) = *distance_to_stop_point; } else { resampling_arclength.insert(resampling_arclength.begin() + i, *distance_to_stop_point); @@ -605,7 +605,7 @@ autoware_planning_msgs::msg::Trajectory resampleTrajectory( const auto & prev_pt = input_trajectory.points.at(i - 1); const auto & curr_pt = input_trajectory.points.at(i); const double ds = - autoware_universe_utils::calcDistance2d(prev_pt.pose.position, curr_pt.pose.position); + autoware::universe_utils::calcDistance2d(prev_pt.pose.position, curr_pt.pose.position); input_arclength.push_back(ds + input_arclength.back()); input_pose.push_back(curr_pt.pose); v_lon.push_back(curr_pt.longitudinal_velocity_mps); @@ -678,7 +678,8 @@ autoware_planning_msgs::msg::Trajectory resampleTrajectory( return input_trajectory; } - const double input_trajectory_len = autoware_motion_utils::calcArcLength(input_trajectory.points); + const double input_trajectory_len = + autoware::motion_utils::calcArcLength(input_trajectory.points); std::vector resampling_arclength; for (double s = 0.0; s < input_trajectory_len; s += resample_interval) { @@ -691,7 +692,8 @@ autoware_planning_msgs::msg::Trajectory resampleTrajectory( // Insert terminal point if ( - input_trajectory_len - resampling_arclength.back() < autoware_motion_utils::overlap_threshold) { + input_trajectory_len - resampling_arclength.back() < + autoware::motion_utils::overlap_threshold) { resampling_arclength.back() = input_trajectory_len; } else { resampling_arclength.push_back(input_trajectory_len); @@ -700,7 +702,7 @@ autoware_planning_msgs::msg::Trajectory resampleTrajectory( // Insert stop point if (resample_input_trajectory_stop_point) { const auto distance_to_stop_point = - autoware_motion_utils::calcDistanceToForwardStopPoint(input_trajectory.points, 0); + autoware::motion_utils::calcDistanceToForwardStopPoint(input_trajectory.points, 0); if (distance_to_stop_point && !resampling_arclength.empty()) { for (size_t i = 1; i < resampling_arclength.size(); ++i) { if ( @@ -710,9 +712,9 @@ autoware_planning_msgs::msg::Trajectory resampleTrajectory( std::fabs(*distance_to_stop_point - resampling_arclength.at(i - 1)); const double dist_to_following_point = std::fabs(resampling_arclength.at(i) - *distance_to_stop_point); - if (dist_to_prev_point < autoware_motion_utils::overlap_threshold) { + if (dist_to_prev_point < autoware::motion_utils::overlap_threshold) { resampling_arclength.at(i - 1) = *distance_to_stop_point; - } else if (dist_to_following_point < autoware_motion_utils::overlap_threshold) { + } else if (dist_to_following_point < autoware::motion_utils::overlap_threshold) { resampling_arclength.at(i) = *distance_to_stop_point; } else { resampling_arclength.insert(resampling_arclength.begin() + i, *distance_to_stop_point); @@ -728,4 +730,4 @@ autoware_planning_msgs::msg::Trajectory resampleTrajectory( use_zero_order_hold_for_twist); } -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils diff --git a/common/autoware_motion_utils/src/trajectory/conversion.cpp b/common/autoware_motion_utils/src/trajectory/conversion.cpp index 63efc7135cae2..368d3e0fbbb75 100644 --- a/common/autoware_motion_utils/src/trajectory/conversion.cpp +++ b/common/autoware_motion_utils/src/trajectory/conversion.cpp @@ -16,7 +16,7 @@ #include -namespace autoware_motion_utils +namespace autoware::motion_utils { /** * @brief Convert std::vector to @@ -51,4 +51,4 @@ std::vector convertToTrajectoryPoi return output; } -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils diff --git a/common/autoware_motion_utils/src/trajectory/interpolation.cpp b/common/autoware_motion_utils/src/trajectory/interpolation.cpp index 4b00c6344a990..4a9eaeca58d30 100644 --- a/common/autoware_motion_utils/src/trajectory/interpolation.cpp +++ b/common/autoware_motion_utils/src/trajectory/interpolation.cpp @@ -22,7 +22,7 @@ using autoware_planning_msgs::msg::TrajectoryPoint; using tier4_planning_msgs::msg::PathPointWithLaneId; using tier4_planning_msgs::msg::PathWithLaneId; -namespace autoware_motion_utils +namespace autoware::motion_utils { TrajectoryPoint calcInterpolatedPoint( const Trajectory & trajectory, const geometry_msgs::msg::Pose & target_pose, @@ -37,14 +37,15 @@ TrajectoryPoint calcInterpolatedPoint( return trajectory.points.front(); } - const size_t segment_idx = autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - trajectory.points, target_pose, dist_threshold, yaw_threshold); + const size_t segment_idx = + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + trajectory.points, target_pose, dist_threshold, yaw_threshold); // Calculate interpolation ratio const auto & curr_pt = trajectory.points.at(segment_idx); const auto & next_pt = trajectory.points.at(segment_idx + 1); - const auto v1 = autoware_universe_utils::point2tfVector(curr_pt, next_pt); - const auto v2 = autoware_universe_utils::point2tfVector(curr_pt, target_pose); + const auto v1 = autoware::universe_utils::point2tfVector(curr_pt, next_pt); + const auto v2 = autoware::universe_utils::point2tfVector(curr_pt, target_pose); if (v1.length2() < 1e-3) { return curr_pt; } @@ -57,7 +58,7 @@ TrajectoryPoint calcInterpolatedPoint( // pose interpolation interpolated_point.pose = - autoware_universe_utils::calcInterpolatedPose(curr_pt, next_pt, clamped_ratio); + autoware::universe_utils::calcInterpolatedPose(curr_pt, next_pt, clamped_ratio); // twist interpolation if (use_zero_order_hold_for_twist) { @@ -105,14 +106,15 @@ PathPointWithLaneId calcInterpolatedPoint( return path.points.front(); } - const size_t segment_idx = autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - path.points, target_pose, dist_threshold, yaw_threshold); + const size_t segment_idx = + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + path.points, target_pose, dist_threshold, yaw_threshold); // Calculate interpolation ratio const auto & curr_pt = path.points.at(segment_idx); const auto & next_pt = path.points.at(segment_idx + 1); - const auto v1 = autoware_universe_utils::point2tfVector(curr_pt.point, next_pt.point); - const auto v2 = autoware_universe_utils::point2tfVector(curr_pt.point, target_pose); + const auto v1 = autoware::universe_utils::point2tfVector(curr_pt.point, next_pt.point); + const auto v2 = autoware::universe_utils::point2tfVector(curr_pt.point, target_pose); if (v1.length2() < 1e-3) { return curr_pt; } @@ -125,7 +127,7 @@ PathPointWithLaneId calcInterpolatedPoint( // pose interpolation interpolated_point.point.pose = - autoware_universe_utils::calcInterpolatedPose(curr_pt.point, next_pt.point, clamped_ratio); + autoware::universe_utils::calcInterpolatedPose(curr_pt.point, next_pt.point, clamped_ratio); // twist interpolation if (use_zero_order_hold_for_twist) { @@ -145,4 +147,4 @@ PathPointWithLaneId calcInterpolatedPoint( return interpolated_point; } -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils diff --git a/common/autoware_motion_utils/src/trajectory/path_with_lane_id.cpp b/common/autoware_motion_utils/src/trajectory/path_with_lane_id.cpp index 52870ba2407d5..cd8de63f56c1d 100644 --- a/common/autoware_motion_utils/src/trajectory/path_with_lane_id.cpp +++ b/common/autoware_motion_utils/src/trajectory/path_with_lane_id.cpp @@ -21,7 +21,7 @@ #include #include -namespace autoware_motion_utils +namespace autoware::motion_utils { std::optional> getPathIndexRangeWithLaneId( @@ -116,15 +116,15 @@ tier4_planning_msgs::msg::PathWithLaneId convertToRearWheelCenter( // apply beta to CoG pose geometry_msgs::msg::Pose cog_pose_with_beta; - cog_pose_with_beta.position = autoware_universe_utils::getPoint(path.points.at(i)); + cog_pose_with_beta.position = autoware::universe_utils::getPoint(path.points.at(i)); cog_pose_with_beta.orientation = - autoware_universe_utils::createQuaternionFromYaw(yaw_vec.at(i) - beta); + autoware::universe_utils::createQuaternionFromYaw(yaw_vec.at(i) - beta); const auto rear_pose = - autoware_universe_utils::calcOffsetPose(cog_pose_with_beta, -rear_to_cog, 0.0, 0.0); + autoware::universe_utils::calcOffsetPose(cog_pose_with_beta, -rear_to_cog, 0.0, 0.0); // update pose - autoware_universe_utils::setPose(rear_pose, cog_path.points.at(i)); + autoware::universe_utils::setPose(rear_pose, cog_path.points.at(i)); } // compensate for the last pose @@ -136,4 +136,4 @@ tier4_planning_msgs::msg::PathWithLaneId convertToRearWheelCenter( return cog_path; } -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils diff --git a/common/autoware_motion_utils/src/trajectory/trajectory.cpp b/common/autoware_motion_utils/src/trajectory/trajectory.cpp index a35e6ff02b84b..5d536c0772fea 100644 --- a/common/autoware_motion_utils/src/trajectory/trajectory.cpp +++ b/common/autoware_motion_utils/src/trajectory/trajectory.cpp @@ -14,7 +14,7 @@ #include "autoware/motion_utils/trajectory/trajectory.hpp" -namespace autoware_motion_utils +namespace autoware::motion_utils { // @@ -599,4 +599,4 @@ template bool isTargetPointFront -namespace autoware_motion_utils +namespace autoware::motion_utils { VehicleStopCheckerBase::VehicleStopCheckerBase(rclcpp::Node * node, double buffer_duration) : clock_(node->get_clock()), logger_(node->get_logger()) @@ -118,13 +118,13 @@ bool VehicleArrivalChecker::isVehicleStoppedAtStopPoint(const double stop_durati } const auto & p = odometry_ptr_->pose.pose.position; - const auto idx = autoware_motion_utils::searchZeroVelocityIndex(trajectory_ptr_->points); + const auto idx = autoware::motion_utils::searchZeroVelocityIndex(trajectory_ptr_->points); if (!idx) { return false; } - return std::abs(autoware_motion_utils::calcSignedArcLength( + return std::abs(autoware::motion_utils::calcSignedArcLength( trajectory_ptr_->points, p, idx.value())) < th_arrived_distance_m; } @@ -132,4 +132,4 @@ void VehicleArrivalChecker::onTrajectory(const Trajectory::ConstSharedPtr msg) { trajectory_ptr_ = msg; } -} // namespace autoware_motion_utils +} // namespace autoware::motion_utils diff --git a/common/autoware_motion_utils/test/src/distance/test_distance.cpp b/common/autoware_motion_utils/test/src/distance/test_distance.cpp index f32a92f5c5cbc..f6d6a9cc4dafd 100644 --- a/common/autoware_motion_utils/test/src/distance/test_distance.cpp +++ b/common/autoware_motion_utils/test/src/distance/test_distance.cpp @@ -16,7 +16,7 @@ #include "gtest/gtest.h" namespace { -using autoware_motion_utils::calcDecelDistWithJerkAndAccConstraints; +using autoware::motion_utils::calcDecelDistWithJerkAndAccConstraints; constexpr double epsilon = 1e-3; diff --git a/common/autoware_motion_utils/test/src/marker/test_virtual_wall_marker_creator.cpp b/common/autoware_motion_utils/test/src/marker/test_virtual_wall_marker_creator.cpp index 5ddb0b1a1e8f8..5e2e0cc4bdf02 100644 --- a/common/autoware_motion_utils/test/src/marker/test_virtual_wall_marker_creator.cpp +++ b/common/autoware_motion_utils/test/src/marker/test_virtual_wall_marker_creator.cpp @@ -38,9 +38,9 @@ bool has_ns_id( TEST(VirtualWallMarkerCreator, oneWall) { - autoware_motion_utils::VirtualWall wall; - autoware_motion_utils::VirtualWallMarkerCreator creator; - wall.style = autoware_motion_utils::VirtualWallType::stop; + autoware::motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWallMarkerCreator creator; + wall.style = autoware::motion_utils::VirtualWallType::stop; wall.pose.position.x = 1.0; wall.pose.position.y = 2.0; creator.add_virtual_wall(wall); @@ -63,16 +63,16 @@ TEST(VirtualWallMarkerCreator, oneWall) TEST(VirtualWallMarkerCreator, manyWalls) { - autoware_motion_utils::VirtualWall wall; - autoware_motion_utils::VirtualWallMarkerCreator creator; - wall.style = autoware_motion_utils::VirtualWallType::stop; + autoware::motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWallMarkerCreator creator; + wall.style = autoware::motion_utils::VirtualWallType::stop; wall.ns = "ns1_"; creator.add_virtual_wall(wall); creator.add_virtual_wall(wall); creator.add_virtual_wall(wall); wall.ns = "ns2_"; creator.add_virtual_wall(wall); - wall.style = autoware_motion_utils::VirtualWallType::slowdown; + wall.style = autoware::motion_utils::VirtualWallType::slowdown; wall.ns = "ns2_"; creator.add_virtual_wall(wall); creator.add_virtual_wall(wall); @@ -80,7 +80,7 @@ TEST(VirtualWallMarkerCreator, manyWalls) creator.add_virtual_wall(wall); creator.add_virtual_wall(wall); creator.add_virtual_wall(wall); - wall.style = autoware_motion_utils::VirtualWallType::deadline; + wall.style = autoware::motion_utils::VirtualWallType::deadline; wall.ns = "ns1_"; creator.add_virtual_wall(wall); wall.ns = "ns2_"; diff --git a/common/autoware_motion_utils/test/src/resample/test_resample.cpp b/common/autoware_motion_utils/test/src/resample/test_resample.cpp index 1f83da0726c42..62db1b665d07a 100644 --- a/common/autoware_motion_utils/test/src/resample/test_resample.cpp +++ b/common/autoware_motion_utils/test/src/resample/test_resample.cpp @@ -27,13 +27,13 @@ namespace { +using autoware::universe_utils::createPoint; +using autoware::universe_utils::createQuaternionFromRPY; +using autoware::universe_utils::transformPoint; using autoware_planning_msgs::msg::Path; using autoware_planning_msgs::msg::PathPoint; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; -using autoware_universe_utils::createPoint; -using autoware_universe_utils::createQuaternionFromRPY; -using autoware_universe_utils::transformPoint; using tier4_planning_msgs::msg::PathPointWithLaneId; using tier4_planning_msgs::msg::PathWithLaneId; @@ -177,7 +177,7 @@ std::vector generateArclength(const size_t num_points, const double inte TEST(resample_vector_pose, resample_by_same_interval) { - using autoware_motion_utils::resamplePoseVector; + using autoware::motion_utils::resamplePoseVector; using geometry_msgs::msg::Pose; std::vector path(10); @@ -220,7 +220,7 @@ TEST(resample_vector_pose, resample_by_same_interval) TEST(resample_path_with_lane_id, resample_path_by_vector) { - using autoware_motion_utils::resamplePath; + using autoware::motion_utils::resamplePath; // Output is same as input { auto path = generateTestPathWithLaneId(10, 1.0, 3.0, 1.0, 0.01); @@ -251,7 +251,7 @@ TEST(resample_path_with_lane_id, resample_path_by_vector) // Change the last point orientation path.points.back() = generateTestPathPointWithLaneId( - 9.0, 0.0, 0.0, autoware_universe_utils::pi / 3.0, 3.0, 1.0, 0.01, true, {9}); + 9.0, 0.0, 0.0, autoware::universe_utils::pi / 3.0, 3.0, 1.0, 0.01, true, {9}); { const auto resampled_path = resamplePath(path, resampled_arclength); for (size_t i = 0; i < resampled_path.points.size() - 1; ++i) { @@ -276,7 +276,7 @@ TEST(resample_path_with_lane_id, resample_path_by_vector) const auto p = resampled_path.points.back(); const auto ans_p = path.points.back(); - const auto ans_quat = autoware_universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); + const auto ans_quat = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); EXPECT_NEAR(p.point.pose.position.x, ans_p.point.pose.position.x, epsilon); EXPECT_NEAR(p.point.pose.position.y, ans_p.point.pose.position.y, epsilon); EXPECT_NEAR(p.point.pose.position.z, ans_p.point.pose.position.z, epsilon); @@ -540,14 +540,14 @@ TEST(resample_path_with_lane_id, resample_path_by_vector) TEST(resample_path_with_lane_id, resample_path_by_vector_backward) { - using autoware_motion_utils::resamplePath; + using autoware::motion_utils::resamplePath; { tier4_planning_msgs::msg::PathWithLaneId path; path.points.resize(10); for (size_t i = 0; i < 10; ++i) { path.points.at(i) = generateTestPathPointWithLaneId( - i * 1.0, 0.0, 0.0, autoware_universe_utils::pi, i * 1.0, i * 0.5, i * 0.1, false, + i * 1.0, 0.0, 0.0, autoware::universe_utils::pi, i * 1.0, i * 0.5, i * 0.1, false, {static_cast(i)}); } path.points.back().point.is_final = true; @@ -639,7 +639,7 @@ TEST(resample_path_with_lane_id, resample_path_by_vector_backward) } } - const auto ans_quat = autoware_universe_utils::createQuaternionFromYaw(M_PI); + const auto ans_quat = autoware::universe_utils::createQuaternionFromYaw(M_PI); for (size_t i = 0; i < resampled_path.points.size(); ++i) { const auto p = resampled_path.points.at(i).point; EXPECT_NEAR(p.pose.orientation.x, ans_quat.x, epsilon); @@ -659,7 +659,7 @@ TEST(resample_path_with_lane_id, resample_path_by_vector_backward) } path.points.back().point.is_final = true; path.points.at(0).point.pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(M_PI + M_PI / 3.0); + autoware::universe_utils::createQuaternionFromYaw(M_PI + M_PI / 3.0); std::vector resampled_arclength = {0.0, 1.2, 1.5, 5.3, 7.5, 9.0}; const auto resampled_path = resamplePath(path, resampled_arclength); @@ -750,7 +750,7 @@ TEST(resample_path_with_lane_id, resample_path_by_vector_backward) // Initial Orientation { - const auto ans_quat = autoware_universe_utils::createQuaternionFromYaw(M_PI + M_PI / 3.0); + const auto ans_quat = autoware::universe_utils::createQuaternionFromYaw(M_PI + M_PI / 3.0); const auto p = resampled_path.points.at(0).point; EXPECT_NEAR(p.pose.orientation.x, ans_quat.x, epsilon); EXPECT_NEAR(p.pose.orientation.y, ans_quat.y, epsilon); @@ -758,7 +758,7 @@ TEST(resample_path_with_lane_id, resample_path_by_vector_backward) EXPECT_NEAR(p.pose.orientation.w, ans_quat.w, epsilon); } - const auto ans_quat = autoware_universe_utils::createQuaternionFromYaw(M_PI); + const auto ans_quat = autoware::universe_utils::createQuaternionFromYaw(M_PI); for (size_t i = 1; i < resampled_path.points.size(); ++i) { const auto p = resampled_path.points.at(i).point; EXPECT_NEAR(p.pose.orientation.x, ans_quat.x, epsilon); @@ -771,7 +771,7 @@ TEST(resample_path_with_lane_id, resample_path_by_vector_backward) TEST(resample_path_with_lane_id, resample_path_by_vector_non_default) { - using autoware_motion_utils::resamplePath; + using autoware::motion_utils::resamplePath; // Lerp x, y { @@ -919,7 +919,7 @@ TEST(resample_path_with_lane_id, resample_path_by_vector_non_default) } const double pitch = std::atan(1.0); - const auto ans_quat = autoware_universe_utils::createQuaternionFromRPY(0.0, pitch, 0.0); + const auto ans_quat = autoware::universe_utils::createQuaternionFromRPY(0.0, pitch, 0.0); for (size_t i = 0; i < resampled_path.points.size(); ++i) { const auto p = resampled_path.points.at(i).point; EXPECT_NEAR(p.pose.orientation.x, ans_quat.x, epsilon); @@ -1009,7 +1009,7 @@ TEST(resample_path_with_lane_id, resample_path_by_vector_non_default) TEST(resample_path_with_lane_id, resample_path_by_same_interval) { - using autoware_motion_utils::resamplePath; + using autoware::motion_utils::resamplePath; // Same point resampling { @@ -1045,7 +1045,7 @@ TEST(resample_path_with_lane_id, resample_path_by_same_interval) } // Change the last point orientation path.points.back() = generateTestPathPointWithLaneId( - 9.0, 0.0, 0.0, autoware_universe_utils::pi / 3.0, 3.0, 1.0, 0.01, true, {9}); + 9.0, 0.0, 0.0, autoware::universe_utils::pi / 3.0, 3.0, 1.0, 0.01, true, {9}); { const auto resampled_path = resamplePath(path, 1.0); for (size_t i = 0; i < resampled_path.points.size() - 1; ++i) { @@ -1070,7 +1070,7 @@ TEST(resample_path_with_lane_id, resample_path_by_same_interval) const auto p = resampled_path.points.back(); const auto ans_p = path.points.back(); - const auto ans_quat = autoware_universe_utils::createQuaternionFromYaw(0.0); + const auto ans_quat = autoware::universe_utils::createQuaternionFromYaw(0.0); EXPECT_NEAR(p.point.pose.position.x, ans_p.point.pose.position.x, epsilon); EXPECT_NEAR(p.point.pose.position.y, ans_p.point.pose.position.y, epsilon); EXPECT_NEAR(p.point.pose.position.z, ans_p.point.pose.position.z, epsilon); @@ -1194,7 +1194,7 @@ TEST(resample_path_with_lane_id, resample_path_by_same_interval) path.points.at(0).point.longitudinal_velocity_mps = 5.0; path.points.back().point.is_final = true; - const double ds = 1.0 - autoware_motion_utils::overlap_threshold; + const double ds = 1.0 - autoware::motion_utils::overlap_threshold; const auto resampled_path = resamplePath(path, ds); for (size_t i = 0; i < resampled_path.points.size() - 1; ++i) { const auto p = resampled_path.points.at(i); @@ -1564,7 +1564,7 @@ TEST(resample_path_with_lane_id, resample_path_by_same_interval) TEST(resample_path, resample_path_by_vector) { - using autoware_motion_utils::resamplePath; + using autoware::motion_utils::resamplePath; // Output is same as input { auto path = generateTestPath(10, 1.0, 3.0, 1.0, 0.01); @@ -1590,7 +1590,7 @@ TEST(resample_path, resample_path_by_vector) // Change the last point orientation path.points.back() = - generateTestPathPoint(9.0, 0.0, 0.0, autoware_universe_utils::pi / 3.0, 3.0, 1.0, 0.01); + generateTestPathPoint(9.0, 0.0, 0.0, autoware::universe_utils::pi / 3.0, 3.0, 1.0, 0.01); { const auto resampled_path = resamplePath(path, resampled_arclength); for (size_t i = 0; i < resampled_path.points.size() - 1; ++i) { @@ -1610,7 +1610,7 @@ TEST(resample_path, resample_path_by_vector) const auto p = resampled_path.points.back(); const auto ans_p = path.points.back(); - const auto ans_quat = autoware_universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); + const auto ans_quat = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); EXPECT_NEAR(p.pose.position.x, ans_p.pose.position.x, epsilon); EXPECT_NEAR(p.pose.position.y, ans_p.pose.position.y, epsilon); EXPECT_NEAR(p.pose.position.z, ans_p.pose.position.z, epsilon); @@ -1812,7 +1812,7 @@ TEST(resample_path, resample_path_by_vector) TEST(resample_path, resample_path_by_vector_backward) { - using autoware_motion_utils::resamplePath; + using autoware::motion_utils::resamplePath; { autoware_planning_msgs::msg::Path path; @@ -1884,7 +1884,7 @@ TEST(resample_path, resample_path_by_vector_backward) EXPECT_NEAR(p.heading_rate_rps, 0.9, epsilon); } - const auto ans_quat = autoware_universe_utils::createQuaternionFromYaw(M_PI); + const auto ans_quat = autoware::universe_utils::createQuaternionFromYaw(M_PI); for (size_t i = 0; i < resampled_path.points.size(); ++i) { const auto p = resampled_path.points.at(i); EXPECT_NEAR(p.pose.orientation.x, ans_quat.x, epsilon); @@ -1902,7 +1902,7 @@ TEST(resample_path, resample_path_by_vector_backward) path.points.at(i) = generateTestPathPoint(i * 1.0, 0.0, 0.0, M_PI, i * 1.0, i * 0.5, i * 0.1); } path.points.at(0).pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(M_PI + M_PI / 3.0); + autoware::universe_utils::createQuaternionFromYaw(M_PI + M_PI / 3.0); std::vector resampled_arclength = {0.0, 1.2, 1.5, 5.3, 7.5, 9.0}; const auto resampled_path = resamplePath(path, resampled_arclength); @@ -1969,7 +1969,7 @@ TEST(resample_path, resample_path_by_vector_backward) // Initial Orientation { - const auto ans_quat = autoware_universe_utils::createQuaternionFromYaw(M_PI + M_PI / 3.0); + const auto ans_quat = autoware::universe_utils::createQuaternionFromYaw(M_PI + M_PI / 3.0); const auto p = resampled_path.points.at(0); EXPECT_NEAR(p.pose.orientation.x, ans_quat.x, epsilon); EXPECT_NEAR(p.pose.orientation.y, ans_quat.y, epsilon); @@ -1977,7 +1977,7 @@ TEST(resample_path, resample_path_by_vector_backward) EXPECT_NEAR(p.pose.orientation.w, ans_quat.w, epsilon); } - const auto ans_quat = autoware_universe_utils::createQuaternionFromYaw(M_PI); + const auto ans_quat = autoware::universe_utils::createQuaternionFromYaw(M_PI); for (size_t i = 1; i < resampled_path.points.size(); ++i) { const auto p = resampled_path.points.at(i); EXPECT_NEAR(p.pose.orientation.x, ans_quat.x, epsilon); @@ -1990,7 +1990,7 @@ TEST(resample_path, resample_path_by_vector_backward) TEST(resample_path, resample_path_by_vector_non_default) { - using autoware_motion_utils::resamplePath; + using autoware::motion_utils::resamplePath; // Lerp x, y { @@ -2103,7 +2103,7 @@ TEST(resample_path, resample_path_by_vector_non_default) } const double pitch = std::atan(1.0); - const auto ans_quat = autoware_universe_utils::createQuaternionFromRPY(0.0, pitch, 0.0); + const auto ans_quat = autoware::universe_utils::createQuaternionFromRPY(0.0, pitch, 0.0); for (size_t i = 0; i < resampled_path.points.size(); ++i) { const auto p = resampled_path.points.at(i); EXPECT_NEAR(p.pose.orientation.x, ans_quat.x, epsilon); @@ -2175,7 +2175,7 @@ TEST(resample_path, resample_path_by_vector_non_default) TEST(resample_path, resample_path_by_same_interval) { - using autoware_motion_utils::resamplePath; + using autoware::motion_utils::resamplePath; // Same point resampling { @@ -2205,7 +2205,7 @@ TEST(resample_path, resample_path_by_same_interval) // Change the last point orientation path.points.back() = - generateTestPathPoint(9.0, 0.0, 0.0, autoware_universe_utils::pi / 3.0, 3.0, 1.0, 0.01); + generateTestPathPoint(9.0, 0.0, 0.0, autoware::universe_utils::pi / 3.0, 3.0, 1.0, 0.01); { const auto resampled_path = resamplePath(path, 1.0); for (size_t i = 0; i < resampled_path.points.size() - 1; ++i) { @@ -2225,7 +2225,7 @@ TEST(resample_path, resample_path_by_same_interval) const auto p = resampled_path.points.back(); const auto ans_p = path.points.back(); - const auto ans_quat = autoware_universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); + const auto ans_quat = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); EXPECT_NEAR(p.pose.position.x, ans_p.pose.position.x, epsilon); EXPECT_NEAR(p.pose.position.y, ans_p.pose.position.y, epsilon); EXPECT_NEAR(p.pose.position.z, ans_p.pose.position.z, epsilon); @@ -2321,7 +2321,7 @@ TEST(resample_path, resample_path_by_same_interval) } path.points.at(0).longitudinal_velocity_mps = 5.0; - const double ds = 1.0 - autoware_motion_utils::overlap_threshold; + const double ds = 1.0 - autoware::motion_utils::overlap_threshold; const auto resampled_path = resamplePath(path, ds); for (size_t i = 0; i < resampled_path.points.size() - 1; ++i) { const auto p = resampled_path.points.at(i); @@ -2633,7 +2633,7 @@ TEST(resample_path, resample_path_by_same_interval) TEST(resample_trajectory, resample_trajectory_by_vector) { - using autoware_motion_utils::resampleTrajectory; + using autoware::motion_utils::resampleTrajectory; // Output is same as input { auto traj = generateTestTrajectory(10, 1.0, 3.0, 1.0, 0.01, 0.5); @@ -2660,7 +2660,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector) // Change the last point orientation traj.points.back() = generateTestTrajectoryPoint( - 9.0, 0.0, 0.0, autoware_universe_utils::pi / 3.0, 3.0, 1.0, 0.01, 0.5); + 9.0, 0.0, 0.0, autoware::universe_utils::pi / 3.0, 3.0, 1.0, 0.01, 0.5); { const auto resampled_path = resampleTrajectory(traj, resampled_arclength); for (size_t i = 0; i < resampled_path.points.size() - 1; ++i) { @@ -2681,7 +2681,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector) const auto p = resampled_path.points.back(); const auto ans_p = traj.points.back(); - const auto ans_quat = autoware_universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); + const auto ans_quat = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); EXPECT_NEAR(p.pose.position.x, ans_p.pose.position.x, epsilon); EXPECT_NEAR(p.pose.position.y, ans_p.pose.position.y, epsilon); EXPECT_NEAR(p.pose.position.z, ans_p.pose.position.z, epsilon); @@ -2891,7 +2891,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector) TEST(resample_trajectory, resample_trajectory_by_vector_non_default) { - using autoware_motion_utils::resampleTrajectory; + using autoware::motion_utils::resampleTrajectory; // Lerp x, y { @@ -3013,7 +3013,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector_non_default) } const double pitch = std::atan(1.0); - const auto ans_quat = autoware_universe_utils::createQuaternionFromRPY(0.0, pitch, 0.0); + const auto ans_quat = autoware::universe_utils::createQuaternionFromRPY(0.0, pitch, 0.0); for (size_t i = 0; i < resampled_traj.points.size(); ++i) { const auto p = resampled_traj.points.at(i); EXPECT_NEAR(p.pose.orientation.x, ans_quat.x, epsilon); @@ -3090,7 +3090,7 @@ TEST(resample_trajectory, resample_trajectory_by_vector_non_default) TEST(resample_trajectory, resample_trajectory_by_same_interval) { - using autoware_motion_utils::resampleTrajectory; + using autoware::motion_utils::resampleTrajectory; // Same point resampling { @@ -3122,7 +3122,7 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) // Change the last point orientation traj.points.back() = generateTestTrajectoryPoint( - 9.0, 0.0, 0.0, autoware_universe_utils::pi / 3.0, 3.0, 1.0, 0.01, 0.5); + 9.0, 0.0, 0.0, autoware::universe_utils::pi / 3.0, 3.0, 1.0, 0.01, 0.5); { const auto resampled_path = resampleTrajectory(traj, 1.0); for (size_t i = 0; i < resampled_path.points.size() - 1; ++i) { @@ -3143,7 +3143,7 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) const auto p = resampled_path.points.back(); const auto ans_p = traj.points.back(); - const auto ans_quat = autoware_universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); + const auto ans_quat = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); EXPECT_NEAR(p.pose.position.x, ans_p.pose.position.x, epsilon); EXPECT_NEAR(p.pose.position.y, ans_p.pose.position.y, epsilon); EXPECT_NEAR(p.pose.position.z, ans_p.pose.position.z, epsilon); @@ -3246,7 +3246,7 @@ TEST(resample_trajectory, resample_trajectory_by_same_interval) } traj.points.at(0).longitudinal_velocity_mps = 5.0; - const double ds = 1.0 - autoware_motion_utils::overlap_threshold; + const double ds = 1.0 - autoware::motion_utils::overlap_threshold; const auto resampled_traj = resampleTrajectory(traj, ds); for (size_t i = 0; i < resampled_traj.points.size() - 1; ++i) { const auto p = resampled_traj.points.at(i); diff --git a/common/autoware_motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp b/common/autoware_motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp index 6cbc0b1cc3c7e..dc828e885af64 100644 --- a/common/autoware_motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp +++ b/common/autoware_motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp @@ -22,9 +22,9 @@ namespace { +using autoware::universe_utils::createPoint; +using autoware::universe_utils::createQuaternionFromRPY; using autoware_planning_msgs::msg::Trajectory; -using autoware_universe_utils::createPoint; -using autoware_universe_utils::createQuaternionFromRPY; constexpr double epsilon = 1e-6; @@ -66,7 +66,7 @@ TEST(trajectory_benchmark, DISABLED_calcLateralOffset) std::default_random_engine e1(r()); std::uniform_real_distribution uniform_dist(0.0, 1000.0); - using autoware_motion_utils::calcLateralOffset; + using autoware::motion_utils::calcLateralOffset; const auto traj = generateTestTrajectory(1000, 1.0, 0.0, 0.0, 0.1); constexpr auto nb_iteration = 10000; diff --git a/common/autoware_motion_utils/test/src/trajectory/test_interpolation.cpp b/common/autoware_motion_utils/test/src/trajectory/test_interpolation.cpp index 8f6fb82f8066b..b4b60ff403048 100644 --- a/common/autoware_motion_utils/test/src/trajectory/test_interpolation.cpp +++ b/common/autoware_motion_utils/test/src/trajectory/test_interpolation.cpp @@ -27,11 +27,11 @@ namespace { +using autoware::universe_utils::createPoint; +using autoware::universe_utils::createQuaternionFromRPY; +using autoware::universe_utils::transformPoint; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; -using autoware_universe_utils::createPoint; -using autoware_universe_utils::createQuaternionFromRPY; -using autoware_universe_utils::transformPoint; using tier4_planning_msgs::msg::PathPointWithLaneId; using tier4_planning_msgs::msg::PathWithLaneId; @@ -124,7 +124,7 @@ T generateTestPath( TEST(Interpolation, interpolate_path_for_trajectory) { - using autoware_motion_utils::calcInterpolatedPoint; + using autoware::motion_utils::calcInterpolatedPoint; { autoware_planning_msgs::msg::Trajectory traj; @@ -348,7 +348,7 @@ TEST(Interpolation, interpolate_path_for_trajectory) TEST(Interpolation, interpolate_path_for_path) { - using autoware_motion_utils::calcInterpolatedPoint; + using autoware::motion_utils::calcInterpolatedPoint; { tier4_planning_msgs::msg::PathWithLaneId path; @@ -540,7 +540,7 @@ TEST(Interpolation, interpolate_path_for_path) TEST(Interpolation, interpolate_points_with_length) { - using autoware_motion_utils::calcInterpolatedPose; + using autoware::motion_utils::calcInterpolatedPose; { autoware_planning_msgs::msg::Trajectory traj; diff --git a/common/autoware_motion_utils/test/src/trajectory/test_path_with_lane_id.cpp b/common/autoware_motion_utils/test/src/trajectory/test_path_with_lane_id.cpp index b9e3a59e39b29..62e4ac74cb639 100644 --- a/common/autoware_motion_utils/test/src/trajectory/test_path_with_lane_id.cpp +++ b/common/autoware_motion_utils/test/src/trajectory/test_path_with_lane_id.cpp @@ -22,7 +22,7 @@ namespace { -using autoware_universe_utils::createPoint; +using autoware::universe_utils::createPoint; using tier4_planning_msgs::msg::PathPointWithLaneId; using tier4_planning_msgs::msg::PathWithLaneId; @@ -31,7 +31,7 @@ geometry_msgs::msg::Pose createPose( { geometry_msgs::msg::Pose p; p.position = createPoint(x, y, z); - p.orientation = autoware_universe_utils::createQuaternionFromRPY(roll, pitch, yaw); + p.orientation = autoware::universe_utils::createQuaternionFromRPY(roll, pitch, yaw); return p; } @@ -54,7 +54,7 @@ PathWithLaneId generateTestPathWithLaneId(const size_t num_points, const double TEST(path_with_lane_id, getPathIndexRangeWithLaneId) { - using autoware_motion_utils::getPathIndexRangeWithLaneId; + using autoware::motion_utils::getPathIndexRangeWithLaneId; using tier4_planning_msgs::msg::PathWithLaneId; // Usual cases @@ -99,8 +99,8 @@ TEST(path_with_lane_id, getPathIndexRangeWithLaneId) TEST(path_with_lane_id, findNearestIndexFromLaneId) { - using autoware_motion_utils::findNearestIndexFromLaneId; - using autoware_motion_utils::findNearestSegmentIndexFromLaneId; + using autoware::motion_utils::findNearestIndexFromLaneId; + using autoware::motion_utils::findNearestSegmentIndexFromLaneId; const auto path = generateTestPathWithLaneId(10, 1.0); @@ -164,7 +164,7 @@ TEST(path_with_lane_id, findNearestIndexFromLaneId) // NOTE: This test is temporary for the current implementation. TEST(path_with_lane_id, convertToRearWheelCenter) { - using autoware_motion_utils::convertToRearWheelCenter; + using autoware::motion_utils::convertToRearWheelCenter; PathWithLaneId path; diff --git a/common/autoware_motion_utils/test/src/trajectory/test_trajectory.cpp b/common/autoware_motion_utils/test/src/trajectory/test_trajectory.cpp index f22a2e62efa7b..4ff9b2a33ca13 100644 --- a/common/autoware_motion_utils/test/src/trajectory/test_trajectory.cpp +++ b/common/autoware_motion_utils/test/src/trajectory/test_trajectory.cpp @@ -28,9 +28,9 @@ namespace { using autoware_planning_msgs::msg::Trajectory; using TrajectoryPointArray = std::vector; -using autoware_universe_utils::createPoint; -using autoware_universe_utils::createQuaternionFromRPY; -using autoware_universe_utils::transformPoint; +using autoware::universe_utils::createPoint; +using autoware::universe_utils::createQuaternionFromRPY; +using autoware::universe_utils::transformPoint; constexpr double epsilon = 1e-6; @@ -94,7 +94,7 @@ void updateTrajectoryVelocityAt(T & points, const size_t idx, const double vel) TEST(trajectory, validateNonEmpty) { - using autoware_motion_utils::validateNonEmpty; + using autoware::motion_utils::validateNonEmpty; // Empty EXPECT_THROW(validateNonEmpty(Trajectory{}.points), std::invalid_argument); @@ -106,7 +106,7 @@ TEST(trajectory, validateNonEmpty) TEST(trajectory, validateNonSharpAngle_DefaultThreshold) { - using autoware_motion_utils::validateNonSharpAngle; + using autoware::motion_utils::validateNonSharpAngle; using autoware_planning_msgs::msg::TrajectoryPoint; TrajectoryPoint p1; @@ -135,9 +135,9 @@ TEST(trajectory, validateNonSharpAngle_DefaultThreshold) TEST(trajectory, validateNonSharpAngle_SetThreshold) { - using autoware_motion_utils::validateNonSharpAngle; + using autoware::motion_utils::validateNonSharpAngle; + using autoware::universe_utils::pi; using autoware_planning_msgs::msg::TrajectoryPoint; - using autoware_universe_utils::pi; TrajectoryPoint p1; p1.pose = createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0); @@ -165,7 +165,7 @@ TEST(trajectory, validateNonSharpAngle_SetThreshold) TEST(trajectory, searchZeroVelocityIndex) { - using autoware_motion_utils::searchZeroVelocityIndex; + using autoware::motion_utils::searchZeroVelocityIndex; // Empty EXPECT_FALSE(searchZeroVelocityIndex(Trajectory{}.points)); @@ -244,7 +244,7 @@ TEST(trajectory, searchZeroVelocityIndex) TEST(trajectory, searchZeroVelocityIndex_from_pose) { - using autoware_motion_utils::searchZeroVelocityIndex; + using autoware::motion_utils::searchZeroVelocityIndex; // No zero velocity point { @@ -307,7 +307,7 @@ TEST(trajectory, searchZeroVelocityIndex_from_pose) TEST(trajectory, findNearestIndex_Pos_StraightTrajectory) { - using autoware_motion_utils::findNearestIndex; + using autoware::motion_utils::findNearestIndex; const auto traj = generateTestTrajectory(10, 1.0); @@ -338,7 +338,7 @@ TEST(trajectory, findNearestIndex_Pos_StraightTrajectory) TEST(trajectory, findNearestIndex_Pos_CurvedTrajectory) { - using autoware_motion_utils::findNearestIndex; + using autoware::motion_utils::findNearestIndex; const auto traj = generateTestTrajectory(10, 1.0, 0.0, 0.0, 0.1); @@ -348,7 +348,7 @@ TEST(trajectory, findNearestIndex_Pos_CurvedTrajectory) TEST(trajectory, findNearestIndex_Pose_NoThreshold) { - using autoware_motion_utils::findNearestIndex; + using autoware::motion_utils::findNearestIndex; const auto traj = generateTestTrajectory(10, 1.0); @@ -374,7 +374,7 @@ TEST(trajectory, findNearestIndex_Pose_NoThreshold) TEST(trajectory, findNearestIndex_Pose_DistThreshold) { - using autoware_motion_utils::findNearestIndex; + using autoware::motion_utils::findNearestIndex; const auto traj = generateTestTrajectory(10, 1.0); @@ -390,7 +390,7 @@ TEST(trajectory, findNearestIndex_Pose_DistThreshold) TEST(trajectory, findNearestIndex_Pose_YawThreshold) { - using autoware_motion_utils::findNearestIndex; + using autoware::motion_utils::findNearestIndex; const auto traj = generateTestTrajectory(10, 1.0); const auto max_d = std::numeric_limits::max(); @@ -409,7 +409,7 @@ TEST(trajectory, findNearestIndex_Pose_YawThreshold) TEST(trajectory, findNearestIndex_Pose_DistAndYawThreshold) { - using autoware_motion_utils::findNearestIndex; + using autoware::motion_utils::findNearestIndex; const auto traj = generateTestTrajectory(10, 1.0); @@ -423,7 +423,7 @@ TEST(trajectory, findNearestIndex_Pose_DistAndYawThreshold) TEST(trajectory, findNearestSegmentIndex) { - using autoware_motion_utils::findNearestSegmentIndex; + using autoware::motion_utils::findNearestSegmentIndex; const auto traj = generateTestTrajectory(10, 1.0); @@ -463,7 +463,7 @@ TEST(trajectory, findNearestSegmentIndex) TEST(trajectory, calcLongitudinalOffsetToSegment_StraightTrajectory) { - using autoware_motion_utils::calcLongitudinalOffsetToSegment; + using autoware::motion_utils::calcLongitudinalOffsetToSegment; const auto traj = generateTestTrajectory(10, 1.0); const bool throw_exception = true; @@ -513,7 +513,7 @@ TEST(trajectory, calcLongitudinalOffsetToSegment_StraightTrajectory) TEST(trajectory, calcLongitudinalOffsetToSegment_CurveTrajectory) { - using autoware_motion_utils::calcLongitudinalOffsetToSegment; + using autoware::motion_utils::calcLongitudinalOffsetToSegment; const auto traj = generateTestTrajectory(10, 1.0, 0.0, 0.0, 0.1); @@ -525,7 +525,7 @@ TEST(trajectory, calcLongitudinalOffsetToSegment_CurveTrajectory) TEST(trajectory, calcLateralOffset) { - using autoware_motion_utils::calcLateralOffset; + using autoware::motion_utils::calcLateralOffset; const auto traj = generateTestTrajectory(10, 1.0); const bool throw_exception = true; @@ -566,7 +566,7 @@ TEST(trajectory, calcLateralOffset) TEST(trajectory, calcLateralOffset_without_segment_idx) { - using autoware_motion_utils::calcLateralOffset; + using autoware::motion_utils::calcLateralOffset; const auto traj = generateTestTrajectory(10, 1.0); const bool throw_exception = true; @@ -627,7 +627,7 @@ TEST(trajectory, calcLateralOffset_without_segment_idx) TEST(trajectory, calcLateralOffset_CurveTrajectory) { - using autoware_motion_utils::calcLateralOffset; + using autoware::motion_utils::calcLateralOffset; const auto traj = generateTestTrajectory(10, 1.0, 0.0, 0.0, 0.1); @@ -638,7 +638,7 @@ TEST(trajectory, calcLateralOffset_CurveTrajectory) TEST(trajectory, calcSignedArcLengthFromIndexToIndex) { - using autoware_motion_utils::calcSignedArcLength; + using autoware::motion_utils::calcSignedArcLength; const auto traj = generateTestTrajectory(10, 1.0); @@ -661,7 +661,7 @@ TEST(trajectory, calcSignedArcLengthFromIndexToIndex) TEST(trajectory, calcSignedArcLengthFromPointToIndex) { - using autoware_motion_utils::calcSignedArcLength; + using autoware::motion_utils::calcSignedArcLength; const auto traj = generateTestTrajectory(10, 1.0); @@ -690,7 +690,7 @@ TEST(trajectory, calcSignedArcLengthFromPointToIndex) TEST(trajectory, calcSignedArcLengthFromIndexToPoint) { - using autoware_motion_utils::calcSignedArcLength; + using autoware::motion_utils::calcSignedArcLength; const auto traj = generateTestTrajectory(10, 1.0); @@ -719,7 +719,7 @@ TEST(trajectory, calcSignedArcLengthFromIndexToPoint) TEST(trajectory, calcSignedArcLengthFromPointToPoint) { - using autoware_motion_utils::calcSignedArcLength; + using autoware::motion_utils::calcSignedArcLength; const auto traj = generateTestTrajectory(10, 1.0); @@ -782,7 +782,7 @@ TEST(trajectory, calcSignedArcLengthFromPointToPoint) TEST(trajectory, calcArcLength) { - using autoware_motion_utils::calcArcLength; + using autoware::motion_utils::calcArcLength; const auto traj = generateTestTrajectory(10, 1.0); @@ -795,7 +795,7 @@ TEST(trajectory, calcArcLength) TEST(trajectory, convertToTrajectory) { - using autoware_motion_utils::convertToTrajectory; + using autoware::motion_utils::convertToTrajectory; // Size check { @@ -807,7 +807,7 @@ TEST(trajectory, convertToTrajectory) TEST(trajectory, convertToTrajectoryPointArray) { - using autoware_motion_utils::convertToTrajectoryPointArray; + using autoware::motion_utils::convertToTrajectoryPointArray; const auto traj_input = generateTestTrajectory(100, 1.0); const auto traj = convertToTrajectoryPointArray(traj_input); @@ -823,7 +823,7 @@ TEST(trajectory, convertToTrajectoryPointArray) TEST(trajectory, calcDistanceToForwardStopPointFromIndex) { - using autoware_motion_utils::calcDistanceToForwardStopPoint; + using autoware::motion_utils::calcDistanceToForwardStopPoint; auto traj_input = generateTestTrajectory(100, 1.0, 3.0); traj_input.points.at(50).longitudinal_velocity_mps = 0.0; @@ -881,7 +881,7 @@ TEST(trajectory, calcDistanceToForwardStopPointFromIndex) TEST(trajectory, calcDistanceToForwardStopPointFromPose) { - using autoware_motion_utils::calcDistanceToForwardStopPoint; + using autoware::motion_utils::calcDistanceToForwardStopPoint; auto traj_input = generateTestTrajectory(100, 1.0, 3.0); traj_input.points.at(50).longitudinal_velocity_mps = 0.0; @@ -965,7 +965,7 @@ TEST(trajectory, calcDistanceToForwardStopPointFromPose) TEST(trajectory, calcDistanceToForwardStopPoint_DistThreshold) { - using autoware_motion_utils::calcDistanceToForwardStopPoint; + using autoware::motion_utils::calcDistanceToForwardStopPoint; auto traj_input = generateTestTrajectory(100, 1.0, 3.0); traj_input.points.at(50).longitudinal_velocity_mps = 0.0; @@ -1009,8 +1009,8 @@ TEST(trajectory, calcDistanceToForwardStopPoint_DistThreshold) TEST(trajectory, calcDistanceToForwardStopPoint_YawThreshold) { - using autoware_motion_utils::calcDistanceToForwardStopPoint; - using autoware_universe_utils::deg2rad; + using autoware::motion_utils::calcDistanceToForwardStopPoint; + using autoware::universe_utils::deg2rad; const auto max_d = std::numeric_limits::max(); auto traj_input = generateTestTrajectory(100, 1.0, 3.0); @@ -1061,10 +1061,10 @@ TEST(trajectory, calcDistanceToForwardStopPoint_YawThreshold) TEST(trajectory, calcLongitudinalOffsetPointFromIndex) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::calcLongitudinalOffsetPoint; - using autoware_motion_utils::calcSignedArcLength; - using autoware_universe_utils::getPoint; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::calcLongitudinalOffsetPoint; + using autoware::motion_utils::calcSignedArcLength; + using autoware::universe_utils::getPoint; const auto traj = generateTestTrajectory(10, 1.0); const auto total_length = calcArcLength(traj.points); @@ -1137,11 +1137,11 @@ TEST(trajectory, calcLongitudinalOffsetPointFromIndex) TEST(trajectory, calcLongitudinalOffsetPointFromPoint) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::calcLongitudinalOffsetPoint; - using autoware_motion_utils::calcSignedArcLength; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::getPoint; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::calcLongitudinalOffsetPoint; + using autoware::motion_utils::calcSignedArcLength; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::getPoint; const auto traj = generateTestTrajectory(10, 1.0); const auto total_length = calcArcLength(traj.points); @@ -1215,10 +1215,10 @@ TEST(trajectory, calcLongitudinalOffsetPointFromPoint) TEST(trajectory, calcLongitudinalOffsetPoseFromIndex) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::calcLongitudinalOffsetPose; - using autoware_motion_utils::calcSignedArcLength; - using autoware_universe_utils::getPoint; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::calcLongitudinalOffsetPose; + using autoware::motion_utils::calcSignedArcLength; + using autoware::universe_utils::getPoint; const auto traj = generateTestTrajectory(10, 1.0); const auto total_length = calcArcLength(traj.points); @@ -1299,10 +1299,10 @@ TEST(trajectory, calcLongitudinalOffsetPoseFromIndex) TEST(trajectory, calcLongitudinalOffsetPoseFromIndex_quatInterpolation) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::calcLongitudinalOffsetPose; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::calcLongitudinalOffsetPose; + using autoware::universe_utils::deg2rad; using autoware_planning_msgs::msg::TrajectoryPoint; - using autoware_universe_utils::deg2rad; Trajectory traj{}; @@ -1385,10 +1385,10 @@ TEST(trajectory, calcLongitudinalOffsetPoseFromIndex_quatInterpolation) TEST(trajectory, calcLongitudinalOffsetPoseFromIndex_quatSphericalInterpolation) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::calcLongitudinalOffsetPose; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::calcLongitudinalOffsetPose; + using autoware::universe_utils::deg2rad; using autoware_planning_msgs::msg::TrajectoryPoint; - using autoware_universe_utils::deg2rad; Trajectory traj{}; @@ -1477,11 +1477,11 @@ TEST(trajectory, calcLongitudinalOffsetPoseFromIndex_quatSphericalInterpolation) TEST(trajectory, calcLongitudinalOffsetPoseFromPoint) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::calcLongitudinalOffsetPose; - using autoware_motion_utils::calcSignedArcLength; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::getPoint; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::calcLongitudinalOffsetPose; + using autoware::motion_utils::calcSignedArcLength; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::getPoint; const auto traj = generateTestTrajectory(10, 1.0); const auto total_length = calcArcLength(traj.points); @@ -1563,12 +1563,12 @@ TEST(trajectory, calcLongitudinalOffsetPoseFromPoint) TEST(trajectory, calcLongitudinalOffsetPoseFromPoint_quatInterpolation) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::calcLongitudinalOffsetPose; - using autoware_motion_utils::calcLongitudinalOffsetToSegment; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::calcLongitudinalOffsetPose; + using autoware::motion_utils::calcLongitudinalOffsetToSegment; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::deg2rad; using autoware_planning_msgs::msg::TrajectoryPoint; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::deg2rad; Trajectory traj{}; @@ -1637,12 +1637,12 @@ TEST(trajectory, calcLongitudinalOffsetPoseFromPoint_quatInterpolation) TEST(trajectory, calcLongitudinalOffsetPoseFromPoint_quatSphericalInterpolation) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::calcLongitudinalOffsetPose; - using autoware_motion_utils::calcLongitudinalOffsetToSegment; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::calcLongitudinalOffsetPose; + using autoware::motion_utils::calcLongitudinalOffsetToSegment; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::deg2rad; using autoware_planning_msgs::msg::TrajectoryPoint; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::deg2rad; Trajectory traj{}; @@ -1715,13 +1715,13 @@ TEST(trajectory, calcLongitudinalOffsetPoseFromPoint_quatSphericalInterpolation) TEST(trajectory, insertTargetPoint) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::findNearestSegmentIndex; - using autoware_motion_utils::insertTargetPoint; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::getPose; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::findNearestSegmentIndex; + using autoware::motion_utils::insertTargetPoint; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::getPose; const auto traj = generateTestTrajectory(10, 1.0); const auto total_length = calcArcLength(traj.points); @@ -1928,19 +1928,19 @@ TEST(trajectory, insertTargetPoint) TEST(trajectory, insertTargetPoint_Reverse) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::findNearestSegmentIndex; - using autoware_motion_utils::insertTargetPoint; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::createQuaternionFromYaw; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::getPose; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::findNearestSegmentIndex; + using autoware::motion_utils::insertTargetPoint; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::createQuaternionFromYaw; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::getPose; constexpr double overlap_threshold = 1e-4; auto traj = generateTestTrajectory(10, 1.0); for (size_t i = 0; i < traj.points.size(); ++i) { - traj.points.at(i).pose.orientation = createQuaternionFromYaw(autoware_universe_utils::pi); + traj.points.at(i).pose.orientation = createQuaternionFromYaw(autoware::universe_utils::pi); } const auto total_length = calcArcLength(traj.points); @@ -1986,13 +1986,13 @@ TEST(trajectory, insertTargetPoint_Reverse) TEST(trajectory, insertTargetPoint_OverlapThreshold) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::findNearestSegmentIndex; - using autoware_motion_utils::insertTargetPoint; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::getPose; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::findNearestSegmentIndex; + using autoware::motion_utils::insertTargetPoint; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::getPose; constexpr double overlap_threshold = 1e-4; const auto traj = generateTestTrajectory(10, 1.0); @@ -2079,13 +2079,13 @@ TEST(trajectory, insertTargetPoint_OverlapThreshold) TEST(trajectory, insertTargetPoint_Length) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::findNearestSegmentIndex; - using autoware_motion_utils::insertTargetPoint; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::getPose; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::findNearestSegmentIndex; + using autoware::motion_utils::insertTargetPoint; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::getPose; const auto traj = generateTestTrajectory(10, 1.0); const auto total_length = calcArcLength(traj.points); @@ -2317,13 +2317,13 @@ TEST(trajectory, insertTargetPoint_Length) TEST(trajectory, insertTargetPoint_Length_Without_Target_Point) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::findNearestSegmentIndex; - using autoware_motion_utils::insertTargetPoint; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::getPose; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::findNearestSegmentIndex; + using autoware::motion_utils::insertTargetPoint; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::getPose; const auto traj = generateTestTrajectory(10, 1.0); const auto total_length = calcArcLength(traj.points); @@ -2503,13 +2503,13 @@ TEST(trajectory, insertTargetPoint_Length_Without_Target_Point) TEST(trajectory, insertTargetPoint_Length_Without_Target_Point_Non_Zero_Start_Idx) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::findNearestSegmentIndex; - using autoware_motion_utils::insertTargetPoint; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::getPose; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::findNearestSegmentIndex; + using autoware::motion_utils::insertTargetPoint; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::getPose; const auto traj = generateTestTrajectory(10, 1.0); @@ -2733,13 +2733,13 @@ TEST(trajectory, insertTargetPoint_Length_Without_Target_Point_Non_Zero_Start_Id TEST(trajectory, insertTargetPoint_Negative_Length_Without_Target_Point_Non_Zero_Start_Idx) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::findNearestSegmentIndex; - using autoware_motion_utils::insertTargetPoint; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::getPose; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::findNearestSegmentIndex; + using autoware::motion_utils::insertTargetPoint; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::getPose; const auto traj = generateTestTrajectory(10, 1.0); @@ -2920,13 +2920,13 @@ TEST(trajectory, insertTargetPoint_Negative_Length_Without_Target_Point_Non_Zero TEST(trajectory, insertTargetPoint_Length_from_a_pose) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::findNearestSegmentIndex; - using autoware_motion_utils::insertTargetPoint; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::getPose; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::findNearestSegmentIndex; + using autoware::motion_utils::insertTargetPoint; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::getPose; const auto traj = generateTestTrajectory(10, 1.0); const auto total_length = calcArcLength(traj.points); @@ -3272,13 +3272,13 @@ TEST(trajectory, insertTargetPoint_Length_from_a_pose) TEST(trajectory, insertStopPoint_from_a_source_index) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::findNearestSegmentIndex; - using autoware_motion_utils::insertStopPoint; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::getPose; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::findNearestSegmentIndex; + using autoware::motion_utils::insertStopPoint; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::getPose; const auto traj = generateTestTrajectory(10, 1.0, 10.0); @@ -3527,13 +3527,13 @@ TEST(trajectory, insertStopPoint_from_a_source_index) TEST(trajectory, insertStopPoint_from_front_point) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::findNearestSegmentIndex; - using autoware_motion_utils::insertStopPoint; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::getPose; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::findNearestSegmentIndex; + using autoware::motion_utils::insertStopPoint; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::getPose; const auto traj = generateTestTrajectory(10, 1.0, 10.0); @@ -3724,13 +3724,13 @@ TEST(trajectory, insertStopPoint_from_front_point) TEST(trajectory, insertStopPoint_from_a_pose) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::findNearestSegmentIndex; - using autoware_motion_utils::insertStopPoint; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::getPose; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::findNearestSegmentIndex; + using autoware::motion_utils::insertStopPoint; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::getPose; const auto traj = generateTestTrajectory(10, 1.0, 10.0); const auto total_length = calcArcLength(traj.points); @@ -4110,13 +4110,13 @@ TEST(trajectory, insertStopPoint_from_a_pose) TEST(trajectory, insertStopPoint_with_pose_and_segment_index) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::findNearestSegmentIndex; - using autoware_motion_utils::insertStopPoint; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::getPose; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::findNearestSegmentIndex; + using autoware::motion_utils::insertStopPoint; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::getPose; const auto traj = generateTestTrajectory(10, 1.0, 3.0); const auto total_length = calcArcLength(traj.points); @@ -4354,12 +4354,12 @@ TEST(trajectory, insertStopPoint_with_pose_and_segment_index) TEST(trajectory, insertDecelPoint_from_a_point) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::findNearestSegmentIndex; - using autoware_motion_utils::insertDecelPoint; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::getLongitudinalVelocity; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::findNearestSegmentIndex; + using autoware::motion_utils::insertDecelPoint; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::getLongitudinalVelocity; const auto traj = generateTestTrajectory(10, 1.0, 10.0); const auto total_length = calcArcLength(traj.points); @@ -4444,9 +4444,9 @@ TEST(trajectory, insertDecelPoint_from_a_point) TEST(trajectory, findFirstNearestIndexWithSoftConstraints) { - using autoware_motion_utils::findFirstNearestIndexWithSoftConstraints; - using autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints; - using autoware_universe_utils::pi; + using autoware::motion_utils::findFirstNearestIndexWithSoftConstraints; + using autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints; + using autoware::universe_utils::pi; const auto traj = generateTestTrajectory(10, 1.0); @@ -4970,7 +4970,7 @@ TEST(trajectory, findFirstNearestIndexWithSoftConstraints) TEST(trajectory, calcSignedArcLengthFromPointAndSegmentIndexToPointAndSegmentIndex) { - using autoware_motion_utils::calcSignedArcLength; + using autoware::motion_utils::calcSignedArcLength; const auto traj = generateTestTrajectory(10, 1.0); @@ -5040,7 +5040,7 @@ TEST(trajectory, calcSignedArcLengthFromPointAndSegmentIndexToPointAndSegmentInd TEST(trajectory, calcSignedArcLengthFromPointAndSegmentIndexToPointIndex) { - using autoware_motion_utils::calcSignedArcLength; + using autoware::motion_utils::calcSignedArcLength; const auto traj = generateTestTrajectory(10, 1.0); @@ -5119,7 +5119,7 @@ TEST(trajectory, calcSignedArcLengthFromPointAndSegmentIndexToPointIndex) TEST(trajectory, removeOverlapPoints) { - using autoware_motion_utils::removeOverlapPoints; + using autoware::motion_utils::removeOverlapPoints; const auto traj = generateTestTrajectory(10, 1.0, 1.0); const auto removed_traj = removeOverlapPoints(traj.points, 0); @@ -5246,101 +5246,101 @@ TEST(trajectory, removeOverlapPoints) TEST(trajectory, cropForwardPoints) { - using autoware_motion_utils::cropForwardPoints; + using autoware::motion_utils::cropForwardPoints; const auto traj = generateTestTrajectory(10, 1.0, 1.0); { // Normal case const auto cropped_traj_points = - cropForwardPoints(traj.points, autoware_universe_utils::createPoint(1.5, 1.5, 0.0), 1, 4.8); + cropForwardPoints(traj.points, autoware::universe_utils::createPoint(1.5, 1.5, 0.0), 1, 4.8); EXPECT_EQ(cropped_traj_points.size(), static_cast(7)); } { // Forward length is longer than points arc length. const auto cropped_traj_points = - cropForwardPoints(traj.points, autoware_universe_utils::createPoint(1.5, 1.5, 0.0), 1, 10.0); + cropForwardPoints(traj.points, autoware::universe_utils::createPoint(1.5, 1.5, 0.0), 1, 10.0); EXPECT_EQ(cropped_traj_points.size(), static_cast(10)); } { // Point is on the previous segment const auto cropped_traj_points = - cropForwardPoints(traj.points, autoware_universe_utils::createPoint(1.0, 1.0, 0.0), 0, 2.5); + cropForwardPoints(traj.points, autoware::universe_utils::createPoint(1.0, 1.0, 0.0), 0, 2.5); EXPECT_EQ(cropped_traj_points.size(), static_cast(4)); } { // Point is on the next segment const auto cropped_traj_points = - cropForwardPoints(traj.points, autoware_universe_utils::createPoint(1.0, 1.0, 0.0), 1, 2.5); + cropForwardPoints(traj.points, autoware::universe_utils::createPoint(1.0, 1.0, 0.0), 1, 2.5); EXPECT_EQ(cropped_traj_points.size(), static_cast(4)); } } TEST(trajectory, cropBackwardPoints) { - using autoware_motion_utils::cropBackwardPoints; + using autoware::motion_utils::cropBackwardPoints; const auto traj = generateTestTrajectory(10, 1.0, 1.0); { // Normal case const auto cropped_traj_points = - cropBackwardPoints(traj.points, autoware_universe_utils::createPoint(8.5, 8.5, 0.0), 8, 4.8); + cropBackwardPoints(traj.points, autoware::universe_utils::createPoint(8.5, 8.5, 0.0), 8, 4.8); EXPECT_EQ(cropped_traj_points.size(), static_cast(6)); } { // Backward length is longer than points arc length. - const auto cropped_traj_points = - cropBackwardPoints(traj.points, autoware_universe_utils::createPoint(8.5, 8.5, 0.0), 8, 10.0); + const auto cropped_traj_points = cropBackwardPoints( + traj.points, autoware::universe_utils::createPoint(8.5, 8.5, 0.0), 8, 10.0); EXPECT_EQ(cropped_traj_points.size(), static_cast(10)); } { // Point is on the previous segment const auto cropped_traj_points = - cropBackwardPoints(traj.points, autoware_universe_utils::createPoint(8.0, 8.0, 0.0), 7, 2.5); + cropBackwardPoints(traj.points, autoware::universe_utils::createPoint(8.0, 8.0, 0.0), 7, 2.5); EXPECT_EQ(cropped_traj_points.size(), static_cast(4)); } { // Point is on the next segment const auto cropped_traj_points = - cropBackwardPoints(traj.points, autoware_universe_utils::createPoint(8.0, 8.0, 0.0), 8, 2.5); + cropBackwardPoints(traj.points, autoware::universe_utils::createPoint(8.0, 8.0, 0.0), 8, 2.5); EXPECT_EQ(cropped_traj_points.size(), static_cast(4)); } } TEST(trajectory, cropPoints) { - using autoware_motion_utils::cropPoints; + using autoware::motion_utils::cropPoints; const auto traj = generateTestTrajectory(10, 1.0, 1.0); { // Normal case const auto cropped_traj_points = - cropPoints(traj.points, autoware_universe_utils::createPoint(3.5, 3.5, 0.0), 3, 2.3, 1.2); + cropPoints(traj.points, autoware::universe_utils::createPoint(3.5, 3.5, 0.0), 3, 2.3, 1.2); EXPECT_EQ(cropped_traj_points.size(), static_cast(3)); } { // Length is longer than points arc length. const auto cropped_traj_points = - cropPoints(traj.points, autoware_universe_utils::createPoint(3.5, 3.5, 0.0), 3, 10.0, 10.0); + cropPoints(traj.points, autoware::universe_utils::createPoint(3.5, 3.5, 0.0), 3, 10.0, 10.0); EXPECT_EQ(cropped_traj_points.size(), static_cast(10)); } { // Point is on the previous segment const auto cropped_traj_points = - cropPoints(traj.points, autoware_universe_utils::createPoint(3.0, 3.0, 0.0), 2, 2.2, 1.9); + cropPoints(traj.points, autoware::universe_utils::createPoint(3.0, 3.0, 0.0), 2, 2.2, 1.9); EXPECT_EQ(cropped_traj_points.size(), static_cast(4)); } { // Point is on the next segment const auto cropped_traj_points = - cropPoints(traj.points, autoware_universe_utils::createPoint(3.0, 3.0, 0.0), 3, 2.2, 1.9); + cropPoints(traj.points, autoware::universe_utils::createPoint(3.0, 3.0, 0.0), 3, 2.2, 1.9); EXPECT_EQ(cropped_traj_points.size(), static_cast(4)); } } TEST(Trajectory, removeFirstInvalidOrientationPoints) { - using autoware_motion_utils::insertOrientation; - using autoware_motion_utils::removeFirstInvalidOrientationPoints; + using autoware::motion_utils::insertOrientation; + using autoware::motion_utils::removeFirstInvalidOrientationPoints; const double max_yaw_diff = M_PI_2; @@ -5357,7 +5357,7 @@ TEST(Trajectory, removeFirstInvalidOrientationPoints) EXPECT_EQ(traj.points.at(i), modified_traj.points.at(i)); const double yaw1 = tf2::getYaw(modified_traj.points.at(i).pose.orientation); const double yaw2 = tf2::getYaw(modified_traj.points.at(i + 1).pose.orientation); - const double yaw_diff = std::abs(autoware_universe_utils::normalizeRadian(yaw1 - yaw2)); + const double yaw_diff = std::abs(autoware::universe_utils::normalizeRadian(yaw1 - yaw2)); EXPECT_LE(yaw_diff, max_yaw_diff); } }; @@ -5392,7 +5392,7 @@ TEST(Trajectory, removeFirstInvalidOrientationPoints) TEST(trajectory, calcYawDeviation) { - using autoware_motion_utils::calcYawDeviation; + using autoware::motion_utils::calcYawDeviation; using autoware_planning_msgs::msg::TrajectoryPoint; constexpr double tolerance = 1e-3; @@ -5419,9 +5419,9 @@ TEST(trajectory, calcYawDeviation) TEST(trajectory, isTargetPointFront) { - using autoware_motion_utils::isTargetPointFront; + using autoware::motion_utils::isTargetPointFront; + using autoware::universe_utils::createPoint; using autoware_planning_msgs::msg::TrajectoryPoint; - using autoware_universe_utils::createPoint; // Generate test trajectory const auto trajectory = generateTestTrajectory(10, 1.0); diff --git a/common/autoware_motion_utils/test/src/vehicle/test_vehicle_state_checker.cpp b/common/autoware_motion_utils/test/src/vehicle/test_vehicle_state_checker.cpp index d18aa8d283320..b2d2f3a2e8003 100644 --- a/common/autoware_motion_utils/test/src/vehicle/test_vehicle_state_checker.cpp +++ b/common/autoware_motion_utils/test/src/vehicle/test_vehicle_state_checker.cpp @@ -32,11 +32,11 @@ constexpr double STOP_DURATION_THRESHOLD_600_MS = 0.6; constexpr double STOP_DURATION_THRESHOLD_800_MS = 0.8; constexpr double STOP_DURATION_THRESHOLD_1000_MS = 1.0; -using autoware_motion_utils::VehicleArrivalChecker; -using autoware_motion_utils::VehicleStopChecker; -using autoware_universe_utils::createPoint; -using autoware_universe_utils::createQuaternion; -using autoware_universe_utils::createTranslation; +using autoware::motion_utils::VehicleArrivalChecker; +using autoware::motion_utils::VehicleStopChecker; +using autoware::universe_utils::createPoint; +using autoware::universe_utils::createQuaternion; +using autoware::universe_utils::createTranslation; using nav_msgs::msg::Odometry; class CheckerNode : public rclcpp::Node diff --git a/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp b/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp index b4b5834f71fa1..49d2c848ab508 100644 --- a/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp +++ b/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp @@ -62,8 +62,8 @@ using autoware_planning_msgs::msg::Trajectory; using tier4_planning_msgs::msg::PathPointWithLaneId; using tier4_planning_msgs::msg::PathWithLaneId; using RouteSections = std::vector; -using autoware_universe_utils::createPoint; -using autoware_universe_utils::createQuaternionFromRPY; +using autoware::universe_utils::createPoint; +using autoware::universe_utils::createQuaternionFromRPY; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/boost_geometry.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/boost_geometry.hpp index c90cc714367f1..a0e24c68b7918 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/boost_geometry.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/boost_geometry.hpp @@ -25,7 +25,7 @@ #include -namespace autoware_universe_utils +namespace autoware::universe_utils { // 2D struct Point2d; @@ -93,12 +93,12 @@ inline Point3d fromMsg(const geometry_msgs::msg::Point & msg) point.z() = msg.z; return point; } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils -BOOST_GEOMETRY_REGISTER_POINT_2D( // NOLINT - autoware_universe_utils::Point2d, double, cs::cartesian, x(), y()) // NOLINT -BOOST_GEOMETRY_REGISTER_POINT_3D( // NOLINT - autoware_universe_utils::Point3d, double, cs::cartesian, x(), y(), z()) // NOLINT -BOOST_GEOMETRY_REGISTER_RING(autoware_universe_utils::LinearRing2d) // NOLINT +BOOST_GEOMETRY_REGISTER_POINT_2D( // NOLINT + autoware::universe_utils::Point2d, double, cs::cartesian, x(), y()) // NOLINT +BOOST_GEOMETRY_REGISTER_POINT_3D( // NOLINT + autoware::universe_utils::Point3d, double, cs::cartesian, x(), y(), z()) // NOLINT +BOOST_GEOMETRY_REGISTER_RING(autoware::universe_utils::LinearRing2d) // NOLINT #endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/boost_polygon_utils.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/boost_polygon_utils.hpp index 477a1b4c27a6c..1313ec558fe01 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/boost_polygon_utils.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/boost_polygon_utils.hpp @@ -24,7 +24,7 @@ #include -namespace autoware_universe_utils +namespace autoware::universe_utils { bool isClockwise(const Polygon2d & polygon); Polygon2d inverseClockwise(const Polygon2d & polygon); @@ -47,6 +47,6 @@ Polygon2d toFootprint( const double base_to_rear, const double width); double getArea(const autoware_perception_msgs::msg::Shape & shape); Polygon2d expandPolygon(const Polygon2d & input_polygon, const double offset); -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/geometry.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/geometry.hpp index 0af9d30ad09c1..87c06dfd9cf08 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/geometry.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/geometry.hpp @@ -96,7 +96,7 @@ inline void doTransform( #endif } // namespace tf2 -namespace autoware_universe_utils +namespace autoware::universe_utils { template geometry_msgs::msg::Point getPoint(const T & p) @@ -577,6 +577,6 @@ std::optional intersect( const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2, const geometry_msgs::msg::Point & p3, const geometry_msgs::msg::Point & p4); -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__GEOMETRY_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/pose_deviation.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/pose_deviation.hpp index 2f2b4a5d3dfb0..c3a602caf4232 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/pose_deviation.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/pose_deviation.hpp @@ -18,7 +18,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { struct PoseDeviation { @@ -39,6 +39,6 @@ double calcYawDeviation( PoseDeviation calcPoseDeviation( const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Pose & target_pose); -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/math/constants.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/math/constants.hpp index 2c1f9fe646723..f06770c2925c7 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/math/constants.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/math/constants.hpp @@ -15,10 +15,10 @@ #ifndef AUTOWARE__UNIVERSE_UTILS__MATH__CONSTANTS_HPP_ #define AUTOWARE__UNIVERSE_UTILS__MATH__CONSTANTS_HPP_ -namespace autoware_universe_utils +namespace autoware::universe_utils { constexpr double pi = 3.14159265358979323846; // To be replaced by std::numbers::pi in C++20 constexpr double gravity = 9.80665; -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__MATH__CONSTANTS_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/math/normalization.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/math/normalization.hpp index 502ed4b4f7b34..16af7f44415cc 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/math/normalization.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/math/normalization.hpp @@ -19,7 +19,7 @@ #include -namespace autoware_universe_utils +namespace autoware::universe_utils { inline double normalizeDegree(const double deg, const double min_deg = -180) { @@ -45,6 +45,6 @@ inline double normalizeRadian(const double rad, const double min_rad = -pi) return value - std::copysign(2 * pi, value); } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__MATH__NORMALIZATION_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/math/range.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/math/range.hpp index fabf67a683680..ed0ef455bfcfe 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/math/range.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/math/range.hpp @@ -20,7 +20,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { template std::vector arange(const T start, const T stop, const T step = 1) @@ -73,6 +73,6 @@ std::vector linspace(const T start, const T stop, const size_t num) return out; } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__MATH__RANGE_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/math/sin_table.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/math/sin_table.hpp index bf67a1b521b6d..e87d8a2e5fc40 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/math/sin_table.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/math/sin_table.hpp @@ -17,7 +17,7 @@ #include -namespace autoware_universe_utils +namespace autoware::universe_utils { constexpr size_t sin_table_size = 32769; @@ -25,6 +25,6 @@ constexpr size_t discrete_arcs_num_90 = 32768; constexpr size_t discrete_arcs_num_360 = 131072; extern const float g_sin_table[sin_table_size]; -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__MATH__SIN_TABLE_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/math/trigonometry.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/math/trigonometry.hpp index 7f58735d35963..19a59523c7f08 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/math/trigonometry.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/math/trigonometry.hpp @@ -17,7 +17,7 @@ #include -namespace autoware_universe_utils +namespace autoware::universe_utils { float sin(float radian); @@ -26,6 +26,6 @@ float cos(float radian); std::pair sin_and_cos(float radian); -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__MATH__TRIGONOMETRY_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/math/unit_conversion.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/math/unit_conversion.hpp index 66be4d99d5803..36ce8e9f39514 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/math/unit_conversion.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/math/unit_conversion.hpp @@ -17,7 +17,7 @@ #include "autoware/universe_utils/math/constants.hpp" -namespace autoware_universe_utils +namespace autoware::universe_utils { constexpr double deg2rad(const double deg) { @@ -36,6 +36,6 @@ constexpr double mps2kmph(const double mps) { return mps * 3600.0 / 1000.0; } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__MATH__UNIT_CONVERSION_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/debug_publisher.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/debug_publisher.hpp index 0965f8ffbaefa..acd82995b1d84 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/debug_publisher.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/debug_publisher.hpp @@ -25,14 +25,14 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { namespace debug_publisher { template < class T_msg, class T, std::enable_if_t< - autoware_universe_utils::debug_traits::is_debug_message::value, std::nullptr_t> = + autoware::universe_utils::debug_traits::is_debug_message::value, std::nullptr_t> = nullptr> T_msg toDebugMsg(const T & data, const rclcpp::Time & stamp) { @@ -73,6 +73,6 @@ class DebugPublisher const char * ns_; std::unordered_map> pub_map_; }; -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__ROS__DEBUG_PUBLISHER_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/debug_traits.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/debug_traits.hpp index 330b01b68a0b2..8420f930e0ce9 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/debug_traits.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/debug_traits.hpp @@ -28,7 +28,7 @@ #include -namespace autoware_universe_utils::debug_traits +namespace autoware::universe_utils::debug_traits { template struct is_debug_message : std::false_type @@ -84,6 +84,6 @@ template <> struct is_debug_message : std::true_type { }; -} // namespace autoware_universe_utils::debug_traits +} // namespace autoware::universe_utils::debug_traits #endif // AUTOWARE__UNIVERSE_UTILS__ROS__DEBUG_TRAITS_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/logger_level_configure.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/logger_level_configure.hpp index 41163ea38b018..b1b11d33ab448 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/logger_level_configure.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/logger_level_configure.hpp @@ -27,7 +27,7 @@ // ... // // // Define logger_configure as a node class member variable -// std::unique_ptr logger_configure_; +// std::unique_ptr logger_configure_; // } // // ___In your_node.cpp___ @@ -45,7 +45,7 @@ #include -namespace autoware_universe_utils +namespace autoware::universe_utils { class LoggerLevelConfigure { @@ -64,5 +64,5 @@ class LoggerLevelConfigure const ConfigLogger::Response::SharedPtr response); }; -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__ROS__LOGGER_LEVEL_CONFIGURE_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/marker_helper.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/marker_helper.hpp index ad2d2f84f82e0..6991962c420d1 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/marker_helper.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/marker_helper.hpp @@ -22,7 +22,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { inline geometry_msgs::msg::Point createMarkerPosition(double x, double y, double z) { @@ -76,6 +76,6 @@ void appendMarkerArray( visualization_msgs::msg::MarkerArray * marker_array, const std::optional & current_time = {}); -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__ROS__MARKER_HELPER_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/msg_covariance.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/msg_covariance.hpp index 55caf1955b6ec..ff957a878440e 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/msg_covariance.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/msg_covariance.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE__UNIVERSE_UTILS__ROS__MSG_COVARIANCE_HPP_ #define AUTOWARE__UNIVERSE_UTILS__ROS__MSG_COVARIANCE_HPP_ -namespace autoware_universe_utils +namespace autoware::universe_utils { namespace xyz_covariance_index { @@ -115,6 +115,6 @@ enum XYZ_UPPER_COV_IDX { Z_Z = 5, }; } // namespace xyz_upper_covariance_index -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__ROS__MSG_COVARIANCE_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/parameter.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/parameter.hpp index 5ef1837e0cece..89846688d365d 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/parameter.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/parameter.hpp @@ -19,7 +19,7 @@ #include -namespace autoware_universe_utils +namespace autoware::universe_utils { template T getOrDeclareParameter(rclcpp::Node & node, const std::string & name) @@ -30,6 +30,6 @@ T getOrDeclareParameter(rclcpp::Node & node, const std::string & name) return node.declare_parameter(name); } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__ROS__PARAMETER_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/pcl_conversion.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/pcl_conversion.hpp index cce8a75b37aa9..7fab38790921a 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/pcl_conversion.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/pcl_conversion.hpp @@ -20,7 +20,7 @@ #include -namespace autoware_universe_utils +namespace autoware::universe_utils { /** * @brief a faster implementation of converting sensor_msgs::msg::PointCloud2 to @@ -67,6 +67,6 @@ void transformPointCloudFromROSMsg( } } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__ROS__PCL_CONVERSION_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/polling_subscriber.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/polling_subscriber.hpp index a41e13229a826..1b7ea0bd69951 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/polling_subscriber.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/polling_subscriber.hpp @@ -23,7 +23,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { inline rclcpp::SensorDataQoS SingleDepthSensorQoS() @@ -159,6 +159,6 @@ class InterProcessPollingSubscriber= 2)>::typ }; }; -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/processing_time_publisher.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/processing_time_publisher.hpp index bb92d615b0a8d..96cddc595a5b9 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/processing_time_publisher.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/processing_time_publisher.hpp @@ -23,7 +23,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { class ProcessingTimePublisher { @@ -62,6 +62,6 @@ class ProcessingTimePublisher return oss.str(); } }; -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__ROS__PROCESSING_TIME_PUBLISHER_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/published_time_publisher.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/published_time_publisher.hpp index 960295944a14b..60112d9e83cf3 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/published_time_publisher.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/published_time_publisher.hpp @@ -26,7 +26,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { class PublishedTimePublisher @@ -109,6 +109,6 @@ class PublishedTimePublisher // store them for each different publisher of the node std::map::SharedPtr, GidCompare> publishers_; }; -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__ROS__PUBLISHED_TIME_PUBLISHER_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/self_pose_listener.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/self_pose_listener.hpp index 0bd9a4db5b674..cdcf78a9c5edc 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/self_pose_listener.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/self_pose_listener.hpp @@ -22,7 +22,7 @@ #include -namespace autoware_universe_utils +namespace autoware::universe_utils { class SelfPoseListener { @@ -53,6 +53,6 @@ class SelfPoseListener private: TransformListener transform_listener_; }; -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__ROS__SELF_POSE_LISTENER_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/transform_listener.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/transform_listener.hpp index 176a11dcde529..e053ef3668034 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/transform_listener.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/transform_listener.hpp @@ -26,7 +26,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { class TransformListener { @@ -82,6 +82,6 @@ class TransformListener std::shared_ptr tf_buffer_; std::shared_ptr tf_listener_; }; -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__ROS__TRANSFORM_LISTENER_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/update_param.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/update_param.hpp index 8bb505d765aef..bebb38af0b261 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/update_param.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/update_param.hpp @@ -20,7 +20,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { template bool updateParam(const std::vector & params, const std::string & name, T & value) @@ -37,6 +37,6 @@ bool updateParam(const std::vector & params, const std::strin value = itr->template get_value(); return true; } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__ROS__UPDATE_PARAM_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/uuid_helper.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/uuid_helper.hpp index 7d4892f724848..62c9f75f3f233 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/uuid_helper.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/uuid_helper.hpp @@ -23,7 +23,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { inline unique_identifier_msgs::msg::UUID generateUUID() { @@ -58,6 +58,6 @@ inline unique_identifier_msgs::msg::UUID toUUIDMsg(const boost::uuids::uuid & id return ros_uuid; } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__ROS__UUID_HELPER_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/wait_for_param.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/wait_for_param.hpp index 0aaef92835653..1faaaa861b1c4 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/wait_for_param.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/wait_for_param.hpp @@ -21,7 +21,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { template T waitForParam( @@ -47,6 +47,6 @@ T waitForParam( return {}; } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__ROS__WAIT_FOR_PARAM_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/system/backtrace.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/system/backtrace.hpp index f195cd2b32391..0b025160bacf8 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/system/backtrace.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/system/backtrace.hpp @@ -15,11 +15,11 @@ #ifndef AUTOWARE__UNIVERSE_UTILS__SYSTEM__BACKTRACE_HPP_ #define AUTOWARE__UNIVERSE_UTILS__SYSTEM__BACKTRACE_HPP_ -namespace autoware_universe_utils +namespace autoware::universe_utils { void print_backtrace(); -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__SYSTEM__BACKTRACE_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/system/stop_watch.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/system/stop_watch.hpp index 3df651825f1aa..eb5cb546b8c7f 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/system/stop_watch.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/system/stop_watch.hpp @@ -19,7 +19,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { template < class OutputUnit = std::chrono::seconds, class InternalUnit = std::chrono::microseconds, @@ -58,6 +58,6 @@ class StopWatch std::unordered_map t_start_; }; -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__SYSTEM__STOP_WATCH_HPP_ diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/transform/transforms.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/transform/transforms.hpp index f480a709d169e..8a92116b426ec 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/transform/transforms.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/transform/transforms.hpp @@ -21,7 +21,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { template void transformPointCloud( @@ -46,6 +46,6 @@ void transformPointCloud( pcl::transformPointCloud(cloud_in, cloud_out, transform); } } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils #endif // AUTOWARE__UNIVERSE_UTILS__TRANSFORM__TRANSFORMS_HPP_ diff --git a/common/autoware_universe_utils/src/geometry/boost_polygon_utils.cpp b/common/autoware_universe_utils/src/geometry/boost_polygon_utils.cpp index ce9232a8c1add..da3da42cbc41b 100644 --- a/common/autoware_universe_utils/src/geometry/boost_polygon_utils.cpp +++ b/common/autoware_universe_utils/src/geometry/boost_polygon_utils.cpp @@ -23,8 +23,8 @@ namespace { namespace bg = boost::geometry; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point & geom_point) { @@ -68,7 +68,7 @@ double getCircleArea(const geometry_msgs::msg::Vector3 & dimensions) } } // namespace -namespace autoware_universe_utils +namespace autoware::universe_utils { bool isClockwise(const Polygon2d & polygon) { @@ -123,16 +123,16 @@ Polygon2d toPolygon2d( Polygon2d polygon; if (shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { - const auto point0 = autoware_universe_utils::calcOffsetPose( + const auto point0 = autoware::universe_utils::calcOffsetPose( pose, shape.dimensions.x / 2.0, shape.dimensions.y / 2.0, 0.0) .position; - const auto point1 = autoware_universe_utils::calcOffsetPose( + const auto point1 = autoware::universe_utils::calcOffsetPose( pose, -shape.dimensions.x / 2.0, shape.dimensions.y / 2.0, 0.0) .position; - const auto point2 = autoware_universe_utils::calcOffsetPose( + const auto point2 = autoware::universe_utils::calcOffsetPose( pose, -shape.dimensions.x / 2.0, -shape.dimensions.y / 2.0, 0.0) .position; - const auto point3 = autoware_universe_utils::calcOffsetPose( + const auto point3 = autoware::universe_utils::calcOffsetPose( pose, shape.dimensions.x / 2.0, -shape.dimensions.y / 2.0, 0.0) .position; @@ -179,24 +179,24 @@ Polygon2d toPolygon2d( return isClockwise(polygon) ? polygon : inverseClockwise(polygon); } -autoware_universe_utils::Polygon2d toPolygon2d( +autoware::universe_utils::Polygon2d toPolygon2d( const autoware_perception_msgs::msg::DetectedObject & object) { - return autoware_universe_utils::toPolygon2d( + return autoware::universe_utils::toPolygon2d( object.kinematics.pose_with_covariance.pose, object.shape); } -autoware_universe_utils::Polygon2d toPolygon2d( +autoware::universe_utils::Polygon2d toPolygon2d( const autoware_perception_msgs::msg::TrackedObject & object) { - return autoware_universe_utils::toPolygon2d( + return autoware::universe_utils::toPolygon2d( object.kinematics.pose_with_covariance.pose, object.shape); } -autoware_universe_utils::Polygon2d toPolygon2d( +autoware::universe_utils::Polygon2d toPolygon2d( const autoware_perception_msgs::msg::PredictedObject & object) { - return autoware_universe_utils::toPolygon2d( + return autoware::universe_utils::toPolygon2d( object.kinematics.initial_pose_with_covariance.pose, object.shape); } @@ -206,16 +206,16 @@ Polygon2d toFootprint( { Polygon2d polygon; const auto point0 = - autoware_universe_utils::calcOffsetPose(base_link_pose, base_to_front, width / 2.0, 0.0) + autoware::universe_utils::calcOffsetPose(base_link_pose, base_to_front, width / 2.0, 0.0) .position; const auto point1 = - autoware_universe_utils::calcOffsetPose(base_link_pose, base_to_front, -width / 2.0, 0.0) + autoware::universe_utils::calcOffsetPose(base_link_pose, base_to_front, -width / 2.0, 0.0) .position; const auto point2 = - autoware_universe_utils::calcOffsetPose(base_link_pose, -base_to_rear, -width / 2.0, 0.0) + autoware::universe_utils::calcOffsetPose(base_link_pose, -base_to_rear, -width / 2.0, 0.0) .position; const auto point3 = - autoware_universe_utils::calcOffsetPose(base_link_pose, -base_to_rear, width / 2.0, 0.0) + autoware::universe_utils::calcOffsetPose(base_link_pose, -base_to_rear, width / 2.0, 0.0) .position; appendPointToPolygon(polygon, point0); @@ -272,4 +272,4 @@ Polygon2d expandPolygon(const Polygon2d & input_polygon, const double offset) boost::geometry::correct(expanded_polygon); return expanded_polygon; } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils diff --git a/common/autoware_universe_utils/src/geometry/geometry.cpp b/common/autoware_universe_utils/src/geometry/geometry.cpp index e6a491671595a..1f4fd318e227b 100644 --- a/common/autoware_universe_utils/src/geometry/geometry.cpp +++ b/common/autoware_universe_utils/src/geometry/geometry.cpp @@ -32,7 +32,7 @@ void fromMsg(const geometry_msgs::msg::PoseStamped & msg, tf2::Stamped().x(point32.x).y(point32.y).z(point32.z); - const auto transformed_point = autoware_universe_utils::transformPoint(point, pose); + const auto transformed_point = autoware::universe_utils::transformPoint(point, pose); return geometry_msgs::build() .x(transformed_point.x) .y(transformed_point.y) @@ -383,4 +383,4 @@ std::optional intersect( return intersect_point; } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils diff --git a/common/autoware_universe_utils/src/geometry/pose_deviation.cpp b/common/autoware_universe_utils/src/geometry/pose_deviation.cpp index 5c81519510c8e..77849e73f5dfd 100644 --- a/common/autoware_universe_utils/src/geometry/pose_deviation.cpp +++ b/common/autoware_universe_utils/src/geometry/pose_deviation.cpp @@ -28,7 +28,7 @@ #include #endif -namespace autoware_universe_utils +namespace autoware::universe_utils { double calcLateralDeviation( @@ -82,4 +82,4 @@ PoseDeviation calcPoseDeviation( return deviation; } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils diff --git a/common/autoware_universe_utils/src/math/sin_table.cpp b/common/autoware_universe_utils/src/math/sin_table.cpp index bc0a5d7b09024..ce021869176ee 100644 --- a/common/autoware_universe_utils/src/math/sin_table.cpp +++ b/common/autoware_universe_utils/src/math/sin_table.cpp @@ -14,7 +14,7 @@ #include "autoware/universe_utils/math/sin_table.hpp" -namespace autoware_universe_utils +namespace autoware::universe_utils { const float g_sin_table[sin_table_size] = { @@ -8212,4 +8212,4 @@ const float g_sin_table[sin_table_size] = { 0.9999999816164293f, 0.9999999896592414f, 0.9999999954041073f, 0.9999999988510269f, 1.0000000000000000f}; -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils diff --git a/common/autoware_universe_utils/src/math/trigonometry.cpp b/common/autoware_universe_utils/src/math/trigonometry.cpp index 40a993343b1de..586b9075ba6d5 100644 --- a/common/autoware_universe_utils/src/math/trigonometry.cpp +++ b/common/autoware_universe_utils/src/math/trigonometry.cpp @@ -19,12 +19,12 @@ #include -namespace autoware_universe_utils +namespace autoware::universe_utils { float sin(float radian) { - float degree = radian * (180.f / static_cast(autoware_universe_utils::pi)) * + float degree = radian * (180.f / static_cast(autoware::universe_utils::pi)) * (discrete_arcs_num_360 / 360.f); size_t idx = (static_cast(std::round(degree)) % discrete_arcs_num_360 + discrete_arcs_num_360) % @@ -46,13 +46,13 @@ float sin(float radian) float cos(float radian) { - return sin(radian + static_cast(autoware_universe_utils::pi) / 2.f); + return sin(radian + static_cast(autoware::universe_utils::pi) / 2.f); } std::pair sin_and_cos(float radian) { constexpr float tmp = - (180.f / static_cast(autoware_universe_utils::pi)) * (discrete_arcs_num_360 / 360.f); + (180.f / static_cast(autoware::universe_utils::pi)) * (discrete_arcs_num_360 / 360.f); const float degree = radian * tmp; size_t idx = (static_cast(std::round(degree)) % discrete_arcs_num_360 + discrete_arcs_num_360) % @@ -72,4 +72,4 @@ std::pair sin_and_cos(float radian) } } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils diff --git a/common/autoware_universe_utils/src/ros/logger_level_configure.cpp b/common/autoware_universe_utils/src/ros/logger_level_configure.cpp index 77e8d9bf16d7f..d517b81b93224 100644 --- a/common/autoware_universe_utils/src/ros/logger_level_configure.cpp +++ b/common/autoware_universe_utils/src/ros/logger_level_configure.cpp @@ -16,7 +16,7 @@ #include -namespace autoware_universe_utils +namespace autoware::universe_utils { LoggerLevelConfigure::LoggerLevelConfigure(rclcpp::Node * node) : ros_logger_(node->get_logger()) { @@ -58,4 +58,4 @@ void LoggerLevelConfigure::onLoggerConfigService( return; } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils diff --git a/common/autoware_universe_utils/src/ros/marker_helper.cpp b/common/autoware_universe_utils/src/ros/marker_helper.cpp index d4f97af2ef90f..507be41dea7bb 100644 --- a/common/autoware_universe_utils/src/ros/marker_helper.cpp +++ b/common/autoware_universe_utils/src/ros/marker_helper.cpp @@ -14,7 +14,7 @@ #include "autoware/universe_utils/ros/marker_helper.hpp" -namespace autoware_universe_utils +namespace autoware::universe_utils { visualization_msgs::msg::Marker createDefaultMarker( @@ -68,4 +68,4 @@ void appendMarkerArray( } } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils diff --git a/common/autoware_universe_utils/src/system/backtrace.cpp b/common/autoware_universe_utils/src/system/backtrace.cpp index f4c4312ce44fb..7af91bdcc60dc 100644 --- a/common/autoware_universe_utils/src/system/backtrace.cpp +++ b/common/autoware_universe_utils/src/system/backtrace.cpp @@ -23,7 +23,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { void print_backtrace() @@ -49,4 +49,4 @@ void print_backtrace() free(symbol_list); } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils diff --git a/common/autoware_universe_utils/test/src/geometry/test_boost_geometry.cpp b/common/autoware_universe_utils/test/src/geometry/test_boost_geometry.cpp index 764bb388fc74a..7c688e1982838 100644 --- a/common/autoware_universe_utils/test/src/geometry/test_boost_geometry.cpp +++ b/common/autoware_universe_utils/test/src/geometry/test_boost_geometry.cpp @@ -20,8 +20,8 @@ namespace bg = boost::geometry; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Point3d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Point3d; TEST(boost_geometry, boost_geometry_distance) { @@ -54,7 +54,7 @@ TEST(boost_geometry, to_2d) TEST(boost_geometry, toMsg) { - using autoware_universe_utils::toMsg; + using autoware::universe_utils::toMsg; { const Point3d p(1.0, 2.0, 3.0); @@ -68,7 +68,7 @@ TEST(boost_geometry, toMsg) TEST(boost_geometry, fromMsg) { - using autoware_universe_utils::fromMsg; + using autoware::universe_utils::fromMsg; geometry_msgs::msg::Point p_msg; p_msg.x = 1.0; diff --git a/common/autoware_universe_utils/test/src/geometry/test_boost_polygon_utils.cpp b/common/autoware_universe_utils/test/src/geometry/test_boost_polygon_utils.cpp index ed576ba0dceaf..4b75e8130a253 100644 --- a/common/autoware_universe_utils/test/src/geometry/test_boost_polygon_utils.cpp +++ b/common/autoware_universe_utils/test/src/geometry/test_boost_polygon_utils.cpp @@ -19,7 +19,7 @@ #include -using autoware_universe_utils::Polygon2d; +using autoware::universe_utils::Polygon2d; namespace { @@ -39,7 +39,7 @@ geometry_msgs::msg::Pose createPose(const double x, const double y, const double p.position.x = x; p.position.y = y; p.position.z = 0.0; - p.orientation = autoware_universe_utils::createQuaternionFromYaw(yaw); + p.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); return p; } @@ -47,7 +47,7 @@ geometry_msgs::msg::Pose createPose(const double x, const double y, const double TEST(boost_geometry, boost_isClockwise) { - using autoware_universe_utils::isClockwise; + using autoware::universe_utils::isClockwise; // empty Polygon2d empty_polygon; @@ -72,8 +72,8 @@ TEST(boost_geometry, boost_isClockwise) TEST(boost_geometry, boost_inverseClockwise) { - using autoware_universe_utils::inverseClockwise; - using autoware_universe_utils::isClockwise; + using autoware::universe_utils::inverseClockwise; + using autoware::universe_utils::isClockwise; // empty Polygon2d empty_polygon; @@ -100,7 +100,7 @@ TEST(boost_geometry, boost_inverseClockwise) TEST(boost_geometry, boost_rotatePolygon) { constexpr double epsilon = 1e-6; - using autoware_universe_utils::rotatePolygon; + using autoware::universe_utils::rotatePolygon; // empty geometry_msgs::msg::Polygon empty_polygon; @@ -130,7 +130,7 @@ TEST(boost_geometry, boost_rotatePolygon) TEST(boost_geometry, boost_toPolygon2d) { - using autoware_universe_utils::toPolygon2d; + using autoware::universe_utils::toPolygon2d; { // bounding box const double x = 1.0; @@ -206,7 +206,7 @@ TEST(boost_geometry, boost_toPolygon2d) TEST(boost_geometry, boost_toFootprint) { - using autoware_universe_utils::toFootprint; + using autoware::universe_utils::toFootprint; // from base link { @@ -234,7 +234,7 @@ TEST(boost_geometry, boost_toFootprint) TEST(boost_geometry, boost_getArea) { - using autoware_universe_utils::getArea; + using autoware::universe_utils::getArea; { // bounding box const double x = 1.0; @@ -290,7 +290,7 @@ TEST(boost_geometry, boost_getArea) TEST(boost_geometry, boost_expandPolygon) { - using autoware_universe_utils::expandPolygon; + using autoware::universe_utils::expandPolygon; { // box with a certain offset Polygon2d box_poly{{{-1.0, -1.0}, {-1.0, 1.0}, {1.0, 1.0}, {1.0, -1.0}, {-1.0, -1.0}}}; diff --git a/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp b/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp index 37e43c0ce08dd..194cd7d503d12 100644 --- a/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp +++ b/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp @@ -25,7 +25,7 @@ constexpr double epsilon = 1e-6; TEST(geometry, getPoint) { - using autoware_universe_utils::getPoint; + using autoware::universe_utils::getPoint; const double x_ans = 1.0; const double y_ans = 2.0; @@ -114,7 +114,7 @@ TEST(geometry, getPoint) TEST(geometry, getPose) { - using autoware_universe_utils::getPose; + using autoware::universe_utils::getPose; const double x_ans = 1.0; const double y_ans = 2.0; @@ -203,7 +203,7 @@ TEST(geometry, getPose) TEST(geometry, getLongitudinalVelocity) { - using autoware_universe_utils::getLongitudinalVelocity; + using autoware::universe_utils::getLongitudinalVelocity; const double velocity = 1.0; @@ -222,7 +222,7 @@ TEST(geometry, getLongitudinalVelocity) TEST(geometry, setPose) { - using autoware_universe_utils::setPose; + using autoware::universe_utils::setPose; const double x_ans = 1.0; const double y_ans = 2.0; @@ -292,9 +292,9 @@ TEST(geometry, setPose) TEST(geometry, setOrientation) { - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::setOrientation; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::setOrientation; geometry_msgs::msg::Pose p; const auto orientation = createQuaternionFromRPY(deg2rad(30), deg2rad(30), deg2rad(30)); @@ -308,7 +308,7 @@ TEST(geometry, setOrientation) TEST(geometry, setLongitudinalVelocity) { - using autoware_universe_utils::setLongitudinalVelocity; + using autoware::universe_utils::setLongitudinalVelocity; const double velocity = 1.0; @@ -327,7 +327,7 @@ TEST(geometry, setLongitudinalVelocity) TEST(geometry, createPoint) { - using autoware_universe_utils::createPoint; + using autoware::universe_utils::createPoint; const geometry_msgs::msg::Point p_out = createPoint(1.0, 2.0, 3.0); EXPECT_DOUBLE_EQ(p_out.x, 1.0); @@ -337,7 +337,7 @@ TEST(geometry, createPoint) TEST(geometry, createQuaternion) { - using autoware_universe_utils::createQuaternion; + using autoware::universe_utils::createQuaternion; // (0.18257419, 0.36514837, 0.54772256, 0.73029674) is normalized quaternion of (1, 2, 3, 4) const geometry_msgs::msg::Quaternion q_out = @@ -350,7 +350,7 @@ TEST(geometry, createQuaternion) TEST(geometry, createTranslation) { - using autoware_universe_utils::createTranslation; + using autoware::universe_utils::createTranslation; const geometry_msgs::msg::Vector3 v_out = createTranslation(1.0, 2.0, 3.0); EXPECT_DOUBLE_EQ(v_out.x, 1.0); @@ -360,8 +360,8 @@ TEST(geometry, createTranslation) TEST(geometry, createQuaternionFromRPY) { - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; { const auto q_out = createQuaternionFromRPY(0, 0, 0); @@ -390,8 +390,8 @@ TEST(geometry, createQuaternionFromRPY) TEST(geometry, createQuaternionFromYaw) { - using autoware_universe_utils::createQuaternionFromYaw; - using autoware_universe_utils::deg2rad; + using autoware::universe_utils::createQuaternionFromYaw; + using autoware::universe_utils::deg2rad; { const auto q_out = createQuaternionFromYaw(0); @@ -420,9 +420,9 @@ TEST(geometry, createQuaternionFromYaw) TEST(geometry, calcElevationAngle) { - using autoware_universe_utils::calcElevationAngle; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::deg2rad; + using autoware::universe_utils::calcElevationAngle; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::deg2rad; { const auto p1 = createPoint(1.0, 1.0, 1.0); @@ -468,9 +468,9 @@ TEST(geometry, calcElevationAngle) TEST(geometry, calcAzimuthAngle) { - using autoware_universe_utils::calcAzimuthAngle; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::deg2rad; + using autoware::universe_utils::calcAzimuthAngle; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::deg2rad; { const auto p1 = createPoint(0.0, 0.0, 9.0); @@ -521,7 +521,7 @@ TEST(geometry, calcAzimuthAngle) TEST(geometry, calcDistance2d) { - using autoware_universe_utils::calcDistance2d; + using autoware::universe_utils::calcDistance2d; geometry_msgs::msg::Point point; point.x = 1.0; @@ -538,7 +538,7 @@ TEST(geometry, calcDistance2d) TEST(geometry, calcSquaredDistance2d) { - using autoware_universe_utils::calcSquaredDistance2d; + using autoware::universe_utils::calcSquaredDistance2d; geometry_msgs::msg::Point point; point.x = 1.0; @@ -555,7 +555,7 @@ TEST(geometry, calcSquaredDistance2d) TEST(geometry, calcDistance3d) { - using autoware_universe_utils::calcDistance3d; + using autoware::universe_utils::calcDistance3d; geometry_msgs::msg::Point point; point.x = 1.0; @@ -572,9 +572,9 @@ TEST(geometry, calcDistance3d) TEST(geometry, getRPY) { - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::getRPY; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::getRPY; { const double ans_roll = deg2rad(5); @@ -610,9 +610,9 @@ TEST(geometry, getRPY) TEST(geometry, getRPY_wrapper) { - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::getRPY; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::getRPY; { const double ans_roll = deg2rad(45); @@ -652,9 +652,9 @@ TEST(geometry, getRPY_wrapper) TEST(geometry, transform2pose) { - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::transform2pose; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::transform2pose; { geometry_msgs::msg::Transform transform; @@ -703,9 +703,9 @@ TEST(geometry, transform2pose) TEST(geometry, pose2transform) { - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::pose2transform; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::pose2transform; { geometry_msgs::msg::Pose pose; @@ -756,9 +756,9 @@ TEST(geometry, pose2transform) TEST(geometry, point2tfVector) { - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::point2tfVector; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::point2tfVector; // Point { @@ -823,11 +823,11 @@ TEST(geometry, point2tfVector) TEST(geometry, transformPoint) { - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::Point2d; - using autoware_universe_utils::Point3d; - using autoware_universe_utils::transformPoint; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::Point2d; + using autoware::universe_utils::Point3d; + using autoware::universe_utils::transformPoint; { const Point2d p(1.0, 2.0); @@ -916,9 +916,9 @@ TEST(geometry, transformPoint) TEST(geometry, transformPose) { - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::transformPose; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::transformPose; geometry_msgs::msg::Pose pose; pose.position.x = 2.0; @@ -967,9 +967,9 @@ TEST(geometry, transformPose) TEST(geometry, inverseTransformPose) { - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::inverseTransformPose; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::inverseTransformPose; geometry_msgs::msg::Pose pose; pose.position.x = 2.0; @@ -1018,10 +1018,10 @@ TEST(geometry, inverseTransformPose) TEST(geometry, inverseTransformPoint) { - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::inverseTransformPoint; - using autoware_universe_utils::inverseTransformPose; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::inverseTransformPoint; + using autoware::universe_utils::inverseTransformPose; geometry_msgs::msg::Pose pose_transform; pose_transform.position.x = 1.0; @@ -1050,10 +1050,10 @@ TEST(geometry, inverseTransformPoint) TEST(geometry, transformVector) { - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::MultiPoint3d; - using autoware_universe_utils::transformVector; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::MultiPoint3d; + using autoware::universe_utils::transformVector; { const MultiPoint3d ps{{1.0, 2.0, 3.0}, {2.0, 3.0, 4.0}}; @@ -1078,51 +1078,51 @@ TEST(geometry, transformVector) TEST(geometry, calcCurvature) { - using autoware_universe_utils::calcCurvature; + using autoware::universe_utils::calcCurvature; // Straight Line { - geometry_msgs::msg::Point p1 = autoware_universe_utils::createPoint(0.0, 0.0, 0.0); - geometry_msgs::msg::Point p2 = autoware_universe_utils::createPoint(1.0, 0.0, 0.0); - geometry_msgs::msg::Point p3 = autoware_universe_utils::createPoint(2.0, 0.0, 0.0); + geometry_msgs::msg::Point p1 = autoware::universe_utils::createPoint(0.0, 0.0, 0.0); + geometry_msgs::msg::Point p2 = autoware::universe_utils::createPoint(1.0, 0.0, 0.0); + geometry_msgs::msg::Point p3 = autoware::universe_utils::createPoint(2.0, 0.0, 0.0); EXPECT_DOUBLE_EQ(calcCurvature(p1, p2, p3), 0.0); } // Clockwise Curved Road with a 1[m] radius { - geometry_msgs::msg::Point p1 = autoware_universe_utils::createPoint(0.0, 0.0, 0.0); - geometry_msgs::msg::Point p2 = autoware_universe_utils::createPoint(1.0, 1.0, 0.0); - geometry_msgs::msg::Point p3 = autoware_universe_utils::createPoint(2.0, 0.0, 0.0); + geometry_msgs::msg::Point p1 = autoware::universe_utils::createPoint(0.0, 0.0, 0.0); + geometry_msgs::msg::Point p2 = autoware::universe_utils::createPoint(1.0, 1.0, 0.0); + geometry_msgs::msg::Point p3 = autoware::universe_utils::createPoint(2.0, 0.0, 0.0); EXPECT_DOUBLE_EQ(calcCurvature(p1, p2, p3), -1.0); } // Clockwise Curved Road with a 5[m] radius { - geometry_msgs::msg::Point p1 = autoware_universe_utils::createPoint(0.0, 0.0, 0.0); - geometry_msgs::msg::Point p2 = autoware_universe_utils::createPoint(5.0, 5.0, 0.0); - geometry_msgs::msg::Point p3 = autoware_universe_utils::createPoint(10.0, 0.0, 0.0); + geometry_msgs::msg::Point p1 = autoware::universe_utils::createPoint(0.0, 0.0, 0.0); + geometry_msgs::msg::Point p2 = autoware::universe_utils::createPoint(5.0, 5.0, 0.0); + geometry_msgs::msg::Point p3 = autoware::universe_utils::createPoint(10.0, 0.0, 0.0); EXPECT_DOUBLE_EQ(calcCurvature(p1, p2, p3), -0.2); } // Counter-Clockwise Curved Road with a 1[m] radius { - geometry_msgs::msg::Point p1 = autoware_universe_utils::createPoint(0.0, 0.0, 0.0); - geometry_msgs::msg::Point p2 = autoware_universe_utils::createPoint(-1.0, 1.0, 0.0); - geometry_msgs::msg::Point p3 = autoware_universe_utils::createPoint(-2.0, 0.0, 0.0); + geometry_msgs::msg::Point p1 = autoware::universe_utils::createPoint(0.0, 0.0, 0.0); + geometry_msgs::msg::Point p2 = autoware::universe_utils::createPoint(-1.0, 1.0, 0.0); + geometry_msgs::msg::Point p3 = autoware::universe_utils::createPoint(-2.0, 0.0, 0.0); EXPECT_DOUBLE_EQ(calcCurvature(p1, p2, p3), 1.0); } // Counter-Clockwise Curved Road with a 5[m] radius { - geometry_msgs::msg::Point p1 = autoware_universe_utils::createPoint(0.0, 0.0, 0.0); - geometry_msgs::msg::Point p2 = autoware_universe_utils::createPoint(-5.0, 5.0, 0.0); - geometry_msgs::msg::Point p3 = autoware_universe_utils::createPoint(-10.0, 0.0, 0.0); + geometry_msgs::msg::Point p1 = autoware::universe_utils::createPoint(0.0, 0.0, 0.0); + geometry_msgs::msg::Point p2 = autoware::universe_utils::createPoint(-5.0, 5.0, 0.0); + geometry_msgs::msg::Point p3 = autoware::universe_utils::createPoint(-10.0, 0.0, 0.0); EXPECT_DOUBLE_EQ(calcCurvature(p1, p2, p3), 0.2); } // Give same points { - geometry_msgs::msg::Point p1 = autoware_universe_utils::createPoint(0.0, 0.0, 0.0); - geometry_msgs::msg::Point p2 = autoware_universe_utils::createPoint(1.0, 0.0, 0.0); + geometry_msgs::msg::Point p1 = autoware::universe_utils::createPoint(0.0, 0.0, 0.0); + geometry_msgs::msg::Point p2 = autoware::universe_utils::createPoint(1.0, 0.0, 0.0); ASSERT_ANY_THROW(calcCurvature(p1, p1, p1)); ASSERT_ANY_THROW(calcCurvature(p1, p1, p2)); ASSERT_ANY_THROW(calcCurvature(p1, p2, p1)); @@ -1132,11 +1132,11 @@ TEST(geometry, calcCurvature) TEST(geometry, calcOffsetPose) { - using autoware_universe_utils::calcOffsetPose; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::createQuaternion; - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; + using autoware::universe_utils::calcOffsetPose; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::createQuaternion; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; // Only translation { @@ -1224,12 +1224,12 @@ TEST(geometry, calcOffsetPose) TEST(geometry, isDrivingForward) { - using autoware_universe_utils::calcInterpolatedPoint; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::createQuaternion; - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; - using autoware_universe_utils::isDrivingForward; + using autoware::universe_utils::calcInterpolatedPoint; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::createQuaternion; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; + using autoware::universe_utils::isDrivingForward; const double epsilon = 1e-3; @@ -1286,8 +1286,8 @@ TEST(geometry, isDrivingForward) TEST(geometry, calcInterpolatedPoint) { - using autoware_universe_utils::calcInterpolatedPoint; - using autoware_universe_utils::createPoint; + using autoware::universe_utils::calcInterpolatedPoint; + using autoware::universe_utils::createPoint; { const auto src_point = createPoint(0.0, 0.0, 0.0); @@ -1343,11 +1343,11 @@ TEST(geometry, calcInterpolatedPoint) TEST(geometry, calcInterpolatedPose) { - using autoware_universe_utils::calcInterpolatedPose; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::createQuaternion; - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; + using autoware::universe_utils::calcInterpolatedPose; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::createQuaternion; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; const double epsilon = 1e-3; // Position Interpolation @@ -1527,11 +1527,11 @@ TEST(geometry, calcInterpolatedPose) TEST(geometry, calcInterpolatedPose_with_Spherical_Interpolation) { - using autoware_universe_utils::calcInterpolatedPose; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::createQuaternion; - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; + using autoware::universe_utils::calcInterpolatedPose; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::createQuaternion; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; const double epsilon = 1e-3; // Position Interpolation @@ -1675,7 +1675,7 @@ TEST(geometry, calcInterpolatedPose_with_Spherical_Interpolation) TEST(geometry, getTwist) { - using autoware_universe_utils::createVector3; + using autoware::universe_utils::createVector3; geometry_msgs::msg::Vector3 velocity = createVector3(1.0, 2.0, 3.0); geometry_msgs::msg::Vector3 angular = createVector3(0.1, 0.2, 0.3); @@ -1691,7 +1691,7 @@ TEST(geometry, getTwist) // getTwist { - auto t_out = autoware_universe_utils::createTwist(velocity, angular); + auto t_out = autoware::universe_utils::createTwist(velocity, angular); EXPECT_DOUBLE_EQ(t_out.linear.x, twist.linear.x); EXPECT_DOUBLE_EQ(t_out.linear.y, twist.linear.y); EXPECT_DOUBLE_EQ(t_out.linear.z, twist.linear.z); @@ -1703,32 +1703,32 @@ TEST(geometry, getTwist) TEST(geometry, getTwistNorm) { - using autoware_universe_utils::createVector3; + using autoware::universe_utils::createVector3; geometry_msgs::msg::TwistWithCovariance twist_with_covariance; twist_with_covariance.twist = geometry_msgs::build() .linear(createVector3(3.0, 4.0, 0.0)) .angular(createVector3(0.1, 0.2, 0.3)); - EXPECT_NEAR(autoware_universe_utils::calcNorm(twist_with_covariance.twist.linear), 5.0, epsilon); + EXPECT_NEAR(autoware::universe_utils::calcNorm(twist_with_covariance.twist.linear), 5.0, epsilon); } TEST(geometry, isTwistCovarianceValid) { - using autoware_universe_utils::createVector3; + using autoware::universe_utils::createVector3; geometry_msgs::msg::TwistWithCovariance twist_with_covariance; twist_with_covariance.twist = geometry_msgs::build() .linear(createVector3(1.0, 2.0, 3.0)) .angular(createVector3(0.1, 0.2, 0.3)); - EXPECT_EQ(autoware_universe_utils::isTwistCovarianceValid(twist_with_covariance), false); + EXPECT_EQ(autoware::universe_utils::isTwistCovarianceValid(twist_with_covariance), false); twist_with_covariance.covariance.at(0) = 1.0; - EXPECT_EQ(autoware_universe_utils::isTwistCovarianceValid(twist_with_covariance), true); + EXPECT_EQ(autoware::universe_utils::isTwistCovarianceValid(twist_with_covariance), true); } TEST(geometry, intersect) { - using autoware_universe_utils::createPoint; - using autoware_universe_utils::intersect; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::intersect; { // Normally crossing const auto p1 = createPoint(0.0, -1.0, 0.0); diff --git a/common/autoware_universe_utils/test/src/geometry/test_path_with_lane_id_geometry.cpp b/common/autoware_universe_utils/test/src/geometry/test_path_with_lane_id_geometry.cpp index 058149af2c192..4ed1c5497c6ae 100644 --- a/common/autoware_universe_utils/test/src/geometry/test_path_with_lane_id_geometry.cpp +++ b/common/autoware_universe_utils/test/src/geometry/test_path_with_lane_id_geometry.cpp @@ -18,7 +18,7 @@ TEST(geometry, getPoint_PathWithLaneId) { - using autoware_universe_utils::getPoint; + using autoware::universe_utils::getPoint; const double x_ans = 1.0; const double y_ans = 2.0; @@ -36,7 +36,7 @@ TEST(geometry, getPoint_PathWithLaneId) TEST(geometry, getPose_PathWithLaneId) { - using autoware_universe_utils::getPose; + using autoware::universe_utils::getPose; const double x_ans = 1.0; const double y_ans = 2.0; @@ -66,7 +66,7 @@ TEST(geometry, getPose_PathWithLaneId) TEST(geometry, getLongitudinalVelocity_PathWithLaneId) { - using autoware_universe_utils::getLongitudinalVelocity; + using autoware::universe_utils::getLongitudinalVelocity; const double velocity = 1.0; @@ -77,7 +77,7 @@ TEST(geometry, getLongitudinalVelocity_PathWithLaneId) TEST(geometry, setPose_PathWithLaneId) { - using autoware_universe_utils::setPose; + using autoware::universe_utils::setPose; const double x_ans = 1.0; const double y_ans = 2.0; @@ -109,7 +109,7 @@ TEST(geometry, setPose_PathWithLaneId) TEST(geometry, setLongitudinalVelocity_PathWithLaneId) { - using autoware_universe_utils::setLongitudinalVelocity; + using autoware::universe_utils::setLongitudinalVelocity; const double velocity = 1.0; diff --git a/common/autoware_universe_utils/test/src/geometry/test_pose_deviation.cpp b/common/autoware_universe_utils/test/src/geometry/test_pose_deviation.cpp index 0808223bb9ea2..c9a5c2cec4fac 100644 --- a/common/autoware_universe_utils/test/src/geometry/test_pose_deviation.cpp +++ b/common/autoware_universe_utils/test/src/geometry/test_pose_deviation.cpp @@ -20,9 +20,9 @@ TEST(geometry, pose_deviation) { - using autoware_universe_utils::calcPoseDeviation; - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::deg2rad; + using autoware::universe_utils::calcPoseDeviation; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::deg2rad; geometry_msgs::msg::Pose pose1; pose1.position.x = 1.0; diff --git a/common/autoware_universe_utils/test/src/math/test_constants.cpp b/common/autoware_universe_utils/test/src/math/test_constants.cpp index 47e76efd66f6e..6c449834157b0 100644 --- a/common/autoware_universe_utils/test/src/math/test_constants.cpp +++ b/common/autoware_universe_utils/test/src/math/test_constants.cpp @@ -18,14 +18,14 @@ TEST(constants, pi) { - using autoware_universe_utils::pi; + using autoware::universe_utils::pi; EXPECT_DOUBLE_EQ(pi, 3.14159265358979323846); } TEST(constants, gravity) { - using autoware_universe_utils::gravity; + using autoware::universe_utils::gravity; EXPECT_DOUBLE_EQ(gravity, 9.80665); } diff --git a/common/autoware_universe_utils/test/src/math/test_normalization.cpp b/common/autoware_universe_utils/test/src/math/test_normalization.cpp index 19b8a29019057..ae7f3cd7a7a4c 100644 --- a/common/autoware_universe_utils/test/src/math/test_normalization.cpp +++ b/common/autoware_universe_utils/test/src/math/test_normalization.cpp @@ -18,7 +18,7 @@ TEST(normalization, normalizeDegree) { - using autoware_universe_utils::normalizeDegree; + using autoware::universe_utils::normalizeDegree; // -180 <= deg < 180 { @@ -51,7 +51,7 @@ TEST(normalization, normalizeDegree) TEST(normalization, normalizeRadian) { - using autoware_universe_utils::normalizeRadian; + using autoware::universe_utils::normalizeRadian; // -M_PI <= deg < M_PI { diff --git a/common/autoware_universe_utils/test/src/math/test_range.cpp b/common/autoware_universe_utils/test/src/math/test_range.cpp index 400a6a4dd20c1..12be5b646957b 100644 --- a/common/autoware_universe_utils/test/src/math/test_range.cpp +++ b/common/autoware_universe_utils/test/src/math/test_range.cpp @@ -44,7 +44,7 @@ void expect_eq_vector(const std::vector & input, const std::vector & e TEST(arange_Test, arange_double) { - using autoware_universe_utils::arange; + using autoware::universe_utils::arange; // general cases { @@ -82,7 +82,7 @@ TEST(arange_Test, arange_double) TEST(arange_Test, arange_float) { - using autoware_universe_utils::arange; + using autoware::universe_utils::arange; // general cases { @@ -121,7 +121,7 @@ TEST(arange_Test, arange_float) TEST(arange_Test, arange_int) { - using autoware_universe_utils::arange; + using autoware::universe_utils::arange; // general cases { @@ -154,7 +154,7 @@ TEST(arange_Test, arange_int) TEST(test_linspace, linspace_double) { - using autoware_universe_utils::linspace; + using autoware::universe_utils::linspace; // general cases { @@ -182,7 +182,7 @@ TEST(test_linspace, linspace_double) TEST(test_linspace, linspace_float) { - using autoware_universe_utils::linspace; + using autoware::universe_utils::linspace; // general cases { @@ -211,7 +211,7 @@ TEST(test_linspace, linspace_float) TEST(test_linspace, linspace_int) { - using autoware_universe_utils::linspace; + using autoware::universe_utils::linspace; // general cases { diff --git a/common/autoware_universe_utils/test/src/math/test_trigonometry.cpp b/common/autoware_universe_utils/test/src/math/test_trigonometry.cpp index c4ba81a6b77ff..b55b27a34a6ac 100644 --- a/common/autoware_universe_utils/test/src/math/test_trigonometry.cpp +++ b/common/autoware_universe_utils/test/src/math/test_trigonometry.cpp @@ -21,31 +21,31 @@ TEST(trigonometry, sin) { - float x = 4.f * autoware_universe_utils::pi / 128.f; + float x = 4.f * autoware::universe_utils::pi / 128.f; for (int i = 0; i < 128; i++) { EXPECT_TRUE( std::abs( std::sin(x * static_cast(i)) - - autoware_universe_utils::sin(x * static_cast(i))) < 10e-5); + autoware::universe_utils::sin(x * static_cast(i))) < 10e-5); } } TEST(trigonometry, cos) { - float x = 4.f * autoware_universe_utils::pi / 128.f; + float x = 4.f * autoware::universe_utils::pi / 128.f; for (int i = 0; i < 128; i++) { EXPECT_TRUE( std::abs( std::cos(x * static_cast(i)) - - autoware_universe_utils::cos(x * static_cast(i))) < 10e-5); + autoware::universe_utils::cos(x * static_cast(i))) < 10e-5); } } TEST(trigonometry, sin_and_cos) { - float x = 4.f * autoware_universe_utils::pi / 128.f; + float x = 4.f * autoware::universe_utils::pi / 128.f; for (int i = 0; i < 128; i++) { - const auto sin_and_cos = autoware_universe_utils::sin_and_cos(x * static_cast(i)); + const auto sin_and_cos = autoware::universe_utils::sin_and_cos(x * static_cast(i)); EXPECT_TRUE(std::abs(std::sin(x * static_cast(i)) - sin_and_cos.first) < 10e-7); EXPECT_TRUE(std::abs(std::cos(x * static_cast(i)) - sin_and_cos.second) < 10e-7); } diff --git a/common/autoware_universe_utils/test/src/math/test_unit_conversion.cpp b/common/autoware_universe_utils/test/src/math/test_unit_conversion.cpp index e00b85f9e24f2..605b0e7d3c5a6 100644 --- a/common/autoware_universe_utils/test/src/math/test_unit_conversion.cpp +++ b/common/autoware_universe_utils/test/src/math/test_unit_conversion.cpp @@ -16,11 +16,11 @@ #include -using autoware_universe_utils::pi; +using autoware::universe_utils::pi; TEST(unit_conversion, deg2rad) { - using autoware_universe_utils::deg2rad; + using autoware::universe_utils::deg2rad; EXPECT_DOUBLE_EQ(deg2rad(-720), -4 * pi); EXPECT_DOUBLE_EQ(deg2rad(0), 0); @@ -33,7 +33,7 @@ TEST(unit_conversion, deg2rad) TEST(unit_conversion, rad2deg) { - using autoware_universe_utils::rad2deg; + using autoware::universe_utils::rad2deg; EXPECT_DOUBLE_EQ(rad2deg(-4 * pi), -720); EXPECT_DOUBLE_EQ(rad2deg(0), 0); @@ -46,7 +46,7 @@ TEST(unit_conversion, rad2deg) TEST(unit_conversion, kmph2mps) { - using autoware_universe_utils::kmph2mps; + using autoware::universe_utils::kmph2mps; EXPECT_DOUBLE_EQ(kmph2mps(0), 0); EXPECT_DOUBLE_EQ(kmph2mps(36), 10); @@ -56,7 +56,7 @@ TEST(unit_conversion, kmph2mps) TEST(unit_conversion, mps2kmph) { - using autoware_universe_utils::mps2kmph; + using autoware::universe_utils::mps2kmph; EXPECT_DOUBLE_EQ(mps2kmph(0), 0); EXPECT_DOUBLE_EQ(mps2kmph(10), 36); diff --git a/common/autoware_universe_utils/test/src/ros/test_published_time_publisher.cpp b/common/autoware_universe_utils/test/src/ros/test_published_time_publisher.cpp index 238a97e901611..f9c0bd45c4fb4 100644 --- a/common/autoware_universe_utils/test/src/ros/test_published_time_publisher.cpp +++ b/common/autoware_universe_utils/test/src/ros/test_published_time_publisher.cpp @@ -24,7 +24,7 @@ class PublishedTimePublisherWithSubscriptionTest : public ::testing::Test { protected: std::shared_ptr node_{nullptr}; - std::shared_ptr published_time_publisher_ptr_{ + std::shared_ptr published_time_publisher_ptr_{ nullptr}; std::shared_ptr> first_test_publisher_ptr_{nullptr}; @@ -70,7 +70,7 @@ class PublishedTimePublisherWithSubscriptionTest : public ::testing::Test // Create a PublishedTimePublisher published_time_publisher_ptr_ = - std::make_shared(node_.get()); + std::make_shared(node_.get()); // Create the first subscriber first_test_subscriber_ptr_ = @@ -98,7 +98,7 @@ class PublishedTimePublisherWithoutSubscriptionTest : public ::testing::Test { protected: std::shared_ptr node_{nullptr}; - std::shared_ptr published_time_publisher_ptr_{ + std::shared_ptr published_time_publisher_ptr_{ nullptr}; std::shared_ptr> first_test_publisher_ptr_{nullptr}; @@ -135,7 +135,7 @@ class PublishedTimePublisherWithoutSubscriptionTest : public ::testing::Test // Create a PublishedTimePublisher published_time_publisher_ptr_ = - std::make_shared(node_.get()); + std::make_shared(node_.get()); rclcpp::spin_some(node_); } diff --git a/common/autoware_universe_utils/test/src/system/test_stop_watch.cpp b/common/autoware_universe_utils/test/src/system/test_stop_watch.cpp index 6bf9857595f98..55e10e9bd2ffd 100644 --- a/common/autoware_universe_utils/test/src/system/test_stop_watch.cpp +++ b/common/autoware_universe_utils/test/src/system/test_stop_watch.cpp @@ -21,7 +21,7 @@ TEST(system, StopWatch_sec) { - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::StopWatch; StopWatch stop_watch; @@ -50,7 +50,7 @@ TEST(system, StopWatch_sec) TEST(system, StopWatch_msec) { - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::StopWatch; StopWatch stop_watch; diff --git a/common/autoware_universe_utils/test/src/transform/test_transform.cpp b/common/autoware_universe_utils/test/src/transform/test_transform.cpp index e659ec0f2a749..2935600c9f446 100644 --- a/common/autoware_universe_utils/test/src/transform/test_transform.cpp +++ b/common/autoware_universe_utils/test/src/transform/test_transform.cpp @@ -31,7 +31,7 @@ TEST(system, transform_point_cloud) 42301.179688, -0.001429, -0.017543, 0.999845, -3.157415, 0.000000, 0.000000, 0.000000, 1.000000; pcl::PointCloud cloud_transformed; - autoware_universe_utils::transformPointCloud(cloud, cloud_transformed, transform); + autoware::universe_utils::transformPointCloud(cloud, cloud_transformed, transform); pcl::PointXYZI pt1_gt(89603.187500, 42270.878906, -13.056946, 4); @@ -53,8 +53,8 @@ TEST(system, empty_point_cloud) pcl::PointCloud cloud_transformed; EXPECT_NO_THROW( - autoware_universe_utils::transformPointCloud(cloud, cloud_transformed, transform)); + autoware::universe_utils::transformPointCloud(cloud, cloud_transformed, transform)); EXPECT_NO_FATAL_FAILURE( - autoware_universe_utils::transformPointCloud(cloud, cloud_transformed, transform)); + autoware::universe_utils::transformPointCloud(cloud, cloud_transformed, transform)); EXPECT_EQ(cloud_transformed.size(), 0ul); } diff --git a/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator.hpp b/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator.hpp index 370765a81c743..69c8840b39421 100644 --- a/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator.hpp +++ b/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator.hpp @@ -25,7 +25,7 @@ namespace goal_distance_calculator { -using autoware_universe_utils::PoseDeviation; +using autoware::universe_utils::PoseDeviation; struct Param { diff --git a/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator_node.hpp b/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator_node.hpp index c1154884e8340..037841a505017 100644 --- a/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator_node.hpp +++ b/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator_node.hpp @@ -45,7 +45,7 @@ class GoalDistanceCalculatorNode : public rclcpp::Node private: // Subscriber rclcpp::Subscription::SharedPtr sub_initial_pose_; - autoware_universe_utils::SelfPoseListener self_pose_listener_; + autoware::universe_utils::SelfPoseListener self_pose_listener_; rclcpp::Subscription::SharedPtr sub_route_; // Data Buffer @@ -56,7 +56,7 @@ class GoalDistanceCalculatorNode : public rclcpp::Node void onRoute(const autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr & msg); // Publisher - autoware_universe_utils::DebugPublisher debug_publisher_; + autoware::universe_utils::DebugPublisher debug_publisher_; // Timer rclcpp::TimerBase::SharedPtr timer_; diff --git a/common/goal_distance_calculator/src/goal_distance_calculator.cpp b/common/goal_distance_calculator/src/goal_distance_calculator.cpp index 5491fe96c0848..a577d43675224 100755 --- a/common/goal_distance_calculator/src/goal_distance_calculator.cpp +++ b/common/goal_distance_calculator/src/goal_distance_calculator.cpp @@ -21,7 +21,7 @@ Output GoalDistanceCalculator::update(const Input & input) Output output{}; output.goal_deviation = - autoware_universe_utils::calcPoseDeviation(input.route->goal_pose, input.current_pose->pose); + autoware::universe_utils::calcPoseDeviation(input.route->goal_pose, input.current_pose->pose); return output; } diff --git a/common/goal_distance_calculator/src/goal_distance_calculator_node.cpp b/common/goal_distance_calculator/src/goal_distance_calculator_node.cpp index 7f4346dac63dc..8e4e4c90bc470 100644 --- a/common/goal_distance_calculator/src/goal_distance_calculator_node.cpp +++ b/common/goal_distance_calculator/src/goal_distance_calculator_node.cpp @@ -107,7 +107,7 @@ void GoalDistanceCalculatorNode::onTimer() output_ = goal_distance_calculator_->update(input_); { - using autoware_universe_utils::rad2deg; + using autoware::universe_utils::rad2deg; const auto & deviation = output_.goal_deviation; debug_publisher_.publish( diff --git a/common/interpolation/include/interpolation/spline_interpolation_points_2d.hpp b/common/interpolation/include/interpolation/spline_interpolation_points_2d.hpp index b2fc5c6c36e54..398d841c54710 100644 --- a/common/interpolation/include/interpolation/spline_interpolation_points_2d.hpp +++ b/common/interpolation/include/interpolation/spline_interpolation_points_2d.hpp @@ -53,7 +53,7 @@ class SplineInterpolationPoints2d { std::vector points_inner; for (const auto & p : points) { - points_inner.push_back(autoware_universe_utils::getPoint(p)); + points_inner.push_back(autoware::universe_utils::getPoint(p)); } calcSplineCoefficientsInner(points_inner); } diff --git a/common/interpolation/src/spline_interpolation_points_2d.cpp b/common/interpolation/src/spline_interpolation_points_2d.cpp index 11bc407e4c511..4d6d1639f2ac7 100644 --- a/common/interpolation/src/spline_interpolation_points_2d.cpp +++ b/common/interpolation/src/spline_interpolation_points_2d.cpp @@ -118,7 +118,7 @@ geometry_msgs::msg::Pose SplineInterpolationPoints2d::getSplineInterpolatedPose( geometry_msgs::msg::Pose pose; pose.position = getSplineInterpolatedPoint(idx, s); pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(getSplineInterpolatedYaw(idx, s)); + autoware::universe_utils::createQuaternionFromYaw(getSplineInterpolatedYaw(idx, s)); return pose; } diff --git a/common/interpolation/test/src/test_spline_interpolation_points_2d.cpp b/common/interpolation/test/src/test_spline_interpolation_points_2d.cpp index 2d582e2318600..4013832220cd8 100644 --- a/common/interpolation/test/src/test_spline_interpolation_points_2d.cpp +++ b/common/interpolation/test/src/test_spline_interpolation_points_2d.cpp @@ -25,7 +25,7 @@ constexpr double epsilon = 1e-6; TEST(spline_interpolation, splineYawFromPoints) { - using autoware_universe_utils::createPoint; + using autoware::universe_utils::createPoint; { // straight std::vector points; @@ -96,7 +96,7 @@ TEST(spline_interpolation, splineYawFromPoints) TEST(spline_interpolation, SplineInterpolationPoints2d) { - using autoware_universe_utils::createPoint; + using autoware::universe_utils::createPoint; // curve std::vector points; @@ -199,8 +199,8 @@ TEST(spline_interpolation, SplineInterpolationPoints2d) TEST(spline_interpolation, SplineInterpolationPoints2dPolymorphism) { + using autoware::universe_utils::createPoint; using autoware_planning_msgs::msg::TrajectoryPoint; - using autoware_universe_utils::createPoint; std::vector points; points.push_back(createPoint(-2.0, -10.0, 0.0)); diff --git a/common/object_recognition_utils/include/object_recognition_utils/matching.hpp b/common/object_recognition_utils/include/object_recognition_utils/matching.hpp index eb8a7b81dbfb9..ae50227df1166 100644 --- a/common/object_recognition_utils/include/object_recognition_utils/matching.hpp +++ b/common/object_recognition_utils/include/object_recognition_utils/matching.hpp @@ -28,7 +28,7 @@ namespace object_recognition_utils { -using autoware_universe_utils::Polygon2d; +using autoware::universe_utils::Polygon2d; // minimum area to avoid division by zero static const double MIN_AREA = 1e-6; @@ -37,7 +37,7 @@ inline double getConvexShapeArea(const Polygon2d & source_polygon, const Polygon boost::geometry::model::multi_polygon union_polygons; boost::geometry::union_(source_polygon, target_polygon, union_polygons); - autoware_universe_utils::Polygon2d hull; + autoware::universe_utils::Polygon2d hull; boost::geometry::convex_hull(union_polygons, hull); return boost::geometry::area(hull); } @@ -67,9 +67,9 @@ inline double getUnionArea(const Polygon2d & source_polygon, const Polygon2d & t template double get2dIoU(const T1 source_object, const T2 target_object, const double min_union_area = 0.01) { - const auto source_polygon = autoware_universe_utils::toPolygon2d(source_object); + const auto source_polygon = autoware::universe_utils::toPolygon2d(source_object); if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0; - const auto target_polygon = autoware_universe_utils::toPolygon2d(target_object); + const auto target_polygon = autoware::universe_utils::toPolygon2d(target_object); if (boost::geometry::area(target_polygon) < MIN_AREA) return 0.0; const double intersection_area = getIntersectionArea(source_polygon, target_polygon); @@ -84,9 +84,9 @@ double get2dIoU(const T1 source_object, const T2 target_object, const double min template double get2dGeneralizedIoU(const T1 & source_object, const T2 & target_object) { - const auto source_polygon = autoware_universe_utils::toPolygon2d(source_object); + const auto source_polygon = autoware::universe_utils::toPolygon2d(source_object); if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0; - const auto target_polygon = autoware_universe_utils::toPolygon2d(target_object); + const auto target_polygon = autoware::universe_utils::toPolygon2d(target_object); if (boost::geometry::area(target_polygon) < MIN_AREA) return 0.0; const double intersection_area = getIntersectionArea(source_polygon, target_polygon); @@ -100,10 +100,10 @@ double get2dGeneralizedIoU(const T1 & source_object, const T2 & target_object) template double get2dPrecision(const T1 source_object, const T2 target_object) { - const auto source_polygon = autoware_universe_utils::toPolygon2d(source_object); + const auto source_polygon = autoware::universe_utils::toPolygon2d(source_object); const double source_area = boost::geometry::area(source_polygon); if (source_area < MIN_AREA) return 0.0; - const auto target_polygon = autoware_universe_utils::toPolygon2d(target_object); + const auto target_polygon = autoware::universe_utils::toPolygon2d(target_object); if (boost::geometry::area(target_polygon) < MIN_AREA) return 0.0; const double intersection_area = getIntersectionArea(source_polygon, target_polygon); @@ -115,9 +115,9 @@ double get2dPrecision(const T1 source_object, const T2 target_object) template double get2dRecall(const T1 source_object, const T2 target_object) { - const auto source_polygon = autoware_universe_utils::toPolygon2d(source_object); + const auto source_polygon = autoware::universe_utils::toPolygon2d(source_object); if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0; - const auto target_polygon = autoware_universe_utils::toPolygon2d(target_object); + const auto target_polygon = autoware::universe_utils::toPolygon2d(target_object); const double target_area = boost::geometry::area(target_polygon); if (target_area < MIN_AREA) return 0.0; diff --git a/common/object_recognition_utils/src/predicted_path_utils.cpp b/common/object_recognition_utils/src/predicted_path_utils.cpp index e748d1165bef7..e26c9e6a7e1ea 100644 --- a/common/object_recognition_utils/src/predicted_path_utils.cpp +++ b/common/object_recognition_utils/src/predicted_path_utils.cpp @@ -38,7 +38,7 @@ boost::optional calcInterpolatedPose( if (relative_time - epsilon < time_step * path_idx) { const double offset = relative_time - time_step * (path_idx - 1); const double ratio = std::clamp(offset / time_step, 0.0, 1.0); - return autoware_universe_utils::calcInterpolatedPose(prev_pt, pt, ratio, false); + return autoware::universe_utils::calcInterpolatedPose(prev_pt, pt, ratio, false); } } @@ -90,7 +90,7 @@ autoware_perception_msgs::msg::PredictedPath resamplePredictedPath( // Set Position for (size_t i = 0; i < resampled_size; ++i) { - const auto p = autoware_universe_utils::createPoint( + const auto p = autoware::universe_utils::createPoint( interpolated_x.at(i), interpolated_y.at(i), interpolated_z.at(i)); resampled_path.path.at(i).position = p; resampled_path.path.at(i).orientation = interpolated_quat.at(i); diff --git a/common/object_recognition_utils/test/src/test_matching.cpp b/common/object_recognition_utils/test/src/test_matching.cpp index 1481492e40e71..6005ac8d1efbc 100644 --- a/common/object_recognition_utils/test/src/test_matching.cpp +++ b/common/object_recognition_utils/test/src/test_matching.cpp @@ -19,8 +19,8 @@ #include -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Point3d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Point3d; constexpr double epsilon = 1e-06; @@ -30,7 +30,7 @@ geometry_msgs::msg::Pose createPose(const double x, const double y, const double { geometry_msgs::msg::Pose p; p.position = geometry_msgs::build().x(x).y(y).z(0.0); - p.orientation = autoware_universe_utils::createQuaternionFromYaw(yaw); + p.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); return p; } } // namespace diff --git a/common/object_recognition_utils/test/src/test_predicted_path_utils.cpp b/common/object_recognition_utils/test/src/test_predicted_path_utils.cpp index 94136c9c4da9c..305a1173acf12 100644 --- a/common/object_recognition_utils/test/src/test_predicted_path_utils.cpp +++ b/common/object_recognition_utils/test/src/test_predicted_path_utils.cpp @@ -18,17 +18,17 @@ #include -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Point3d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Point3d; constexpr double epsilon = 1e-06; namespace { +using autoware::universe_utils::createPoint; +using autoware::universe_utils::createQuaternionFromRPY; +using autoware::universe_utils::transformPoint; using autoware_perception_msgs::msg::PredictedPath; -using autoware_universe_utils::createPoint; -using autoware_universe_utils::createQuaternionFromRPY; -using autoware_universe_utils::transformPoint; geometry_msgs::msg::Pose createPose( double x, double y, double z, double roll, double pitch, double yaw) @@ -62,9 +62,9 @@ PredictedPath createTestPredictedPath( TEST(predicted_path_utils, testCalcInterpolatedPose) { - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::createQuaternionFromYaw; - using autoware_universe_utils::deg2rad; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::createQuaternionFromYaw; + using autoware::universe_utils::deg2rad; using object_recognition_utils::calcInterpolatedPose; const auto path = createTestPredictedPath(100, 0.1, 1.0); @@ -128,9 +128,9 @@ TEST(predicted_path_utils, testCalcInterpolatedPose) TEST(predicted_path_utils, resamplePredictedPath_by_vector) { - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::createQuaternionFromYaw; - using autoware_universe_utils::deg2rad; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::createQuaternionFromYaw; + using autoware::universe_utils::deg2rad; using object_recognition_utils::resamplePredictedPath; const auto path = createTestPredictedPath(10, 1.0, 1.0); @@ -205,9 +205,9 @@ TEST(predicted_path_utils, resamplePredictedPath_by_vector) TEST(predicted_path_utils, resamplePredictedPath_by_sampling_time) { - using autoware_universe_utils::createQuaternionFromRPY; - using autoware_universe_utils::createQuaternionFromYaw; - using autoware_universe_utils::deg2rad; + using autoware::universe_utils::createQuaternionFromRPY; + using autoware::universe_utils::createQuaternionFromYaw; + using autoware::universe_utils::deg2rad; using object_recognition_utils::resamplePredictedPath; const auto path = createTestPredictedPath(10, 1.0, 1.0); diff --git a/common/path_distance_calculator/src/path_distance_calculator.cpp b/common/path_distance_calculator/src/path_distance_calculator.cpp index b503d926df53b..47dd8258de5bb 100644 --- a/common/path_distance_calculator/src/path_distance_calculator.cpp +++ b/common/path_distance_calculator/src/path_distance_calculator.cpp @@ -48,7 +48,7 @@ PathDistanceCalculator::PathDistanceCalculator(const rclcpp::NodeOptions & optio return; } - const double distance = autoware_motion_utils::calcSignedArcLength( + const double distance = autoware::motion_utils::calcSignedArcLength( path->points, pose->pose.position, path->points.size() - 1); tier4_debug_msgs::msg::Float64Stamped msg; diff --git a/common/path_distance_calculator/src/path_distance_calculator.hpp b/common/path_distance_calculator/src/path_distance_calculator.hpp index ceef07ca268c4..8e8fbf8d6a019 100644 --- a/common/path_distance_calculator/src/path_distance_calculator.hpp +++ b/common/path_distance_calculator/src/path_distance_calculator.hpp @@ -30,7 +30,7 @@ class PathDistanceCalculator : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_path_; rclcpp::Publisher::SharedPtr pub_dist_; rclcpp::TimerBase::SharedPtr timer_; - autoware_universe_utils::SelfPoseListener self_pose_listener_; + autoware::universe_utils::SelfPoseListener self_pose_listener_; autoware_planning_msgs::msg::Path::SharedPtr path_; }; diff --git a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp index 6d7109fbfa061..ef5663f024c8d 100644 --- a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp +++ b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp @@ -61,22 +61,22 @@ void visualizeBound( const auto [normal_vector_angle, adaptive_width] = [&]() -> std::pair { if (i == 0) { return std::make_pair( - autoware_universe_utils::calcAzimuthAngle(bound.at(i), bound.at(i + 1)) + M_PI_2, width); + autoware::universe_utils::calcAzimuthAngle(bound.at(i), bound.at(i + 1)) + M_PI_2, width); } if (i == bound.size() - 1) { return std::make_pair( - autoware_universe_utils::calcAzimuthAngle(bound.at(i - 1), bound.at(i)) + M_PI_2, width); + autoware::universe_utils::calcAzimuthAngle(bound.at(i - 1), bound.at(i)) + M_PI_2, width); } const auto & prev_p = bound.at(i - 1); const auto & curr_p = bound.at(i); const auto & next_p = bound.at(i + 1); - const float curr_to_prev_angle = autoware_universe_utils::calcAzimuthAngle(curr_p, prev_p); - const float curr_to_next_angle = autoware_universe_utils::calcAzimuthAngle(curr_p, next_p); + const float curr_to_prev_angle = autoware::universe_utils::calcAzimuthAngle(curr_p, prev_p); + const float curr_to_next_angle = autoware::universe_utils::calcAzimuthAngle(curr_p, next_p); const float normal_vector_angle = (curr_to_prev_angle + curr_to_next_angle) / 2.0; const float diff_angle = - autoware_universe_utils::normalizeRadian(normal_vector_angle - curr_to_next_angle); + autoware::universe_utils::normalizeRadian(normal_vector_angle - curr_to_next_angle); if (diff_angle == 0.0) { return std::make_pair(normal_vector_angle, width); } diff --git a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp index 8edae446c46b0..25f890799465d 100644 --- a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp +++ b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp @@ -86,8 +86,8 @@ bool validateFloats(const typename T::ConstSharedPtr & msg_ptr) { for (auto && path_point : msg_ptr->points) { if ( - !rviz_common::validateFloats(autoware_universe_utils::getPose(path_point)) && - !rviz_common::validateFloats(autoware_universe_utils::getLongitudinalVelocity(path_point))) { + !rviz_common::validateFloats(autoware::universe_utils::getPose(path_point)) && + !rviz_common::validateFloats(autoware::universe_utils::getLongitudinalVelocity(path_point))) { return false; } } @@ -358,8 +358,8 @@ class AutowarePathBaseDisplay : public rviz_common::MessageFilterDisplay for (size_t point_idx = 0; point_idx < msg_ptr->points.size(); point_idx++) { const auto & path_point = msg_ptr->points.at(point_idx); - const auto & pose = autoware_universe_utils::getPose(path_point); - const auto & velocity = autoware_universe_utils::getLongitudinalVelocity(path_point); + const auto & pose = autoware::universe_utils::getPose(path_point); + const auto & velocity = autoware::universe_utils::getLongitudinalVelocity(path_point); // path if (property_path_view_.getBool()) { @@ -454,9 +454,9 @@ class AutowarePathBaseDisplay : public rviz_common::MessageFilterDisplay (point_idx != msg_ptr->points.size() - 1) ? point_idx + 1 : point_idx; const auto & prev_path_pos = - autoware_universe_utils::getPose(msg_ptr->points.at(prev_idx)).position; + autoware::universe_utils::getPose(msg_ptr->points.at(prev_idx)).position; const auto & next_path_pos = - autoware_universe_utils::getPose(msg_ptr->points.at(next_idx)).position; + autoware::universe_utils::getPose(msg_ptr->points.at(next_idx)).position; Ogre::Vector3 position; position.x = pose.position.x; @@ -467,7 +467,7 @@ class AutowarePathBaseDisplay : public rviz_common::MessageFilterDisplay rviz_rendering::MovableText * text = slope_texts_.at(point_idx); const double slope = - autoware_universe_utils::calcElevationAngle(prev_path_pos, next_path_pos); + autoware::universe_utils::calcElevationAngle(prev_path_pos, next_path_pos); std::stringstream ss; ss << std::fixed << std::setprecision(2) << slope; @@ -511,7 +511,7 @@ class AutowarePathBaseDisplay : public rviz_common::MessageFilterDisplay for (size_t p_idx = 0; p_idx < msg_ptr->points.size(); p_idx++) { const auto & point = msg_ptr->points.at(p_idx); - const auto & pose = autoware_universe_utils::getPose(point); + const auto & pose = autoware::universe_utils::getPose(point); // footprint if (property_footprint_view_.getBool()) { Ogre::ColourValue color; diff --git a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/utils.hpp b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/utils.hpp index c82f5b5df3885..7e99af8b9efb6 100644 --- a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/utils.hpp +++ b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/utils.hpp @@ -29,7 +29,7 @@ bool isDrivingForward(const T points_with_twist, size_t target_idx) // 1. check velocity const double target_velocity = - autoware_universe_utils::getLongitudinalVelocity(points_with_twist.at(target_idx)); + autoware::universe_utils::getLongitudinalVelocity(points_with_twist.at(target_idx)); if (epsilon < target_velocity) { return true; } else if (target_velocity < -epsilon) { @@ -46,13 +46,13 @@ bool isDrivingForward(const T points_with_twist, size_t target_idx) const size_t first_idx = is_last_point ? target_idx - 1 : target_idx; const size_t second_idx = is_last_point ? target_idx : target_idx + 1; - const auto first_pose = autoware_universe_utils::getPose(points_with_twist.at(first_idx)); - const auto second_pose = autoware_universe_utils::getPose(points_with_twist.at(second_idx)); + const auto first_pose = autoware::universe_utils::getPose(points_with_twist.at(first_idx)); + const auto second_pose = autoware::universe_utils::getPose(points_with_twist.at(second_idx)); const double first_traj_yaw = tf2::getYaw(first_pose.orientation); const double driving_direction_yaw = - autoware_universe_utils::calcAzimuthAngle(first_pose.position, second_pose.position); + autoware::universe_utils::calcAzimuthAngle(first_pose.position, second_pose.position); if ( - std::abs(autoware_universe_utils::normalizeRadian(first_traj_yaw - driving_direction_yaw)) < + std::abs(autoware::universe_utils::normalizeRadian(first_traj_yaw - driving_direction_yaw)) < M_PI_2) { return true; } diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.cpp b/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.cpp index a77e5769f7ff8..1d884d01065fa 100644 --- a/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.cpp +++ b/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.cpp @@ -231,14 +231,14 @@ void AccelerationMeterDisplay::updateVisualization() inner_arc_.y0 = line_width_ / 2.0; inner_arc_.x1 = w; inner_arc_.y1 = h; - inner_arc_.start_angle = autoware_universe_utils::rad2deg(min_range_theta - M_PI); - inner_arc_.end_angle = autoware_universe_utils::rad2deg(max_range_theta - min_range_theta); + inner_arc_.start_angle = autoware::universe_utils::rad2deg(min_range_theta - M_PI); + inner_arc_.end_angle = autoware::universe_utils::rad2deg(max_range_theta - min_range_theta); outer_arc_.x0 = w * 3 / 8; outer_arc_.y0 = h * 3 / 8; outer_arc_.x1 = w / 4; outer_arc_.y1 = h / 4; - outer_arc_.start_angle = autoware_universe_utils::rad2deg(min_range_theta - M_PI); - outer_arc_.end_angle = autoware_universe_utils::rad2deg(max_range_theta - min_range_theta); + outer_arc_.start_angle = autoware::universe_utils::rad2deg(min_range_theta - M_PI); + outer_arc_.end_angle = autoware::universe_utils::rad2deg(max_range_theta - min_range_theta); } } // namespace rviz_plugins diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.hpp b/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.hpp index 86adc54306262..03fef97f536a5 100644 --- a/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.hpp +++ b/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.hpp @@ -67,8 +67,8 @@ private Q_SLOTS: private: static constexpr float meter_min_acceleration_ = -10.0f; static constexpr float meter_max_acceleration_ = 10.0f; - static constexpr float meter_min_angle_ = autoware_universe_utils::deg2rad(40.f); - static constexpr float meter_max_angle_ = autoware_universe_utils::deg2rad(320.f); + static constexpr float meter_min_angle_ = autoware::universe_utils::deg2rad(40.f); + static constexpr float meter_max_angle_ = autoware::universe_utils::deg2rad(320.f); static constexpr int line_width_ = 2; static constexpr int hand_width_ = 4; struct Line // for drawLine diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp b/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp index 90bd6e91f9e4a..8f7348c87be3c 100644 --- a/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp +++ b/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp @@ -212,14 +212,14 @@ void ConsoleMeterDisplay::updateVisualization() inner_arc_.y0 = line_width_ / 2.0; inner_arc_.x1 = w; inner_arc_.y1 = h; - inner_arc_.start_angle = autoware_universe_utils::rad2deg(min_range_theta - M_PI); - inner_arc_.end_angle = autoware_universe_utils::rad2deg(max_range_theta - min_range_theta); + inner_arc_.start_angle = autoware::universe_utils::rad2deg(min_range_theta - M_PI); + inner_arc_.end_angle = autoware::universe_utils::rad2deg(max_range_theta - min_range_theta); outer_arc_.x0 = w * 3 / 8; outer_arc_.y0 = h * 3 / 8; outer_arc_.x1 = w / 4; outer_arc_.y1 = h / 4; - outer_arc_.start_angle = autoware_universe_utils::rad2deg(min_range_theta - M_PI); - outer_arc_.end_angle = autoware_universe_utils::rad2deg(max_range_theta - min_range_theta); + outer_arc_.start_angle = autoware::universe_utils::rad2deg(min_range_theta - M_PI); + outer_arc_.end_angle = autoware::universe_utils::rad2deg(max_range_theta - min_range_theta); } } // namespace rviz_plugins diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.hpp b/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.hpp index fc54208ddb8c8..98cf8bbae4228 100644 --- a/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.hpp +++ b/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.hpp @@ -63,10 +63,10 @@ private Q_SLOTS: // QImage hud_; private: - static constexpr float meter_min_velocity_ = autoware_universe_utils::kmph2mps(0.f); - static constexpr float meter_max_velocity_ = autoware_universe_utils::kmph2mps(60.f); - static constexpr float meter_min_angle_ = autoware_universe_utils::deg2rad(40.f); - static constexpr float meter_max_angle_ = autoware_universe_utils::deg2rad(320.f); + static constexpr float meter_min_velocity_ = autoware::universe_utils::kmph2mps(0.f); + static constexpr float meter_max_velocity_ = autoware::universe_utils::kmph2mps(60.f); + static constexpr float meter_min_angle_ = autoware::universe_utils::deg2rad(40.f); + static constexpr float meter_max_angle_ = autoware::universe_utils::deg2rad(320.f); static constexpr int line_width_ = 2; static constexpr int hand_width_ = 4; struct Line // for drawLine diff --git a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp index 2a1156adb41a0..8c454d5d583b6 100644 --- a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp +++ b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp @@ -60,9 +60,9 @@ using nav_msgs::msg::Odometry; using sensor_msgs::msg::Imu; using sensor_msgs::msg::PointCloud2; using PointCloud = pcl::PointCloud; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; using autoware::vehicle_info_utils::VehicleInfo; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; using diagnostic_updater::DiagnosticStatusWrapper; using diagnostic_updater::Updater; using visualization_msgs::msg::Marker; @@ -208,7 +208,7 @@ class CollisionDataKeeper const double p_vel = p_dist / p_dt; const auto nearest_idx = - autoware_motion_utils::findNearestIndex(path, nearest_collision_point); + autoware::motion_utils::findNearestIndex(path, nearest_collision_point); const auto & nearest_path_pose = path.at(nearest_idx); // When the ego moves backwards, the direction of movement axis is reversed const auto & traj_yaw = (current_ego_speed > 0.0) @@ -247,16 +247,16 @@ class AEB : public rclcpp::Node explicit AEB(const rclcpp::NodeOptions & node_options); // subscriber - autoware_universe_utils::InterProcessPollingSubscriber sub_point_cloud_{ - this, "~/input/pointcloud", autoware_universe_utils::SingleDepthSensorQoS()}; - autoware_universe_utils::InterProcessPollingSubscriber sub_velocity_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_point_cloud_{ + this, "~/input/pointcloud", autoware::universe_utils::SingleDepthSensorQoS()}; + autoware::universe_utils::InterProcessPollingSubscriber sub_velocity_{ this, "~/input/velocity"}; - autoware_universe_utils::InterProcessPollingSubscriber sub_imu_{this, "~/input/imu"}; - autoware_universe_utils::InterProcessPollingSubscriber sub_predicted_traj_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_imu_{this, "~/input/imu"}; + autoware::universe_utils::InterProcessPollingSubscriber sub_predicted_traj_{ this, "~/input/predicted_trajectory"}; - autoware_universe_utils::InterProcessPollingSubscriber predicted_objects_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber predicted_objects_sub_{ this, "~/input/objects"}; - autoware_universe_utils::InterProcessPollingSubscriber sub_autoware_state_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_autoware_state_{ this, "/autoware/state"}; // publisher rclcpp::Publisher::SharedPtr pub_obstacle_pointcloud_; diff --git a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp index b046acd9153e9..64bedd2163912 100644 --- a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp +++ b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp @@ -37,10 +37,10 @@ namespace autoware::motion::control::autonomous_emergency_braking::utils { +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::TransformStamped; diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index e898ff4788da4..fca3341680997 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -75,33 +75,33 @@ Polygon2d createPolygon( appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(base_pose, longitudinal_offset, width, 0.0).position); + autoware::universe_utils::calcOffsetPose(base_pose, longitudinal_offset, width, 0.0).position); appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(base_pose, longitudinal_offset, -width, 0.0).position); + autoware::universe_utils::calcOffsetPose(base_pose, longitudinal_offset, -width, 0.0).position); appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(base_pose, -rear_overhang, -width, 0.0).position); + autoware::universe_utils::calcOffsetPose(base_pose, -rear_overhang, -width, 0.0).position); appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(base_pose, -rear_overhang, width, 0.0).position); + autoware::universe_utils::calcOffsetPose(base_pose, -rear_overhang, width, 0.0).position); appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(next_pose, longitudinal_offset, width, 0.0).position); + autoware::universe_utils::calcOffsetPose(next_pose, longitudinal_offset, width, 0.0).position); appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(next_pose, longitudinal_offset, -width, 0.0).position); + autoware::universe_utils::calcOffsetPose(next_pose, longitudinal_offset, -width, 0.0).position); appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(next_pose, -rear_overhang, -width, 0.0).position); + autoware::universe_utils::calcOffsetPose(next_pose, -rear_overhang, -width, 0.0).position); appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(next_pose, -rear_overhang, width, 0.0).position); + autoware::universe_utils::calcOffsetPose(next_pose, -rear_overhang, width, 0.0).position); - polygon = autoware_universe_utils::isClockwise(polygon) + polygon = autoware::universe_utils::isClockwise(polygon) ? polygon - : autoware_universe_utils::inverseClockwise(polygon); + : autoware::universe_utils::inverseClockwise(polygon); Polygon2d hull_polygon; bg::convex_hull(polygon, hull_polygon); @@ -175,7 +175,7 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) rcl_interfaces::msg::SetParametersResult AEB::onParameter( const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; updateParam(parameters, "publish_debug_pointcloud", publish_debug_pointcloud_); updateParam(parameters, "use_predicted_trajectory", use_predicted_trajectory_); updateParam(parameters, "use_imu_path", use_imu_path_); @@ -527,8 +527,8 @@ Path AEB::generateEgoPath(const double curr_v, const double curr_w) double curr_y = 0.0; double curr_yaw = 0.0; geometry_msgs::msg::Pose ini_pose; - ini_pose.position = autoware_universe_utils::createPoint(curr_x, curr_y, 0.0); - ini_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(curr_yaw); + ini_pose.position = autoware::universe_utils::createPoint(curr_x, curr_y, 0.0); + ini_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(curr_yaw); path.push_back(ini_pose); if (std::abs(curr_v) < 0.1) { @@ -544,23 +544,23 @@ Path AEB::generateEgoPath(const double curr_v, const double curr_w) curr_y = curr_y + curr_v * std::sin(curr_yaw) * dt; curr_yaw = curr_yaw + curr_w * dt; geometry_msgs::msg::Pose current_pose; - current_pose.position = autoware_universe_utils::createPoint(curr_x, curr_y, 0.0); - current_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(curr_yaw); - if (autoware_universe_utils::calcDistance2d(path.back(), current_pose) < 1e-3) { + current_pose.position = autoware::universe_utils::createPoint(curr_x, curr_y, 0.0); + current_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(curr_yaw); + if (autoware::universe_utils::calcDistance2d(path.back(), current_pose) < 1e-3) { continue; } path.push_back(current_pose); } // If path is shorter than minimum path length - while (autoware_motion_utils::calcArcLength(path) < min_generated_path_length_) { + while (autoware::motion_utils::calcArcLength(path) < min_generated_path_length_) { curr_x = curr_x + curr_v * std::cos(curr_yaw) * dt; curr_y = curr_y + curr_v * std::sin(curr_yaw) * dt; curr_yaw = curr_yaw + curr_w * dt; geometry_msgs::msg::Pose current_pose; - current_pose.position = autoware_universe_utils::createPoint(curr_x, curr_y, 0.0); - current_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(curr_yaw); - if (autoware_universe_utils::calcDistance2d(path.back(), current_pose) < 1e-3) { + current_pose.position = autoware::universe_utils::createPoint(curr_x, curr_y, 0.0); + current_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(curr_yaw); + if (autoware::universe_utils::calcDistance2d(path.back(), current_pose) < 1e-3) { continue; } path.push_back(current_pose); @@ -624,7 +624,7 @@ void AEB::createObjectDataUsingPredictedObjects( const auto current_p = [&]() { const auto & first_point_of_path = ego_path.front(); const auto & p = first_point_of_path.position; - return autoware_universe_utils::createPoint(p.x, p.y, p.z); + return autoware::universe_utils::createPoint(p.x, p.y, p.z); }(); auto get_object_tangent_velocity = @@ -634,7 +634,7 @@ void AEB::createObjectDataUsingPredictedObjects( predicted_object.kinematics.initial_twist_with_covariance.twist.linear.y); const auto obj_yaw = tf2::getYaw(obj_pose.orientation); - const auto obj_idx = autoware_motion_utils::findNearestIndex(ego_path, obj_pose.position); + const auto obj_idx = autoware::motion_utils::findNearestIndex(ego_path, obj_pose.position); const auto path_yaw = (current_ego_speed > 0.0) ? tf2::getYaw(ego_path.at(obj_idx).orientation) : tf2::getYaw(ego_path.at(obj_idx).orientation) + M_PI; @@ -670,9 +670,9 @@ void AEB::createObjectDataUsingPredictedObjects( bool collision_points_added{false}; for (const auto & collision_point : collision_points_bg) { const auto obj_position = - autoware_universe_utils::createPoint(collision_point.x(), collision_point.y(), 0.0); + autoware::universe_utils::createPoint(collision_point.x(), collision_point.y(), 0.0); const double obj_arc_length = - autoware_motion_utils::calcSignedArcLength(ego_path, current_p, obj_position); + autoware::motion_utils::calcSignedArcLength(ego_path, current_p, obj_position); if (std::isnan(obj_arc_length)) continue; // If the object is behind the ego, we need to use the backward long offset. The @@ -744,13 +744,13 @@ void AEB::createObjectDataUsingPointCloudClusters( const auto current_p = [&]() { const auto & first_point_of_path = ego_path.front(); const auto & p = first_point_of_path.position; - return autoware_universe_utils::createPoint(p.x, p.y, p.z); + return autoware::universe_utils::createPoint(p.x, p.y, p.z); }(); for (const auto & p : *points_belonging_to_cluster_hulls) { - const auto obj_position = autoware_universe_utils::createPoint(p.x, p.y, p.z); + const auto obj_position = autoware::universe_utils::createPoint(p.x, p.y, p.z); const double obj_arc_length = - autoware_motion_utils::calcSignedArcLength(ego_path, current_p, obj_position); + autoware::motion_utils::calcSignedArcLength(ego_path, current_p, obj_position); if (std::isnan(obj_arc_length)) continue; // If the object is behind the ego, we need to use the backward long offset. The distance should @@ -812,36 +812,38 @@ void AEB::addMarker( const double color_r, const double color_g, const double color_b, const double color_a, const std::string & ns, MarkerArray & debug_markers) { - auto path_marker = autoware_universe_utils::createDefaultMarker( + auto path_marker = autoware::universe_utils::createDefaultMarker( "base_link", current_time, ns + "_path", 0L, Marker::LINE_STRIP, - autoware_universe_utils::createMarkerScale(0.2, 0.2, 0.2), - autoware_universe_utils::createMarkerColor(color_r, color_g, color_b, color_a)); + autoware::universe_utils::createMarkerScale(0.2, 0.2, 0.2), + autoware::universe_utils::createMarkerColor(color_r, color_g, color_b, color_a)); path_marker.points.resize(path.size()); for (size_t i = 0; i < path.size(); ++i) { path_marker.points.at(i) = path.at(i).position; } debug_markers.markers.push_back(path_marker); - auto polygon_marker = autoware_universe_utils::createDefaultMarker( + auto polygon_marker = autoware::universe_utils::createDefaultMarker( "base_link", current_time, ns + "_polygon", 0, Marker::LINE_LIST, - autoware_universe_utils::createMarkerScale(0.03, 0.0, 0.0), - autoware_universe_utils::createMarkerColor(color_r, color_g, color_b, color_a)); + autoware::universe_utils::createMarkerScale(0.03, 0.0, 0.0), + autoware::universe_utils::createMarkerColor(color_r, color_g, color_b, color_a)); for (const auto & poly : polygons) { for (size_t dp_idx = 0; dp_idx < poly.outer().size(); ++dp_idx) { const auto & boost_cp = poly.outer().at(dp_idx); const auto & boost_np = poly.outer().at((dp_idx + 1) % poly.outer().size()); - const auto curr_point = autoware_universe_utils::createPoint(boost_cp.x(), boost_cp.y(), 0.0); - const auto next_point = autoware_universe_utils::createPoint(boost_np.x(), boost_np.y(), 0.0); + const auto curr_point = + autoware::universe_utils::createPoint(boost_cp.x(), boost_cp.y(), 0.0); + const auto next_point = + autoware::universe_utils::createPoint(boost_np.x(), boost_np.y(), 0.0); polygon_marker.points.push_back(curr_point); polygon_marker.points.push_back(next_point); } } debug_markers.markers.push_back(polygon_marker); - auto object_data_marker = autoware_universe_utils::createDefaultMarker( + auto object_data_marker = autoware::universe_utils::createDefaultMarker( "base_link", current_time, ns + "_objects", 0, Marker::SPHERE_LIST, - autoware_universe_utils::createMarkerScale(0.5, 0.5, 0.5), - autoware_universe_utils::createMarkerColor(color_r, color_g, color_b, color_a)); + autoware::universe_utils::createMarkerScale(0.5, 0.5, 0.5), + autoware::universe_utils::createMarkerColor(color_r, color_g, color_b, color_a)); for (const auto & e : objects) { object_data_marker.points.push_back(e.position); } @@ -850,11 +852,11 @@ void AEB::addMarker( // Visualize planner type text if (closest_object.has_value()) { const auto & obj = closest_object.value(); - const auto color = autoware_universe_utils::createMarkerColor(0.95, 0.95, 0.95, 0.999); - auto closest_object_velocity_marker_array = autoware_universe_utils::createDefaultMarker( + const auto color = autoware::universe_utils::createMarkerColor(0.95, 0.95, 0.95, 0.999); + auto closest_object_velocity_marker_array = autoware::universe_utils::createDefaultMarker( "base_link", obj.stamp, ns + "_closest_object_velocity", 0, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, - autoware_universe_utils::createMarkerScale(0.0, 0.0, 0.7), color); + autoware::universe_utils::createMarkerScale(0.0, 0.0, 0.7), color); closest_object_velocity_marker_array.pose.position = obj.position; const auto ego_velocity = current_velocity_ptr_->longitudinal_velocity; closest_object_velocity_marker_array.text = @@ -868,10 +870,10 @@ void AEB::addMarker( void AEB::addCollisionMarker(const ObjectData & data, MarkerArray & debug_markers) { - auto point_marker = autoware_universe_utils::createDefaultMarker( + auto point_marker = autoware::universe_utils::createDefaultMarker( "base_link", data.stamp, "collision_point", 0, Marker::SPHERE, - autoware_universe_utils::createMarkerScale(0.3, 0.3, 0.3), - autoware_universe_utils::createMarkerColor(1.0, 0.0, 0.0, 0.3)); + autoware::universe_utils::createMarkerScale(0.3, 0.3, 0.3), + autoware::universe_utils::createMarkerColor(1.0, 0.0, 0.0, 0.3)); point_marker.pose.position = data.position; debug_markers.markers.push_back(point_marker); } diff --git a/control/autoware_autonomous_emergency_braking/src/utils.cpp b/control/autoware_autonomous_emergency_braking/src/utils.cpp index 81f6afee31172..c284ee3c99dbb 100644 --- a/control/autoware_autonomous_emergency_braking/src/utils.cpp +++ b/control/autoware_autonomous_emergency_braking/src/utils.cpp @@ -16,10 +16,10 @@ namespace autoware::motion::control::autonomous_emergency_braking::utils { +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::TransformStamped; diff --git a/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp b/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp index 4434dc23ebf96..ecb46aee123e3 100644 --- a/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp +++ b/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp @@ -69,9 +69,9 @@ class ControlValidator : public rclcpp::Node void setStatus(DiagnosticStatusWrapper & stat, const bool & is_ok, const std::string & msg); rclcpp::Subscription::SharedPtr sub_predicted_traj_; - autoware_universe_utils::InterProcessPollingSubscriber sub_kinematics_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_kinematics_{ this, "~/input/kinematics"}; - autoware_universe_utils::InterProcessPollingSubscriber sub_reference_traj_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_reference_traj_{ this, "~/input/reference_trajectory"}; rclcpp::Publisher::SharedPtr pub_status_; rclcpp::Publisher::SharedPtr pub_markers_; diff --git a/control/autoware_control_validator/include/autoware/control_validator/utils.hpp b/control/autoware_control_validator/include/autoware/control_validator/utils.hpp index d64c718df3887..375ad557d02df 100644 --- a/control/autoware_control_validator/include/autoware/control_validator/utils.hpp +++ b/control/autoware_control_validator/include/autoware/control_validator/utils.hpp @@ -26,8 +26,8 @@ namespace autoware::control_validator { -using autoware_motion_utils::convertToTrajectory; -using autoware_motion_utils::convertToTrajectoryPointArray; +using autoware::motion_utils::convertToTrajectory; +using autoware::motion_utils::convertToTrajectoryPointArray; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; using geometry_msgs::msg::Pose; diff --git a/control/autoware_control_validator/src/debug_marker.cpp b/control/autoware_control_validator/src/debug_marker.cpp index 7fdd447f075df..d5d8644515ab1 100644 --- a/control/autoware_control_validator/src/debug_marker.cpp +++ b/control/autoware_control_validator/src/debug_marker.cpp @@ -48,7 +48,7 @@ void ControlValidatorDebugMarkerPublisher::pushPoseMarker( void ControlValidatorDebugMarkerPublisher::pushPoseMarker( const geometry_msgs::msg::Pose & pose, const std::string & ns, int id) { - using autoware_universe_utils::createMarkerColor; + using autoware::universe_utils::createMarkerColor; // append arrow marker std_msgs::msg::ColorRGBA color; @@ -64,9 +64,9 @@ void ControlValidatorDebugMarkerPublisher::pushPoseMarker( { color = createMarkerColor(0.0, 0.0, 1.0, 0.999); } - Marker marker = autoware_universe_utils::createDefaultMarker( + Marker marker = autoware::universe_utils::createDefaultMarker( "map", node_->get_clock()->now(), ns, getMarkerId(ns), Marker::ARROW, - autoware_universe_utils::createMarkerScale(0.2, 0.1, 0.3), color); + autoware::universe_utils::createMarkerScale(0.2, 0.1, 0.3), color); marker.lifetime = rclcpp::Duration::from_seconds(0.2); marker.pose = pose; @@ -76,10 +76,10 @@ void ControlValidatorDebugMarkerPublisher::pushPoseMarker( void ControlValidatorDebugMarkerPublisher::pushWarningMsg( const geometry_msgs::msg::Pose & pose, const std::string & msg) { - visualization_msgs::msg::Marker marker = autoware_universe_utils::createDefaultMarker( + visualization_msgs::msg::Marker marker = autoware::universe_utils::createDefaultMarker( "map", node_->get_clock()->now(), "warning_msg", 0, Marker::TEXT_VIEW_FACING, - autoware_universe_utils::createMarkerScale(0.0, 0.0, 1.0), - autoware_universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.999)); + autoware::universe_utils::createMarkerScale(0.0, 0.0, 1.0), + autoware::universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.999)); marker.lifetime = rclcpp::Duration::from_seconds(0.2); marker.pose = pose; marker.text = msg; @@ -90,8 +90,8 @@ void ControlValidatorDebugMarkerPublisher::pushVirtualWall(const geometry_msgs:: { const auto now = node_->get_clock()->now(); const auto stop_wall_marker = - autoware_motion_utils::createStopVirtualWallMarker(pose, "control_validator", now, 0); - autoware_universe_utils::appendMarkerArray(stop_wall_marker, &marker_array_virtual_wall_, now); + autoware::motion_utils::createStopVirtualWallMarker(pose, "control_validator", now, 0); + autoware::universe_utils::appendMarkerArray(stop_wall_marker, &marker_array_virtual_wall_, now); } void ControlValidatorDebugMarkerPublisher::publish() diff --git a/control/autoware_control_validator/src/utils.cpp b/control/autoware_control_validator/src/utils.cpp index e60c6ea723b4f..821d64c3af6e6 100644 --- a/control/autoware_control_validator/src/utils.cpp +++ b/control/autoware_control_validator/src/utils.cpp @@ -37,7 +37,7 @@ void insertPointInPredictedTrajectory( TrajectoryPoints & modified_trajectory, const Pose & reference_pose, const TrajectoryPoints & predicted_trajectory) { - const auto point_to_interpolate = autoware_motion_utils::calcInterpolatedPoint( + const auto point_to_interpolate = autoware::motion_utils::calcInterpolatedPoint( convertToTrajectory(predicted_trajectory), reference_pose); modified_trajectory.insert(modified_trajectory.begin(), point_to_interpolate); } @@ -59,7 +59,7 @@ bool removeFrontTrajectoryPoint( bool predicted_trajectory_point_removed = false; for (const auto & point : predicted_trajectory_points) { if ( - autoware_motion_utils::calcLongitudinalOffsetToSegment( + autoware::motion_utils::calcLongitudinalOffsetToSegment( trajectory_points, 0, point.pose.position) < 0.0) { modified_trajectory_points.erase(modified_trajectory_points.begin()); @@ -75,7 +75,7 @@ bool removeFrontTrajectoryPoint( Trajectory alignTrajectoryWithReferenceTrajectory( const Trajectory & trajectory, const Trajectory & predicted_trajectory) { - const auto last_seg_length = autoware_motion_utils::calcSignedArcLength( + const auto last_seg_length = autoware::motion_utils::calcSignedArcLength( trajectory.points, trajectory.points.size() - 2, trajectory.points.size() - 1); // If no overlapping between trajectory and predicted_trajectory, return empty trajectory @@ -85,9 +85,9 @@ Trajectory alignTrajectoryWithReferenceTrajectory( // predicted_trajectory: p1------------------pN // trajectory: t1------------------tN const bool & is_p_n_before_t1 = - autoware_motion_utils::calcLongitudinalOffsetToSegment( + autoware::motion_utils::calcLongitudinalOffsetToSegment( trajectory.points, 0, predicted_trajectory.points.back().pose.position) < 0.0; - const bool & is_p1_behind_t_n = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const bool & is_p1_behind_t_n = autoware::motion_utils::calcLongitudinalOffsetToSegment( trajectory.points, trajectory.points.size() - 2, predicted_trajectory.points.front().pose.position) - last_seg_length > @@ -149,11 +149,11 @@ double calcMaxLateralDistance( alignTrajectoryWithReferenceTrajectory(reference_trajectory, predicted_trajectory); double max_dist = 0; for (const auto & point : alined_predicted_trajectory.points) { - const auto p0 = autoware_universe_utils::getPoint(point); + const auto p0 = autoware::universe_utils::getPoint(point); // find nearest segment const size_t nearest_segment_idx = - autoware_motion_utils::findNearestSegmentIndex(reference_trajectory.points, p0); - const double temp_dist = std::abs(autoware_motion_utils::calcLateralOffset( + autoware::motion_utils::findNearestSegmentIndex(reference_trajectory.points, p0); + const double temp_dist = std::abs(autoware::motion_utils::calcLateralOffset( reference_trajectory.points, p0, nearest_segment_idx)); if (temp_dist > max_dist) { max_dist = temp_dist; diff --git a/control/autoware_joy_controller/include/autoware/joy_controller/joy_controller.hpp b/control/autoware_joy_controller/include/autoware/joy_controller/joy_controller.hpp index cea29ad887121..fd2d89f446dbb 100644 --- a/control/autoware_joy_controller/include/autoware/joy_controller/joy_controller.hpp +++ b/control/autoware_joy_controller/include/autoware/joy_controller/joy_controller.hpp @@ -70,9 +70,9 @@ class AutowareJoyControllerNode : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr callback_group_services_; // Subscriber - autoware_universe_utils::InterProcessPollingSubscriber sub_joy_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_joy_{ this, "input/joy"}; - autoware_universe_utils::InterProcessPollingSubscriber sub_odom_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_odom_{ this, "input/odometry"}; rclcpp::Time last_joy_received_time_; diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp index b5df59a45038c..b43a7d0d0369a 100644 --- a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp @@ -47,12 +47,12 @@ namespace autoware::lane_departure_checker { +using autoware::universe_utils::LinearRing2d; +using autoware::universe_utils::PoseDeviation; +using autoware::universe_utils::Segment2d; using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; -using autoware_universe_utils::LinearRing2d; -using autoware_universe_utils::PoseDeviation; -using autoware_universe_utils::Segment2d; using tier4_planning_msgs::msg::PathWithLaneId; using TrajectoryPoints = std::vector; typedef boost::geometry::index::rtree> SegmentRtree; @@ -122,7 +122,7 @@ class LaneDepartureChecker std::vector> getLaneletsFromPath( const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const; - std::optional getFusedLaneletPolygonForPath( + std::optional getFusedLaneletPolygonForPath( const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const; bool checkPathWillLeaveLane( diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp index 7f3fad0be4d28..e6421b2af84bb 100644 --- a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp @@ -67,15 +67,15 @@ class LaneDepartureCheckerNode : public rclcpp::Node private: // Subscriber - autoware_universe_utils::InterProcessPollingSubscriber sub_odom_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_odom_{ this, "~/input/odometry"}; - autoware_universe_utils::InterProcessPollingSubscriber sub_lanelet_map_bin_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_lanelet_map_bin_{ this, "~/input/lanelet_map_bin", rclcpp::QoS{1}.transient_local()}; - autoware_universe_utils::InterProcessPollingSubscriber sub_route_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_route_{ this, "~/input/route"}; - autoware_universe_utils::InterProcessPollingSubscriber sub_reference_trajectory_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_reference_trajectory_{ this, "~/input/reference_trajectory"}; - autoware_universe_utils::InterProcessPollingSubscriber sub_predicted_trajectory_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_predicted_trajectory_{ this, "~/input/predicted_trajectory"}; // Data Buffer @@ -99,8 +99,8 @@ class LaneDepartureCheckerNode : public rclcpp::Node void onPredictedTrajectory(const Trajectory::ConstSharedPtr msg); // Publisher - autoware_universe_utils::DebugPublisher debug_publisher_{this, "~/debug"}; - autoware_universe_utils::ProcessingTimePublisher processing_time_publisher_{this}; + autoware::universe_utils::DebugPublisher debug_publisher_{this, "~/debug"}; + autoware::universe_utils::ProcessingTimePublisher processing_time_publisher_{this}; // Timer rclcpp::TimerBase::SharedPtr timer_; diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp index 84de8441c5a40..132eba8dde0c9 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp @@ -30,12 +30,12 @@ #include #include -using autoware_motion_utils::calcArcLength; -using autoware_universe_utils::LinearRing2d; -using autoware_universe_utils::LineString2d; -using autoware_universe_utils::MultiPoint2d; -using autoware_universe_utils::MultiPolygon2d; -using autoware_universe_utils::Point2d; +using autoware::motion_utils::calcArcLength; +using autoware::universe_utils::LinearRing2d; +using autoware::universe_utils::LineString2d; +using autoware::universe_utils::MultiPoint2d; +using autoware::universe_utils::MultiPolygon2d; +using autoware::universe_utils::Point2d; namespace { @@ -102,7 +102,7 @@ Output LaneDepartureChecker::update(const Input & input) { Output output{}; - autoware_universe_utils::StopWatch stop_watch; + autoware::universe_utils::StopWatch stop_watch; output.trajectory_deviation = calcTrajectoryDeviation( *input.reference_trajectory, input.current_odom->pose.pose, param_.ego_nearest_dist_threshold, @@ -169,9 +169,9 @@ PoseDeviation LaneDepartureChecker::calcTrajectoryDeviation( const Trajectory & trajectory, const geometry_msgs::msg::Pose & pose, const double dist_threshold, const double yaw_threshold) { - const auto nearest_idx = autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + const auto nearest_idx = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( trajectory.points, pose, dist_threshold, yaw_threshold); - return autoware_universe_utils::calcPoseDeviation(trajectory.points.at(nearest_idx).pose, pose); + return autoware::universe_utils::calcPoseDeviation(trajectory.points.at(nearest_idx).pose, pose); } TrajectoryPoints LaneDepartureChecker::resampleTrajectory( @@ -183,8 +183,8 @@ TrajectoryPoints LaneDepartureChecker::resampleTrajectory( for (size_t i = 1; i < trajectory.points.size() - 1; ++i) { const auto & point = trajectory.points.at(i); - const auto p1 = autoware_universe_utils::fromMsg(resampled.back().pose.position); - const auto p2 = autoware_universe_utils::fromMsg(point.pose.position); + const auto p1 = autoware::universe_utils::fromMsg(resampled.back().pose.position); + const auto p2 = autoware::universe_utils::fromMsg(point.pose.position); if (boost::geometry::distance(p1.to_2d(), p2.to_2d()) > interval) { resampled.push_back(point); @@ -205,8 +205,8 @@ TrajectoryPoints LaneDepartureChecker::cutTrajectory( for (size_t i = 1; i < trajectory.size(); ++i) { const auto & point = trajectory.at(i); - const auto p1 = autoware_universe_utils::fromMsg(cut.back().pose.position); - const auto p2 = autoware_universe_utils::fromMsg(point.pose.position); + const auto p1 = autoware::universe_utils::fromMsg(cut.back().pose.position); + const auto p2 = autoware::universe_utils::fromMsg(point.pose.position); const auto points_distance = boost::geometry::distance(p1.to_2d(), p2.to_2d()); const auto remain_distance = length - total_length; @@ -251,7 +251,7 @@ std::vector LaneDepartureChecker::createVehicleFootprints( std::vector vehicle_footprints; for (const auto & p : trajectory) { vehicle_footprints.push_back( - transformVector(local_vehicle_footprint, autoware_universe_utils::pose2transform(p.pose))); + transformVector(local_vehicle_footprint, autoware::universe_utils::pose2transform(p.pose))); } return vehicle_footprints; @@ -268,7 +268,7 @@ std::vector LaneDepartureChecker::createVehicleFootprints( std::vector vehicle_footprints; for (const auto & p : path.points) { vehicle_footprints.push_back(transformVector( - local_vehicle_footprint, autoware_universe_utils::pose2transform(p.point.pose))); + local_vehicle_footprint, autoware::universe_utils::pose2transform(p.point.pose))); } return vehicle_footprints; @@ -322,18 +322,18 @@ std::vector> LaneDepartureChecker::getLanele lanelet_map_ptr->laneletLayer, footprint_hull_basic_polygon, 0.0); } -std::optional +std::optional LaneDepartureChecker::getFusedLaneletPolygonForPath( const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const { const auto lanelets_distance_pair = getLaneletsFromPath(lanelet_map_ptr, path); auto to_polygon2d = - [](const lanelet::BasicPolygon2d & poly) -> autoware_universe_utils::Polygon2d { - autoware_universe_utils::Polygon2d p; + [](const lanelet::BasicPolygon2d & poly) -> autoware::universe_utils::Polygon2d { + autoware::universe_utils::Polygon2d p; auto & outer = p.outer(); for (const auto & p : poly) { - autoware_universe_utils::Point2d p2d(p.x(), p.y()); + autoware::universe_utils::Point2d p2d(p.x(), p.y()); outer.push_back(p2d); } boost::geometry::correct(p); @@ -341,15 +341,15 @@ LaneDepartureChecker::getFusedLaneletPolygonForPath( }; // Fuse lanelets into a single BasicPolygon2d - auto fused_lanelets = [&]() -> std::optional { + auto fused_lanelets = [&]() -> std::optional { if (lanelets_distance_pair.empty()) return std::nullopt; - autoware_universe_utils::MultiPolygon2d lanelet_unions; - autoware_universe_utils::MultiPolygon2d result; + autoware::universe_utils::MultiPolygon2d lanelet_unions; + autoware::universe_utils::MultiPolygon2d result; for (size_t i = 0; i < lanelets_distance_pair.size(); ++i) { const auto & route_lanelet = lanelets_distance_pair.at(i).second; const auto & p = route_lanelet.polygon2d().basicPolygon(); - autoware_universe_utils::Polygon2d poly = to_polygon2d(p); + autoware::universe_utils::Polygon2d poly = to_polygon2d(p); boost::geometry::union_(lanelet_unions, poly, result); lanelet_unions = result; result.clear(); diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index 84ab3877fe9f9..427cf0898470e 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -31,7 +31,7 @@ #include #include -using autoware_universe_utils::rad2deg; +using autoware::universe_utils::rad2deg; namespace { @@ -251,7 +251,7 @@ bool LaneDepartureCheckerNode::isDataValid() void LaneDepartureCheckerNode::onTimer() { std::map processing_time_map; - autoware_universe_utils::StopWatch stop_watch; + autoware::universe_utils::StopWatch stop_watch; stop_watch.tic("Total"); current_odom_ = sub_odom_.takeData(); @@ -453,9 +453,9 @@ void LaneDepartureCheckerNode::checkTrajectoryDeviation( visualization_msgs::msg::MarkerArray LaneDepartureCheckerNode::createMarkerArray() const { - using autoware_universe_utils::createDefaultMarker; - using autoware_universe_utils::createMarkerColor; - using autoware_universe_utils::createMarkerScale; + using autoware::universe_utils::createDefaultMarker; + using autoware::universe_utils::createMarkerColor; + using autoware::universe_utils::createMarkerScale; visualization_msgs::msg::MarkerArray marker_array; diff --git a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_trajectory.hpp b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_trajectory.hpp index 2edbfdd3e1e90..b761aa9f19d23 100644 --- a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_trajectory.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_trajectory.hpp @@ -117,7 +117,7 @@ class MPCTrajectory point.pose.position.x = x.at(i); point.pose.position.y = y.at(i); point.pose.position.z = z.at(i); - point.pose.orientation = autoware_universe_utils::createQuaternionFromYaw(yaw.at(i)); + point.pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw.at(i)); point.longitudinal_velocity_mps = vx.at(i); points.push_back(point); } diff --git a/control/autoware_mpc_lateral_controller/src/mpc.cpp b/control/autoware_mpc_lateral_controller/src/mpc.cpp index 23235fe445e24..b6ddba60490d6 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc.cpp @@ -25,9 +25,9 @@ namespace autoware::motion::control::mpc_lateral_controller { -using autoware_universe_utils::calcDistance2d; -using autoware_universe_utils::normalizeRadian; -using autoware_universe_utils::rad2deg; +using autoware::universe_utils::calcDistance2d; +using autoware::universe_utils::normalizeRadian; +using autoware::universe_utils::rad2deg; MPC::MPC(rclcpp::Node & node) { @@ -167,10 +167,10 @@ void MPC::setReferenceTrajectory( const Odometry & current_kinematics) { const size_t nearest_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( trajectory_msg.points, current_kinematics.pose.pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); - const double ego_offset_to_segment = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const double ego_offset_to_segment = autoware::motion_utils::calcLongitudinalOffsetToSegment( trajectory_msg.points, nearest_seg_idx, current_kinematics.pose.pose.position); const auto mpc_traj_raw = MPCUtils::convertToMPCTrajectory(trajectory_msg); @@ -184,7 +184,7 @@ void MPC::setReferenceTrajectory( } const auto is_forward_shift = - autoware_motion_utils::isDrivingForward(mpc_traj_resampled.toTrajectoryPoints()); + autoware::motion_utils::isDrivingForward(mpc_traj_resampled.toTrajectoryPoints()); // if driving direction is unknown, use previous value m_is_forward_shift = is_forward_shift ? is_forward_shift.value() : m_is_forward_shift; @@ -391,7 +391,7 @@ MPCTrajectory MPC::applyVelocityDynamicsFilter( } const size_t nearest_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( autoware_traj.points, current_kinematics.pose.pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); @@ -501,7 +501,7 @@ MPCMatrix MPC::generateMPCMatrix( // get reference input (feed-forward) m_vehicle_model_ptr->setCurvature(ref_smooth_k); m_vehicle_model_ptr->calculateReferenceInput(Uref); - if (std::fabs(Uref(0, 0)) < autoware_universe_utils::deg2rad(m_param.zero_ff_steer_deg)) { + if (std::fabs(Uref(0, 0)) < autoware::universe_utils::deg2rad(m_param.zero_ff_steer_deg)) { Uref(0, 0) = 0.0; // ignore curvature noise } m.Uref_ex.block(i * DIM_U, 0, DIM_U, 1) = Uref; @@ -678,7 +678,7 @@ double MPC::getPredictionDeltaTime( { // Calculate the time min_prediction_length ahead from current_pose const auto autoware_traj = MPCUtils::convertToAutowareTrajectory(input); - const size_t nearest_idx = autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + const size_t nearest_idx = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( autoware_traj.points, current_kinematics.pose.pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); double sum_dist = 0; diff --git a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp index 83a19cbe86acf..efa17e5236907 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -435,7 +435,7 @@ bool MpcLateralController::isStoppedState() const // for the stop state judgement. However, it has been removed since the steering // control was turned off when approaching/exceeding the stop line on a curve or // emergency stop situation and it caused large tracking error. - const size_t nearest = autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + const size_t nearest = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( m_current_trajectory.points, m_current_kinematic_state.pose.pose, m_ego_nearest_dist_threshold, m_ego_nearest_yaw_threshold); @@ -643,7 +643,7 @@ bool MpcLateralController::isTrajectoryShapeChanged() const // TODO(Horibe): update implementation to check trajectory shape around ego vehicle. // Now temporally check the goal position. for (const auto & trajectory : m_trajectory_buffer) { - const auto change_distance = autoware_universe_utils::calcDistance2d( + const auto change_distance = autoware::universe_utils::calcDistance2d( trajectory.points.back().pose, m_current_trajectory.points.back().pose); if (change_distance > m_new_traj_end_dist) { return true; diff --git a/control/autoware_mpc_lateral_controller/src/mpc_utils.cpp b/control/autoware_mpc_lateral_controller/src/mpc_utils.cpp index a2dd346a442b3..37eb47ab0396e 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc_utils.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_utils.cpp @@ -42,9 +42,9 @@ double calcLongitudinalOffset( namespace MPCUtils { -using autoware_universe_utils::calcDistance2d; -using autoware_universe_utils::createQuaternionFromYaw; -using autoware_universe_utils::normalizeRadian; +using autoware::universe_utils::calcDistance2d; +using autoware::universe_utils::createQuaternionFromYaw; +using autoware::universe_utils::normalizeRadian; double calcDistance2d(const MPCTrajectory & trajectory, const size_t idx1, const size_t idx2) { @@ -240,7 +240,7 @@ std::vector calcTrajectoryCurvature( p2.y = traj.y.at(curr_idx); p3.y = traj.y.at(next_idx); try { - curvature_vec.at(curr_idx) = autoware_universe_utils::calcCurvature(p1, p2, p3); + curvature_vec.at(curr_idx) = autoware::universe_utils::calcCurvature(p1, p2, p3); } catch (...) { std::cerr << "[MPC] 2 points are too close to calculate curvature." << std::endl; curvature_vec.at(curr_idx) = 0.0; @@ -281,7 +281,7 @@ Trajectory convertToAutowareTrajectory(const MPCTrajectory & input) p.pose.position.x = input.x.at(i); p.pose.position.y = input.y.at(i); p.pose.position.z = input.z.at(i); - p.pose.orientation = autoware_universe_utils::createQuaternionFromYaw(input.yaw.at(i)); + p.pose.orientation = autoware::universe_utils::createQuaternionFromYaw(input.yaw.at(i)); p.longitudinal_velocity_mps = static_cast(input.vx.at(i)); output.points.push_back(p); @@ -346,7 +346,7 @@ bool calcNearestPoseInterp( return false; } - *nearest_index = autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + *nearest_index = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( autoware_traj.points, self_pose, max_dist, max_yaw); const size_t traj_size = traj.size(); @@ -389,7 +389,7 @@ bool calcNearestPoseInterp( prev_traj_point.x = traj.x.at(prev); prev_traj_point.y = traj.y.at(prev); const double traj_seg_length = - autoware_universe_utils::calcDistance2d(prev_traj_point, next_traj_point); + autoware::universe_utils::calcDistance2d(prev_traj_point, next_traj_point); /* if distance between two points are too close */ if (traj_seg_length < 1.0E-5) { nearest_pose->position.x = traj.x.at(*nearest_index); @@ -460,7 +460,7 @@ void extendTrajectoryInYawDirection( const double dt = interval / extend_vel; const size_t num_extended_point = static_cast(extend_dist / interval); for (size_t i = 0; i < num_extended_point; ++i) { - extended_pose = autoware_universe_utils::calcOffsetPose(extended_pose, x_offset, 0.0, 0.0); + extended_pose = autoware::universe_utils::calcOffsetPose(extended_pose, x_offset, 0.0, 0.0); traj.push_back( extended_pose.position.x, extended_pose.position.y, extended_pose.position.z, traj.yaw.back(), extend_vel, traj.k.back(), traj.smooth_k.back(), traj.relative_time.back() + dt); diff --git a/control/autoware_operation_mode_transition_manager/src/node.hpp b/control/autoware_operation_mode_transition_manager/src/node.hpp index 46cc360355e67..d69d79f9640d8 100644 --- a/control/autoware_operation_mode_transition_manager/src/node.hpp +++ b/control/autoware_operation_mode_transition_manager/src/node.hpp @@ -49,9 +49,9 @@ class OperationModeTransitionManager : public rclcpp::Node const ChangeOperationModeAPI::Service::Response::SharedPtr response); using ControlModeCommandType = ControlModeCommand::Request::_mode_type; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_control_mode_report_{this, "control_mode_report"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_gate_operation_mode_{this, "gate_operation_mode"}; rclcpp::Client::SharedPtr cli_control_mode_; rclcpp::Publisher::SharedPtr pub_debug_info_; diff --git a/control/autoware_operation_mode_transition_manager/src/state.cpp b/control/autoware_operation_mode_transition_manager/src/state.cpp index ea2f9bf4bf03c..31cd32e6311a9 100644 --- a/control/autoware_operation_mode_transition_manager/src/state.cpp +++ b/control/autoware_operation_mode_transition_manager/src/state.cpp @@ -26,9 +26,9 @@ namespace autoware::operation_mode_transition_manager { -using autoware_motion_utils::findNearestIndex; -using autoware_universe_utils::calcDistance2d; -using autoware_universe_utils::calcYawDeviation; +using autoware::motion_utils::findNearestIndex; +using autoware::universe_utils::calcDistance2d; +using autoware::universe_utils::calcYawDeviation; AutonomousMode::AutonomousMode(rclcpp::Node * node) : logger_(node->get_logger()), clock_(node->get_clock()) @@ -126,7 +126,7 @@ bool AutonomousMode::isModeChangeCompleted() // check for lateral deviation const auto dist_deviation = - autoware_motion_utils::calcLateralOffset(trajectory_.points, kinematics_.pose.pose.position); + autoware::motion_utils::calcLateralOffset(trajectory_.points, kinematics_.pose.pose.position); if (std::isnan(dist_deviation)) { RCLCPP_INFO(logger_, "Not stable yet: lateral offset calculation failed."); return unstable(); @@ -138,7 +138,7 @@ bool AutonomousMode::isModeChangeCompleted() // check for yaw deviation const auto yaw_deviation = - autoware_motion_utils::calcYawDeviation(trajectory_.points, kinematics_.pose.pose); + autoware::motion_utils::calcYawDeviation(trajectory_.points, kinematics_.pose.pose); if (std::isnan(yaw_deviation)) { RCLCPP_INFO(logger_, "Not stable yet: lateral offset calculation failed."); return unstable(); diff --git a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/longitudinal_controller_utils.hpp b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/longitudinal_controller_utils.hpp index f0e231e354bc4..a36a0b4eefccd 100644 --- a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/longitudinal_controller_utils.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/longitudinal_controller_utils.hpp @@ -87,13 +87,13 @@ std::pair lerpTrajectoryPoint( const T & points, const Pose & pose, const double max_dist, const double max_yaw) { TrajectoryPoint interpolated_point; - const size_t seg_idx = autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + const size_t seg_idx = autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( points, pose, max_dist, max_yaw); const double len_to_interpolated = - autoware_motion_utils::calcLongitudinalOffsetToSegment(points, seg_idx, pose.position); + autoware::motion_utils::calcLongitudinalOffsetToSegment(points, seg_idx, pose.position); const double len_segment = - autoware_motion_utils::calcSignedArcLength(points, seg_idx, seg_idx + 1); + autoware::motion_utils::calcSignedArcLength(points, seg_idx, seg_idx + 1); const double interpolate_ratio = std::clamp(len_to_interpolated / len_segment, 0.0, 1.0); { diff --git a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp index ed9fcb3974c83..9291d538b022f 100644 --- a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp @@ -50,10 +50,10 @@ namespace autoware::motion::control::pid_longitudinal_controller { +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerScale; using autoware_adapi_v1_msgs::msg::OperationModeState; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerScale; using visualization_msgs::msg::Marker; namespace trajectory_follower = ::autoware::motion::control::trajectory_follower; diff --git a/control/autoware_pid_longitudinal_controller/src/longitudinal_controller_utils.cpp b/control/autoware_pid_longitudinal_controller/src/longitudinal_controller_utils.cpp index 2a897f92a0efe..5eb6c87e063eb 100644 --- a/control/autoware_pid_longitudinal_controller/src/longitudinal_controller_utils.cpp +++ b/control/autoware_pid_longitudinal_controller/src/longitudinal_controller_utils.cpp @@ -58,12 +58,12 @@ bool isValidTrajectory(const Trajectory & traj) double calcStopDistance( const Pose & current_pose, const Trajectory & traj, const double max_dist, const double max_yaw) { - const auto stop_idx_opt = autoware_motion_utils::searchZeroVelocityIndex(traj.points); + const auto stop_idx_opt = autoware::motion_utils::searchZeroVelocityIndex(traj.points); const size_t end_idx = stop_idx_opt ? *stop_idx_opt : traj.points.size() - 1; - const size_t seg_idx = autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + const size_t seg_idx = autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( traj.points, current_pose, max_dist, max_yaw); - const double signed_length_on_traj = autoware_motion_utils::calcSignedArcLength( + const double signed_length_on_traj = autoware::motion_utils::calcSignedArcLength( traj.points, current_pose.position, seg_idx, traj.points.at(end_idx).pose.position, std::min(end_idx, traj.points.size() - 2)); @@ -93,7 +93,7 @@ double getPitchByTraj( const auto [prev_idx, next_idx] = [&]() { for (size_t i = start_idx + 1; i < trajectory.points.size(); ++i) { - const double dist = autoware_universe_utils::calcDistance3d( + const double dist = autoware::universe_utils::calcDistance3d( trajectory.points.at(start_idx), trajectory.points.at(i)); if (dist > wheel_base) { // calculate pitch from trajectory between rear wheel (nearest) and front center (i) @@ -105,7 +105,7 @@ double getPitchByTraj( std::min(start_idx, trajectory.points.size() - 2), trajectory.points.size() - 1); }(); - return autoware_universe_utils::calcElevationAngle( + return autoware::universe_utils::calcElevationAngle( trajectory.points.at(prev_idx).pose.position, trajectory.points.at(next_idx).pose.position); } @@ -166,7 +166,7 @@ geometry_msgs::msg::Pose findTrajectoryPoseAfterDistance( double remain_dist = distance; geometry_msgs::msg::Pose p = trajectory.points.back().pose; for (size_t i = src_idx; i < trajectory.points.size() - 1; ++i) { - const double dist = autoware_universe_utils::calcDistance3d( + const double dist = autoware::universe_utils::calcDistance3d( trajectory.points.at(i).pose, trajectory.points.at(i + 1).pose); if (remain_dist < dist) { if (remain_dist <= 0.0) { diff --git a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index dda6b9632a769..78c7ccf832514 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -465,10 +465,10 @@ PidLongitudinalController::ControlData PidLongitudinalController::getControlData // check if the deviation is worth emergency m_diagnostic_data.trans_deviation = - autoware_universe_utils::calcDistance2d(current_interpolated_pose.first, current_pose); + autoware::universe_utils::calcDistance2d(current_interpolated_pose.first, current_pose); const bool is_dist_deviation_large = m_state_transition_params.emergency_state_traj_trans_dev < m_diagnostic_data.trans_deviation; - m_diagnostic_data.rot_deviation = std::abs(autoware_universe_utils::normalizeRadian( + m_diagnostic_data.rot_deviation = std::abs(autoware::universe_utils::normalizeRadian( tf2::getYaw(current_interpolated_pose.first.pose.orientation) - tf2::getYaw(current_pose.orientation))); const bool is_yaw_deviation_large = @@ -509,11 +509,11 @@ PidLongitudinalController::ControlData PidLongitudinalController::getControlData // ========================================================================================== // Remove overlapped points after inserting the interpolated points control_data.interpolated_traj.points = - autoware_motion_utils::removeOverlapPoints(control_data.interpolated_traj.points); - control_data.nearest_idx = autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + autoware::motion_utils::removeOverlapPoints(control_data.interpolated_traj.points); + control_data.nearest_idx = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( control_data.interpolated_traj.points, nearest_point.pose, m_ego_nearest_dist_threshold, m_ego_nearest_yaw_threshold); - control_data.target_idx = autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + control_data.target_idx = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( control_data.interpolated_traj.points, target_point.pose, m_ego_nearest_dist_threshold, m_ego_nearest_yaw_threshold); @@ -594,7 +594,7 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d stop_dist > p.drive_state_stop_dist + p.drive_state_offset_stop_dist; const bool departure_condition_from_stopped = stop_dist > p.drive_state_stop_dist; - // NOTE: the same velocity threshold as autoware_motion_utils::searchZeroVelocity + // NOTE: the same velocity threshold as autoware::motion_utils::searchZeroVelocity static constexpr double vel_epsilon = 1e-3; // Let vehicle start after the steering is converged for control accuracy @@ -605,7 +605,7 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d auto marker = createDefaultMarker( "map", clock_->now(), "stop_reason", 0, Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999)); - marker.pose = autoware_universe_utils::calcOffsetPose( + marker.pose = autoware::universe_utils::calcOffsetPose( m_current_kinematic_state.pose.pose, m_wheel_base + m_front_overhang, m_vehicle_width / 2 + 2.0, 1.5); marker.text = "steering not\nconverged"; @@ -971,7 +971,7 @@ PidLongitudinalController::Motion PidLongitudinalController::keepBrakeBeforeStop } const auto traj = control_data.interpolated_traj; - const auto stop_idx = autoware_motion_utils::searchZeroVelocityIndex(traj.points); + const auto stop_idx = autoware::motion_utils::searchZeroVelocityIndex(traj.points); if (!stop_idx) { return output_motion; } diff --git a/control/autoware_pure_pursuit/include/autoware/pure_pursuit/autoware_pure_pursuit_node.hpp b/control/autoware_pure_pursuit/include/autoware/pure_pursuit/autoware_pure_pursuit_node.hpp index 1030b58e0f979..58ce03a0dbf26 100644 --- a/control/autoware_pure_pursuit/include/autoware/pure_pursuit/autoware_pure_pursuit_node.hpp +++ b/control/autoware_pure_pursuit/include/autoware/pure_pursuit/autoware_pure_pursuit_node.hpp @@ -78,10 +78,10 @@ class PurePursuitNode : public rclcpp::Node private: // Subscriber - autoware_universe_utils::SelfPoseListener self_pose_listener_{this}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::SelfPoseListener self_pose_listener_{this}; + autoware::universe_utils::InterProcessPollingSubscriber sub_trajectory_{this, "input/reference_trajectory"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_current_odometry_{this, "input/current_odometry"}; autoware_planning_msgs::msg::Trajectory::ConstSharedPtr trajectory_; diff --git a/control/autoware_pure_pursuit/src/autoware_pure_pursuit/autoware_pure_pursuit_lateral_controller.cpp b/control/autoware_pure_pursuit/src/autoware_pure_pursuit/autoware_pure_pursuit_lateral_controller.cpp index 8a82e60354f36..803a6ef1e8617 100644 --- a/control/autoware_pure_pursuit/src/autoware_pure_pursuit/autoware_pure_pursuit_lateral_controller.cpp +++ b/control/autoware_pure_pursuit/src/autoware_pure_pursuit/autoware_pure_pursuit_lateral_controller.cpp @@ -141,7 +141,7 @@ TrajectoryPoint PurePursuitLateralController::calcNextPose( const double ds, TrajectoryPoint & point, Lateral cmd) const { geometry_msgs::msg::Transform transform; - transform.translation = autoware_universe_utils::createTranslation(ds, 0.0, 0.0); + transform.translation = autoware::universe_utils::createTranslation(ds, 0.0, 0.0); transform.rotation = planning_utils::getQuaternionFromYaw(((tan(cmd.steering_tire_angle) * ds) / param_.wheel_base)); TrajectoryPoint output_p; @@ -158,17 +158,17 @@ void PurePursuitLateralController::setResampledTrajectory() { // Interpolate with constant interval distance. std::vector out_arclength; - const auto input_tp_array = autoware_motion_utils::convertToTrajectoryPointArray(trajectory_); - const auto traj_length = autoware_motion_utils::calcArcLength(input_tp_array); + const auto input_tp_array = autoware::motion_utils::convertToTrajectoryPointArray(trajectory_); + const auto traj_length = autoware::motion_utils::calcArcLength(input_tp_array); for (double s = 0; s < traj_length; s += param_.resampling_ds) { out_arclength.push_back(s); } trajectory_resampled_ = std::make_shared( - autoware_motion_utils::resampleTrajectory( - autoware_motion_utils::convertToTrajectory(input_tp_array), out_arclength)); + autoware::motion_utils::resampleTrajectory( + autoware::motion_utils::convertToTrajectory(input_tp_array), out_arclength)); trajectory_resampled_->points.back() = trajectory_.points.back(); trajectory_resampled_->header = trajectory_.header; - output_tp_array_ = autoware_motion_utils::convertToTrajectoryPointArray(*trajectory_resampled_); + output_tp_array_ = autoware::motion_utils::convertToTrajectoryPointArray(*trajectory_resampled_); } double PurePursuitLateralController::calcCurvature(const size_t closest_idx) @@ -202,10 +202,10 @@ double PurePursuitLateralController::calcCurvature(const size_t closest_idx) double current_curvature = 0.0; try { - current_curvature = autoware_universe_utils::calcCurvature( - autoware_universe_utils::getPoint(trajectory_resampled_->points.at(prev_idx)), - autoware_universe_utils::getPoint(trajectory_resampled_->points.at(closest_idx)), - autoware_universe_utils::getPoint(trajectory_resampled_->points.at(next_idx))); + current_curvature = autoware::universe_utils::calcCurvature( + autoware::universe_utils::getPoint(trajectory_resampled_->points.at(prev_idx)), + autoware::universe_utils::getPoint(trajectory_resampled_->points.at(closest_idx)), + autoware::universe_utils::getPoint(trajectory_resampled_->points.at(next_idx))); } catch (std::exception const & e) { // ...code that handles the error... RCLCPP_WARN(rclcpp::get_logger("pure_pursuit"), "%s", e.what()); @@ -268,7 +268,7 @@ void PurePursuitLateralController::averageFilterTrajectory( boost::optional PurePursuitLateralController::generatePredictedTrajectory() { - const auto closest_idx_result = autoware_motion_utils::findNearestIndex( + const auto closest_idx_result = autoware::motion_utils::findNearestIndex( output_tp_array_, current_odometry_.pose.pose, 3.0, M_PI_4); if (!closest_idx_result) { @@ -427,7 +427,7 @@ boost::optional PurePursuitLateralController::calcTargetCurvature( // Calculate target point for velocity/acceleration const auto closest_idx_result = - autoware_motion_utils::findNearestIndex(output_tp_array_, pose, 3.0, M_PI_4); + autoware::motion_utils::findNearestIndex(output_tp_array_, pose, 3.0, M_PI_4); if (!closest_idx_result) { RCLCPP_ERROR(logger_, "cannot find closest waypoint"); return {}; @@ -439,7 +439,7 @@ boost::optional PurePursuitLateralController::calcTargetCurvature( // calculate the lateral error const double lateral_error = - autoware_motion_utils::calcLateralOffset(trajectory_resampled_->points, pose.position); + autoware::motion_utils::calcLateralOffset(trajectory_resampled_->points, pose.position); // calculate the current curvature diff --git a/control/autoware_shift_decider/include/autoware/shift_decider/autoware_shift_decider.hpp b/control/autoware_shift_decider/include/autoware/shift_decider/autoware_shift_decider.hpp index cffdbf2cdf2ab..c7ce822d1ac18 100644 --- a/control/autoware_shift_decider/include/autoware/shift_decider/autoware_shift_decider.hpp +++ b/control/autoware_shift_decider/include/autoware/shift_decider/autoware_shift_decider.hpp @@ -43,11 +43,11 @@ class ShiftDecider : public rclcpp::Node void initTimer(double period_s); rclcpp::Publisher::SharedPtr pub_shift_cmd_; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_control_cmd_{this, "input/control_cmd"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_autoware_state_{this, "input/state"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_current_gear_{this, "input/current_gear"}; rclcpp::TimerBase::SharedPtr timer_; diff --git a/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp b/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp index 21d58748d31fa..a5f8665328f34 100644 --- a/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp +++ b/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp @@ -55,8 +55,8 @@ using trajectory_follower::LongitudinalOutput; namespace trajectory_follower_node { +using autoware::universe_utils::StopWatch; using autoware_adapi_v1_msgs::msg::OperationModeState; -using autoware_universe_utils::StopWatch; using tier4_debug_msgs::msg::Float64Stamped; namespace trajectory_follower = ::autoware::motion::control::trajectory_follower; @@ -82,20 +82,21 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node std::shared_ptr lateral_controller_; // Subscribers - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_ref_path_{this, "~/input/reference_trajectory"}; - autoware_universe_utils::InterProcessPollingSubscriber sub_odometry_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_odometry_{ this, "~/input/current_odometry"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber< + autoware_vehicle_msgs::msg::SteeringReport> sub_steering_{this, "~/input/current_steering"}; - autoware_universe_utils::InterProcessPollingSubscriber< + autoware::universe_utils::InterProcessPollingSubscriber< geometry_msgs::msg::AccelWithCovarianceStamped> sub_accel_{this, "~/input/current_accel"}; - autoware_universe_utils::InterProcessPollingSubscriber sub_operation_mode_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_operation_mode_{ this, "~/input/current_operation_mode"}; // Publishers @@ -134,9 +135,9 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node const trajectory_follower::InputData & input_data, const trajectory_follower::LateralOutput & lat_out) const; - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; void publishProcessingTime( const double t_ms, const rclcpp::Publisher::SharedPtr pub); diff --git a/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/simple_trajectory_follower.hpp b/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/simple_trajectory_follower.hpp index 0c179ad1996f4..c23128ebfb695 100644 --- a/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/simple_trajectory_follower.hpp +++ b/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/simple_trajectory_follower.hpp @@ -44,9 +44,9 @@ class SimpleTrajectoryFollower : public rclcpp::Node ~SimpleTrajectoryFollower() = default; private: - autoware_universe_utils::InterProcessPollingSubscriber sub_kinematics_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_kinematics_{ this, "~/input/kinematics"}; - autoware_universe_utils::InterProcessPollingSubscriber sub_trajectory_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_trajectory_{ this, "~/input/trajectory"}; rclcpp::Publisher::SharedPtr pub_cmd_; rclcpp::TimerBase::SharedPtr timer_; diff --git a/control/autoware_trajectory_follower_node/src/controller_node.cpp b/control/autoware_trajectory_follower_node/src/controller_node.cpp index 274da6e9a5534..c1e5fe646cdaa 100644 --- a/control/autoware_trajectory_follower_node/src/controller_node.cpp +++ b/control/autoware_trajectory_follower_node/src/controller_node.cpp @@ -81,10 +81,10 @@ Controller::Controller(const rclcpp::NodeOptions & node_options) : Node("control this, get_clock(), period_ns, std::bind(&Controller::callbackTimerControl, this)); } - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } Controller::LateralControllerMode Controller::getLateralControllerMode( @@ -224,10 +224,10 @@ void Controller::publishDebugMarker( // steer converged marker { - auto marker = autoware_universe_utils::createDefaultMarker( + auto marker = autoware::universe_utils::createDefaultMarker( "map", this->now(), "steer_converged", 0, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, - autoware_universe_utils::createMarkerScale(0.0, 0.0, 1.0), - autoware_universe_utils::createMarkerColor(1.0, 1.0, 1.0, 0.99)); + autoware::universe_utils::createMarkerScale(0.0, 0.0, 1.0), + autoware::universe_utils::createMarkerColor(1.0, 1.0, 1.0, 0.99)); marker.pose = input_data.current_odometry.pose.pose; std::stringstream ss; diff --git a/control/autoware_trajectory_follower_node/src/simple_trajectory_follower.cpp b/control/autoware_trajectory_follower_node/src/simple_trajectory_follower.cpp index 81459dc9ef72f..95082e608d50f 100644 --- a/control/autoware_trajectory_follower_node/src/simple_trajectory_follower.cpp +++ b/control/autoware_trajectory_follower_node/src/simple_trajectory_follower.cpp @@ -22,9 +22,9 @@ namespace simple_trajectory_follower { -using autoware_motion_utils::findNearestIndex; -using autoware_universe_utils::calcLateralDeviation; -using autoware_universe_utils::calcYawDeviation; +using autoware::motion_utils::findNearestIndex; +using autoware::universe_utils::calcLateralDeviation; +using autoware::universe_utils::calcYawDeviation; SimpleTrajectoryFollower::SimpleTrajectoryFollower(const rclcpp::NodeOptions & options) : Node("simple_trajectory_follower", options) diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp index 7295032ae3cb7..87e79f59bc356 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -210,10 +210,10 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) timer_pub_status_ = rclcpp::create_timer( this, get_clock(), period_ns, std::bind(&VehicleCmdGate::publishStatus, this)); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); // Parameter Callback set_param_res_ = @@ -223,7 +223,7 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) rcl_interfaces::msg::SetParametersResult VehicleCmdGate::onParameter( const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; // Parameter updateParam(parameters, "use_emergency_handling", use_emergency_handling_); updateParam( diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp index 08de508dbefcc..42e28d633d16b 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp @@ -81,7 +81,7 @@ using nav_msgs::msg::Odometry; using EngageMsg = autoware_vehicle_msgs::msg::Engage; using EngageSrv = tier4_external_api_msgs::srv::Engage; -using autoware_motion_utils::VehicleStopChecker; +using autoware::motion_utils::VehicleStopChecker; struct Commands { Control control; @@ -155,31 +155,31 @@ class VehicleCmdGate : public rclcpp::Node // Subscriber for auto Commands auto_commands_; rclcpp::Subscription::SharedPtr auto_control_cmd_sub_; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber auto_turn_indicator_cmd_sub_{this, "input/auto/turn_indicators_cmd"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber auto_hazard_light_cmd_sub_{this, "input/auto/hazard_lights_cmd"}; - autoware_universe_utils::InterProcessPollingSubscriber auto_gear_cmd_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber auto_gear_cmd_sub_{ this, "input/auto/gear_cmd"}; void onAutoCtrlCmd(Control::ConstSharedPtr msg); // Subscription for external Commands remote_commands_; rclcpp::Subscription::SharedPtr remote_control_cmd_sub_; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber remote_turn_indicator_cmd_sub_{this, "input/external/turn_indicators_cmd"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber remote_hazard_light_cmd_sub_{this, "input/external/hazard_lights_cmd"}; - autoware_universe_utils::InterProcessPollingSubscriber remote_gear_cmd_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber remote_gear_cmd_sub_{ this, "input/external/gear_cmd"}; void onRemoteCtrlCmd(Control::ConstSharedPtr msg); // Subscription for emergency Commands emergency_commands_; rclcpp::Subscription::SharedPtr emergency_control_cmd_sub_; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber emergency_hazard_light_cmd_sub_{this, "input/emergency/hazard_lights_cmd"}; - autoware_universe_utils::InterProcessPollingSubscriber emergency_gear_cmd_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber emergency_gear_cmd_sub_{ this, "input/emergency/gear_cmd"}; void onEmergencyCtrlCmd(Control::ConstSharedPtr msg); @@ -261,9 +261,9 @@ class VehicleCmdGate : public rclcpp::Node MarkerArray createMarkerArray(const IsFilterActivated & filter_activated); void publishMarkers(const IsFilterActivated & filter_activated); - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; }; } // namespace autoware::vehicle_cmd_gate diff --git a/control/control_performance_analysis/src/control_performance_analysis_core.cpp b/control/control_performance_analysis/src/control_performance_analysis_core.cpp index e72adc3ecdad4..5f72c8ea316bd 100644 --- a/control/control_performance_analysis/src/control_performance_analysis_core.cpp +++ b/control/control_performance_analysis/src/control_performance_analysis_core.cpp @@ -86,7 +86,7 @@ std::pair ControlPerformanceAnalysisCore::findClosestPrevWayPoint return std::make_pair(false, std::numeric_limits::quiet_NaN()); } - const auto closest_segment = autoware_motion_utils::findNearestSegmentIndex( + const auto closest_segment = autoware::motion_utils::findNearestSegmentIndex( current_trajectory_ptr_->points, *current_vec_pose_ptr_, p_.acceptable_max_distance_to_waypoint_, p_.acceptable_max_yaw_difference_rad_); @@ -158,7 +158,7 @@ bool ControlPerformanceAnalysisCore::calculateErrorVars() // Compute the yaw angle error. const double heading_yaw_error = - autoware_universe_utils::calcYawDeviation(pose_interp_wp, *current_vec_pose_ptr_); + autoware::universe_utils::calcYawDeviation(pose_interp_wp, *current_vec_pose_ptr_); // Set the values of ErrorMsgVars. @@ -174,7 +174,7 @@ bool ControlPerformanceAnalysisCore::calculateErrorVars() const double Vx = odom_history_ptr_->at(odom_size - 2).twist.twist.linear.x; // Current acceleration calculation - const auto ds = autoware_universe_utils::calcDistance2d( + const auto ds = autoware::universe_utils::calcDistance2d( odom_history_ptr_->at(odom_size - 1).pose.pose, odom_history_ptr_->at(odom_size - 2).pose.pose); const double vel_mean = (odom_history_ptr_->at(odom_size - 1).twist.twist.linear.x + @@ -372,7 +372,7 @@ std::optional ControlPerformanceAnalysisCore::findCurveRefIdx() auto fun_distance_cond = [this](auto point_t) { const double dist = - autoware_universe_utils::calcDistance2d(point_t.pose, *interpolated_pose_ptr_); + autoware::universe_utils::calcDistance2d(point_t.pose, *interpolated_pose_ptr_); return dist > p_.wheelbase_; }; @@ -391,7 +391,7 @@ std::optional ControlPerformanceAnalysisCore::findCurveRefIdx() std::pair ControlPerformanceAnalysisCore::calculateClosestPose() { const auto interp_point = - autoware_motion_utils::calcInterpolatedPoint(*current_trajectory_ptr_, *current_vec_pose_ptr_); + autoware::motion_utils::calcInterpolatedPoint(*current_trajectory_ptr_, *current_vec_pose_ptr_); const double interp_steering_angle = std::atan(p_.wheelbase_ * estimateCurvature()); @@ -443,7 +443,7 @@ double ControlPerformanceAnalysisCore::estimateCurvature() // Compute arc-length ds between 2 points. const double ds_arc_length = - autoware_universe_utils::calcDistance2d(front_axleWP_pose_prev, front_axleWP_pose); + autoware::universe_utils::calcDistance2d(front_axleWP_pose_prev, front_axleWP_pose); // Define waypoints 10 meters behind the rear axle if exist. // If not exist, we will take the first point of the @@ -462,7 +462,7 @@ double ControlPerformanceAnalysisCore::estimateCurvature() // We compute a curvature estimate from these points. double estimated_curvature = 0.0; try { - estimated_curvature = autoware_universe_utils::calcCurvature( + estimated_curvature = autoware::universe_utils::calcCurvature( points.at(loc_of_back_idx).pose.position, points.at(idx_curve_ref_wp).pose.position, points.at(loc_of_forward_idx).pose.position); } catch (...) { @@ -487,7 +487,7 @@ double ControlPerformanceAnalysisCore::estimatePurePursuitCurvature() const double look_ahead_distance_pp = std::max(p_.wheelbase_, 2 * Vx); auto fun_distance_cond = [this, &look_ahead_distance_pp](auto point_t) { - const double dist = autoware_universe_utils::calcDistance2d(point_t, *interpolated_pose_ptr_); + const double dist = autoware::universe_utils::calcDistance2d(point_t, *interpolated_pose_ptr_); return dist > look_ahead_distance_pp; }; diff --git a/control/obstacle_collision_checker/include/obstacle_collision_checker/obstacle_collision_checker.hpp b/control/obstacle_collision_checker/include/obstacle_collision_checker/obstacle_collision_checker.hpp index 27f4405e26f6c..8cce8b88a0e7f 100644 --- a/control/obstacle_collision_checker/include/obstacle_collision_checker/obstacle_collision_checker.hpp +++ b/control/obstacle_collision_checker/include/obstacle_collision_checker/obstacle_collision_checker.hpp @@ -35,7 +35,7 @@ namespace obstacle_collision_checker { -using autoware_universe_utils::LinearRing2d; +using autoware::universe_utils::LinearRing2d; struct Param { diff --git a/control/obstacle_collision_checker/include/obstacle_collision_checker/obstacle_collision_checker_node.hpp b/control/obstacle_collision_checker/include/obstacle_collision_checker/obstacle_collision_checker_node.hpp index 85b3e3d25c2eb..b08ecccd57282 100644 --- a/control/obstacle_collision_checker/include/obstacle_collision_checker/obstacle_collision_checker_node.hpp +++ b/control/obstacle_collision_checker/include/obstacle_collision_checker/obstacle_collision_checker_node.hpp @@ -48,8 +48,8 @@ class ObstacleCollisionCheckerNode : public rclcpp::Node private: // Subscriber - std::shared_ptr self_pose_listener_; - std::shared_ptr transform_listener_; + std::shared_ptr self_pose_listener_; + std::shared_ptr transform_listener_; rclcpp::Subscription::SharedPtr sub_obstacle_pointcloud_; rclcpp::Subscription::SharedPtr sub_reference_trajectory_; @@ -72,8 +72,8 @@ class ObstacleCollisionCheckerNode : public rclcpp::Node void onOdom(const nav_msgs::msg::Odometry::SharedPtr msg); // Publisher - std::shared_ptr debug_publisher_; - std::shared_ptr time_publisher_; + std::shared_ptr debug_publisher_; + std::shared_ptr time_publisher_; // Timer rclcpp::TimerBase::SharedPtr timer_; diff --git a/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker.cpp b/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker.cpp index e6c3aff83ee10..9fb3657b957c7 100644 --- a/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker.cpp +++ b/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker.cpp @@ -90,7 +90,7 @@ ObstacleCollisionChecker::ObstacleCollisionChecker(rclcpp::Node & node) Output ObstacleCollisionChecker::update(const Input & input) { Output output; - autoware_universe_utils::StopWatch stop_watch; + autoware::universe_utils::StopWatch stop_watch; // resample trajectory by braking distance constexpr double min_velocity = 0.01; @@ -131,8 +131,9 @@ autoware_planning_msgs::msg::Trajectory ObstacleCollisionChecker::resampleTrajec for (size_t i = 1; i < trajectory.points.size() - 1; ++i) { const auto & point = trajectory.points.at(i); - const auto p1 = autoware_universe_utils::fromMsg(resampled.points.back().pose.position).to_2d(); - const auto p2 = autoware_universe_utils::fromMsg(point.pose.position).to_2d(); + const auto p1 = + autoware::universe_utils::fromMsg(resampled.points.back().pose.position).to_2d(); + const auto p2 = autoware::universe_utils::fromMsg(point.pose.position).to_2d(); if (boost::geometry::distance(p1, p2) > interval) { resampled.points.push_back(point); @@ -154,8 +155,8 @@ autoware_planning_msgs::msg::Trajectory ObstacleCollisionChecker::cutTrajectory( for (size_t i = 1; i < trajectory.points.size(); ++i) { const auto & point = trajectory.points.at(i); - const auto p1 = autoware_universe_utils::fromMsg(cut.points.back().pose.position); - const auto p2 = autoware_universe_utils::fromMsg(point.pose.position); + const auto p1 = autoware::universe_utils::fromMsg(cut.points.back().pose.position); + const auto p2 = autoware::universe_utils::fromMsg(point.pose.position); const auto points_distance = boost::geometry::distance(p1.to_2d(), p2.to_2d()); const auto remain_distance = length - total_length; @@ -197,8 +198,8 @@ std::vector ObstacleCollisionChecker::createVehicleFootprints( std::vector vehicle_footprints; for (const auto & p : trajectory.points) { vehicle_footprints.push_back( - autoware_universe_utils::transformVector( - local_vehicle_footprint, autoware_universe_utils::pose2transform(p.pose))); + autoware::universe_utils::transformVector( + local_vehicle_footprint, autoware::universe_utils::pose2transform(p.pose))); } return vehicle_footprints; @@ -221,7 +222,7 @@ std::vector ObstacleCollisionChecker::createVehiclePassingAreas( LinearRing2d ObstacleCollisionChecker::createHullFromFootprints( const LinearRing2d & area1, const LinearRing2d & area2) { - autoware_universe_utils::MultiPoint2d combined; + autoware::universe_utils::MultiPoint2d combined; for (const auto & p : area1) { combined.push_back(p); } @@ -256,7 +257,7 @@ bool ObstacleCollisionChecker::hasCollision( { for (const auto & point : obstacle_pointcloud.points) { if (boost::geometry::within( - autoware_universe_utils::Point2d{point.x, point.y}, vehicle_footprint)) { + autoware::universe_utils::Point2d{point.x, point.y}, vehicle_footprint)) { RCLCPP_WARN( rclcpp::get_logger("obstacle_collision_checker"), "[ObstacleCollisionChecker] Collide to Point x: %f y: %f", point.x, point.y); diff --git a/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker_node.cpp b/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker_node.cpp index 9bd95a985e2de..9af5fe24b17ea 100644 --- a/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker_node.cpp +++ b/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker_node.cpp @@ -70,8 +70,8 @@ ObstacleCollisionCheckerNode::ObstacleCollisionCheckerNode(const rclcpp::NodeOpt obstacle_collision_checker_->setParam(param_); // Subscriber - self_pose_listener_ = std::make_shared(this); - transform_listener_ = std::make_shared(this); + self_pose_listener_ = std::make_shared(this); + transform_listener_ = std::make_shared(this); sub_obstacle_pointcloud_ = create_subscription( "input/obstacle_pointcloud", rclcpp::SensorDataQoS(), @@ -87,8 +87,8 @@ ObstacleCollisionCheckerNode::ObstacleCollisionCheckerNode(const rclcpp::NodeOpt // Publisher debug_publisher_ = - std::make_shared(this, "debug/marker"); - time_publisher_ = std::make_shared(this); + std::make_shared(this, "debug/marker"); + time_publisher_ = std::make_shared(this); // Diagnostic Updater updater_.setHardwareID("obstacle_collision_checker"); @@ -283,9 +283,9 @@ void ObstacleCollisionCheckerNode::checkLaneDeparture( visualization_msgs::msg::MarkerArray ObstacleCollisionCheckerNode::createMarkerArray() const { - using autoware_universe_utils::createDefaultMarker; - using autoware_universe_utils::createMarkerColor; - using autoware_universe_utils::createMarkerScale; + using autoware::universe_utils::createDefaultMarker; + using autoware::universe_utils::createMarkerColor; + using autoware::universe_utils::createMarkerScale; visualization_msgs::msg::MarkerArray marker_array; diff --git a/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp b/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp index 01223a4a938be..e2c76bec24860 100644 --- a/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp +++ b/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp @@ -45,10 +45,10 @@ namespace autoware::motion::control::predicted_path_checker using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; using TrajectoryPoints = std::vector; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; using geometry_msgs::msg::Pose; using geometry_msgs::msg::TransformStamped; using PointArray = std::vector; diff --git a/control/predicted_path_checker/include/predicted_path_checker/debug_marker.hpp b/control/predicted_path_checker/include/predicted_path_checker/debug_marker.hpp index 84ccbad32202c..0f537d52cee06 100644 --- a/control/predicted_path_checker/include/predicted_path_checker/debug_marker.hpp +++ b/control/predicted_path_checker/include/predicted_path_checker/debug_marker.hpp @@ -52,12 +52,12 @@ class PredictedPathCheckerDebugNode ~PredictedPathCheckerDebugNode() {} bool pushPolygon( - const autoware_universe_utils::Polygon2d & polygon, const double z, const PolygonType & type); + const autoware::universe_utils::Polygon2d & polygon, const double z, const PolygonType & type); bool pushPolygon(const std::vector & polygon, const PolygonType & type); bool pushPolyhedron( - const autoware_universe_utils::Polygon2d & polyhedron, const double z_min, const double z_max, + const autoware::universe_utils::Polygon2d & polyhedron, const double z_min, const double z_max, const PolygonType & type); bool pushPolyhedron(const std::vector & polyhedron, const PolygonType & type); diff --git a/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp b/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp index 5474bb93fbf4b..b3afcded60438 100644 --- a/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp +++ b/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp @@ -50,9 +50,9 @@ namespace autoware::motion::control::predicted_path_checker using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; using TrajectoryPoints = std::vector; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::PredictedObjects; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; using geometry_msgs::msg::Pose; using geometry_msgs::msg::TransformStamped; @@ -88,7 +88,7 @@ class PredictedPathCheckerNode : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr group_cli_; // Subscriber - std::shared_ptr self_pose_listener_; + std::shared_ptr self_pose_listener_; rclcpp::Subscription::SharedPtr sub_dynamic_objects_; rclcpp::Subscription::SharedPtr sub_reference_trajectory_; diff --git a/control/predicted_path_checker/include/predicted_path_checker/utils.hpp b/control/predicted_path_checker/include/predicted_path_checker/utils.hpp index 05c7a5008db27..6f5c0e5cdb883 100644 --- a/control/predicted_path_checker/include/predicted_path_checker/utils.hpp +++ b/control/predicted_path_checker/include/predicted_path_checker/utils.hpp @@ -39,12 +39,12 @@ namespace utils { +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; using autoware::vehicle_info_utils::VehicleInfo; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; using autoware_planning_msgs::msg::TrajectoryPoint; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::TransformStamped; diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp index fb2eda3d04c33..7771f59d15454 100644 --- a/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp +++ b/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp @@ -80,12 +80,12 @@ CollisionChecker::checkTrajectoryForCollision( double distance_to_current = std::numeric_limits::max(); double distance_to_history = std::numeric_limits::max(); if (found_collision_at_dynamic_objects) { - distance_to_current = autoware_universe_utils::calcDistance2d( + distance_to_current = autoware::universe_utils::calcDistance2d( p_front, found_collision_at_dynamic_objects.get().first); } if (found_collision_at_history) { distance_to_history = - autoware_universe_utils::calcDistance2d(p_front, found_collision_at_history.get().first); + autoware::universe_utils::calcDistance2d(p_front, found_collision_at_history.get().first); } else { predicted_object_history_.clear(); } @@ -140,7 +140,7 @@ CollisionChecker::checkObstacleHistory( bool is_init = false; std::pair nearest_collision_object_with_point; for (const auto & p : collision_points_in_history) { - double norm = autoware_universe_utils::calcDistance2d(p.first, base_pose); + double norm = autoware::universe_utils::calcDistance2d(p.first, base_pose); if (norm < min_norm || !is_init) { min_norm = norm; nearest_collision_object_with_point = p; diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/debug_marker.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/debug_marker.cpp index bf74bf3c8bfc1..3fae5e38e7ede 100644 --- a/control/predicted_path_checker/src/predicted_path_checker_node/debug_marker.cpp +++ b/control/predicted_path_checker/src/predicted_path_checker_node/debug_marker.cpp @@ -28,15 +28,15 @@ #include #include -using autoware_motion_utils::createDeletedStopVirtualWallMarker; -using autoware_motion_utils::createStopVirtualWallMarker; -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerOrientation; -using autoware_universe_utils::createMarkerScale; -using autoware_universe_utils::createPoint; +using autoware::motion_utils::createDeletedStopVirtualWallMarker; +using autoware::motion_utils::createStopVirtualWallMarker; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerOrientation; +using autoware::universe_utils::createMarkerScale; +using autoware::universe_utils::createPoint; namespace autoware::motion::control::predicted_path_checker { @@ -51,7 +51,7 @@ PredictedPathCheckerDebugNode::PredictedPathCheckerDebugNode( } bool PredictedPathCheckerDebugNode::pushPolygon( - const autoware_universe_utils::Polygon2d & polygon, const double z, const PolygonType & type) + const autoware::universe_utils::Polygon2d & polygon, const double z, const PolygonType & type) { std::vector eigen_polygon; for (const auto & point : polygon.outer()) { @@ -82,7 +82,7 @@ bool PredictedPathCheckerDebugNode::pushPolygon( } bool PredictedPathCheckerDebugNode::pushPolyhedron( - const autoware_universe_utils::Polygon2d & polyhedron, const double z_min, const double z_max, + const autoware::universe_utils::Polygon2d & polyhedron, const double z_min, const double z_max, const PolygonType & type) { std::vector eigen_polyhedron; diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp index 524313181f36d..d8cf5c34bf535 100644 --- a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp +++ b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp @@ -67,7 +67,7 @@ PredictedPathCheckerNode::PredictedPathCheckerNode(const rclcpp::NodeOptions & n declare_parameter("collision_checker_params.chattering_threshold", 0.2); // Subscriber - self_pose_listener_ = std::make_shared(this); + self_pose_listener_ = std::make_shared(this); sub_dynamic_objects_ = create_subscription( "~/input/objects", rclcpp::SensorDataQoS(), @@ -242,8 +242,8 @@ void PredictedPathCheckerNode::onTimer() // Convert to trajectory array TrajectoryPoints predicted_trajectory_array = - autoware_motion_utils::convertToTrajectoryPointArray( - autoware_motion_utils::resampleTrajectory(cut_trajectory, node_param_.resample_interval)); + autoware::motion_utils::convertToTrajectoryPointArray( + autoware::motion_utils::resampleTrajectory(cut_trajectory, node_param_.resample_interval)); // Filter the objects @@ -323,7 +323,7 @@ void PredictedPathCheckerNode::onTimer() // trajectory or not const auto reference_trajectory_array = - autoware_motion_utils::convertToTrajectoryPointArray(*reference_trajectory_); + autoware::motion_utils::convertToTrajectoryPointArray(*reference_trajectory_); const auto is_discrete_point = isItDiscretePoint(reference_trajectory_array, predicted_trajectory_array.at(stop_idx)); @@ -368,7 +368,7 @@ TrajectoryPoints PredictedPathCheckerNode::trimTrajectoryFromSelfPose( TrajectoryPoints output{}; const size_t min_distance_index = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( input, self_pose, node_param_.ego_nearest_dist_threshold, node_param_.ego_nearest_yaw_threshold) + 1; @@ -387,9 +387,9 @@ bool PredictedPathCheckerNode::isThereStopPointOnReferenceTrajectory( trimTrajectoryFromSelfPose(reference_trajectory_array, current_pose_.get()->pose); const auto nearest_stop_point_on_ref_trajectory = - autoware_motion_utils::findNearestIndex(trimmed_reference_trajectory_array, pose); + autoware::motion_utils::findNearestIndex(trimmed_reference_trajectory_array, pose); - const auto stop_point_on_trajectory = autoware_motion_utils::searchZeroVelocityIndex( + const auto stop_point_on_trajectory = autoware::motion_utils::searchZeroVelocityIndex( trimmed_reference_trajectory_array, 0, *nearest_stop_point_on_ref_trajectory); return !!stop_point_on_trajectory; @@ -427,18 +427,18 @@ bool PredictedPathCheckerNode::isItDiscretePoint( const TrajectoryPoints & reference_trajectory, const TrajectoryPoint & collision_point) const { const auto nearest_segment = - autoware_motion_utils::findNearestSegmentIndex(reference_trajectory, collision_point.pose); + autoware::motion_utils::findNearestSegmentIndex(reference_trajectory, collision_point.pose); const auto nearest_point = utils::calcInterpolatedPoint( reference_trajectory, collision_point.pose.position, *nearest_segment, false); - const auto distance = autoware_universe_utils::calcDistance2d( + const auto distance = autoware::universe_utils::calcDistance2d( nearest_point.pose.position, collision_point.pose.position); const auto yaw_diff = - std::abs(autoware_universe_utils::calcYawDeviation(nearest_point.pose, collision_point.pose)); + std::abs(autoware::universe_utils::calcYawDeviation(nearest_point.pose, collision_point.pose)); return distance >= node_param_.distinct_point_distance_threshold || - yaw_diff >= autoware_universe_utils::deg2rad(node_param_.distinct_point_yaw_threshold); + yaw_diff >= autoware::universe_utils::deg2rad(node_param_.distinct_point_yaw_threshold); } Trajectory PredictedPathCheckerNode::cutTrajectory( @@ -454,8 +454,8 @@ Trajectory PredictedPathCheckerNode::cutTrajectory( for (size_t i = 1; i < trajectory.points.size(); ++i) { const auto & point = trajectory.points.at(i); - const auto p1 = autoware_universe_utils::fromMsg(cut.points.back().pose.position); - const auto p2 = autoware_universe_utils::fromMsg(point.pose.position); + const auto p1 = autoware::universe_utils::fromMsg(cut.points.back().pose.position); + const auto p2 = autoware::universe_utils::fromMsg(point.pose.position); const auto points_distance = boost::geometry::distance(p1.to_2d(), p2.to_2d()); const auto remain_distance = length - total_length; @@ -482,7 +482,7 @@ Trajectory PredictedPathCheckerNode::cutTrajectory( cut.points.push_back(point); total_length += points_distance; } - autoware_motion_utils::removeOverlapPoints(cut.points); + autoware::motion_utils::removeOverlapPoints(cut.points); return cut; } @@ -501,7 +501,7 @@ size_t PredictedPathCheckerNode::insertStopPoint( TrajectoryPoints & trajectory, const geometry_msgs::msg::Point collision_point) { const auto nearest_collision_segment = - autoware_motion_utils::findNearestSegmentIndex(trajectory, collision_point); + autoware::motion_utils::findNearestSegmentIndex(trajectory, collision_point); const auto nearest_collision_point = utils::calcInterpolatedPoint(trajectory, collision_point, nearest_collision_segment, true); @@ -528,7 +528,7 @@ std::pair PredictedPathCheckerNode::calculateProjectedVelAndAcc( const auto velocity_obj = object.kinematics.initial_twist_with_covariance.twist.linear.x; const auto acceleration_obj = object.kinematics.initial_acceleration_with_covariance.accel.linear.x; - const auto k = std::cos(autoware_universe_utils::normalizeRadian( + const auto k = std::cos(autoware::universe_utils::normalizeRadian( tf2::getYaw(orientation_obj) - tf2::getYaw(orientation_stop_point))); const auto projected_velocity = velocity_obj * k; const auto projected_acceleration = acceleration_obj * k; @@ -555,10 +555,10 @@ void PredictedPathCheckerNode::filterObstacles( // Check is it near to trajectory const double max_length = utils::calcObstacleMaxLength(object.shape); - const size_t seg_idx = autoware_motion_utils::findNearestSegmentIndex( + const size_t seg_idx = autoware::motion_utils::findNearestSegmentIndex( traj, object.kinematics.initial_pose_with_covariance.pose.position); - const auto p_front = autoware_universe_utils::getPoint(traj.at(seg_idx)); - const auto p_back = autoware_universe_utils::getPoint(traj.at(seg_idx + 1)); + const auto p_front = autoware::universe_utils::getPoint(traj.at(seg_idx)); + const auto p_back = autoware::universe_utils::getPoint(traj.at(seg_idx + 1)); const auto & p_target = object.kinematics.initial_pose_with_covariance.pose.position; const Eigen::Vector3d segment_vec{p_back.x - p_front.x, p_back.y - p_front.y, 0.0}; const Eigen::Vector3d target_vec{p_target.x - p_front.x, p_target.y - p_front.y, 0.0}; diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp index 0f4cc202f5c02..d750f3aa07248 100644 --- a/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp +++ b/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp @@ -21,10 +21,10 @@ namespace utils { -using autoware_motion_utils::findFirstNearestIndexWithSoftConstraints; -using autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints; -using autoware_universe_utils::calcDistance2d; -using autoware_universe_utils::getRPY; +using autoware::motion_utils::findFirstNearestIndexWithSoftConstraints; +using autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints; +using autoware::universe_utils::calcDistance2d; +using autoware::universe_utils::getRPY; // Utils Functions Polygon2d createOneStepPolygon( @@ -40,40 +40,40 @@ Polygon2d createOneStepPolygon( { // base step appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(base_step_pose, longitudinal_offset, width, 0.0) + autoware::universe_utils::calcOffsetPose(base_step_pose, longitudinal_offset, width, 0.0) .position); appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(base_step_pose, longitudinal_offset, -width, 0.0) + autoware::universe_utils::calcOffsetPose(base_step_pose, longitudinal_offset, -width, 0.0) .position); appendPointToPolygon( - polygon, autoware_universe_utils::calcOffsetPose(base_step_pose, -rear_overhang, -width, 0.0) + polygon, autoware::universe_utils::calcOffsetPose(base_step_pose, -rear_overhang, -width, 0.0) .position); appendPointToPolygon( - polygon, - autoware_universe_utils::calcOffsetPose(base_step_pose, -rear_overhang, width, 0.0).position); + polygon, autoware::universe_utils::calcOffsetPose(base_step_pose, -rear_overhang, width, 0.0) + .position); } { // next step appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(next_step_pose, longitudinal_offset, width, 0.0) + autoware::universe_utils::calcOffsetPose(next_step_pose, longitudinal_offset, width, 0.0) .position); appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(next_step_pose, longitudinal_offset, -width, 0.0) + autoware::universe_utils::calcOffsetPose(next_step_pose, longitudinal_offset, -width, 0.0) .position); appendPointToPolygon( - polygon, autoware_universe_utils::calcOffsetPose(next_step_pose, -rear_overhang, -width, 0.0) + polygon, autoware::universe_utils::calcOffsetPose(next_step_pose, -rear_overhang, -width, 0.0) .position); appendPointToPolygon( - polygon, - autoware_universe_utils::calcOffsetPose(next_step_pose, -rear_overhang, width, 0.0).position); + polygon, autoware::universe_utils::calcOffsetPose(next_step_pose, -rear_overhang, width, 0.0) + .position); } - polygon = autoware_universe_utils::isClockwise(polygon) + polygon = autoware::universe_utils::isClockwise(polygon) ? polygon - : autoware_universe_utils::inverseClockwise(polygon); + : autoware::universe_utils::inverseClockwise(polygon); Polygon2d hull_polygon; boost::geometry::convex_hull(polygon, hull_polygon); @@ -97,8 +97,8 @@ TrajectoryPoint calcInterpolatedPoint( // Calculate interpolation ratio const auto & curr_pt = trajectory.at(segment_idx); const auto & next_pt = trajectory.at(segment_idx + 1); - const auto v1 = autoware_universe_utils::point2tfVector(curr_pt, next_pt); - const auto v2 = autoware_universe_utils::point2tfVector(curr_pt, target_point); + const auto v1 = autoware::universe_utils::point2tfVector(curr_pt, next_pt); + const auto v2 = autoware::universe_utils::point2tfVector(curr_pt, target_point); if (v1.length2() < 1e-3) { return curr_pt; } @@ -111,7 +111,7 @@ TrajectoryPoint calcInterpolatedPoint( // pose interpolation interpolated_point.pose = - autoware_universe_utils::calcInterpolatedPose(curr_pt, next_pt, clamped_ratio); + autoware::universe_utils::calcInterpolatedPose(curr_pt, next_pt, clamped_ratio); // twist interpolation if (use_zero_order_hold_for_twist) { @@ -160,7 +160,7 @@ std::pair findStopPoint( for (size_t i = collision_idx; i > 0; i--) { distance_point_to_collision = - autoware_motion_utils::calcSignedArcLength(trajectory_array, i - 1, collision_idx); + autoware::motion_utils::calcSignedArcLength(trajectory_array, i - 1, collision_idx); if (distance_point_to_collision >= desired_distance_base_link_to_collision) { stop_segment_idx = i - 1; found_stop_point = true; @@ -176,8 +176,8 @@ std::pair findStopPoint( base_point.pose.position.x - next_point.pose.position.x, base_point.pose.position.y - next_point.pose.position.y)); - geometry_msgs::msg::Pose interpolated_pose = - autoware_universe_utils::calcInterpolatedPose(base_point.pose, next_point.pose, ratio, false); + geometry_msgs::msg::Pose interpolated_pose = autoware::universe_utils::calcInterpolatedPose( + base_point.pose, next_point.pose, ratio, false); TrajectoryPoint output; output.set__pose(interpolated_pose); return std::make_pair(stop_segment_idx, output); @@ -196,7 +196,7 @@ bool isInBrakeDistance( return false; } - const auto distance_to_obstacle = autoware_motion_utils::calcSignedArcLength( + const auto distance_to_obstacle = autoware::motion_utils::calcSignedArcLength( trajectory, trajectory.front().pose.position, trajectory.at(stop_idx).pose.position); const double distance_in_delay = relative_velocity * delay_time_sec + @@ -249,7 +249,7 @@ double getNearestPointAndDistanceForPredictedObject( bool is_init = false; for (const auto & p : points) { - double norm = autoware_universe_utils::calcDistance2d(p, base_pose); + double norm = autoware::universe_utils::calcDistance2d(p, base_pose); if (norm < min_norm || !is_init) { min_norm = norm; *nearest_collision_point = p; @@ -371,7 +371,7 @@ Polygon2d convertObjToPolygon(const PredictedObject & obj) bool isFrontObstacle(const Pose & ego_pose, const geometry_msgs::msg::Point & obstacle_pos) { - const auto yaw = autoware_universe_utils::getRPY(ego_pose).z; + const auto yaw = autoware::universe_utils::getRPY(ego_pose).z; const Eigen::Vector2d base_pose_vec(std::cos(yaw), std::sin(yaw)); const Eigen::Vector2d obstacle_vec( obstacle_pos.x - ego_pose.position.x, obstacle_pos.y - ego_pose.position.y); @@ -403,7 +403,7 @@ void getCurrentObjectPose( PredictedObject & predicted_object, const rclcpp::Time & obj_base_time, const rclcpp::Time & current_time) { - const double yaw = autoware_universe_utils::getRPY( + const double yaw = autoware::universe_utils::getRPY( predicted_object.kinematics.initial_pose_with_covariance.pose.orientation) .z; const double vx = predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x; @@ -414,8 +414,8 @@ void getCurrentObjectPose( const double delta_yaw = predicted_object.kinematics.initial_twist_with_covariance.twist.angular.z * dt; geometry_msgs::msg::Transform transform; - transform.translation = autoware_universe_utils::createTranslation(ds, 0.0, 0.0); - transform.rotation = autoware_universe_utils::createQuaternionFromRPY(0.0, 0.0, yaw); + transform.translation = autoware::universe_utils::createTranslation(ds, 0.0, 0.0); + transform.rotation = autoware::universe_utils::createQuaternionFromRPY(0.0, 0.0, yaw); tf2::Transform tf_pose; tf2::Transform tf_offset; @@ -424,8 +424,8 @@ void getCurrentObjectPose( tf2::toMsg(tf_pose * tf_offset, predicted_object.kinematics.initial_pose_with_covariance.pose); predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x += ax * dt; predicted_object.kinematics.initial_pose_with_covariance.pose.orientation = - autoware_universe_utils::createQuaternionFromRPY( - 0.0, 0.0, autoware_universe_utils::normalizeRadian(yaw + delta_yaw)); + autoware::universe_utils::createQuaternionFromRPY( + 0.0, 0.0, autoware::universe_utils::normalizeRadian(yaw + delta_yaw)); } } // namespace utils diff --git a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp index efeb068fca115..279bada80e1b9 100644 --- a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp +++ b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp @@ -72,9 +72,9 @@ class controlEvaluatorNode : public rclcpp::Node // onDiagnostics(). rclcpp::Subscription::SharedPtr control_diag_sub_; - autoware_universe_utils::InterProcessPollingSubscriber odometry_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber odometry_sub_{ this, "~/input/odometry"}; - autoware_universe_utils::InterProcessPollingSubscriber traj_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber traj_sub_{ this, "~/input/trajectory"}; rclcpp::Publisher::SharedPtr metrics_pub_; diff --git a/evaluator/autoware_control_evaluator/src/metrics/deviation_metrics.cpp b/evaluator/autoware_control_evaluator/src/metrics/deviation_metrics.cpp index a0d8f4076dae4..689291da09f6d 100644 --- a/evaluator/autoware_control_evaluator/src/metrics/deviation_metrics.cpp +++ b/evaluator/autoware_control_evaluator/src/metrics/deviation_metrics.cpp @@ -26,15 +26,16 @@ using autoware_planning_msgs::msg::Trajectory; double calcLateralDeviation(const Trajectory & traj, const Point & point) { - const size_t nearest_index = autoware_motion_utils::findNearestIndex(traj.points, point); + const size_t nearest_index = autoware::motion_utils::findNearestIndex(traj.points, point); return std::abs( - autoware_universe_utils::calcLateralDeviation(traj.points[nearest_index].pose, point)); + autoware::universe_utils::calcLateralDeviation(traj.points[nearest_index].pose, point)); } double calcYawDeviation(const Trajectory & traj, const Pose & pose) { - const size_t nearest_index = autoware_motion_utils::findNearestIndex(traj.points, pose.position); - return std::abs(autoware_universe_utils::calcYawDeviation(traj.points[nearest_index].pose, pose)); + const size_t nearest_index = autoware::motion_utils::findNearestIndex(traj.points, pose.position); + return std::abs( + autoware::universe_utils::calcYawDeviation(traj.points[nearest_index].pose, pose)); } } // namespace metrics diff --git a/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp index b7be356a7c522..8ce8a009652d8 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp @@ -38,8 +38,8 @@ Stat calcLateralDeviation(const Trajectory & ref, const Trajectory & tra */ for (TrajectoryPoint p : traj.points) { const size_t nearest_index = - autoware_motion_utils::findNearestIndex(ref.points, p.pose.position); - stat.add(autoware_universe_utils::calcLateralDeviation( + autoware::motion_utils::findNearestIndex(ref.points, p.pose.position); + stat.add(autoware::universe_utils::calcLateralDeviation( ref.points[nearest_index].pose, p.pose.position)); } return stat; @@ -58,8 +58,8 @@ Stat calcYawDeviation(const Trajectory & ref, const Trajectory & traj) */ for (TrajectoryPoint p : traj.points) { const size_t nearest_index = - autoware_motion_utils::findNearestIndex(ref.points, p.pose.position); - stat.add(autoware_universe_utils::calcYawDeviation(ref.points[nearest_index].pose, p.pose)); + autoware::motion_utils::findNearestIndex(ref.points, p.pose.position); + stat.add(autoware::universe_utils::calcYawDeviation(ref.points[nearest_index].pose, p.pose)); } return stat; } @@ -75,7 +75,7 @@ Stat calcVelocityDeviation(const Trajectory & ref, const Trajectory & tr // TODO(Maxime CLEMENT) need more precise calculation for (TrajectoryPoint p : traj.points) { const size_t nearest_index = - autoware_motion_utils::findNearestIndex(ref.points, p.pose.position); + autoware::motion_utils::findNearestIndex(ref.points, p.pose.position); stat.add(p.longitudinal_velocity_mps - ref.points[nearest_index].longitudinal_velocity_mps); } return stat; @@ -84,21 +84,21 @@ Stat calcVelocityDeviation(const Trajectory & ref, const Trajectory & tr Stat calcLongitudinalDeviation(const Pose & base_pose, const Point & target_point) { Stat stat; - stat.add(std::abs(autoware_universe_utils::calcLongitudinalDeviation(base_pose, target_point))); + stat.add(std::abs(autoware::universe_utils::calcLongitudinalDeviation(base_pose, target_point))); return stat; } Stat calcLateralDeviation(const Pose & base_pose, const Point & target_point) { Stat stat; - stat.add(std::abs(autoware_universe_utils::calcLateralDeviation(base_pose, target_point))); + stat.add(std::abs(autoware::universe_utils::calcLateralDeviation(base_pose, target_point))); return stat; } Stat calcYawDeviation(const Pose & base_pose, const Pose & target_pose) { Stat stat; - stat.add(std::abs(autoware_universe_utils::calcYawDeviation(base_pose, target_pose))); + stat.add(std::abs(autoware::universe_utils::calcYawDeviation(base_pose, target_pose))); return stat; } } // namespace metrics diff --git a/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp b/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp index 906501b05e171..e17cfd98b27da 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp @@ -20,9 +20,9 @@ namespace metrics { namespace utils { +using autoware::universe_utils::calcDistance2d; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; -using autoware_universe_utils::calcDistance2d; size_t getIndexAfterDistance(const Trajectory & traj, const size_t curr_id, const double distance) { diff --git a/evaluator/autoware_planning_evaluator/src/metrics/obstacle_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/obstacle_metrics.cpp index 7836b0b6d694a..3cdaf3d7eaaae 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/obstacle_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/obstacle_metrics.cpp @@ -27,8 +27,8 @@ namespace planning_diagnostics { namespace metrics { +using autoware::universe_utils::calcDistance2d; using autoware_planning_msgs::msg::TrajectoryPoint; -using autoware_universe_utils::calcDistance2d; Stat calcDistanceToObstacle(const PredictedObjects & obstacles, const Trajectory & traj) { diff --git a/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp index 874f2113b7500..4d1c02faa406f 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp @@ -41,7 +41,8 @@ Stat calcFrechetDistance(const Trajectory & traj1, const Trajectory & tr for (size_t i = 0; i < traj1.points.size(); ++i) { for (size_t j = 0; j < traj2.points.size(); ++j) { - const double dist = autoware_universe_utils::calcDistance2d(traj1.points[i], traj2.points[j]); + const double dist = + autoware::universe_utils::calcDistance2d(traj1.points[i], traj2.points[j]); if (i > 0 && j > 0) { ca(i, j) = std::max(std::min(ca(i - 1, j), std::min(ca(i - 1, j - 1), ca(i, j - 1))), dist); } else if (i > 0 /*&& j == 0*/) { @@ -64,29 +65,29 @@ Stat calcLateralDistance(const Trajectory & traj1, const Trajectory & tr return stat; } for (const auto & point : traj2.points) { - const auto p0 = autoware_universe_utils::getPoint(point); + const auto p0 = autoware::universe_utils::getPoint(point); // find nearest segment const size_t nearest_segment_idx = - autoware_motion_utils::findNearestSegmentIndex(traj1.points, p0); + autoware::motion_utils::findNearestSegmentIndex(traj1.points, p0); double dist; // distance to segment if ( nearest_segment_idx == traj1.points.size() - 2 && - autoware_motion_utils::calcLongitudinalOffsetToSegment( + autoware::motion_utils::calcLongitudinalOffsetToSegment( traj1.points, nearest_segment_idx, p0) > - autoware_universe_utils::calcDistance2d( + autoware::universe_utils::calcDistance2d( traj1.points[nearest_segment_idx], traj1.points[nearest_segment_idx + 1])) { // distance to last point - dist = autoware_universe_utils::calcDistance2d(traj1.points.back(), p0); + dist = autoware::universe_utils::calcDistance2d(traj1.points.back(), p0); } else if ( // NOLINT - nearest_segment_idx == 0 && autoware_motion_utils::calcLongitudinalOffsetToSegment( + nearest_segment_idx == 0 && autoware::motion_utils::calcLongitudinalOffsetToSegment( traj1.points, nearest_segment_idx, p0) <= 0) { // distance to first point - dist = autoware_universe_utils::calcDistance2d(traj1.points.front(), p0); + dist = autoware::universe_utils::calcDistance2d(traj1.points.front(), p0); } else { // orthogonal distance - const auto p1 = autoware_universe_utils::getPoint(traj1.points[nearest_segment_idx]); - const auto p2 = autoware_universe_utils::getPoint(traj1.points[nearest_segment_idx + 1]); + const auto p1 = autoware::universe_utils::getPoint(traj1.points[nearest_segment_idx]); + const auto p2 = autoware::universe_utils::getPoint(traj1.points[nearest_segment_idx + 1]); dist = std::abs((p2.x - p1.x) * (p1.y - p0.y) - (p1.x - p0.x) * (p2.y - p1.y)) / std::sqrt((p2.x - p1.x) * (p2.x - p1.x) + (p2.y - p1.y) * (p2.y - p1.y)); } diff --git a/evaluator/autoware_planning_evaluator/src/metrics/trajectory_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/trajectory_metrics.cpp index 3f33447c1ce6b..4526865ced97d 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/trajectory_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/trajectory_metrics.cpp @@ -20,8 +20,8 @@ namespace planning_diagnostics { namespace metrics { -using autoware_universe_utils::calcCurvature; -using autoware_universe_utils::calcDistance2d; +using autoware::universe_utils::calcCurvature; +using autoware::universe_utils::calcDistance2d; Stat calcTrajectoryInterval(const Trajectory & traj) { diff --git a/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp b/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp index d0e35fb24d534..8658a666b4976 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp @@ -123,7 +123,7 @@ Trajectory MetricsCalculator::getLookaheadTrajectory( } const auto ego_index = - autoware_motion_utils::findNearestSegmentIndex(traj.points, ego_pose_.position); + autoware::motion_utils::findNearestSegmentIndex(traj.points, ego_pose_.position); Trajectory lookahead_traj; lookahead_traj.header = traj.header; double dist = 0.0; @@ -132,7 +132,7 @@ Trajectory MetricsCalculator::getLookaheadTrajectory( auto prev_point_it = curr_point_it; while (curr_point_it != traj.points.end() && dist <= max_dist_m && time <= max_time_s) { lookahead_traj.points.push_back(*curr_point_it); - const auto d = autoware_universe_utils::calcDistance2d( + const auto d = autoware::universe_utils::calcDistance2d( prev_point_it->pose.position, curr_point_it->pose.position); dist += d; if (prev_point_it->longitudinal_velocity_mps != 0.0) { diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp index 2d60ef826a5e9..9c49605d944b5 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp +++ b/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp @@ -30,8 +30,8 @@ namespace marker_utils { +using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::PredictedObject; -using autoware_universe_utils::Polygon2d; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using std_msgs::msg::ColorRGBA; diff --git a/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp b/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp index 437e53dbbf1e4..5859bf055d4aa 100644 --- a/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp +++ b/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp @@ -24,7 +24,7 @@ namespace perception_diagnostics { namespace metrics { -using autoware_universe_utils::toHexString; +using autoware::universe_utils::toHexString; bool isCountObject( const std::uint8_t classification, const std::unordered_map & params) diff --git a/evaluator/perception_online_evaluator/src/metrics/deviation_metrics.cpp b/evaluator/perception_online_evaluator/src/metrics/deviation_metrics.cpp index ca9266ec6247b..d5ac88613fa83 100644 --- a/evaluator/perception_online_evaluator/src/metrics/deviation_metrics.cpp +++ b/evaluator/perception_online_evaluator/src/metrics/deviation_metrics.cpp @@ -31,9 +31,9 @@ double calcLateralDeviation(const std::vector & ref_path, const Pose & tar } const size_t nearest_index = - autoware_motion_utils::findNearestIndex(ref_path, target_pose.position); + autoware::motion_utils::findNearestIndex(ref_path, target_pose.position); return std::abs( - autoware_universe_utils::calcLateralDeviation(ref_path[nearest_index], target_pose.position)); + autoware::universe_utils::calcLateralDeviation(ref_path[nearest_index], target_pose.position)); } double calcYawDeviation(const std::vector & ref_path, const Pose & target_pose) @@ -43,8 +43,8 @@ double calcYawDeviation(const std::vector & ref_path, const Pose & target_ } const size_t nearest_index = - autoware_motion_utils::findNearestIndex(ref_path, target_pose.position); - return std::abs(autoware_universe_utils::calcYawDeviation(ref_path[nearest_index], target_pose)); + autoware::motion_utils::findNearestIndex(ref_path, target_pose.position); + return std::abs(autoware::universe_utils::calcYawDeviation(ref_path[nearest_index], target_pose)); } std::vector calcPredictedPathDeviation( @@ -56,9 +56,9 @@ std::vector calcPredictedPathDeviation( return {}; } for (const Pose & p : pred_path.path) { - const size_t nearest_index = autoware_motion_utils::findNearestIndex(ref_path, p.position); + const size_t nearest_index = autoware::motion_utils::findNearestIndex(ref_path, p.position); deviations.push_back( - autoware_universe_utils::calcDistance2d(ref_path[nearest_index].position, p.position)); + autoware::universe_utils::calcDistance2d(ref_path[nearest_index].position, p.position)); } return deviations; diff --git a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp index 8732de1fe3393..212af8711a62e 100644 --- a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp +++ b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp @@ -23,7 +23,7 @@ namespace perception_diagnostics { -using autoware_universe_utils::inverseTransformPoint; +using autoware::universe_utils::inverseTransformPoint; using object_recognition_utils::convertLabelToString; std::optional MetricsCalculator::calculate(const Metric & metric) const @@ -238,7 +238,7 @@ MetricStatMap MetricsCalculator::calcLateralDeviationMetrics( Stat stat{}; const auto stamp = rclcpp::Time(objects.header.stamp); for (const auto & object : objects.objects) { - const auto uuid = autoware_universe_utils::toHexString(object.object_id); + const auto uuid = autoware::universe_utils::toHexString(object.object_id); if (!hasPassedTime(uuid, stamp)) { continue; } @@ -267,7 +267,7 @@ MetricStatMap MetricsCalculator::calcYawDeviationMetrics( Stat stat{}; const auto stamp = rclcpp::Time(objects.header.stamp); for (const auto & object : objects.objects) { - const auto uuid = autoware_universe_utils::toHexString(object.object_id); + const auto uuid = autoware::universe_utils::toHexString(object.object_id); if (!hasPassedTime(uuid, stamp)) { continue; } @@ -326,7 +326,7 @@ PredictedPathDeviationMetrics MetricsCalculator::calcPredictedPathDeviationMetri const auto stamp = objects.header.stamp; for (const auto & object : objects.objects) { - const auto uuid = autoware_universe_utils::toHexString(object.object_id); + const auto uuid = autoware::universe_utils::toHexString(object.object_id); const auto predicted_paths = object.kinematics.predicted_paths; for (size_t i = 0; i < predicted_paths.size(); i++) { const auto predicted_path = predicted_paths[i]; @@ -350,7 +350,7 @@ PredictedPathDeviationMetrics MetricsCalculator::calcPredictedPathDeviationMetri const auto history_pose = history_object.kinematics.initial_pose_with_covariance.pose; const Pose & p = predicted_path.path[j]; const double distance = - autoware_universe_utils::calcDistance2d(p.position, history_pose.position); + autoware::universe_utils::calcDistance2d(p.position, history_pose.position); deviation_map_for_paths[uuid][i].push_back(distance); // Save debug information @@ -424,7 +424,7 @@ MetricStatMap MetricsCalculator::calcYawRateMetrics(const ClassObjectsMap & clas const auto stamp = rclcpp::Time(objects.header.stamp); for (const auto & object : objects.objects) { - const auto uuid = autoware_universe_utils::toHexString(object.object_id); + const auto uuid = autoware::universe_utils::toHexString(object.object_id); if (!hasPassedTime(uuid, stamp)) { continue; } @@ -444,7 +444,7 @@ MetricStatMap MetricsCalculator::calcYawRateMetrics(const ClassObjectsMap & clas tf2::getYaw(previous_object.kinematics.initial_pose_with_covariance.pose.orientation); // Calculate the absolute difference between current_yaw and previous_yaw const double yaw_diff = - std::abs(autoware_universe_utils::normalizeRadian(current_yaw - previous_yaw)); + std::abs(autoware::universe_utils::normalizeRadian(current_yaw - previous_yaw)); // The yaw difference is flipped if the angle is larger than 90 degrees const double yaw_diff_flip_fixed = std::min(yaw_diff, M_PI - yaw_diff); const double yaw_rate = yaw_diff_flip_fixed / time_diff; @@ -494,7 +494,7 @@ void MetricsCalculator::setPredictedObjects( // store objects to check deviation { - using autoware_universe_utils::toHexString; + using autoware::universe_utils::toHexString; for (const auto & object : objects.objects) { std::string uuid = toHexString(object.object_id); updateObjects(uuid, current_stamp_, object); @@ -557,7 +557,7 @@ void MetricsCalculator::updateHistoryPath() const auto current_pose = object.kinematics.initial_pose_with_covariance.pose; const auto prev_pose = prev_object.kinematics.initial_pose_with_covariance.pose; const auto velocity = - autoware_universe_utils::calcDistance2d(current_pose.position, prev_pose.position) / + autoware::universe_utils::calcDistance2d(current_pose.position, prev_pose.position) / time_diff; if (velocity < parameters_->stopped_velocity_threshold) { continue; @@ -603,9 +603,9 @@ std::vector MetricsCalculator::generateHistoryPathWithPrev( std::vector MetricsCalculator::averageFilterPath( const std::vector & path, const size_t window_size) const { - using autoware_universe_utils::calcAzimuthAngle; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::createQuaternionFromYaw; + using autoware::universe_utils::calcAzimuthAngle; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::createQuaternionFromYaw; std::vector filtered_path; filtered_path.reserve(path.size()); // Reserve space to avoid reallocations @@ -645,7 +645,7 @@ std::vector MetricsCalculator::averageFilterPath( if (i > 0) { const double azimuth = calcAzimuthAngle(path.at(i - 1).position, path.at(i).position); const double yaw = tf2::getYaw(path.at(i).orientation); - if (autoware_universe_utils::normalizeRadian(yaw - azimuth) > M_PI_2) { + if (autoware::universe_utils::normalizeRadian(yaw - azimuth) > M_PI_2) { continue; } } @@ -662,7 +662,7 @@ std::vector MetricsCalculator::averageFilterPath( const double azimuth_to_prev = calcAzimuthAngle((it - 2)->position, (it - 1)->position); const double azimuth_to_current = calcAzimuthAngle((it - 1)->position, it->position); if ( - std::abs(autoware_universe_utils::normalizeRadian(azimuth_to_prev - azimuth_to_current)) > + std::abs(autoware::universe_utils::normalizeRadian(azimuth_to_prev - azimuth_to_current)) > M_PI_2) { it = filtered_path.erase(it); continue; diff --git a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp index 56b79eb3acf62..63d635af4ffdf 100644 --- a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp @@ -156,7 +156,7 @@ void PerceptionOnlineEvaluatorNode::publishDebugMarker() for (auto & marker : added.markers) { marker.lifetime = rclcpp::Duration::from_seconds(1.5); } - autoware_universe_utils::appendMarkerArray(added, &marker); + autoware::universe_utils::appendMarkerArray(added, &marker); }; const auto & p = parameters_->debug_marker_parameters; @@ -236,7 +236,7 @@ void PerceptionOnlineEvaluatorNode::publishDebugMarker() rcl_interfaces::msg::SetParametersResult PerceptionOnlineEvaluatorNode::onParameter( const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; auto & p = parameters_; @@ -305,8 +305,8 @@ rcl_interfaces::msg::SetParametersResult PerceptionOnlineEvaluatorNode::onParame void PerceptionOnlineEvaluatorNode::initParameter() { - using autoware_universe_utils::getOrDeclareParameter; - using autoware_universe_utils::updateParam; + using autoware::universe_utils::getOrDeclareParameter; + using autoware::universe_utils::updateParam; auto & p = parameters_; diff --git a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp b/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp index 6085ea0b6ef49..a7a697c4efff6 100644 --- a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp +++ b/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp @@ -28,12 +28,12 @@ namespace marker_utils { -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerOrientation; -using autoware_universe_utils::createMarkerScale; -using autoware_universe_utils::createPoint; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerOrientation; +using autoware::universe_utils::createMarkerScale; +using autoware::universe_utils::createPoint; using std_msgs::msg::ColorRGBA; using visualization_msgs::msg::Marker; @@ -46,13 +46,13 @@ void addFootprintMarker( const double base_to_rear = vehicle_info.rear_overhang_m; marker.points.push_back( - autoware_universe_utils::calcOffsetPose(pose, base_to_front, -half_width, 0.0).position); + autoware::universe_utils::calcOffsetPose(pose, base_to_front, -half_width, 0.0).position); marker.points.push_back( - autoware_universe_utils::calcOffsetPose(pose, base_to_front, half_width, 0.0).position); + autoware::universe_utils::calcOffsetPose(pose, base_to_front, half_width, 0.0).position); marker.points.push_back( - autoware_universe_utils::calcOffsetPose(pose, -base_to_rear, half_width, 0.0).position); + autoware::universe_utils::calcOffsetPose(pose, -base_to_rear, half_width, 0.0).position); marker.points.push_back( - autoware_universe_utils::calcOffsetPose(pose, -base_to_rear, -half_width, 0.0).position); + autoware::universe_utils::calcOffsetPose(pose, -base_to_rear, -half_width, 0.0).position); marker.points.push_back(marker.points.front()); } @@ -167,7 +167,7 @@ std_msgs::msg::ColorRGBA createColorFromString(const std::string & str) const auto r = (hash & 0xFF) / 255.0; const auto g = ((hash >> 8) & 0xFF) / 255.0; const auto b = ((hash >> 16) & 0xFF) / 255.0; - return autoware_universe_utils::createMarkerColor(r, g, b, 0.5); + return autoware::universe_utils::createMarkerColor(r, g, b, 0.5); } MarkerArray createObjectPolygonMarkerArray( @@ -182,7 +182,7 @@ MarkerArray createObjectPolygonMarkerArray( const double z = object.kinematics.initial_pose_with_covariance.pose.position.z; const double height = object.shape.dimensions.z; - const auto polygon = autoware_universe_utils::toPolygon2d( + const auto polygon = autoware::universe_utils::toPolygon2d( object.kinematics.initial_pose_with_covariance.pose, object.shape); for (const auto & p : polygon.outer()) { marker.points.push_back(createPoint(p.x(), p.y(), z - height / 2)); diff --git a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp index a369d36882c9d..e2ab22be2b61b 100644 --- a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp @@ -43,7 +43,7 @@ using ObjectClassification = autoware_perception_msgs::msg::ObjectClassification using nav_msgs::msg::Odometry; using TFMessage = tf2_msgs::msg::TFMessage; -using autoware_universe_utils::generateUUID; +using autoware::universe_utils::generateUUID; constexpr double epsilon = 1e-6; diff --git a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/src/ar_tag_based_localizer.cpp b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/src/ar_tag_based_localizer.cpp index f8781ada3d38d..c39969fb3cc5f 100644 --- a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/src/ar_tag_based_localizer.cpp +++ b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/src/ar_tag_based_localizer.cpp @@ -185,7 +185,7 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg) pose_array_msg.header.frame_id = "map"; for (const Landmark & landmark : landmarks) { const Pose detected_marker_on_map = - autoware_universe_utils::transformPose(landmark.pose, self_pose); + autoware::universe_utils::transformPose(landmark.pose, self_pose); pose_array_msg.poses.push_back(detected_marker_on_map); } detected_tag_pose_pub_->publish(pose_array_msg); @@ -194,7 +194,7 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg) // calc new_self_pose const Pose new_self_pose = landmark_manager_.calculate_new_self_pose(landmarks, self_pose, consider_orientation_); - const Pose diff_pose = autoware_universe_utils::inverseTransformPose(new_self_pose, self_pose); + const Pose diff_pose = autoware::universe_utils::inverseTransformPose(new_self_pose, self_pose); const double distance = std::hypot(diff_pose.position.x, diff_pose.position.y, diff_pose.position.z); diff --git a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/src/landmark_manager.cpp b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/src/landmark_manager.cpp index b2c4a7dd6298a..2fa0fdbdb315d 100644 --- a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/src/landmark_manager.cpp +++ b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/src/landmark_manager.cpp @@ -161,7 +161,7 @@ geometry_msgs::msg::Pose LandmarkManager::calculate_new_self_pose( // convert base_link to map const Pose detected_landmark_on_map = - autoware_universe_utils::transformPose(detected_landmark_on_base_link, self_pose); + autoware::universe_utils::transformPose(detected_landmark_on_base_link, self_pose); // match to map if (landmarks_map_.count(landmark.id) == 0) { @@ -171,7 +171,7 @@ geometry_msgs::msg::Pose LandmarkManager::calculate_new_self_pose( // check all poses for (const Pose mapped_landmark_on_map : landmarks_map_.at(landmark.id)) { // check distance - const double curr_distance = autoware_universe_utils::calcDistance3d( + const double curr_distance = autoware::universe_utils::calcDistance3d( mapped_landmark_on_map.position, detected_landmark_on_map.position); if (curr_distance > min_distance) { continue; diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index ce1d7a95178ee..65003f5fe9864 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -142,7 +142,7 @@ class EKFLocalizer : public rclcpp::Node std::shared_ptr tf_br_; //!< @brief logger configure module - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; //!< @brief extended kalman filter instance. std::unique_ptr ekf_module_; @@ -236,7 +236,7 @@ class EKFLocalizer : public rclcpp::Node const std_srvs::srv::SetBool::Request::SharedPtr req, std_srvs::srv::SetBool::Response::SharedPtr res); - autoware_universe_utils::StopWatch stop_watch_; + autoware::universe_utils::StopWatch stop_watch_; friend class EKFLocalizerTestSuite; // for test code }; diff --git a/localization/ekf_localizer/src/covariance.cpp b/localization/ekf_localizer/src/covariance.cpp index 4e68de981e196..4655ea8a89855 100644 --- a/localization/ekf_localizer/src/covariance.cpp +++ b/localization/ekf_localizer/src/covariance.cpp @@ -17,7 +17,7 @@ #include "autoware/universe_utils/ros/msg_covariance.hpp" #include "ekf_localizer/state_index.hpp" -using COV_IDX = autoware_universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; +using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; std::array ekf_covariance_to_pose_message_covariance(const Matrix6d & P) { diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 5400c0a70b6f3..11fa2b6713a52 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -96,7 +96,7 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options) std::shared_ptr(this, [](auto) {})); ekf_module_ = std::make_unique(warning_, params_); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); z_filter_.set_proc_dev(params_.z_filter_proc_dev); roll_filter_.set_proc_dev(params_.roll_filter_proc_dev); @@ -264,7 +264,7 @@ void EKFLocalizer::timer_tf_callback() const rclcpp::Time current_time = this->now(); geometry_msgs::msg::TransformStamped transform_stamped; - transform_stamped = autoware_universe_utils::pose2transform( + transform_stamped = autoware::universe_utils::pose2transform( ekf_module_->get_current_pose(current_time, z, roll, pitch, false), "base_link"); transform_stamped.header.stamp = current_time; tf_br_->sendTransform(transform_stamped); @@ -436,9 +436,9 @@ void EKFLocalizer::update_simple_1d_filters( { double z = pose.pose.pose.position.z; - const auto rpy = autoware_universe_utils::getRPY(pose.pose.pose.orientation); + const auto rpy = autoware::universe_utils::getRPY(pose.pose.pose.orientation); - using COV_IDX = autoware_universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; double z_dev = pose.pose.covariance[COV_IDX::Z_Z] * static_cast(smoothing_step); double roll_dev = pose.pose.covariance[COV_IDX::ROLL_ROLL] * static_cast(smoothing_step); double pitch_dev = @@ -454,9 +454,9 @@ void EKFLocalizer::init_simple_1d_filters( { double z = pose.pose.pose.position.z; - const auto rpy = autoware_universe_utils::getRPY(pose.pose.pose.orientation); + const auto rpy = autoware::universe_utils::getRPY(pose.pose.pose.orientation); - using COV_IDX = autoware_universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; double z_dev = pose.pose.covariance[COV_IDX::Z_Z]; double roll_dev = pose.pose.covariance[COV_IDX::ROLL_ROLL]; double pitch_dev = pose.pose.covariance[COV_IDX::PITCH_PITCH]; diff --git a/localization/ekf_localizer/src/ekf_module.cpp b/localization/ekf_localizer/src/ekf_module.cpp index 82e01f6b81065..ba6b7dedca82c 100644 --- a/localization/ekf_localizer/src/ekf_module.cpp +++ b/localization/ekf_localizer/src/ekf_module.cpp @@ -65,7 +65,7 @@ void EKFModule::initialize( x(IDX::VX) = 0.0; x(IDX::WZ) = 0.0; - using COV_IDX = autoware_universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; p(IDX::X, IDX::X) = initial_pose.pose.covariance[COV_IDX::X_X]; p(IDX::Y, IDX::Y) = initial_pose.pose.covariance[COV_IDX::Y_Y]; p(IDX::YAW, IDX::YAW) = initial_pose.pose.covariance[COV_IDX::YAW_YAW]; @@ -97,13 +97,13 @@ geometry_msgs::msg::PoseStamped EKFModule::get_current_pose( Pose current_ekf_pose; current_ekf_pose.header.frame_id = params_.pose_frame_id; current_ekf_pose.header.stamp = current_time; - current_ekf_pose.pose.position = autoware_universe_utils::createPoint(x, y, z); + current_ekf_pose.pose.position = autoware::universe_utils::createPoint(x, y, z); if (get_biased_yaw) { current_ekf_pose.pose.orientation = - autoware_universe_utils::createQuaternionFromRPY(roll, pitch, biased_yaw); + autoware::universe_utils::createQuaternionFromRPY(roll, pitch, biased_yaw); } else { current_ekf_pose.pose.orientation = - autoware_universe_utils::createQuaternionFromRPY(roll, pitch, yaw); + autoware::universe_utils::createQuaternionFromRPY(roll, pitch, yaw); } return current_ekf_pose; } @@ -285,7 +285,7 @@ bool EKFModule::measurement_update_pose( geometry_msgs::msg::PoseWithCovarianceStamped EKFModule::compensate_pose_with_z_delay( const PoseWithCovariance & pose, const double delay_time) { - const auto rpy = autoware_universe_utils::getRPY(pose.pose.pose.orientation); + const auto rpy = autoware::universe_utils::getRPY(pose.pose.pose.orientation); const double dz_delay = kalman_filter_.getXelement(IDX::VX) * delay_time * std::sin(-rpy.y); PoseWithCovariance pose_with_z_delay; pose_with_z_delay = pose; diff --git a/localization/ekf_localizer/src/measurement.cpp b/localization/ekf_localizer/src/measurement.cpp index fbc177d602ff0..faf8768938b7d 100644 --- a/localization/ekf_localizer/src/measurement.cpp +++ b/localization/ekf_localizer/src/measurement.cpp @@ -38,7 +38,7 @@ Eigen::Matrix3d pose_measurement_covariance( const std::array & covariance, const size_t smoothing_step) { Eigen::Matrix3d r; - using COV_IDX = autoware_universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; r << covariance.at(COV_IDX::X_X), covariance.at(COV_IDX::X_Y), covariance.at(COV_IDX::X_YAW), covariance.at(COV_IDX::Y_X), covariance.at(COV_IDX::Y_Y), covariance.at(COV_IDX::Y_YAW), covariance.at(COV_IDX::YAW_X), covariance.at(COV_IDX::YAW_Y), covariance.at(COV_IDX::YAW_YAW); @@ -49,7 +49,7 @@ Eigen::Matrix2d twist_measurement_covariance( const std::array & covariance, const size_t smoothing_step) { Eigen::Matrix2d r; - using COV_IDX = autoware_universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; r << covariance.at(COV_IDX::X_X), covariance.at(COV_IDX::X_YAW), covariance.at(COV_IDX::YAW_X), covariance.at(COV_IDX::YAW_YAW); return r * static_cast(smoothing_step); diff --git a/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp b/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp index eb1db06b72998..f1f7214c3b848 100644 --- a/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp +++ b/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp @@ -43,7 +43,7 @@ namespace autoware::gyro_odometer class GyroOdometerNode : public rclcpp::Node { private: - using COV_IDX = autoware_universe_utils::xyz_covariance_index::XYZ_COV_IDX; + using COV_IDX = autoware::universe_utils::xyz_covariance_index::XYZ_COV_IDX; public: explicit GyroOdometerNode(const rclcpp::NodeOptions & node_options); @@ -67,8 +67,8 @@ class GyroOdometerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr twist_with_covariance_pub_; - std::shared_ptr transform_listener_; - std::unique_ptr logger_configure_; + std::shared_ptr transform_listener_; + std::unique_ptr logger_configure_; std::string output_frame_; double message_timeout_sec_; diff --git a/localization/gyro_odometer/src/gyro_odometer_core.cpp b/localization/gyro_odometer/src/gyro_odometer_core.cpp index 0878c44ffa2cb..c661f63d91535 100644 --- a/localization/gyro_odometer/src/gyro_odometer_core.cpp +++ b/localization/gyro_odometer/src/gyro_odometer_core.cpp @@ -33,7 +33,7 @@ namespace autoware::gyro_odometer std::array transform_covariance(const std::array & cov) { - using COV_IDX = autoware_universe_utils::xyz_covariance_index::XYZ_COV_IDX; + using COV_IDX = autoware::universe_utils::xyz_covariance_index::XYZ_COV_IDX; double max_cov = std::max({cov[COV_IDX::X_X], cov[COV_IDX::Y_Y], cov[COV_IDX::Z_Z]}); @@ -52,8 +52,8 @@ GyroOdometerNode::GyroOdometerNode(const rclcpp::NodeOptions & node_options) vehicle_twist_arrived_(false), imu_arrived_(false) { - transform_listener_ = std::make_shared(this); - logger_configure_ = std::make_unique(this); + transform_listener_ = std::make_shared(this); + logger_configure_ = std::make_unique(this); vehicle_twist_sub_ = create_subscription( "vehicle/twist_with_covariance", rclcpp::QoS{100}, @@ -208,8 +208,8 @@ void GyroOdometerNode::concat_gyro_and_odometer() gyro.angular_velocity_covariance = transform_covariance(gyro.angular_velocity_covariance); } - using COV_IDX_XYZ = autoware_universe_utils::xyz_covariance_index::XYZ_COV_IDX; - using COV_IDX_XYZRPY = autoware_universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + using COV_IDX_XYZ = autoware::universe_utils::xyz_covariance_index::XYZ_COV_IDX; + using COV_IDX_XYZRPY = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; // calc mean, covariance double vx_mean = 0; diff --git a/localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp b/localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp index 12f0a1141d199..a178a305f6d12 100644 --- a/localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp +++ b/localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp @@ -43,7 +43,7 @@ class LocalizationErrorMonitor : public rclcpp::Node rclcpp::TimerBase::SharedPtr timer_; - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; double scale_; double error_ellipse_size_; diff --git a/localization/localization_error_monitor/src/localization_error_monitor.cpp b/localization/localization_error_monitor/src/localization_error_monitor.cpp index 51fc1607d048a..204afa7bdec2f 100644 --- a/localization/localization_error_monitor/src/localization_error_monitor.cpp +++ b/localization/localization_error_monitor/src/localization_error_monitor.cpp @@ -55,7 +55,7 @@ LocalizationErrorMonitor::LocalizationErrorMonitor(const rclcpp::NodeOptions & o diag_pub_ = this->create_publisher("/diagnostics", 10); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); } visualization_msgs::msg::Marker LocalizationErrorMonitor::create_ellipse_marker( diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp index 5a28ed7eb8a5e..2f3eb82b1c217 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -203,7 +203,7 @@ class NDTScanMatcher : public rclcpp::Node std::unique_ptr diagnostics_ndt_align_; std::unique_ptr diagnostics_trigger_node_; std::unique_ptr map_update_module_; - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; HyperParameters param_; }; diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index a6e46bb4919eb..ca486a320d9dc 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -210,7 +210,7 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) diagnostics_trigger_node_ = std::make_unique(this, "trigger_node_service_status"); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); } void NDTScanMatcher::callback_timer() @@ -615,7 +615,7 @@ bool NDTScanMatcher::callback_sensor_points_main( pcl::shared_ptr> sensor_points_in_map_ptr( new pcl::PointCloud); - autoware_universe_utils::transformPointCloud( + autoware::universe_utils::transformPointCloud( *sensor_points_in_baselink_frame, *sensor_points_in_map_ptr, ndt_result.pose); publish_point_cloud(sensor_ros_time, param_.frame.map_frame, sensor_points_in_map_ptr); @@ -671,10 +671,10 @@ void NDTScanMatcher::transform_sensor_measurement( } const geometry_msgs::msg::PoseStamped target_to_source_pose_stamped = - autoware_universe_utils::transform2pose(transform); + autoware::universe_utils::transform2pose(transform); const Eigen::Matrix4f base_to_sensor_matrix = pose_to_matrix4f(target_to_source_pose_stamped.pose); - autoware_universe_utils::transformPointCloud( + autoware::universe_utils::transformPointCloud( *sensor_points_input_ptr, *sensor_points_output_ptr, base_to_sensor_matrix); } @@ -686,7 +686,7 @@ void NDTScanMatcher::publish_tf( result_pose_stamped_msg.header.frame_id = param_.frame.map_frame; result_pose_stamped_msg.pose = result_pose_msg; tf2_broadcaster_.sendTransform( - autoware_universe_utils::pose2transform(result_pose_stamped_msg, param_.frame.ndt_base_frame)); + autoware::universe_utils::pose2transform(result_pose_stamped_msg, param_.frame.ndt_base_frame)); } void NDTScanMatcher::publish_pose( @@ -730,7 +730,7 @@ void NDTScanMatcher::publish_marker( marker.header.frame_id = param_.frame.map_frame; marker.type = visualization_msgs::msg::Marker::ARROW; marker.action = visualization_msgs::msg::Marker::ADD; - marker.scale = autoware_universe_utils::createMarkerScale(0.3, 0.1, 0.1); + marker.scale = autoware::universe_utils::createMarkerScale(0.3, 0.1, 0.1); int i = 0; marker.ns = "result_pose_matrix_array"; marker.action = visualization_msgs::msg::Marker::ADD; @@ -759,7 +759,7 @@ void NDTScanMatcher::publish_initial_to_result( { geometry_msgs::msg::PoseStamped initial_to_result_relative_pose_stamped; initial_to_result_relative_pose_stamped.pose = - autoware_universe_utils::inverseTransformPose(result_pose_msg, initial_pose_cov_msg.pose.pose); + autoware::universe_utils::inverseTransformPose(result_pose_msg, initial_pose_cov_msg.pose.pose); initial_to_result_relative_pose_stamped.header.stamp = sensor_ros_time; initial_to_result_relative_pose_stamped.header.frame_id = param_.frame.map_frame; initial_to_result_relative_pose_pub_->publish(initial_to_result_relative_pose_stamped); @@ -1091,7 +1091,7 @@ geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_pose( tpe.add_trial(TreeStructuredParzenEstimator::Trial{result, ndt_result.transform_probability}); auto sensor_points_in_map_ptr = std::make_shared>(); - autoware_universe_utils::transformPointCloud( + autoware::universe_utils::transformPointCloud( *ndt_ptr_->getInputSource(), *sensor_points_in_map_ptr, ndt_result.pose); publish_point_cloud( initial_pose_with_cov.header.stamp, param_.frame.map_frame, sensor_points_in_map_ptr); diff --git a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.cpp b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.cpp index 0866234383727..3a565e7f2e4df 100644 --- a/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.cpp +++ b/localization/pose_estimator_arbiter/example_rule/src/pose_estimator_arbiter/switch_rule/pcd_map_based_rule.cpp @@ -28,9 +28,9 @@ PcdMapBasedRule::PcdMapBasedRule( shared_data_(std::move(shared_data)) { const int pcd_density_upper_threshold = - autoware_universe_utils::getOrDeclareParameter(node, "pcd_density_upper_threshold"); + autoware::universe_utils::getOrDeclareParameter(node, "pcd_density_upper_threshold"); const int pcd_density_lower_threshold = - autoware_universe_utils::getOrDeclareParameter(node, "pcd_density_lower_threshold"); + autoware::universe_utils::getOrDeclareParameter(node, "pcd_density_lower_threshold"); pcd_occupancy_ = std::make_unique( pcd_density_upper_threshold, pcd_density_lower_threshold); diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter.hpp b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter.hpp index 4228ade6be701..013b4b38f9ef6 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter.hpp +++ b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter.hpp @@ -53,7 +53,7 @@ class PoseEstimatorArbiter : public rclcpp::Node // Set of running pose estimators specified by ros param `pose_sources` const std::unordered_set running_estimator_list_; // Configuration to allow changing the log level by service - const std::unique_ptr logger_configure_; + const std::unique_ptr logger_configure_; // This is passed to several modules (stoppers & rule) so that all modules can access common data // without passing them as arguments. Also, modules can register subscriber callbacks through diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_core.cpp b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_core.cpp index 4d655875ba325..8e25628d6e0fc 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_core.cpp +++ b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_core.cpp @@ -46,7 +46,7 @@ PoseEstimatorArbiter::PoseEstimatorArbiter(const rclcpp::NodeOptions & options) : rclcpp::Node("pose_estimator_arbiter", options), running_estimator_list_(parse_estimator_name_args( declare_parameter>("pose_sources"), get_logger())), - logger_configure_(std::make_unique(this)) + logger_configure_(std::make_unique(this)) { // Shared data shared_data_ = std::make_shared(); diff --git a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp index 1e351f8a90d7b..7d75a1fc80f2e 100644 --- a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp +++ b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp @@ -56,7 +56,7 @@ PoseInitializer::PoseInitializer(const rclcpp::NodeOptions & options) stop_check_duration_ = declare_parameter("stop_check_duration"); stop_check_ = std::make_unique(this, stop_check_duration_ + 1.0); } - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); change_state(State::Message::UNINITIALIZED); diff --git a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp index 3a0896a07ba98..a813ec6459810 100644 --- a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp +++ b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp @@ -55,7 +55,7 @@ class PoseInitializer : public rclcpp::Node std::unique_ptr stop_check_; std::unique_ptr ekf_localization_trigger_; std::unique_ptr ndt_localization_trigger_; - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; double stop_check_duration_; void change_node_trigger(bool flag, bool need_spin = false); diff --git a/localization/pose_initializer/src/pose_initializer/stop_check_module.hpp b/localization/pose_initializer/src/pose_initializer/stop_check_module.hpp index 140fb3079de45..31f04029bd00e 100644 --- a/localization/pose_initializer/src/pose_initializer/stop_check_module.hpp +++ b/localization/pose_initializer/src/pose_initializer/stop_check_module.hpp @@ -21,7 +21,7 @@ #include #include -class StopCheckModule : public autoware_motion_utils::VehicleStopCheckerBase +class StopCheckModule : public autoware::motion_utils::VehicleStopCheckerBase { public: StopCheckModule(rclcpp::Node * node, double buffer_duration); diff --git a/localization/pose_instability_detector/src/pose_instability_detector.cpp b/localization/pose_instability_detector/src/pose_instability_detector.cpp index 436fd4eee7692..28398588809eb 100644 --- a/localization/pose_instability_detector/src/pose_instability_detector.cpp +++ b/localization/pose_instability_detector/src/pose_instability_detector.cpp @@ -123,7 +123,7 @@ void PoseInstabilityDetector::callback_timer() // compare dead reckoning pose and latest_odometry_ const Pose latest_ekf_pose = latest_odometry_->pose.pose; - const Pose ekf_to_dr = autoware_universe_utils::inverseTransformPose(*dr_pose, latest_ekf_pose); + const Pose ekf_to_dr = autoware::universe_utils::inverseTransformPose(*dr_pose, latest_ekf_pose); const geometry_msgs::msg::Point pos = ekf_to_dr.position; const auto [ang_x, ang_y, ang_z] = quat_to_rpy(ekf_to_dr.orientation); const std::vector values = {pos.x, pos.y, pos.z, ang_x, ang_y, ang_z}; diff --git a/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp b/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp index aa0244e5d7e90..3ea23ded92efa 100644 --- a/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp +++ b/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp @@ -198,7 +198,7 @@ Ll2Decomposer::MarkerArray Ll2Decomposer::make_sign_marker_msg( marker.header.frame_id = "map"; marker.header.stamp = get_clock()->now(); marker.type = Marker::LINE_STRIP; - marker.color = autoware_universe_utils::createMarkerColor(0.6f, 0.6f, 0.6f, 0.999f); + marker.color = autoware::universe_utils::createMarkerColor(0.6f, 0.6f, 0.6f, 0.999f); marker.scale.x = 0.1; marker.ns = ns; marker.id = id++; @@ -228,7 +228,7 @@ Ll2Decomposer::MarkerArray Ll2Decomposer::make_polygon_marker_msg( marker.header.frame_id = "map"; marker.header.stamp = get_clock()->now(); marker.type = Marker::LINE_STRIP; - marker.color = autoware_universe_utils::createMarkerColor(0.4f, 0.4f, 0.8f, 0.999f); + marker.color = autoware::universe_utils::createMarkerColor(0.4f, 0.4f, 0.8f, 0.999f); marker.scale.x = 0.2; marker.ns = ns; marker.id = id++; diff --git a/localization/yabloc/yabloc_image_processing/src/graph_segment/graph_segment_core.cpp b/localization/yabloc/yabloc_image_processing/src/graph_segment/graph_segment_core.cpp index f319fcc9fd77a..9539e44f61276 100644 --- a/localization/yabloc/yabloc_image_processing/src/graph_segment/graph_segment_core.cpp +++ b/localization/yabloc/yabloc_image_processing/src/graph_segment/graph_segment_core.cpp @@ -98,7 +98,7 @@ void GraphSegment::on_image(const Image & msg) cv::resize(image, resized, cv::Size(), 0.5, 0.5); // Execute graph-based segmentation - autoware_universe_utils::StopWatch stop_watch; + autoware::universe_utils::StopWatch stop_watch; cv::Mat segmented; segmentation_->processImage(resized, segmented); RCLCPP_INFO_STREAM(get_logger(), "segmentation time: " << stop_watch.toc() * 1000 << "[ms]"); diff --git a/localization/yabloc/yabloc_image_processing/src/line_segment_detector/line_segment_detector_core.cpp b/localization/yabloc/yabloc_image_processing/src/line_segment_detector/line_segment_detector_core.cpp index f0f451834c66e..c5cec31e24844 100644 --- a/localization/yabloc/yabloc_image_processing/src/line_segment_detector/line_segment_detector_core.cpp +++ b/localization/yabloc/yabloc_image_processing/src/line_segment_detector/line_segment_detector_core.cpp @@ -53,7 +53,7 @@ void LineSegmentDetector::execute(const cv::Mat & image, const rclcpp::Time & st cv::Mat lines; { - autoware_universe_utils::StopWatch stop_watch; + autoware::universe_utils::StopWatch stop_watch; line_segment_detector_->detect(gray_image, lines); if (lines.size().width != 0) { line_segment_detector_->drawSegments(gray_image, lines); diff --git a/localization/yabloc/yabloc_image_processing/src/undistort/undistort_node.cpp b/localization/yabloc/yabloc_image_processing/src/undistort/undistort_node.cpp index ad38c320fc510..5590387e5ba26 100644 --- a/localization/yabloc/yabloc_image_processing/src/undistort/undistort_node.cpp +++ b/localization/yabloc/yabloc_image_processing/src/undistort/undistort_node.cpp @@ -147,7 +147,7 @@ class UndistortNode : public rclcpp::Node sub_compressed_image_.reset(); } - autoware_universe_utils::StopWatch stop_watch; + autoware::universe_utils::StopWatch stop_watch; remap_and_publish(common::decompress_to_cv_mat(msg), msg.header); RCLCPP_INFO_STREAM(get_logger(), "image undistort: " << stop_watch.toc() << "[ms]"); } @@ -161,7 +161,7 @@ class UndistortNode : public rclcpp::Node make_remap_lut(); } - autoware_universe_utils::StopWatch stop_watch; + autoware::universe_utils::StopWatch stop_watch; remap_and_publish(common::decompress_to_cv_mat(msg), msg.header); RCLCPP_INFO_STREAM(get_logger(), "image undistort: " << stop_watch.toc() << "[ms]"); } diff --git a/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_core.cpp b/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_core.cpp index 861f39454d109..d6a38e7b97b96 100644 --- a/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_core.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_core.cpp @@ -133,7 +133,7 @@ CameraParticleCorrector::split_line_segments(const PointCloud2 & msg) void CameraParticleCorrector::on_line_segments(const PointCloud2 & line_segments_msg) { - autoware_universe_utils::StopWatch stop_watch; + autoware::universe_utils::StopWatch stop_watch; const rclcpp::Time stamp = line_segments_msg.header.stamp; std::optional opt_array = this->get_synchronized_particle_array(stamp); if (!opt_array.has_value()) { @@ -259,7 +259,7 @@ float abs_cos(const Eigen::Vector3f & t, float deg) { const auto radian = static_cast(deg * M_PI / 180.0); Eigen::Vector2f x(t.x(), t.y()); - Eigen::Vector2f y(autoware_universe_utils::cos(radian), autoware_universe_utils::sin(radian)); + Eigen::Vector2f y(autoware::universe_utils::cos(radian), autoware::universe_utils::sin(radian)); x.normalize(); return std::abs(x.dot(y)); } diff --git a/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/hierarchical_cost_map.cpp b/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/hierarchical_cost_map.cpp index f11fe26389ecc..4f03e3d26ecb6 100644 --- a/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/hierarchical_cost_map.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/hierarchical_cost_map.cpp @@ -172,7 +172,7 @@ HierarchicalCostMap::MarkerArray HierarchicalCostMap::show_map_range() const marker.header.frame_id = "map"; marker.id = id++; marker.type = Marker::LINE_STRIP; - marker.color = autoware_universe_utils::createMarkerColor(0, 0, 1.0f, 1.0f); + marker.color = autoware::universe_utils::createMarkerColor(0, 0, 1.0f, 1.0f); marker.scale.x = 0.1; Eigen::Vector2f xy = area.real_scale(); marker.points.push_back(point_msg(xy.x(), xy.y())); diff --git a/perception/autoware_crosswalk_traffic_light_estimator/include/autoware_crosswalk_traffic_light_estimator/node.hpp b/perception/autoware_crosswalk_traffic_light_estimator/include/autoware_crosswalk_traffic_light_estimator/node.hpp index 452805803ffa6..8efb90cc87c89 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/include/autoware_crosswalk_traffic_light_estimator/node.hpp +++ b/perception/autoware_crosswalk_traffic_light_estimator/include/autoware_crosswalk_traffic_light_estimator/node.hpp @@ -39,10 +39,10 @@ namespace autoware::crosswalk_traffic_light_estimator { +using autoware::universe_utils::DebugPublisher; +using autoware::universe_utils::StopWatch; using autoware_map_msgs::msg::LaneletMapBin; using autoware_planning_msgs::msg::LaneletRoute; -using autoware_universe_utils::DebugPublisher; -using autoware_universe_utils::StopWatch; using tier4_debug_msgs::msg::Float64Stamped; using TrafficSignal = autoware_perception_msgs::msg::TrafficLightGroup; using TrafficSignalArray = autoware_perception_msgs::msg::TrafficLightGroupArray; diff --git a/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index 86633721c936b..ce1c587cc3b01 100644 --- a/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -116,6 +116,7 @@ struct PredictionTimeHorizon using LaneletsData = std::vector; using ManeuverProbability = std::unordered_map; +using autoware::universe_utils::StopWatch; using autoware_map_msgs::msg::LaneletMapBin; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObject; @@ -129,7 +130,6 @@ using autoware_perception_msgs::msg::TrafficLightElement; using autoware_perception_msgs::msg::TrafficLightGroup; using autoware_perception_msgs::msg::TrafficLightGroupArray; using autoware_planning_msgs::msg::TrajectoryPoint; -using autoware_universe_utils::StopWatch; using tier4_debug_msgs::msg::StringStamped; using TrajectoryPoints = std::vector; class MapBasedPredictionNode : public rclcpp::Node @@ -143,12 +143,12 @@ class MapBasedPredictionNode : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_debug_markers_; rclcpp::Subscription::SharedPtr sub_objects_; rclcpp::Subscription::SharedPtr sub_map_; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_traffic_signals_{this, "/traffic_signals"}; // debug publisher - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr processing_time_publisher_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr processing_time_publisher_; // Object History std::unordered_map> road_users_history; @@ -169,7 +169,7 @@ class MapBasedPredictionNode : public rclcpp::Node const std::vector & parameters); // Pose Transform Listener - autoware_universe_utils::TransformListener transform_listener_{this}; + autoware::universe_utils::TransformListener transform_listener_{this}; // Path Generator std::shared_ptr path_generator_; @@ -221,7 +221,7 @@ class MapBasedPredictionNode : public rclcpp::Node bool match_lost_and_appeared_crosswalk_users_; bool remember_lost_crosswalk_users_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; // Member Functions void mapCallback(const LaneletMapBin::ConstSharedPtr msg); @@ -314,8 +314,8 @@ class MapBasedPredictionNode : public rclcpp::Node inline std::vector calcTrajectoryCurvatureFrom3Points( const TrajectoryPoints & trajectory, size_t idx_dist) { - using autoware_universe_utils::calcCurvature; - using autoware_universe_utils::getPoint; + using autoware::universe_utils::calcCurvature; + using autoware::universe_utils::getPoint; if (trajectory.size() < 3) { const std::vector k_arr(trajectory.size(), 0.0); diff --git a/perception/autoware_map_based_prediction/src/debug.cpp b/perception/autoware_map_based_prediction/src/debug.cpp index 638c10c1a3b1a..bd40ee0981c0e 100644 --- a/perception/autoware_map_based_prediction/src/debug.cpp +++ b/perception/autoware_map_based_prediction/src/debug.cpp @@ -29,7 +29,7 @@ visualization_msgs::msg::Marker MapBasedPredictionNode::getDebugMarker( marker.type = visualization_msgs::msg::Marker::CUBE; marker.action = visualization_msgs::msg::Marker::ADD; marker.pose = object.kinematics.pose_with_covariance.pose; - marker.scale = autoware_universe_utils::createMarkerScale(3.0, 1.0, 1.0); + marker.scale = autoware::universe_utils::createMarkerScale(3.0, 1.0, 1.0); // Color by maneuver double r = 0.0; @@ -42,7 +42,7 @@ visualization_msgs::msg::Marker MapBasedPredictionNode::getDebugMarker( } else { b = 1.0; } - marker.color = autoware_universe_utils::createMarkerColor(r, g, b, 0.8); + marker.color = autoware::universe_utils::createMarkerColor(r, g, b, 0.8); return marker; } diff --git a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp index 0916a4568561f..f505cb7cc5592 100644 --- a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp @@ -92,10 +92,10 @@ double calcAbsLateralOffset( for (size_t i = 0; i < boundary_path.size(); ++i) { const double x = boundary_line[i].x(); const double y = boundary_line[i].y(); - boundary_path[i] = autoware_universe_utils::createPoint(x, y, 0.0); + boundary_path[i] = autoware::universe_utils::createPoint(x, y, 0.0); } - return std::fabs(autoware_motion_utils::calcLateralOffset(boundary_path, search_pose.position)); + return std::fabs(autoware::motion_utils::calcLateralOffset(boundary_path, search_pose.position)); } /** @@ -218,7 +218,7 @@ double calcAbsYawDiffBetweenLaneletAndObject( const double lane_yaw = lanelet::utils::getLaneletAngle(lanelet, object.kinematics.pose_with_covariance.pose.position); const double delta_yaw = object_yaw - lane_yaw; - const double normalized_delta_yaw = autoware_universe_utils::normalizeRadian(delta_yaw); + const double normalized_delta_yaw = autoware::universe_utils::normalizeRadian(delta_yaw); const double abs_norm_delta = std::fabs(normalized_delta_yaw); return abs_norm_delta; } @@ -418,7 +418,7 @@ boost::optional isReachableCrosswalkEdgePoints( const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position; const auto & obj_vel = object.kinematics.twist_with_covariance.twist.linear; - const auto yaw = autoware_universe_utils::getRPY(object.kinematics.pose_with_covariance.pose).z; + const auto yaw = autoware::universe_utils::getRPY(object.kinematics.pose_with_covariance.pose).z; lanelet::BasicPoint2d obj_pos_as_lanelet(obj_pos.x, obj_pos.y); if (boost::geometry::within(obj_pos_as_lanelet, target_crosswalk.polygon2d().basicPolygon())) { @@ -529,7 +529,7 @@ bool hasPotentialToReach( { const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position; const auto & obj_vel = object.kinematics.twist_with_covariance.twist.linear; - const auto yaw = autoware_universe_utils::getRPY(object.kinematics.pose_with_covariance.pose).z; + const auto yaw = autoware::universe_utils::getRPY(object.kinematics.pose_with_covariance.pose).z; constexpr double stop_velocity_th = 0.14; // [m/s] const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y); @@ -547,16 +547,16 @@ bool hasPotentialToReach( const double pedestrian_to_crosswalk_left_direction = std::atan2(left_point.y() - obj_pos.y, left_point.x() - obj_pos.x); return std::make_pair( - autoware_universe_utils::normalizeRadian( + autoware::universe_utils::normalizeRadian( pedestrian_to_crosswalk_right_direction - pedestrian_to_crosswalk_center_direction), - autoware_universe_utils::normalizeRadian( + autoware::universe_utils::normalizeRadian( pedestrian_to_crosswalk_left_direction - pedestrian_to_crosswalk_center_direction)); }(); const double pedestrian_heading_rel_direction = [&]() { const double pedestrian_heading_direction = std::atan2(obj_vel.x * std::sin(yaw), obj_vel.x * std::cos(yaw)); - return autoware_universe_utils::normalizeRadian( + return autoware::universe_utils::normalizeRadian( pedestrian_heading_direction - pedestrian_to_crosswalk_center_direction); }(); @@ -658,7 +658,7 @@ ObjectClassification::_label_type changeLabelForPrediction( if (within_road_lanelet) return ObjectClassification::MOTORCYCLE; constexpr float high_speed_threshold = - autoware_universe_utils::kmph2mps(25.0); // High speed bicycle 25 km/h + autoware::universe_utils::kmph2mps(25.0); // High speed bicycle 25 km/h // calc abs speed from x and y velocity const double abs_speed = std::hypot( object.kinematics.twist_with_covariance.twist.linear.x, @@ -673,7 +673,7 @@ ObjectClassification::_label_type changeLabelForPrediction( case ObjectClassification::PEDESTRIAN: { const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true); const float max_velocity_for_human_mps = - autoware_universe_utils::kmph2mps(25.0); // Max human being motion speed is 25km/h + autoware::universe_utils::kmph2mps(25.0); // Max human being motion speed is 25km/h const double abs_speed = std::hypot( object.kinematics.twist_with_covariance.twist.linear.x, object.kinematics.twist_with_covariance.twist.linear.y); @@ -859,15 +859,15 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ pub_debug_markers_ = this->create_publisher("maneuver", rclcpp::QoS{1}); processing_time_publisher_ = - std::make_unique(this, "map_based_prediction"); + std::make_unique(this, "map_based_prediction"); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); set_param_res_ = this->add_on_set_parameters_callback( std::bind(&MapBasedPredictionNode::onParam, this, std::placeholders::_1)); stop_watch_ptr_ = - std::make_unique>(); + std::make_unique>(); stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); } @@ -875,7 +875,7 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ rcl_interfaces::msg::SetParametersResult MapBasedPredictionNode::onParam( const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; updateParam(parameters, "max_lateral_accel", max_lateral_accel_); updateParam(parameters, "min_acceleration_before_curve", min_acceleration_before_curve_); @@ -1010,14 +1010,14 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt if ( label_for_prediction == ObjectClassification::PEDESTRIAN || label_for_prediction == ObjectClassification::BICYCLE) { - const std::string object_id = autoware_universe_utils::toHexString(object.object_id); + const std::string object_id = autoware::universe_utils::toHexString(object.object_id); current_crosswalk_users.emplace(object_id, object); } } std::unordered_set predicted_crosswalk_users_ids; for (const auto & object : in_objects->objects) { - std::string object_id = autoware_universe_utils::toHexString(object.object_id); + std::string object_id = autoware::universe_utils::toHexString(object.object_id); TrackedObject transformed_object = object; // transform object frame if it's based on map frame @@ -1036,7 +1036,7 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt switch (label) { case ObjectClassification::PEDESTRIAN: case ObjectClassification::BICYCLE: { - std::string object_id = autoware_universe_utils::toHexString(object.object_id); + std::string object_id = autoware::universe_utils::toHexString(object.object_id); if (match_lost_and_appeared_crosswalk_users_) { object_id = tryMatchNewObjectToDisappeared(object_id, current_crosswalk_users); } @@ -1339,11 +1339,11 @@ bool MapBasedPredictionNode::isIntersecting( const geometry_msgs::msg::Point & point1, const geometry_msgs::msg::Point & point2, const lanelet::ConstPoint3d & point3, const lanelet::ConstPoint3d & point4) { - const auto p1 = autoware_universe_utils::createPoint(point1.x, point1.y, 0.0); - const auto p2 = autoware_universe_utils::createPoint(point2.x, point2.y, 0.0); - const auto p3 = autoware_universe_utils::createPoint(point3.x(), point3.y(), 0.0); - const auto p4 = autoware_universe_utils::createPoint(point4.x(), point4.y(), 0.0); - const auto intersection = autoware_universe_utils::intersect(p1, p2, p3, p4); + const auto p1 = autoware::universe_utils::createPoint(point1.x, point1.y, 0.0); + const auto p2 = autoware::universe_utils::createPoint(point2.x, point2.y, 0.0); + const auto p3 = autoware::universe_utils::createPoint(point3.x(), point3.y(), 0.0); + const auto p4 = autoware::universe_utils::createPoint(point4.x(), point4.y(), 0.0); + const auto intersection = autoware::universe_utils::intersect(p1, p2, p3, p4); return intersection.has_value(); } @@ -1491,7 +1491,7 @@ void MapBasedPredictionNode::updateObjectData(TrackedObject & object) // Compute yaw angle from the velocity and position of the object const auto & object_pose = object.kinematics.pose_with_covariance.pose; const auto & object_twist = object.kinematics.twist_with_covariance.twist; - const auto future_object_pose = autoware_universe_utils::calcOffsetPose( + const auto future_object_pose = autoware::universe_utils::calcOffsetPose( object_pose, object_twist.linear.x * 0.1, object_twist.linear.y * 0.1, 0.0); // assumption: the object vx is much larger than vy @@ -1510,16 +1510,16 @@ void MapBasedPredictionNode::updateObjectData(TrackedObject & object) tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); // flip the angle object.kinematics.pose_with_covariance.pose.orientation = - autoware_universe_utils::createQuaternionFromYaw( - autoware_universe_utils::pi + original_yaw); + autoware::universe_utils::createQuaternionFromYaw( + autoware::universe_utils::pi + original_yaw); break; } default: { - const auto updated_object_yaw = autoware_universe_utils::calcAzimuthAngle( + const auto updated_object_yaw = autoware::universe_utils::calcAzimuthAngle( object_pose.position, future_object_pose.position); object.kinematics.pose_with_covariance.pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(updated_object_yaw); + autoware::universe_utils::createQuaternionFromYaw(updated_object_yaw); break; } } @@ -1536,7 +1536,7 @@ void MapBasedPredictionNode::removeStaleTrafficLightInfo( const bool isDisappeared = std::none_of( in_objects->objects.begin(), in_objects->objects.end(), [&it](autoware_perception_msgs::msg::TrackedObject obj) { - return autoware_universe_utils::toHexString(obj.object_id) == it->first.first; + return autoware::universe_utils::toHexString(obj.object_id) == it->first.first; }); if (isDisappeared) { it = stopped_times_against_green_.erase(it); @@ -1645,7 +1645,7 @@ bool MapBasedPredictionNode::checkCloseLaneletCondition( // If the object is in the objects history, we check if the target lanelet is // inside the current lanelets id or following lanelets - const std::string object_id = autoware_universe_utils::toHexString(object.object_id); + const std::string object_id = autoware::universe_utils::toHexString(object.object_id); if (road_users_history.count(object_id) != 0) { const std::vector & possible_lanelet = road_users_history.at(object_id).back().future_possible_lanelets; @@ -1663,7 +1663,7 @@ bool MapBasedPredictionNode::checkCloseLaneletCondition( const double lane_yaw = lanelet::utils::getLaneletAngle( lanelet.second, object.kinematics.pose_with_covariance.pose.position); const double delta_yaw = object_yaw - lane_yaw; - const double normalized_delta_yaw = autoware_universe_utils::normalizeRadian(delta_yaw); + const double normalized_delta_yaw = autoware::universe_utils::normalizeRadian(delta_yaw); const double abs_norm_delta = std::fabs(normalized_delta_yaw); // Step3. Check if the closest lanelet is valid, and add all @@ -1690,7 +1690,7 @@ float MapBasedPredictionNode::calculateLocalLikelihood( const double obj_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); const double lane_yaw = lanelet::utils::getLaneletAngle(current_lanelet, obj_point); const double delta_yaw = obj_yaw - lane_yaw; - const double abs_norm_delta_yaw = std::fabs(autoware_universe_utils::normalizeRadian(delta_yaw)); + const double abs_norm_delta_yaw = std::fabs(autoware::universe_utils::normalizeRadian(delta_yaw)); // compute lateral distance const auto centerline = current_lanelet.centerline(); @@ -1700,7 +1700,7 @@ float MapBasedPredictionNode::calculateLocalLikelihood( converted_centerline.push_back(converted_p); } const double lat_dist = - std::fabs(autoware_motion_utils::calcLateralOffset(converted_centerline, obj_point)); + std::fabs(autoware::motion_utils::calcLateralOffset(converted_centerline, obj_point)); // Compute Chi-squared distributed (Equation (8) in the paper) const double sigma_d = sigma_lateral_offset_; // Standard Deviation for lateral position @@ -1719,7 +1719,7 @@ void MapBasedPredictionNode::updateRoadUsersHistory( const std_msgs::msg::Header & header, const TrackedObject & object, const LaneletsData & current_lanelets_data) { - std::string object_id = autoware_universe_utils::toHexString(object.object_id); + std::string object_id = autoware::universe_utils::toHexString(object.object_id); const auto current_lanelets = getLanelets(current_lanelets_data); ObjectData single_object_data; @@ -1729,7 +1729,7 @@ void MapBasedPredictionNode::updateRoadUsersHistory( single_object_data.pose = object.kinematics.pose_with_covariance.pose; const double object_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); single_object_data.pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(object_yaw); + autoware::universe_utils::createQuaternionFromYaw(object_yaw); single_object_data.time_delay = std::fabs((this->get_clock()->now() - header.stamp).seconds()); single_object_data.twist = object.kinematics.twist_with_covariance.twist; @@ -1933,7 +1933,7 @@ Maneuver MapBasedPredictionNode::predictObjectManeuver( throw std::logic_error("Lane change detection method is invalid."); }(); - const std::string object_id = autoware_universe_utils::toHexString(object.object_id); + const std::string object_id = autoware::universe_utils::toHexString(object.object_id); if (road_users_history.count(object_id) == 0) { return current_maneuver; } @@ -1972,7 +1972,7 @@ Maneuver MapBasedPredictionNode::predictObjectManeuverByTimeToLaneChange( const double /*object_detected_time*/) { // Step1. Check if we have the object in the buffer - const std::string object_id = autoware_universe_utils::toHexString(object.object_id); + const std::string object_id = autoware::universe_utils::toHexString(object.object_id); if (road_users_history.count(object_id) == 0) { return Maneuver::LANE_FOLLOW; } @@ -2043,7 +2043,7 @@ Maneuver MapBasedPredictionNode::predictObjectManeuverByLatDiffDistance( const double /*object_detected_time*/) { // Step1. Check if we have the object in the buffer - const std::string object_id = autoware_universe_utils::toHexString(object.object_id); + const std::string object_id = autoware::universe_utils::toHexString(object.object_id); if (road_users_history.count(object_id) == 0) { return Maneuver::LANE_FOLLOW; } @@ -2081,7 +2081,7 @@ Maneuver MapBasedPredictionNode::predictObjectManeuverByLatDiffDistance( for (const auto & lanelet : prev_lanelets) { const double lane_yaw = lanelet::utils::getLaneletAngle(lanelet, prev_pose.position); const double delta_yaw = tf2::getYaw(prev_pose.orientation) - lane_yaw; - const double normalized_delta_yaw = autoware_universe_utils::normalizeRadian(delta_yaw); + const double normalized_delta_yaw = autoware::universe_utils::normalizeRadian(delta_yaw); if (normalized_delta_yaw < closest_prev_yaw) { closest_prev_yaw = normalized_delta_yaw; prev_lanelet = lanelet; @@ -2091,7 +2091,7 @@ Maneuver MapBasedPredictionNode::predictObjectManeuverByLatDiffDistance( // Step4. Check if the vehicle has changed lane const auto current_lanelet = current_lanelet_data.lanelet; const auto current_pose = object.kinematics.pose_with_covariance.pose; - const double dist = autoware_universe_utils::calcDistance2d(prev_pose, current_pose); + const double dist = autoware::universe_utils::calcDistance2d(prev_pose, current_pose); lanelet::routing::LaneletPaths possible_paths = routing_graph_ptr_->possiblePaths(prev_lanelet, dist + 2.0, 0, false); bool has_lane_changed = true; @@ -2176,8 +2176,8 @@ geometry_msgs::msg::Pose MapBasedPredictionNode::compensateTimeDelay( const double curr_yaw = prev_yaw + wz * dt; geometry_msgs::msg::Pose current_pose; - current_pose.position = autoware_universe_utils::createPoint(curr_x, curr_y, curr_z); - current_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(curr_yaw); + current_pose.position = autoware::universe_utils::createPoint(curr_x, curr_y, curr_z); + current_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(curr_yaw); return current_pose; } @@ -2189,10 +2189,10 @@ double MapBasedPredictionNode::calcRightLateralOffset( for (size_t i = 0; i < boundary_path.size(); ++i) { const double x = boundary_line[i].x(); const double y = boundary_line[i].y(); - boundary_path[i] = autoware_universe_utils::createPoint(x, y, 0.0); + boundary_path[i] = autoware::universe_utils::createPoint(x, y, 0.0); } - return std::fabs(autoware_motion_utils::calcLateralOffset(boundary_path, search_pose.position)); + return std::fabs(autoware::motion_utils::calcLateralOffset(boundary_path, search_pose.position)); } double MapBasedPredictionNode::calcLeftLateralOffset( @@ -2204,7 +2204,7 @@ double MapBasedPredictionNode::calcLeftLateralOffset( void MapBasedPredictionNode::updateFuturePossibleLanelets( const TrackedObject & object, const lanelet::routing::LaneletPaths & paths) { - std::string object_id = autoware_universe_utils::toHexString(object.object_id); + std::string object_id = autoware::universe_utils::toHexString(object.object_id); if (road_users_history.count(object_id) == 0) { return; } @@ -2331,7 +2331,7 @@ std::vector MapBasedPredictionNode::convertPathType( const double lane_yaw = std::atan2( current_p.position.y - prev_p.position.y, current_p.position.x - prev_p.position.x); - current_p.orientation = autoware_universe_utils::createQuaternionFromYaw(lane_yaw); + current_p.orientation = autoware::universe_utils::createQuaternionFromYaw(lane_yaw); converted_path.push_back(current_p); prev_p = current_p; } @@ -2353,7 +2353,7 @@ std::vector MapBasedPredictionNode::convertPathType( // Prevent from inserting same points if (!converted_path.empty()) { const auto last_p = converted_path.back(); - const double tmp_dist = autoware_universe_utils::calcDistance2d(last_p, current_p); + const double tmp_dist = autoware::universe_utils::calcDistance2d(last_p, current_p); if (tmp_dist < 1e-6) { prev_p = current_p; continue; @@ -2362,7 +2362,7 @@ std::vector MapBasedPredictionNode::convertPathType( const double lane_yaw = std::atan2( current_p.position.y - prev_p.position.y, current_p.position.x - prev_p.position.x); - current_p.orientation = autoware_universe_utils::createQuaternionFromYaw(lane_yaw); + current_p.orientation = autoware::universe_utils::createQuaternionFromYaw(lane_yaw); converted_path.push_back(current_p); prev_p = current_p; } @@ -2370,7 +2370,7 @@ std::vector MapBasedPredictionNode::convertPathType( // Resample Path const auto resampled_converted_path = - autoware_motion_utils::resamplePoseVector(converted_path, reference_path_resolution_); + autoware::motion_utils::resamplePoseVector(converted_path, reference_path_resolution_); converted_paths.push_back(resampled_converted_path); } @@ -2402,7 +2402,7 @@ bool MapBasedPredictionNode::isDuplicated( for (const auto & prev_predicted_path : predicted_paths) { const auto prev_path_end = prev_predicted_path.path.back().position; const auto current_path_end = predicted_path.path.back().position; - const double dist = autoware_universe_utils::calcDistance2d(prev_path_end, current_path_end); + const double dist = autoware::universe_utils::calcDistance2d(prev_path_end, current_path_end); if (dist < CLOSE_PATH_THRESHOLD) { return true; } @@ -2452,10 +2452,10 @@ bool MapBasedPredictionNode::calcIntentionToCrossWithTrafficSignal( }(); const auto key = - std::make_pair(autoware_universe_utils::toHexString(object.object_id), signal_id); + std::make_pair(autoware::universe_utils::toHexString(object.object_id), signal_id); if ( signal_color == TrafficLightElement::GREEN && - autoware_universe_utils::calcNorm(object.kinematics.twist_with_covariance.twist.linear) < + autoware::universe_utils::calcNorm(object.kinematics.twist_with_covariance.twist.linear) < threshold_velocity_assumed_as_stopping_) { stopped_times_against_green_.try_emplace(key, this->get_clock()->now()); diff --git a/perception/autoware_map_based_prediction/src/path_generator.cpp b/perception/autoware_map_based_prediction/src/path_generator.cpp index f28aae2ea9794..aeb1b0fedd33f 100644 --- a/perception/autoware_map_based_prediction/src/path_generator.cpp +++ b/perception/autoware_map_based_prediction/src/path_generator.cpp @@ -50,7 +50,7 @@ PredictedPath PathGenerator::generatePathToTargetPoint( const auto pedestrian_to_entry_point_normalized = pedestrian_to_entry_point.normalized(); const auto pedestrian_to_entry_point_orientation = - autoware_universe_utils::createQuaternionFromYaw(std::atan2( + autoware::universe_utils::createQuaternionFromYaw(std::atan2( pedestrian_to_entry_point_normalized.y(), pedestrian_to_entry_point_normalized.x())); for (double dt = 0.0; dt < arrival_time + ep; dt += sampling_time_interval_) { @@ -94,10 +94,10 @@ PredictedPath PathGenerator::generatePathForCrosswalkUser( const auto pedestrian_to_entry_point_normalized = pedestrian_to_entry_point.normalized(); const auto pedestrian_to_entry_point_orientation = - autoware_universe_utils::createQuaternionFromYaw(std::atan2( + autoware::universe_utils::createQuaternionFromYaw(std::atan2( pedestrian_to_entry_point_normalized.y(), pedestrian_to_entry_point_normalized.x())); const auto entry_to_exit_point_normalized = entry_to_exit_point.normalized(); - const auto entry_to_exit_point_orientation = autoware_universe_utils::createQuaternionFromYaw( + const auto entry_to_exit_point_orientation = autoware::universe_utils::createQuaternionFromYaw( std::atan2(entry_to_exit_point_normalized.y(), entry_to_exit_point_normalized.x())); for (double dt = 0.0; dt < duration + ep; dt += sampling_time_interval_) { @@ -174,7 +174,7 @@ PredictedPath PathGenerator::generateStraightPath( path.time_step = rclcpp::Duration::from_seconds(sampling_time_interval_); path.path.reserve(static_cast((duration) / sampling_time_interval_)); for (double dt = 0.0; dt < duration; dt += sampling_time_interval_) { - const auto future_obj_pose = autoware_universe_utils::calcOffsetPose( + const auto future_obj_pose = autoware::universe_utils::calcOffsetPose( object_pose, object_twist.linear.x * dt, object_twist.linear.y * dt, 0.0); path.path.push_back(future_obj_pose); } @@ -187,7 +187,7 @@ PredictedPath PathGenerator::generatePolynomialPath( const double lateral_duration, const double speed_limit) const { // Get current Frenet Point - const double ref_path_len = autoware_motion_utils::calcArcLength(ref_path); + const double ref_path_len = autoware::motion_utils::calcArcLength(ref_path); const auto current_point = getFrenetPoint(object, ref_path, speed_limit, duration); // Step1. Set Target Frenet Point @@ -319,7 +319,7 @@ PosePath PathGenerator::interpolateReferencePath( base_path_y.at(i) = base_path.at(i).position.y; base_path_z.at(i) = base_path.at(i).position.z; if (i > 0) { - base_path_s.at(i) = base_path_s.at(i - 1) + autoware_universe_utils::calcDistance2d( + base_path_s.at(i) = base_path_s.at(i - 1) + autoware::universe_utils::calcDistance2d( base_path.at(i - 1), base_path.at(i)); } } @@ -344,16 +344,16 @@ PosePath PathGenerator::interpolateReferencePath( for (size_t i = 0; i < interpolate_num - 1; ++i) { geometry_msgs::msg::Pose interpolated_pose; const auto current_point = - autoware_universe_utils::createPoint(spline_ref_path_x.at(i), spline_ref_path_y.at(i), 0.0); - const auto next_point = autoware_universe_utils::createPoint( + autoware::universe_utils::createPoint(spline_ref_path_x.at(i), spline_ref_path_y.at(i), 0.0); + const auto next_point = autoware::universe_utils::createPoint( spline_ref_path_x.at(i + 1), spline_ref_path_y.at(i + 1), 0.0); - const double yaw = autoware_universe_utils::calcAzimuthAngle(current_point, next_point); - interpolated_pose.position = autoware_universe_utils::createPoint( + const double yaw = autoware::universe_utils::calcAzimuthAngle(current_point, next_point); + interpolated_pose.position = autoware::universe_utils::createPoint( spline_ref_path_x.at(i), spline_ref_path_y.at(i), spline_ref_path_z.at(i)); - interpolated_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(yaw); + interpolated_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); interpolated_path.at(i) = interpolated_pose; } - interpolated_path.back().position = autoware_universe_utils::createPoint( + interpolated_path.back().position = autoware::universe_utils::createPoint( spline_ref_path_x.back(), spline_ref_path_y.back(), spline_ref_path_z.back()); interpolated_path.back().orientation = interpolated_path.at(interpolate_num - 2).orientation; @@ -376,14 +376,14 @@ PredictedPath PathGenerator::convertToPredictedPath( // Converted Pose auto predicted_pose = - autoware_universe_utils::calcOffsetPose(ref_pose, 0.0, frenet_point.d, 0.0); + autoware::universe_utils::calcOffsetPose(ref_pose, 0.0, frenet_point.d, 0.0); predicted_pose.position.z = object.kinematics.pose_with_covariance.pose.position.z; if (i == 0) { predicted_pose.orientation = object.kinematics.pose_with_covariance.pose.orientation; } else { - const double yaw = autoware_universe_utils::calcAzimuthAngle( + const double yaw = autoware::universe_utils::calcAzimuthAngle( predicted_path.path.at(i - 1).position, predicted_pose.position); - predicted_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(yaw); + predicted_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); } predicted_path.path.at(i) = predicted_pose; } @@ -399,8 +399,8 @@ FrenetPoint PathGenerator::getFrenetPoint( const auto obj_point = object.kinematics.pose_with_covariance.pose.position; const size_t nearest_segment_idx = - autoware_motion_utils::findNearestSegmentIndex(ref_path, obj_point); - const double l = autoware_motion_utils::calcLongitudinalOffsetToSegment( + autoware::motion_utils::findNearestSegmentIndex(ref_path, obj_point); + const double l = autoware::motion_utils::calcLongitudinalOffsetToSegment( ref_path, nearest_segment_idx, obj_point); const float vx = static_cast(object.kinematics.twist_with_covariance.twist.linear.x); const float vy = static_cast(object.kinematics.twist_with_covariance.twist.linear.y); @@ -480,8 +480,9 @@ FrenetPoint PathGenerator::getFrenetPoint( const float acceleration_adjusted_velocity_x = get_acceleration_adjusted_velocity(vx, ax); const float acceleration_adjusted_velocity_y = get_acceleration_adjusted_velocity(vy, ay); - frenet_point.s = autoware_motion_utils::calcSignedArcLength(ref_path, 0, nearest_segment_idx) + l; - frenet_point.d = autoware_motion_utils::calcLateralOffset(ref_path, obj_point); + frenet_point.s = + autoware::motion_utils::calcSignedArcLength(ref_path, 0, nearest_segment_idx) + l; + frenet_point.d = autoware::motion_utils::calcLateralOffset(ref_path, obj_point); frenet_point.s_vel = acceleration_adjusted_velocity_x * std::cos(delta_yaw) - acceleration_adjusted_velocity_y * std::sin(delta_yaw); frenet_point.d_vel = acceleration_adjusted_velocity_x * std::sin(delta_yaw) + diff --git a/perception/cluster_merger/include/cluster_merger/node.hpp b/perception/cluster_merger/include/cluster_merger/node.hpp index adc02680e0d94..a60a76f1c2ef0 100644 --- a/perception/cluster_merger/include/cluster_merger/node.hpp +++ b/perception/cluster_merger/include/cluster_merger/node.hpp @@ -59,7 +59,7 @@ class ClusterMergerNode : public rclcpp::Node std::string output_frame_id_; std::vector::SharedPtr> sub_objects_array{}; - std::shared_ptr transform_listener_; + std::shared_ptr transform_listener_; void objectsCallback( const DetectedObjectsWithFeature::ConstSharedPtr & input_objects0_msg, diff --git a/perception/compare_map_segmentation/src/distance_based_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/distance_based_compare_map_filter_nodelet.cpp index f72e87e2e3610..2962ba1e28a75 100644 --- a/perception/compare_map_segmentation/src/distance_based_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/distance_based_compare_map_filter_nodelet.cpp @@ -109,8 +109,8 @@ DistanceBasedCompareMapFilterComponent::DistanceBasedCompareMapFilterComponent( { // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ = std::make_unique(this, "distance_based_compare_map_filter"); stop_watch_ptr_->tic("cyclic_time"); diff --git a/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp index 6e8f527cc465c..e14ae7d55a1d4 100644 --- a/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp @@ -72,8 +72,8 @@ VoxelBasedApproximateCompareMapFilterComponent::VoxelBasedApproximateCompareMapF { // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ = std::make_unique(this, "voxel_based_approximate_compare_map_filter"); diff --git a/perception/compare_map_segmentation/src/voxel_based_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/voxel_based_compare_map_filter_nodelet.cpp index 720b5cf1d229a..449ae76181bc6 100644 --- a/perception/compare_map_segmentation/src/voxel_based_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/voxel_based_compare_map_filter_nodelet.cpp @@ -31,8 +31,8 @@ VoxelBasedCompareMapFilterComponent::VoxelBasedCompareMapFilterComponent( { // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ = std::make_unique(this, "voxel_based_compare_map_filter"); stop_watch_ptr_->tic("cyclic_time"); diff --git a/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter_nodelet.cpp index 3aacf31c9332f..0a660bfffd7fb 100644 --- a/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter_nodelet.cpp @@ -101,8 +101,8 @@ VoxelDistanceBasedCompareMapFilterComponent::VoxelDistanceBasedCompareMapFilterC { // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ = std::make_unique(this, "voxel_distance_based_compare_map_filter"); diff --git a/perception/detected_object_feature_remover/include/detected_object_feature_remover/detected_object_feature_remover.hpp b/perception/detected_object_feature_remover/include/detected_object_feature_remover/detected_object_feature_remover.hpp index 3a29e7dd1d533..02e4c9c3ca29a 100644 --- a/perception/detected_object_feature_remover/include/detected_object_feature_remover/detected_object_feature_remover.hpp +++ b/perception/detected_object_feature_remover/include/detected_object_feature_remover/detected_object_feature_remover.hpp @@ -36,7 +36,7 @@ class DetectedObjectFeatureRemover : public rclcpp::Node private: rclcpp::Subscription::SharedPtr sub_; rclcpp::Publisher::SharedPtr pub_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; void objectCallback(const DetectedObjectsWithFeature::ConstSharedPtr input); void convert(const DetectedObjectsWithFeature & objs_with_feature, DetectedObjects & objs); }; diff --git a/perception/detected_object_feature_remover/src/detected_object_feature_remover.cpp b/perception/detected_object_feature_remover/src/detected_object_feature_remover.cpp index 43a1d4d3d26ea..3fe9e6fde8683 100644 --- a/perception/detected_object_feature_remover/src/detected_object_feature_remover.cpp +++ b/perception/detected_object_feature_remover/src/detected_object_feature_remover.cpp @@ -24,7 +24,7 @@ DetectedObjectFeatureRemover::DetectedObjectFeatureRemover(const rclcpp::NodeOpt sub_ = this->create_subscription( "~/input", 1, std::bind(&DetectedObjectFeatureRemover::objectCallback, this, _1)); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } void DetectedObjectFeatureRemover::objectCallback( diff --git a/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp index b96a57b12a233..9b9894d56a424 100644 --- a/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp @@ -35,10 +35,10 @@ namespace object_lanelet_filter { -using autoware_universe_utils::LinearRing2d; -using autoware_universe_utils::MultiPoint2d; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; +using autoware::universe_utils::LinearRing2d; +using autoware::universe_utils::MultiPoint2d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; class ObjectLaneletFilterNode : public rclcpp::Node { @@ -52,7 +52,7 @@ class ObjectLaneletFilterNode : public rclcpp::Node rclcpp::Publisher::SharedPtr object_pub_; rclcpp::Subscription::SharedPtr map_sub_; rclcpp::Subscription::SharedPtr object_sub_; - std::unique_ptr debug_publisher_{nullptr}; + std::unique_ptr debug_publisher_{nullptr}; lanelet::LaneletMapPtr lanelet_map_ptr_; lanelet::ConstLanelets road_lanelets_; @@ -89,7 +89,7 @@ class ObjectLaneletFilterNode : public rclcpp::Node const autoware_perception_msgs::msg::DetectedObject & object); geometry_msgs::msg::Polygon setFootprint(const autoware_perception_msgs::msg::DetectedObject &); - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; }; } // namespace object_lanelet_filter diff --git a/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_position_filter.hpp b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_position_filter.hpp index d9eb3d367d4cf..ea70d62fd952d 100644 --- a/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_position_filter.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_position_filter.hpp @@ -54,7 +54,7 @@ class ObjectPositionFilterNode : public rclcpp::Node utils::FilterTargetLabel filter_target_; bool isObjectInBounds(const autoware_perception_msgs::msg::DetectedObject & object) const; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; }; } // namespace object_position_filter diff --git a/perception/detected_object_validation/include/detected_object_validation/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 index 450072f258e2a..47685dec7dbdc 100644 --- a/perception/detected_object_validation/include/detected_object_validation/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 @@ -131,7 +131,7 @@ class ObstaclePointCloudBasedValidator : public rclcpp::Node rclcpp::Publisher::SharedPtr objects_pub_; message_filters::Subscriber objects_sub_; message_filters::Subscriber obstacle_pointcloud_sub_; - std::unique_ptr debug_publisher_{nullptr}; + std::unique_ptr debug_publisher_{nullptr}; tf2_ros::Buffer tf_buffer_; tf2_ros::TransformListener tf_listener_; @@ -145,7 +145,7 @@ class ObstaclePointCloudBasedValidator : public rclcpp::Node std::shared_ptr debugger_; bool using_2d_validator_; std::unique_ptr validator_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; private: void onObjectsAndObstaclePointCloud( diff --git a/perception/detected_object_validation/include/detected_object_validation/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 index 399db8cd8c1f3..beb8faf5db1a3 100644 --- a/perception/detected_object_validation/include/detected_object_validation/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 @@ -43,7 +43,7 @@ class OccupancyGridBasedValidator : public rclcpp::Node message_filters::Subscriber occ_grid_sub_; tf2_ros::Buffer tf_buffer_; tf2_ros::TransformListener tf_listener_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; typedef message_filters::sync_policies::ApproximateTime< autoware_perception_msgs::msg::DetectedObjects, nav_msgs::msg::OccupancyGrid> diff --git a/perception/detected_object_validation/src/object_lanelet_filter.cpp b/perception/detected_object_validation/src/object_lanelet_filter.cpp index 42247a2e36d2b..cc3a600783a8f 100644 --- a/perception/detected_object_validation/src/object_lanelet_filter.cpp +++ b/perception/detected_object_validation/src/object_lanelet_filter.cpp @@ -63,9 +63,9 @@ ObjectLaneletFilterNode::ObjectLaneletFilterNode(const rclcpp::NodeOptions & nod "output/object", rclcpp::QoS{1}); debug_publisher_ = - std::make_unique(this, "object_lanelet_filter"); + std::make_unique(this, "object_lanelet_filter"); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } void ObjectLaneletFilterNode::mapCallback( @@ -237,7 +237,8 @@ bool ObjectLaneletFilterNode::isObjectOverlapLanelets( const auto footprint = setFootprint(object); for (const auto & point : footprint.points) { const geometry_msgs::msg::Point32 point_transformed = - autoware_universe_utils::transformPoint(point, object.kinematics.pose_with_covariance.pose); + autoware::universe_utils::transformPoint( + point, object.kinematics.pose_with_covariance.pose); polygon.outer().emplace_back(point_transformed.x, point_transformed.y); } polygon.outer().push_back(polygon.outer().front()); @@ -246,7 +247,8 @@ bool ObjectLaneletFilterNode::isObjectOverlapLanelets( // if object do not have bounding box, check each footprint is inside polygon for (const auto & point : object.shape.footprint.points) { const geometry_msgs::msg::Point32 point_transformed = - autoware_universe_utils::transformPoint(point, object.kinematics.pose_with_covariance.pose); + autoware::universe_utils::transformPoint( + point, object.kinematics.pose_with_covariance.pose); geometry_msgs::msg::Pose point2d; point2d.position.x = point_transformed.x; point2d.position.y = point_transformed.y; @@ -296,7 +298,7 @@ bool ObjectLaneletFilterNode::isSameDirectionWithLanelets( const double lane_yaw = lanelet::utils::getLaneletAngle( lanelet, object.kinematics.pose_with_covariance.pose.position); const double delta_yaw = object_velocity_yaw - lane_yaw; - const double normalized_delta_yaw = autoware_universe_utils::normalizeRadian(delta_yaw); + const double normalized_delta_yaw = autoware::universe_utils::normalizeRadian(delta_yaw); const double abs_norm_delta_yaw = std::fabs(normalized_delta_yaw); if (abs_norm_delta_yaw < filter_settings_.lanelet_direction_filter_velocity_yaw_threshold) { diff --git a/perception/detected_object_validation/src/object_position_filter.cpp b/perception/detected_object_validation/src/object_position_filter.cpp index 8e22cd1b88d88..dccff8a6ccc67 100644 --- a/perception/detected_object_validation/src/object_position_filter.cpp +++ b/perception/detected_object_validation/src/object_position_filter.cpp @@ -43,7 +43,7 @@ ObjectPositionFilterNode::ObjectPositionFilterNode(const rclcpp::NodeOptions & n object_pub_ = this->create_publisher( "output/object", rclcpp::QoS{1}); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } void ObjectPositionFilterNode::objectCallback( 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 10e923b91c1bd..fbb3f863be7c4 100644 --- a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp +++ b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp @@ -33,7 +33,7 @@ namespace obstacle_pointcloud_based_validator { namespace bg = boost::geometry; using Shape = autoware_perception_msgs::msg::Shape; -using Polygon2d = autoware_universe_utils::Polygon2d; +using Polygon2d = autoware::universe_utils::Polygon2d; Validator::Validator(PointsNumThresholdParam & points_num_threshold_param) { @@ -96,8 +96,8 @@ std::optional Validator2D::getPointCloudWithinObject( { std::vector vertices_array; pcl::Vertices vertices; - Polygon2d poly2d = - autoware_universe_utils::toPolygon2d(object.kinematics.pose_with_covariance.pose, object.shape); + Polygon2d poly2d = autoware::universe_utils::toPolygon2d( + object.kinematics.pose_with_covariance.pose, object.shape); if (bg::is_empty(poly2d)) return std::nullopt; pcl::PointCloud::Ptr poly3d(new pcl::PointCloud); @@ -211,8 +211,8 @@ std::optional Validator3D::getPointCloudWithinObject( auto const object_height = object.shape.dimensions.x; auto z_min = object_position.z - object_height / 2.0f; auto z_max = object_position.z + object_height / 2.0f; - Polygon2d poly2d = - autoware_universe_utils::toPolygon2d(object.kinematics.pose_with_covariance.pose, object.shape); + Polygon2d poly2d = autoware::universe_utils::toPolygon2d( + object.kinematics.pose_with_covariance.pose, object.shape); if (bg::is_empty(poly2d)) return std::nullopt; pcl::PointCloud::Ptr poly3d(new pcl::PointCloud); @@ -304,13 +304,13 @@ ObstaclePointCloudBasedValidator::ObstaclePointCloudBasedValidator( objects_pub_ = create_publisher( "~/output/objects", rclcpp::QoS{1}); - debug_publisher_ = std::make_unique( + debug_publisher_ = std::make_unique( this, "obstacle_pointcloud_based_validator"); const bool enable_debugger = declare_parameter("enable_debugger", false); if (enable_debugger) debugger_ = std::make_shared(this); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud( const autoware_perception_msgs::msg::DetectedObjects::ConstSharedPtr & input_objects, 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 ec29818ee6491..b8682a6e56b3b 100644 --- a/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp +++ b/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp @@ -33,7 +33,7 @@ namespace occupancy_grid_based_validator { using Shape = autoware_perception_msgs::msg::Shape; -using Polygon2d = autoware_universe_utils::Polygon2d; +using Polygon2d = autoware::universe_utils::Polygon2d; OccupancyGridBasedValidator::OccupancyGridBasedValidator(const rclcpp::NodeOptions & node_options) : rclcpp::Node("occupancy_grid_based_validator", node_options), @@ -53,7 +53,7 @@ OccupancyGridBasedValidator::OccupancyGridBasedValidator(const rclcpp::NodeOptio mean_threshold_ = declare_parameter("mean_threshold", 0.6); enable_debug_ = declare_parameter("enable_debug", false); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } void OccupancyGridBasedValidator::onObjectsAndOccGrid( @@ -107,8 +107,8 @@ std::optional OccupancyGridBasedValidator::getMask( const auto & resolution = occupancy_grid.info.resolution; const auto & origin = occupancy_grid.info.origin; std::vector pixel_vertices; - Polygon2d poly2d = - autoware_universe_utils::toPolygon2d(object.kinematics.pose_with_covariance.pose, object.shape); + Polygon2d poly2d = autoware::universe_utils::toPolygon2d( + object.kinematics.pose_with_covariance.pose, object.shape); bool is_polygon_within_image = true; for (const auto & p : poly2d.outer()) { diff --git a/perception/detection_by_tracker/include/detection_by_tracker/debugger.hpp b/perception/detection_by_tracker/include/detection_by_tracker/debugger.hpp index 40caa06d3acbf..0169082a2253a 100644 --- a/perception/detection_by_tracker/include/detection_by_tracker/debugger.hpp +++ b/perception/detection_by_tracker/include/detection_by_tracker/debugger.hpp @@ -60,9 +60,9 @@ class Debugger divided_objects_pub_ = node->create_publisher( "debug/divided_objects", 1); processing_time_publisher_ = - std::make_unique(node, "detection_by_tracker"); + std::make_unique(node, "detection_by_tracker"); stop_watch_ptr_ = - std::make_unique>(); + std::make_unique>(); this->startStopWatch(); } @@ -103,8 +103,8 @@ class Debugger rclcpp::Publisher::SharedPtr merged_objects_pub_; rclcpp::Publisher::SharedPtr divided_objects_pub_; // debug publisher - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr processing_time_publisher_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr processing_time_publisher_; autoware_perception_msgs::msg::DetectedObjects removeFeature( const tier4_perception_msgs::msg::DetectedObjectsWithFeature & input) diff --git a/perception/detection_by_tracker/include/detection_by_tracker/detection_by_tracker_core.hpp b/perception/detection_by_tracker/include/detection_by_tracker/detection_by_tracker_core.hpp index de9453c68ca95..d6d030aadb000 100644 --- a/perception/detection_by_tracker/include/detection_by_tracker/detection_by_tracker_core.hpp +++ b/perception/detection_by_tracker/include/detection_by_tracker/detection_by_tracker_core.hpp @@ -84,7 +84,7 @@ class DetectionByTracker : public rclcpp::Node detection_by_tracker::utils::TrackerIgnoreLabel tracker_ignore_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; void setMaxSearchRange(); diff --git a/perception/detection_by_tracker/src/detection_by_tracker_core.cpp b/perception/detection_by_tracker/src/detection_by_tracker_core.cpp index dd63013bff038..4e502b359120d 100644 --- a/perception/detection_by_tracker/src/detection_by_tracker_core.cpp +++ b/perception/detection_by_tracker/src/detection_by_tracker_core.cpp @@ -61,7 +61,7 @@ boost::optional getReferenceYawInfo(const uint8_t label, const const bool is_vehicle = Label::CAR == label || Label::TRUCK == label || Label::BUS == label || Label::TRAILER == label; if (is_vehicle) { - return ReferenceYawInfo{yaw, autoware_universe_utils::deg2rad(30)}; + return ReferenceYawInfo{yaw, autoware::universe_utils::deg2rad(30)}; } else { return boost::none; } @@ -136,9 +136,9 @@ bool TrackerHandler::estimateTrackedObjects( estimated_object.kinematics.pose_with_covariance.pose.position.y = y + vx * std::sin(yaw) * dt.seconds(); estimated_object.kinematics.pose_with_covariance.pose.position.z = z; - const float yaw_hat = autoware_universe_utils::normalizeRadian(yaw + wz * dt.seconds()); + const float yaw_hat = autoware::universe_utils::normalizeRadian(yaw + wz * dt.seconds()); estimated_object.kinematics.pose_with_covariance.pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(yaw_hat); + autoware::universe_utils::createQuaternionFromYaw(yaw_hat); output.objects.push_back(estimated_object); } return true; @@ -178,7 +178,7 @@ DetectionByTracker::DetectionByTracker(const rclcpp::NodeOptions & node_options) false, 10, 10000, 0.7, 0.3, 0); debugger_ = std::make_shared(this); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } void DetectionByTracker::setMaxSearchRange() @@ -284,7 +284,7 @@ void DetectionByTracker::divideUnderSegmentedObjects( for (const auto & initial_object : in_cluster_objects.feature_objects) { // search near object - const float distance = autoware_universe_utils::calcDistance2d( + const float distance = autoware::universe_utils::calcDistance2d( tracked_object.kinematics.pose_with_covariance.pose, initial_object.object.kinematics.pose_with_covariance.pose); if (max_search_range < distance) { @@ -420,7 +420,7 @@ void DetectionByTracker::mergeOverSegmentedObjects( pcl::PointCloud pcl_merged_cluster; for (const auto & initial_object : in_cluster_objects.feature_objects) { - const float distance = autoware_universe_utils::calcDistance2d( + const float distance = autoware::universe_utils::calcDistance2d( tracked_object.kinematics.pose_with_covariance.pose, initial_object.object.kinematics.pose_with_covariance.pose); diff --git a/perception/elevation_map_loader/src/elevation_map_loader_node.cpp b/perception/elevation_map_loader/src/elevation_map_loader_node.cpp index 1d3d091165b4c..3b249e45ae194 100644 --- a/perception/elevation_map_loader/src/elevation_map_loader_node.cpp +++ b/perception/elevation_map_loader/src/elevation_map_loader_node.cpp @@ -356,7 +356,7 @@ void ElevationMapLoaderNode::inpaintElevationMap(const float radius) // Convert elevation layer to OpenCV image to fill in holes. // Get the inpaint mask (nonzero pixels indicate where values need to be filled in). namespace bg = boost::geometry; - using autoware_universe_utils::Point2d; + using autoware::universe_utils::Point2d; elevation_map_.add("inpaint_mask", 0.0); diff --git a/perception/euclidean_cluster/src/euclidean_cluster_node.cpp b/perception/euclidean_cluster/src/euclidean_cluster_node.cpp index 31f24766de9a9..f986b0334935f 100644 --- a/perception/euclidean_cluster/src/euclidean_cluster_node.cpp +++ b/perception/euclidean_cluster/src/euclidean_cluster_node.cpp @@ -39,9 +39,9 @@ EuclideanClusterNode::EuclideanClusterNode(const rclcpp::NodeOptions & options) "output", rclcpp::QoS{1}); debug_pub_ = this->create_publisher("debug/clusters", 1); stop_watch_ptr_ = - std::make_unique>(); + std::make_unique>(); debug_publisher_ = - std::make_unique(this, "euclidean_cluster"); + std::make_unique(this, "euclidean_cluster"); stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); } diff --git a/perception/euclidean_cluster/src/euclidean_cluster_node.hpp b/perception/euclidean_cluster/src/euclidean_cluster_node.hpp index 23724ae880827..92f10696d17dc 100644 --- a/perception/euclidean_cluster/src/euclidean_cluster_node.hpp +++ b/perception/euclidean_cluster/src/euclidean_cluster_node.hpp @@ -41,8 +41,8 @@ class EuclideanClusterNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_pub_; std::shared_ptr cluster_; - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr debug_publisher_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr debug_publisher_; }; } // namespace euclidean_cluster diff --git a/perception/euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp b/perception/euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp index 2160fd50faafb..e9425095a3b0d 100644 --- a/perception/euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp +++ b/perception/euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp @@ -43,8 +43,8 @@ VoxelGridBasedEuclideanClusterNode::VoxelGridBasedEuclideanClusterNode( "output", rclcpp::QoS{1}); debug_pub_ = this->create_publisher("debug/clusters", 1); stop_watch_ptr_ = - std::make_unique>(); - debug_publisher_ = std::make_unique( + std::make_unique>(); + debug_publisher_ = std::make_unique( this, "voxel_grid_based_euclidean_cluster"); stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); diff --git a/perception/euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.hpp b/perception/euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.hpp index 3a954436ce8ca..b0c5d0e5a7fbf 100644 --- a/perception/euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.hpp +++ b/perception/euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.hpp @@ -41,8 +41,8 @@ class VoxelGridBasedEuclideanClusterNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_pub_; std::shared_ptr cluster_; - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr debug_publisher_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr debug_publisher_; }; } // namespace euclidean_cluster diff --git a/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp b/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp index 39498f9c8c82f..3ae41173a7a7d 100644 --- a/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp +++ b/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp @@ -280,9 +280,9 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter rcl_interfaces::msg::SetParametersResult onParameter(const std::vector & p); // debugger - std::unique_ptr> stop_watch_ptr_{ + std::unique_ptr> stop_watch_ptr_{ nullptr}; - std::unique_ptr debug_publisher_ptr_{nullptr}; + std::unique_ptr debug_publisher_ptr_{nullptr}; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp index 7af02da734524..7853aa400b6a5 100644 --- a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp @@ -25,11 +25,11 @@ namespace ground_segmentation { +using autoware::universe_utils::calcDistance3d; +using autoware::universe_utils::deg2rad; +using autoware::universe_utils::normalizeDegree; +using autoware::universe_utils::normalizeRadian; using autoware::vehicle_info_utils::VehicleInfoUtils; -using autoware_universe_utils::calcDistance3d; -using autoware_universe_utils::deg2rad; -using autoware_universe_utils::normalizeDegree; -using autoware_universe_utils::normalizeRadian; using pointcloud_preprocessor::get_param; ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & options) @@ -79,8 +79,8 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ptr_ = std::make_unique(this, "scan_ground_filter"); stop_watch_ptr_->tic("cyclic_time"); diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp index 92859a80e48f6..df8bf66433300 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp @@ -138,8 +138,8 @@ class FusionNode : public rclcpp::Node float filter_scope_max_z_; /** \brief processing time publisher. **/ - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr debug_publisher_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr debug_publisher_; }; } // namespace image_projection_based_fusion diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index e561642b76951..20273fd1de547 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -130,8 +130,8 @@ FusionNode::FusionNode( // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ = std::make_unique(this, get_name()); stop_watch_ptr_->tic("cyclic_time"); diff --git a/perception/image_projection_based_fusion/src/utils/utils.cpp b/perception/image_projection_based_fusion/src/utils/utils.cpp index fb99364147509..2e997f3e8e60f 100644 --- a/perception/image_projection_based_fusion/src/utils/utils.cpp +++ b/perception/image_projection_based_fusion/src/utils/utils.cpp @@ -70,7 +70,7 @@ void closest_cluster( std::memcpy(&point.y, &cluster.data[i * point_step + y_offset], sizeof(float)); std::memcpy(&point.z, &cluster.data[i * point_step + z_offset], sizeof(float)); - point_data.distance = autoware_universe_utils::calcDistance2d(center, point); + point_data.distance = autoware::universe_utils::calcDistance2d(center, point); point_data.orig_index = i; points_data.push_back(point_data); } @@ -258,7 +258,7 @@ pcl::PointXYZ getClosestPoint(const pcl::PointCloud & cluster) pcl::PointXYZ orig_point = pcl::PointXYZ(0.0, 0.0, 0.0); for (std::size_t i = 0; i < cluster.points.size(); ++i) { pcl::PointXYZ point = cluster.points.at(i); - double dist_closest_point = autoware_universe_utils::calcDistance2d(point, orig_point); + double dist_closest_point = autoware::universe_utils::calcDistance2d(point, orig_point); if (min_dist > dist_closest_point) { min_dist = dist_closest_point; closest_point = pcl::PointXYZ(point.x, point.y, point.z); diff --git a/perception/lidar_apollo_instance_segmentation/include/lidar_apollo_instance_segmentation/node.hpp b/perception/lidar_apollo_instance_segmentation/include/lidar_apollo_instance_segmentation/node.hpp index 9082e209fb330..f159f125677c4 100644 --- a/perception/lidar_apollo_instance_segmentation/include/lidar_apollo_instance_segmentation/node.hpp +++ b/perception/lidar_apollo_instance_segmentation/include/lidar_apollo_instance_segmentation/node.hpp @@ -47,8 +47,8 @@ class LidarInstanceSegmentationNode : public rclcpp::Node std::shared_ptr detector_ptr_; std::shared_ptr debugger_ptr_; void pointCloudCallback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg); - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr debug_publisher_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr debug_publisher_; public: explicit LidarInstanceSegmentationNode(const rclcpp::NodeOptions & node_options); diff --git a/perception/lidar_apollo_instance_segmentation/src/detector.cpp b/perception/lidar_apollo_instance_segmentation/src/detector.cpp index 592c63ed22169..b704bab39338a 100644 --- a/perception/lidar_apollo_instance_segmentation/src/detector.cpp +++ b/perception/lidar_apollo_instance_segmentation/src/detector.cpp @@ -88,7 +88,8 @@ bool LidarApolloInstanceSegmentation::transformCloud( target_frame_, input.header.frame_id, input.header.stamp, std::chrono::milliseconds(500)); Eigen::Matrix4f affine_matrix = tf2::transformToEigen(transform_stamped.transform).matrix().cast(); - autoware_universe_utils::transformPointCloud(pcl_input, pcl_transformed_cloud, affine_matrix); + autoware::universe_utils::transformPointCloud( + pcl_input, pcl_transformed_cloud, affine_matrix); transformed_cloud.header.frame_id = target_frame_; pcl_transformed_cloud.header.frame_id = target_frame_; } catch (tf2::TransformException & ex) { @@ -103,7 +104,7 @@ bool LidarApolloInstanceSegmentation::transformCloud( pcl::PointCloud pointcloud_with_z_offset; Eigen::Affine3f z_up_translation(Eigen::Translation3f(0, 0, z_offset)); Eigen::Matrix4f z_up_transform = z_up_translation.matrix(); - autoware_universe_utils::transformPointCloud( + autoware::universe_utils::transformPointCloud( pcl_transformed_cloud, pcl_transformed_cloud, z_up_transform); pcl::toROSMsg(pcl_transformed_cloud, transformed_cloud); diff --git a/perception/lidar_apollo_instance_segmentation/src/node.cpp b/perception/lidar_apollo_instance_segmentation/src/node.cpp index 6034fe917bf42..93b2f3344de99 100644 --- a/perception/lidar_apollo_instance_segmentation/src/node.cpp +++ b/perception/lidar_apollo_instance_segmentation/src/node.cpp @@ -28,8 +28,8 @@ LidarInstanceSegmentationNode::LidarInstanceSegmentationNode( using std::placeholders::_1; // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ = std::make_unique(this, "lidar_apollo_instance_segmentation"); stop_watch_ptr_->tic("cyclic_time"); diff --git a/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp b/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp index a516d35edfd6b..e78cd57b3a4a1 100644 --- a/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp +++ b/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp @@ -147,7 +147,7 @@ void ApolloLidarSegmentation::transformCloud( tf_buffer_->lookupTransform(target_frame_, input.header.frame_id, time_point); Eigen::Matrix4f affine_matrix = tf2::transformToEigen(transform_stamped.transform).matrix().cast(); - autoware_universe_utils::transformPointCloud( + autoware::universe_utils::transformPointCloud( in_cluster, transformed_cloud_cluster, affine_matrix); transformed_cloud_cluster.header.frame_id = target_frame_; } else { @@ -158,7 +158,7 @@ void ApolloLidarSegmentation::transformCloud( if (z_offset != 0) { Eigen::Affine3f z_up_translation(Eigen::Translation3f(0, 0, z_offset)); Eigen::Matrix4f z_up_transform = z_up_translation.matrix(); - autoware_universe_utils::transformPointCloud( + autoware::universe_utils::transformPointCloud( transformed_cloud_cluster, transformed_cloud_cluster, z_up_transform); } diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/node.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/node.hpp index 032627861e1b3..154ff97cdb887 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/node.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/node.hpp @@ -62,11 +62,11 @@ class LidarCenterPointNode : public rclcpp::Node std::unique_ptr detector_ptr_{nullptr}; // debugger - std::unique_ptr> stop_watch_ptr_{ + std::unique_ptr> stop_watch_ptr_{ nullptr}; - std::unique_ptr debug_publisher_ptr_{nullptr}; + std::unique_ptr debug_publisher_ptr_{nullptr}; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; }; } // namespace centerpoint diff --git a/perception/lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp b/perception/lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp index 533d04eebd433..16f4fc89bbcd6 100644 --- a/perception/lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp +++ b/perception/lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp @@ -49,7 +49,7 @@ bool NonMaximumSuppression::isTargetPairObject( } const auto search_sqr_dist_2d = params_.search_distance_2d_ * params_.search_distance_2d_; - const auto sqr_dist_2d = autoware_universe_utils::calcSquaredDistance2d( + const auto sqr_dist_2d = autoware::universe_utils::calcSquaredDistance2d( object_recognition_utils::getPose(object1), object_recognition_utils::getPose(object2)); return sqr_dist_2d <= search_sqr_dist_2d; } diff --git a/perception/lidar_centerpoint/lib/ros_utils.cpp b/perception/lidar_centerpoint/lib/ros_utils.cpp index 4799ec322d779..039d340cc2dc4 100644 --- a/perception/lidar_centerpoint/lib/ros_utils.cpp +++ b/perception/lidar_centerpoint/lib/ros_utils.cpp @@ -50,14 +50,14 @@ void box3DToDetectedObject( // pose and shape // mmdet3d yaw format to ros yaw format - float yaw = -box3d.yaw - autoware_universe_utils::pi / 2; + float yaw = -box3d.yaw - autoware::universe_utils::pi / 2; obj.kinematics.pose_with_covariance.pose.position = - autoware_universe_utils::createPoint(box3d.x, box3d.y, box3d.z); + autoware::universe_utils::createPoint(box3d.x, box3d.y, box3d.z); obj.kinematics.pose_with_covariance.pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(yaw); + autoware::universe_utils::createQuaternionFromYaw(yaw); obj.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; obj.shape.dimensions = - autoware_universe_utils::createTranslation(box3d.length, box3d.width, box3d.height); + autoware::universe_utils::createTranslation(box3d.length, box3d.width, box3d.height); if (has_variance) { obj.kinematics.has_position_covariance = has_variance; obj.kinematics.pose_with_covariance.covariance = convertPoseCovarianceMatrix(box3d); @@ -102,7 +102,7 @@ uint8_t getSemanticType(const std::string & class_name) std::array convertPoseCovarianceMatrix(const Box3D & box3d) { - using POSE_IDX = autoware_universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + using POSE_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; std::array pose_covariance{}; pose_covariance[POSE_IDX::X_X] = box3d.x_variance; pose_covariance[POSE_IDX::Y_Y] = box3d.y_variance; @@ -113,7 +113,7 @@ std::array convertPoseCovarianceMatrix(const Box3D & box3d) std::array convertTwistCovarianceMatrix(const Box3D & box3d) { - using POSE_IDX = autoware_universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + using POSE_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; std::array twist_covariance{}; twist_covariance[POSE_IDX::X_X] = box3d.vel_x_variance; twist_covariance[POSE_IDX::Y_Y] = box3d.vel_y_variance; diff --git a/perception/lidar_centerpoint/src/node.cpp b/perception/lidar_centerpoint/src/node.cpp index 5c0931196675a..8bf62e3e0168b 100644 --- a/perception/lidar_centerpoint/src/node.cpp +++ b/perception/lidar_centerpoint/src/node.cpp @@ -118,8 +118,8 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ptr_ = std::make_unique(this, "lidar_centerpoint"); stop_watch_ptr_->tic("cyclic_time"); @@ -131,7 +131,7 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti rclcpp::shutdown(); } published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } void LidarCenterPointNode::pointCloudCallback( diff --git a/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/node.hpp b/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/node.hpp index cb387c404c07e..88a43139908a7 100644 --- a/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/node.hpp +++ b/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/node.hpp @@ -59,9 +59,9 @@ class LIDAR_CENTERPOINT_TVM_PUBLIC LidarCenterPointTVMNode : public rclcpp::Node std::unique_ptr detector_ptr_{nullptr}; // debugger - std::unique_ptr> stop_watch_ptr_{ + std::unique_ptr> stop_watch_ptr_{ nullptr}; - std::unique_ptr debug_publisher_ptr_{nullptr}; + std::unique_ptr debug_publisher_ptr_{nullptr}; }; } // namespace lidar_centerpoint_tvm diff --git a/perception/lidar_centerpoint_tvm/lib/ros_utils.cpp b/perception/lidar_centerpoint_tvm/lib/ros_utils.cpp index 16d7094e1e628..94639d71e66c0 100644 --- a/perception/lidar_centerpoint_tvm/lib/ros_utils.cpp +++ b/perception/lidar_centerpoint_tvm/lib/ros_utils.cpp @@ -65,14 +65,14 @@ void box3DToDetectedObject( // pose and shape // mmdet3d yaw format to ros yaw format - float yaw = -box3d.yaw - autoware_universe_utils::pi / 2; + float yaw = -box3d.yaw - autoware::universe_utils::pi / 2; obj.kinematics.pose_with_covariance.pose.position = - autoware_universe_utils::createPoint(box3d.x, box3d.y, box3d.z); + autoware::universe_utils::createPoint(box3d.x, box3d.y, box3d.z); obj.kinematics.pose_with_covariance.pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(yaw); + autoware::universe_utils::createQuaternionFromYaw(yaw); obj.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; obj.shape.dimensions = - autoware_universe_utils::createTranslation(box3d.length, box3d.width, box3d.height); + autoware::universe_utils::createTranslation(box3d.length, box3d.width, box3d.height); // twist if (has_twist) { diff --git a/perception/lidar_centerpoint_tvm/src/node.cpp b/perception/lidar_centerpoint_tvm/src/node.cpp index fec19a479a89f..9cf82b1c6bcae 100644 --- a/perception/lidar_centerpoint_tvm/src/node.cpp +++ b/perception/lidar_centerpoint_tvm/src/node.cpp @@ -94,8 +94,8 @@ LidarCenterPointTVMNode::LidarCenterPointTVMNode(const rclcpp::NodeOptions & nod // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ptr_ = std::make_unique(this, "lidar_centerpoint_tvm"); stop_watch_ptr_->tic("cyclic_time"); diff --git a/perception/lidar_transfusion/include/lidar_transfusion/lidar_transfusion_node.hpp b/perception/lidar_transfusion/include/lidar_transfusion/lidar_transfusion_node.hpp index d57405b1c3b7b..a82013fac6ce7 100644 --- a/perception/lidar_transfusion/include/lidar_transfusion/lidar_transfusion_node.hpp +++ b/perception/lidar_transfusion/include/lidar_transfusion/lidar_transfusion_node.hpp @@ -63,10 +63,10 @@ class LIDAR_TRANSFUSION_PUBLIC LidarTransfusionNode : public rclcpp::Node std::unique_ptr detector_ptr_{nullptr}; // debugger - std::unique_ptr> stop_watch_ptr_{ + std::unique_ptr> stop_watch_ptr_{ nullptr}; - std::unique_ptr debug_publisher_ptr_{nullptr}; - std::unique_ptr published_time_pub_{nullptr}; + std::unique_ptr debug_publisher_ptr_{nullptr}; + std::unique_ptr published_time_pub_{nullptr}; }; } // namespace lidar_transfusion diff --git a/perception/lidar_transfusion/include/lidar_transfusion/transfusion_trt.hpp b/perception/lidar_transfusion/include/lidar_transfusion/transfusion_trt.hpp index d454932935b64..0a9ea413dc30d 100644 --- a/perception/lidar_transfusion/include/lidar_transfusion/transfusion_trt.hpp +++ b/perception/lidar_transfusion/include/lidar_transfusion/transfusion_trt.hpp @@ -83,7 +83,7 @@ class LIDAR_TRANSFUSION_PUBLIC TransfusionTRT std::unique_ptr network_trt_ptr_{nullptr}; std::unique_ptr vg_ptr_{nullptr}; - std::unique_ptr> stop_watch_ptr_{ + std::unique_ptr> stop_watch_ptr_{ nullptr}; std::unique_ptr pre_ptr_{nullptr}; std::unique_ptr post_ptr_{nullptr}; diff --git a/perception/lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp b/perception/lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp index a8b4ddbfd5db9..dd12c52970d38 100644 --- a/perception/lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp +++ b/perception/lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp @@ -49,7 +49,7 @@ bool NonMaximumSuppression::isTargetPairObject( } const auto search_sqr_dist_2d = params_.search_distance_2d_ * params_.search_distance_2d_; - const auto sqr_dist_2d = autoware_universe_utils::calcSquaredDistance2d( + const auto sqr_dist_2d = autoware::universe_utils::calcSquaredDistance2d( object_recognition_utils::getPose(object1), object_recognition_utils::getPose(object2)); return sqr_dist_2d <= search_sqr_dist_2d; } diff --git a/perception/lidar_transfusion/lib/ros_utils.cpp b/perception/lidar_transfusion/lib/ros_utils.cpp index cdfa693af2219..ef5c45c339b64 100644 --- a/perception/lidar_transfusion/lib/ros_utils.cpp +++ b/perception/lidar_transfusion/lib/ros_utils.cpp @@ -49,14 +49,14 @@ void box3DToDetectedObject( // pose and shape // mmdet3d yaw format to ros yaw format - float yaw = box3d.yaw + autoware_universe_utils::pi / 2; + float yaw = box3d.yaw + autoware::universe_utils::pi / 2; obj.kinematics.pose_with_covariance.pose.position = - autoware_universe_utils::createPoint(box3d.x, box3d.y, box3d.z); + autoware::universe_utils::createPoint(box3d.x, box3d.y, box3d.z); obj.kinematics.pose_with_covariance.pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(yaw); + autoware::universe_utils::createQuaternionFromYaw(yaw); obj.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; obj.shape.dimensions = - autoware_universe_utils::createTranslation(box3d.length, box3d.width, box3d.height); + autoware::universe_utils::createTranslation(box3d.length, box3d.width, box3d.height); } uint8_t getSemanticType(const std::string & class_name) diff --git a/perception/lidar_transfusion/lib/transfusion_trt.cpp b/perception/lidar_transfusion/lib/transfusion_trt.cpp index 4a8416a16e18c..d940b83c12cb4 100644 --- a/perception/lidar_transfusion/lib/transfusion_trt.cpp +++ b/perception/lidar_transfusion/lib/transfusion_trt.cpp @@ -38,7 +38,7 @@ TransfusionTRT::TransfusionTRT( network_param.onnx_path(), network_param.engine_path(), network_param.trt_precision()); vg_ptr_ = std::make_unique(densification_param, config_, stream_); stop_watch_ptr_ = - std::make_unique>(); + std::make_unique>(); stop_watch_ptr_->tic("processing/inner"); initPtr(); diff --git a/perception/lidar_transfusion/src/lidar_transfusion_node.cpp b/perception/lidar_transfusion/src/lidar_transfusion_node.cpp index 07b19f1db51f8..e3ea6b3780de8 100644 --- a/perception/lidar_transfusion/src/lidar_transfusion_node.cpp +++ b/perception/lidar_transfusion/src/lidar_transfusion_node.cpp @@ -94,12 +94,12 @@ LidarTransfusionNode::LidarTransfusionNode(const rclcpp::NodeOptions & options) objects_pub_ = this->create_publisher( "~/output/objects", rclcpp::QoS(1)); - published_time_pub_ = std::make_unique(this); + published_time_pub_ = std::make_unique(this); // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ptr_ = std::make_unique(this, this->get_name()); stop_watch_ptr_->tic("cyclic"); diff --git a/perception/multi_object_tracker/include/multi_object_tracker/debugger/debugger.hpp b/perception/multi_object_tracker/include/multi_object_tracker/debugger/debugger.hpp index 08d36c80d4cf8..3019f16ada7c9 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/debugger/debugger.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/debugger/debugger.hpp @@ -56,7 +56,7 @@ class TrackerDebugger rclcpp::Node & node_; rclcpp::Publisher::SharedPtr debug_tentative_objects_pub_; - std::unique_ptr processing_time_publisher_; + std::unique_ptr processing_time_publisher_; rclcpp::Publisher::SharedPtr debug_objects_markers_pub_; diagnostic_updater::Updater diagnostic_updater_; diff --git a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp index b24eadd586e73..4c1ccced1bcf7 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp @@ -73,7 +73,7 @@ class MultiObjectTracker : public rclcpp::Node // debugger std::unique_ptr debugger_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; // publish timer rclcpp::TimerBase::SharedPtr publish_timer_; diff --git a/perception/multi_object_tracker/src/data_association/data_association.cpp b/perception/multi_object_tracker/src/data_association/data_association.cpp index d033e98cce46e..013137aa8b82c 100644 --- a/perception/multi_object_tracker/src/data_association/data_association.cpp +++ b/perception/multi_object_tracker/src/data_association/data_association.cpp @@ -52,8 +52,8 @@ double getFormedYawAngle( const geometry_msgs::msg::Quaternion & tracker_quat, const bool distinguish_front_or_back = true) { const double measurement_yaw = - autoware_universe_utils::normalizeRadian(tf2::getYaw(measurement_quat)); - const double tracker_yaw = autoware_universe_utils::normalizeRadian(tf2::getYaw(tracker_quat)); + autoware::universe_utils::normalizeRadian(tf2::getYaw(measurement_quat)); + const double tracker_yaw = autoware::universe_utils::normalizeRadian(tf2::getYaw(tracker_quat)); const double angle_range = distinguish_front_or_back ? M_PI : M_PI_2; const double angle_step = distinguish_front_or_back ? 2.0 * M_PI : M_PI; // Fixed measurement_yaw to be in the range of +-90 or 180 degrees of X_t(IDX::YAW) @@ -170,7 +170,7 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( (*tracker_itr)->getTrackedObject(measurements.header.stamp, tracked_object); const double max_dist = max_dist_matrix_(tracker_label, measurement_label); - const double dist = autoware_universe_utils::calcDistance2d( + const double dist = autoware::universe_utils::calcDistance2d( measurement_object.kinematics.pose_with_covariance.pose.position, tracked_object.kinematics.pose_with_covariance.pose.position); @@ -183,7 +183,7 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( if (passed_gate) { const double max_area = max_area_matrix_(tracker_label, measurement_label); const double min_area = min_area_matrix_(tracker_label, measurement_label); - const double area = autoware_universe_utils::getArea(measurement_object.shape); + const double area = autoware::universe_utils::getArea(measurement_object.shape); if (area < min_area || max_area < area) passed_gate = false; } // angle gate diff --git a/perception/multi_object_tracker/src/debugger/debugger.cpp b/perception/multi_object_tracker/src/debugger/debugger.cpp index bb5fdef9be690..a3ece17eab112 100644 --- a/perception/multi_object_tracker/src/debugger/debugger.cpp +++ b/perception/multi_object_tracker/src/debugger/debugger.cpp @@ -24,7 +24,7 @@ TrackerDebugger::TrackerDebugger(rclcpp::Node & node, const std::string & frame_ // initialize debug publishers if (debug_settings_.publish_processing_time) { processing_time_publisher_ = - std::make_unique(&node_, "multi_object_tracker"); + std::make_unique(&node_, "multi_object_tracker"); } if (debug_settings_.publish_tentative_objects) { 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 af61cfb8259b1..54255e706e35a 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -200,7 +200,7 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) debugger_ = std::make_unique(*this, world_frame_id_); debugger_->setObjectChannels(input_names_short); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } void MultiObjectTracker::onTrigger() diff --git a/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp index fa7adb8396612..05e06107c2247 100644 --- a/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp @@ -57,9 +57,9 @@ BicycleTracker::BicycleTracker( // Initialize parameters // measurement noise covariance: detector uncertainty + ego vehicle motion uncertainty - double r_stddev_x = 0.5; // in vehicle coordinate [m] - double r_stddev_y = 0.4; // in vehicle coordinate [m] - double r_stddev_yaw = autoware_universe_utils::deg2rad(30); // in map coordinate [rad] + double r_stddev_x = 0.5; // in vehicle coordinate [m] + double r_stddev_y = 0.4; // in vehicle coordinate [m] + double r_stddev_yaw = autoware::universe_utils::deg2rad(30); // in map coordinate [rad] ekf_params_.r_cov_x = std::pow(r_stddev_x, 2.0); ekf_params_.r_cov_y = std::pow(r_stddev_y, 2.0); ekf_params_.r_cov_yaw = std::pow(r_stddev_yaw, 2.0); @@ -102,8 +102,8 @@ BicycleTracker::BicycleTracker( // Set motion limits { - constexpr double max_vel = autoware_universe_utils::kmph2mps(80); // [m/s] maximum velocity - constexpr double max_slip = 30; // [deg] maximum slip angle + constexpr double max_vel = autoware::universe_utils::kmph2mps(80); // [m/s] maximum velocity + constexpr double max_slip = 30; // [deg] maximum slip angle motion_model_.setMotionLimits(max_vel, max_slip); // maximum velocity and slip angle } @@ -126,7 +126,7 @@ BicycleTracker::BicycleTracker( constexpr double p0_stddev_x = 0.8; // in object coordinate [m] constexpr double p0_stddev_y = 0.5; // in object coordinate [m] constexpr double p0_stddev_yaw = - autoware_universe_utils::deg2rad(25); // in map coordinate [rad] + autoware::universe_utils::deg2rad(25); // in map coordinate [rad] constexpr double p0_cov_x = p0_stddev_x * p0_stddev_x; constexpr double p0_cov_y = p0_stddev_y * p0_stddev_y; constexpr double p0_cov_yaw = p0_stddev_yaw * p0_stddev_yaw; @@ -145,7 +145,7 @@ BicycleTracker::BicycleTracker( if (!object.kinematics.has_twist_covariance) { constexpr double p0_stddev_vel = - autoware_universe_utils::kmph2mps(1000); // in object coordinate [m/s] + autoware::universe_utils::kmph2mps(1000); // in object coordinate [m/s] vel_cov = std::pow(p0_stddev_vel, 2.0); } else { vel_cov = object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; @@ -153,7 +153,7 @@ BicycleTracker::BicycleTracker( const double slip = 0.0; const double p0_stddev_slip = - autoware_universe_utils::deg2rad(5); // in object coordinate [rad/s] + autoware::universe_utils::deg2rad(5); // in object coordinate [rad/s] const double slip_cov = std::pow(p0_stddev_slip, 2.0); // initialize motion model @@ -328,7 +328,7 @@ bool BicycleTracker::getTrackedObject( const auto origin_yaw = tf2::getYaw(object_.kinematics.pose_with_covariance.pose.orientation); const auto ekf_pose_yaw = tf2::getYaw(pose_with_cov.pose.orientation); object.shape.footprint = - autoware_universe_utils::rotatePolygon(object.shape.footprint, origin_yaw - ekf_pose_yaw); + autoware::universe_utils::rotatePolygon(object.shape.footprint, origin_yaw - ekf_pose_yaw); return true; } diff --git a/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp index 92815f5e33a6b..4414d8a21ca01 100644 --- a/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp @@ -58,10 +58,10 @@ BigVehicleTracker::BigVehicleTracker( // Initialize parameters // measurement noise covariance: detector uncertainty + ego vehicle motion uncertainty - float r_stddev_x = 0.5; // in vehicle coordinate [m] - float r_stddev_y = 0.4; // in vehicle coordinate [m] - float r_stddev_yaw = autoware_universe_utils::deg2rad(20); // in map coordinate [rad] - float r_stddev_vel = 1.0; // in object coordinate [m/s] + float r_stddev_x = 0.5; // in vehicle coordinate [m] + float r_stddev_y = 0.4; // in vehicle coordinate [m] + float r_stddev_yaw = autoware::universe_utils::deg2rad(20); // in map coordinate [rad] + float r_stddev_vel = 1.0; // in object coordinate [m/s] ekf_params_.r_cov_x = std::pow(r_stddev_x, 2.0); ekf_params_.r_cov_y = std::pow(r_stddev_y, 2.0); ekf_params_.r_cov_yaw = std::pow(r_stddev_yaw, 2.0); @@ -70,7 +70,7 @@ BigVehicleTracker::BigVehicleTracker( // velocity deviation threshold // if the predicted velocity is close to the observed velocity, // the observed velocity is used as the measurement. - velocity_deviation_threshold_ = autoware_universe_utils::kmph2mps(10); // [m/s] + velocity_deviation_threshold_ = autoware::universe_utils::kmph2mps(10); // [m/s] // OBJECT SHAPE MODEL if (object.shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { @@ -120,8 +120,8 @@ BigVehicleTracker::BigVehicleTracker( // Set motion limits { - constexpr double max_vel = autoware_universe_utils::kmph2mps(100); // [m/s] maximum velocity - constexpr double max_slip = 30; // [deg] maximum slip angle + constexpr double max_vel = autoware::universe_utils::kmph2mps(100); // [m/s] maximum velocity + constexpr double max_slip = 30; // [deg] maximum slip angle motion_model_.setMotionLimits(max_vel, max_slip); // maximum velocity and slip angle } @@ -144,7 +144,7 @@ BigVehicleTracker::BigVehicleTracker( constexpr double p0_stddev_x = 1.5; // in object coordinate [m] constexpr double p0_stddev_y = 0.5; // in object coordinate [m] constexpr double p0_stddev_yaw = - autoware_universe_utils::deg2rad(25); // in map coordinate [rad] + autoware::universe_utils::deg2rad(25); // in map coordinate [rad] constexpr double p0_cov_x = p0_stddev_x * p0_stddev_x; constexpr double p0_cov_y = p0_stddev_y * p0_stddev_y; constexpr double p0_cov_yaw = p0_stddev_yaw * p0_stddev_yaw; @@ -163,7 +163,7 @@ BigVehicleTracker::BigVehicleTracker( if (!object.kinematics.has_twist_covariance) { constexpr double p0_stddev_vel = - autoware_universe_utils::kmph2mps(1000); // in object coordinate [m/s] + autoware::universe_utils::kmph2mps(1000); // in object coordinate [m/s] vel_cov = std::pow(p0_stddev_vel, 2.0); } else { vel_cov = object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; @@ -171,7 +171,7 @@ BigVehicleTracker::BigVehicleTracker( const double slip = 0.0; const double p0_stddev_slip = - autoware_universe_utils::deg2rad(5); // in object coordinate [rad/s] + autoware::universe_utils::deg2rad(5); // in object coordinate [rad/s] const double slip_cov = std::pow(p0_stddev_slip, 2.0); // initialize motion model @@ -423,7 +423,7 @@ bool BigVehicleTracker::getTrackedObject( const auto origin_yaw = tf2::getYaw(object_.kinematics.pose_with_covariance.pose.orientation); const auto ekf_pose_yaw = tf2::getYaw(pose_with_cov.pose.orientation); object.shape.footprint = - autoware_universe_utils::rotatePolygon(object.shape.footprint, origin_yaw - ekf_pose_yaw); + autoware::universe_utils::rotatePolygon(object.shape.footprint, origin_yaw - ekf_pose_yaw); return true; } diff --git a/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp index 892b993a75348..1fff1a13add65 100644 --- a/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp @@ -58,10 +58,10 @@ NormalVehicleTracker::NormalVehicleTracker( // Initialize parameters // measurement noise covariance: detector uncertainty + ego vehicle motion uncertainty - float r_stddev_x = 0.5; // in vehicle coordinate [m] - float r_stddev_y = 0.4; // in vehicle coordinate [m] - float r_stddev_yaw = autoware_universe_utils::deg2rad(20); // in map coordinate [rad] - float r_stddev_vel = 1.0; // in object coordinate [m/s] + float r_stddev_x = 0.5; // in vehicle coordinate [m] + float r_stddev_y = 0.4; // in vehicle coordinate [m] + float r_stddev_yaw = autoware::universe_utils::deg2rad(20); // in map coordinate [rad] + float r_stddev_vel = 1.0; // in object coordinate [m/s] ekf_params_.r_cov_x = std::pow(r_stddev_x, 2.0); ekf_params_.r_cov_y = std::pow(r_stddev_y, 2.0); ekf_params_.r_cov_yaw = std::pow(r_stddev_yaw, 2.0); @@ -70,7 +70,7 @@ NormalVehicleTracker::NormalVehicleTracker( // velocity deviation threshold // if the predicted velocity is close to the observed velocity, // the observed velocity is used as the measurement. - velocity_deviation_threshold_ = autoware_universe_utils::kmph2mps(10); // [m/s] + velocity_deviation_threshold_ = autoware::universe_utils::kmph2mps(10); // [m/s] // OBJECT SHAPE MODEL if (object.shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { @@ -121,8 +121,8 @@ NormalVehicleTracker::NormalVehicleTracker( // Set motion limits { - constexpr double max_vel = autoware_universe_utils::kmph2mps(100); // [m/s] maximum velocity - constexpr double max_slip = 30; // [deg] maximum slip angle + constexpr double max_vel = autoware::universe_utils::kmph2mps(100); // [m/s] maximum velocity + constexpr double max_slip = 30; // [deg] maximum slip angle motion_model_.setMotionLimits(max_vel, max_slip); // maximum velocity and slip angle } @@ -145,7 +145,7 @@ NormalVehicleTracker::NormalVehicleTracker( constexpr double p0_stddev_x = 1.0; // in object coordinate [m] constexpr double p0_stddev_y = 0.3; // in object coordinate [m] constexpr double p0_stddev_yaw = - autoware_universe_utils::deg2rad(25); // in map coordinate [rad] + autoware::universe_utils::deg2rad(25); // in map coordinate [rad] constexpr double p0_cov_x = p0_stddev_x * p0_stddev_x; constexpr double p0_cov_y = p0_stddev_y * p0_stddev_y; constexpr double p0_cov_yaw = p0_stddev_yaw * p0_stddev_yaw; @@ -164,7 +164,7 @@ NormalVehicleTracker::NormalVehicleTracker( if (!object.kinematics.has_twist_covariance) { constexpr double p0_stddev_vel = - autoware_universe_utils::kmph2mps(1000); // in object coordinate [m/s] + autoware::universe_utils::kmph2mps(1000); // in object coordinate [m/s] vel_cov = std::pow(p0_stddev_vel, 2.0); } else { vel_cov = object.kinematics.twist_with_covariance.covariance[utils::MSG_COV_IDX::X_X]; @@ -172,7 +172,7 @@ NormalVehicleTracker::NormalVehicleTracker( const double slip = 0.0; const double p0_stddev_slip = - autoware_universe_utils::deg2rad(5); // in object coordinate [rad/s] + autoware::universe_utils::deg2rad(5); // in object coordinate [rad/s] const double slip_cov = std::pow(p0_stddev_slip, 2.0); // initialize motion model @@ -425,7 +425,7 @@ bool NormalVehicleTracker::getTrackedObject( const auto origin_yaw = tf2::getYaw(object_.kinematics.pose_with_covariance.pose.orientation); const auto ekf_pose_yaw = tf2::getYaw(pose_with_cov.pose.orientation); object.shape.footprint = - autoware_universe_utils::rotatePolygon(object.shape.footprint, origin_yaw - ekf_pose_yaw); + autoware::universe_utils::rotatePolygon(object.shape.footprint, origin_yaw - ekf_pose_yaw); return true; } diff --git a/perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp index 005d3c15df4df..887810066f038 100644 --- a/perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp @@ -57,9 +57,9 @@ PedestrianTracker::PedestrianTracker( // Initialize parameters // measurement noise covariance - float r_stddev_x = 0.4; // [m] - float r_stddev_y = 0.4; // [m] - float r_stddev_yaw = autoware_universe_utils::deg2rad(30); // [rad] + float r_stddev_x = 0.4; // [m] + float r_stddev_y = 0.4; // [m] + float r_stddev_yaw = autoware::universe_utils::deg2rad(30); // [rad] ekf_params_.r_cov_x = std::pow(r_stddev_x, 2.0); ekf_params_.r_cov_y = std::pow(r_stddev_y, 2.0); ekf_params_.r_cov_yaw = std::pow(r_stddev_yaw, 2.0); @@ -86,18 +86,18 @@ PedestrianTracker::PedestrianTracker( // Set motion model parameters { - constexpr double q_stddev_x = 0.5; // [m/s] - constexpr double q_stddev_y = 0.5; // [m/s] - constexpr double q_stddev_yaw = autoware_universe_utils::deg2rad(20); // [rad/s] - constexpr double q_stddev_vx = 9.8 * 0.3; // [m/(s*s)] - constexpr double q_stddev_wz = autoware_universe_utils::deg2rad(30); // [rad/(s*s)] + constexpr double q_stddev_x = 0.5; // [m/s] + constexpr double q_stddev_y = 0.5; // [m/s] + constexpr double q_stddev_yaw = autoware::universe_utils::deg2rad(20); // [rad/s] + constexpr double q_stddev_vx = 9.8 * 0.3; // [m/(s*s)] + constexpr double q_stddev_wz = autoware::universe_utils::deg2rad(30); // [rad/(s*s)] motion_model_.setMotionParams(q_stddev_x, q_stddev_y, q_stddev_yaw, q_stddev_vx, q_stddev_wz); } // Set motion limits motion_model_.setMotionLimits( - autoware_universe_utils::kmph2mps(100), /* [m/s] maximum velocity */ - 30.0 /* [deg/s] maximum turn rate */ + autoware::universe_utils::kmph2mps(100), /* [m/s] maximum velocity */ + 30.0 /* [deg/s] maximum turn rate */ ); // Set initial state @@ -121,7 +121,7 @@ PedestrianTracker::PedestrianTracker( constexpr double p0_stddev_x = 2.0; // in object coordinate [m] constexpr double p0_stddev_y = 2.0; // in object coordinate [m] constexpr double p0_stddev_yaw = - autoware_universe_utils::deg2rad(1000); // in map coordinate [rad] + autoware::universe_utils::deg2rad(1000); // in map coordinate [rad] constexpr double p0_cov_x = p0_stddev_x * p0_stddev_x; constexpr double p0_cov_y = p0_stddev_y * p0_stddev_y; constexpr double p0_cov_yaw = p0_stddev_yaw * p0_stddev_yaw; @@ -140,9 +140,9 @@ PedestrianTracker::PedestrianTracker( if (!object.kinematics.has_twist_covariance) { constexpr double p0_stddev_vel = - autoware_universe_utils::kmph2mps(120); // in object coordinate [m/s] + autoware::universe_utils::kmph2mps(120); // in object coordinate [m/s] constexpr double p0_stddev_wz = - autoware_universe_utils::deg2rad(360); // in object coordinate [rad/s] + autoware::universe_utils::deg2rad(360); // in object coordinate [rad/s] vel_cov = std::pow(p0_stddev_vel, 2.0); wz_cov = std::pow(p0_stddev_wz, 2.0); } else { @@ -323,7 +323,7 @@ bool PedestrianTracker::getTrackedObject( const auto origin_yaw = tf2::getYaw(object_.kinematics.pose_with_covariance.pose.orientation); const auto ekf_pose_yaw = tf2::getYaw(pose_with_cov.pose.orientation); object.shape.footprint = - autoware_universe_utils::rotatePolygon(object.shape.footprint, origin_yaw - ekf_pose_yaw); + autoware::universe_utils::rotatePolygon(object.shape.footprint, origin_yaw - ekf_pose_yaw); } return true; diff --git a/perception/multi_object_tracker/src/tracker/model/unknown_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/unknown_tracker.cpp index 52952c7820396..8e484623ef0aa 100644 --- a/perception/multi_object_tracker/src/tracker/model/unknown_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/unknown_tracker.cpp @@ -67,8 +67,8 @@ UnknownTracker::UnknownTracker( // Set motion limits motion_model_.setMotionLimits( - autoware_universe_utils::kmph2mps(60), /* [m/s] maximum velocity, x */ - autoware_universe_utils::kmph2mps(60) /* [m/s] maximum velocity, y */ + autoware::universe_utils::kmph2mps(60), /* [m/s] maximum velocity, x */ + autoware::universe_utils::kmph2mps(60) /* [m/s] maximum velocity, y */ ); // Set initial state @@ -107,8 +107,8 @@ UnknownTracker::UnknownTracker( } if (!object.kinematics.has_twist_covariance) { - constexpr double p0_stddev_vx = autoware_universe_utils::kmph2mps(10); // [m/s] - constexpr double p0_stddev_vy = autoware_universe_utils::kmph2mps(10); // [m/s] + constexpr double p0_stddev_vx = autoware::universe_utils::kmph2mps(10); // [m/s] + constexpr double p0_stddev_vy = autoware::universe_utils::kmph2mps(10); // [m/s] const double p0_cov_vx = std::pow(p0_stddev_vx, 2.0); const double p0_cov_vy = std::pow(p0_stddev_vy, 2.0); twist_cov[utils::MSG_COV_IDX::X_X] = p0_cov_vx; diff --git a/perception/multi_object_tracker/src/tracker/motion_model/bicycle_motion_model.cpp b/perception/multi_object_tracker/src/tracker/motion_model/bicycle_motion_model.cpp index bf040d417e6bb..f21855c2356ef 100644 --- a/perception/multi_object_tracker/src/tracker/motion_model/bicycle_motion_model.cpp +++ b/perception/multi_object_tracker/src/tracker/motion_model/bicycle_motion_model.cpp @@ -60,8 +60,8 @@ void BicycleMotionModel::setDefaultParams() lr_min); // set motion limitations - constexpr double max_vel = autoware_universe_utils::kmph2mps(100); // [m/s] maximum velocity - constexpr double max_slip = 30.0; // [deg] maximum slip angle + constexpr double max_vel = autoware::universe_utils::kmph2mps(100); // [m/s] maximum velocity + constexpr double max_slip = 30.0; // [deg] maximum slip angle setMotionLimits(max_vel, max_slip); // set prediction parameters @@ -79,13 +79,13 @@ void BicycleMotionModel::setMotionParams( // set process noise covariance parameters motion_params_.q_stddev_acc_long = q_stddev_acc_long; motion_params_.q_stddev_acc_lat = q_stddev_acc_lat; - motion_params_.q_stddev_yaw_rate_min = autoware_universe_utils::deg2rad(q_stddev_yaw_rate_min); - motion_params_.q_stddev_yaw_rate_max = autoware_universe_utils::deg2rad(q_stddev_yaw_rate_max); + motion_params_.q_stddev_yaw_rate_min = autoware::universe_utils::deg2rad(q_stddev_yaw_rate_min); + motion_params_.q_stddev_yaw_rate_max = autoware::universe_utils::deg2rad(q_stddev_yaw_rate_max); motion_params_.q_cov_slip_rate_min = - std::pow(autoware_universe_utils::deg2rad(q_stddev_slip_rate_min), 2.0); + std::pow(autoware::universe_utils::deg2rad(q_stddev_slip_rate_min), 2.0); motion_params_.q_cov_slip_rate_max = - std::pow(autoware_universe_utils::deg2rad(q_stddev_slip_rate_max), 2.0); - motion_params_.q_max_slip_angle = autoware_universe_utils::deg2rad(q_max_slip_angle); + std::pow(autoware::universe_utils::deg2rad(q_stddev_slip_rate_max), 2.0); + motion_params_.q_max_slip_angle = autoware::universe_utils::deg2rad(q_max_slip_angle); constexpr double minimum_wheel_pos = 0.01; // minimum of 0.01m if (lf_min < minimum_wheel_pos || lr_min < minimum_wheel_pos) { @@ -103,7 +103,7 @@ void BicycleMotionModel::setMotionLimits(const double & max_vel, const double & { // set motion limitations motion_params_.max_vel = max_vel; - motion_params_.max_slip = autoware_universe_utils::deg2rad(max_slip); + motion_params_.max_slip = autoware::universe_utils::deg2rad(max_slip); } bool BicycleMotionModel::initialize( @@ -252,7 +252,7 @@ bool BicycleMotionModel::limitStates() Eigen::MatrixXd P_t(DIM, DIM); ekf_.getX(X_t); ekf_.getP(P_t); - X_t(IDX::YAW) = autoware_universe_utils::normalizeRadian(X_t(IDX::YAW)); + X_t(IDX::YAW) = autoware::universe_utils::normalizeRadian(X_t(IDX::YAW)); if (!(-motion_params_.max_vel <= X_t(IDX::VEL) && X_t(IDX::VEL) <= motion_params_.max_vel)) { X_t(IDX::VEL) = X_t(IDX::VEL) < 0 ? -motion_params_.max_vel : motion_params_.max_vel; } diff --git a/perception/multi_object_tracker/src/tracker/motion_model/ctrv_motion_model.cpp b/perception/multi_object_tracker/src/tracker/motion_model/ctrv_motion_model.cpp index af05590e3b05b..79ce6e5dbb61c 100644 --- a/perception/multi_object_tracker/src/tracker/motion_model/ctrv_motion_model.cpp +++ b/perception/multi_object_tracker/src/tracker/motion_model/ctrv_motion_model.cpp @@ -40,17 +40,17 @@ CTRVMotionModel::CTRVMotionModel() : MotionModel(), logger_(rclcpp::get_logger(" void CTRVMotionModel::setDefaultParams() { // process noise covariance - constexpr double q_stddev_x = 0.5; // [m/s] - constexpr double q_stddev_y = 0.5; // [m/s] - constexpr double q_stddev_yaw = autoware_universe_utils::deg2rad(20); // [rad/s] - constexpr double q_stddev_vel = 9.8 * 0.3; // [m/(s*s)] - constexpr double q_stddev_wz = autoware_universe_utils::deg2rad(30); // [rad/(s*s)] + constexpr double q_stddev_x = 0.5; // [m/s] + constexpr double q_stddev_y = 0.5; // [m/s] + constexpr double q_stddev_yaw = autoware::universe_utils::deg2rad(20); // [rad/s] + constexpr double q_stddev_vel = 9.8 * 0.3; // [m/(s*s)] + constexpr double q_stddev_wz = autoware::universe_utils::deg2rad(30); // [rad/(s*s)] setMotionParams(q_stddev_x, q_stddev_y, q_stddev_yaw, q_stddev_vel, q_stddev_wz); // set motion limitations - constexpr double max_vel = autoware_universe_utils::kmph2mps(10); // [m/s] maximum velocity - constexpr double max_wz = 30.0; // [deg] maximum yaw rate + constexpr double max_vel = autoware::universe_utils::kmph2mps(10); // [m/s] maximum velocity + constexpr double max_wz = 30.0; // [deg] maximum yaw rate setMotionLimits(max_vel, max_wz); // set prediction parameters @@ -74,7 +74,7 @@ void CTRVMotionModel::setMotionLimits(const double & max_vel, const double & max { // set motion limitations motion_params_.max_vel = max_vel; - motion_params_.max_wz = autoware_universe_utils::deg2rad(max_wz); + motion_params_.max_wz = autoware::universe_utils::deg2rad(max_wz); } bool CTRVMotionModel::initialize( @@ -220,7 +220,7 @@ bool CTRVMotionModel::limitStates() Eigen::MatrixXd P_t(DIM, DIM); ekf_.getX(X_t); ekf_.getP(P_t); - X_t(IDX::YAW) = autoware_universe_utils::normalizeRadian(X_t(IDX::YAW)); + X_t(IDX::YAW) = autoware::universe_utils::normalizeRadian(X_t(IDX::YAW)); if (!(-motion_params_.max_vel <= X_t(IDX::VEL) && X_t(IDX::VEL) <= motion_params_.max_vel)) { X_t(IDX::VEL) = X_t(IDX::VEL) < 0 ? -motion_params_.max_vel : motion_params_.max_vel; } diff --git a/perception/multi_object_tracker/src/tracker/motion_model/cv_motion_model.cpp b/perception/multi_object_tracker/src/tracker/motion_model/cv_motion_model.cpp index 5ce944b0a79bb..8b3e9014f52d7 100644 --- a/perception/multi_object_tracker/src/tracker/motion_model/cv_motion_model.cpp +++ b/perception/multi_object_tracker/src/tracker/motion_model/cv_motion_model.cpp @@ -49,8 +49,8 @@ void CVMotionModel::setDefaultParams() setMotionParams(q_stddev_x, q_stddev_y, q_stddev_vx, q_stddev_vy); // set motion limitations - constexpr double max_vx = autoware_universe_utils::kmph2mps(60); // [m/s] maximum x velocity - constexpr double max_vy = autoware_universe_utils::kmph2mps(60); // [m/s] maximum y velocity + constexpr double max_vx = autoware::universe_utils::kmph2mps(60); // [m/s] maximum x velocity + constexpr double max_vy = autoware::universe_utils::kmph2mps(60); // [m/s] maximum y velocity setMotionLimits(max_vx, max_vy); // set prediction parameters diff --git a/perception/object_merger/include/object_merger/node.hpp b/perception/object_merger/include/object_merger/node.hpp index 26fccca21aa22..2f5918a9c7f17 100644 --- a/perception/object_merger/include/object_merger/node.hpp +++ b/perception/object_merger/include/object_merger/node.hpp @@ -84,10 +84,10 @@ class ObjectAssociationMergerNode : public rclcpp::Node } overlapped_judge_param_; // debug publisher - std::unique_ptr processing_time_publisher_; - std::unique_ptr> stop_watch_ptr_; + std::unique_ptr processing_time_publisher_; + std::unique_ptr> stop_watch_ptr_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; }; } // namespace object_association diff --git a/perception/object_merger/src/object_association_merger/data_association/data_association.cpp b/perception/object_merger/src/object_association_merger/data_association/data_association.cpp index 634be73508a2d..c32fe480ff4af 100644 --- a/perception/object_merger/src/object_association_merger/data_association/data_association.cpp +++ b/perception/object_merger/src/object_association_merger/data_association/data_association.cpp @@ -31,8 +31,8 @@ double getFormedYawAngle( const geometry_msgs::msg::Quaternion & quat0, const geometry_msgs::msg::Quaternion & quat1, const bool distinguish_front_or_back = true) { - const double yaw0 = autoware_universe_utils::normalizeRadian(tf2::getYaw(quat0)); - const double yaw1 = autoware_universe_utils::normalizeRadian(tf2::getYaw(quat1)); + const double yaw0 = autoware::universe_utils::normalizeRadian(tf2::getYaw(quat0)); + const double yaw1 = autoware::universe_utils::normalizeRadian(tf2::getYaw(quat1)); const double angle_range = distinguish_front_or_back ? M_PI : M_PI_2; const double angle_step = distinguish_front_or_back ? 2.0 * M_PI : M_PI; // Fixed yaw0 to be in the range of +-90 or 180 degrees of yaw1 @@ -133,7 +133,7 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( double score = 0.0; if (can_assign_matrix_(object1_label, object0_label)) { const double max_dist = max_dist_matrix_(object1_label, object0_label); - const double dist = autoware_universe_utils::calcDistance2d( + const double dist = autoware::universe_utils::calcDistance2d( object0.kinematics.pose_with_covariance.pose.position, object1.kinematics.pose_with_covariance.pose.position); diff --git a/perception/object_merger/src/object_association_merger/node.cpp b/perception/object_merger/src/object_association_merger/node.cpp index cc1069321f6f8..5077268731955 100644 --- a/perception/object_merger/src/object_association_merger/node.cpp +++ b/perception/object_merger/src/object_association_merger/node.cpp @@ -43,7 +43,7 @@ bool isUnknownObjectOverlapped( const double distance_threshold = distance_threshold_map.at( object_recognition_utils::getHighestProbLabel(known_object.classification)); const double sq_distance_threshold = std::pow(distance_threshold, 2.0); - const double sq_distance = autoware_universe_utils::calcSquaredDistance2d( + const double sq_distance = autoware::universe_utils::calcSquaredDistance2d( unknown_object.kinematics.pose_with_covariance.pose, known_object.kinematics.pose_with_covariance.pose); if (sq_distance_threshold < sq_distance) return false; @@ -121,13 +121,13 @@ ObjectAssociationMergerNode::ObjectAssociationMergerNode(const rclcpp::NodeOptio // Debug publisher processing_time_publisher_ = - std::make_unique(this, "object_association_merger"); + std::make_unique(this, "object_association_merger"); stop_watch_ptr_ = - std::make_unique>(); + std::make_unique>(); stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } void ObjectAssociationMergerNode::objectsCallback( diff --git a/perception/object_velocity_splitter/src/object_velocity_splitter_node/object_velocity_splitter_node.cpp b/perception/object_velocity_splitter/src/object_velocity_splitter_node/object_velocity_splitter_node.cpp index 4d635cf330fa6..e15871d18840f 100644 --- a/perception/object_velocity_splitter/src/object_velocity_splitter_node/object_velocity_splitter_node.cpp +++ b/perception/object_velocity_splitter/src/object_velocity_splitter_node/object_velocity_splitter_node.cpp @@ -74,7 +74,7 @@ void ObjectVelocitySplitterNode::onObjects(const DetectedObjects::ConstSharedPtr for (const auto & object : objects_data_->objects) { if ( - std::abs(autoware_universe_utils::calcNorm( + std::abs(autoware::universe_utils::calcNorm( object.kinematics.twist_with_covariance.twist.linear)) < node_param_.velocity_threshold) { low_speed_objects.objects.emplace_back(object); } else { diff --git a/perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp b/perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp index bed7f84ab79a2..ae6d7a34fca2a 100644 --- a/perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp +++ b/perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp @@ -120,9 +120,9 @@ class OccupancyGridMapOutlierFilterComponent : public rclcpp::Node // Debugger std::shared_ptr debugger_ptr_; - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr debug_publisher_; - std::unique_ptr published_time_publisher_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr debug_publisher_; + std::unique_ptr published_time_publisher_; // ROS Parameters std::string map_frame_; diff --git a/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp b/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp index 37811f4f6fb08..f62a3f7e689fc 100644 --- a/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp +++ b/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp @@ -73,7 +73,7 @@ geometry_msgs::msg::PoseStamped getPoseStamped( RCLCPP_WARN_THROTTLE( rclcpp::get_logger("occupancy_grid_map_outlier_filter"), clock, 5000, "%s", ex.what()); } - return autoware_universe_utils::transform2pose(tf_stamped); + return autoware::universe_utils::transform2pose(tf_stamped); } boost::optional getCost( @@ -225,8 +225,8 @@ OccupancyGridMapOutlierFilterComponent::OccupancyGridMapOutlierFilterComponent( { // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ = std::make_unique(this, "occupancy_grid_map_outlier_filter"); stop_watch_ptr_->tic("cyclic_time"); diff --git a/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/fusion/synchronized_grid_map_fusion_node.hpp b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/fusion/synchronized_grid_map_fusion_node.hpp index d09b1d9782604..84ca13c8b1881 100644 --- a/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/fusion/synchronized_grid_map_fusion_node.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/fusion/synchronized_grid_map_fusion_node.hpp @@ -85,8 +85,8 @@ class GridMapFusionNode : public rclcpp::Node rclcpp::Publisher::SharedPtr fused_map_pub_; rclcpp::Publisher::SharedPtr single_frame_pub_; std::vector::SharedPtr> grid_map_subs_; - std::unique_ptr> stop_watch_ptr_{}; - std::unique_ptr debug_publisher_ptr_{}; + std::unique_ptr> stop_watch_ptr_{}; + std::unique_ptr debug_publisher_ptr_{}; // Topics manager std::size_t num_input_topics_{1}; diff --git a/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp index 7c3b7b3e4b1a3..1d119102dc28d 100644 --- a/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp +++ b/perception/probabilistic_occupancy_grid_map/include/probabilistic_occupancy_grid_map/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp @@ -68,8 +68,8 @@ class PointcloudBasedOccupancyGridMapNode : public rclcpp::Node rclcpp::Publisher::SharedPtr occupancy_grid_map_pub_; message_filters::Subscriber obstacle_pointcloud_sub_; message_filters::Subscriber raw_pointcloud_sub_; - std::unique_ptr> stop_watch_ptr_{}; - std::unique_ptr debug_publisher_ptr_{}; + std::unique_ptr> stop_watch_ptr_{}; + std::unique_ptr debug_publisher_ptr_{}; std::shared_ptr tf2_{std::make_shared(get_clock())}; std::shared_ptr tf2_listener_{std::make_shared(*tf2_)}; diff --git a/perception/probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp b/perception/probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp index 211479ed24e6b..fa93db802b0ce 100644 --- a/perception/probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp @@ -142,8 +142,8 @@ GridMapFusionNode::GridMapFusionNode(const rclcpp::NodeOptions & node_options) // debug tools { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ptr_ = std::make_unique(this, "synchronized_grid_map_fusion"); stop_watch_ptr_->tic("cyclic_time"); diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp index f66ca3c7fc472..d4e177209f99d 100644 --- a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp @@ -55,9 +55,9 @@ void OccupancyGridMapFixedBlindSpot::updateWithPointCloud( const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud, const Pose & robot_pose, const Pose & scan_origin) { - constexpr double min_angle = autoware_universe_utils::deg2rad(-180.0); - constexpr double max_angle = autoware_universe_utils::deg2rad(180.0); - constexpr double angle_increment = autoware_universe_utils::deg2rad(0.1); + constexpr double min_angle = autoware::universe_utils::deg2rad(-180.0); + constexpr double max_angle = autoware::universe_utils::deg2rad(180.0); + constexpr double angle_increment = autoware::universe_utils::deg2rad(0.1); const size_t angle_bin_size = ((max_angle - min_angle) / angle_increment) + size_t(1 /*margin*/); // Transform from base_link to map frame diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp index 0a16c488158f1..79fc6e8c40b5e 100644 --- a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp @@ -56,9 +56,9 @@ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud( const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud, const Pose & robot_pose, const Pose & scan_origin) { - constexpr double min_angle = autoware_universe_utils::deg2rad(-180.0); - constexpr double max_angle = autoware_universe_utils::deg2rad(180.0); - constexpr double angle_increment = autoware_universe_utils::deg2rad(0.1); + constexpr double min_angle = autoware::universe_utils::deg2rad(-180.0); + constexpr double max_angle = autoware::universe_utils::deg2rad(180.0); + constexpr double angle_increment = autoware::universe_utils::deg2rad(0.1); const size_t angle_bin_size = ((max_angle - min_angle) / angle_increment) + size_t(1 /*margin*/); // Transform from base_link to map frame diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp index 2f3a97c82ccc8..d019280aefda0 100644 --- a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp @@ -119,8 +119,8 @@ PointcloudBasedOccupancyGridMapNode::PointcloudBasedOccupancyGridMapNode( // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ptr_ = std::make_unique(this, "pointcloud_based_occupancy_grid_map"); diff --git a/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp b/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp index 8e9a8431a4258..209207fe10f34 100644 --- a/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/utils/utils.cpp @@ -50,7 +50,7 @@ void transformPointcloud( const sensor_msgs::msg::PointCloud2 & input, const geometry_msgs::msg::Pose & pose, sensor_msgs::msg::PointCloud2 & output) { - const auto transform = autoware_universe_utils::pose2transform(pose); + const auto transform = autoware::universe_utils::pose2transform(pose); Eigen::Matrix4f tf_matrix = tf2::transformToEigen(transform).matrix().cast(); pcl_ros::transformPointCloud(tf_matrix, input, output); @@ -96,7 +96,7 @@ geometry_msgs::msg::Pose getPose( geometry_msgs::msg::TransformStamped tf_stamped; tf_stamped = tf2.lookupTransform( target_frame, source_header.frame_id, source_header.stamp, rclcpp::Duration::from_seconds(0.5)); - pose = autoware_universe_utils::transform2pose(tf_stamped.transform); + pose = autoware::universe_utils::transform2pose(tf_stamped.transform); return pose; } @@ -108,7 +108,7 @@ geometry_msgs::msg::Pose getPose( geometry_msgs::msg::TransformStamped tf_stamped; tf_stamped = tf2.lookupTransform(target_frame, source_frame, stamp, rclcpp::Duration::from_seconds(0.5)); - pose = autoware_universe_utils::transform2pose(tf_stamped.transform); + pose = autoware::universe_utils::transform2pose(tf_stamped.transform); return pose; } diff --git a/perception/radar_crossing_objects_noise_filter/src/radar_crossing_objects_noise_filter_node/radar_crossing_objects_noise_filter_node.cpp b/perception/radar_crossing_objects_noise_filter/src/radar_crossing_objects_noise_filter_node/radar_crossing_objects_noise_filter_node.cpp index 339cb8afa454b..2f5884c04ce37 100644 --- a/perception/radar_crossing_objects_noise_filter/src/radar_crossing_objects_noise_filter_node/radar_crossing_objects_noise_filter_node.cpp +++ b/perception/radar_crossing_objects_noise_filter/src/radar_crossing_objects_noise_filter_node/radar_crossing_objects_noise_filter_node.cpp @@ -125,13 +125,13 @@ rcl_interfaces::msg::SetParametersResult RadarCrossingObjectsNoiseFilterNode::on bool RadarCrossingObjectsNoiseFilterNode::isNoise(const DetectedObject & object) { const double velocity = std::abs( - autoware_universe_utils::calcNorm(object.kinematics.twist_with_covariance.twist.linear)); + autoware::universe_utils::calcNorm(object.kinematics.twist_with_covariance.twist.linear)); const double object_angle = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); const double object_position_angle = std::atan2( object.kinematics.pose_with_covariance.pose.position.y, object.kinematics.pose_with_covariance.pose.position.x); const double crossing_yaw = - autoware_universe_utils::normalizeRadian(object_angle - object_position_angle); + autoware::universe_utils::normalizeRadian(object_angle - object_position_angle); if ( velocity > node_param_.velocity_threshold && diff --git a/perception/radar_crossing_objects_noise_filter/test/test_radar_crossing_objects_noise_filter/test_radar_crossing_objects_filter_is_noise.cpp b/perception/radar_crossing_objects_noise_filter/test/test_radar_crossing_objects_noise_filter/test_radar_crossing_objects_filter_is_noise.cpp index 501edcbe84af8..44ccaae8ee7fc 100644 --- a/perception/radar_crossing_objects_noise_filter/test/test_radar_crossing_objects_noise_filter/test_radar_crossing_objects_filter_is_noise.cpp +++ b/perception/radar_crossing_objects_noise_filter/test/test_radar_crossing_objects_noise_filter/test_radar_crossing_objects_filter_is_noise.cpp @@ -48,9 +48,9 @@ TEST(RadarCrossingObjectsFilter, IsNoise) { rclcpp::init(0, nullptr); { - auto velocity = autoware_universe_utils::createVector3(40.0, 30.0, 0.0); - auto position = autoware_universe_utils::createPoint(1.0, 0.0, 0.0); - auto orientation = autoware_universe_utils::createQuaternion(1.0, 1.0, 1.0, 0.0); + auto velocity = autoware::universe_utils::createVector3(40.0, 30.0, 0.0); + auto position = autoware::universe_utils::createPoint(1.0, 0.0, 0.0); + auto orientation = autoware::universe_utils::createQuaternion(1.0, 1.0, 1.0, 0.0); auto object = get_object(velocity, position, orientation); { double velocity_threshold = 40.0; @@ -81,9 +81,9 @@ TEST(RadarCrossingObjectsFilter, IsNoise) } { - auto velocity = autoware_universe_utils::createVector3(40.0, 30.0, 0.0); - auto position = autoware_universe_utils::createPoint(1.0, 2.0, 0.0); - auto orientation = autoware_universe_utils::createQuaternion(1.0, 1.0, 1.0, 0.0); + auto velocity = autoware::universe_utils::createVector3(40.0, 30.0, 0.0); + auto position = autoware::universe_utils::createPoint(1.0, 2.0, 0.0); + auto orientation = autoware::universe_utils::createQuaternion(1.0, 1.0, 1.0, 0.0); auto object = get_object(velocity, position, orientation); { double velocity_threshold = 40.0; @@ -112,9 +112,9 @@ TEST(RadarCrossingObjectsFilter, IsNoise) } { - auto velocity = autoware_universe_utils::createVector3(24.0, 18.0, 0.0); - auto position = autoware_universe_utils::createPoint(1.0, 0.0, 0.0); - auto orientation = autoware_universe_utils::createQuaternion(1.0, 1.0, 1.0, 0.0); + auto velocity = autoware::universe_utils::createVector3(24.0, 18.0, 0.0); + auto position = autoware::universe_utils::createPoint(1.0, 0.0, 0.0); + auto orientation = autoware::universe_utils::createQuaternion(1.0, 1.0, 1.0, 0.0); auto object = get_object(velocity, position, orientation); { double velocity_threshold = 40.0; @@ -143,9 +143,9 @@ TEST(RadarCrossingObjectsFilter, IsNoise) } { - auto velocity = autoware_universe_utils::createVector3(24.0, 18.0, 0.0); - auto position = autoware_universe_utils::createPoint(1.0, 2.0, 0.0); - auto orientation = autoware_universe_utils::createQuaternion(1.0, 1.0, 1.0, 0.0); + auto velocity = autoware::universe_utils::createVector3(24.0, 18.0, 0.0); + auto position = autoware::universe_utils::createPoint(1.0, 2.0, 0.0); + auto orientation = autoware::universe_utils::createQuaternion(1.0, 1.0, 1.0, 0.0); auto object = get_object(velocity, position, orientation); { double velocity_threshold = 40.0; diff --git a/perception/radar_fusion_to_detected_object/include/radar_fusion_to_detected_object/radar_fusion_to_detected_object.hpp b/perception/radar_fusion_to_detected_object/include/radar_fusion_to_detected_object/radar_fusion_to_detected_object.hpp index ef6891c6c8944..cd7e7de6b2ff4 100644 --- a/perception/radar_fusion_to_detected_object/include/radar_fusion_to_detected_object/radar_fusion_to_detected_object.hpp +++ b/perception/radar_fusion_to_detected_object/include/radar_fusion_to_detected_object/radar_fusion_to_detected_object.hpp @@ -32,10 +32,10 @@ namespace radar_fusion_to_detected_object { +using autoware::universe_utils::LinearRing2d; +using autoware::universe_utils::Point2d; using autoware_perception_msgs::msg::DetectedObject; using autoware_perception_msgs::msg::DetectedObjects; -using autoware_universe_utils::LinearRing2d; -using autoware_universe_utils::Point2d; using geometry_msgs::msg::Point; using geometry_msgs::msg::PoseWithCovariance; using geometry_msgs::msg::Twist; diff --git a/perception/radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp b/perception/radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp index 85940b7f99f3d..5a0c1b5412312 100644 --- a/perception/radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp +++ b/perception/radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp @@ -29,10 +29,10 @@ namespace radar_fusion_to_detected_object { +using autoware::universe_utils::LinearRing2d; +using autoware::universe_utils::Point2d; using autoware_perception_msgs::msg::DetectedObject; using autoware_perception_msgs::msg::DetectedObjects; -using autoware_universe_utils::LinearRing2d; -using autoware_universe_utils::Point2d; using geometry_msgs::msg::Point; using geometry_msgs::msg::PoseWithCovariance; using geometry_msgs::msg::Twist; @@ -136,7 +136,7 @@ RadarFusionToDetectedObject::Output RadarFusionToDetectedObject::update( bool RadarFusionToDetectedObject::hasTwistCovariance( const TwistWithCovariance & twist_with_covariance) { - using IDX = autoware_universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + using IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; auto covariance = twist_with_covariance.covariance; if (covariance[IDX::X_X] == 0.0 && covariance[IDX::Y_Y] == 0.0 && covariance[IDX::Z_Z] == 0.0) { return false; @@ -151,11 +151,11 @@ bool RadarFusionToDetectedObject::isYawCorrect( const DetectedObject & object, const TwistWithCovariance & twist_with_covariance, const double & yaw_threshold) { - const double twist_yaw = autoware_universe_utils::normalizeRadian( + const double twist_yaw = autoware::universe_utils::normalizeRadian( std::atan2(twist_with_covariance.twist.linear.y, twist_with_covariance.twist.linear.x)); - const double object_yaw = autoware_universe_utils::normalizeRadian( + const double object_yaw = autoware::universe_utils::normalizeRadian( tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation)); - const double diff_yaw = autoware_universe_utils::normalizeRadian(twist_yaw - object_yaw); + const double diff_yaw = autoware::universe_utils::normalizeRadian(twist_yaw - object_yaw); if (std::abs(diff_yaw) < yaw_threshold) { return true; } else if (M_PI - yaw_threshold < std::abs(diff_yaw)) { @@ -174,12 +174,12 @@ RadarFusionToDetectedObject::filterRadarWithinObject( { std::vector outputs{}; - autoware_universe_utils::Point2d object_size{ + autoware::universe_utils::Point2d object_size{ object.shape.dimensions.x, object.shape.dimensions.y}; LinearRing2d object_box = createObject2dWithMargin(object_size, param_.bounding_box_margin); - object_box = autoware_universe_utils::transformVector( + object_box = autoware::universe_utils::transformVector( object_box, - autoware_universe_utils::pose2transform(object.kinematics.pose_with_covariance.pose)); + autoware::universe_utils::pose2transform(object.kinematics.pose_with_covariance.pose)); for (const auto & radar : (*radars)) { Point2d radar_point{ @@ -214,10 +214,10 @@ TwistWithCovariance RadarFusionToDetectedObject::estimateTwist( Eigen::Vector2d vec_min_distance(0.0, 0.0); if (param_.velocity_weight_min_distance > 0.0) { auto comp_func = [&](const RadarInput & a, const RadarInput & b) { - return autoware_universe_utils::calcSquaredDistance2d( + return autoware::universe_utils::calcSquaredDistance2d( a.pose_with_covariance.pose.position, object.kinematics.pose_with_covariance.pose.position) < - autoware_universe_utils::calcSquaredDistance2d( + autoware::universe_utils::calcSquaredDistance2d( b.pose_with_covariance.pose.position, object.kinematics.pose_with_covariance.pose.position); }; diff --git a/perception/radar_object_clustering/README.md b/perception/radar_object_clustering/README.md index abd2b6f9d1bfe..8f936ce61a1f3 100644 --- a/perception/radar_object_clustering/README.md +++ b/perception/radar_object_clustering/README.md @@ -83,13 +83,13 @@ These are used in `isSameObject` function as below. bool RadarObjectClusteringNode::isSameObject( const DetectedObject & object_1, const DetectedObject & object_2) { - const double angle_diff = std::abs(autoware_universe_utils::normalizeRadian( + const double angle_diff = std::abs(autoware::universe_utils::normalizeRadian( tf2::getYaw(object_1.kinematics.pose_with_covariance.pose.orientation) - tf2::getYaw(object_2.kinematics.pose_with_covariance.pose.orientation))); const double velocity_diff = std::abs( object_1.kinematics.twist_with_covariance.twist.linear.x - object_2.kinematics.twist_with_covariance.twist.linear.x); - const double distance = autoware_universe_utils::calcDistance2d( + const double distance = autoware::universe_utils::calcDistance2d( object_1.kinematics.pose_with_covariance.pose.position, object_2.kinematics.pose_with_covariance.pose.position); diff --git a/perception/radar_object_clustering/src/radar_object_clustering_node/radar_object_clustering_node.cpp b/perception/radar_object_clustering/src/radar_object_clustering_node/radar_object_clustering_node.cpp index 1681260c711b2..339ab21741d29 100644 --- a/perception/radar_object_clustering/src/radar_object_clustering_node/radar_object_clustering_node.cpp +++ b/perception/radar_object_clustering/src/radar_object_clustering_node/radar_object_clustering_node.cpp @@ -179,13 +179,13 @@ void RadarObjectClusteringNode::onObjects(const DetectedObjects::ConstSharedPtr bool RadarObjectClusteringNode::isSameObject( const DetectedObject & object_1, const DetectedObject & object_2) { - const double angle_diff = std::abs(autoware_universe_utils::normalizeRadian( + const double angle_diff = std::abs(autoware::universe_utils::normalizeRadian( tf2::getYaw(object_1.kinematics.pose_with_covariance.pose.orientation) - tf2::getYaw(object_2.kinematics.pose_with_covariance.pose.orientation))); const double velocity_diff = std::abs( object_1.kinematics.twist_with_covariance.twist.linear.x - object_2.kinematics.twist_with_covariance.twist.linear.x); - const double distance = autoware_universe_utils::calcDistance2d( + const double distance = autoware::universe_utils::calcDistance2d( object_1.kinematics.pose_with_covariance.pose.position, object_2.kinematics.pose_with_covariance.pose.position); diff --git a/perception/radar_object_tracker/src/data_association/data_association.cpp b/perception/radar_object_tracker/src/data_association/data_association.cpp index ddfb0c3e8f76d..b308f62a24dfa 100644 --- a/perception/radar_object_tracker/src/data_association/data_association.cpp +++ b/perception/radar_object_tracker/src/data_association/data_association.cpp @@ -55,8 +55,8 @@ double getFormedYawAngle( const geometry_msgs::msg::Quaternion & tracker_quat, const bool distinguish_front_or_back = true) { const double measurement_yaw = - autoware_universe_utils::normalizeRadian(tf2::getYaw(measurement_quat)); - const double tracker_yaw = autoware_universe_utils::normalizeRadian(tf2::getYaw(tracker_quat)); + autoware::universe_utils::normalizeRadian(tf2::getYaw(measurement_quat)); + const double tracker_yaw = autoware::universe_utils::normalizeRadian(tf2::getYaw(tracker_quat)); const double angle_range = distinguish_front_or_back ? M_PI : M_PI_2; const double angle_step = distinguish_front_or_back ? 2.0 * M_PI : M_PI; // Fixed measurement_yaw to be in the range of +-90 or 180 degrees of X_t(IDX::YAW) @@ -203,7 +203,7 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( double score = 0.0; if (can_assign_matrix_(tracker_label, measurement_label)) { const double max_dist = max_dist_matrix_(tracker_label, measurement_label); - const double dist = autoware_universe_utils::calcDistance2d( + const double dist = autoware::universe_utils::calcDistance2d( measurement_object.kinematics.pose_with_covariance.pose.position, tracked_object.kinematics.pose_with_covariance.pose.position); @@ -221,7 +221,7 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( if (passed_gate) { const double max_area = max_area_matrix_(tracker_label, measurement_label); const double min_area = min_area_matrix_(tracker_label, measurement_label); - const double area = autoware_universe_utils::getArea(measurement_object.shape); + const double area = autoware::universe_utils::getArea(measurement_object.shape); if (area < min_area || max_area < area) { passed_gate = false; } diff --git a/perception/radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp b/perception/radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp index 0548002606d5d..e1603fbfab702 100644 --- a/perception/radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp +++ b/perception/radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp @@ -209,7 +209,7 @@ void ConstantTurnRateMotionTracker::loadDefaultModelParameters(const std::string // limitation // (TODO): this may be written in another yaml file based on classify result const float max_speed_kmph = config["default"]["limit"]["max_speed"].as(); // [km/h] - max_vx_ = autoware_universe_utils::kmph2mps(max_speed_kmph); // [m/s] + max_vx_ = autoware::universe_utils::kmph2mps(max_speed_kmph); // [m/s] } bool ConstantTurnRateMotionTracker::predict(const rclcpp::Time & time) @@ -393,7 +393,7 @@ bool ConstantTurnRateMotionTracker::measureWithPose( Eigen::MatrixXd Y_yaw = Eigen::MatrixXd::Zero(1, 1); const auto yaw = [&] { - auto obj_yaw = autoware_universe_utils::normalizeRadian( + auto obj_yaw = autoware::universe_utils::normalizeRadian( tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation)); while (M_PI_2 <= yaw_state - obj_yaw) { obj_yaw = obj_yaw + M_PI; @@ -617,7 +617,7 @@ bool ConstantTurnRateMotionTracker::getTrackedObject( const auto origin_yaw = tf2::getYaw(object_.kinematics.pose_with_covariance.pose.orientation); const auto ekf_pose_yaw = tf2::getYaw(pose_with_cov.pose.orientation); object.shape.footprint = - autoware_universe_utils::rotatePolygon(object.shape.footprint, origin_yaw - ekf_pose_yaw); + autoware::universe_utils::rotatePolygon(object.shape.footprint, origin_yaw - ekf_pose_yaw); } return true; diff --git a/perception/radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp b/perception/radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp index 754ff88861b0d..1bc548fa7a951 100644 --- a/perception/radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp +++ b/perception/radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp @@ -237,8 +237,8 @@ void LinearMotionTracker::loadDefaultModelParameters(const std::string & path) // limitation // (TODO): this may be written in another yaml file based on classify result const float max_speed_kmph = config["default"]["limit"]["max_speed"].as(); // [km/h] - max_vx_ = autoware_universe_utils::kmph2mps(max_speed_kmph); // [m/s] - max_vy_ = autoware_universe_utils::kmph2mps(max_speed_kmph); // [rad/s] + max_vx_ = autoware::universe_utils::kmph2mps(max_speed_kmph); // [m/s] + max_vy_ = autoware::universe_utils::kmph2mps(max_speed_kmph); // [rad/s] } bool LinearMotionTracker::predict(const rclcpp::Time & time) @@ -682,7 +682,7 @@ bool LinearMotionTracker::getTrackedObject( const auto origin_yaw = tf2::getYaw(object_.kinematics.pose_with_covariance.pose.orientation); const auto ekf_pose_yaw = tf2::getYaw(pose_with_cov.pose.orientation); object.shape.footprint = - autoware_universe_utils::rotatePolygon(object.shape.footprint, origin_yaw - ekf_pose_yaw); + autoware::universe_utils::rotatePolygon(object.shape.footprint, origin_yaw - ekf_pose_yaw); } return true; diff --git a/perception/radar_object_tracker/src/utils/radar_object_tracker_utils.cpp b/perception/radar_object_tracker/src/utils/radar_object_tracker_utils.cpp index fa1acda54e4fe..ba2500a60beff 100644 --- a/perception/radar_object_tracker/src/utils/radar_object_tracker_utils.cpp +++ b/perception/radar_object_tracker/src/utils/radar_object_tracker_utils.cpp @@ -81,10 +81,10 @@ bool checkCloseLaneletCondition( double object_motion_yaw = object_yaw; bool velocity_is_reverted = object.kinematics.twist_with_covariance.twist.linear.x < 0.0; if (velocity_is_reverted) { - object_motion_yaw = autoware_universe_utils::normalizeRadian(object_yaw + M_PI); + object_motion_yaw = autoware::universe_utils::normalizeRadian(object_yaw + M_PI); } const double delta_yaw = object_motion_yaw - lane_yaw; - const double normalized_delta_yaw = autoware_universe_utils::normalizeRadian(delta_yaw); + const double normalized_delta_yaw = autoware::universe_utils::normalizeRadian(delta_yaw); const double abs_norm_delta_yaw = std::fabs(normalized_delta_yaw); if (abs_norm_delta_yaw > max_angle_diff_from_lane) { @@ -134,14 +134,14 @@ bool hasValidVelocityDirectionToLanelet( const double object_vel_y = object.kinematics.twist_with_covariance.twist.linear.y; const double object_vel_yaw = std::atan2(object_vel_y, object_vel_x); const double object_vel_yaw_global = - autoware_universe_utils::normalizeRadian(object_yaw + object_vel_yaw); + autoware::universe_utils::normalizeRadian(object_yaw + object_vel_yaw); const double object_vel = std::hypot(object_vel_x, object_vel_y); for (const auto & lanelet : lanelets) { const double lane_yaw = lanelet::utils::getLaneletAngle( lanelet, object.kinematics.pose_with_covariance.pose.position); const double delta_yaw = object_vel_yaw_global - lane_yaw; - const double normalized_delta_yaw = autoware_universe_utils::normalizeRadian(delta_yaw); + const double normalized_delta_yaw = autoware::universe_utils::normalizeRadian(delta_yaw); const double lane_vel = object_vel * std::sin(normalized_delta_yaw); if (std::fabs(lane_vel) < max_lateral_velocity) { diff --git a/perception/radar_tracks_msgs_converter/include/radar_tracks_msgs_converter/radar_tracks_msgs_converter_node.hpp b/perception/radar_tracks_msgs_converter/include/radar_tracks_msgs_converter/radar_tracks_msgs_converter_node.hpp index 8db732245b1fd..30d02c90b0594 100644 --- a/perception/radar_tracks_msgs_converter/include/radar_tracks_msgs_converter/radar_tracks_msgs_converter_node.hpp +++ b/perception/radar_tracks_msgs_converter/include/radar_tracks_msgs_converter/radar_tracks_msgs_converter_node.hpp @@ -64,7 +64,7 @@ class RadarTracksMsgsConverterNode : public rclcpp::Node // Subscriber rclcpp::Subscription::SharedPtr sub_radar_{}; rclcpp::Subscription::SharedPtr sub_odometry_{}; - std::shared_ptr transform_listener_; + std::shared_ptr transform_listener_; // Callback void onRadarTracks(const RadarTracks::ConstSharedPtr msg); diff --git a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp index 0caf29df2735e..36f4d3cd3da90 100644 --- a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp +++ b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp @@ -92,7 +92,7 @@ RadarTracksMsgsConverterNode::RadarTracksMsgsConverterNode(const rclcpp::NodeOpt sub_odometry_ = create_subscription( "~/input/odometry", rclcpp::QoS{1}, std::bind(&RadarTracksMsgsConverterNode::onTwist, this, _1)); - transform_listener_ = std::make_shared(this); + transform_listener_ = std::make_shared(this); // Publisher pub_tracked_objects_ = create_publisher("~/output/radar_tracked_objects", 1); @@ -261,7 +261,7 @@ TrackedObjects RadarTracksMsgsConverterNode::convertRadarTrackToTrackedObjects() } // yaw angle (vehicle heading) is obtained from ground velocity - double yaw = autoware_universe_utils::normalizeRadian( + double yaw = autoware::universe_utils::normalizeRadian( std::atan2(compensated_velocity.y, compensated_velocity.x)); // kinematics setting @@ -273,7 +273,7 @@ TrackedObjects RadarTracksMsgsConverterNode::convertRadarTrackToTrackedObjects() // velocity of object is defined in the object coordinate // heading is obtained from ground velocity kinematics.pose_with_covariance.pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(yaw); + autoware::universe_utils::createQuaternionFromYaw(yaw); // longitudinal velocity is the length of the velocity vector // lateral velocity is zero, use default value kinematics.twist_with_covariance.twist.linear.x = std::sqrt( @@ -334,8 +334,8 @@ geometry_msgs::msg::Vector3 RadarTracksMsgsConverterNode::compensateVelocityEgoM std::array RadarTracksMsgsConverterNode::convertPoseCovarianceMatrix( const radar_msgs::msg::RadarTrack & radar_track) { - using POSE_IDX = autoware_universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; - using RADAR_IDX = autoware_universe_utils::xyz_upper_covariance_index::XYZ_UPPER_COV_IDX; + using POSE_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + using RADAR_IDX = autoware::universe_utils::xyz_upper_covariance_index::XYZ_UPPER_COV_IDX; std::array pose_covariance{}; pose_covariance[POSE_IDX::X_X] = radar_track.position_covariance[RADAR_IDX::X_X]; pose_covariance[POSE_IDX::X_Y] = radar_track.position_covariance[RADAR_IDX::X_Y]; @@ -351,8 +351,8 @@ std::array RadarTracksMsgsConverterNode::convertPoseCovarianceMatrix std::array RadarTracksMsgsConverterNode::convertTwistCovarianceMatrix( const radar_msgs::msg::RadarTrack & radar_track) { - using POSE_IDX = autoware_universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; - using RADAR_IDX = autoware_universe_utils::xyz_upper_covariance_index::XYZ_UPPER_COV_IDX; + using POSE_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + using RADAR_IDX = autoware::universe_utils::xyz_upper_covariance_index::XYZ_UPPER_COV_IDX; std::array twist_covariance{}; twist_covariance[POSE_IDX::X_X] = radar_track.velocity_covariance[RADAR_IDX::X_X]; twist_covariance[POSE_IDX::X_Y] = radar_track.velocity_covariance[RADAR_IDX::X_Y]; @@ -368,8 +368,8 @@ std::array RadarTracksMsgsConverterNode::convertTwistCovarianceMatri std::array RadarTracksMsgsConverterNode::convertAccelerationCovarianceMatrix( const radar_msgs::msg::RadarTrack & radar_track) { - using POSE_IDX = autoware_universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; - using RADAR_IDX = autoware_universe_utils::xyz_upper_covariance_index::XYZ_UPPER_COV_IDX; + using POSE_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + using RADAR_IDX = autoware::universe_utils::xyz_upper_covariance_index::XYZ_UPPER_COV_IDX; std::array acceleration_covariance{}; acceleration_covariance[POSE_IDX::X_X] = radar_track.acceleration_covariance[RADAR_IDX::X_X]; acceleration_covariance[POSE_IDX::X_Y] = radar_track.acceleration_covariance[RADAR_IDX::X_Y]; diff --git a/perception/raindrop_cluster_filter/include/raindrop_cluster_filter/low_intensity_cluster_filter/low_intensity_cluster_filter.hpp b/perception/raindrop_cluster_filter/include/raindrop_cluster_filter/low_intensity_cluster_filter/low_intensity_cluster_filter.hpp index 5e010b21478fc..b3ebc4d916947 100644 --- a/perception/raindrop_cluster_filter/include/raindrop_cluster_filter/low_intensity_cluster_filter/low_intensity_cluster_filter.hpp +++ b/perception/raindrop_cluster_filter/include/raindrop_cluster_filter/low_intensity_cluster_filter/low_intensity_cluster_filter.hpp @@ -68,9 +68,9 @@ class LowIntensityClusterFilter : public rclcpp::Node utils::FilterTargetLabel filter_target_; // debugger - std::unique_ptr> stop_watch_ptr_{ + std::unique_ptr> stop_watch_ptr_{ nullptr}; - std::unique_ptr debug_publisher_ptr_{nullptr}; + std::unique_ptr debug_publisher_ptr_{nullptr}; }; } // namespace low_intensity_cluster_filter diff --git a/perception/raindrop_cluster_filter/src/low_intensity_cluster_filter.cpp b/perception/raindrop_cluster_filter/src/low_intensity_cluster_filter.cpp index cae09d3cb20e7..4772c355ec0b6 100644 --- a/perception/raindrop_cluster_filter/src/low_intensity_cluster_filter.cpp +++ b/perception/raindrop_cluster_filter/src/low_intensity_cluster_filter.cpp @@ -52,8 +52,8 @@ LowIntensityClusterFilter::LowIntensityClusterFilter(const rclcpp::NodeOptions & "output/objects", rclcpp::QoS{1}); // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ptr_ = std::make_unique(this, "low_intensity_cluster_filter_node"); @@ -85,8 +85,8 @@ void LowIntensityClusterFilter::objectCallback( geometry_msgs::msg::Pose max_pose; max_pose.position.x = max_x_; max_pose.position.y = max_y_; - auto min_ranged_transformed = autoware_universe_utils::transformPose(min_range, transform_stamp); - auto max_range_transformed = autoware_universe_utils::transformPose(max_pose, transform_stamp); + auto min_ranged_transformed = autoware::universe_utils::transformPose(min_range, transform_stamp); + auto max_range_transformed = autoware::universe_utils::transformPose(max_pose, transform_stamp); for (const auto & feature_object : input_msg->feature_objects) { const auto & object = feature_object.object; const auto & label = object.classification.front().label; diff --git a/perception/shape_estimation/lib/corrector/utils.cpp b/perception/shape_estimation/lib/corrector/utils.cpp index 953736e0924ce..1332647b0f1f4 100644 --- a/perception/shape_estimation/lib/corrector/utils.cpp +++ b/perception/shape_estimation/lib/corrector/utils.cpp @@ -246,9 +246,9 @@ bool correctWithDefaultValue( // correct to set long length is x, short length is y if (shape.dimensions.x < shape.dimensions.y) { - geometry_msgs::msg::Vector3 rpy = autoware_universe_utils::getRPY(pose.orientation); + geometry_msgs::msg::Vector3 rpy = autoware::universe_utils::getRPY(pose.orientation); rpy.z = rpy.z + M_PI_2; - pose.orientation = autoware_universe_utils::createQuaternionFromRPY(rpy.x, rpy.y, rpy.z); + pose.orientation = autoware::universe_utils::createQuaternionFromRPY(rpy.x, rpy.y, rpy.z); double temp = shape.dimensions.x; shape.dimensions.x = shape.dimensions.y; shape.dimensions.y = temp; diff --git a/perception/shape_estimation/src/node.cpp b/perception/shape_estimation/src/node.cpp index 119b0d22b3f7d..5719cd97b3ed5 100644 --- a/perception/shape_estimation/src/node.cpp +++ b/perception/shape_estimation/src/node.cpp @@ -54,13 +54,13 @@ ShapeEstimationNode::ShapeEstimationNode(const rclcpp::NodeOptions & node_option std::make_unique(use_corrector, use_filter, use_boost_bbox_optimizer); processing_time_publisher_ = - std::make_unique(this, "shape_estimation"); + std::make_unique(this, "shape_estimation"); stop_watch_ptr_ = - std::make_unique>(); + std::make_unique>(); stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } static autoware_perception_msgs::msg::ObjectClassification::_label_type get_label( @@ -114,7 +114,7 @@ void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstShared if (use_vehicle_reference_yaw_ && is_vehicle) { ref_yaw_info = ReferenceYawInfo{ static_cast(tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation)), - autoware_universe_utils::deg2rad(10)}; + autoware::universe_utils::deg2rad(10)}; } if (use_vehicle_reference_shape_size_ && is_vehicle) { ref_shape_size_info = ReferenceShapeSizeInfo{object.shape, ReferenceShapeSizeInfo::Mode::Min}; diff --git a/perception/shape_estimation/src/node.hpp b/perception/shape_estimation/src/node.hpp index db2a8b9ddaedd..807f12e39b025 100644 --- a/perception/shape_estimation/src/node.hpp +++ b/perception/shape_estimation/src/node.hpp @@ -35,11 +35,11 @@ class ShapeEstimationNode : public rclcpp::Node // ros rclcpp::Publisher::SharedPtr pub_; rclcpp::Subscription::SharedPtr sub_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; // debug publisher - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr processing_time_publisher_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr processing_time_publisher_; void callback(const DetectedObjectsWithFeature::ConstSharedPtr input_msg); diff --git a/perception/simple_object_merger/include/simple_object_merger/simple_object_merger_node.hpp b/perception/simple_object_merger/include/simple_object_merger/simple_object_merger_node.hpp index 73ccd33464d81..d25eef20cc676 100644 --- a/perception/simple_object_merger/include/simple_object_merger/simple_object_merger_node.hpp +++ b/perception/simple_object_merger/include/simple_object_merger/simple_object_merger_node.hpp @@ -47,7 +47,7 @@ class SimpleObjectMergerNode : public rclcpp::Node // Subscriber rclcpp::Subscription::SharedPtr sub_objects_{}; std::vector::SharedPtr> sub_objects_array{}; - std::shared_ptr transform_listener_; + std::shared_ptr transform_listener_; // Callback void onData(const DetectedObjects::ConstSharedPtr msg, size_t array_number); diff --git a/perception/simple_object_merger/src/simple_object_merger_node/simple_object_merger_node.cpp b/perception/simple_object_merger/src/simple_object_merger_node/simple_object_merger_node.cpp index af8f02caef72b..faa531560ba09 100644 --- a/perception/simple_object_merger/src/simple_object_merger_node/simple_object_merger_node.cpp +++ b/perception/simple_object_merger/src/simple_object_merger_node/simple_object_merger_node.cpp @@ -98,7 +98,7 @@ SimpleObjectMergerNode::SimpleObjectMergerNode(const rclcpp::NodeOptions & node_ } // Subscriber - transform_listener_ = std::make_shared(this); + transform_listener_ = std::make_shared(this); sub_objects_array.resize(input_topic_size); objects_data_.resize(input_topic_size); diff --git a/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox_node.hpp b/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox_node.hpp index 885852106a82c..6044148a932ae 100644 --- a/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox_node.hpp +++ b/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox_node.hpp @@ -63,8 +63,8 @@ class TrtYoloXNode : public rclcpp::Node LabelMap label_map_; std::unique_ptr trt_yolox_; - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr debug_publisher_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr debug_publisher_; }; } // namespace tensorrt_yolox diff --git a/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp b/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp index 4eb266445489e..4ee18b99e4bc6 100644 --- a/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp +++ b/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp @@ -31,9 +31,9 @@ TrtYoloXNode::TrtYoloXNode(const rclcpp::NodeOptions & node_options) { { stop_watch_ptr_ = - std::make_unique>(); + std::make_unique>(); debug_publisher_ = - std::make_unique(this, "tensorrt_yolox"); + std::make_unique(this, "tensorrt_yolox"); stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); } diff --git a/perception/tracking_object_merger/include/tracking_object_merger/decorative_tracker_merger.hpp b/perception/tracking_object_merger/include/tracking_object_merger/decorative_tracker_merger.hpp index be03ec3868af9..3683ba02b38cd 100644 --- a/perception/tracking_object_merger/include/tracking_object_merger/decorative_tracker_merger.hpp +++ b/perception/tracking_object_merger/include/tracking_object_merger/decorative_tracker_merger.hpp @@ -86,8 +86,8 @@ class DecorativeTrackerMergerNode : public rclcpp::Node // debug object publisher rclcpp::Publisher::SharedPtr debug_object_pub_; bool publish_interpolated_sub_objects_; - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr processing_time_publisher_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr processing_time_publisher_; /* handle objects */ std::unordered_map> @@ -106,7 +106,7 @@ class DecorativeTrackerMergerNode : public rclcpp::Node // tracker default settings TrackerStateParameter tracker_state_parameter_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; // merge policy (currently not used) struct diff --git a/perception/tracking_object_merger/src/data_association/data_association.cpp b/perception/tracking_object_merger/src/data_association/data_association.cpp index ae4c05013b7db..4d10a415df7da 100644 --- a/perception/tracking_object_merger/src/data_association/data_association.cpp +++ b/perception/tracking_object_merger/src/data_association/data_association.cpp @@ -31,8 +31,8 @@ double getFormedYawAngle( const geometry_msgs::msg::Quaternion & quat0, const geometry_msgs::msg::Quaternion & quat1, const bool distinguish_front_or_back = true) { - const double yaw0 = autoware_universe_utils::normalizeRadian(tf2::getYaw(quat0)); - const double yaw1 = autoware_universe_utils::normalizeRadian(tf2::getYaw(quat1)); + const double yaw0 = autoware::universe_utils::normalizeRadian(tf2::getYaw(quat0)); + const double yaw1 = autoware::universe_utils::normalizeRadian(tf2::getYaw(quat1)); const double angle_range = distinguish_front_or_back ? M_PI : M_PI_2; const double angle_step = distinguish_front_or_back ? 2.0 * M_PI : M_PI; // Fixed yaw0 to be in the range of +-90 or 180 degrees of yaw1 @@ -183,7 +183,7 @@ double DataAssociation::calcScoreBetweenObjects( double score = 0.0; if (can_assign_matrix_(object1_label, object0_label)) { const double max_dist = max_dist_matrix_(object1_label, object0_label); - const double dist = autoware_universe_utils::calcDistance2d( + const double dist = autoware::universe_utils::calcDistance2d( object0.kinematics.pose_with_covariance.pose.position, object1.kinematics.pose_with_covariance.pose.position); diff --git a/perception/tracking_object_merger/src/decorative_tracker_merger.cpp b/perception/tracking_object_merger/src/decorative_tracker_merger.cpp index d1bc61d90edac..99dccab3ff72c 100644 --- a/perception/tracking_object_merger/src/decorative_tracker_merger.cpp +++ b/perception/tracking_object_merger/src/decorative_tracker_merger.cpp @@ -155,14 +155,14 @@ DecorativeTrackerMergerNode::DecorativeTrackerMergerNode(const rclcpp::NodeOptio set3dDataAssociation("radar-radar", data_association_map_); // debug publisher - processing_time_publisher_ = std::make_unique( + processing_time_publisher_ = std::make_unique( this, "decorative_object_merger_node"); stop_watch_ptr_ = - std::make_unique>(); + std::make_unique>(); stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } void DecorativeTrackerMergerNode::set3dDataAssociation( diff --git a/perception/tracking_object_merger/src/utils/utils.cpp b/perception/tracking_object_merger/src/utils/utils.cpp index 7d8b5a4cc02f3..e981ef09a21b0 100644 --- a/perception/tracking_object_merger/src/utils/utils.cpp +++ b/perception/tracking_object_merger/src/utils/utils.cpp @@ -280,7 +280,7 @@ bool objectsHaveSameMotionDirections(const TrackedObject & main_obj, const Track // diff of motion yaw angle const auto motion_yaw_diff = std::fabs(main_motion_yaw - sub_motion_yaw); const auto normalized_motion_yaw_diff = - autoware_universe_utils::normalizeRadian(motion_yaw_diff); // -pi ~ pi + autoware::universe_utils::normalizeRadian(motion_yaw_diff); // -pi ~ pi // evaluate if motion yaw angle is same constexpr double yaw_threshold = M_PI / 4.0; // 45 deg if (std::abs(normalized_motion_yaw_diff) < yaw_threshold) { @@ -305,7 +305,7 @@ bool objectsYawIsReverted(const TrackedObject & main_obj, const TrackedObject & const auto sub_yaw = tf2::getYaw(sub_obj.kinematics.pose_with_covariance.pose.orientation); // calc yaw diff const auto yaw_diff = std::fabs(main_yaw - sub_yaw); - const auto normalized_yaw_diff = autoware_universe_utils::normalizeRadian(yaw_diff); // -pi ~ pi + const auto normalized_yaw_diff = autoware::universe_utils::normalizeRadian(yaw_diff); // -pi ~ pi // evaluate if yaw is reverted constexpr double yaw_threshold = M_PI / 2.0; // 90 deg if (std::abs(normalized_yaw_diff) >= yaw_threshold) { diff --git a/perception/traffic_light_map_based_detector/src/node.cpp b/perception/traffic_light_map_based_detector/src/node.cpp index 7224db018ccff..7750bf642516a 100644 --- a/perception/traffic_light_map_based_detector/src/node.cpp +++ b/perception/traffic_light_map_based_detector/src/node.cpp @@ -512,9 +512,10 @@ void MapBasedDetector::getVisibleTrafficLights( double max_angle_range; if (pedestrian_tl_id_.find(traffic_light.id()) != pedestrian_tl_id_.end()) { max_angle_range = - autoware_universe_utils::deg2rad(config_.pedestrian_traffic_light_max_angle_range); + autoware::universe_utils::deg2rad(config_.pedestrian_traffic_light_max_angle_range); } else { - max_angle_range = autoware_universe_utils::deg2rad(config_.car_traffic_light_max_angle_range); + max_angle_range = + autoware::universe_utils::deg2rad(config_.car_traffic_light_max_angle_range); } // traffic light bottom left const auto & tl_bl = traffic_light.front(); @@ -530,7 +531,7 @@ void MapBasedDetector::getVisibleTrafficLights( } // check angle range - const double tl_yaw = autoware_universe_utils::normalizeRadian( + const double tl_yaw = autoware::universe_utils::normalizeRadian( std::atan2(tl_br.y() - tl_bl.y(), tl_br.x() - tl_bl.x()) + M_PI_2); // get direction of z axis @@ -538,7 +539,7 @@ void MapBasedDetector::getVisibleTrafficLights( tf2::Matrix3x3 camera_rotation_matrix(tf_map2camera.getRotation()); camera_z_dir = camera_rotation_matrix * camera_z_dir; double camera_yaw = std::atan2(camera_z_dir.y(), camera_z_dir.x()); - camera_yaw = autoware_universe_utils::normalizeRadian(camera_yaw); + camera_yaw = autoware::universe_utils::normalizeRadian(camera_yaw); if (!isInAngleRange(tl_yaw, camera_yaw, max_angle_range)) { continue; } diff --git a/perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp b/perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp index 8a1bea3303c67..6515a515397da 100644 --- a/perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp +++ b/perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp @@ -102,7 +102,7 @@ void CloudOcclusionPredictor::predict( pcl::PointCloud cloud_camera; // points within roi pcl::PointCloud cloud_roi; - autoware_universe_utils::transformPointCloudFromROSMsg(*cloud_msg, cloud_camera, camera2cloud); + autoware::universe_utils::transformPointCloudFromROSMsg(*cloud_msg, cloud_camera, camera2cloud); filterCloud(cloud_camera, roi_tls, roi_brs, cloud_roi); diff --git a/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp b/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp index 11f05ad126bc1..70167f0833586 100644 --- a/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp +++ b/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp @@ -163,7 +163,7 @@ class FreespacePlannerNode : public rclcpp::Node TransformStamped getTransform(const std::string & from, const std::string & to); - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; }; } // namespace autoware::freespace_planner diff --git a/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp b/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp index b0cf556c49b5d..55068263f5d5b 100644 --- a/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp +++ b/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp @@ -142,8 +142,8 @@ Trajectory getPartialTrajectory( double calcDistance2d(const Trajectory & trajectory, const Pose & pose) { - const auto idx = autoware_motion_utils::findNearestIndex(trajectory.points, pose.position); - return autoware_universe_utils::calcDistance2d(trajectory.points.at(idx), pose); + const auto idx = autoware::motion_utils::findNearestIndex(trajectory.points, pose.position); + return autoware::universe_utils::calcDistance2d(trajectory.points.at(idx), pose); } Pose transformPose(const Pose & pose, const TransformStamped & transform) @@ -287,7 +287,7 @@ FreespacePlannerNode::FreespacePlannerNode(const rclcpp::NodeOptions & node_opti this, get_clock(), period_ns, std::bind(&FreespacePlannerNode::onTimer, this)); } - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); } PlannerCommonParam FreespacePlannerNode::getPlannerCommonParam() @@ -365,7 +365,7 @@ bool FreespacePlannerNode::isPlanRequired() if (node_param_.replan_when_obstacle_found) { algo_->setMap(*occupancy_grid_); - const size_t nearest_index_partial = autoware_motion_utils::findNearestIndex( + const size_t nearest_index_partial = autoware::motion_utils::findNearestIndex( partial_trajectory_.points, current_pose_.pose.position); const size_t end_index_partial = partial_trajectory_.points.size() - 1; @@ -395,7 +395,7 @@ bool FreespacePlannerNode::isPlanRequired() void FreespacePlannerNode::updateTargetIndex() { const auto is_near_target = - autoware_universe_utils::calcDistance2d(trajectory_.points.at(target_index_), current_pose_) < + autoware::universe_utils::calcDistance2d(trajectory_.points.at(target_index_), current_pose_) < node_param_.th_arrived_distance_m; const auto is_stopped = isStopped(odom_buffer_, node_param_.th_stopped_velocity_mps); diff --git a/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp b/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp index dbab68be5f8be..2d47c7acb9801 100644 --- a/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp @@ -21,8 +21,8 @@ namespace autoware::freespace_planning_algorithms { -using autoware_universe_utils::createQuaternionFromYaw; -using autoware_universe_utils::normalizeRadian; +using autoware::universe_utils::createQuaternionFromYaw; +using autoware::universe_utils::normalizeRadian; geometry_msgs::msg::Pose transformPose( const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::TransformStamped & transform) @@ -97,7 +97,7 @@ double PlannerWaypoints::compute_length() const for (size_t i = 0; i < waypoints.size() - 1; ++i) { const auto pose_a = waypoints.at(i); const auto pose_b = waypoints.at(i + 1); - total_cost += autoware_universe_utils::calcDistance2d(pose_a.pose, pose_b.pose); + total_cost += autoware::universe_utils::calcDistance2d(pose_a.pose, pose_b.pose); } return total_cost; } diff --git a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp index 5aa7f9889ccf8..6d093b3c7c0cd 100644 --- a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp @@ -42,7 +42,7 @@ double calcReedsSheppDistance( void setYaw(geometry_msgs::msg::Quaternion * orientation, const double yaw) { - *orientation = autoware_universe_utils::createQuaternionFromYaw(yaw); + *orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); } geometry_msgs::msg::Pose calcRelativePose( @@ -209,7 +209,7 @@ double AstarSearch::estimateCost(const geometry_msgs::msg::Pose & pose) const total_cost += calcReedsSheppDistance(pose, goal_pose_, radius) * astar_param_.distance_heuristic_weight; } else { - total_cost += autoware_universe_utils::calcDistance2d(pose, goal_pose_) * + total_cost += autoware::universe_utils::calcDistance2d(pose, goal_pose_) * astar_param_.distance_heuristic_weight; } return total_cost; @@ -332,7 +332,7 @@ bool AstarSearch::isGoal(const AstarNode & node) const const double lateral_goal_range = planner_common_param_.lateral_goal_range / 2.0; const double longitudinal_goal_range = planner_common_param_.longitudinal_goal_range / 2.0; const double goal_angle = - autoware_universe_utils::deg2rad(planner_common_param_.angle_goal_range / 2.0); + autoware::universe_utils::deg2rad(planner_common_param_.angle_goal_range / 2.0); const auto relative_pose = calcRelativePose(goal_pose_, node2pose(node)); @@ -348,7 +348,7 @@ bool AstarSearch::isGoal(const AstarNode & node) const } const auto angle_diff = - autoware_universe_utils::normalizeRadian(tf2::getYaw(relative_pose.orientation)); + autoware::universe_utils::normalizeRadian(tf2::getYaw(relative_pose.orientation)); if (std::abs(angle_diff) > goal_angle) { return false; } @@ -363,7 +363,7 @@ geometry_msgs::msg::Pose AstarSearch::node2pose(const AstarNode & node) const pose_local.position.x = node.x; pose_local.position.y = node.y; pose_local.position.z = goal_pose_.position.z; - pose_local.orientation = autoware_universe_utils::createQuaternionFromYaw(node.theta); + pose_local.orientation = autoware::universe_utils::createQuaternionFromYaw(node.theta); return pose_local; } diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp index edce59e4f473b..69c52b9c2eafb 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -108,7 +108,7 @@ geometry_msgs::msg::Pose get_closest_centerline_pose( const double lane_yaw = lanelet::utils::getLaneletAngle(closest_lanelet, point.position); - const auto nearest_idx = autoware_motion_utils::findNearestIndex( + const auto nearest_idx = autoware::motion_utils::findNearestIndex( convertCenterlineToPoints(closest_lanelet), point.position); const auto nearest_point = closest_lanelet.centerline()[nearest_idx]; @@ -190,13 +190,13 @@ PlannerPlugin::MarkerArray DefaultPlanner::visualize(const LaneletRoute & route) } const std_msgs::msg::ColorRGBA cl_route = - autoware_universe_utils::createMarkerColor(0.8, 0.99, 0.8, 0.15); + autoware::universe_utils::createMarkerColor(0.8, 0.99, 0.8, 0.15); const std_msgs::msg::ColorRGBA cl_ll_borders = - autoware_universe_utils::createMarkerColor(1.0, 1.0, 1.0, 0.999); + autoware::universe_utils::createMarkerColor(1.0, 1.0, 1.0, 0.999); const std_msgs::msg::ColorRGBA cl_end = - autoware_universe_utils::createMarkerColor(0.2, 0.2, 0.4, 0.05); + autoware::universe_utils::createMarkerColor(0.2, 0.2, 0.4, 0.05); const std_msgs::msg::ColorRGBA cl_goal = - autoware_universe_utils::createMarkerColor(0.2, 0.4, 0.4, 0.05); + autoware::universe_utils::createMarkerColor(0.2, 0.4, 0.4, 0.05); visualization_msgs::msg::MarkerArray route_marker_array; insert_marker_array( @@ -216,27 +216,27 @@ PlannerPlugin::MarkerArray DefaultPlanner::visualize(const LaneletRoute & route) } visualization_msgs::msg::MarkerArray DefaultPlanner::visualize_debug_footprint( - autoware_universe_utils::LinearRing2d goal_footprint) const + autoware::universe_utils::LinearRing2d goal_footprint) const { visualization_msgs::msg::MarkerArray msg; - auto marker = autoware_universe_utils::createDefaultMarker( + auto marker = autoware::universe_utils::createDefaultMarker( "map", rclcpp::Clock().now(), "goal_footprint", 0, visualization_msgs::msg::Marker::LINE_STRIP, - autoware_universe_utils::createMarkerScale(0.05, 0.0, 0.0), - autoware_universe_utils::createMarkerColor(0.99, 0.99, 0.2, 1.0)); + autoware::universe_utils::createMarkerScale(0.05, 0.0, 0.0), + autoware::universe_utils::createMarkerColor(0.99, 0.99, 0.2, 1.0)); marker.lifetime = rclcpp::Duration::from_seconds(2.5); marker.points.push_back( - autoware_universe_utils::createPoint(goal_footprint[0][0], goal_footprint[0][1], 0.0)); + autoware::universe_utils::createPoint(goal_footprint[0][0], goal_footprint[0][1], 0.0)); marker.points.push_back( - autoware_universe_utils::createPoint(goal_footprint[1][0], goal_footprint[1][1], 0.0)); + autoware::universe_utils::createPoint(goal_footprint[1][0], goal_footprint[1][1], 0.0)); marker.points.push_back( - autoware_universe_utils::createPoint(goal_footprint[2][0], goal_footprint[2][1], 0.0)); + autoware::universe_utils::createPoint(goal_footprint[2][0], goal_footprint[2][1], 0.0)); marker.points.push_back( - autoware_universe_utils::createPoint(goal_footprint[3][0], goal_footprint[3][1], 0.0)); + autoware::universe_utils::createPoint(goal_footprint[3][0], goal_footprint[3][1], 0.0)); marker.points.push_back( - autoware_universe_utils::createPoint(goal_footprint[4][0], goal_footprint[4][1], 0.0)); + autoware::universe_utils::createPoint(goal_footprint[4][0], goal_footprint[4][1], 0.0)); marker.points.push_back( - autoware_universe_utils::createPoint(goal_footprint[5][0], goal_footprint[5][1], 0.0)); + autoware::universe_utils::createPoint(goal_footprint[5][0], goal_footprint[5][1], 0.0)); marker.points.push_back(marker.points.front()); msg.markers.push_back(marker); @@ -247,7 +247,7 @@ visualization_msgs::msg::MarkerArray DefaultPlanner::visualize_debug_footprint( bool DefaultPlanner::check_goal_footprint_inside_lanes( const lanelet::ConstLanelet & current_lanelet, const lanelet::ConstLanelet & combined_prev_lanelet, - const autoware_universe_utils::Polygon2d & goal_footprint, double & next_lane_length, + const autoware::universe_utils::Polygon2d & goal_footprint, double & next_lane_length, const double search_margin) { // check if goal footprint is in current lane @@ -302,8 +302,8 @@ bool DefaultPlanner::is_goal_valid( shoulder_lanelets, goal, &closest_shoulder_lanelet)) { const auto lane_yaw = lanelet::utils::getLaneletAngle(closest_shoulder_lanelet, goal.position); const auto goal_yaw = tf2::getYaw(goal.orientation); - const auto angle_diff = autoware_universe_utils::normalizeRadian(lane_yaw - goal_yaw); - const double th_angle = autoware_universe_utils::deg2rad(param_.goal_angle_threshold_deg); + const auto angle_diff = autoware::universe_utils::normalizeRadian(lane_yaw - goal_yaw); + const double th_angle = autoware::universe_utils::deg2rad(param_.goal_angle_threshold_deg); if (std::abs(angle_diff) < th_angle) { return true; } @@ -332,8 +332,8 @@ bool DefaultPlanner::is_goal_valid( } const auto local_vehicle_footprint = vehicle_info_.createFootprint(); - autoware_universe_utils::LinearRing2d goal_footprint = - transformVector(local_vehicle_footprint, autoware_universe_utils::pose2transform(goal)); + autoware::universe_utils::LinearRing2d goal_footprint = + transformVector(local_vehicle_footprint, autoware::universe_utils::pose2transform(goal)); pub_goal_footprint_marker_->publish(visualize_debug_footprint(goal_footprint)); const auto polygon_footprint = convert_linear_ring_to_polygon(goal_footprint); @@ -357,9 +357,9 @@ bool DefaultPlanner::is_goal_valid( if (is_in_lane(closest_lanelet, goal_lanelet_pt)) { const auto lane_yaw = lanelet::utils::getLaneletAngle(closest_lanelet, goal.position); const auto goal_yaw = tf2::getYaw(goal.orientation); - const auto angle_diff = autoware_universe_utils::normalizeRadian(lane_yaw - goal_yaw); + const auto angle_diff = autoware::universe_utils::normalizeRadian(lane_yaw - goal_yaw); - const double th_angle = autoware_universe_utils::deg2rad(param_.goal_angle_threshold_deg); + const double th_angle = autoware::universe_utils::deg2rad(param_.goal_angle_threshold_deg); if (std::abs(angle_diff) < th_angle) { return true; } diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp index 0b7d889a24f83..60c2a53b82123 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp @@ -52,7 +52,7 @@ class DefaultPlanner : public mission_planner::PlannerPlugin void clearRoute() override; MarkerArray visualize(const LaneletRoute & route) const override; MarkerArray visualize_debug_footprint( - autoware_universe_utils::LinearRing2d goal_footprint_) const; + autoware::universe_utils::LinearRing2d goal_footprint_) const; autoware::vehicle_info_utils::VehicleInfo vehicle_info_; private: @@ -86,7 +86,7 @@ class DefaultPlanner : public mission_planner::PlannerPlugin bool check_goal_footprint_inside_lanes( const lanelet::ConstLanelet & current_lanelet, const lanelet::ConstLanelet & combined_prev_lanelet, - const autoware_universe_utils::Polygon2d & goal_footprint, double & next_lane_length, + const autoware::universe_utils::Polygon2d & goal_footprint, double & next_lane_length, const double search_margin = 2.0); /** diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp b/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp index 904e618f825fb..5046b81c72b96 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp @@ -21,10 +21,10 @@ #include #include -autoware_universe_utils::Polygon2d convert_linear_ring_to_polygon( - autoware_universe_utils::LinearRing2d footprint) +autoware::universe_utils::Polygon2d convert_linear_ring_to_polygon( + autoware::universe_utils::LinearRing2d footprint) { - autoware_universe_utils::Polygon2d footprint_polygon; + autoware::universe_utils::Polygon2d footprint_polygon; boost::geometry::append(footprint_polygon.outer(), footprint[0]); boost::geometry::append(footprint_polygon.outer(), footprint[1]); boost::geometry::append(footprint_polygon.outer(), footprint[2]); @@ -120,7 +120,7 @@ geometry_msgs::msg::Pose convertBasicPoint3dToPose( pose.position.y = point.y(); pose.position.z = point.z(); - pose.orientation = autoware_universe_utils::createQuaternionFromYaw(lane_yaw); + pose.orientation = autoware::universe_utils::createQuaternionFromYaw(lane_yaw); return pose; } diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.hpp b/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.hpp index 04f235a58206f..c8812e2c76dd6 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.hpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.hpp @@ -42,8 +42,8 @@ bool exists(const std::vector & vectors, const T & item) return false; } -autoware_universe_utils::Polygon2d convert_linear_ring_to_polygon( - autoware_universe_utils::LinearRing2d footprint); +autoware::universe_utils::Polygon2d convert_linear_ring_to_polygon( + autoware::universe_utils::LinearRing2d footprint); void insert_marker_array( visualization_msgs::msg::MarkerArray * a1, const visualization_msgs::msg::MarkerArray & a2); diff --git a/planning/autoware_mission_planner/src/mission_planner/arrival_checker.cpp b/planning/autoware_mission_planner/src/mission_planner/arrival_checker.cpp index b0af480d10357..da14712dd6c64 100644 --- a/planning/autoware_mission_planner/src/mission_planner/arrival_checker.cpp +++ b/planning/autoware_mission_planner/src/mission_planner/arrival_checker.cpp @@ -26,7 +26,7 @@ namespace autoware::mission_planner ArrivalChecker::ArrivalChecker(rclcpp::Node * node) : vehicle_stop_checker_(node) { const double angle_deg = node->declare_parameter("arrival_check_angle_deg"); - angle_ = autoware_universe_utils::deg2rad(angle_deg); + angle_ = autoware::universe_utils::deg2rad(angle_deg); distance_ = node->declare_parameter("arrival_check_distance"); duration_ = node->declare_parameter("arrival_check_duration"); } @@ -67,14 +67,14 @@ bool ArrivalChecker::is_arrived(const PoseStamped & pose) const } // Check distance. - if (distance_ < autoware_universe_utils::calcDistance2d(pose.pose, goal.pose)) { + if (distance_ < autoware::universe_utils::calcDistance2d(pose.pose, goal.pose)) { return false; } // Check angle. const double yaw_pose = tf2::getYaw(pose.pose.orientation); const double yaw_goal = tf2::getYaw(goal.pose.orientation); - const double yaw_diff = autoware_universe_utils::normalizeRadian(yaw_pose - yaw_goal); + const double yaw_diff = autoware::universe_utils::normalizeRadian(yaw_pose - yaw_goal); if (angle_ < std::fabs(yaw_diff)) { return false; } diff --git a/planning/autoware_mission_planner/src/mission_planner/arrival_checker.hpp b/planning/autoware_mission_planner/src/mission_planner/arrival_checker.hpp index 0b892d7998078..708b3de40bdab 100644 --- a/planning/autoware_mission_planner/src/mission_planner/arrival_checker.hpp +++ b/planning/autoware_mission_planner/src/mission_planner/arrival_checker.hpp @@ -42,7 +42,7 @@ class ArrivalChecker double duration_; std::optional goal_with_uuid_; rclcpp::Subscription::SharedPtr sub_goal_; - autoware_motion_utils::VehicleStopChecker vehicle_stop_checker_; + autoware::motion_utils::VehicleStopChecker vehicle_stop_checker_; }; } // namespace autoware::mission_planner diff --git a/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp b/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp index fc90b91f6d996..e484b9915aa87 100644 --- a/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp @@ -78,7 +78,7 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) const auto period = rclcpp::Rate(10).period(); data_check_timer_ = create_wall_timer(period, [this] { check_initialization(); }); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); } void MissionPlanner::publish_pose_log(const Pose & pose, const std::string & pose_type) diff --git a/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp b/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp index ab108d07918d2..1a04a91c14ba3 100644 --- a/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp @@ -85,7 +85,7 @@ class MissionPlanner : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_modified_goal_; rclcpp::Subscription::SharedPtr sub_odometry_; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_reroute_availability_{this, "~/input/reroute_availability"}; rclcpp::Subscription::SharedPtr sub_vector_map_; @@ -132,7 +132,7 @@ class MissionPlanner : public rclcpp::Node double minimum_reroute_length_; bool check_reroute_safety(const LaneletRoute & original_route, const LaneletRoute & target_route); - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; }; } // namespace autoware::mission_planner diff --git a/planning/autoware_objects_of_interest_marker_interface/src/coloring.cpp b/planning/autoware_objects_of_interest_marker_interface/src/coloring.cpp index 8dba7731649b4..038006517f45a 100644 --- a/planning/autoware_objects_of_interest_marker_interface/src/coloring.cpp +++ b/planning/autoware_objects_of_interest_marker_interface/src/coloring.cpp @@ -22,7 +22,7 @@ std_msgs::msg::ColorRGBA convertFromColorCode(const uint64_t code, const float a const float g = static_cast((code << 48) >> 56) / 255.0; const float b = static_cast((code << 56) >> 56) / 255.0; - return autoware_universe_utils::createMarkerColor(r, g, b, alpha); + return autoware::universe_utils::createMarkerColor(r, g, b, alpha); } } // namespace diff --git a/planning/autoware_objects_of_interest_marker_interface/src/marker_utils.cpp b/planning/autoware_objects_of_interest_marker_interface/src/marker_utils.cpp index 4cbf6924abf36..42d92bd0c91da 100644 --- a/planning/autoware_objects_of_interest_marker_interface/src/marker_utils.cpp +++ b/planning/autoware_objects_of_interest_marker_interface/src/marker_utils.cpp @@ -20,8 +20,8 @@ using geometry_msgs::msg::Point; using std_msgs::msg::ColorRGBA; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerScale; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerScale; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; @@ -66,9 +66,9 @@ Marker createCircleMarker( for (size_t i = 0; i < num_points; ++i) { Point point; const double ratio = static_cast(i) / static_cast(num_points); - const double theta = 2 * autoware_universe_utils::pi * ratio; - point.x = data.pose.position.x + radius * autoware_universe_utils::cos(theta); - point.y = data.pose.position.y + radius * autoware_universe_utils::sin(theta); + const double theta = 2 * autoware::universe_utils::pi * ratio; + point.x = data.pose.position.x + radius * autoware::universe_utils::cos(theta); + point.y = data.pose.position.y + radius * autoware::universe_utils::sin(theta); point.z = data.pose.position.z + height + height_offset; marker.points.push_back(point); } diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/common_structs.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/common_structs.hpp index a7f4787f76c48..e4ae670ef6b97 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/common_structs.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/common_structs.hpp @@ -63,7 +63,7 @@ struct Obstacle twist(object.kinematics.initial_twist_with_covariance.twist), twist_reliable(true), classification(object.classification.at(0)), - uuid(autoware_universe_utils::toHexString(object.object_id)), + uuid(autoware::universe_utils::toHexString(object.object_id)), shape(object.shape), ego_to_obstacle_distance(ego_to_obstacle_distance), lat_dist_from_obstacle_to_traj(lat_dist_from_obstacle_to_traj) @@ -74,7 +74,7 @@ struct Obstacle } } - Polygon2d toPolygon() const { return autoware_universe_utils::toPolygon2d(pose, shape); } + Polygon2d toPolygon() const { return autoware::universe_utils::toPolygon2d(pose, shape); } rclcpp::Time stamp; // This is not the current stamp, but when the object was observed. geometry_msgs::msg::Pose pose; // interpolated with the current stamp @@ -198,33 +198,33 @@ struct LongitudinalInfo void onParam(const std::vector & parameters) { - autoware_universe_utils::updateParam(parameters, "normal.max_accel", max_accel); - autoware_universe_utils::updateParam(parameters, "normal.min_accel", min_accel); - autoware_universe_utils::updateParam(parameters, "normal.max_jerk", max_jerk); - autoware_universe_utils::updateParam(parameters, "normal.min_jerk", min_jerk); - autoware_universe_utils::updateParam(parameters, "limit.max_accel", limit_max_accel); - autoware_universe_utils::updateParam(parameters, "limit.min_accel", limit_min_accel); - autoware_universe_utils::updateParam(parameters, "limit.max_jerk", limit_max_jerk); - autoware_universe_utils::updateParam(parameters, "limit.min_jerk", limit_min_jerk); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam(parameters, "normal.max_accel", max_accel); + autoware::universe_utils::updateParam(parameters, "normal.min_accel", min_accel); + autoware::universe_utils::updateParam(parameters, "normal.max_jerk", max_jerk); + autoware::universe_utils::updateParam(parameters, "normal.min_jerk", min_jerk); + autoware::universe_utils::updateParam(parameters, "limit.max_accel", limit_max_accel); + autoware::universe_utils::updateParam(parameters, "limit.min_accel", limit_min_accel); + autoware::universe_utils::updateParam(parameters, "limit.max_jerk", limit_max_jerk); + autoware::universe_utils::updateParam(parameters, "limit.min_jerk", limit_min_jerk); + autoware::universe_utils::updateParam( parameters, "common.slow_down_min_accel", slow_down_min_accel); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "common.slow_down_min_jerk", slow_down_min_jerk); - autoware_universe_utils::updateParam(parameters, "common.idling_time", idling_time); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam(parameters, "common.idling_time", idling_time); + autoware::universe_utils::updateParam( parameters, "common.min_ego_accel_for_rss", min_ego_accel_for_rss); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "common.min_object_accel_for_rss", min_object_accel_for_rss); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "common.safe_distance_margin", safe_distance_margin); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "common.terminal_safe_distance_margin", terminal_safe_distance_margin); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "common.hold_stop_velocity_threshold", hold_stop_velocity_threshold); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "common.hold_stop_distance_threshold", hold_stop_distance_threshold); } @@ -265,7 +265,7 @@ struct DebugData MarkerArray stop_wall_marker; MarkerArray cruise_wall_marker; MarkerArray slow_down_wall_marker; - std::vector detection_polygons; + std::vector detection_polygons; }; struct EgoNearestParam @@ -280,21 +280,22 @@ struct EgoNearestParam TrajectoryPoint calcInterpolatedPoint( const std::vector & traj_points, const geometry_msgs::msg::Pose & pose) const { - return autoware_motion_utils::calcInterpolatedPoint( - autoware_motion_utils::convertToTrajectory(traj_points), pose, dist_threshold, yaw_threshold); + return autoware::motion_utils::calcInterpolatedPoint( + autoware::motion_utils::convertToTrajectory(traj_points), pose, dist_threshold, + yaw_threshold); } size_t findIndex( const std::vector & traj_points, const geometry_msgs::msg::Pose & pose) const { - return autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( traj_points, pose, dist_threshold, yaw_threshold); } size_t findSegmentIndex( const std::vector & traj_points, const geometry_msgs::msg::Pose & pose) const { - return autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( traj_points, pose, dist_threshold, yaw_threshold); } diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp index 5d0d99a742d1c..dd9a6c3880672 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp @@ -145,11 +145,11 @@ class ObstacleCruisePlannerNode : public rclcpp::Node // subscriber rclcpp::Subscription::SharedPtr traj_sub_; - autoware_universe_utils::InterProcessPollingSubscriber ego_odom_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber ego_odom_sub_{ this, "~/input/odometry"}; - autoware_universe_utils::InterProcessPollingSubscriber objects_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber objects_sub_{ this, "~/input/objects"}; - autoware_universe_utils::InterProcessPollingSubscriber acc_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber acc_sub_{ this, "~/input/acceleration"}; // Vehicle Parameters @@ -161,7 +161,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node PlanningAlgorithm planning_algorithm_; // stop watch - mutable autoware_universe_utils::StopWatch< + mutable autoware::universe_utils::StopWatch< std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> stop_watch_; mutable std::shared_ptr debug_data_ptr_{nullptr}; @@ -274,9 +274,9 @@ class ObstacleCruisePlannerNode : public rclcpp::Node std::vector prev_closest_stop_obstacles_{}; - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; }; } // namespace autoware::motion_planning diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp index 525a2cfca6ece..0641d076bb3ff 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp @@ -125,7 +125,7 @@ class PlannerInterface bool suppress_sudden_obstacle_stop_; // stop watch - autoware_universe_utils::StopWatch< + autoware::universe_utils::StopWatch< std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> stop_watch_; @@ -172,7 +172,7 @@ class PlannerInterface const geometry_msgs::msg::Pose & ego_pose) const { const auto & p = ego_nearest_param_; - return autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( traj_points, ego_pose, p.dist_threshold, p.yaw_threshold); } @@ -181,7 +181,7 @@ class PlannerInterface const geometry_msgs::msg::Pose & ego_pose) const { const auto & p = ego_nearest_param_; - return autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( traj_points, ego_pose, p.dist_threshold, p.yaw_threshold); } @@ -303,29 +303,29 @@ class PlannerInterface if (obstacle_to_param_struct_map.count(label + "." + movement_postfix) < 1) continue; auto & param_by_obstacle_label = obstacle_to_param_struct_map.at(label + "." + movement_postfix); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "slow_down." + label + "." + movement_postfix + ".max_lat_margin", param_by_obstacle_label.max_lat_margin); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "slow_down." + label + "." + movement_postfix + ".min_lat_margin", param_by_obstacle_label.min_lat_margin); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "slow_down." + label + "." + movement_postfix + ".max_ego_velocity", param_by_obstacle_label.max_ego_velocity); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "slow_down." + label + "." + movement_postfix + ".min_ego_velocity", param_by_obstacle_label.min_ego_velocity); } } // common parameters - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "slow_down.time_margin_on_target_velocity", time_margin_on_target_velocity); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "slow_down.lpf_gain_slow_down_vel", lpf_gain_slow_down_vel); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "slow_down.lpf_gain_lat_dist", lpf_gain_lat_dist); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "slow_down.lpf_gain_dist_to_slow_down", lpf_gain_dist_to_slow_down); } @@ -385,15 +385,15 @@ class PlannerInterface if (type_str == "default") { continue; } - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, param_prefix + type_str + ".limit_min_acc", param.limit_min_acc); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, param_prefix + type_str + ".sudden_object_acc_threshold", param.sudden_object_acc_threshold); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, param_prefix + type_str + ".sudden_object_dist_threshold", param.sudden_object_dist_threshold); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, param_prefix + type_str + ".abandon_to_stop", param.abandon_to_stop); param.sudden_object_acc_threshold = diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/polygon_utils.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/polygon_utils.hpp index e9c661d575733..fa6ee17d117be 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/polygon_utils.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/polygon_utils.hpp @@ -30,8 +30,8 @@ namespace polygon_utils { namespace bg = boost::geometry; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; Polygon2d createOneStepPolygon( const std::vector & last_poses, diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp index bc9f6070e159d..5721efd051f63 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp @@ -60,7 +60,7 @@ using tier4_planning_msgs::msg::VelocityLimitClearCommand; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; namespace bg = boost::geometry; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; #endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_ diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/utils.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/utils.hpp index ceb5da13882bd..8af9a63f3a1fa 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/utils.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/utils.hpp @@ -62,7 +62,7 @@ size_t getIndexWithLongitudinalOffset( if (longitudinal_offset > 0) { for (size_t i = *start_idx; i < points.size() - 1; ++i) { const double segment_length = - autoware_universe_utils::calcDistance2d(points.at(i), points.at(i + 1)); + autoware::universe_utils::calcDistance2d(points.at(i), points.at(i + 1)); sum_length += segment_length; if (sum_length >= longitudinal_offset) { const double back_length = sum_length - longitudinal_offset; @@ -79,7 +79,7 @@ size_t getIndexWithLongitudinalOffset( for (size_t i = *start_idx; 0 < i; --i) { const double segment_length = - autoware_universe_utils::calcDistance2d(points.at(i - 1), points.at(i)); + autoware::universe_utils::calcDistance2d(points.at(i - 1), points.at(i)); sum_length += segment_length; if (sum_length >= -longitudinal_offset) { const double back_length = sum_length + longitudinal_offset; diff --git a/planning/autoware_obstacle_cruise_planner/src/node.cpp b/planning/autoware_obstacle_cruise_planner/src/node.cpp index b40523c6a0d10..f6e7c2bb43b38 100644 --- a/planning/autoware_obstacle_cruise_planner/src/node.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/node.cpp @@ -58,9 +58,9 @@ std::optional calcDistanceToFrontVehicle( const std::vector & traj_points, const size_t ego_idx, const geometry_msgs::msg::Point & obstacle_pos) { - const size_t obstacle_idx = autoware_motion_utils::findNearestIndex(traj_points, obstacle_pos); + const size_t obstacle_idx = autoware::motion_utils::findNearestIndex(traj_points, obstacle_pos); const auto ego_to_obstacle_distance = - autoware_motion_utils::calcSignedArcLength(traj_points, ego_idx, obstacle_idx); + autoware::motion_utils::calcSignedArcLength(traj_points, ego_idx, obstacle_idx); if (ego_to_obstacle_distance < 0.0) return std::nullopt; return ego_to_obstacle_distance; } @@ -83,12 +83,12 @@ double calcDiffAngleAgainstTrajectory( const std::vector & traj_points, const geometry_msgs::msg::Pose & target_pose) { const size_t nearest_idx = - autoware_motion_utils::findNearestIndex(traj_points, target_pose.position); + autoware::motion_utils::findNearestIndex(traj_points, target_pose.position); const double traj_yaw = tf2::getYaw(traj_points.at(nearest_idx).pose.orientation); const double target_yaw = tf2::getYaw(target_pose.orientation); - const double diff_yaw = autoware_universe_utils::normalizeRadian(target_yaw - traj_yaw); + const double diff_yaw = autoware::universe_utils::normalizeRadian(target_yaw - traj_yaw); return diff_yaw; } @@ -96,7 +96,7 @@ std::pair projectObstacleVelocityToTrajectory( const std::vector & traj_points, const Obstacle & obstacle) { const size_t object_idx = - autoware_motion_utils::findNearestIndex(traj_points, obstacle.pose.position); + autoware::motion_utils::findNearestIndex(traj_points, obstacle.pose.position); const double traj_yaw = tf2::getYaw(traj_points.at(object_idx).pose.orientation); const double obstacle_yaw = tf2::getYaw(obstacle.pose.orientation); @@ -132,7 +132,7 @@ TrajectoryPoint getExtendTrajectoryPoint( const double extend_distance, const TrajectoryPoint & goal_point, const bool is_driving_forward) { TrajectoryPoint extend_trajectory_point; - extend_trajectory_point.pose = autoware_universe_utils::calcOffsetPose( + extend_trajectory_point.pose = autoware::universe_utils::calcOffsetPose( goal_point.pose, extend_distance * (is_driving_forward ? 1.0 : -1.0), 0.0, 0.0); extend_trajectory_point.longitudinal_velocity_mps = goal_point.longitudinal_velocity_mps; extend_trajectory_point.lateral_velocity_mps = goal_point.lateral_velocity_mps; @@ -146,7 +146,7 @@ std::vector extendTrajectoryPoints( { auto output_points = input_points; const auto is_driving_forward_opt = - autoware_motion_utils::isDrivingForwardWithTwist(input_points); + autoware::motion_utils::isDrivingForwardWithTwist(input_points); const bool is_driving_forward = is_driving_forward_opt ? *is_driving_forward_opt : true; if (extend_distance < std::numeric_limits::epsilon()) { @@ -189,12 +189,12 @@ std::vector getTargetObjectType(rclcpp::Node & node, const std::string & pa std::vector resampleTrajectoryPoints( const std::vector & traj_points, const double interval) { - const auto traj = autoware_motion_utils::convertToTrajectory(traj_points); - const auto resampled_traj = autoware_motion_utils::resampleTrajectory(traj, interval); - return autoware_motion_utils::convertToTrajectoryPointArray(resampled_traj); + const auto traj = autoware::motion_utils::convertToTrajectory(traj_points); + const auto resampled_traj = autoware::motion_utils::resampleTrajectory(traj, interval); + return autoware::motion_utils::convertToTrajectoryPointArray(resampled_traj); } -geometry_msgs::msg::Point toGeomPoint(const autoware_universe_utils::Point2d & point) +geometry_msgs::msg::Point toGeomPoint(const autoware::universe_utils::Point2d & point) { geometry_msgs::msg::Point geom_point; geom_point.x = point.x(); @@ -281,75 +281,75 @@ void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam( const std::vector & parameters) { // behavior determination - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.decimate_trajectory_step_length", decimate_trajectory_step_length); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.crossing_obstacle.obstacle_velocity_threshold", crossing_obstacle_velocity_threshold); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.crossing_obstacle.obstacle_traj_angle_threshold", crossing_obstacle_traj_angle_threshold); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.stop.crossing_obstacle.collision_time_margin", collision_time_margin); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.cruise.outside_obstacle.obstacle_velocity_threshold", outside_obstacle_min_velocity_threshold); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.cruise.outside_obstacle.ego_obstacle_overlap_time_threshold", ego_obstacle_overlap_time_threshold); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.cruise.outside_obstacle.max_prediction_time_for_collision_check", max_prediction_time_for_collision_check); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.stop_obstacle_hold_time_threshold", stop_obstacle_hold_time_threshold); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.prediction_resampling_time_interval", prediction_resampling_time_interval); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.prediction_resampling_time_horizon", prediction_resampling_time_horizon); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.stop.max_lat_margin", max_lat_margin_for_stop); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.stop.max_lat_margin_against_unknown", max_lat_margin_for_stop_against_unknown); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.cruise.max_lat_margin", max_lat_margin_for_cruise); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.cruise.yield.enable_yield", enable_yield); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.cruise.yield.lat_distance_threshold", yield_lat_distance_threshold); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.cruise.yield.max_lat_dist_between_obstacles", max_lat_dist_between_obstacles); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.cruise.yield.stopped_obstacle_velocity_threshold", stopped_obstacle_velocity_threshold); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.cruise.yield.max_obstacles_collision_time", max_obstacles_collision_time); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.slow_down.max_lat_margin", max_lat_margin_for_slow_down); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.slow_down.lat_hysteresis_margin", lat_hysteresis_margin_for_slow_down); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.slow_down.successive_num_to_entry_slow_down_condition", successive_num_to_entry_slow_down_condition); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.slow_down.successive_num_to_exit_slow_down_condition", successive_num_to_exit_slow_down_condition); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.consider_current_pose.enable_to_consider_current_pose", enable_to_consider_current_pose); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "behavior_determination.consider_current_pose.time_to_convergence", time_to_convergence); } @@ -440,9 +440,9 @@ ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & set_param_res_ = this->add_on_set_parameters_callback( std::bind(&ObstacleCruisePlannerNode::onParam, this, std::placeholders::_1)); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } ObstacleCruisePlannerNode::PlanningAlgorithm ObstacleCruisePlannerNode::getPlanningAlgorithmType( @@ -461,17 +461,17 @@ rcl_interfaces::msg::SetParametersResult ObstacleCruisePlannerNode::onParam( { planner_ptr_->onParam(parameters); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "common.enable_debug_info", enable_debug_info_); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "common.enable_calculation_time_info", enable_calculation_time_info_); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "common.stop_on_curve.enable_approaching", enable_approaching_on_curve_); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "common.stop_on_curve.additional_safe_distance_margin", additional_safe_distance_margin_on_curve_); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "common.stop_on_curve.min_safe_distance_margin", min_safe_distance_margin_on_curve_); @@ -480,7 +480,7 @@ rcl_interfaces::msg::SetParametersResult ObstacleCruisePlannerNode::onParam( enable_approaching_on_curve_, additional_safe_distance_margin_on_curve_, min_safe_distance_margin_on_curve_, suppress_sudden_obstacle_stop_); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "common.enable_slow_down_planning", enable_slow_down_planning_); behavior_determination_param_.onParam(parameters); @@ -504,7 +504,7 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms const auto & objects = *objects_ptr; const auto & acc = *acc_ptr; - const auto traj_points = autoware_motion_utils::convertToTrajectoryPointArray(*msg); + const auto traj_points = autoware::motion_utils::convertToTrajectoryPointArray(*msg); // check if subscribed variables are ready if (traj_points.empty()) { return; @@ -513,7 +513,7 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms stop_watch_.tic(__func__); *debug_data_ptr_ = DebugData(); - const auto is_driving_forward = autoware_motion_utils::isDrivingForwardWithTwist(traj_points); + const auto is_driving_forward = autoware::motion_utils::isDrivingForwardWithTwist(traj_points); is_driving_forward_ = is_driving_forward ? is_driving_forward.value() : is_driving_forward_; // 1. Convert predicted objects to obstacles which are @@ -546,7 +546,7 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms // 7. Publish trajectory const auto output_traj = - autoware_motion_utils::convertToTrajectory(slow_down_traj_points, msg->header); + autoware::motion_utils::convertToTrajectory(slow_down_traj_points, msg->header); trajectory_pub_->publish(output_traj); // 8. Publish debug data @@ -573,10 +573,10 @@ std::vector ObstacleCruisePlannerNode::createOneStepPolygons( const double vehicle_width = vehicle_info.vehicle_width_m; const size_t nearest_idx = - autoware_motion_utils::findNearestSegmentIndex(traj_points, current_ego_pose.position); + autoware::motion_utils::findNearestSegmentIndex(traj_points, current_ego_pose.position); const auto nearest_pose = traj_points.at(nearest_idx).pose; const auto current_ego_pose_error = - autoware_universe_utils::inverseTransformPose(current_ego_pose, nearest_pose); + autoware::universe_utils::inverseTransformPose(current_ego_pose, nearest_pose); const double current_ego_lat_error = current_ego_pose_error.position.y; const double current_ego_yaw_error = tf2::getYaw(current_ego_pose_error.orientation); double time_elapsed{0.0}; @@ -592,11 +592,11 @@ std::vector ObstacleCruisePlannerNode::createOneStepPolygons( const double rem_ratio = (p.time_to_convergence - time_elapsed) / p.time_to_convergence; geometry_msgs::msg::Pose indexed_pose_err; indexed_pose_err.set__orientation( - autoware_universe_utils::createQuaternionFromYaw(current_ego_yaw_error * rem_ratio)); + autoware::universe_utils::createQuaternionFromYaw(current_ego_yaw_error * rem_ratio)); indexed_pose_err.set__position( - autoware_universe_utils::createPoint(0.0, current_ego_lat_error * rem_ratio, 0.0)); + autoware::universe_utils::createPoint(0.0, current_ego_lat_error * rem_ratio, 0.0)); current_poses.push_back( - autoware_universe_utils::transformPose(indexed_pose_err, traj_points.at(i).pose)); + autoware::universe_utils::transformPose(indexed_pose_err, traj_points.at(i).pose)); if (traj_points.at(i).longitudinal_velocity_mps != 0.0) { time_elapsed += p.decimate_trajectory_step_length / std::abs(traj_points.at(i).longitudinal_velocity_mps); @@ -610,23 +610,23 @@ std::vector ObstacleCruisePlannerNode::createOneStepPolygons( if (i == 0 && traj_points.at(i).longitudinal_velocity_mps > 1e-3) { boost::geometry::append( idx_poly, - autoware_universe_utils::toFootprint(pose, front_length, rear_length, vehicle_width) + autoware::universe_utils::toFootprint(pose, front_length, rear_length, vehicle_width) .outer()); boost::geometry::append( - idx_poly, autoware_universe_utils::fromMsg( - autoware_universe_utils::calcOffsetPose( + idx_poly, autoware::universe_utils::fromMsg( + autoware::universe_utils::calcOffsetPose( pose, front_length, vehicle_width * 0.5 + lat_margin, 0.0) .position) .to_2d()); boost::geometry::append( - idx_poly, autoware_universe_utils::fromMsg( - autoware_universe_utils::calcOffsetPose( + idx_poly, autoware::universe_utils::fromMsg( + autoware::universe_utils::calcOffsetPose( pose, front_length, -vehicle_width * 0.5 - lat_margin, 0.0) .position) .to_2d()); } else { boost::geometry::append( - idx_poly, autoware_universe_utils::toFootprint( + idx_poly, autoware::universe_utils::toFootprint( pose, front_length, rear_length, vehicle_width + lat_margin * 2.0) .outer()); } @@ -655,7 +655,7 @@ std::vector ObstacleCruisePlannerNode::convertToObstacles( std::vector target_obstacles; for (const auto & predicted_object : objects.objects) { const auto & object_id = - autoware_universe_utils::toHexString(predicted_object.object_id).substr(0, 4); + autoware::universe_utils::toHexString(predicted_object.object_id).substr(0, 4); const auto & current_obstacle_pose = obstacle_cruise_utils::getCurrentObjectPose(predicted_object, obj_stamp, now(), true); @@ -683,7 +683,7 @@ std::vector ObstacleCruisePlannerNode::convertToObstacles( // 3. Check if rough lateral distance is smaller than the threshold const double lat_dist_from_obstacle_to_traj = - autoware_motion_utils::calcLateralOffset(traj_points, current_obstacle_pose.pose.position); + autoware::motion_utils::calcLateralOffset(traj_points, current_obstacle_pose.pose.position); const double min_lat_dist_to_traj_poly = [&]() { const double obstacle_max_length = calcObstacleMaxLength(predicted_object.shape); @@ -749,10 +749,10 @@ bool ObstacleCruisePlannerNode::isFrontCollideObstacle( const size_t first_collision_idx) const { const auto obstacle_idx = - autoware_motion_utils::findNearestIndex(traj_points, obstacle.pose.position); + autoware::motion_utils::findNearestIndex(traj_points, obstacle.pose.position); const double obstacle_to_col_points_distance = - autoware_motion_utils::calcSignedArcLength(traj_points, obstacle_idx, first_collision_idx); + autoware::motion_utils::calcSignedArcLength(traj_points, obstacle_idx, first_collision_idx); const double obstacle_max_length = calcObstacleMaxLength(obstacle.shape); // If the obstacle is far in front of the collision point, the obstacle is behind the ego. @@ -944,7 +944,7 @@ std::optional ObstacleCruisePlannerNode::createYieldCruiseObstac } const auto collision_points = [&]() -> std::optional> { - const auto obstacle_idx = autoware_motion_utils::findNearestIndex(traj_points, obstacle.pose); + const auto obstacle_idx = autoware::motion_utils::findNearestIndex(traj_points, obstacle.pose); if (!obstacle_idx) return std::nullopt; const auto collision_traj_point = traj_points.at(obstacle_idx.value()); const auto object_time = now() + traj_points.at(obstacle_idx.value()).time_from_start; @@ -1358,7 +1358,7 @@ std::optional ObstacleCruisePlannerNode::createSlowDownObstacl for (const auto & collision_poly : front_collision_polygons) { for (const auto & collision_point : collision_poly.outer()) { const auto collision_geom_point = toGeomPoint(collision_point); - const double dist = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const double dist = autoware::motion_utils::calcLongitudinalOffsetToSegment( traj_points, front_seg_idx, collision_geom_point); if (dist < front_min_dist) { front_min_dist = dist; @@ -1373,7 +1373,7 @@ std::optional ObstacleCruisePlannerNode::createSlowDownObstacl for (const auto & collision_poly : back_collision_polygons) { for (const auto & collision_point : collision_poly.outer()) { const auto collision_geom_point = toGeomPoint(collision_point); - const double dist = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const double dist = autoware::motion_utils::calcLongitudinalOffsetToSegment( traj_points, back_seg_idx, collision_geom_point); if (back_max_dist < dist) { back_max_dist = dist; @@ -1396,7 +1396,7 @@ void ObstacleCruisePlannerNode::checkConsistency( const auto predicted_object_itr = std::find_if( predicted_objects.objects.begin(), predicted_objects.objects.end(), [&prev_closest_stop_obstacle](const PredictedObject & po) { - return autoware_universe_utils::toHexString(po.object_id) == + return autoware::universe_utils::toHexString(po.object_id) == prev_closest_stop_obstacle.uuid; }); // If previous closest obstacle disappear from the perception result, do nothing anymore. @@ -1456,7 +1456,7 @@ double ObstacleCruisePlannerNode::calcCollisionTimeMargin( ? std::abs(vehicle_info_.max_longitudinal_offset_m) : std::abs(vehicle_info_.min_longitudinal_offset_m); const double dist_from_ego_to_obstacle = - std::abs(autoware_motion_utils::calcSignedArcLength( + std::abs(autoware::motion_utils::calcSignedArcLength( traj_points, ego_pose.position, collision_points.front().point)) - abs_ego_offset; return dist_from_ego_to_obstacle / std::max(1e-6, std::abs(ego_vel)); @@ -1531,10 +1531,10 @@ void ObstacleCruisePlannerNode::publishDebugMarker() const } } for (size_t i = 0; i < stop_collision_points.size(); ++i) { - auto collision_point_marker = autoware_universe_utils::createDefaultMarker( + auto collision_point_marker = autoware::universe_utils::createDefaultMarker( "map", now(), "cruise_collision_points", i, Marker::SPHERE, - autoware_universe_utils::createMarkerScale(0.25, 0.25, 0.25), - autoware_universe_utils::createMarkerColor(1.0, 0.0, 0.0, 0.999)); + autoware::universe_utils::createMarkerScale(0.25, 0.25, 0.25), + autoware::universe_utils::createMarkerColor(1.0, 0.0, 0.0, 0.999)); collision_point_marker.pose.position = stop_collision_points.at(i); debug_marker.markers.push_back(collision_point_marker); } @@ -1547,10 +1547,10 @@ void ObstacleCruisePlannerNode::publishDebugMarker() const debug_marker.markers.push_back(obstacle_marker); // collision point - auto collision_point_marker = autoware_universe_utils::createDefaultMarker( + auto collision_point_marker = autoware::universe_utils::createDefaultMarker( "map", now(), "stop_collision_points", 0, Marker::SPHERE, - autoware_universe_utils::createMarkerScale(0.25, 0.25, 0.25), - autoware_universe_utils::createMarkerColor(1.0, 0.0, 0.0, 0.999)); + autoware::universe_utils::createMarkerScale(0.25, 0.25, 0.25), + autoware::universe_utils::createMarkerColor(1.0, 0.0, 0.0, 0.999)); collision_point_marker.pose.position = debug_data_ptr_->obstacles_to_stop.at(i).collision_point; debug_marker.markers.push_back(collision_point_marker); } @@ -1564,16 +1564,16 @@ void ObstacleCruisePlannerNode::publishDebugMarker() const debug_marker.markers.push_back(obstacle_marker); // collision points - auto front_collision_point_marker = autoware_universe_utils::createDefaultMarker( + auto front_collision_point_marker = autoware::universe_utils::createDefaultMarker( "map", now(), "slow_down_collision_points", i * 2 + 0, Marker::SPHERE, - autoware_universe_utils::createMarkerScale(0.25, 0.25, 0.25), - autoware_universe_utils::createMarkerColor(1.0, 0.0, 0.0, 0.999)); + autoware::universe_utils::createMarkerScale(0.25, 0.25, 0.25), + autoware::universe_utils::createMarkerColor(1.0, 0.0, 0.0, 0.999)); front_collision_point_marker.pose.position = debug_data_ptr_->obstacles_to_slow_down.at(i).front_collision_point; - auto back_collision_point_marker = autoware_universe_utils::createDefaultMarker( + auto back_collision_point_marker = autoware::universe_utils::createDefaultMarker( "map", now(), "slow_down_collision_points", i * 2 + 1, Marker::SPHERE, - autoware_universe_utils::createMarkerScale(0.25, 0.25, 0.25), - autoware_universe_utils::createMarkerColor(1.0, 0.0, 0.0, 0.999)); + autoware::universe_utils::createMarkerScale(0.25, 0.25, 0.25), + autoware::universe_utils::createMarkerColor(1.0, 0.0, 0.0, 0.999)); back_collision_point_marker.pose.position = debug_data_ptr_->obstacles_to_slow_down.at(i).back_collision_point; @@ -1590,10 +1590,10 @@ void ObstacleCruisePlannerNode::publishDebugMarker() const } { // footprint polygons - auto marker = autoware_universe_utils::createDefaultMarker( + auto marker = autoware::universe_utils::createDefaultMarker( "map", now(), "detection_polygons", 0, Marker::LINE_LIST, - autoware_universe_utils::createMarkerScale(0.01, 0.0, 0.0), - autoware_universe_utils::createMarkerColor(0.0, 1.0, 0.0, 0.999)); + autoware::universe_utils::createMarkerScale(0.01, 0.0, 0.0), + autoware::universe_utils::createMarkerColor(0.0, 1.0, 0.0, 0.999)); for (const auto & detection_polygon : debug_data_ptr_->detection_polygons) { for (size_t dp_idx = 0; dp_idx < detection_polygon.outer().size(); ++dp_idx) { @@ -1602,16 +1602,16 @@ void ObstacleCruisePlannerNode::publishDebugMarker() const detection_polygon.outer().at((dp_idx + 1) % detection_polygon.outer().size()); marker.points.push_back( - autoware_universe_utils::createPoint(current_point.x(), current_point.y(), 0.0)); + autoware::universe_utils::createPoint(current_point.x(), current_point.y(), 0.0)); marker.points.push_back( - autoware_universe_utils::createPoint(next_point.x(), next_point.y(), 0.0)); + autoware::universe_utils::createPoint(next_point.x(), next_point.y(), 0.0)); } } debug_marker.markers.push_back(marker); } // slow down debug wall marker - autoware_universe_utils::appendMarkerArray( + autoware::universe_utils::appendMarkerArray( debug_data_ptr_->slow_down_debug_wall_marker, &debug_marker); debug_marker_pub_->publish(debug_marker); diff --git a/planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp b/planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp index b409ed9239f7e..d256a64984667 100644 --- a/planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp @@ -174,7 +174,7 @@ std::vector OptimizationBasedPlanner::generateCruiseTrajectory( // Publish Debug trajectories const double traj_front_to_vehicle_offset = - autoware_motion_utils::calcSignedArcLength(stop_traj_points, 0, closest_idx); + autoware::motion_utils::calcSignedArcLength(stop_traj_points, 0, closest_idx); publishDebugTrajectory( planner_data, traj_front_to_vehicle_offset, time_vec, *s_boundaries, optimized_result); @@ -217,7 +217,7 @@ std::vector OptimizationBasedPlanner::generateCruiseTrajectory( } } const auto traj_stop_dist = - autoware_motion_utils::calcDistanceToForwardStopPoint(stop_traj_points, closest_idx); + autoware::motion_utils::calcDistanceToForwardStopPoint(stop_traj_points, closest_idx); if (traj_stop_dist) { closest_stop_dist = std::min(*traj_stop_dist + traj_front_to_vehicle_offset, closest_stop_dist); } @@ -227,7 +227,7 @@ std::vector OptimizationBasedPlanner::generateCruiseTrajectory( std::vector resampled_opt_position; for (size_t i = closest_idx; i < stop_traj_points.size(); ++i) { const double query_s = std::max( - autoware_motion_utils::calcSignedArcLength(stop_traj_points, 0, i), opt_position.front()); + autoware::motion_utils::calcSignedArcLength(stop_traj_points, 0, i), opt_position.front()); if (query_s > opt_position.back()) { break_id = i; break; @@ -253,7 +253,7 @@ std::vector OptimizationBasedPlanner::generateCruiseTrajectory( output.back().longitudinal_velocity_mps = 0.0; // terminal velocity is zero // Insert Closest Stop Point - autoware_motion_utils::insertStopPoint(0, closest_stop_dist, output); + autoware::motion_utils::insertStopPoint(0, closest_stop_dist, output); prev_output_ = output; return output; @@ -309,7 +309,7 @@ std::tuple OptimizationBasedPlanner::calcInitialMotion( TrajectoryPoint prev_output_closest_point; if (smoothed_trajectory_ptr_) { - prev_output_closest_point = autoware_motion_utils::calcInterpolatedPoint( + prev_output_closest_point = autoware::motion_utils::calcInterpolatedPoint( *smoothed_trajectory_ptr_, ego_pose, ego_nearest_param_.dist_threshold, ego_nearest_param_.yaw_threshold); } else { @@ -336,7 +336,7 @@ std::tuple OptimizationBasedPlanner::calcInitialMotion( const double engage_vel_thr = engage_velocity_ * engage_exit_ratio_; if (vehicle_speed < engage_vel_thr) { if (target_vel >= engage_velocity_) { - const auto stop_dist = autoware_motion_utils::calcDistanceToForwardStopPoint( + const auto stop_dist = autoware::motion_utils::calcDistanceToForwardStopPoint( input_traj_points, ego_pose, ego_nearest_param_.dist_threshold, ego_nearest_param_.yaw_threshold); if ((stop_dist && *stop_dist > stop_dist_to_prohibit_engage_) || !stop_dist) { @@ -372,7 +372,7 @@ bool OptimizationBasedPlanner::checkHasReachedGoal( const PlannerData & planner_data, const std::vector & stop_traj_points) { // If goal is close and current velocity is low, we don't optimize trajectory - const auto closest_stop_dist = autoware_motion_utils::calcDistanceToForwardStopPoint( + const auto closest_stop_dist = autoware::motion_utils::calcDistanceToForwardStopPoint( stop_traj_points, planner_data.ego_pose, ego_nearest_param_.dist_threshold, ego_nearest_param_.yaw_threshold); if (closest_stop_dist && *closest_stop_dist < 0.5 && planner_data.ego_vel < 0.6) { @@ -428,7 +428,7 @@ std::optional OptimizationBasedPlanner::getSBoundaries( const double rss_dist = calcRSSDistance(planner_data.ego_vel, obj_vel); const auto & safe_distance_margin = longitudinal_info_.safe_distance_margin; - const double ego_obj_length = autoware_motion_utils::calcSignedArcLength( + const double ego_obj_length = autoware::motion_utils::calcSignedArcLength( stop_traj_points, planner_data.ego_pose.position, obj.collision_points.front().point); const double slow_down_point_length = ego_obj_length - (rss_dist + safe_distance_margin); @@ -442,15 +442,15 @@ std::optional OptimizationBasedPlanner::getSBoundaries( if (min_slow_down_idx) { const auto & current_time = planner_data.current_time; - const auto marker_pose = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto marker_pose = autoware::motion_utils::calcLongitudinalOffsetPose( stop_traj_points, planner_data.ego_pose.position, min_slow_down_point_length); if (marker_pose) { MarkerArray wall_msg; - const auto markers = autoware_motion_utils::createSlowDownVirtualWallMarker( + const auto markers = autoware::motion_utils::createSlowDownVirtualWallMarker( marker_pose.value(), "obstacle to follow", current_time, 0); - autoware_universe_utils::appendMarkerArray(markers, &wall_msg); + autoware::universe_utils::appendMarkerArray(markers, &wall_msg); // publish rviz marker debug_wall_marker_pub_->publish(wall_msg); @@ -583,7 +583,7 @@ bool OptimizationBasedPlanner::checkOnTrajectory( } const double lateral_offset = - std::fabs(autoware_motion_utils::calcLateralOffset(stop_traj_points, point.point)); + std::fabs(autoware::motion_utils::calcLateralOffset(stop_traj_points, point.point)); if (lateral_offset < vehicle_info_.max_lateral_offset_m + 0.1) { return true; @@ -597,10 +597,10 @@ std::optional OptimizationBasedPlanner::calcTrajectoryLengthFromCurrentP { const size_t ego_segment_idx = ego_nearest_param_.findSegmentIndex(traj_points, ego_pose); - const double traj_length = autoware_motion_utils::calcSignedArcLength( + const double traj_length = autoware::motion_utils::calcSignedArcLength( traj_points, ego_pose.position, ego_segment_idx, traj_points.size() - 1); - const auto dist_to_closest_stop_point = autoware_motion_utils::calcDistanceToForwardStopPoint( + const auto dist_to_closest_stop_point = autoware::motion_utils::calcDistanceToForwardStopPoint( traj_points, ego_pose, ego_nearest_param_.dist_threshold, ego_nearest_param_.yaw_threshold); if (dist_to_closest_stop_point) { return std::min(traj_length, dist_to_closest_stop_point.value()); @@ -627,7 +627,7 @@ geometry_msgs::msg::Pose OptimizationBasedPlanner::transformBaseLink2Center( geometry_msgs::msg::Pose center_pose; center_pose.position = - autoware_universe_utils::createPoint(map2center.x(), map2center.y(), map2center.z()); + autoware::universe_utils::createPoint(map2center.x(), map2center.y(), map2center.z()); center_pose.orientation = pose_base_link.orientation; return center_pose; diff --git a/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp b/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp index 56201229cdee6..345265b1d20b0 100644 --- a/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp @@ -313,13 +313,13 @@ std::vector PIDBasedPlanner::planCruise( const size_t wall_idx = obstacle_cruise_utils::getIndexWithLongitudinalOffset( stop_traj_points, dist_to_rss_wall, ego_idx); - auto markers = autoware_motion_utils::createSlowDownVirtualWallMarker( + auto markers = autoware::motion_utils::createSlowDownVirtualWallMarker( stop_traj_points.at(wall_idx).pose, "obstacle cruise", planner_data.current_time, 0); // NOTE: use a different color from slow down one to visualize cruise and slow down // separately. markers.markers.front().color = - autoware_universe_utils::createMarkerColor(1.0, 0.6, 0.1, 0.5); - autoware_universe_utils::appendMarkerArray(markers, &debug_data_ptr_->cruise_wall_marker); + autoware::universe_utils::createMarkerColor(1.0, 0.6, 0.1, 0.5); + autoware::universe_utils::appendMarkerArray(markers, &debug_data_ptr_->cruise_wall_marker); // cruise obstacle debug_data_ptr_->obstacles_to_cruise.push_back(cruise_obstacle_info->obstacle); @@ -345,8 +345,8 @@ std::vector PIDBasedPlanner::planCruise( // delete marker const auto markers = - autoware_motion_utils::createDeletedSlowDownVirtualWallMarker(planner_data.current_time, 0); - autoware_universe_utils::appendMarkerArray(markers, &debug_data_ptr_->cruise_wall_marker); + autoware::motion_utils::createDeletedSlowDownVirtualWallMarker(planner_data.current_time, 0); + autoware::universe_utils::appendMarkerArray(markers, &debug_data_ptr_->cruise_wall_marker); return stop_traj_points; } @@ -480,7 +480,7 @@ std::vector PIDBasedPlanner::doCruiseWithTrajectory( // set target longitudinal motion const auto prev_traj_closest_point = [&]() -> TrajectoryPoint { // if (smoothed_trajectory_ptr_) { - // return autoware_motion_utils::calcInterpolatedPoint( + // return autoware::motion_utils::calcInterpolatedPoint( // *smoothed_trajectory_ptr_, planner_data.ego_pose, nearest_dist_deviation_threshold_, // nearest_yaw_deviation_threshold_); // } @@ -492,7 +492,7 @@ std::vector PIDBasedPlanner::doCruiseWithTrajectory( auto cruise_traj_points = getAccelerationLimitedTrajectory( stop_traj_points, planner_data.ego_pose, v0, a0, target_acc, target_jerk_ratio); - const auto zero_vel_idx_opt = autoware_motion_utils::searchZeroVelocityIndex(cruise_traj_points); + const auto zero_vel_idx_opt = autoware::motion_utils::searchZeroVelocityIndex(cruise_traj_points); if (!zero_vel_idx_opt) { return cruise_traj_points; } @@ -529,7 +529,7 @@ std::vector PIDBasedPlanner::getAccelerationLimitedTrajectory( }; // calculate sv graph - const double s_traj = autoware_motion_utils::calcArcLength(traj_points); + const double s_traj = autoware::motion_utils::calcArcLength(traj_points); // const double t_max = 10.0; const double s_max = 50.0; const double max_sampling_num = 100.0; @@ -599,7 +599,7 @@ std::vector PIDBasedPlanner::getAccelerationLimitedTrajectory( double sum_dist = 0.0; for (size_t i = ego_seg_idx; i < acc_limited_traj_points.size(); ++i) { if (i != ego_seg_idx) { - sum_dist += autoware_universe_utils::calcDistance2d( + sum_dist += autoware::universe_utils::calcDistance2d( acc_limited_traj_points.at(i - 1), acc_limited_traj_points.at(i)); } @@ -622,7 +622,7 @@ std::vector PIDBasedPlanner::getAccelerationLimitedTrajectory( void PIDBasedPlanner::updateCruiseParam(const std::vector & parameters) { - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.min_accel_during_cruise", min_accel_during_cruise_); { // velocity limit based planner @@ -632,26 +632,26 @@ void PIDBasedPlanner::updateCruiseParam(const std::vector & p double ki = p.pid_vel_controller->getKi(); double kd = p.pid_vel_controller->getKd(); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.velocity_limit_based_planner.kp", kp); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.velocity_limit_based_planner.ki", ki); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.velocity_limit_based_planner.kd", kd); p.pid_vel_controller->updateParam(kp, ki, kd); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.velocity_limit_based_planner.output_ratio_during_accel", p.output_ratio_during_accel); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.vel_to_acc_weight", p.vel_to_acc_weight); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.velocity_limit_based_planner.enable_jerk_limit_to_output_acc", p.enable_jerk_limit_to_output_acc); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.velocity_limit_based_planner.disable_target_acceleration", p.disable_target_acceleration); @@ -665,11 +665,11 @@ void PIDBasedPlanner::updateCruiseParam(const std::vector & p double ki_acc = p.pid_acc_controller->getKi(); double kd_acc = p.pid_acc_controller->getKd(); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.velocity_insertion_based_planner.kp_acc", kp_acc); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.velocity_insertion_based_planner.ki_acc", ki_acc); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.velocity_insertion_based_planner.kd_acc", kd_acc); p.pid_acc_controller->updateParam(kp_acc, ki_acc, kd_acc); @@ -678,32 +678,32 @@ void PIDBasedPlanner::updateCruiseParam(const std::vector & p double ki_jerk = p.pid_jerk_controller->getKi(); double kd_jerk = p.pid_jerk_controller->getKd(); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.velocity_insertion_based_planner.kp_jerk", kp_jerk); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.velocity_insertion_based_planner.ki_jerk", ki_jerk); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.velocity_insertion_based_planner.kd_jerk", kd_jerk); p.pid_jerk_controller->updateParam(kp_jerk, ki_jerk, kd_jerk); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.velocity_insertion_based_planner.output_acc_ratio_during_accel", p.output_acc_ratio_during_accel); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.velocity_insertion_based_planner.output_jerk_ratio_during_accel", p.output_jerk_ratio_during_accel); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.velocity_insertion_based_planner.enable_jerk_limit_to_output_acc", p.enable_jerk_limit_to_output_acc); } // min_cruise_target_vel - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.min_cruise_target_vel", min_cruise_target_vel_); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "cruise.pid_based_planner.time_to_evaluate_rss", time_to_evaluate_rss_); } diff --git a/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp b/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp index 40c48c78ab021..343cb720fb802 100644 --- a/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp @@ -50,7 +50,7 @@ tier4_planning_msgs::msg::StopReasonArray makeStopReasonArray( stop_factor.stop_pose = stop_pose; geometry_msgs::msg::Point stop_factor_point = stop_obstacle.collision_point; stop_factor_point.z = stop_pose.position.z; - stop_factor.dist_to_stop_pose = autoware_motion_utils::calcSignedArcLength( + stop_factor.dist_to_stop_pose = autoware::motion_utils::calcSignedArcLength( planner_data.traj_points, planner_data.ego_pose.position, stop_pose.position); stop_factor.stop_factor_points.emplace_back(stop_factor_point); @@ -218,14 +218,14 @@ double calcDecelerationVelocityFromDistanceToTarget( std::vector resampleTrajectoryPoints( const std::vector & traj_points, const double interval) { - const auto traj = autoware_motion_utils::convertToTrajectory(traj_points); - const auto resampled_traj = autoware_motion_utils::resampleTrajectory(traj, interval); - return autoware_motion_utils::convertToTrajectoryPointArray(resampled_traj); + const auto traj = autoware::motion_utils::convertToTrajectory(traj_points); + const auto resampled_traj = autoware::motion_utils::resampleTrajectory(traj, interval); + return autoware::motion_utils::convertToTrajectoryPointArray(resampled_traj); } -autoware_universe_utils::Point2d convertPoint(const geometry_msgs::msg::Point & p) +autoware::universe_utils::Point2d convertPoint(const geometry_msgs::msg::Point & p) { - return autoware_universe_utils::Point2d{p.x, p.y}; + return autoware::universe_utils::Point2d{p.x, p.y}; } } // namespace @@ -248,8 +248,8 @@ std::vector PlannerInterface::generateStopTrajectory( // delete marker const auto markers = - autoware_motion_utils::createDeletedStopVirtualWallMarker(planner_data.current_time, 0); - autoware_universe_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); + autoware::motion_utils::createDeletedStopVirtualWallMarker(planner_data.current_time, 0); + autoware::universe_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); prev_stop_distance_info_ = std::nullopt; return planner_data.traj_points; @@ -269,14 +269,14 @@ std::vector PlannerInterface::generateStopTrajectory( const auto ego_segment_idx = ego_nearest_param_.findSegmentIndex(planner_data.traj_points, planner_data.ego_pose); const double dist_to_collide_on_ref_traj = - autoware_motion_utils::calcSignedArcLength(planner_data.traj_points, 0, ego_segment_idx) + + autoware::motion_utils::calcSignedArcLength(planner_data.traj_points, 0, ego_segment_idx) + stop_obstacle.dist_to_collide_on_decimated_traj; const double desired_margin = [&]() { const double margin_from_obstacle = calculateMarginFromObstacleOnCurve(planner_data, stop_obstacle); // Use terminal margin (terminal_safe_distance_margin) for obstacle stop - const auto ref_traj_length = autoware_motion_utils::calcSignedArcLength( + const auto ref_traj_length = autoware::motion_utils::calcSignedArcLength( planner_data.traj_points, 0, planner_data.traj_points.size() - 1); if (dist_to_collide_on_ref_traj > ref_traj_length) { return longitudinal_info_.terminal_safe_distance_margin; @@ -284,11 +284,11 @@ std::vector PlannerInterface::generateStopTrajectory( // If behavior stop point is ahead of the closest_obstacle_stop point within a certain // margin we set closest_obstacle_stop_distance to closest_behavior_stop_distance - const auto closest_behavior_stop_idx = autoware_motion_utils::searchZeroVelocityIndex( + const auto closest_behavior_stop_idx = autoware::motion_utils::searchZeroVelocityIndex( planner_data.traj_points, ego_segment_idx + 1); if (closest_behavior_stop_idx) { const double closest_behavior_stop_dist_on_ref_traj = - autoware_motion_utils::calcSignedArcLength( + autoware::motion_utils::calcSignedArcLength( planner_data.traj_points, 0, *closest_behavior_stop_idx); const double stop_dist_diff = closest_behavior_stop_dist_on_ref_traj - (dist_to_collide_on_ref_traj - margin_from_obstacle); @@ -329,7 +329,7 @@ std::vector PlannerInterface::generateStopTrajectory( } const double acceptable_stop_pos = - autoware_motion_utils::calcSignedArcLength( + autoware::motion_utils::calcSignedArcLength( planner_data.traj_points, 0, planner_data.ego_pose.position) + calcMinimumDistanceToStop( planner_data.ego_vel, longitudinal_info_.limit_max_accel, acceptable_stop_acc.value()); @@ -356,8 +356,8 @@ std::vector PlannerInterface::generateStopTrajectory( if (!determined_zero_vel_dist) { // delete marker const auto markers = - autoware_motion_utils::createDeletedStopVirtualWallMarker(planner_data.current_time, 0); - autoware_universe_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); + autoware::motion_utils::createDeletedStopVirtualWallMarker(planner_data.current_time, 0); + autoware::universe_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); prev_stop_distance_info_ = std::nullopt; return planner_data.traj_points; @@ -370,9 +370,9 @@ std::vector PlannerInterface::generateStopTrajectory( // NOTE: We assume that the current trajectory's front point is ahead of the previous // trajectory's front point. const size_t traj_front_point_prev_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( prev_stop_distance_info_->first, planner_data.traj_points.front().pose); - const double diff_dist_front_points = autoware_motion_utils::calcSignedArcLength( + const double diff_dist_front_points = autoware::motion_utils::calcSignedArcLength( prev_stop_distance_info_->first, 0, planner_data.traj_points.front().pose.position, traj_front_point_prev_seg_idx); @@ -387,13 +387,13 @@ std::vector PlannerInterface::generateStopTrajectory( // Insert stop point auto output_traj_points = planner_data.traj_points; const auto zero_vel_idx = - autoware_motion_utils::insertStopPoint(0, *determined_zero_vel_dist, output_traj_points); + autoware::motion_utils::insertStopPoint(0, *determined_zero_vel_dist, output_traj_points); if (zero_vel_idx) { // virtual wall marker for stop obstacle - const auto markers = autoware_motion_utils::createStopVirtualWallMarker( + const auto markers = autoware::motion_utils::createStopVirtualWallMarker( output_traj_points.at(*zero_vel_idx).pose, "obstacle stop", planner_data.current_time, 0, abs_ego_offset, "", planner_data.is_driving_forward); - autoware_universe_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); + autoware::universe_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); debug_data_ptr_->obstacles_to_stop.push_back(*determined_stop_obstacle); // Publish Stop Reason @@ -406,7 +406,7 @@ std::vector PlannerInterface::generateStopTrajectory( // Publish if ego vehicle will over run against the stop point with a limit acceleration const bool will_over_run = determined_zero_vel_dist.value() > - autoware_motion_utils::calcSignedArcLength( + autoware::motion_utils::calcSignedArcLength( planner_data.traj_points, 0, planner_data.ego_pose.position) + determined_stop_obstacle->dist_to_collide_on_decimated_traj + determined_desired_margin.value() + 0.1; @@ -448,7 +448,7 @@ double PlannerInterface::calculateMarginFromObstacleOnCurve( : std::abs(vehicle_info_.min_longitudinal_offset_m); // calculate short trajectory points towards obstacle - const size_t obj_segment_idx = autoware_motion_utils::findNearestSegmentIndex( + const size_t obj_segment_idx = autoware::motion_utils::findNearestSegmentIndex( planner_data.traj_points, stop_obstacle.collision_point); std::vector short_traj_points{planner_data.traj_points.at(obj_segment_idx + 1)}; double sum_short_traj_length{0.0}; @@ -460,7 +460,7 @@ double PlannerInterface::calculateMarginFromObstacleOnCurve( longitudinal_info_.safe_distance_margin + abs_ego_offset < sum_short_traj_length) { break; } - sum_short_traj_length += autoware_universe_utils::calcDistance2d( + sum_short_traj_length += autoware::universe_utils::calcDistance2d( planner_data.traj_points.at(i), planner_data.traj_points.at(i + 1)); } std::reverse(short_traj_points.begin(), short_traj_points.end()); @@ -471,15 +471,15 @@ double PlannerInterface::calculateMarginFromObstacleOnCurve( // calculate collision index between straight line from ego pose and object const auto calculate_distance_from_straight_ego_path = [&](const auto & ego_pose, const auto & object_polygon) { - const auto forward_ego_pose = autoware_universe_utils::calcOffsetPose( + const auto forward_ego_pose = autoware::universe_utils::calcOffsetPose( ego_pose, longitudinal_info_.safe_distance_margin + 3.0, 0.0, 0.0); - const auto ego_straight_segment = autoware_universe_utils::Segment2d{ + const auto ego_straight_segment = autoware::universe_utils::Segment2d{ convertPoint(ego_pose.position), convertPoint(forward_ego_pose.position)}; return boost::geometry::distance(ego_straight_segment, object_polygon); }; const auto resampled_short_traj_points = resampleTrajectoryPoints(short_traj_points, 0.5); const auto object_polygon = - autoware_universe_utils::toPolygon2d(stop_obstacle.pose, stop_obstacle.shape); + autoware::universe_utils::toPolygon2d(stop_obstacle.pose, stop_obstacle.shape); const auto collision_idx = [&]() -> std::optional { for (size_t i = 0; i < resampled_short_traj_points.size(); ++i) { const double dist_to_obj = calculate_distance_from_straight_ego_path( @@ -499,7 +499,7 @@ double PlannerInterface::calculateMarginFromObstacleOnCurve( // calculate margin from obstacle const double partial_segment_length = [&]() { - const double collision_segment_length = autoware_universe_utils::calcDistance2d( + const double collision_segment_length = autoware::universe_utils::calcDistance2d( resampled_short_traj_points.at(*collision_idx - 1), resampled_short_traj_points.at(*collision_idx)); const double prev_dist = calculate_distance_from_straight_ego_path( @@ -512,7 +512,7 @@ double PlannerInterface::calculateMarginFromObstacleOnCurve( const double short_margin_from_obstacle = partial_segment_length + - autoware_motion_utils::calcSignedArcLength( + autoware::motion_utils::calcSignedArcLength( resampled_short_traj_points, *collision_idx, stop_obstacle.collision_point) - abs_ego_offset + additional_safe_distance_margin_on_curve_; @@ -532,9 +532,9 @@ double PlannerInterface::calcDistanceToCollisionPoint( ego_nearest_param_.findSegmentIndex(planner_data.traj_points, planner_data.ego_pose); const size_t collision_segment_idx = - autoware_motion_utils::findNearestSegmentIndex(planner_data.traj_points, collision_point); + autoware::motion_utils::findNearestSegmentIndex(planner_data.traj_points, collision_point); - const auto dist_to_collision_point = autoware_motion_utils::calcSignedArcLength( + const auto dist_to_collision_point = autoware::motion_utils::calcSignedArcLength( planner_data.traj_points, planner_data.ego_pose.position, ego_segment_idx, collision_point, collision_segment_idx); @@ -553,7 +553,7 @@ std::vector PlannerInterface::generateSlowDownTrajectory( const double dist_to_ego = [&]() { const size_t ego_seg_idx = ego_nearest_param_.findSegmentIndex(slow_down_traj_points, planner_data.ego_pose); - return autoware_motion_utils::calcSignedArcLength( + return autoware::motion_utils::calcSignedArcLength( slow_down_traj_points, 0, planner_data.ego_pose.position, ego_seg_idx); }(); const double abs_ego_offset = planner_data.is_driving_forward @@ -563,7 +563,7 @@ std::vector PlannerInterface::generateSlowDownTrajectory( // define function to insert slow down velocity to trajectory const auto insert_point_in_trajectory = [&](const double lon_dist) -> std::optional { const auto inserted_idx = - autoware_motion_utils::insertTargetPoint(0, lon_dist, slow_down_traj_points); + autoware::motion_utils::insertTargetPoint(0, lon_dist, slow_down_traj_points); if (inserted_idx) { if (inserted_idx.value() + 1 <= slow_down_traj_points.size() - 1) { // zero-order hold for velocity interpolation @@ -648,25 +648,25 @@ std::vector PlannerInterface::generateSlowDownTrajectory( return *slow_down_end_idx; }(); - const auto markers = autoware_motion_utils::createSlowDownVirtualWallMarker( + const auto markers = autoware::motion_utils::createSlowDownVirtualWallMarker( slow_down_traj_points.at(slow_down_wall_idx).pose, "obstacle slow down", planner_data.current_time, i, abs_ego_offset, "", planner_data.is_driving_forward); - autoware_universe_utils::appendMarkerArray(markers, &debug_data_ptr_->slow_down_wall_marker); + autoware::universe_utils::appendMarkerArray(markers, &debug_data_ptr_->slow_down_wall_marker); } // add debug virtual wall if (slow_down_start_idx) { - const auto markers = autoware_motion_utils::createSlowDownVirtualWallMarker( + const auto markers = autoware::motion_utils::createSlowDownVirtualWallMarker( slow_down_traj_points.at(*slow_down_start_idx).pose, "obstacle slow down start", planner_data.current_time, i * 2, abs_ego_offset, "", planner_data.is_driving_forward); - autoware_universe_utils::appendMarkerArray( + autoware::universe_utils::appendMarkerArray( markers, &debug_data_ptr_->slow_down_debug_wall_marker); } if (slow_down_end_idx) { - const auto markers = autoware_motion_utils::createSlowDownVirtualWallMarker( + const auto markers = autoware::motion_utils::createSlowDownVirtualWallMarker( slow_down_traj_points.at(*slow_down_end_idx).pose, "obstacle slow down end", planner_data.current_time, i * 2 + 1, abs_ego_offset, "", planner_data.is_driving_forward); - autoware_universe_utils::appendMarkerArray( + autoware::universe_utils::appendMarkerArray( markers, &debug_data_ptr_->slow_down_debug_wall_marker); } @@ -728,9 +728,9 @@ PlannerInterface::calculateDistanceToSlowDownWithConstraints( // calculate distance to collision points const double dist_to_front_collision = - autoware_motion_utils::calcSignedArcLength(traj_points, 0, obstacle.front_collision_point); + autoware::motion_utils::calcSignedArcLength(traj_points, 0, obstacle.front_collision_point); const double dist_to_back_collision = - autoware_motion_utils::calcSignedArcLength(traj_points, 0, obstacle.back_collision_point); + autoware::motion_utils::calcSignedArcLength(traj_points, 0, obstacle.back_collision_point); // calculate offset distance to first collision considering relative velocity const double relative_vel = planner_data.ego_vel - obstacle.velocity; @@ -773,9 +773,9 @@ PlannerInterface::calculateDistanceToSlowDownWithConstraints( const auto apply_lowpass_filter = [&](const double dist_to_slow_down, const auto prev_point) { if (prev_output && prev_point) { const size_t seg_idx = - autoware_motion_utils::findNearestSegmentIndex(traj_points, prev_point->position); + autoware::motion_utils::findNearestSegmentIndex(traj_points, prev_point->position); const double prev_dist_to_slow_down = - autoware_motion_utils::calcSignedArcLength(traj_points, 0, prev_point->position, seg_idx); + autoware::motion_utils::calcSignedArcLength(traj_points, 0, prev_point->position, seg_idx); return signal_processing::lowpassFilter( dist_to_slow_down, prev_dist_to_slow_down, slow_down_param_.lpf_gain_dist_to_slow_down); } diff --git a/planning/autoware_obstacle_cruise_planner/src/polygon_utils.cpp b/planning/autoware_obstacle_cruise_planner/src/polygon_utils.cpp index 1a032c9f5603f..8c3abe58f5d59 100644 --- a/planning/autoware_obstacle_cruise_planner/src/polygon_utils.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/polygon_utils.cpp @@ -35,7 +35,7 @@ PointWithStamp calcNearestCollisionPoint( std::vector dist_vec; for (const auto & collision_point : collision_points) { - const double dist = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const double dist = autoware::motion_utils::calcLongitudinalOffsetToSegment( segment_points, 0, collision_point.point); dist_vec.push_back(dist); } @@ -51,10 +51,10 @@ std::optional>> getCollisionIndex( const geometry_msgs::msg::Pose & object_pose, const rclcpp::Time & object_time, const Shape & object_shape, const double max_dist = std::numeric_limits::max()) { - const auto obj_polygon = autoware_universe_utils::toPolygon2d(object_pose, object_shape); + const auto obj_polygon = autoware::universe_utils::toPolygon2d(object_pose, object_shape); for (size_t i = 0; i < traj_polygons.size(); ++i) { const double approximated_dist = - autoware_universe_utils::calcDistance2d(traj_points.at(i).pose, object_pose); + autoware::universe_utils::calcDistance2d(traj_points.at(i).pose, object_pose); if (approximated_dist > max_dist) { continue; } @@ -105,14 +105,14 @@ std::optional> getCollisionPoint( const double x_diff_to_bumper = is_driving_forward ? vehicle_info.max_longitudinal_offset_m : vehicle_info.min_longitudinal_offset_m; - const auto bumper_pose = autoware_universe_utils::calcOffsetPose( + const auto bumper_pose = autoware::universe_utils::calcOffsetPose( traj_points.at(collision_info->first).pose, x_diff_to_bumper, 0.0, 0.0); std::optional max_collision_length = std::nullopt; std::optional max_collision_point = std::nullopt; for (const auto & poly_vertex : collision_info->second) { const double dist_from_bumper = - std::abs(autoware_universe_utils::inverseTransformPoint(poly_vertex.point, bumper_pose).x); + std::abs(autoware::universe_utils::inverseTransformPoint(poly_vertex.point, bumper_pose).x); if (!max_collision_length.has_value() || dist_from_bumper > *max_collision_length) { max_collision_length = dist_from_bumper; @@ -121,7 +121,7 @@ std::optional> getCollisionPoint( } return std::make_pair( *max_collision_point, - autoware_motion_utils::calcSignedArcLength(traj_points, 0, collision_info->first) - + autoware::motion_utils::calcSignedArcLength(traj_points, 0, collision_info->first) - *max_collision_length); } diff --git a/planning/autoware_obstacle_cruise_planner/src/utils.cpp b/planning/autoware_obstacle_cruise_planner/src/utils.cpp index b95fb6e5d29f9..8162d8036d9dc 100644 --- a/planning/autoware_obstacle_cruise_planner/src/utils.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/utils.cpp @@ -59,10 +59,10 @@ visualization_msgs::msg::Marker getObjectMarker( { const auto current_time = rclcpp::Clock().now(); - auto marker = autoware_universe_utils::createDefaultMarker( + auto marker = autoware::universe_utils::createDefaultMarker( "map", current_time, ns, idx, visualization_msgs::msg::Marker::SPHERE, - autoware_universe_utils::createMarkerScale(2.0, 2.0, 2.0), - autoware_universe_utils::createMarkerColor(r, g, b, 0.8)); + autoware::universe_utils::createMarkerScale(2.0, 2.0, 2.0), + autoware::universe_utils::createMarkerColor(r, g, b, 0.8)); marker.pose = obj_pose; diff --git a/planning/autoware_path_optimizer/include/autoware/path_optimizer/common_structs.hpp b/planning/autoware_path_optimizer/include/autoware/path_optimizer/common_structs.hpp index df9dec3cf3b75..7f2688ffaad95 100644 --- a/planning/autoware_path_optimizer/include/autoware/path_optimizer/common_structs.hpp +++ b/planning/autoware_path_optimizer/include/autoware/path_optimizer/common_structs.hpp @@ -89,7 +89,7 @@ struct TimeKeeper double accumulated_time{0.0}; - autoware_universe_utils::StopWatch< + autoware::universe_utils::StopWatch< std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> stop_watch_; }; @@ -122,7 +122,7 @@ struct TrajectoryParam void onParam(const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; // common updateParam( @@ -145,7 +145,7 @@ struct EgoNearestParam void onParam(const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; updateParam(parameters, "ego_nearest_dist_threshold", dist_threshold); updateParam(parameters, "ego_nearest_yaw_threshold", yaw_threshold); } diff --git a/planning/autoware_path_optimizer/include/autoware/path_optimizer/mpt_optimizer.hpp b/planning/autoware_path_optimizer/include/autoware/path_optimizer/mpt_optimizer.hpp index cece0142bc29a..4303e5c7e05b4 100644 --- a/planning/autoware_path_optimizer/include/autoware/path_optimizer/mpt_optimizer.hpp +++ b/planning/autoware_path_optimizer/include/autoware/path_optimizer/mpt_optimizer.hpp @@ -93,9 +93,9 @@ struct ReferencePoint geometry_msgs::msg::Pose offsetDeviation(const double lat_dev, const double yaw_dev) const { - auto pose_with_deviation = autoware_universe_utils::calcOffsetPose(pose, 0.0, lat_dev, 0.0); + auto pose_with_deviation = autoware::universe_utils::calcOffsetPose(pose, 0.0, lat_dev, 0.0); pose_with_deviation.orientation = - autoware_universe_utils::createQuaternionFromYaw(getYaw() + yaw_dev); + autoware::universe_utils::createQuaternionFromYaw(getYaw() + yaw_dev); return pose_with_deviation; } }; diff --git a/planning/autoware_path_optimizer/include/autoware/path_optimizer/node.hpp b/planning/autoware_path_optimizer/include/autoware/path_optimizer/node.hpp index d7356c0e43fc4..359c20f2a4d29 100644 --- a/planning/autoware_path_optimizer/include/autoware/path_optimizer/node.hpp +++ b/planning/autoware_path_optimizer/include/autoware/path_optimizer/node.hpp @@ -52,7 +52,7 @@ class PathOptimizer : public rclcpp::Node public: bool isDrivingForward(const std::vector & path_points) { - const auto is_driving_forward = autoware_motion_utils::isDrivingForward(path_points); + const auto is_driving_forward = autoware::motion_utils::isDrivingForward(path_points); is_driving_forward_ = is_driving_forward ? is_driving_forward.value() : is_driving_forward_; return is_driving_forward_; } @@ -90,7 +90,7 @@ class PathOptimizer : public rclcpp::Node // interface subscriber rclcpp::Subscription::SharedPtr path_sub_; - autoware_universe_utils::InterProcessPollingSubscriber ego_odom_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber ego_odom_sub_{ this, "~/input/odometry"}; // debug publisher @@ -137,9 +137,9 @@ class PathOptimizer : public rclcpp::Node private: double vehicle_stop_margin_outside_drivable_area_; - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; }; } // namespace autoware::path_optimizer diff --git a/planning/autoware_path_optimizer/include/autoware/path_optimizer/utils/geometry_utils.hpp b/planning/autoware_path_optimizer/include/autoware/path_optimizer/utils/geometry_utils.hpp index e53cf37890691..edc91bd40d4dc 100644 --- a/planning/autoware_path_optimizer/include/autoware/path_optimizer/utils/geometry_utils.hpp +++ b/planning/autoware_path_optimizer/include/autoware/path_optimizer/utils/geometry_utils.hpp @@ -36,14 +36,14 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { template <> geometry_msgs::msg::Point getPoint(const autoware::path_optimizer::ReferencePoint & p); template <> geometry_msgs::msg::Pose getPose(const autoware::path_optimizer::ReferencePoint & p); -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils namespace autoware::path_optimizer { @@ -52,8 +52,8 @@ namespace geometry_utils template bool isSamePoint(const T1 & t1, const T2 & t2) { - const auto p1 = autoware_universe_utils::getPoint(t1); - const auto p2 = autoware_universe_utils::getPoint(t2); + const auto p1 = autoware::universe_utils::getPoint(t1); + const auto p2 = autoware::universe_utils::getPoint(t2); constexpr double epsilon = 1e-6; if (epsilon < std::abs(p1.x - p2.x) || epsilon < std::abs(p1.y - p2.y)) { diff --git a/planning/autoware_path_optimizer/include/autoware/path_optimizer/utils/trajectory_utils.hpp b/planning/autoware_path_optimizer/include/autoware/path_optimizer/utils/trajectory_utils.hpp index acc40573ef542..a54d60835aadf 100644 --- a/planning/autoware_path_optimizer/include/autoware/path_optimizer/utils/trajectory_utils.hpp +++ b/planning/autoware_path_optimizer/include/autoware/path_optimizer/utils/trajectory_utils.hpp @@ -35,7 +35,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { template <> geometry_msgs::msg::Point getPoint(const autoware::path_optimizer::ReferencePoint & p); @@ -45,7 +45,7 @@ geometry_msgs::msg::Pose getPose(const autoware::path_optimizer::ReferencePoint template <> double getLongitudinalVelocity(const autoware::path_optimizer::ReferencePoint & p); -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils namespace autoware::path_optimizer { @@ -61,14 +61,14 @@ std::optional getPointIndexAfter( } double sum_length = - -autoware_motion_utils::calcLongitudinalOffsetToSegment(points, target_seg_idx, target_pos); + -autoware::motion_utils::calcLongitudinalOffsetToSegment(points, target_seg_idx, target_pos); std::optional output_idx{std::nullopt}; // search forward if (sum_length < min_offset) { for (size_t i = target_seg_idx + 1; i < points.size(); ++i) { - sum_length += autoware_universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); + sum_length += autoware::universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); if (min_offset < sum_length) { output_idx = i - 1; } @@ -82,7 +82,7 @@ std::optional getPointIndexAfter( // search backward for (size_t i = target_seg_idx; 0 < i; --i) { // NOTE: use size_t since i is always positive value - sum_length -= autoware_universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); + sum_length -= autoware::universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); if (sum_length < min_offset) { output_idx = i - 1; } @@ -98,7 +98,7 @@ template TrajectoryPoint convertToTrajectoryPoint(const T & point) { TrajectoryPoint traj_point; - traj_point.pose = autoware_universe_utils::getPose(point); + traj_point.pose = autoware::universe_utils::getPose(point); traj_point.longitudinal_velocity_mps = point.longitudinal_velocity_mps; traj_point.lateral_velocity_mps = point.lateral_velocity_mps; traj_point.heading_rate_rps = point.heading_rate_rps; @@ -109,9 +109,9 @@ template <> inline TrajectoryPoint convertToTrajectoryPoint(const ReferencePoint & ref_point) { TrajectoryPoint traj_point; - traj_point.pose = autoware_universe_utils::getPose(ref_point); + traj_point.pose = autoware::universe_utils::getPose(ref_point); traj_point.longitudinal_velocity_mps = - autoware_universe_utils::getLongitudinalVelocity(ref_point); + autoware::universe_utils::getLongitudinalVelocity(ref_point); return traj_point; } @@ -144,7 +144,7 @@ size_t findEgoIndex( const std::vector & points, const geometry_msgs::msg::Pose & ego_pose, const EgoNearestParam & ego_nearest_param) { - return autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( points, ego_pose, ego_nearest_param.dist_threshold, ego_nearest_param.yaw_threshold); } @@ -153,7 +153,7 @@ size_t findEgoSegmentIndex( const std::vector & points, const geometry_msgs::msg::Pose & ego_pose, const EgoNearestParam & ego_nearest_param) { - return autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( points, ego_pose, ego_nearest_param.dist_threshold, ego_nearest_param.yaw_threshold); } @@ -173,13 +173,13 @@ std::optional updateFrontPointForFix( { // calculate front point to insert in points as a fixed point const size_t front_seg_idx_for_fix = trajectory_utils::findEgoSegmentIndex( - points_for_fix, autoware_universe_utils::getPose(points.front()), ego_nearest_param); + points_for_fix, autoware::universe_utils::getPose(points.front()), ego_nearest_param); const size_t front_point_idx_for_fix = front_seg_idx_for_fix; const auto & front_fix_point = points_for_fix.at(front_point_idx_for_fix); // check if the points_for_fix is longer in front than points const double lon_offset_to_prev_front = - autoware_motion_utils::calcSignedArcLength(points, 0, front_fix_point.pose.position); + autoware::motion_utils::calcSignedArcLength(points, 0, front_fix_point.pose.position); if (0 < lon_offset_to_prev_front) { RCLCPP_DEBUG( rclcpp::get_logger("autoware_path_optimizer.trajectory_utils"), @@ -187,7 +187,7 @@ std::optional updateFrontPointForFix( return std::nullopt; } - const double dist = autoware_universe_utils::calcDistance2d(points.front(), front_fix_point); + const double dist = autoware::universe_utils::calcDistance2d(points.front(), front_fix_point); // check if deviation is not too large constexpr double max_lat_error = 3.0; diff --git a/planning/autoware_path_optimizer/src/debug_marker.cpp b/planning/autoware_path_optimizer/src/debug_marker.cpp index eea6ada555044..397c334eca5b7 100644 --- a/planning/autoware_path_optimizer/src/debug_marker.cpp +++ b/planning/autoware_path_optimizer/src/debug_marker.cpp @@ -20,10 +20,10 @@ namespace autoware::path_optimizer { -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerScale; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerScale; namespace { @@ -53,16 +53,16 @@ MarkerArray getFootprintsMarkerArray( const double base_to_rear = vehicle_info.rear_overhang_m; marker.points.push_back( - autoware_universe_utils::calcOffsetPose(traj_point.pose, base_to_front, base_to_left, 0.0) + autoware::universe_utils::calcOffsetPose(traj_point.pose, base_to_front, base_to_left, 0.0) .position); marker.points.push_back( - autoware_universe_utils::calcOffsetPose(traj_point.pose, base_to_front, -base_to_right, 0.0) + autoware::universe_utils::calcOffsetPose(traj_point.pose, base_to_front, -base_to_right, 0.0) .position); marker.points.push_back( - autoware_universe_utils::calcOffsetPose(traj_point.pose, -base_to_rear, -base_to_right, 0.0) + autoware::universe_utils::calcOffsetPose(traj_point.pose, -base_to_rear, -base_to_right, 0.0) .position); marker.points.push_back( - autoware_universe_utils::calcOffsetPose(traj_point.pose, -base_to_rear, base_to_left, 0.0) + autoware::universe_utils::calcOffsetPose(traj_point.pose, -base_to_rear, base_to_left, 0.0) .position); marker.points.push_back(marker.points.front()); @@ -110,7 +110,7 @@ MarkerArray getBoundsWidthMarkerArray( (vehicle_info.wheel_tread_m / 2.0) + vehicle_info.right_overhang_m; const double lb_y = ref_points.at(i).bounds_on_constraints.at(bound_idx).lower_bound - base_to_right; - const auto lb = autoware_universe_utils::calcOffsetPose(pose, 0.0, lb_y, 0.0).position; + const auto lb = autoware::universe_utils::calcOffsetPose(pose, 0.0, lb_y, 0.0).position; lb_marker.points.push_back(pose.position); lb_marker.points.push_back(lb); @@ -132,7 +132,7 @@ MarkerArray getBoundsWidthMarkerArray( (vehicle_info.wheel_tread_m / 2.0) + vehicle_info.left_overhang_m; const double ub_y = ref_points.at(i).bounds_on_constraints.at(bound_idx).upper_bound + base_to_left; - const auto ub = autoware_universe_utils::calcOffsetPose(pose, 0.0, ub_y, 0.0).position; + const auto ub = autoware::universe_utils::calcOffsetPose(pose, 0.0, ub_y, 0.0).position; ub_marker.points.push_back(pose.position); ub_marker.points.push_back(ub); @@ -167,11 +167,11 @@ MarkerArray getBoundsLineMarkerArray( const double base_to_right = (vehicle_info.wheel_tread_m / 2.0) + vehicle_info.right_overhang_m; const double base_to_left = (vehicle_info.wheel_tread_m / 2.0) + vehicle_info.left_overhang_m; const double ub_y = ref_points.at(i).bounds.upper_bound + base_to_left; - const auto ub = autoware_universe_utils::calcOffsetPose(pose, 0.0, ub_y, 0.0).position; + const auto ub = autoware::universe_utils::calcOffsetPose(pose, 0.0, ub_y, 0.0).position; ub_marker.points.push_back(ub); const double lb_y = ref_points.at(i).bounds.lower_bound - base_to_right; - const auto lb = autoware_universe_utils::calcOffsetPose(pose, 0.0, lb_y, 0.0).position; + const auto lb = autoware::universe_utils::calcOffsetPose(pose, 0.0, lb_y, 0.0).position; lb_marker.points.push_back(lb); } marker_array.markers.push_back(ub_marker); @@ -205,22 +205,22 @@ MarkerArray getVehicleCircleLinesMarkerArray( // apply lateral and yaw deviation auto pose_with_deviation = - autoware_universe_utils::calcOffsetPose(ref_point.pose, 0.0, lat_dev, 0.0); + autoware::universe_utils::calcOffsetPose(ref_point.pose, 0.0, lat_dev, 0.0); pose_with_deviation.orientation = - autoware_universe_utils::createQuaternionFromYaw(ref_point.getYaw() + yaw_dev); + autoware::universe_utils::createQuaternionFromYaw(ref_point.getYaw() + yaw_dev); for (const double d : vehicle_circle_longitudinal_offsets) { // apply longitudinal offset - auto base_pose = autoware_universe_utils::calcOffsetPose(pose_with_deviation, d, 0.0, 0.0); + auto base_pose = autoware::universe_utils::calcOffsetPose(pose_with_deviation, d, 0.0, 0.0); base_pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(ref_point.getYaw() + ref_point.alpha); + autoware::universe_utils::createQuaternionFromYaw(ref_point.getYaw() + ref_point.alpha); const double base_to_right = (vehicle_info.wheel_tread_m / 2.0) + vehicle_info.right_overhang_m; const double base_to_left = (vehicle_info.wheel_tread_m / 2.0) + vehicle_info.left_overhang_m; const auto ub = - autoware_universe_utils::calcOffsetPose(base_pose, 0.0, base_to_left, 0.0).position; + autoware::universe_utils::calcOffsetPose(base_pose, 0.0, base_to_left, 0.0).position; const auto lb = - autoware_universe_utils::calcOffsetPose(base_pose, 0.0, -base_to_right, 0.0).position; + autoware::universe_utils::calcOffsetPose(base_pose, 0.0, -base_to_right, 0.0).position; marker.points.push_back(ub); marker.points.push_back(lb); @@ -247,7 +247,7 @@ MarkerArray getCurrentVehicleCirclesMarkerArray( "map", rclcpp::Clock().now(), ns, id, Marker::LINE_STRIP, createMarkerScale(0.05, 0.0, 0.0), createMarkerColor(r, g, b, 0.8)); marker.lifetime = rclcpp::Duration::from_seconds(1.5); - marker.pose = autoware_universe_utils::calcOffsetPose(ego_pose, offset, 0.0, 0.0); + marker.pose = autoware::universe_utils::calcOffsetPose(ego_pose, offset, 0.0, 0.0); constexpr size_t circle_dividing_num = 16; for (size_t e_idx = 0; e_idx < circle_dividing_num + 1; ++e_idx) { @@ -289,7 +289,7 @@ MarkerArray getVehicleCirclesMarkerArray( "map", rclcpp::Clock().now(), ns, id, Marker::LINE_STRIP, createMarkerScale(0.05, 0.0, 0.0), createMarkerColor(r, g, b, 0.8)); marker.lifetime = rclcpp::Duration::from_seconds(1.5); - marker.pose = autoware_universe_utils::calcOffsetPose(mpt_traj_point.pose, offset, 0.0, 0.0); + marker.pose = autoware::universe_utils::calcOffsetPose(mpt_traj_point.pose, offset, 0.0, 0.0); constexpr size_t circle_dividing_num = 16; for (size_t e_idx = 0; e_idx < circle_dividing_num + 1; ++e_idx) { @@ -356,15 +356,15 @@ visualization_msgs::msg::MarkerArray getFootprintByDrivableAreaMarkerArray( const double base_to_rear = vehicle_info.rear_overhang_m; marker.points.push_back( - autoware_universe_utils::calcOffsetPose(stop_pose, base_to_front, base_to_left, 0.0).position); + autoware::universe_utils::calcOffsetPose(stop_pose, base_to_front, base_to_left, 0.0).position); marker.points.push_back( - autoware_universe_utils::calcOffsetPose(stop_pose, base_to_front, -base_to_right, 0.0) + autoware::universe_utils::calcOffsetPose(stop_pose, base_to_front, -base_to_right, 0.0) .position); marker.points.push_back( - autoware_universe_utils::calcOffsetPose(stop_pose, -base_to_rear, -base_to_right, 0.0) + autoware::universe_utils::calcOffsetPose(stop_pose, -base_to_rear, -base_to_right, 0.0) .position); marker.points.push_back( - autoware_universe_utils::calcOffsetPose(stop_pose, -base_to_rear, base_to_left, 0.0).position); + autoware::universe_utils::calcOffsetPose(stop_pose, -base_to_rear, base_to_left, 0.0).position); marker.points.push_back(marker.points.front()); msg.markers.push_back(marker); diff --git a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp index 7ecb7543d0463..a5da50862c9fb 100644 --- a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp +++ b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp @@ -125,8 +125,8 @@ std::vector toStdVector(const Eigen::VectorXd & eigen_vec) bool isLeft(const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Point & target_pos) { const double base_theta = tf2::getYaw(pose.orientation); - const double target_theta = autoware_universe_utils::calcAzimuthAngle(pose.position, target_pos); - const double diff_theta = autoware_universe_utils::normalizeRadian(target_theta - base_theta); + const double target_theta = autoware::universe_utils::calcAzimuthAngle(pose.position, target_pos); + const double diff_theta = autoware::universe_utils::normalizeRadian(target_theta - base_theta); return diff_theta > 0; } @@ -141,18 +141,18 @@ double calcLateralDistToBounds( const double max_lat_offset = is_left_bound ? max_lat_offset_for_left : -max_lat_offset_for_left; const double min_lat_offset = is_left_bound ? min_lat_offset_for_left : -min_lat_offset_for_left; const auto max_lat_offset_point = - autoware_universe_utils::calcOffsetPose(pose, 0.0, max_lat_offset, 0.0).position; + autoware::universe_utils::calcOffsetPose(pose, 0.0, max_lat_offset, 0.0).position; const auto min_lat_offset_point = - autoware_universe_utils::calcOffsetPose(pose, 0.0, min_lat_offset, 0.0).position; + autoware::universe_utils::calcOffsetPose(pose, 0.0, min_lat_offset, 0.0).position; double closest_dist_to_bound = max_lat_offset; for (size_t i = 0; i < bound.size() - 1; ++i) { - const auto intersect_point = autoware_universe_utils::intersect( + const auto intersect_point = autoware::universe_utils::intersect( min_lat_offset_point, max_lat_offset_point, bound.at(i), bound.at(i + 1)); if (intersect_point) { const bool is_point_left = isLeft(pose, *intersect_point); const double dist_to_bound = - autoware_universe_utils::calcDistance2d(pose.position, *intersect_point) * + autoware::universe_utils::calcDistance2d(pose.position, *intersect_point) * (is_point_left ? 1.0 : -1.0); // the bound which is closest to the centerline will be chosen @@ -283,7 +283,7 @@ MPTOptimizer::MPTParam::MPTParam( void MPTOptimizer::MPTParam::onParam(const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; { // option updateParam(parameters, "mpt.option.steer_limit_constraint", steer_limit_constraint); @@ -564,7 +564,7 @@ std::vector MPTOptimizer::calcReferencePoints( constexpr double tmp_margin = 10.0; size_t ego_seg_idx = trajectory_utils::findEgoSegmentIndex(ref_points, p.ego_pose, ego_nearest_param_); - ref_points = autoware_motion_utils::cropPoints( + ref_points = autoware::motion_utils::cropPoints( ref_points, p.ego_pose.position, ego_seg_idx, forward_traj_length + tmp_margin, backward_traj_length + tmp_margin); @@ -579,7 +579,7 @@ std::vector MPTOptimizer::calcReferencePoints( // 4. crop backward // NOTE: Start point may change. Spline calculation is required. - ref_points = autoware_motion_utils::cropPoints( + ref_points = autoware::motion_utils::cropPoints( ref_points, p.ego_pose.position, ego_seg_idx, forward_traj_length + tmp_margin, backward_traj_length); ref_points_spline = SplineInterpolationPoints2d(ref_points); @@ -605,7 +605,7 @@ std::vector MPTOptimizer::calcReferencePoints( updateExtraPoints(ref_points); // 9. crop forward - // ref_points = autoware_motion_utils::cropForwardPoints( + // ref_points = autoware::motion_utils::cropForwardPoints( // ref_points, p.ego_pose.position, ego_seg_idx, forward_traj_length); if (static_cast(mpt_param_.num_points) < ref_points.size()) { ref_points.resize(mpt_param_.num_points); @@ -623,7 +623,7 @@ void MPTOptimizer::updateOrientation( const auto yaw_vec = ref_points_spline.getSplineInterpolatedYaws(); for (size_t i = 0; i < ref_points.size(); ++i) { ref_points.at(i).pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(yaw_vec.at(i)); + autoware::universe_utils::createQuaternionFromYaw(yaw_vec.at(i)); } } @@ -691,7 +691,7 @@ void MPTOptimizer::updateDeltaArcLength(std::vector & ref_points ref_points.at(i).delta_arc_length = (i == ref_points.size() - 1) ? 0.0 - : autoware_universe_utils::calcDistance2d(ref_points.at(i + 1), ref_points.at(i)); + : autoware::universe_utils::calcDistance2d(ref_points.at(i + 1), ref_points.at(i)); } } @@ -704,14 +704,14 @@ void MPTOptimizer::updateExtraPoints(std::vector & ref_points) c const auto front_wheel_pos = trajectory_utils::getNearestPosition(ref_points, i, vehicle_info_.wheel_base_m); - const bool are_too_close_points = autoware_universe_utils::calcDistance2d( + const bool are_too_close_points = autoware::universe_utils::calcDistance2d( front_wheel_pos, ref_points.at(i).pose.position) < 1e-03; const auto front_wheel_yaw = are_too_close_points ? ref_points.at(i).getYaw() - : autoware_universe_utils::calcAzimuthAngle( + : autoware::universe_utils::calcAzimuthAngle( ref_points.at(i).pose.position, front_wheel_pos); ref_points.at(i).alpha = - autoware_universe_utils::normalizeRadian(front_wheel_yaw - ref_points.at(i).getYaw()); + autoware::universe_utils::normalizeRadian(front_wheel_yaw - ref_points.at(i).getYaw()); } { // avoidance @@ -771,10 +771,10 @@ void MPTOptimizer::updateExtraPoints(std::vector & ref_points) c if (prev_ref_points_ptr_ && !prev_ref_points_ptr_->empty()) { for (int i = 0; i < static_cast(ref_points.size()); ++i) { const size_t prev_idx = trajectory_utils::findEgoIndex( - *prev_ref_points_ptr_, autoware_universe_utils::getPose(ref_points.at(i)), + *prev_ref_points_ptr_, autoware::universe_utils::getPose(ref_points.at(i)), ego_nearest_param_); - const double dist_to_prev = autoware_universe_utils::calcDistance2d( + const double dist_to_prev = autoware::universe_utils::calcDistance2d( ref_points.at(i), prev_ref_points_ptr_->at(prev_idx)); if (max_dist_threshold < dist_to_prev) { continue; @@ -1081,7 +1081,7 @@ void MPTOptimizer::avoidSuddenSteering( return; } const size_t prev_ego_idx = trajectory_utils::findEgoIndex( - *prev_ref_points_ptr_, autoware_universe_utils::getPose(ref_points.front()), + *prev_ref_points_ptr_, autoware::universe_utils::getPose(ref_points.front()), ego_nearest_param_); const double max_bound_fixing_length = ego_vel * mpt_param_.max_bound_fixing_time; @@ -1129,11 +1129,11 @@ void MPTOptimizer::updateVehicleBounds( collision_check_pose.position.y - ref_point.pose.position.y, collision_check_pose.position.x - ref_point.pose.position.x); const double offset_y = - -autoware_universe_utils::calcDistance2d(ref_point, collision_check_pose) * + -autoware::universe_utils::calcDistance2d(ref_point, collision_check_pose) * std::sin(tmp_yaw - collision_check_yaw); const auto vehicle_bounds_pose = - autoware_universe_utils::calcOffsetPose(collision_check_pose, 0.0, offset_y, 0.0); + autoware::universe_utils::calcOffsetPose(collision_check_pose, 0.0, offset_y, 0.0); // interpolate bounds const auto bounds = [&]() { @@ -1587,7 +1587,7 @@ Eigen::VectorXd MPTOptimizer::calcInitialSolutionForManualWarmStart( Eigen::VectorXd u0 = Eigen::VectorXd::Zero(D_un); - const size_t nearest_idx = autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + const size_t nearest_idx = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( prev_ref_points, ref_points.front().pose, ego_nearest_param_.dist_threshold, ego_nearest_param_.yaw_threshold); @@ -1713,17 +1713,17 @@ void MPTOptimizer::publishDebugTrajectories( time_keeper_ptr_->tic(__func__); // reference points - const auto ref_traj = autoware_motion_utils::convertToTrajectory( + const auto ref_traj = autoware::motion_utils::convertToTrajectory( trajectory_utils::convertToTrajectoryPoints(ref_points), header); debug_ref_traj_pub_->publish(ref_traj); // fixed reference points const auto fixed_traj_points = extractFixedPoints(ref_points); - const auto fixed_traj = autoware_motion_utils::convertToTrajectory(fixed_traj_points, header); + const auto fixed_traj = autoware::motion_utils::convertToTrajectory(fixed_traj_points, header); debug_fixed_traj_pub_->publish(fixed_traj); // mpt points - const auto mpt_traj = autoware_motion_utils::convertToTrajectory(mpt_traj_points, header); + const auto mpt_traj = autoware::motion_utils::convertToTrajectory(mpt_traj_points, header); debug_mpt_traj_pub_->publish(mpt_traj); time_keeper_ptr_->toc(__func__, " "); diff --git a/planning/autoware_path_optimizer/src/node.cpp b/planning/autoware_path_optimizer/src/node.cpp index 46fb7d0d5bb95..3899867a9dcce 100644 --- a/planning/autoware_path_optimizer/src/node.cpp +++ b/planning/autoware_path_optimizer/src/node.cpp @@ -56,7 +56,7 @@ Float64Stamped createFloat64Stamped(const rclcpp::Time & now, const float & data void setZeroVelocityAfterStopPoint(std::vector & traj_points) { - const auto opt_zero_vel_idx = autoware_motion_utils::searchZeroVelocityIndex(traj_points); + const auto opt_zero_vel_idx = autoware::motion_utils::searchZeroVelocityIndex(traj_points); if (opt_zero_vel_idx) { for (size_t i = opt_zero_vel_idx.value(); i < traj_points.size(); ++i) { traj_points.at(i).longitudinal_velocity_mps = 0.0; @@ -75,7 +75,7 @@ std::vector calcSegmentLengthVector(const std::vector & std::vector segment_length_vector; for (size_t i = 0; i < points.size() - 1; ++i) { const double segment_length = - autoware_universe_utils::calcDistance2d(points.at(i), points.at(i + 1)); + autoware::universe_utils::calcDistance2d(points.at(i), points.at(i + 1)); segment_length_vector.push_back(segment_length); } return segment_length_vector; @@ -150,15 +150,15 @@ PathOptimizer::PathOptimizer(const rclcpp::NodeOptions & node_options) set_param_res_ = this->add_on_set_parameters_callback( std::bind(&PathOptimizer::onParam, this, std::placeholders::_1)); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } rcl_interfaces::msg::SetParametersResult PathOptimizer::onParam( const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; // parameters for option updateParam( @@ -246,7 +246,7 @@ void PathOptimizer::onPath(const Path::ConstSharedPtr path_ptr) const auto traj_points = trajectory_utils::convertToTrajectoryPoints(path_ptr->points); const auto output_traj_msg = - autoware_motion_utils::convertToTrajectory(traj_points, path_ptr->header); + autoware::motion_utils::convertToTrajectory(traj_points, path_ptr->header); traj_pub_->publish(output_traj_msg); published_time_publisher_->publish_if_subscribed(traj_pub_, output_traj_msg.header.stamp); return; @@ -279,7 +279,7 @@ void PathOptimizer::onPath(const Path::ConstSharedPtr path_ptr) createFloat64Stamped(now(), time_keeper_ptr_->getAccumulatedTime())); const auto output_traj_msg = - autoware_motion_utils::convertToTrajectory(full_traj_points, path_ptr->header); + autoware::motion_utils::convertToTrajectory(full_traj_points, path_ptr->header); traj_pub_->publish(output_traj_msg); published_time_publisher_->publish_if_subscribed(traj_pub_, output_traj_msg.header.stamp); } @@ -400,7 +400,7 @@ void PathOptimizer::applyInputVelocity( const size_t ego_seg_idx = trajectory_utils::findEgoSegmentIndex(input_traj_points, ego_pose, ego_nearest_param_); - const auto cropped_points = autoware_motion_utils::cropForwardPoints( + const auto cropped_points = autoware::motion_utils::cropForwardPoints( input_traj_points, ego_pose.position, ego_seg_idx, optimized_traj_length + margin_traj_length); @@ -453,14 +453,14 @@ void PathOptimizer::applyInputVelocity( // insert stop point explicitly const auto stop_idx = - autoware_motion_utils::searchZeroVelocityIndex(forward_cropped_input_traj_points); + autoware::motion_utils::searchZeroVelocityIndex(forward_cropped_input_traj_points); if (stop_idx) { const auto & input_stop_pose = forward_cropped_input_traj_points.at(stop_idx.value()).pose; - // NOTE: autoware_motion_utils::findNearestSegmentIndex is used instead of + // NOTE: autoware::motion_utils::findNearestSegmentIndex is used instead of // trajectory_utils::findEgoSegmentIndex // for the case where input_traj_points is much longer than output_traj_points, and the // former has a stop point but the latter will not have. - const auto stop_seg_idx = autoware_motion_utils::findNearestSegmentIndex( + const auto stop_seg_idx = autoware::motion_utils::findNearestSegmentIndex( output_traj_points, input_stop_pose, ego_nearest_param_.dist_threshold, ego_nearest_param_.yaw_threshold); @@ -471,9 +471,9 @@ void PathOptimizer::applyInputVelocity( } if (*stop_seg_idx == output_traj_points.size() - 2) { const double signed_projected_length_to_segment = - autoware_motion_utils::calcLongitudinalOffsetToSegment( + autoware::motion_utils::calcLongitudinalOffsetToSegment( output_traj_points, *stop_seg_idx, input_stop_pose.position); - const double segment_length = autoware_motion_utils::calcSignedArcLength( + const double segment_length = autoware::motion_utils::calcSignedArcLength( output_traj_points, *stop_seg_idx, *stop_seg_idx + 1); if (segment_length < signed_projected_length_to_segment) { // NOTE: input_stop_pose is outside output_traj_points. @@ -533,10 +533,10 @@ void PathOptimizer::insertZeroVelocityOutsideDrivableArea( debug_data_ptr_->stop_pose_by_drivable_area = optimized_traj_points.at(*first_outside_idx).pose; const auto stop_idx = [&]() { const auto dist = - autoware_motion_utils::calcSignedArcLength(optimized_traj_points, 0, *first_outside_idx); + autoware::motion_utils::calcSignedArcLength(optimized_traj_points, 0, *first_outside_idx); const auto dist_with_margin = dist - vehicle_stop_margin_outside_drivable_area_; const auto first_outside_idx_with_margin = - autoware_motion_utils::insertTargetPoint(0, dist_with_margin, optimized_traj_points); + autoware::motion_utils::insertTargetPoint(0, dist_with_margin, optimized_traj_points); if (first_outside_idx_with_margin) { return *first_outside_idx_with_margin; } @@ -561,11 +561,11 @@ void PathOptimizer::publishVirtualWall(const geometry_msgs::msg::Pose & stop_pos { time_keeper_ptr_->tic(__func__); - auto virtual_wall_marker = autoware_motion_utils::createStopVirtualWallMarker( + auto virtual_wall_marker = autoware::motion_utils::createStopVirtualWallMarker( stop_pose, "outside drivable area", now(), 0, vehicle_info_.max_longitudinal_offset_m); if (!enable_outside_drivable_area_stop_) { virtual_wall_marker.markers.front().color = - autoware_universe_utils::createMarkerColor(0.0, 1.0, 0.0, 0.5); + autoware::universe_utils::createMarkerColor(0.0, 1.0, 0.0, 0.5); } virtual_wall_pub_->publish(virtual_wall_marker); @@ -664,7 +664,7 @@ void PathOptimizer::publishDebugData(const Header & header) const // publish trajectories const auto debug_extended_traj = - autoware_motion_utils::convertToTrajectory(debug_data_ptr_->extended_traj_points, header); + autoware::motion_utils::convertToTrajectory(debug_data_ptr_->extended_traj_points, header); debug_extended_traj_pub_->publish(debug_extended_traj); time_keeper_ptr_->toc(__func__, " "); diff --git a/planning/autoware_path_optimizer/src/replan_checker.cpp b/planning/autoware_path_optimizer/src/replan_checker.cpp index 9228631b80afa..11e31bfd2d459 100644 --- a/planning/autoware_path_optimizer/src/replan_checker.cpp +++ b/planning/autoware_path_optimizer/src/replan_checker.cpp @@ -39,7 +39,7 @@ ReplanChecker::ReplanChecker(rclcpp::Node * node, const EgoNearestParam & ego_ne void ReplanChecker::onParam(const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; updateParam( parameters, "replan.max_path_shape_around_ego_lat_dist", max_path_shape_around_ego_lat_dist_); @@ -78,7 +78,7 @@ bool ReplanChecker::isResetRequired(const PlannerData & planner_data) const // ego pose is lost or new ego pose is designated in simulation const double delta_dist = - autoware_universe_utils::calcDistance2d(p.ego_pose, prev_ego_pose_ptr_->position); + autoware::universe_utils::calcDistance2d(p.ego_pose, prev_ego_pose_ptr_->position); if (max_ego_moving_dist_ < delta_dist) { RCLCPP_DEBUG( logger_, @@ -144,14 +144,14 @@ bool ReplanChecker::isPathAroundEgoChanged( // calculate ego's lateral offset to previous trajectory points const auto prev_ego_seg_idx = trajectory_utils::findEgoSegmentIndex(prev_traj_points, p.ego_pose, ego_nearest_param_); - const double prev_ego_lat_offset = autoware_motion_utils::calcLateralOffset( + const double prev_ego_lat_offset = autoware::motion_utils::calcLateralOffset( prev_traj_points, p.ego_pose.position, prev_ego_seg_idx); // calculate ego's lateral offset to current trajectory points const auto ego_seg_idx = trajectory_utils::findEgoSegmentIndex(p.traj_points, p.ego_pose, ego_nearest_param_); const double ego_lat_offset = - autoware_motion_utils::calcLateralOffset(p.traj_points, p.ego_pose.position, ego_seg_idx); + autoware::motion_utils::calcLateralOffset(p.traj_points, p.ego_pose.position, ego_seg_idx); const double diff_ego_lat_offset = prev_ego_lat_offset - ego_lat_offset; if (std::abs(diff_ego_lat_offset) < max_path_shape_around_ego_lat_dist_) { @@ -174,7 +174,7 @@ bool ReplanChecker::isPathForwardChanged( constexpr double lon_dist_interval = 10.0; for (double lon_dist = lon_dist_interval; lon_dist <= max_path_shape_forward_lon_dist_; lon_dist += lon_dist_interval) { - const auto prev_forward_point = autoware_motion_utils::calcLongitudinalOffsetPoint( + const auto prev_forward_point = autoware::motion_utils::calcLongitudinalOffsetPoint( prev_traj_points, prev_ego_seg_idx, lon_dist); if (!prev_forward_point) { continue; @@ -182,9 +182,9 @@ bool ReplanChecker::isPathForwardChanged( // calculate lateral offset of current trajectory points to prev forward point const auto forward_seg_idx = - autoware_motion_utils::findNearestSegmentIndex(p.traj_points, *prev_forward_point); - const double forward_lat_offset = - autoware_motion_utils::calcLateralOffset(p.traj_points, *prev_forward_point, forward_seg_idx); + autoware::motion_utils::findNearestSegmentIndex(p.traj_points, *prev_forward_point); + const double forward_lat_offset = autoware::motion_utils::calcLateralOffset( + p.traj_points, *prev_forward_point, forward_seg_idx); if (max_path_shape_forward_lat_dist_ < std::abs(forward_lat_offset)) { return true; } @@ -205,7 +205,7 @@ bool ReplanChecker::isPathGoalChanged( } const double goal_moving_dist = - autoware_universe_utils::calcDistance2d(p.traj_points.back(), prev_traj_points.back()); + autoware::universe_utils::calcDistance2d(p.traj_points.back(), prev_traj_points.back()); if (goal_moving_dist < max_goal_moving_dist_) { return false; } diff --git a/planning/autoware_path_optimizer/src/utils/geometry_utils.cpp b/planning/autoware_path_optimizer/src/utils/geometry_utils.cpp index a94f8b4bbabe7..bed9bbfa500c6 100644 --- a/planning/autoware_path_optimizer/src/utils/geometry_utils.cpp +++ b/planning/autoware_path_optimizer/src/utils/geometry_utils.cpp @@ -39,17 +39,17 @@ namespace autoware::path_optimizer { namespace bg = boost::geometry; -using autoware_universe_utils::LinearRing2d; -using autoware_universe_utils::LineString2d; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; +using autoware::universe_utils::LinearRing2d; +using autoware::universe_utils::LineString2d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; namespace { geometry_msgs::msg::Point getStartPoint( const std::vector & bound, const geometry_msgs::msg::Point & point) { - const size_t segment_idx = autoware_motion_utils::findNearestSegmentIndex(bound, point); + const size_t segment_idx = autoware::motion_utils::findNearestSegmentIndex(bound, point); const auto & curr_seg_point = bound.at(segment_idx); const auto & next_seg_point = bound.at(segment_idx); const Eigen::Vector2d first_to_target{point.x - curr_seg_point.x, point.y - curr_seg_point.y}; @@ -62,7 +62,7 @@ geometry_msgs::msg::Point getStartPoint( } const auto first_point = - autoware_motion_utils::calcLongitudinalOffsetPoint(bound, segment_idx, length); + autoware::motion_utils::calcLongitudinalOffsetPoint(bound, segment_idx, length); if (first_point) { return *first_point; } @@ -86,7 +86,7 @@ bool isFrontDrivableArea( // ignore point behind of the front line const std::vector front_bound = {left_start_point, right_start_point}; const double lat_dist_to_front_bound = - autoware_motion_utils::calcLateralOffset(front_bound, point); + autoware::motion_utils::calcLateralOffset(front_bound, point); if (lat_dist_to_front_bound < min_dist) { return true; } @@ -136,13 +136,13 @@ bool isOutsideDrivableAreaFromRectangleFootprint( // calculate footprint corner points const auto top_left_pos = - autoware_universe_utils::calcOffsetPose(pose, base_to_front, base_to_left, 0.0).position; + autoware::universe_utils::calcOffsetPose(pose, base_to_front, base_to_left, 0.0).position; const auto top_right_pos = - autoware_universe_utils::calcOffsetPose(pose, base_to_front, -base_to_right, 0.0).position; + autoware::universe_utils::calcOffsetPose(pose, base_to_front, -base_to_right, 0.0).position; const auto bottom_right_pos = - autoware_universe_utils::calcOffsetPose(pose, -base_to_rear, -base_to_right, 0.0).position; + autoware::universe_utils::calcOffsetPose(pose, -base_to_rear, -base_to_right, 0.0).position; const auto bottom_left_pos = - autoware_universe_utils::calcOffsetPose(pose, -base_to_rear, base_to_left, 0.0).position; + autoware::universe_utils::calcOffsetPose(pose, -base_to_rear, base_to_left, 0.0).position; if (use_footprint_polygon_for_outside_drivable_area_check) { // calculate footprint polygon diff --git a/planning/autoware_path_optimizer/src/utils/trajectory_utils.cpp b/planning/autoware_path_optimizer/src/utils/trajectory_utils.cpp index a1b429ae2357e..433d1d0995088 100644 --- a/planning/autoware_path_optimizer/src/utils/trajectory_utils.cpp +++ b/planning/autoware_path_optimizer/src/utils/trajectory_utils.cpp @@ -33,7 +33,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { template <> geometry_msgs::msg::Point getPoint(const autoware::path_optimizer::ReferencePoint & p) @@ -52,7 +52,7 @@ double getLongitudinalVelocity(const autoware::path_optimizer::ReferencePoint & { return p.longitudinal_velocity_mps; } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils namespace autoware::path_optimizer { @@ -108,12 +108,12 @@ void compensateLastPose( const geometry_msgs::msg::Pose last_traj_pose = traj_points.back().pose; - const double dist = - autoware_universe_utils::calcDistance2d(last_path_point.pose.position, last_traj_pose.position); + const double dist = autoware::universe_utils::calcDistance2d( + last_path_point.pose.position, last_traj_pose.position); const double norm_diff_yaw = [&]() { const double diff_yaw = tf2::getYaw(last_path_point.pose.orientation) - tf2::getYaw(last_traj_pose.orientation); - return autoware_universe_utils::normalizeRadian(diff_yaw); + return autoware::universe_utils::normalizeRadian(diff_yaw); }(); if (dist > delta_dist_threshold || std::fabs(norm_diff_yaw) > delta_yaw_threshold) { traj_points.push_back(convertToTrajectoryPoint(last_path_point)); @@ -140,10 +140,10 @@ std::vector resampleTrajectoryPoints( { constexpr bool enable_resampling_stop_point = true; - const auto traj = autoware_motion_utils::convertToTrajectory(traj_points); - const auto resampled_traj = autoware_motion_utils::resampleTrajectory( + const auto traj = autoware::motion_utils::convertToTrajectory(traj_points); + const auto resampled_traj = autoware::motion_utils::resampleTrajectory( traj, interval, false, true, true, enable_resampling_stop_point); - return autoware_motion_utils::convertToTrajectoryPointArray(resampled_traj); + return autoware::motion_utils::convertToTrajectoryPointArray(resampled_traj); } // NOTE: stop point will not be resampled @@ -152,10 +152,10 @@ std::vector resampleTrajectoryPointsWithoutStopPoint( { constexpr bool enable_resampling_stop_point = false; - const auto traj = autoware_motion_utils::convertToTrajectory(traj_points); - const auto resampled_traj = autoware_motion_utils::resampleTrajectory( + const auto traj = autoware::motion_utils::convertToTrajectory(traj_points); + const auto resampled_traj = autoware::motion_utils::resampleTrajectory( traj, interval, false, true, true, enable_resampling_stop_point); - return autoware_motion_utils::convertToTrajectoryPointArray(resampled_traj); + return autoware::motion_utils::convertToTrajectoryPointArray(resampled_traj); } std::vector resampleReferencePoints( @@ -175,7 +175,7 @@ std::vector resampleReferencePoints( base_keys.push_back(0.0); } else { const double delta_arc_length = - autoware_universe_utils::calcDistance2d(ref_points.at(i), ref_points.at(i - 1)); + autoware::universe_utils::calcDistance2d(ref_points.at(i), ref_points.at(i - 1)); base_keys.push_back(base_keys.back() + delta_arc_length); } @@ -187,7 +187,7 @@ std::vector resampleReferencePoints( if (i == 0) { query_keys.push_back(0.0); } else { - const double delta_arc_length = autoware_universe_utils::calcDistance2d( + const double delta_arc_length = autoware::universe_utils::calcDistance2d( resampled_ref_points.at(i), resampled_ref_points.at(i - 1)); const double key = query_keys.back() + delta_arc_length; if (base_keys.back() < key) { @@ -220,7 +220,7 @@ void insertStopPoint( std::vector & traj_points, const geometry_msgs::msg::Pose & input_stop_pose, const size_t stop_seg_idx) { - const double offset_to_segment = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const double offset_to_segment = autoware::motion_utils::calcLongitudinalOffsetToSegment( traj_points, stop_seg_idx, input_stop_pose.position); const auto traj_spline = SplineInterpolationPoints2d(traj_points); diff --git a/planning/autoware_path_smoother/include/autoware/path_smoother/common_structs.hpp b/planning/autoware_path_smoother/include/autoware/path_smoother/common_structs.hpp index e26d13b94ecb0..0b7e28ee1cbb5 100644 --- a/planning/autoware_path_smoother/include/autoware/path_smoother/common_structs.hpp +++ b/planning/autoware_path_smoother/include/autoware/path_smoother/common_structs.hpp @@ -83,7 +83,7 @@ struct TimeKeeper double accumulated_time{0.0}; - autoware_universe_utils::StopWatch< + autoware::universe_utils::StopWatch< std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> stop_watch_; }; @@ -100,7 +100,7 @@ struct CommonParam void onParam(const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; // common updateParam( @@ -123,7 +123,7 @@ struct EgoNearestParam void onParam(const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; updateParam(parameters, "ego_nearest_dist_threshold", dist_threshold); updateParam(parameters, "ego_nearest_yaw_threshold", yaw_threshold); } diff --git a/planning/autoware_path_smoother/include/autoware/path_smoother/elastic_band_smoother.hpp b/planning/autoware_path_smoother/include/autoware/path_smoother/elastic_band_smoother.hpp index 6a2c3ef45f66b..2de74a4f14f4f 100644 --- a/planning/autoware_path_smoother/include/autoware/path_smoother/elastic_band_smoother.hpp +++ b/planning/autoware_path_smoother/include/autoware/path_smoother/elastic_band_smoother.hpp @@ -49,7 +49,7 @@ class ElasticBandSmoother : public rclcpp::Node public: bool isDrivingForward(const std::vector & path_points) { - const auto is_driving_forward = autoware_motion_utils::isDrivingForward(path_points); + const auto is_driving_forward = autoware::motion_utils::isDrivingForward(path_points); is_driving_forward_ = is_driving_forward ? is_driving_forward.value() : is_driving_forward_; return is_driving_forward_; } @@ -82,7 +82,7 @@ class ElasticBandSmoother : public rclcpp::Node // interface subscriber rclcpp::Subscription::SharedPtr path_sub_; - autoware_universe_utils::InterProcessPollingSubscriber odom_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber odom_sub_{ this, "~/input/odometry"}; // debug publisher @@ -113,9 +113,9 @@ class ElasticBandSmoother : public rclcpp::Node const std::vector & traj_points, const std::vector & optimized_points) const; - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; }; } // namespace autoware::path_smoother diff --git a/planning/autoware_path_smoother/include/autoware/path_smoother/utils/geometry_utils.hpp b/planning/autoware_path_smoother/include/autoware/path_smoother/utils/geometry_utils.hpp index df9dbdf7f7e49..603ae8a91f944 100644 --- a/planning/autoware_path_smoother/include/autoware/path_smoother/utils/geometry_utils.hpp +++ b/planning/autoware_path_smoother/include/autoware/path_smoother/utils/geometry_utils.hpp @@ -24,8 +24,8 @@ namespace geometry_utils template bool isSamePoint(const T1 & t1, const T2 & t2) { - const auto p1 = autoware_universe_utils::getPoint(t1); - const auto p2 = autoware_universe_utils::getPoint(t2); + const auto p1 = autoware::universe_utils::getPoint(t1); + const auto p2 = autoware::universe_utils::getPoint(t2); constexpr double epsilon = 1e-6; return (std::abs(p1.x - p2.x) <= epsilon && std::abs(p1.y - p2.y) <= epsilon); diff --git a/planning/autoware_path_smoother/include/autoware/path_smoother/utils/trajectory_utils.hpp b/planning/autoware_path_smoother/include/autoware/path_smoother/utils/trajectory_utils.hpp index 715a3c35609a1..77a9dbae81a0c 100644 --- a/planning/autoware_path_smoother/include/autoware/path_smoother/utils/trajectory_utils.hpp +++ b/planning/autoware_path_smoother/include/autoware/path_smoother/utils/trajectory_utils.hpp @@ -49,14 +49,14 @@ std::optional getPointIndexAfter( } double sum_length = - -autoware_motion_utils::calcLongitudinalOffsetToSegment(points, target_seg_idx, target_pos); + -autoware::motion_utils::calcLongitudinalOffsetToSegment(points, target_seg_idx, target_pos); std::optional output_idx{std::nullopt}; // search forward if (sum_length < min_offset) { for (size_t i = target_seg_idx + 1; i < points.size(); ++i) { - sum_length += autoware_universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); + sum_length += autoware::universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); if (min_offset < sum_length) { output_idx = i - 1; } @@ -70,7 +70,7 @@ std::optional getPointIndexAfter( // search backward for (size_t i = target_seg_idx; 0 < i; --i) { // NOTE: use size_t since i is always positive value - sum_length -= autoware_universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); + sum_length -= autoware::universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); if (sum_length < min_offset) { output_idx = i - 1; } @@ -86,7 +86,7 @@ template TrajectoryPoint convertToTrajectoryPoint(const T & point) { TrajectoryPoint traj_point; - traj_point.pose = autoware_universe_utils::getPose(point); + traj_point.pose = autoware::universe_utils::getPose(point); traj_point.longitudinal_velocity_mps = point.longitudinal_velocity_mps; traj_point.lateral_velocity_mps = point.lateral_velocity_mps; traj_point.heading_rate_rps = point.heading_rate_rps; @@ -109,7 +109,7 @@ size_t findEgoSegmentIndex( const std::vector & points, const geometry_msgs::msg::Pose & ego_pose, const EgoNearestParam & ego_nearest_param) { - return autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( points, ego_pose, ego_nearest_param.dist_threshold, ego_nearest_param.yaw_threshold); } @@ -128,13 +128,13 @@ std::optional updateFrontPointForFix( { // calculate front point to insert in points as a fixed point const size_t front_seg_idx_for_fix = trajectory_utils::findEgoSegmentIndex( - points_for_fix, autoware_universe_utils::getPose(points.front()), ego_nearest_param); + points_for_fix, autoware::universe_utils::getPose(points.front()), ego_nearest_param); const size_t front_point_idx_for_fix = front_seg_idx_for_fix; const auto & front_fix_point = points_for_fix.at(front_point_idx_for_fix); // check if the points_for_fix is longer in front than points const double lon_offset_to_prev_front = - autoware_motion_utils::calcSignedArcLength(points, 0, front_fix_point.pose.position); + autoware::motion_utils::calcSignedArcLength(points, 0, front_fix_point.pose.position); if (0 < lon_offset_to_prev_front) { RCLCPP_DEBUG( rclcpp::get_logger("autoware_path_smoother.trajectory_utils"), @@ -142,7 +142,7 @@ std::optional updateFrontPointForFix( return std::nullopt; } - const double dist = autoware_universe_utils::calcDistance2d(points.front(), front_fix_point); + const double dist = autoware::universe_utils::calcDistance2d(points.front(), front_fix_point); // check if deviation is not too large constexpr double max_lat_error = 3.0; diff --git a/planning/autoware_path_smoother/src/elastic_band.cpp b/planning/autoware_path_smoother/src/elastic_band.cpp index b0c5974eca036..4222e0fe98438 100644 --- a/planning/autoware_path_smoother/src/elastic_band.cpp +++ b/planning/autoware_path_smoother/src/elastic_band.cpp @@ -125,7 +125,7 @@ EBPathSmoother::EBParam::EBParam(rclcpp::Node * node) void EBPathSmoother::EBParam::onParam(const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; { // option updateParam(parameters, "elastic_band.option.enable_warm_start", enable_warm_start); @@ -212,7 +212,7 @@ std::vector EBPathSmoother::smoothTrajectory( const size_t ego_seg_idx = trajectory_utils::findEgoSegmentIndex(traj_points, ego_pose, ego_nearest_param_); - const auto cropped_traj_points = autoware_motion_utils::cropPoints( + const auto cropped_traj_points = autoware::motion_utils::cropPoints( traj_points, ego_pose.position, ego_seg_idx, forward_traj_length, backward_traj_length); // check if goal is contained in cropped_traj_points @@ -263,7 +263,7 @@ std::vector EBPathSmoother::smoothTrajectory( // 8. publish eb trajectory const auto eb_traj = - autoware_motion_utils::convertToTrajectory(*eb_traj_points, createHeader(clock_.now())); + autoware::motion_utils::convertToTrajectory(*eb_traj_points, createHeader(clock_.now())); debug_eb_traj_pub_->publish(eb_traj); time_keeper_ptr_->toc(__func__, " "); @@ -389,8 +389,8 @@ void EBPathSmoother::updateConstraint( } // publish fixed trajectory - const auto eb_fixed_traj = - autoware_motion_utils::convertToTrajectory(debug_fixed_traj_points, createHeader(clock_.now())); + const auto eb_fixed_traj = autoware::motion_utils::convertToTrajectory( + debug_fixed_traj_points, createHeader(clock_.now())); debug_eb_fixed_traj_pub_->publish(eb_fixed_traj); time_keeper_ptr_->toc(__func__, " "); @@ -443,12 +443,12 @@ std::optional> EBPathSmoother::convertOptimizedPoin auto eb_traj_point = traj_points.at(i); eb_traj_point.pose = - autoware_universe_utils::calcOffsetPose(eb_traj_point.pose, 0.0, lat_offset, 0.0); + autoware::universe_utils::calcOffsetPose(eb_traj_point.pose, 0.0, lat_offset, 0.0); eb_traj_points.push_back(eb_traj_point); } // update orientation - autoware_motion_utils::insertOrientation(eb_traj_points, true); + autoware::motion_utils::insertOrientation(eb_traj_points, true); time_keeper_ptr_->toc(__func__, " "); return eb_traj_points; diff --git a/planning/autoware_path_smoother/src/elastic_band_smoother.cpp b/planning/autoware_path_smoother/src/elastic_band_smoother.cpp index 8814fb5f9e5fd..b92798f92728c 100644 --- a/planning/autoware_path_smoother/src/elastic_band_smoother.cpp +++ b/planning/autoware_path_smoother/src/elastic_band_smoother.cpp @@ -54,7 +54,7 @@ Float64Stamped createFloat64Stamped(const rclcpp::Time & now, const float & data void setZeroVelocityAfterStopPoint(std::vector & traj_points) { - const auto opt_zero_vel_idx = autoware_motion_utils::searchZeroVelocityIndex(traj_points); + const auto opt_zero_vel_idx = autoware::motion_utils::searchZeroVelocityIndex(traj_points); if (opt_zero_vel_idx) { for (size_t i = opt_zero_vel_idx.value(); i < traj_points.size(); ++i) { traj_points.at(i).longitudinal_velocity_mps = 0.0; @@ -105,15 +105,15 @@ ElasticBandSmoother::ElasticBandSmoother(const rclcpp::NodeOptions & node_option set_param_res_ = this->add_on_set_parameters_callback( std::bind(&ElasticBandSmoother::onParam, this, std::placeholders::_1)); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } rcl_interfaces::msg::SetParametersResult ElasticBandSmoother::onParam( const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; // parameters for ego nearest search ego_nearest_param_.onParam(parameters); @@ -170,7 +170,7 @@ void ElasticBandSmoother::onPath(const Path::ConstSharedPtr path_ptr) const auto traj_points = trajectory_utils::convertToTrajectoryPoints(path_ptr->points); const auto output_traj_msg = - autoware_motion_utils::convertToTrajectory(traj_points, path_ptr->header); + autoware::motion_utils::convertToTrajectory(traj_points, path_ptr->header); traj_pub_->publish(output_traj_msg); path_pub_->publish(*path_ptr); published_time_publisher_->publish_if_subscribed(path_pub_, path_ptr->header.stamp); @@ -224,7 +224,7 @@ void ElasticBandSmoother::onPath(const Path::ConstSharedPtr path_ptr) createFloat64Stamped(now(), time_keeper_ptr_->getAccumulatedTime())); const auto output_traj_msg = - autoware_motion_utils::convertToTrajectory(full_traj_points, path_ptr->header); + autoware::motion_utils::convertToTrajectory(full_traj_points, path_ptr->header); traj_pub_->publish(output_traj_msg); const auto output_path_msg = trajectory_utils::create_path(*path_ptr, full_traj_points); path_pub_->publish(output_path_msg); @@ -261,12 +261,12 @@ void ElasticBandSmoother::applyInputVelocity( time_keeper_ptr_->tic(__func__); // crop forward for faster calculation - const double output_traj_length = autoware_motion_utils::calcArcLength(output_traj_points); + const double output_traj_length = autoware::motion_utils::calcArcLength(output_traj_points); constexpr double margin_traj_length = 10.0; const auto forward_cropped_input_traj_points = [&]() { const size_t ego_seg_idx = trajectory_utils::findEgoSegmentIndex(input_traj_points, ego_pose, ego_nearest_param_); - return autoware_motion_utils::cropForwardPoints( + return autoware::motion_utils::cropForwardPoints( input_traj_points, ego_pose.position, ego_seg_idx, output_traj_length + margin_traj_length); }(); @@ -289,14 +289,14 @@ void ElasticBandSmoother::applyInputVelocity( // insert stop point explicitly const auto stop_idx = - autoware_motion_utils::searchZeroVelocityIndex(forward_cropped_input_traj_points); + autoware::motion_utils::searchZeroVelocityIndex(forward_cropped_input_traj_points); if (stop_idx) { const auto & input_stop_pose = forward_cropped_input_traj_points.at(stop_idx.value()).pose; - // NOTE: autoware_motion_utils::findNearestSegmentIndex is used instead of + // NOTE: autoware::motion_utils::findNearestSegmentIndex is used instead of // trajectory_utils::findEgoSegmentIndex // for the case where input_traj_points is much longer than output_traj_points, and the // former has a stop point but the latter will not have. - const auto stop_seg_idx = autoware_motion_utils::findNearestSegmentIndex( + const auto stop_seg_idx = autoware::motion_utils::findNearestSegmentIndex( output_traj_points, input_stop_pose, ego_nearest_param_.dist_threshold, ego_nearest_param_.yaw_threshold); @@ -307,9 +307,9 @@ void ElasticBandSmoother::applyInputVelocity( } if (*stop_seg_idx == output_traj_points.size() - 2) { const double signed_projected_length_to_segment = - autoware_motion_utils::calcLongitudinalOffsetToSegment( + autoware::motion_utils::calcLongitudinalOffsetToSegment( output_traj_points, *stop_seg_idx, input_stop_pose.position); - const double segment_length = autoware_motion_utils::calcSignedArcLength( + const double segment_length = autoware::motion_utils::calcSignedArcLength( output_traj_points, *stop_seg_idx, *stop_seg_idx + 1); if (segment_length < signed_projected_length_to_segment) { // NOTE: input_stop_pose is outside output_traj_points. diff --git a/planning/autoware_path_smoother/src/replan_checker.cpp b/planning/autoware_path_smoother/src/replan_checker.cpp index 67096d29cab8d..5d2e7a05e4b17 100644 --- a/planning/autoware_path_smoother/src/replan_checker.cpp +++ b/planning/autoware_path_smoother/src/replan_checker.cpp @@ -40,7 +40,7 @@ ReplanChecker::ReplanChecker(rclcpp::Node * node, const EgoNearestParam & ego_ne void ReplanChecker::onParam(const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; updateParam(parameters, "replan.enable", enable_); updateParam( @@ -80,7 +80,7 @@ bool ReplanChecker::isResetRequired(const PlannerData & planner_data) const // ego pose is lost or new ego pose is designated in simulation const double delta_dist = - autoware_universe_utils::calcDistance2d(p.ego_pose, prev_ego_pose_ptr_->position); + autoware::universe_utils::calcDistance2d(p.ego_pose, prev_ego_pose_ptr_->position); if (max_ego_moving_dist_ < delta_dist) { RCLCPP_DEBUG( logger_, @@ -140,14 +140,14 @@ bool ReplanChecker::isPathAroundEgoChanged( // calculate ego's lateral offset to previous trajectory points const auto prev_ego_seg_idx = trajectory_utils::findEgoSegmentIndex(prev_traj_points, p.ego_pose, ego_nearest_param_); - const double prev_ego_lat_offset = autoware_motion_utils::calcLateralOffset( + const double prev_ego_lat_offset = autoware::motion_utils::calcLateralOffset( prev_traj_points, p.ego_pose.position, prev_ego_seg_idx); // calculate ego's lateral offset to current trajectory points const auto ego_seg_idx = trajectory_utils::findEgoSegmentIndex(p.traj_points, p.ego_pose, ego_nearest_param_); const double ego_lat_offset = - autoware_motion_utils::calcLateralOffset(p.traj_points, p.ego_pose.position, ego_seg_idx); + autoware::motion_utils::calcLateralOffset(p.traj_points, p.ego_pose.position, ego_seg_idx); const double diff_ego_lat_offset = prev_ego_lat_offset - ego_lat_offset; if (std::abs(diff_ego_lat_offset) < max_path_shape_around_ego_lat_dist_) { @@ -170,7 +170,7 @@ bool ReplanChecker::isPathForwardChanged( constexpr double lon_dist_interval = 10.0; for (double lon_dist = lon_dist_interval; lon_dist <= max_path_shape_forward_lon_dist_; lon_dist += lon_dist_interval) { - const auto prev_forward_point = autoware_motion_utils::calcLongitudinalOffsetPoint( + const auto prev_forward_point = autoware::motion_utils::calcLongitudinalOffsetPoint( prev_traj_points, prev_ego_seg_idx, lon_dist); if (!prev_forward_point) { continue; @@ -178,9 +178,9 @@ bool ReplanChecker::isPathForwardChanged( // calculate lateral offset of current trajectory points to prev forward point const auto forward_seg_idx = - autoware_motion_utils::findNearestSegmentIndex(p.traj_points, *prev_forward_point); - const double forward_lat_offset = - autoware_motion_utils::calcLateralOffset(p.traj_points, *prev_forward_point, forward_seg_idx); + autoware::motion_utils::findNearestSegmentIndex(p.traj_points, *prev_forward_point); + const double forward_lat_offset = autoware::motion_utils::calcLateralOffset( + p.traj_points, *prev_forward_point, forward_seg_idx); if (max_path_shape_forward_lat_dist_ < std::abs(forward_lat_offset)) { return true; } @@ -201,7 +201,7 @@ bool ReplanChecker::isPathGoalChanged( } const double goal_moving_dist = - autoware_universe_utils::calcDistance2d(p.traj_points.back(), prev_traj_points.back()); + autoware::universe_utils::calcDistance2d(p.traj_points.back(), prev_traj_points.back()); if (goal_moving_dist < max_goal_moving_dist_) { return false; } diff --git a/planning/autoware_path_smoother/src/utils/trajectory_utils.cpp b/planning/autoware_path_smoother/src/utils/trajectory_utils.cpp index b55dc901b0cdc..4a36359ded4f3 100644 --- a/planning/autoware_path_smoother/src/utils/trajectory_utils.cpp +++ b/planning/autoware_path_smoother/src/utils/trajectory_utils.cpp @@ -54,10 +54,10 @@ std::vector resampleTrajectoryPoints( { constexpr bool enable_resampling_stop_point = true; - const auto traj = autoware_motion_utils::convertToTrajectory(traj_points); - const auto resampled_traj = autoware_motion_utils::resampleTrajectory( + const auto traj = autoware::motion_utils::convertToTrajectory(traj_points); + const auto resampled_traj = autoware::motion_utils::resampleTrajectory( traj, interval, false, true, true, enable_resampling_stop_point); - return autoware_motion_utils::convertToTrajectoryPointArray(resampled_traj); + return autoware::motion_utils::convertToTrajectoryPointArray(resampled_traj); } // NOTE: stop point will not be resampled @@ -66,17 +66,17 @@ std::vector resampleTrajectoryPointsWithoutStopPoint( { constexpr bool enable_resampling_stop_point = false; - const auto traj = autoware_motion_utils::convertToTrajectory(traj_points); - const auto resampled_traj = autoware_motion_utils::resampleTrajectory( + const auto traj = autoware::motion_utils::convertToTrajectory(traj_points); + const auto resampled_traj = autoware::motion_utils::resampleTrajectory( traj, interval, false, true, true, enable_resampling_stop_point); - return autoware_motion_utils::convertToTrajectoryPointArray(resampled_traj); + return autoware::motion_utils::convertToTrajectoryPointArray(resampled_traj); } void insertStopPoint( std::vector & traj_points, const geometry_msgs::msg::Pose & input_stop_pose, const size_t stop_seg_idx) { - const double offset_to_segment = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const double offset_to_segment = autoware::motion_utils::calcLongitudinalOffsetToSegment( traj_points, stop_seg_idx, input_stop_pose.position); const auto traj_spline = SplineInterpolationPoints2d(traj_points); diff --git a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp index dfaefd7c882d1..9a93b647dac02 100644 --- a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp +++ b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp @@ -57,8 +57,8 @@ Pose createPoseFromLaneID(const lanelet::Id & lane_id) // calculate middle pose geometry_msgs::msg::Pose middle_pose; middle_pose.position = middle_pos; - const double yaw = autoware_universe_utils::calcAzimuthAngle(middle_pos, next_middle_pos); - middle_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(yaw); + const double yaw = autoware::universe_utils::calcAzimuthAngle(middle_pos, next_middle_pos); + middle_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); return middle_pose; } diff --git a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp index 2907d264d1a1d..1526e061ca4d1 100644 --- a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp +++ b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp @@ -296,7 +296,7 @@ void PlanningInterfaceTestManager::publishNominalPath( { autoware::test_utils::publishToTargetNode( test_node_, target_node, topic_name, normal_path_pub_, - autoware_motion_utils::convertToPath( + autoware::motion_utils::convertToPath( autoware::test_utils::loadPathWithLaneIdInYaml()), 5); } diff --git a/planning/autoware_planning_topic_converter/src/path_to_trajectory.cpp b/planning/autoware_planning_topic_converter/src/path_to_trajectory.cpp index a03897ebb86f6..ff2f3084fc9ba 100644 --- a/planning/autoware_planning_topic_converter/src/path_to_trajectory.cpp +++ b/planning/autoware_planning_topic_converter/src/path_to_trajectory.cpp @@ -24,7 +24,7 @@ namespace TrajectoryPoint convertToTrajectoryPoint(const PathPoint & point) { TrajectoryPoint traj_point; - traj_point.pose = autoware_universe_utils::getPose(point); + traj_point.pose = autoware::universe_utils::getPose(point); traj_point.longitudinal_velocity_mps = point.longitudinal_velocity_mps; traj_point.lateral_velocity_mps = point.lateral_velocity_mps; traj_point.heading_rate_rps = point.heading_rate_rps; @@ -50,7 +50,7 @@ PathToTrajectory::PathToTrajectory(const rclcpp::NodeOptions & options) void PathToTrajectory::process(const Path::ConstSharedPtr msg) { const auto trajectory_points = convertToTrajectoryPoints(msg->points); - const auto output = autoware_motion_utils::convertToTrajectory(trajectory_points, msg->header); + const auto output = autoware::motion_utils::convertToTrajectory(trajectory_points, msg->header); pub_->publish(output); } diff --git a/planning/autoware_planning_validator/include/autoware/planning_validator/planning_validator.hpp b/planning/autoware_planning_validator/include/autoware/planning_validator/planning_validator.hpp index 1d47aefaa31e4..e996855b9b4da 100644 --- a/planning/autoware_planning_validator/include/autoware/planning_validator/planning_validator.hpp +++ b/planning/autoware_planning_validator/include/autoware/planning_validator/planning_validator.hpp @@ -36,10 +36,10 @@ namespace autoware::planning_validator { +using autoware::universe_utils::StopWatch; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; using autoware_planning_validator::msg::PlanningValidatorStatus; -using autoware_universe_utils::StopWatch; using diagnostic_updater::DiagnosticStatusWrapper; using diagnostic_updater::Updater; using nav_msgs::msg::Odometry; @@ -103,7 +103,7 @@ class PlanningValidator : public rclcpp::Node void setStatus(DiagnosticStatusWrapper & stat, const bool & is_ok, const std::string & msg); - autoware_universe_utils::InterProcessPollingSubscriber sub_kinematics_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_kinematics_{ this, "~/input/kinematics"}; rclcpp::Subscription::SharedPtr sub_traj_; rclcpp::Publisher::SharedPtr pub_traj_; @@ -137,9 +137,9 @@ class PlanningValidator : public rclcpp::Node std::shared_ptr debug_pose_publisher_; - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; StopWatch stop_watch_; }; diff --git a/planning/autoware_planning_validator/src/debug_marker.cpp b/planning/autoware_planning_validator/src/debug_marker.cpp index d4aa27ca2ee9a..7de23de8eda01 100644 --- a/planning/autoware_planning_validator/src/debug_marker.cpp +++ b/planning/autoware_planning_validator/src/debug_marker.cpp @@ -48,7 +48,7 @@ void PlanningValidatorDebugMarkerPublisher::pushPoseMarker( void PlanningValidatorDebugMarkerPublisher::pushPoseMarker( const geometry_msgs::msg::Pose & pose, const std::string & ns, int id) { - using autoware_universe_utils::createMarkerColor; + using autoware::universe_utils::createMarkerColor; // append arrow marker std_msgs::msg::ColorRGBA color; @@ -64,9 +64,9 @@ void PlanningValidatorDebugMarkerPublisher::pushPoseMarker( { color = createMarkerColor(0.0, 0.0, 1.0, 0.999); } - Marker marker = autoware_universe_utils::createDefaultMarker( + Marker marker = autoware::universe_utils::createDefaultMarker( "map", node_->get_clock()->now(), ns, getMarkerId(ns), Marker::ARROW, - autoware_universe_utils::createMarkerScale(0.2, 0.1, 0.3), color); + autoware::universe_utils::createMarkerScale(0.2, 0.1, 0.3), color); marker.lifetime = rclcpp::Duration::from_seconds(0.2); marker.pose = pose; @@ -76,10 +76,10 @@ void PlanningValidatorDebugMarkerPublisher::pushPoseMarker( void PlanningValidatorDebugMarkerPublisher::pushWarningMsg( const geometry_msgs::msg::Pose & pose, const std::string & msg) { - visualization_msgs::msg::Marker marker = autoware_universe_utils::createDefaultMarker( + visualization_msgs::msg::Marker marker = autoware::universe_utils::createDefaultMarker( "map", node_->get_clock()->now(), "warning_msg", 0, Marker::TEXT_VIEW_FACING, - autoware_universe_utils::createMarkerScale(0.0, 0.0, 1.0), - autoware_universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.999)); + autoware::universe_utils::createMarkerScale(0.0, 0.0, 1.0), + autoware::universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.999)); marker.lifetime = rclcpp::Duration::from_seconds(0.2); marker.pose = pose; marker.text = msg; @@ -89,9 +89,9 @@ void PlanningValidatorDebugMarkerPublisher::pushWarningMsg( void PlanningValidatorDebugMarkerPublisher::pushVirtualWall(const geometry_msgs::msg::Pose & pose) { const auto now = node_->get_clock()->now(); - const auto stop_wall_marker = - autoware_motion_utils::createStopVirtualWallMarker(pose, "autoware_planning_validator", now, 0); - autoware_universe_utils::appendMarkerArray(stop_wall_marker, &marker_array_virtual_wall_, now); + const auto stop_wall_marker = autoware::motion_utils::createStopVirtualWallMarker( + pose, "autoware_planning_validator", now, 0); + autoware::universe_utils::appendMarkerArray(stop_wall_marker, &marker_array_virtual_wall_, now); } void PlanningValidatorDebugMarkerPublisher::publish() diff --git a/planning/autoware_planning_validator/src/planning_validator.cpp b/planning/autoware_planning_validator/src/planning_validator.cpp index b3f2ab88a4a45..29e8932c87842 100644 --- a/planning/autoware_planning_validator/src/planning_validator.cpp +++ b/planning/autoware_planning_validator/src/planning_validator.cpp @@ -44,9 +44,9 @@ PlanningValidator::PlanningValidator(const rclcpp::NodeOptions & options) setupParameters(); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } void PlanningValidator::setupParameters() @@ -450,7 +450,7 @@ bool PlanningValidator::checkValidSteeringRate(const Trajectory & trajectory) bool PlanningValidator::checkValidVelocityDeviation(const Trajectory & trajectory) { // TODO(horibe): set appropriate thresholds for index search - const auto idx = autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + const auto idx = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( trajectory.points, current_kinematics_->pose.pose); validation_status_.velocity_deviation = std::abs( @@ -466,10 +466,10 @@ bool PlanningValidator::checkValidVelocityDeviation(const Trajectory & trajector bool PlanningValidator::checkValidDistanceDeviation(const Trajectory & trajectory) { // TODO(horibe): set appropriate thresholds for index search - const auto idx = autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + const auto idx = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( trajectory.points, current_kinematics_->pose.pose); - validation_status_.distance_deviation = autoware_universe_utils::calcDistance2d( + validation_status_.distance_deviation = autoware::universe_utils::calcDistance2d( trajectory.points.at(idx), current_kinematics_->pose.pose); if (validation_status_.distance_deviation > validation_params_.distance_deviation_threshold) { @@ -487,7 +487,7 @@ bool PlanningValidator::checkValidLongitudinalDistanceDeviation(const Trajectory const auto ego_pose = current_kinematics_->pose.pose; const size_t idx = - autoware_motion_utils::findFirstNearestIndexWithSoftConstraints(trajectory.points, ego_pose); + autoware::motion_utils::findFirstNearestIndexWithSoftConstraints(trajectory.points, ego_pose); if (0 < idx && idx < trajectory.points.size() - 1) { return true; // ego-nearest point exists between trajectory points. @@ -495,13 +495,13 @@ bool PlanningValidator::checkValidLongitudinalDistanceDeviation(const Trajectory // Check if the valid longitudinal deviation for given segment index const auto HasValidLongitudinalDeviation = [&](const size_t seg_idx, const bool is_last) { - auto long_offset = autoware_motion_utils::calcLongitudinalOffsetToSegment( + auto long_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( trajectory.points, seg_idx, ego_pose.position); // for last, need to remove distance for the last segment. if (is_last) { const auto size = trajectory.points.size(); - long_offset -= autoware_universe_utils::calcDistance2d( + long_offset -= autoware::universe_utils::calcDistance2d( trajectory.points.at(size - 1), trajectory.points.at(size - 2)); } @@ -532,7 +532,7 @@ bool PlanningValidator::checkValidForwardTrajectoryLength(const Trajectory & tra return true; // Ego is almost stopped. } - const auto forward_length = autoware_motion_utils::calcSignedArcLength( + const auto forward_length = autoware::motion_utils::calcSignedArcLength( trajectory.points, current_kinematics_->pose.pose.position, trajectory.points.size() - 1); const auto acc = validation_params_.forward_trajectory_length_acceleration; diff --git a/planning/autoware_planning_validator/src/utils.cpp b/planning/autoware_planning_validator/src/utils.cpp index 3d21c89704a03..ae580a7a7c6f1 100644 --- a/planning/autoware_planning_validator/src/utils.cpp +++ b/planning/autoware_planning_validator/src/utils.cpp @@ -24,9 +24,9 @@ namespace autoware::planning_validator { -using autoware_universe_utils::calcCurvature; -using autoware_universe_utils::calcDistance2d; -using autoware_universe_utils::getPoint; +using autoware::universe_utils::calcCurvature; +using autoware::universe_utils::calcDistance2d; +using autoware::universe_utils::getPoint; namespace { @@ -138,7 +138,7 @@ void calcCurvature( const auto p2 = getPoint(trajectory.points.at(i)); const auto p3 = getPoint(trajectory.points.at(next_idx)); try { - curvature_arr.at(i) = autoware_universe_utils::calcCurvature(p1, p2, p3); + curvature_arr.at(i) = autoware::universe_utils::calcCurvature(p1, p2, p3); } catch (...) { curvature_arr.at(i) = 0.0; // maybe distance is too close } @@ -236,12 +236,12 @@ std::pair calcMaxRelativeAngles(const Trajectory & trajectory) const auto & p2 = trajectory.points.at(i + 1).pose.position; const auto & p3 = trajectory.points.at(i + 2).pose.position; - const auto angle_a = autoware_universe_utils::calcAzimuthAngle(p1, p2); - const auto angle_b = autoware_universe_utils::calcAzimuthAngle(p2, p3); + const auto angle_a = autoware::universe_utils::calcAzimuthAngle(p1, p2); + const auto angle_b = autoware::universe_utils::calcAzimuthAngle(p2, p3); // convert relative angle to [-pi ~ pi] const auto relative_angle = - std::abs(autoware_universe_utils::normalizeRadian(angle_b - angle_a)); + std::abs(autoware::universe_utils::normalizeRadian(angle_b - angle_a)); takeBigger(max_relative_angles, max_index, std::abs(relative_angle), i); } diff --git a/planning/autoware_planning_validator/test/src/test_planning_validator_helper.cpp b/planning/autoware_planning_validator/test/src/test_planning_validator_helper.cpp index b4985700fdcb6..bdf4ca96d9fdd 100644 --- a/planning/autoware_planning_validator/test/src/test_planning_validator_helper.cpp +++ b/planning/autoware_planning_validator/test/src/test_planning_validator_helper.cpp @@ -19,9 +19,9 @@ #include +using autoware::universe_utils::createQuaternionFromYaw; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; -using autoware_universe_utils::createQuaternionFromYaw; Trajectory generateTrajectoryWithConstantAcceleration( const double interval_distance, const double speed, const double yaw, const size_t size, diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp index 4c1eb1d1c4ef6..da1292fa862c6 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -143,7 +143,7 @@ void RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() for (auto & llt : remaining_shortest_path) { if (remaining_shortest_path.size() == 1) { - remaining_distance_ += autoware_universe_utils::calcDistance2d( + remaining_distance_ += autoware::universe_utils::calcDistance2d( current_vehicle_pose_.position, goal_pose_.position); break; } diff --git a/planning/autoware_route_handler/src/route_handler.cpp b/planning/autoware_route_handler/src/route_handler.cpp index cffac44b6947e..d534ecc4c84a8 100644 --- a/planning/autoware_route_handler/src/route_handler.cpp +++ b/planning/autoware_route_handler/src/route_handler.cpp @@ -110,7 +110,7 @@ PathWithLaneId removeOverlappingPoints(const PathWithLaneId & input_path) constexpr double min_dist = 0.001; if ( - autoware_universe_utils::calcDistance3d(filtered_path.points.back().point, pt.point) < + autoware::universe_utils::calcDistance3d(filtered_path.points.back().point, pt.point) < min_dist) { filtered_path.points.back().lane_ids.push_back(pt.lane_ids.front()); filtered_path.points.back().point.longitudinal_velocity_mps = std::min( @@ -1725,14 +1725,14 @@ PathWithLaneId RouteHandler::getCenterLinePath( double angle{0.0}; const auto & pts = reference_path.points; if (i + 1 < reference_path.points.size()) { - angle = autoware_universe_utils::calcAzimuthAngle( + angle = autoware::universe_utils::calcAzimuthAngle( pts.at(i).point.pose.position, pts.at(i + 1).point.pose.position); } else if (i != 0) { - angle = autoware_universe_utils::calcAzimuthAngle( + angle = autoware::universe_utils::calcAzimuthAngle( pts.at(i - 1).point.pose.position, pts.at(i).point.pose.position); } reference_path.points.at(i).point.pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(angle); + autoware::universe_utils::createQuaternionFromYaw(angle); } return reference_path; diff --git a/planning/autoware_route_handler/test/test_route_handler.cpp b/planning/autoware_route_handler/test/test_route_handler.cpp index 056d46056f452..35a2fe3ef45da 100644 --- a/planning/autoware_route_handler/test/test_route_handler.cpp +++ b/planning/autoware_route_handler/test/test_route_handler.cpp @@ -53,10 +53,10 @@ TEST_F(TestRouteHandler, getLaneletSequenceWhenOverlappingRoute) ASSERT_FALSE(route_handler_->isHandlerReady()); geometry_msgs::msg::Pose start_pose, goal_pose; - start_pose.position = autoware_universe_utils::createPoint(3728.870361, 73739.281250, 0); - start_pose.orientation = autoware_universe_utils::createQuaternion(0, 0, -0.513117, 0.858319); - goal_pose.position = autoware_universe_utils::createPoint(3729.961182, 73727.328125, 0); - goal_pose.orientation = autoware_universe_utils::createQuaternion(0, 0, 0.234831, 0.972036); + start_pose.position = autoware::universe_utils::createPoint(3728.870361, 73739.281250, 0); + start_pose.orientation = autoware::universe_utils::createQuaternion(0, 0, -0.513117, 0.858319); + goal_pose.position = autoware::universe_utils::createPoint(3729.961182, 73727.328125, 0); + goal_pose.orientation = autoware::universe_utils::createQuaternion(0, 0, 0.234831, 0.972036); lanelet::ConstLanelets path_lanelets; ASSERT_TRUE( @@ -86,16 +86,17 @@ TEST_F(TestRouteHandler, getClosestRouteLaneletFromLaneletWhenOverlappingRoute) geometry_msgs::msg::Pose reference_pose, search_pose; lanelet::ConstLanelet reference_lanelet; - reference_pose.position = autoware_universe_utils::createPoint(3730.88, 73735.3, 0); - reference_pose.orientation = autoware_universe_utils::createQuaternion(0, 0, -0.504626, 0.863338); + reference_pose.position = autoware::universe_utils::createPoint(3730.88, 73735.3, 0); + reference_pose.orientation = + autoware::universe_utils::createQuaternion(0, 0, -0.504626, 0.863338); const auto found_reference_lanelet = route_handler_->getClosestLaneletWithinRoute(reference_pose, &reference_lanelet); ASSERT_TRUE(found_reference_lanelet); ASSERT_EQ(reference_lanelet.id(), 168); lanelet::ConstLanelet closest_lanelet; - search_pose.position = autoware_universe_utils::createPoint(3736.89, 73730.8, 0); - search_pose.orientation = autoware_universe_utils::createQuaternion(0, 0, 0.223244, 0.974763); + search_pose.position = autoware::universe_utils::createPoint(3736.89, 73730.8, 0); + search_pose.orientation = autoware::universe_utils::createQuaternion(0, 0, 0.223244, 0.974763); bool found_lanelet = route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lanelet); ASSERT_TRUE(found_lanelet); ASSERT_EQ(closest_lanelet.id(), 345); @@ -112,56 +113,56 @@ TEST_F(TestRouteHandler, getClosestRouteLaneletFromLaneletWhenOverlappingRoute) // Pose search_pose; -// search_pose.position = autoware_universe_utils::createPoint(-1.0, 1.75, 0); -// search_pose.orientation = autoware_universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); +// search_pose.position = autoware::universe_utils::createPoint(-1.0, 1.75, 0); +// search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); // const auto closest_lane_obtained7 = // route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); // ASSERT_TRUE(closest_lane_obtained7); // ASSERT_EQ(closest_lane.id(), 4775); -// search_pose.position = autoware_universe_utils::createPoint(-0.5, 1.75, 0); +// search_pose.position = autoware::universe_utils::createPoint(-0.5, 1.75, 0); // const auto closest_lane_obtained = -// search_pose.orientation = autoware_universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); +// search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); // route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); // ASSERT_TRUE(closest_lane_obtained); // ASSERT_EQ(closest_lane.id(), 4775); -// search_pose.position = autoware_universe_utils::createPoint(-.01, 1.75, 0); -// search_pose.orientation = autoware_universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); +// search_pose.position = autoware::universe_utils::createPoint(-.01, 1.75, 0); +// search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); // const auto closest_lane_obtained3 = // route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); // ASSERT_TRUE(closest_lane_obtained3); // ASSERT_EQ(closest_lane.id(), 4775); -// search_pose.position = autoware_universe_utils::createPoint(0.0, 1.75, 0); -// search_pose.orientation = autoware_universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); +// search_pose.position = autoware::universe_utils::createPoint(0.0, 1.75, 0); +// search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); // const auto closest_lane_obtained1 = // route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); // ASSERT_TRUE(closest_lane_obtained1); // ASSERT_EQ(closest_lane.id(), 4775); -// search_pose.position = autoware_universe_utils::createPoint(0.01, 1.75, 0); -// search_pose.orientation = autoware_universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); +// search_pose.position = autoware::universe_utils::createPoint(0.01, 1.75, 0); +// search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); // const auto closest_lane_obtained2 = // route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); // ASSERT_TRUE(closest_lane_obtained2); // ASSERT_EQ(closest_lane.id(), 4424); -// search_pose.position = autoware_universe_utils::createPoint(0.5, 1.75, 0); -// search_pose.orientation = autoware_universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); +// search_pose.position = autoware::universe_utils::createPoint(0.5, 1.75, 0); +// search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); // const auto closest_lane_obtained4 = // route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); // ASSERT_TRUE(closest_lane_obtained4); // ASSERT_EQ(closest_lane.id(), 4424); -// search_pose.position = autoware_universe_utils::createPoint(1.0, 1.75, 0); -// search_pose.orientation = autoware_universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); +// search_pose.position = autoware::universe_utils::createPoint(1.0, 1.75, 0); +// search_pose.orientation = autoware::universe_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); // const auto closest_lane_obtained5 = // route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); diff --git a/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp b/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp index e008a3d647436..557c0c871583d 100644 --- a/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp +++ b/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp @@ -73,12 +73,12 @@ class ScenarioSelectorNode : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_lanelet_map_; rclcpp::Subscription::SharedPtr sub_route_; - autoware_universe_utils::InterProcessPollingSubscriber::SharedPtr + autoware::universe_utils::InterProcessPollingSubscriber::SharedPtr sub_odom_; rclcpp::Subscription::SharedPtr sub_lane_driving_trajectory_; rclcpp::Subscription::SharedPtr sub_parking_trajectory_; - autoware_universe_utils::InterProcessPollingSubscriber::SharedPtr + autoware::universe_utils::InterProcessPollingSubscriber::SharedPtr sub_parking_state_; rclcpp::Publisher::SharedPtr pub_trajectory_; rclcpp::Publisher::SharedPtr pub_scenario_; @@ -93,7 +93,7 @@ class ScenarioSelectorNode : public rclcpp::Node std::deque twist_buffer_; std::shared_ptr route_handler_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; // Parameters double update_rate_; diff --git a/planning/autoware_scenario_selector/src/node.cpp b/planning/autoware_scenario_selector/src/node.cpp index d1516c68050c1..4dcf1b6adb111 100644 --- a/planning/autoware_scenario_selector/src/node.cpp +++ b/planning/autoware_scenario_selector/src/node.cpp @@ -382,7 +382,7 @@ ScenarioSelectorNode::ScenarioSelectorNode(const rclcpp::NodeOptions & node_opti timer_ = rclcpp::create_timer( this, get_clock(), period_ns, std::bind(&ScenarioSelectorNode::onTimer, this)); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } } // namespace autoware::scenario_selector diff --git a/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp b/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp index d73573833d1fa..cbfcac5789812 100644 --- a/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp +++ b/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp @@ -73,10 +73,10 @@ std::vector generate_centerline_with_bag(rclcpp::Node & node) centerline_traj_points.at(i - 1).pose.orientation; } } else { - const double yaw_angle = autoware_universe_utils::calcAzimuthAngle( + const double yaw_angle = autoware::universe_utils::calcAzimuthAngle( centerline_traj_points.at(i).pose.position, centerline_traj_points.at(i + 1).pose.position); centerline_traj_points.at(i).pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(yaw_angle); + autoware::universe_utils::createQuaternionFromYaw(yaw_angle); } } diff --git a/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp b/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp index 7bba3a6d5a722..1f72dea1cd35f 100644 --- a/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp +++ b/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp @@ -82,20 +82,20 @@ OptimizationTrajectoryBasedCenterline::generate_centerline_with_optimization( // get ego nearest search parameters and resample interval in behavior_path_planner const double ego_nearest_dist_threshold = - autoware_universe_utils::getOrDeclareParameter(node, "ego_nearest_dist_threshold"); + autoware::universe_utils::getOrDeclareParameter(node, "ego_nearest_dist_threshold"); const double ego_nearest_yaw_threshold = - autoware_universe_utils::getOrDeclareParameter(node, "ego_nearest_yaw_threshold"); + autoware::universe_utils::getOrDeclareParameter(node, "ego_nearest_yaw_threshold"); const double behavior_path_interval = - autoware_universe_utils::getOrDeclareParameter(node, "output_path_interval"); + autoware::universe_utils::getOrDeclareParameter(node, "output_path_interval"); const double behavior_vel_interval = - autoware_universe_utils::getOrDeclareParameter(node, "behavior_output_path_interval"); + autoware::universe_utils::getOrDeclareParameter(node, "behavior_output_path_interval"); // extract path with lane id from lanelets const auto raw_path_with_lane_id = [&]() { const auto non_resampled_path_with_lane_id = utils::get_path_with_lane_id( route_handler, route_lanelets, start_center_pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); - return autoware_motion_utils::resamplePath( + return autoware::motion_utils::resamplePath( non_resampled_path_with_lane_id, behavior_path_interval); }(); pub_raw_path_with_lane_id_->publish(raw_path_with_lane_id); @@ -104,7 +104,7 @@ OptimizationTrajectoryBasedCenterline::generate_centerline_with_optimization( // convert path with lane id to path const auto raw_path = [&]() { const auto non_resampled_path = convert_to_path(raw_path_with_lane_id); - return autoware_motion_utils::resamplePath(non_resampled_path, behavior_vel_interval); + return autoware::motion_utils::resamplePath(non_resampled_path, behavior_vel_interval); }(); pub_raw_path_->publish(raw_path); RCLCPP_INFO(node.get_logger(), "Converted to path and published."); @@ -124,7 +124,7 @@ std::vector OptimizationTrajectoryBasedCenterline::optimize_tra // convert to trajectory points const auto raw_traj_points = [&]() { const auto raw_traj = convert_to_trajectory(raw_path); - return autoware_motion_utils::convertToTrajectoryPointArray(raw_traj); + return autoware::motion_utils::convertToTrajectoryPointArray(raw_traj); }(); // create an instance of elastic band and model predictive trajectory. @@ -166,7 +166,7 @@ std::vector OptimizationTrajectoryBasedCenterline::optimize_tra // connect the previously and currently optimized trajectory points for (size_t j = 0; j < whole_optimized_traj_points.size(); ++j) { - const double dist = autoware_universe_utils::calcDistance2d( + const double dist = autoware::universe_utils::calcDistance2d( whole_optimized_traj_points.at(j), optimized_traj_points.front()); if (dist < 0.5) { const std::vector extracted_whole_optimized_traj_points{ diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp index 706f0e9c75475..c5ecc48ee209d 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp @@ -89,13 +89,13 @@ LinearRing2d create_vehicle_footprint( std::vector geom_points; geom_points.push_back( - autoware_universe_utils::calcOffsetPose(pose, x_front, y_left, 0.0).position); + autoware::universe_utils::calcOffsetPose(pose, x_front, y_left, 0.0).position); geom_points.push_back( - autoware_universe_utils::calcOffsetPose(pose, x_front, y_right, 0.0).position); + autoware::universe_utils::calcOffsetPose(pose, x_front, y_right, 0.0).position); geom_points.push_back( - autoware_universe_utils::calcOffsetPose(pose, x_rear, y_right, 0.0).position); + autoware::universe_utils::calcOffsetPose(pose, x_rear, y_right, 0.0).position); geom_points.push_back( - autoware_universe_utils::calcOffsetPose(pose, x_rear, y_left, 0.0).position); + autoware::universe_utils::calcOffsetPose(pose, x_rear, y_left, 0.0).position); LinearRing2d footprint; for (const auto & geom_point : geom_points) { @@ -117,7 +117,7 @@ geometry_msgs::msg::Pose get_text_pose( const double x_front = i.front_overhang_m + i.wheel_base_m; const double y_left = i.wheel_tread_m / 2.0 + i.left_overhang_m + 1.0; - return autoware_universe_utils::calcOffsetPose(pose, x_front, y_left, 0.0); + return autoware::universe_utils::calcOffsetPose(pose, x_front, y_left, 0.0); } std::array convert_hex_string_to_decimal(const std::string & hex_str_color) @@ -166,10 +166,10 @@ std::vector resample_trajectory_points( const std::vector & input_traj_points, const double resample_interval) { // resample and calculate trajectory points' orientation - const auto input_traj = autoware_motion_utils::convertToTrajectory(input_traj_points); + const auto input_traj = autoware::motion_utils::convertToTrajectory(input_traj_points); auto resampled_input_traj = - autoware_motion_utils::resampleTrajectory(input_traj, resample_interval); - return autoware_motion_utils::convertToTrajectoryPointArray(resampled_input_traj); + autoware::motion_utils::resampleTrajectory(input_traj, resample_interval); + return autoware::motion_utils::convertToTrajectoryPointArray(resampled_input_traj); } } // namespace @@ -203,7 +203,7 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( sub_save_map_ = create_subscription( "/centerline_updater_helper/save_map", rclcpp::QoS{1}, [this](const std_msgs::msg::Bool & msg) { const auto lanelet2_output_file_path = - autoware_universe_utils::getOrDeclareParameter( + autoware::universe_utils::getOrDeclareParameter( *this, "lanelet2_output_file_path"); if (!centerline_with_route_ || msg.data) { const auto & c = *centerline_with_route_; @@ -274,7 +274,7 @@ void StaticCenterlineGeneratorNode::update_centerline_range( centerline.begin() + traj_range_indices_.second + 1); pub_centerline_->publish( - autoware_motion_utils::convertToTrajectory(selected_centerline, create_header(this->now()))); + autoware::motion_utils::convertToTrajectory(selected_centerline, create_header(this->now()))); } void StaticCenterlineGeneratorNode::run() @@ -326,10 +326,10 @@ CenterlineWithRoute StaticCenterlineGeneratorNode::generate_centerline_with_rout centerline_with_route.centerline = resample_trajectory_points(centerline_with_route.centerline, output_trajectory_interval); - pub_whole_centerline_->publish(autoware_motion_utils::convertToTrajectory( + pub_whole_centerline_->publish(autoware::motion_utils::convertToTrajectory( centerline_with_route.centerline, create_header(this->now()))); - pub_centerline_->publish(autoware_motion_utils::convertToTrajectory( + pub_centerline_->publish(autoware::motion_utils::convertToTrajectory( centerline_with_route.centerline, create_header(this->now()))); return centerline_with_route; @@ -577,10 +577,11 @@ void StaticCenterlineGeneratorNode::evaluate( const std::vector & optimized_traj_points) { const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); - const auto dist_thresh_vec = autoware_universe_utils::getOrDeclareParameter>( + const auto dist_thresh_vec = autoware::universe_utils::getOrDeclareParameter>( *this, "marker_color_dist_thresh"); const auto marker_color_vec = - autoware_universe_utils::getOrDeclareParameter>(*this, "marker_color"); + autoware::universe_utils::getOrDeclareParameter>( + *this, "marker_color"); const auto get_marker_color = [&](const double dist) -> boost::optional> { for (size_t i = 0; i < dist_thresh_vec.size(); ++i) { const double dist_thresh = dist_thresh_vec.at(i); @@ -627,13 +628,13 @@ void StaticCenterlineGeneratorNode::evaluate( // add footprint marker const auto footprint_marker = utils::create_footprint_marker(footprint_poly, marker_color, now(), i); - autoware_universe_utils::appendMarkerArray(footprint_marker, &marker_array); + autoware::universe_utils::appendMarkerArray(footprint_marker, &marker_array); // add text of distance to bounds marker const auto text_pose = get_text_pose(traj_point.pose, vehicle_info_); const auto text_marker = utils::create_distance_text_marker(text_pose, min_dist_to_bound, marker_color, now(), i); - autoware_universe_utils::appendMarkerArray(text_marker, &marker_array); + autoware::universe_utils::appendMarkerArray(text_marker, &marker_array); } } diff --git a/planning/autoware_static_centerline_generator/src/type_alias.hpp b/planning/autoware_static_centerline_generator/src/type_alias.hpp index 88b4d3ffa14b4..c5157acc2b525 100644 --- a/planning/autoware_static_centerline_generator/src/type_alias.hpp +++ b/planning/autoware_static_centerline_generator/src/type_alias.hpp @@ -29,6 +29,9 @@ namespace autoware::static_centerline_generator { using autoware::route_handler::RouteHandler; +using autoware::universe_utils::LinearRing2d; +using autoware::universe_utils::LineString2d; +using autoware::universe_utils::Point2d; using autoware_map_msgs::msg::LaneletMapBin; using autoware_perception_msgs::msg::PredictedObjects; using autoware_planning_msgs::msg::LaneletRoute; @@ -36,9 +39,6 @@ using autoware_planning_msgs::msg::Path; using autoware_planning_msgs::msg::PathPoint; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; -using autoware_universe_utils::LinearRing2d; -using autoware_universe_utils::LineString2d; -using autoware_universe_utils::Point2d; using tier4_planning_msgs::msg::PathWithLaneId; using visualization_msgs::msg::MarkerArray; } // namespace autoware::static_centerline_generator diff --git a/planning/autoware_static_centerline_generator/src/utils.cpp b/planning/autoware_static_centerline_generator/src/utils.cpp index 10b2589f3bf7b..de362e3af5d7f 100644 --- a/planning/autoware_static_centerline_generator/src/utils.cpp +++ b/planning/autoware_static_centerline_generator/src/utils.cpp @@ -94,8 +94,8 @@ geometry_msgs::msg::Pose get_center_pose( // calculate middle pose geometry_msgs::msg::Pose middle_pose; middle_pose.position = middle_pos; - const double yaw = autoware_universe_utils::calcAzimuthAngle(middle_pos, next_middle_pos); - middle_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(yaw); + const double yaw = autoware::universe_utils::calcAzimuthAngle(middle_pos, next_middle_pos); + middle_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); return middle_pose; } @@ -189,11 +189,11 @@ MarkerArray create_footprint_marker( const double g = marker_color.at(1); const double b = marker_color.at(2); - auto marker = autoware_universe_utils::createDefaultMarker( + auto marker = autoware::universe_utils::createDefaultMarker( "map", rclcpp::Clock().now(), "unsafe_footprints", idx, visualization_msgs::msg::Marker::LINE_STRIP, - autoware_universe_utils::createMarkerScale(0.1, 0.0, 0.0), - autoware_universe_utils::createMarkerColor(r, g, b, 0.999)); + autoware::universe_utils::createMarkerScale(0.1, 0.0, 0.0), + autoware::universe_utils::createMarkerColor(r, g, b, 0.999)); marker.header.stamp = now; marker.lifetime = rclcpp::Duration(0, 0); @@ -221,11 +221,11 @@ MarkerArray create_distance_text_marker( const double g = marker_color.at(1); const double b = marker_color.at(2); - auto marker = autoware_universe_utils::createDefaultMarker( + auto marker = autoware::universe_utils::createDefaultMarker( "map", rclcpp::Clock().now(), "unsafe_footprints_distance", idx, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, - autoware_universe_utils::createMarkerScale(0.5, 0.5, 0.5), - autoware_universe_utils::createMarkerColor(r, g, b, 0.999)); + autoware::universe_utils::createMarkerScale(0.5, 0.5, 0.5), + autoware::universe_utils::createMarkerColor(r, g, b, 0.999)); marker.pose = pose; marker.header.stamp = now; marker.lifetime = rclcpp::Duration(0, 0); diff --git a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp index e4eaf259e95f9..7897a868ee172 100644 --- a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp +++ b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp @@ -52,12 +52,12 @@ Polygon2d createSelfPolygon( } } // namespace -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerScale; -using autoware_universe_utils::createPoint; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerScale; +using autoware::universe_utils::createPoint; SurroundObstacleCheckerDebugNode::SurroundObstacleCheckerDebugNode( const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double base_link2front, diff --git a/planning/autoware_surround_obstacle_checker/src/node.cpp b/planning/autoware_surround_obstacle_checker/src/node.cpp index 8a02c6d686736..9c899c2226497 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.cpp +++ b/planning/autoware_surround_obstacle_checker/src/node.cpp @@ -51,9 +51,9 @@ namespace autoware::surround_obstacle_checker namespace bg = boost::geometry; using Point2d = bg::model::d2::point_xy; using Polygon2d = bg::model::polygon; +using autoware::universe_utils::createPoint; +using autoware::universe_utils::pose2transform; using autoware_perception_msgs::msg::ObjectClassification; -using autoware_universe_utils::createPoint; -using autoware_universe_utils::pose2transform; namespace { @@ -193,7 +193,7 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio p.publish_debug_footprints = this->declare_parameter("publish_debug_footprints"); p.debug_footprint_label = this->declare_parameter("debug_footprint_label"); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); } vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); @@ -251,12 +251,12 @@ rcl_interfaces::msg::SetParametersResult SurroundObstacleCheckerNode::onParam( use_dynamic_object_ = false; for (const auto & label_pair : label_map_) { bool & check_current_label = node_param_.enable_check_map.at(label_pair.second); - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, label_pair.first + ".enable_check", check_current_label); use_dynamic_object_ = use_dynamic_object_ || check_current_label; } - autoware_universe_utils::updateParam( + autoware::universe_utils::updateParam( parameters, "debug_footprint_label", node_param_.debug_footprint_label); const auto check_distances = getCheckDistances(node_param_.debug_footprint_label); debug_ptr_->updateFootprintMargin( @@ -411,7 +411,7 @@ std::optional SurroundObstacleCheckerNode::getNearestObstacleByPointCl tf2::transformToEigen(transform_stamped.value().transform).cast(); pcl::PointCloud transformed_pointcloud; pcl::fromROSMsg(*pointcloud_ptr_, transformed_pointcloud); - autoware_universe_utils::transformPointCloud( + autoware::universe_utils::transformPointCloud( transformed_pointcloud, transformed_pointcloud, isometry); const double front_margin = node_param_.pointcloud_surround_check_front_distance; diff --git a/planning/autoware_surround_obstacle_checker/src/node.hpp b/planning/autoware_surround_obstacle_checker/src/node.hpp index 8a21f6cee6a32..e0bcf771948ca 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.hpp +++ b/planning/autoware_surround_obstacle_checker/src/node.hpp @@ -46,8 +46,8 @@ namespace autoware::surround_obstacle_checker { +using autoware::motion_utils::VehicleStopChecker; using autoware::vehicle_info_utils::VehicleInfo; -using autoware_motion_utils::VehicleStopChecker; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::Shape; using tier4_planning_msgs::msg::VelocityLimit; @@ -111,11 +111,11 @@ class SurroundObstacleCheckerNode : public rclcpp::Node rclcpp::TimerBase::SharedPtr timer_; // publisher and subscriber - autoware_universe_utils::InterProcessPollingSubscriber sub_odometry_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_odometry_{ this, "~/input/odometry"}; - autoware_universe_utils::InterProcessPollingSubscriber - sub_pointcloud_{this, "~/input/pointcloud", autoware_universe_utils::SingleDepthSensorQoS()}; - autoware_universe_utils::InterProcessPollingSubscriber sub_dynamic_objects_{ + autoware::universe_utils::InterProcessPollingSubscriber + sub_pointcloud_{this, "~/input/pointcloud", autoware::universe_utils::SingleDepthSensorQoS()}; + autoware::universe_utils::InterProcessPollingSubscriber sub_dynamic_objects_{ this, "~/input/objects"}; rclcpp::Publisher::SharedPtr pub_stop_reason_; rclcpp::Publisher::SharedPtr pub_clear_velocity_limit_; @@ -143,7 +143,7 @@ class SurroundObstacleCheckerNode : public rclcpp::Node State state_ = State::PASS; std::shared_ptr last_obstacle_found_time_; - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; bool use_dynamic_object_; diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp index b64f681be46fe..0dd18615be5ef 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp @@ -88,13 +88,13 @@ class VelocitySmootherNode : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_virtual_wall_; rclcpp::Publisher::SharedPtr pub_over_stop_velocity_; rclcpp::Subscription::SharedPtr sub_current_trajectory_; - autoware_universe_utils::InterProcessPollingSubscriber sub_current_odometry_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_current_odometry_{ this, "/localization/kinematic_state"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_current_acceleration_{this, "~/input/acceleration"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_external_velocity_limit_{this, "~/input/external_velocity_limit_mps"}; - autoware_universe_utils::InterProcessPollingSubscriber sub_operation_mode_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_operation_mode_{ this, "~/input/operation_mode_state"}; Odometry::ConstSharedPtr current_odometry_ptr_; // current odometry @@ -245,7 +245,7 @@ class VelocitySmootherNode : public rclcpp::Node void initCommonParam(); // debug - autoware_universe_utils::StopWatch stop_watch_; + autoware::universe_utils::StopWatch stop_watch_; std::shared_ptr prev_time_; double prev_acc_; rclcpp::Publisher::SharedPtr pub_dist_to_stopline_; @@ -273,8 +273,8 @@ class VelocitySmootherNode : public rclcpp::Node void flipVelocity(TrajectoryPoints & points) const; void publishStopWatchTime(); - std::unique_ptr logger_configure_; - std::unique_ptr published_time_publisher_; + std::unique_ptr logger_configure_; + std::unique_ptr published_time_publisher_; }; } // namespace autoware::velocity_smoother diff --git a/planning/autoware_velocity_smoother/src/node.cpp b/planning/autoware_velocity_smoother/src/node.cpp index 42c5f1657999c..aefbd9ef20f84 100644 --- a/planning/autoware_velocity_smoother/src/node.cpp +++ b/planning/autoware_velocity_smoother/src/node.cpp @@ -90,9 +90,9 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti clock_ = get_clock(); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } void VelocitySmootherNode::setupSmoother(const double wheelbase) @@ -300,7 +300,7 @@ void VelocitySmootherNode::initCommonParam() void VelocitySmootherNode::publishTrajectory(const TrajectoryPoints & trajectory) const { - Trajectory publishing_trajectory = autoware_motion_utils::convertToTrajectory(trajectory); + Trajectory publishing_trajectory = autoware::motion_utils::convertToTrajectory(trajectory); publishing_trajectory.header = base_traj_raw_ptr_->header; pub_trajectory_->publish(publishing_trajectory); published_time_publisher_->publish_if_subscribed( @@ -434,10 +434,10 @@ void VelocitySmootherNode::onCurrentTrajectory(const Trajectory::ConstSharedPtr } // calculate trajectory velocity - auto input_points = autoware_motion_utils::convertToTrajectoryPointArray(*base_traj_raw_ptr_); + auto input_points = autoware::motion_utils::convertToTrajectoryPointArray(*base_traj_raw_ptr_); // guard for invalid trajectory - input_points = autoware_motion_utils::removeOverlapPoints(input_points); + input_points = autoware::motion_utils::removeOverlapPoints(input_points); if (input_points.size() < 2) { RCLCPP_ERROR(get_logger(), "No enough points in trajectory after overlap points removal"); return; @@ -687,7 +687,7 @@ void VelocitySmootherNode::insertBehindVelocity( // TODO(planning/control team) deal with overlapped lanes with the same direction const size_t seg_idx = [&]() { // with distance and yaw thresholds - const auto opt_nearest_seg_idx = autoware_motion_utils::findNearestSegmentIndex( + const auto opt_nearest_seg_idx = autoware::motion_utils::findNearestSegmentIndex( prev_output_, output.at(i).pose, node_param_.ego_nearest_dist_threshold, node_param_.ego_nearest_yaw_threshold); if (opt_nearest_seg_idx) { @@ -695,13 +695,13 @@ void VelocitySmootherNode::insertBehindVelocity( } // with distance threshold - const auto opt_second_nearest_seg_idx = autoware_motion_utils::findNearestSegmentIndex( + const auto opt_second_nearest_seg_idx = autoware::motion_utils::findNearestSegmentIndex( prev_output_, output.at(i).pose, node_param_.ego_nearest_dist_threshold); if (opt_second_nearest_seg_idx) { return opt_second_nearest_seg_idx.value(); } - return autoware_motion_utils::findNearestSegmentIndex( + return autoware::motion_utils::findNearestSegmentIndex( prev_output_, output.at(i).pose.position); }(); const auto prev_output_point = @@ -722,9 +722,9 @@ void VelocitySmootherNode::publishStopDistance(const TrajectoryPoints & trajecto // stop distance calculation const double stop_dist_lim{50.0}; double stop_dist{stop_dist_lim}; - const auto stop_idx{autoware_motion_utils::searchZeroVelocityIndex(trajectory)}; + const auto stop_idx{autoware::motion_utils::searchZeroVelocityIndex(trajectory)}; if (stop_idx) { - stop_dist = autoware_motion_utils::calcSignedArcLength(trajectory, closest, *stop_idx); + stop_dist = autoware::motion_utils::calcSignedArcLength(trajectory, closest, *stop_idx); } else { stop_dist = closest > 0 ? stop_dist : -stop_dist; } @@ -820,14 +820,14 @@ std::pair VelocitySmootherNode::ca void VelocitySmootherNode::overwriteStopPoint( const TrajectoryPoints & input, TrajectoryPoints & output) const { - const auto stop_idx = autoware_motion_utils::searchZeroVelocityIndex(input); + const auto stop_idx = autoware::motion_utils::searchZeroVelocityIndex(input); if (!stop_idx) { return; } // Get Closest Point from Output // TODO(planning/control team) deal with overlapped lanes with the same directions - const auto nearest_output_point_idx = autoware_motion_utils::findNearestIndex( + const auto nearest_output_point_idx = autoware::motion_utils::findNearestIndex( output, input.at(*stop_idx).pose, node_param_.ego_nearest_dist_threshold, node_param_.ego_nearest_yaw_threshold); @@ -876,11 +876,11 @@ void VelocitySmootherNode::applyExternalVelocityLimit(TrajectoryPoints & traj) c // insert the point at the distance of external velocity limit const auto & current_pose = current_odometry_ptr_->pose.pose; const size_t closest_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( traj, current_pose, node_param_.ego_nearest_dist_threshold, node_param_.ego_nearest_yaw_threshold); const auto inserted_index = - autoware_motion_utils::insertTargetPoint(closest_seg_idx, external_velocity_limit_.dist, traj); + autoware::motion_utils::insertTargetPoint(closest_seg_idx, external_velocity_limit_.dist, traj); if (!inserted_index) { traj.back().longitudinal_velocity_mps = std::min( traj.back().longitudinal_velocity_mps, static_cast(external_velocity_limit_.velocity)); @@ -893,7 +893,7 @@ void VelocitySmootherNode::applyExternalVelocityLimit(TrajectoryPoints & traj) c // create virtual wall if (std::abs(external_velocity_limit_.velocity) < 1e-3) { - const auto virtual_wall_marker = autoware_motion_utils::createStopVirtualWallMarker( + const auto virtual_wall_marker = autoware::motion_utils::createStopVirtualWallMarker( traj.at(*inserted_index).pose, external_velocity_limit_.sender, this->now(), 0, base_link2front_); pub_virtual_wall_->publish(virtual_wall_marker); @@ -905,13 +905,13 @@ void VelocitySmootherNode::applyExternalVelocityLimit(TrajectoryPoints & traj) c void VelocitySmootherNode::applyStopApproachingVelocity(TrajectoryPoints & traj) const { - const auto stop_idx = autoware_motion_utils::searchZeroVelocityIndex(traj); + const auto stop_idx = autoware::motion_utils::searchZeroVelocityIndex(traj); if (!stop_idx) { return; // no stop point. } double distance_sum = 0.0; for (size_t i = *stop_idx - 1; i < traj.size(); --i) { // search backward - distance_sum += autoware_universe_utils::calcDistance2d(traj.at(i), traj.at(i + 1)); + distance_sum += autoware::universe_utils::calcDistance2d(traj.at(i), traj.at(i + 1)); if (distance_sum > node_param_.stopping_distance) { break; } @@ -1022,7 +1022,7 @@ double VelocitySmootherNode::calcTravelDistance() const if (prev_closest_point_) { const double travel_dist = - autoware_universe_utils::calcDistance2d(*prev_closest_point_, closest_point); + autoware::universe_utils::calcDistance2d(*prev_closest_point_, closest_point); return travel_dist; } @@ -1039,14 +1039,14 @@ bool VelocitySmootherNode::isEngageStatus(const double target_vel) const Trajectory VelocitySmootherNode::toTrajectoryMsg( const TrajectoryPoints & points, const std_msgs::msg::Header * header) const { - auto trajectory = autoware_motion_utils::convertToTrajectory(points); + auto trajectory = autoware::motion_utils::convertToTrajectory(points); trajectory.header = header ? *header : base_traj_raw_ptr_->header; return trajectory; } size_t VelocitySmootherNode::findNearestIndexFromEgo(const TrajectoryPoints & points) const { - return autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( points, current_odometry_ptr_->pose.pose, node_param_.ego_nearest_dist_threshold, node_param_.ego_nearest_yaw_threshold); } @@ -1077,7 +1077,7 @@ TrajectoryPoint VelocitySmootherNode::calcProjectedTrajectoryPoint( const TrajectoryPoints & trajectory, const Pose & pose) const { const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( trajectory, pose, node_param_.ego_nearest_dist_threshold, node_param_.ego_nearest_yaw_threshold); return trajectory_utils::calcInterpolatedTrajectoryPoint(trajectory, pose, current_seg_idx); diff --git a/planning/autoware_velocity_smoother/src/resample.cpp b/planning/autoware_velocity_smoother/src/resample.cpp index f24dc17df0538..f69ad5a592272 100644 --- a/planning/autoware_velocity_smoother/src/resample.cpp +++ b/planning/autoware_velocity_smoother/src/resample.cpp @@ -33,17 +33,17 @@ TrajectoryPoints resampleTrajectory( { // Arc length from the initial point to the closest point const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( input, current_pose, nearest_dist_threshold, nearest_yaw_threshold); - const double negative_front_arclength_value = autoware_motion_utils::calcSignedArcLength( + const double negative_front_arclength_value = autoware::motion_utils::calcSignedArcLength( input, current_pose.position, current_seg_idx, input.at(0).pose.position, 0); const auto front_arclength_value = std::fabs(negative_front_arclength_value); const auto dist_to_closest_stop_point = - autoware_motion_utils::calcDistanceToForwardStopPoint(input, current_pose); + autoware::motion_utils::calcDistanceToForwardStopPoint(input, current_pose); // Get the resample size from the closest point - const double trajectory_length = autoware_motion_utils::calcArcLength(input); + const double trajectory_length = autoware::motion_utils::calcArcLength(input); const double Nt = param.resample_time / std::max(param.dense_resample_dt, 0.001); const double ds_nominal = std::max(v_current * param.dense_resample_dt, param.dense_min_interval_distance); @@ -128,14 +128,14 @@ TrajectoryPoints resampleTrajectory( return input; } - const auto output_traj = autoware_motion_utils::resampleTrajectory( - autoware_motion_utils::convertToTrajectory(input), out_arclength, false, true, use_zoh_for_v); - auto output = autoware_motion_utils::convertToTrajectoryPointArray(output_traj); + const auto output_traj = autoware::motion_utils::resampleTrajectory( + autoware::motion_utils::convertToTrajectory(input), out_arclength, false, true, use_zoh_for_v); + auto output = autoware::motion_utils::convertToTrajectoryPointArray(output_traj); // add end point directly to consider the endpoint velocity. if (is_endpoint_included) { constexpr double ep_dist = 1.0E-3; - if (autoware_universe_utils::calcDistance2d(output.back(), input.back()) < ep_dist) { + if (autoware::universe_utils::calcDistance2d(output.back(), input.back()) < ep_dist) { output.back() = input.back(); } else { output.push_back(input.back()); @@ -151,9 +151,9 @@ TrajectoryPoints resampleTrajectory( const ResampleParam & param, const double nominal_ds, const bool use_zoh_for_v) { // input arclength - const double trajectory_length = autoware_motion_utils::calcArcLength(input); + const double trajectory_length = autoware::motion_utils::calcArcLength(input); const auto dist_to_closest_stop_point = - autoware_motion_utils::calcDistanceToForwardStopPoint(input, current_pose); + autoware::motion_utils::calcDistanceToForwardStopPoint(input, current_pose); // distance to stop point double stop_arclength_value = param.max_trajectory_length; @@ -172,9 +172,9 @@ TrajectoryPoints resampleTrajectory( // Step1. Resample front trajectory // Arc length from the initial point to the closest point const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( input, current_pose, nearest_dist_threshold, nearest_yaw_threshold); - const double negative_front_arclength_value = autoware_motion_utils::calcSignedArcLength( + const double negative_front_arclength_value = autoware::motion_utils::calcSignedArcLength( input, current_pose.position, current_seg_idx, input.at(0).pose.position, static_cast(0)); const auto front_arclength_value = std::fabs(negative_front_arclength_value); @@ -248,14 +248,14 @@ TrajectoryPoints resampleTrajectory( return input; } - const auto output_traj = autoware_motion_utils::resampleTrajectory( - autoware_motion_utils::convertToTrajectory(input), out_arclength, false, true, use_zoh_for_v); - auto output = autoware_motion_utils::convertToTrajectoryPointArray(output_traj); + const auto output_traj = autoware::motion_utils::resampleTrajectory( + autoware::motion_utils::convertToTrajectory(input), out_arclength, false, true, use_zoh_for_v); + auto output = autoware::motion_utils::convertToTrajectoryPointArray(output_traj); // add end point directly to consider the endpoint velocity. if (is_endpoint_included) { constexpr double ep_dist = 1.0E-3; - if (autoware_universe_utils::calcDistance2d(output.back(), input.back()) < ep_dist) { + if (autoware::universe_utils::calcDistance2d(output.back(), input.back()) < ep_dist) { output.back() = input.back(); } else { output.push_back(input.back()); diff --git a/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp index 27b54ccf8bf2b..7f263fdea5e36 100644 --- a/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp @@ -252,7 +252,7 @@ TrajectoryPoints AnalyticalJerkConstrainedSmoother::resampleTrajectory( const auto tp1 = input.at(i + 1); const double dist_thr = 0.001; // 1mm - const double dist_tp0_tp1 = autoware_universe_utils::calcDistance2d(tp0, tp1); + const double dist_tp0_tp1 = autoware::universe_utils::calcDistance2d(tp0, tp1); if (std::fabs(dist_tp0_tp1) < dist_thr) { output.push_back(input.at(i)); continue; @@ -298,9 +298,9 @@ TrajectoryPoints AnalyticalJerkConstrainedSmoother::applyLateralAccelerationFilt for (double s = 0; s < in_arclength.back(); s += points_interval) { out_arclength.push_back(s); } - const auto output_traj = autoware_motion_utils::resampleTrajectory( - autoware_motion_utils::convertToTrajectory(input), out_arclength); - output = autoware_motion_utils::convertToTrajectoryPointArray(output_traj); + const auto output_traj = autoware::motion_utils::resampleTrajectory( + autoware::motion_utils::convertToTrajectory(input), out_arclength); + output = autoware::motion_utils::convertToTrajectoryPointArray(output_traj); output.back() = input.back(); // keep the final speed. } else { output = input; @@ -355,7 +355,7 @@ TrajectoryPoints AnalyticalJerkConstrainedSmoother::applyLateralAccelerationFilt } if ( - autoware_universe_utils::calcDistance2d(output.at(end_index), output.at(index)) < + autoware::universe_utils::calcDistance2d(output.at(end_index), output.at(index)) < dist_threshold) { end_index = index; min_latacc_velocity = std::min( @@ -441,7 +441,7 @@ bool AnalyticalJerkConstrainedSmoother::applyForwardJerkFilter( for (size_t i = start_index + 1; i < base_trajectory.size(); ++i) { const double prev_vel = output_trajectory.at(i - 1).longitudinal_velocity_mps; const double ds = - autoware_universe_utils::calcDistance2d(base_trajectory.at(i - 1), base_trajectory.at(i)); + autoware::universe_utils::calcDistance2d(base_trajectory.at(i - 1), base_trajectory.at(i)); const double dt = ds / std::max(prev_vel, 1.0); const double prev_acc = output_trajectory.at(i - 1).acceleration_mps2; @@ -487,7 +487,7 @@ bool AnalyticalJerkConstrainedSmoother::applyBackwardDecelFilter( } } for (size_t i = decel_target_index; i > start_index; --i) { - dist += autoware_universe_utils::calcDistance2d( + dist += autoware::universe_utils::calcDistance2d( output_trajectory.at(i - 1), output_trajectory.at(i)); dist_to_target.at(i - 1) = dist; } diff --git a/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp b/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp index fd9c4f34b4dc7..739ba6e7cef38 100644 --- a/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp @@ -225,8 +225,8 @@ bool calcStopVelocityWithConstantJerkAccLimit( std::vector distances; distances.push_back(distance); for (size_t i = start_index; i < output_trajectory.size() - 1; ++i) { - distance += - autoware_universe_utils::calcDistance2d(output_trajectory.at(i), output_trajectory.at(i + 1)); + distance += autoware::universe_utils::calcDistance2d( + output_trajectory.at(i), output_trajectory.at(i + 1)); if (distance > xs.back()) { break; } diff --git a/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp index 9f9f50b955757..cab8e49a3b45d 100644 --- a/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp @@ -131,7 +131,7 @@ bool JerkFilteredSmoother::apply( // to avoid getting 0 as a stop point, search zero velocity index from 1. // the size of the resampled trajectory must not be less than 2. - const auto zero_vel_id = autoware_motion_utils::searchZeroVelocityIndex( + const auto zero_vel_id = autoware::motion_utils::searchZeroVelocityIndex( opt_resampled_trajectory, 1, opt_resampled_trajectory.size()); if (!zero_vel_id) { @@ -385,7 +385,7 @@ TrajectoryPoints JerkFilteredSmoother::forwardJerkFilter( output.front().longitudinal_velocity_mps = current_vel; output.front().acceleration_mps2 = current_acc; for (size_t i = 1; i < input.size(); ++i) { - const double ds = autoware_universe_utils::calcDistance2d(input.at(i), input.at(i - 1)); + const double ds = autoware::universe_utils::calcDistance2d(input.at(i), input.at(i - 1)); const double max_dt = std::pow(6.0 * ds / j_max, 1.0 / 3.0); // assuming v0 = a0 = 0. const double dt = std::min(ds / std::max(current_vel, 1.0e-6), max_dt); @@ -439,8 +439,8 @@ TrajectoryPoints JerkFilteredSmoother::mergeFilteredTrajectory( merged.at(i).longitudinal_velocity_mps = current_vel; merged.at(i).acceleration_mps2 = current_acc; - const double ds = - autoware_universe_utils::calcDistance2d(forward_filtered.at(i + 1), forward_filtered.at(i)); + const double ds = autoware::universe_utils::calcDistance2d( + forward_filtered.at(i + 1), forward_filtered.at(i)); const double max_dt = std::pow(6.0 * ds / std::fabs(j_min), 1.0 / 3.0); // assuming v0 = a0 = 0. const double dt = std::min(ds / std::max(current_vel, 1.0e-6), max_dt); diff --git a/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp b/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp index a1972d5dbc1e0..700cf45b7eb9d 100644 --- a/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp @@ -34,10 +34,10 @@ namespace TrajectoryPoints applyPreProcess( const TrajectoryPoints & input, const double interval, const bool use_resampling) { - using autoware_motion_utils::calcArcLength; - using autoware_motion_utils::convertToTrajectory; - using autoware_motion_utils::convertToTrajectoryPointArray; - using autoware_motion_utils::resampleTrajectory; + using autoware::motion_utils::calcArcLength; + using autoware::motion_utils::convertToTrajectory; + using autoware::motion_utils::convertToTrajectoryPointArray; + using autoware::motion_utils::resampleTrajectory; if (!use_resampling) { return input; @@ -141,13 +141,13 @@ TrajectoryPoints SmootherBase::applyLateralAccelerationFilter( // since the resampling takes a long time, omit the resampling when it is not requested if (use_resampling) { std::vector out_arclength; - const auto traj_length = autoware_motion_utils::calcArcLength(input); + const auto traj_length = autoware::motion_utils::calcArcLength(input); for (double s = 0; s < traj_length; s += points_interval) { out_arclength.push_back(s); } - const auto output_traj = autoware_motion_utils::resampleTrajectory( - autoware_motion_utils::convertToTrajectory(input), out_arclength); - output = autoware_motion_utils::convertToTrajectoryPointArray(output_traj); + const auto output_traj = autoware::motion_utils::resampleTrajectory( + autoware::motion_utils::convertToTrajectory(input), out_arclength); + output = autoware::motion_utils::convertToTrajectoryPointArray(output_traj); output.back() = input.back(); // keep the final speed. } else { output = input; @@ -249,7 +249,7 @@ TrajectoryPoints SmootherBase::applySteeringRateLimit( } const auto steer_rate = steer_rate_arr.at(i); - if (steer_rate < autoware_universe_utils::deg2rad(base_param_.max_steering_angle_rate)) { + if (steer_rate < autoware::universe_utils::deg2rad(base_param_.max_steering_angle_rate)) { continue; } @@ -257,7 +257,7 @@ TrajectoryPoints SmootherBase::applySteeringRateLimit( (output.at(i).longitudinal_velocity_mps + output.at(i + 1).longitudinal_velocity_mps) / 2.0; const auto target_mean_vel = mean_vel * - (autoware_universe_utils::deg2rad(base_param_.max_steering_angle_rate) / steer_rate); + (autoware::universe_utils::deg2rad(base_param_.max_steering_angle_rate) / steer_rate); for (size_t k = 0; k < 2; k++) { auto & velocity = output.at(i + k).longitudinal_velocity_mps; diff --git a/planning/autoware_velocity_smoother/src/trajectory_utils.cpp b/planning/autoware_velocity_smoother/src/trajectory_utils.cpp index 94fa668fa576c..ea0453370e03a 100644 --- a/planning/autoware_velocity_smoother/src/trajectory_utils.cpp +++ b/planning/autoware_velocity_smoother/src/trajectory_utils.cpp @@ -34,7 +34,7 @@ inline void convertEulerAngleToMonotonic(std::vector & a) { for (unsigned int i = 1; i < a.size(); ++i) { const double da = a[i] - a[i - 1]; - a[i] = a[i - 1] + autoware_universe_utils::normalizeRadian(da); + a[i] = a[i - 1] + autoware::universe_utils::normalizeRadian(da); } } @@ -87,7 +87,7 @@ TrajectoryPoint calcInterpolatedTrajectoryPoint( { const auto & seg_pt = trajectory.at(seg_idx); const auto & next_pt = trajectory.at(seg_idx + 1); - traj_p.pose = autoware_universe_utils::calcInterpolatedPose(seg_pt.pose, next_pt.pose, prop); + traj_p.pose = autoware::universe_utils::calcInterpolatedPose(seg_pt.pose, next_pt.pose, prop); traj_p.longitudinal_velocity_mps = interpolation::lerp( seg_pt.longitudinal_velocity_mps, next_pt.longitudinal_velocity_mps, prop); traj_p.acceleration_mps2 = @@ -110,7 +110,7 @@ TrajectoryPoints extractPathAroundIndex( { double dist_sum = 0.0; for (size_t i = index; i < trajectory.size() - 1; ++i) { - dist_sum += autoware_universe_utils::calcDistance2d(trajectory.at(i), trajectory.at(i + 1)); + dist_sum += autoware::universe_utils::calcDistance2d(trajectory.at(i), trajectory.at(i + 1)); if (dist_sum > ahead_length) { ahead_index = i + 1; break; @@ -123,7 +123,7 @@ TrajectoryPoints extractPathAroundIndex( { double dist_sum{0.0}; for (size_t i = index; i != 0; --i) { - dist_sum += autoware_universe_utils::calcDistance2d(trajectory.at(i), trajectory[i - 1]); + dist_sum += autoware::universe_utils::calcDistance2d(trajectory.at(i), trajectory[i - 1]); if (dist_sum > behind_length) { behind_index = i - 1; break; @@ -152,7 +152,7 @@ std::vector calcArclengthArray(const TrajectoryPoints & trajectory) for (unsigned int i = 1; i < trajectory.size(); ++i) { const TrajectoryPoint tp = trajectory.at(i); const TrajectoryPoint tp_prev = trajectory.at(i - 1); - dist += autoware_universe_utils::calcDistance2d(tp.pose, tp_prev.pose); + dist += autoware::universe_utils::calcDistance2d(tp.pose, tp_prev.pose); arclength.at(i) = dist; } return arclength; @@ -164,7 +164,7 @@ std::vector calcTrajectoryIntervalDistance(const TrajectoryPoints & traj for (unsigned int i = 1; i < trajectory.size(); ++i) { const TrajectoryPoint tp = trajectory.at(i); const TrajectoryPoint tp_prev = trajectory.at(i - 1); - const double dist = autoware_universe_utils::calcDistance2d(tp.pose, tp_prev.pose); + const double dist = autoware::universe_utils::calcDistance2d(tp.pose, tp_prev.pose); intervals.push_back(dist); } return intervals; @@ -173,8 +173,8 @@ std::vector calcTrajectoryIntervalDistance(const TrajectoryPoints & traj std::vector calcTrajectoryCurvatureFrom3Points( const TrajectoryPoints & trajectory, size_t idx_dist) { - using autoware_universe_utils::calcCurvature; - using autoware_universe_utils::getPoint; + using autoware::universe_utils::calcCurvature; + using autoware::universe_utils::getPoint; if (trajectory.size() < 3) { const std::vector k_arr(trajectory.size(), 0.0); @@ -595,7 +595,7 @@ std::vector calcVelocityProfileWithConstantJerkAndAccelerationLimit( double calcStopDistance(const TrajectoryPoints & trajectory, const size_t closest) { - const auto idx = autoware_motion_utils::searchZeroVelocityIndex(trajectory); + const auto idx = autoware::motion_utils::searchZeroVelocityIndex(trajectory); if (!idx) { return std::numeric_limits::max(); // stop point is located far away @@ -603,7 +603,7 @@ double calcStopDistance(const TrajectoryPoints & trajectory, const size_t closes // TODO(Horibe): use arc length distance const double stop_dist = - autoware_universe_utils::calcDistance2d(trajectory.at(*idx), trajectory.at(closest)); + autoware::universe_utils::calcDistance2d(trajectory.at(*idx), trajectory.at(closest)); return stop_dist; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp index 267963dc32681..02b90186d9b2f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp @@ -32,8 +32,8 @@ using autoware::behavior_path_planner::ObjectParameter; void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) { + using autoware::universe_utils::getOrDeclareParameter; using autoware_perception_msgs::msg::ObjectClassification; - using autoware_universe_utils::getOrDeclareParameter; // init manager interface initInterface(node, {"left", "right"}); diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp index 247f94c63fc8f..a19cbda6ccad7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -195,9 +195,9 @@ void AvoidanceByLaneChange::fillAvoidanceTargetObjects( std::optional AvoidanceByLaneChange::createObjectData( const AvoidancePlanningData & data, const PredictedObject & object) const { - using autoware_motion_utils::findNearestIndex; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::calcLateralDeviation; + using autoware::motion_utils::findNearestIndex; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::calcLateralDeviation; using boost::geometry::return_centroid; const auto p = std::dynamic_pointer_cast(avoidance_parameters_); diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp index 53ecf19b8215f..6ea15a9309c3c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp @@ -57,8 +57,8 @@ std::vector getAllKeys(const std::unordered_map & map) namespace autoware::behavior_path_planner { +using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::PredictedPath; -using autoware_universe_utils::Polygon2d; using tier4_planning_msgs::msg::PathWithLaneId; struct MinMaxValue @@ -176,7 +176,7 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface const PredictedObject & predicted_object, const double arg_vel, const double arg_lat_vel, const bool arg_is_object_on_ego_path, const std::optional & arg_latest_time_inside_ego_path) - : uuid(autoware_universe_utils::toHexString(predicted_object.object_id)), + : uuid(autoware::universe_utils::toHexString(predicted_object.object_id)), label(predicted_object.classification.front().label), pose(predicted_object.kinematics.initial_pose_with_covariance.pose), shape(predicted_object.shape), @@ -374,8 +374,8 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface }; struct EgoPathReservePoly { - const autoware_universe_utils::Polygon2d left_avoid; - const autoware_universe_utils::Polygon2d right_avoid; + const autoware::universe_utils::Polygon2d left_avoid; + const autoware::universe_utils::Polygon2d right_avoid; }; bool canTransitSuccessState() override; @@ -431,11 +431,11 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface const DynamicAvoidanceObject & object) const; std::pair getAdjacentLanes( const double forward_distance, const double backward_distance) const; - std::optional calcEgoPathBasedDynamicObstaclePolygon( + std::optional calcEgoPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const; - std::optional calcObjectPathBasedDynamicObstaclePolygon( + std::optional calcObjectPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const; - std::optional calcPredictedPathBasedDynamicObstaclePolygon( + std::optional calcPredictedPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object, const EgoPathReservePoly & ego_path_poly) const; EgoPathReservePoly calcEgoPathReservePoly(const PathWithLaneId & ego_path) const; @@ -455,7 +455,7 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface TargetObjectsManager target_objects_manager_; - mutable autoware_universe_utils::StopWatch< + mutable autoware::universe_utils::StopWatch< std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> stop_watch_; }; diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp index 9b0db95bb0df5..eccf2b2a1bfde 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp @@ -152,7 +152,7 @@ void DynamicObstacleAvoidanceModuleManager::init(rclcpp::Node * node) void DynamicObstacleAvoidanceModuleManager::updateModuleParams( [[maybe_unused]] const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; auto & p = parameters_; { // common diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp index 0c8ec1c530b7a..8b411340e4ddc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp @@ -41,7 +41,7 @@ namespace autoware::behavior_path_planner { namespace { -geometry_msgs::msg::Point toGeometryPoint(const autoware_universe_utils::Point2d & point) +geometry_msgs::msg::Point toGeometryPoint(const autoware::universe_utils::Point2d & point) { geometry_msgs::msg::Point geom_obj_point; geom_obj_point.x = point.x(); @@ -65,25 +65,25 @@ MinMaxValue combineMinMaxValues(const MinMaxValue & r1, const MinMaxValue & r2) void appendObjectMarker(MarkerArray & marker_array, const geometry_msgs::msg::Pose & obj_pose) { - auto marker = autoware_universe_utils::createDefaultMarker( + auto marker = autoware::universe_utils::createDefaultMarker( "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "dynamic_objects_to_avoid", marker_array.markers.size(), visualization_msgs::msg::Marker::CUBE, - autoware_universe_utils::createMarkerScale(3.0, 1.0, 1.0), - autoware_universe_utils::createMarkerColor(1.0, 0.5, 0.6, 0.8)); + autoware::universe_utils::createMarkerScale(3.0, 1.0, 1.0), + autoware::universe_utils::createMarkerColor(1.0, 0.5, 0.6, 0.8)); marker.pose = obj_pose; marker_array.markers.push_back(marker); } void appendExtractedPolygonMarker( - MarkerArray & marker_array, const autoware_universe_utils::Polygon2d & obj_poly, + MarkerArray & marker_array, const autoware::universe_utils::Polygon2d & obj_poly, const double obj_z) { - auto marker = autoware_universe_utils::createDefaultMarker( + auto marker = autoware::universe_utils::createDefaultMarker( "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "extracted_polygons", marker_array.markers.size(), visualization_msgs::msg::Marker::LINE_STRIP, - autoware_universe_utils::createMarkerScale(0.1, 0.0, 0.0), - autoware_universe_utils::createMarkerColor(1.0, 0.5, 0.6, 0.8)); + autoware::universe_utils::createMarkerScale(0.1, 0.0, 0.0), + autoware::universe_utils::createMarkerColor(1.0, 0.5, 0.6, 0.8)); // NOTE: obj_poly.outer() has already duplicated points to close the polygon. for (size_t i = 0; i < obj_poly.outer().size(); ++i) { @@ -117,7 +117,7 @@ std::pair projectObstacleVelocityToTrajectory( { const auto & obj_pose = object.kinematics.initial_pose_with_covariance.pose; const double obj_yaw = tf2::getYaw(obj_pose.orientation); - const size_t obj_idx = autoware_motion_utils::findNearestIndex(path_points, obj_pose.position); + const size_t obj_idx = autoware::motion_utils::findNearestIndex(path_points, obj_pose.position); const double path_yaw = tf2::getYaw(path_points.at(obj_idx).point.pose.orientation); const Eigen::Rotation2Dd R_ego_to_obstacle(obj_yaw - path_yaw); @@ -173,19 +173,19 @@ double calcDiffAngleAgainstPath( const geometry_msgs::msg::Pose & target_pose) { const size_t nearest_idx = - autoware_motion_utils::findNearestIndex(path_points, target_pose.position); + autoware::motion_utils::findNearestIndex(path_points, target_pose.position); const double traj_yaw = tf2::getYaw(path_points.at(nearest_idx).point.pose.orientation); const double target_yaw = tf2::getYaw(target_pose.orientation); - const double diff_yaw = autoware_universe_utils::normalizeRadian(target_yaw - traj_yaw); + const double diff_yaw = autoware::universe_utils::normalizeRadian(target_yaw - traj_yaw); return diff_yaw; } [[maybe_unused]] double calcDiffAngleBetweenPaths( const std::vector & path_points, const PredictedPath & predicted_path) { - const size_t nearest_idx = autoware_motion_utils::findNearestSegmentIndex( + const size_t nearest_idx = autoware::motion_utils::findNearestSegmentIndex( path_points, predicted_path.path.front().position); const double ego_yaw = tf2::getYaw(path_points.at(nearest_idx).point.pose.orientation); @@ -193,7 +193,7 @@ double calcDiffAngleAgainstPath( double signed_max_angle{0.0}; for (size_t i = 0; i < std::min(max_predicted_path_size, predicted_path.path.size()); ++i) { const double obj_yaw = tf2::getYaw(predicted_path.path.at(i).orientation); - const double diff_yaw = autoware_universe_utils::normalizeRadian(obj_yaw - ego_yaw); + const double diff_yaw = autoware::universe_utils::normalizeRadian(obj_yaw - ego_yaw); if (std::abs(signed_max_angle) < std::abs(diff_yaw)) { signed_max_angle = diff_yaw; } @@ -205,34 +205,34 @@ double calcDistanceToPath( const std::vector & path_points, const geometry_msgs::msg::Point & target_pos) { - const size_t target_idx = autoware_motion_utils::findNearestIndex(path_points, target_pos); + const size_t target_idx = autoware::motion_utils::findNearestIndex(path_points, target_pos); if (target_idx == 0 || target_idx == path_points.size() - 1) { const double target_yaw = tf2::getYaw(path_points.at(target_idx).point.pose.orientation); - const double angle_to_target_pos = autoware_universe_utils::calcAzimuthAngle( + const double angle_to_target_pos = autoware::universe_utils::calcAzimuthAngle( path_points.at(target_idx).point.pose.position, target_pos); const double diff_yaw = - autoware_universe_utils::normalizeRadian(angle_to_target_pos - target_yaw); + autoware::universe_utils::normalizeRadian(angle_to_target_pos - target_yaw); if ( (target_idx == 0 && (diff_yaw < -M_PI_2 || M_PI_2 < diff_yaw)) || (target_idx == path_points.size() - 1 && (-M_PI_2 < diff_yaw && diff_yaw < M_PI_2))) { - return autoware_universe_utils::calcDistance2d(path_points.at(target_idx), target_pos); + return autoware::universe_utils::calcDistance2d(path_points.at(target_idx), target_pos); } } - return std::abs(autoware_motion_utils::calcLateralOffset(path_points, target_pos)); + return std::abs(autoware::motion_utils::calcLateralOffset(path_points, target_pos)); } bool isLeft( const std::vector & path_points, const geometry_msgs::msg::Point & target_pos) { - const size_t target_idx = autoware_motion_utils::findNearestIndex(path_points, target_pos); + const size_t target_idx = autoware::motion_utils::findNearestIndex(path_points, target_pos); const double target_yaw = tf2::getYaw(path_points.at(target_idx).point.pose.orientation); - const double angle_to_target_pos = autoware_universe_utils::calcAzimuthAngle( + const double angle_to_target_pos = autoware::universe_utils::calcAzimuthAngle( path_points.at(target_idx).point.pose.position, target_pos); const double diff_yaw = - autoware_universe_utils::normalizeRadian(angle_to_target_pos - target_yaw); + autoware::universe_utils::normalizeRadian(angle_to_target_pos - target_yaw); if (0 < diff_yaw) { return true; @@ -283,7 +283,7 @@ std::optional> intersectLines( ++source_seg_idx) { for (int target_seg_idx = 0; target_seg_idx < static_cast(target_line.size()) - 1; ++target_seg_idx) { - const auto intersect_point = autoware_universe_utils::intersect( + const auto intersect_point = autoware::universe_utils::intersect( source_line.at(source_seg_idx).position, source_line.at(source_seg_idx + 1).position, target_line.at(target_seg_idx), target_line.at(target_seg_idx + 1)); if (intersect_point) { @@ -329,7 +329,7 @@ bool DynamicObstacleAvoidanceModule::isExecutionRequested() const } // check if the ego is driving forward - const auto is_driving_forward = autoware_motion_utils::isDrivingForward(input_path.points); + const auto is_driving_forward = autoware::motion_utils::isDrivingForward(input_path.points); if (!is_driving_forward || !(*is_driving_forward)) { return false; } @@ -498,7 +498,7 @@ void DynamicObstacleAvoidanceModule::registerRegulatedObjects( const auto & predicted_objects = planner_data_->dynamic_object->objects; for (const auto & predicted_object : predicted_objects) { - const auto obj_uuid = autoware_universe_utils::toHexString(predicted_object.object_id); + const auto obj_uuid = autoware::universe_utils::toHexString(predicted_object.object_id); const auto & obj_pose = predicted_object.kinematics.initial_pose_with_covariance.pose; const double obj_vel_norm = std::hypot( predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x, @@ -586,7 +586,7 @@ void DynamicObstacleAvoidanceModule::registerUnregulatedObjects( const auto & predicted_objects = planner_data_->dynamic_object->objects; for (const auto & predicted_object : predicted_objects) { - const auto obj_uuid = autoware_universe_utils::toHexString(predicted_object.object_id); + const auto obj_uuid = autoware::universe_utils::toHexString(predicted_object.object_id); const auto & obj_pose = predicted_object.kinematics.initial_pose_with_covariance.pose; const double obj_vel_norm = std::hypot( predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x, @@ -626,7 +626,7 @@ void DynamicObstacleAvoidanceModule::registerUnregulatedObjects( // 1.f. calculate the object is on ego's path or not const double dist_obj_center_to_path = - std::abs(autoware_motion_utils::calcLateralOffset(input_path.points, obj_pose.position)); + std::abs(autoware::motion_utils::calcLateralOffset(input_path.points, obj_pose.position)); const bool is_object_on_ego_path = dist_obj_center_to_path < planner_data_->parameters.vehicle_width / 2.0 + parameters_->min_obj_lat_offset_to_ego_path; @@ -766,7 +766,7 @@ void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstRegulatedObje // 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 double lon_offset_ego_to_obj = autoware_motion_utils::calcSignedArcLength( + const double lon_offset_ego_to_obj = autoware::motion_utils::calcSignedArcLength( input_path.points, getEgoPose().position, ego_seg_idx, lat_lon_offset.nearest_idx); if (0 < lon_offset_ego_to_obj) { return std::max( @@ -788,7 +788,7 @@ void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstRegulatedObje // 2.h. calculate longitudinal and lateral offset to avoid to generate object polygon by // "ego_path_base" - const auto obj_points = autoware_universe_utils::toPolygon2d(object.pose, object.shape); + const auto obj_points = autoware::universe_utils::toPolygon2d(object.pose, object.shape); const auto lon_offset_to_avoid = calcMinMaxLongitudinalOffsetToAvoid( ref_path_points_for_obj_poly, object.pose, obj_points, object.vel, obj_path, object.shape, time_while_collision); @@ -831,7 +831,7 @@ void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstUnregulatedOb getLateralLongitudinalOffset(input_path.points, object.pose, object.shape); const double signed_dist_ego_to_obj = [&]() { const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(input_path.points); - const double lon_offset_ego_to_obj = autoware_motion_utils::calcSignedArcLength( + const double lon_offset_ego_to_obj = autoware::motion_utils::calcSignedArcLength( input_path.points, getEgoPose().position, ego_seg_idx, lat_lon_offset.nearest_idx); if (0 < lon_offset_ego_to_obj) { return std::max( @@ -891,19 +891,19 @@ LatFeasiblePaths DynamicObstacleAvoidanceModule::generateLateralFeasiblePaths( const double y = feasible_lat_offset; const auto feasible_left_bound_point = - autoware_universe_utils::calcOffsetPose(ego_pose, x, -y, 0.0).position; + autoware::universe_utils::calcOffsetPose(ego_pose, x, -y, 0.0).position; ego_lat_feasible_paths.left_path.push_back(feasible_left_bound_point); const auto feasible_right_bound_point = - autoware_universe_utils::calcOffsetPose(ego_pose, x, y, 0.0).position; + autoware::universe_utils::calcOffsetPose(ego_pose, x, y, 0.0).position; ego_lat_feasible_paths.right_path.push_back(feasible_right_bound_point); } - autoware_universe_utils::appendMarkerArray( + autoware::universe_utils::appendMarkerArray( marker_utils::createPointsMarkerArray( ego_lat_feasible_paths.left_path, "ego_lat_feasible_left_path", 0, 0.6, 0.9, 0.9), &debug_marker_); - autoware_universe_utils::appendMarkerArray( + autoware::universe_utils::appendMarkerArray( marker_utils::createPointsMarkerArray( ego_lat_feasible_paths.right_path, "ego_lat_feasible_right_path", 0, 0.6, 0.9, 0.9), &debug_marker_); @@ -918,7 +918,7 @@ LatFeasiblePaths DynamicObstacleAvoidanceModule::generateLateralFeasiblePaths( // 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(autoware_motion_utils::calcLateralOffset(ego_ref_path_points, ego_pos)); + std::abs(autoware::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) { @@ -927,7 +927,7 @@ LatFeasiblePaths DynamicObstacleAvoidanceModule::generateLateralFeasiblePaths( } 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(autoware_motion_utils::calcLateralOffset( + const double dist_ref_paths = std::abs(autoware::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) { @@ -947,7 +947,7 @@ DynamicObstacleAvoidanceModule::calcCollisionSection( std::optional collision_start_idx{std::nullopt}; double lon_dist = 0.0; for (size_t i = ego_idx; i < ego_path.size() - 1; ++i) { - lon_dist += autoware_universe_utils::calcDistance2d(ego_path.at(i), ego_path.at(i + 1)); + lon_dist += autoware::universe_utils::calcDistance2d(ego_path.at(i), ego_path.at(i + 1)); const double elapsed_time = lon_dist / ego_vel; const auto future_ego_pose = ego_path.at(i); @@ -956,7 +956,7 @@ DynamicObstacleAvoidanceModule::calcCollisionSection( if (future_obj_pose) { const double dist_ego_to_obj = - autoware_universe_utils::calcDistance2d(future_ego_pose, *future_obj_pose); + autoware::universe_utils::calcDistance2d(future_ego_pose, *future_obj_pose); if (dist_ego_to_obj < 1.0) { if (!collision_start_idx) { collision_start_idx = i; @@ -982,7 +982,7 @@ TimeWhileCollision DynamicObstacleAvoidanceModule::calcTimeWhileCollision( // Set maximum time-to-collision 0 if the object longitudinally overlaps ego. // NOTE: This is to avoid objects running right beside ego even if time-to-collision is negative. const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(ego_path); - const double lon_offset_ego_to_obj_idx = autoware_motion_utils::calcSignedArcLength( + const double lon_offset_ego_to_obj_idx = autoware::motion_utils::calcSignedArcLength( ego_path, getEgoPose().position, ego_seg_idx, lat_lon_offset.nearest_idx); const double relative_velocity = getEgoSpeed() - obj_tangent_vel; @@ -1054,7 +1054,7 @@ bool DynamicObstacleAvoidanceModule::willObjectCutIn( const bool will_object_cut_in = [&]() { for (const auto & predicted_path_point : predicted_path.path) { const double paths_lat_diff = - autoware_motion_utils::calcLateralOffset(ego_path, predicted_path_point.position); + autoware::motion_utils::calcLateralOffset(ego_path, predicted_path_point.position); if (std::abs(paths_lat_diff) < planner_data_->parameters.vehicle_width / 2.0) { return true; } @@ -1070,7 +1070,7 @@ bool DynamicObstacleAvoidanceModule::willObjectCutIn( const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(ego_path); const double relative_velocity = getEgoSpeed() - obj_tangent_vel; const double lon_offset_ego_to_obj = - autoware_motion_utils::calcSignedArcLength( + autoware::motion_utils::calcSignedArcLength( ego_path, getEgoPose().position, ego_seg_idx, lat_lon_offset.nearest_idx) + lat_lon_offset.min_lon_offset; if ( @@ -1134,7 +1134,7 @@ DynamicObstacleAvoidanceModule::DecisionWithReason DynamicObstacleAvoidanceModul // Check if object is in the lane before ego's lane change. const double dist_to_ref_path_before_lane_change = std::abs( - autoware_motion_utils::calcLateralOffset(*ref_path_before_lane_change_, obj_pose.position)); + autoware::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; @@ -1190,8 +1190,8 @@ DynamicObstacleAvoidanceModule::getLateralLongitudinalOffset( const autoware_perception_msgs::msg::Shape & obj_shape) const { const size_t obj_seg_idx = - autoware_motion_utils::findNearestSegmentIndex(ego_path, obj_pose.position); - const auto obj_points = autoware_universe_utils::toPolygon2d(obj_pose, obj_shape); + autoware::motion_utils::findNearestSegmentIndex(ego_path, obj_pose.position); + const auto obj_points = autoware::universe_utils::toPolygon2d(obj_pose, obj_shape); // TODO(murooka) calculation is not so accurate. std::vector obj_lat_offset_vec; @@ -1199,16 +1199,16 @@ DynamicObstacleAvoidanceModule::getLateralLongitudinalOffset( 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 = - autoware_motion_utils::findNearestSegmentIndex(ego_path, geom_obj_point); + autoware::motion_utils::findNearestSegmentIndex(ego_path, geom_obj_point); // calculate lateral offset const double obj_point_lat_offset = - autoware_motion_utils::calcLateralOffset(ego_path, geom_obj_point, obj_point_seg_idx); + autoware::motion_utils::calcLateralOffset(ego_path, geom_obj_point, obj_point_seg_idx); obj_lat_offset_vec.push_back(obj_point_lat_offset); // calculate longitudinal offset - const double lon_offset = - autoware_motion_utils::calcLongitudinalOffsetToSegment(ego_path, obj_seg_idx, geom_obj_point); + const double lon_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( + ego_path, obj_seg_idx, geom_obj_point); obj_lon_offset_vec.push_back(lon_offset); } @@ -1226,15 +1226,15 @@ MinMaxValue DynamicObstacleAvoidanceModule::calcMinMaxLongitudinalOffsetToAvoid( const PredictedPath & obj_path, const autoware_perception_msgs::msg::Shape & obj_shape, const TimeWhileCollision & time_while_collision) const { - const size_t obj_seg_idx = - autoware_motion_utils::findNearestSegmentIndex(ref_path_points_for_obj_poly, obj_pose.position); + const size_t obj_seg_idx = autoware::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 = [&]() { std::vector obj_lon_offset_vec; 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 = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const double lon_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( ref_path_points_for_obj_poly, obj_seg_idx, geom_obj_point); obj_lon_offset_vec.push_back(lon_offset); } @@ -1299,7 +1299,7 @@ double DynamicObstacleAvoidanceModule::calcValidLengthToAvoid( { const auto & input_path_points = getPreviousModuleOutput().path.points; const size_t obj_seg_idx = - autoware_motion_utils::findNearestSegmentIndex(input_path_points, obj_pose.position); + autoware::motion_utils::findNearestSegmentIndex(input_path_points, obj_pose.position); constexpr double dist_threshold_additional_margin = 0.5; const double dist_threshold_paths = @@ -1317,7 +1317,7 @@ double DynamicObstacleAvoidanceModule::calcValidLengthToAvoid( std::reverse(cropped_ego_path_points.begin(), cropped_ego_path_points.end()); } if (cropped_ego_path_points.size() < 2) { - return autoware_motion_utils::calcArcLength(obj_path.path); + return autoware::motion_utils::calcArcLength(obj_path.path); } // calculate where the object's path will be forked from (= far from) the ego's path. @@ -1371,18 +1371,18 @@ double DynamicObstacleAvoidanceModule::calcValidLengthToAvoid( const auto prev_min_dist = calc_min_dist(prev_valid_obj_path_end_idx); const auto next_min_dist = calc_min_dist(next_valid_obj_path_end_idx); if (prev_min_dist && next_min_dist) { - const double segment_length = autoware_universe_utils::calcDistance2d( + const double segment_length = autoware::universe_utils::calcDistance2d( obj_path.path.at(prev_valid_obj_path_end_idx), obj_path.path.at(next_valid_obj_path_end_idx)); const double partial_segment_length = segment_length * (dist_threshold_paths - *prev_min_dist) / (*next_min_dist - *prev_min_dist); - return autoware_motion_utils::calcSignedArcLength( + return autoware::motion_utils::calcSignedArcLength( obj_path.path, 0, prev_valid_obj_path_end_idx) + partial_segment_length; } } - return autoware_motion_utils::calcSignedArcLength(obj_path.path, 0, valid_obj_path_end_idx); + return autoware::motion_utils::calcSignedArcLength(obj_path.path, 0, valid_obj_path_end_idx); } // min value denotes near side, max value denotes far side @@ -1400,8 +1400,8 @@ DynamicObstacleAvoidanceModule::calcMinMaxLateralOffsetToAvoidRegulatedObject( return true; } const size_t obj_point_idx = - autoware_motion_utils::findNearestIndex(ref_path_points_for_obj_poly, obj_pos); - const double paths_lat_diff = std::abs(autoware_motion_utils::calcLateralOffset( + autoware::motion_utils::findNearestIndex(ref_path_points_for_obj_poly, obj_pos); + const double paths_lat_diff = std::abs(autoware::motion_utils::calcLateralOffset( prev_object->ref_path_points_for_obj_poly, ref_path_points_for_obj_poly.at(obj_point_idx).point.pose.position)); @@ -1419,9 +1419,9 @@ DynamicObstacleAvoidanceModule::calcMinMaxLateralOffsetToAvoidRegulatedObject( std::vector obj_lat_abs_offset_vec; 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 = autoware_motion_utils::findNearestSegmentIndex( + const size_t obj_point_seg_idx = autoware::motion_utils::findNearestSegmentIndex( ref_path_points_for_obj_poly, geom_obj_point); - const double obj_point_lat_offset = autoware_motion_utils::calcLateralOffset( + const double obj_point_lat_offset = autoware::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); } @@ -1494,8 +1494,8 @@ DynamicObstacleAvoidanceModule::calcMinMaxLateralOffsetToAvoidUnregulatedObject( return true; } const size_t obj_point_idx = - autoware_motion_utils::findNearestIndex(ref_path_points_for_obj_poly, object.pose.position); - const double paths_lat_diff = std::abs(autoware_motion_utils::calcLateralOffset( + autoware::motion_utils::findNearestIndex(ref_path_points_for_obj_poly, object.pose.position); + const double paths_lat_diff = std::abs(autoware::motion_utils::calcLateralOffset( prev_object->ref_path_points_for_obj_poly, ref_path_points_for_obj_poly.at(obj_point_idx).point.pose.position)); @@ -1509,13 +1509,13 @@ DynamicObstacleAvoidanceModule::calcMinMaxLateralOffsetToAvoidUnregulatedObject( }(); const auto obj_occupancy_region = [&]() { - const auto obj_points = autoware_universe_utils::toPolygon2d(object.pose, object.shape); + const auto obj_points = autoware::universe_utils::toPolygon2d(object.pose, object.shape); std::vector lat_pos_vec; for (size_t i = 0; i < obj_points.outer().size(); ++i) { const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); - const double obj_point_lat_offset = autoware_motion_utils::calcLateralOffset( + const double obj_point_lat_offset = autoware::motion_utils::calcLateralOffset( ref_path_points_for_obj_poly, geom_obj_point, - autoware_motion_utils::findNearestSegmentIndex( + autoware::motion_utils::findNearestSegmentIndex( ref_path_points_for_obj_poly, geom_obj_point)); lat_pos_vec.push_back(obj_point_lat_offset); } @@ -1566,7 +1566,7 @@ DynamicObstacleAvoidanceModule::calcMinMaxLateralOffsetToAvoidUnregulatedObject( } // NOTE: object does not have const only to update min_bound_lat_offset. -std::optional +std::optional DynamicObstacleAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const { @@ -1576,16 +1576,16 @@ DynamicObstacleAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( auto ref_path_points_for_obj_poly = object.ref_path_points_for_obj_poly; - const size_t obj_seg_idx = autoware_motion_utils::findNearestSegmentIndex( + const size_t obj_seg_idx = autoware::motion_utils::findNearestSegmentIndex( ref_path_points_for_obj_poly, object.pose.position); - // const auto obj_points = autoware_universe_utils::toPolygon2d(object.pose, object.shape); + // const auto obj_points = autoware::universe_utils::toPolygon2d(object.pose, object.shape); - const auto lon_bound_start_idx_opt = autoware_motion_utils::insertTargetPoint( + const auto lon_bound_start_idx_opt = autoware::motion_utils::insertTargetPoint( 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 = autoware_motion_utils::insertTargetPoint( + const auto lon_bound_end_idx_opt = autoware::motion_utils::insertTargetPoint( 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) { @@ -1602,7 +1602,7 @@ DynamicObstacleAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( std::vector obj_inner_bound_poses; for (size_t i = lon_bound_start_idx; i <= lon_bound_end_idx; ++i) { // NOTE: object.lat_offset_to_avoid->min_value is not the minimum value but the inner value. - obj_inner_bound_poses.push_back(autoware_universe_utils::calcOffsetPose( + obj_inner_bound_poses.push_back(autoware::universe_utils::calcOffsetPose( ref_path_points_for_obj_poly.at(i).point.pose, 0.0, object.lat_offset_to_avoid->min_value, 0.0)); } @@ -1618,18 +1618,18 @@ DynamicObstacleAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( // Check if the object polygon intersects with the ego_lat_feasible_path. if (intersect_result) { const auto & [bound_seg_idx, intersect_point] = *intersect_result; - const double lon_offset = autoware_universe_utils::calcDistance2d( + const double lon_offset = autoware::universe_utils::calcDistance2d( obj_inner_bound_poses.at(bound_seg_idx), intersect_point); const auto obj_inner_bound_start_idx_opt = - autoware_motion_utils::insertTargetPoint(bound_seg_idx, lon_offset, obj_inner_bound_poses); + autoware::motion_utils::insertTargetPoint(bound_seg_idx, lon_offset, obj_inner_bound_poses); if (obj_inner_bound_start_idx_opt) { return *obj_inner_bound_start_idx_opt; } } // Check if the object polygon is fully outside the ego_lat_feasible_path. - const double obj_poly_lat_offset = autoware_motion_utils::calcLateralOffset( + const double obj_poly_lat_offset = autoware::motion_utils::calcLateralOffset( ego_lat_feasible_path, obj_inner_bound_poses.front().position); if ( (!object.is_collision_left && 0 < obj_poly_lat_offset) || @@ -1650,17 +1650,17 @@ DynamicObstacleAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( std::vector feasible_obj_outer_bound_points; for (const auto & feasible_obj_inner_bound_pose : feasible_obj_inner_bound_poses) { feasible_obj_outer_bound_points.push_back( - autoware_universe_utils::calcOffsetPose( + autoware::universe_utils::calcOffsetPose( feasible_obj_inner_bound_pose, 0.0, object.lat_offset_to_avoid->max_value - object.lat_offset_to_avoid->min_value, 0.0) .position); } // create obj_polygon from inner/outer bound points - autoware_universe_utils::Polygon2d obj_poly; + autoware::universe_utils::Polygon2d obj_poly; const auto add_points_to_obj_poly = [&](const auto & bound_points) { for (const auto & bound_point : bound_points) { - obj_poly.outer().push_back(autoware_universe_utils::Point2d(bound_point.x, bound_point.y)); + obj_poly.outer().push_back(autoware::universe_utils::Point2d(bound_point.x, bound_point.y)); } }; add_points_to_obj_poly(feasible_obj_inner_bound_points); @@ -1672,7 +1672,7 @@ DynamicObstacleAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( } // should be replace by the function calcPredictedPathBasedDynamicObstaclePolygon() (takagi) -std::optional +std::optional DynamicObstacleAvoidanceModule::calcObjectPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const { @@ -1683,7 +1683,7 @@ DynamicObstacleAvoidanceModule::calcObjectPathBasedDynamicObstaclePolygon( // calculate left and right bound std::vector obj_left_bound_points; std::vector obj_right_bound_points; - const double obj_path_length = autoware_motion_utils::calcArcLength(obj_path.path); + const double obj_path_length = autoware::motion_utils::calcArcLength(obj_path.path); for (size_t i = 0; i < obj_path.path.size(); ++i) { const double lon_offset = [&]() { if (i == 0) @@ -1701,26 +1701,26 @@ DynamicObstacleAvoidanceModule::calcObjectPathBasedDynamicObstaclePolygon( const auto & obj_pose = obj_path.path.at(i); obj_left_bound_points.push_back( - autoware_universe_utils::calcOffsetPose( + autoware::universe_utils::calcOffsetPose( obj_pose, lon_offset, object.shape.dimensions.y / 2.0 + parameters_->lat_offset_from_obstacle, 0.0) .position); obj_right_bound_points.push_back( - autoware_universe_utils::calcOffsetPose( + autoware::universe_utils::calcOffsetPose( obj_pose, lon_offset, -object.shape.dimensions.y / 2.0 - parameters_->lat_offset_from_obstacle, 0.0) .position); } // create obj_polygon from inner/outer bound points - autoware_universe_utils::Polygon2d obj_poly; + autoware::universe_utils::Polygon2d obj_poly; for (const auto & bound_point : obj_right_bound_points) { - const auto obj_poly_point = autoware_universe_utils::Point2d(bound_point.x, bound_point.y); + const auto obj_poly_point = autoware::universe_utils::Point2d(bound_point.x, bound_point.y); obj_poly.outer().push_back(obj_poly_point); } std::reverse(obj_left_bound_points.begin(), obj_left_bound_points.end()); for (const auto & bound_point : obj_left_bound_points) { - const auto obj_poly_point = autoware_universe_utils::Point2d(bound_point.x, bound_point.y); + const auto obj_poly_point = autoware::universe_utils::Point2d(bound_point.x, bound_point.y); obj_poly.outer().push_back(obj_poly_point); } @@ -1731,7 +1731,7 @@ DynamicObstacleAvoidanceModule::calcObjectPathBasedDynamicObstaclePolygon( // Calculate polygons according to predicted_path with certain confidence, // except for the area required for ego safety. // input: an object, the minimum area required for ego safety, and some global params -std::optional +std::optional DynamicObstacleAvoidanceModule::calcPredictedPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object, const EgoPathReservePoly & ego_path_poly) const { @@ -1747,10 +1747,10 @@ DynamicObstacleAvoidanceModule::calcPredictedPathBasedDynamicObstaclePolygon( } } - autoware_universe_utils::Polygon2d obj_points_as_poly; + autoware::universe_utils::Polygon2d obj_points_as_poly; for (const auto pose : obj_poses) { boost::geometry::append( - obj_points_as_poly, autoware_universe_utils::toFootprint( + obj_points_as_poly, autoware::universe_utils::toFootprint( pose, object.shape.dimensions.x * 0.5, object.shape.dimensions.x * 0.5, object.shape.dimensions.y * 0.5) .outer()); @@ -1759,7 +1759,7 @@ DynamicObstacleAvoidanceModule::calcPredictedPathBasedDynamicObstaclePolygon( Polygon2d obj_poly; boost::geometry::convex_hull(obj_points_as_poly, obj_poly); - autoware_universe_utils::MultiPolygon2d expanded_poly; + autoware::universe_utils::MultiPolygon2d expanded_poly; namespace strategy = boost::geometry::strategy::buffer; boost::geometry::buffer( obj_poly, expanded_poly, @@ -1768,7 +1768,7 @@ DynamicObstacleAvoidanceModule::calcPredictedPathBasedDynamicObstaclePolygon( strategy::point_circle()); if (expanded_poly.empty()) return {}; - autoware_universe_utils::MultiPolygon2d output_poly; + autoware::universe_utils::MultiPolygon2d output_poly; boost::geometry::difference( expanded_poly[0], object.is_collision_left ? ego_path_poly.right_avoid : ego_path_poly.left_avoid, output_poly); @@ -1804,27 +1804,27 @@ DynamicObstacleAvoidanceModule::calcEgoPathReservePoly(const PathWithLaneId & eg assert(!ego_path.points.empty()); - autoware_universe_utils::LineString2d ego_path_lines; + autoware::universe_utils::LineString2d ego_path_lines; for (const auto & path_point : ego_path.points) { ego_path_lines.push_back( - autoware_universe_utils::fromMsg(path_point.point.pose.position).to_2d()); + autoware::universe_utils::fromMsg(path_point.point.pose.position).to_2d()); } auto calcReservePoly = [&ego_path_lines]( const strategy::distance_asymmetric path_expand_strategy, const strategy::distance_asymmetric steer_expand_strategy, const std::vector & outer_body_path) - -> autoware_universe_utils::Polygon2d { + -> autoware::universe_utils::Polygon2d { // reserve area based on the reference path - autoware_universe_utils::MultiPolygon2d path_poly; + autoware::universe_utils::MultiPolygon2d path_poly; boost::geometry::buffer( ego_path_lines, path_poly, path_expand_strategy, strategy::side_straight(), strategy::join_round(), strategy::end_flat(), strategy::point_circle()); // reserve area steer to the avoidance path - autoware_universe_utils::LineString2d steer_lines; + autoware::universe_utils::LineString2d steer_lines; for (const auto & point : outer_body_path) { - const auto bg_point = autoware_universe_utils::fromMsg(point).to_2d(); + const auto bg_point = autoware::universe_utils::fromMsg(point).to_2d(); if (boost::geometry::within(bg_point, path_poly)) { if (steer_lines.size() != 0) { ; @@ -1834,12 +1834,12 @@ DynamicObstacleAvoidanceModule::calcEgoPathReservePoly(const PathWithLaneId & eg } // boost::geometry::append(steer_lines, bg_point); } - autoware_universe_utils::MultiPolygon2d steer_poly; + autoware::universe_utils::MultiPolygon2d steer_poly; boost::geometry::buffer( steer_lines, steer_poly, steer_expand_strategy, strategy::side_straight(), strategy::join_round(), strategy::end_flat(), strategy::point_circle()); - autoware_universe_utils::MultiPolygon2d output_poly; + autoware::universe_utils::MultiPolygon2d output_poly; boost::geometry::union_(path_poly, steer_poly, output_poly); if (output_poly.size() != 1) { assert(false); @@ -1853,11 +1853,11 @@ DynamicObstacleAvoidanceModule::calcEgoPathReservePoly(const PathWithLaneId & eg const double vehicle_half_width = planner_data_->parameters.vehicle_width * 0.5; const double reserve_width_obj_side = vehicle_half_width - parameters_->max_lat_offset_to_avoid; - const autoware_universe_utils::Polygon2d left_avoid_poly = calcReservePoly( + const autoware::universe_utils::Polygon2d left_avoid_poly = calcReservePoly( strategy::distance_asymmetric(vehicle_half_width, reserve_width_obj_side), strategy::distance_asymmetric(vehicle_half_width, 0.0), motion_saturated_outer_paths.right_path); - const autoware_universe_utils::Polygon2d right_avoid_poly = calcReservePoly( + const autoware::universe_utils::Polygon2d right_avoid_poly = calcReservePoly( strategy::distance_asymmetric(reserve_width_obj_side, vehicle_half_width), strategy::distance_asymmetric(0.0, vehicle_half_width), motion_saturated_outer_paths.left_path); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp index dc8a60c9a8373..f670e3b05fa77 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp @@ -22,7 +22,7 @@ #include -using autoware_universe_utils::LinearRing2d; +using autoware::universe_utils::LinearRing2d; using geometry_msgs::msg::Pose; using tier4_planning_msgs::msg::PathWithLaneId; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index ed2735448fdbc..e34cd202011d0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -69,7 +69,7 @@ using autoware::behavior_path_planner::utils::path_safety_checker::ObjectsFilter using autoware::behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; using autoware::behavior_path_planner::utils::path_safety_checker::SafetyCheckParams; using autoware::behavior_path_planner::utils::path_safety_checker::TargetObjectsOnLane; -using autoware_universe_utils::Polygon2d; +using autoware::universe_utils::Polygon2d; #define DEFINE_SETTER_WITH_MUTEX(TYPE, NAME) \ public: \ @@ -387,7 +387,7 @@ class GoalPlannerModule : public SceneModuleInterface std::shared_ptr ego_predicted_path_params; std::shared_ptr objects_filtering_params; std::shared_ptr safety_check_params; - autoware_universe_utils::LinearRing2d vehicle_footprint; + autoware::universe_utils::LinearRing2d vehicle_footprint; PlannerData planner_data; ModuleStatus current_status; @@ -409,7 +409,7 @@ class GoalPlannerModule : public SceneModuleInterface const PlannerData & planner_data, const ModuleStatus & current_status, const BehaviorModuleOutput & previous_module_output, const std::shared_ptr goal_searcher_, - const autoware_universe_utils::LinearRing2d & vehicle_footprint); + const autoware::universe_utils::LinearRing2d & vehicle_footprint); private: void initializeOccupancyGridMap( @@ -484,7 +484,7 @@ class GoalPlannerModule : public SceneModuleInterface std::deque odometry_buffer_stopped_; std::deque odometry_buffer_stuck_; - autoware_universe_utils::LinearRing2d vehicle_footprint_; + autoware::universe_utils::LinearRing2d vehicle_footprint_; std::recursive_mutex mutex_; // TODO(Mamoru Sobue): isSafePath() modifies ThreadSafeData::check_collision, avoid this mutable diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp index 38c55b0b87ecb..5d056add4665e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp @@ -23,7 +23,7 @@ namespace autoware::behavior_path_planner { -using autoware_universe_utils::LinearRing2d; +using autoware::universe_utils::LinearRing2d; using BasicPolygons2d = std::vector; class GoalSearcher : public GoalSearcherBase diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp index 4a1a925eb114c..baead4c229efd 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp @@ -26,7 +26,7 @@ namespace autoware::behavior_path_planner { -using autoware_universe_utils::MultiPolygon2d; +using autoware::universe_utils::MultiPolygon2d; using geometry_msgs::msg::Pose; struct GoalCandidate diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp index d1760c7f5a137..d2ba416c7fa90 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner_base.hpp @@ -25,7 +25,7 @@ #include #include -using autoware_universe_utils::LinearRing2d; +using autoware::universe_utils::LinearRing2d; using geometry_msgs::msg::Pose; using tier4_planning_msgs::msg::PathWithLaneId; @@ -67,7 +67,7 @@ struct PullOverPath partial_paths.at(i).points.end()); } } - path.points = autoware_motion_utils::removeOverlapPoints(path.points); + path.points = autoware::motion_utils::removeOverlapPoints(path.points); return path; } @@ -76,7 +76,7 @@ struct PullOverPath { const PathWithLaneId full_path = getFullPath(); const size_t start_idx = - autoware_motion_utils::findNearestIndex(full_path.points, start_pose.position); + autoware::motion_utils::findNearestIndex(full_path.points, start_pose.position); PathWithLaneId parking_path{}; std::copy( diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp index 927145fc69db1..98a513d519b43 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp @@ -42,7 +42,7 @@ using geometry_msgs::msg::Twist; using tier4_planning_msgs::msg::PathWithLaneId; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; -using Polygon2d = autoware_universe_utils::Polygon2d; +using Polygon2d = autoware::universe_utils::Polygon2d; lanelet::ConstLanelets getPullOverLanes( const RouteHandler & route_handler, const bool left_side, const double backward_distance, @@ -94,8 +94,8 @@ std::vector createPathFootPrints( // debug MarkerArray createPullOverAreaMarkerArray( - const autoware_universe_utils::MultiPolygon2d area_polygons, const std_msgs::msg::Header & header, - const std_msgs::msg::ColorRGBA & color, const double z); + const autoware::universe_utils::MultiPolygon2d area_polygons, + const std_msgs::msg::Header & header, const std_msgs::msg::ColorRGBA & color, const double z); MarkerArray createPosesMarkerArray( const std::vector & poses, std::string && ns, const std_msgs::msg::ColorRGBA & color); MarkerArray createTextsMarkerArray( diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp index b5dac4264de39..10e0137978bd6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/default_fixed_goal_planner.cpp @@ -25,7 +25,7 @@ namespace autoware::behavior_path_planner { -using Point2d = autoware_universe_utils::Point2d; +using Point2d = autoware::universe_utils::Point2d; using tier4_planning_msgs::msg::PathWithLaneId; BehaviorModuleOutput DefaultFixedGoalPlanner::plan( const std::shared_ptr & planner_data) const diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/freespace_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/freespace_pull_over.cpp index 3082bcf26cba7..ee35790ee2ab1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/freespace_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/freespace_pull_over.cpp @@ -57,7 +57,7 @@ std::optional FreespacePullOver::plan(const Pose & goal_pose) constexpr double straight_distance = 1.0; const Pose end_pose = use_back_ ? goal_pose - : autoware_universe_utils::calcOffsetPose(goal_pose, -straight_distance, 0.0, 0.0); + : autoware::universe_utils::calcOffsetPose(goal_pose, -straight_distance, 0.0, 0.0); if (!planner_->makePlan(current_pose, end_pose)) { return {}; } @@ -85,7 +85,7 @@ std::optional FreespacePullOver::plan(const Pose & goal_pose) size_t index = std::distance(last_path.points.begin(), it); if (index == 0) continue; const double distance = - autoware_universe_utils::calcDistance2d(end_pose.position, it->point.pose.position); + autoware::universe_utils::calcDistance2d(end_pose.position, it->point.pose.position); if (distance < th_goal_distance) { last_path.points.erase(it, last_path.points.end()); break; @@ -123,7 +123,7 @@ std::optional FreespacePullOver::plan(const Pose & goal_pose) // Check if driving forward for each path, return empty if not for (auto & path : partial_paths) { - if (!autoware_motion_utils::isDrivingForward(path.points)) { + if (!autoware::motion_utils::isDrivingForward(path.points)) { return {}; } } diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index a329e984fc7c0..2ac0b9493e67a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -40,14 +40,14 @@ #include using autoware::behavior_path_planner::utils::parking_departure::calcFeasibleDecelDistance; -using autoware_motion_utils::calcLongitudinalOffsetPose; -using autoware_motion_utils::calcSignedArcLength; -using autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints; -using autoware_motion_utils::insertDecelPoint; -using autoware_universe_utils::calcDistance2d; -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::inverseTransformPose; +using autoware::motion_utils::calcLongitudinalOffsetPose; +using autoware::motion_utils::calcSignedArcLength; +using autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints; +using autoware::motion_utils::insertDecelPoint; +using autoware::universe_utils::calcDistance2d; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::inverseTransformPose; using nav_msgs::msg::OccupancyGrid; namespace autoware::behavior_path_planner @@ -137,7 +137,7 @@ bool GoalPlannerModule::hasPreviousModulePathShapeChanged( // the last path constexpr double LATERAL_DEVIATION_THRESH = 0.3; for (const auto & p : previous_module_output.path.points) { - const size_t nearest_seg_idx = autoware_motion_utils::findNearestSegmentIndex( + const size_t nearest_seg_idx = autoware::motion_utils::findNearestSegmentIndex( last_previous_module_output->path.points, p.point.pose.position); const auto seg_front = last_previous_module_output->path.points.at(nearest_seg_idx); const auto seg_back = last_previous_module_output->path.points.at(nearest_seg_idx + 1); @@ -155,7 +155,7 @@ bool GoalPlannerModule::hasPreviousModulePathShapeChanged( // p.point.pose.position is not within the segment, skip lateral distance check continue; } - const double lateral_distance = std::abs(autoware_motion_utils::calcLateralOffset( + const double lateral_distance = std::abs(autoware::motion_utils::calcLateralOffset( last_previous_module_output->path.points, p.point.pose.position, nearest_seg_idx)); if (lateral_distance > LATERAL_DEVIATION_THRESH) { return true; @@ -171,7 +171,7 @@ bool GoalPlannerModule::hasDeviatedFromLastPreviousModulePath( if (!last_previous_module_output) { return true; } - return std::abs(autoware_motion_utils::calcLateralOffset( + return std::abs(autoware::motion_utils::calcLateralOffset( last_previous_module_output->path.points, planner_data->self_odometry->pose.pose.position)) > 0.3; } @@ -181,7 +181,7 @@ bool GoalPlannerModule::hasDeviatedFromCurrentPreviousModulePath( const BehaviorModuleOutput & previous_module_output) const { constexpr double LATERAL_DEVIATION_THRESH = 0.3; - return std::abs(autoware_motion_utils::calcLateralOffset( + return std::abs(autoware::motion_utils::calcLateralOffset( previous_module_output.path.points, planner_data->self_odometry->pose.pose.position)) > LATERAL_DEVIATION_THRESH; } @@ -770,7 +770,7 @@ bool GoalPlannerModule::canReturnToLaneParking() const Point & current_point = planner_data_->self_odometry->pose.pose.position; constexpr double th_distance = 0.5; const bool is_close_to_path = - std::abs(autoware_motion_utils::calcLateralOffset(path.points, current_point)) < th_distance; + std::abs(autoware::motion_utils::calcLateralOffset(path.points, current_point)) < th_distance; if (!is_close_to_path) { return false; } @@ -1266,9 +1266,9 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( // if ego is sufficiently close to the start of the nearest candidate path, the path is decided const auto & current_pose = planner_data->self_odometry->pose.pose; const size_t ego_segment_idx = - autoware_motion_utils::findNearestSegmentIndex(current_path.points, current_pose.position); + autoware::motion_utils::findNearestSegmentIndex(current_path.points, current_pose.position); - const size_t start_pose_segment_idx = autoware_motion_utils::findNearestSegmentIndex( + const size_t start_pose_segment_idx = autoware::motion_utils::findNearestSegmentIndex( current_path.points, pull_over_path->start_pose.position); const double dist_to_parking_start_pose = calcSignedArcLength( current_path.points, current_pose.position, ego_segment_idx, @@ -1500,19 +1500,19 @@ std::pair GoalPlannerModule::calcDistanceToPathChange() const const auto full_path = thread_safe_data_.get_pull_over_path()->getFullPath(); - const auto ego_segment_idx = autoware_motion_utils::findNearestSegmentIndex( + const auto ego_segment_idx = autoware::motion_utils::findNearestSegmentIndex( full_path.points, planner_data_->self_odometry->pose.pose, std::numeric_limits::max(), M_PI_2); if (!ego_segment_idx) { return {std::numeric_limits::max(), std::numeric_limits::max()}; } - const size_t start_pose_segment_idx = autoware_motion_utils::findNearestSegmentIndex( + const size_t start_pose_segment_idx = autoware::motion_utils::findNearestSegmentIndex( full_path.points, thread_safe_data_.get_pull_over_path()->start_pose.position); const double dist_to_parking_start_pose = calcSignedArcLength( full_path.points, planner_data_->self_odometry->pose.pose.position, *ego_segment_idx, thread_safe_data_.get_pull_over_path()->start_pose.position, start_pose_segment_idx); - const size_t goal_pose_segment_idx = autoware_motion_utils::findNearestSegmentIndex( + const size_t goal_pose_segment_idx = autoware::motion_utils::findNearestSegmentIndex( full_path.points, thread_safe_data_.get_modified_goal_pose()->goal_pose.position); const double dist_to_parking_finish_pose = calcSignedArcLength( full_path.points, planner_data_->self_odometry->pose.pose.position, *ego_segment_idx, @@ -1646,7 +1646,7 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath(const PathWithLaneId auto stop_path = path; const auto & current_pose = planner_data_->self_odometry->pose.pose; const auto stop_idx = - autoware_motion_utils::insertStopPoint(current_pose, *min_stop_distance, stop_path.points); + autoware::motion_utils::insertStopPoint(current_pose, *min_stop_distance, stop_path.points); if (stop_idx) { debug_stop_pose_with_info_.set(stop_path.points.at(*stop_idx).point.pose, "feasible stop"); } @@ -1764,7 +1764,7 @@ bool GoalPlannerModule::hasFinishedCurrentPath() const auto current_path_end = thread_safe_data_.get_pull_over_path()->getCurrentPath().points.back(); const auto & self_pose = planner_data_->self_odometry->pose.pose; - return autoware_universe_utils::calcDistance2d(current_path_end, self_pose) < + return autoware::universe_utils::calcDistance2d(current_path_end, self_pose) < parameters_->th_arrived_distance; } @@ -1789,9 +1789,9 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() const auto & end_pose = thread_safe_data_.get_pull_over_path()->end_pose; const auto shift_start_idx = - autoware_motion_utils::findNearestIndex(path.points, start_pose.position); + autoware::motion_utils::findNearestIndex(path.points, start_pose.position); const auto shift_end_idx = - autoware_motion_utils::findNearestIndex(path.points, end_pose.position); + autoware::motion_utils::findNearestIndex(path.points, end_pose.position); const auto is_ignore_signal = [this](const lanelet::Id & id) { if (!ignore_signal_.has_value()) { @@ -1835,7 +1835,7 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() const auto stop_point = thread_safe_data_.get_pull_over_path()->partial_paths.front().points.back(); const double distance_from_ego_to_stop_point = - std::abs(autoware_motion_utils::calcSignedArcLength( + std::abs(autoware::motion_utils::calcSignedArcLength( path.points, stop_point.point.pose.position, current_pose.position)); return distance_from_ego_to_stop_point < distance_threshold; }); @@ -1880,7 +1880,7 @@ bool GoalPlannerModule::checkObjectsCollision( std::vector obj_polygons; for (const auto & object : target_objects.objects) { - obj_polygons.push_back(autoware_universe_utils::toPolygon2d(object)); + obj_polygons.push_back(autoware::universe_utils::toPolygon2d(object)); } /* Expand ego collision check polygon @@ -1889,7 +1889,7 @@ bool GoalPlannerModule::checkObjectsCollision( * - `extra_lateral_margin` adds the lateral margin on curves. */ std::vector ego_polygons_expanded{}; - const auto curvatures = autoware_motion_utils::calcCurvature(path.points); + const auto curvatures = autoware::motion_utils::calcCurvature(path.points); for (size_t i = 0; i < path.points.size(); ++i) { const auto p = path.points.at(i); @@ -1904,7 +1904,7 @@ bool GoalPlannerModule::checkObjectsCollision( extra_stopping_margin, std::abs(curvatures.at(i) * std::pow(p.point.longitudinal_velocity_mps, 2))); - const auto ego_polygon = autoware_universe_utils::toFootprint( + const auto ego_polygon = autoware::universe_utils::toFootprint( p.point.pose, planner_data->parameters.base_link2front + collision_check_margin + extra_stopping_margin, planner_data->parameters.base_link2rear + collision_check_margin, @@ -2202,7 +2202,7 @@ static std::vector filterOb for (const auto & target_lane : target_lanes) { const auto lane_poly = target_lane.polygon2d().basicPolygon(); for (const auto & filtered_object : filtered_objects.objects) { - const auto object_bbox = autoware_universe_utils::toPolygon2d(filtered_object); + const auto object_bbox = autoware::universe_utils::toPolygon2d(filtered_object); if (boost::geometry::within(object_bbox, lane_poly)) { within_filtered_objects.push_back(filtered_object); } @@ -2285,7 +2285,7 @@ std::pair GoalPlannerModule::isSafePath( lanelet::utils::conversion::toGeomMsgPt(fist_road_lane.centerline().front()); const double lane_yaw = lanelet::utils::getLaneletAngle(fist_road_lane, first_road_point); first_road_pose.position = first_road_point; - first_road_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(lane_yaw); + first_road_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(lane_yaw); // if current ego pose is before pull over lanes segment, use first road lanelet center pose if ( calcSignedArcLength(pull_over_path.points, first_road_pose.position, current_pose.position) < @@ -2362,10 +2362,10 @@ void GoalPlannerModule::setDebugData() { debug_marker_.markers.clear(); - using autoware_motion_utils::createStopVirtualWallMarker; - using autoware_universe_utils::createDefaultMarker; - using autoware_universe_utils::createMarkerColor; - using autoware_universe_utils::createMarkerScale; + using autoware::motion_utils::createStopVirtualWallMarker; + using autoware::universe_utils::createDefaultMarker; + using autoware::universe_utils::createMarkerColor; + using autoware::universe_utils::createMarkerScale; using marker_utils::createObjectsMarkerArray; using marker_utils::createPathMarkerArray; using marker_utils::createPoseMarkerArray; @@ -2380,7 +2380,7 @@ void GoalPlannerModule::setDebugData() for (auto & marker : added.markers) { marker.lifetime = rclcpp::Duration::from_seconds(1.5); } - autoware_universe_utils::appendMarkerArray(added, &debug_marker_); + autoware::universe_utils::appendMarkerArray(added, &debug_marker_); }; if (utils::isAllowedGoalModification(planner_data_->route_handler)) { // Visualize pull over areas @@ -2428,10 +2428,10 @@ void GoalPlannerModule::setDebugData() createPathMarkerArray(partial_path, "partial_path_" + std::to_string(i), 0, 0.9, 0.5, 0.9)); } - auto marker = autoware_universe_utils::createDefaultMarker( + auto marker = autoware::universe_utils::createDefaultMarker( "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "detection_polygons", 0, Marker::LINE_LIST, - autoware_universe_utils::createMarkerScale(0.01, 0.0, 0.0), - autoware_universe_utils::createMarkerColor(0.0, 0.0, 1.0, 0.999)); + autoware::universe_utils::createMarkerScale(0.01, 0.0, 0.0), + autoware::universe_utils::createMarkerColor(0.0, 0.0, 1.0, 0.999)); const double ego_z = planner_data_->self_odometry->pose.pose.position.z; for (const auto & ego_polygon : debug_data_.ego_polygons_expanded) { for (size_t ep_idx = 0; ep_idx < ego_polygon.outer().size(); ++ep_idx) { @@ -2439,19 +2439,19 @@ void GoalPlannerModule::setDebugData() const auto & next_point = ego_polygon.outer().at((ep_idx + 1) % ego_polygon.outer().size()); marker.points.push_back( - autoware_universe_utils::createPoint(current_point.x(), current_point.y(), ego_z)); + autoware::universe_utils::createPoint(current_point.x(), current_point.y(), ego_z)); marker.points.push_back( - autoware_universe_utils::createPoint(next_point.x(), next_point.y(), ego_z)); + autoware::universe_utils::createPoint(next_point.x(), next_point.y(), ego_z)); } } debug_marker_.markers.push_back(marker); if (parameters_->safety_check_params.enable_safety_check) { - autoware_universe_utils::appendMarkerArray( + autoware::universe_utils::appendMarkerArray( goal_planner_utils::createLaneletPolygonMarkerArray( debug_data_.expanded_pull_over_lane_between_ego.polygon3d(), header, "expanded_pull_over_lane_between_ego", - autoware_universe_utils::createMarkerColor(1.0, 0.7, 0.0, 0.999)), + autoware::universe_utils::createMarkerColor(1.0, 0.7, 0.0, 0.999)), &debug_marker_); } @@ -2578,7 +2578,7 @@ void GoalPlannerModule::printParkingPositionError() const real_shoulder_to_map_shoulder + parameters_->margin_from_boundary - dy; RCLCPP_INFO( getLogger(), "current pose to goal, dx:%f dy:%f dyaw:%f from_real_shoulder:%f", dx, dy, - autoware_universe_utils::rad2deg( + autoware::universe_utils::rad2deg( tf2::getYaw(current_pose.orientation) - tf2::getYaw(thread_safe_data_.get_modified_goal_pose()->goal_pose.orientation)), distance_from_real_shoulder); @@ -2634,7 +2634,7 @@ void GoalPlannerModule::GoalPlannerData::update( const PlannerData & planner_data_, const ModuleStatus & current_status_, const BehaviorModuleOutput & previous_module_output_, const std::shared_ptr goal_searcher_, - const autoware_universe_utils::LinearRing2d & vehicle_footprint_) + const autoware::universe_utils::LinearRing2d & vehicle_footprint_) { parameters = parameters_; ego_predicted_path_params = ego_predicted_path_params_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp index 564d22f2df2eb..04ee5278912ac 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp @@ -33,7 +33,7 @@ namespace autoware::behavior_path_planner { using autoware::lane_departure_checker::LaneDepartureChecker; -using autoware_universe_utils::calcOffsetPose; +using autoware::universe_utils::calcOffsetPose; using lanelet::autoware::NoParkingArea; using lanelet::autoware::NoStoppingArea; @@ -136,7 +136,7 @@ GoalCandidates GoalSearcher::search( // todo(kosuke55): fix orientation for inverseTransformPoint temporarily Pose center_pose = p.point.pose; center_pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(tf2::getYaw(center_pose.orientation)); + autoware::universe_utils::createQuaternionFromYaw(tf2::getYaw(center_pose.orientation)); // ignore goal_pose near lane start const double distance_from_lane_start = @@ -156,7 +156,7 @@ GoalCandidates GoalSearcher::search( // original means non lateral offset poses const Pose original_search_pose = calcOffsetPose(center_pose, 0, offset_from_center_line, 0); const double longitudinal_distance_from_original_goal = - std::abs(autoware_motion_utils::calcSignedArcLength( + std::abs(autoware::motion_utils::calcSignedArcLength( center_line_path.points, reference_goal_pose_.position, original_search_pose.position)); original_search_poses.push_back(original_search_pose); // for createAreaPolygon Pose search_pose{}; @@ -167,7 +167,7 @@ GoalCandidates GoalSearcher::search( search_pose = calcOffsetPose(original_search_pose, 0, sign * dy, 0); const auto transformed_vehicle_footprint = - transformVector(vehicle_footprint_, autoware_universe_utils::pose2transform(search_pose)); + transformVector(vehicle_footprint_, autoware::universe_utils::pose2transform(search_pose)); if (isInAreas(transformed_vehicle_footprint, getNoParkingAreaPolygons(pull_over_lanes))) { // break here to exclude goals located laterally in no_parking_areas @@ -245,8 +245,8 @@ void GoalSearcher::countObjectsToAvoid( for (const auto & object : objects.objects) { for (const auto & p : current_center_line_path.points) { const auto transformed_vehicle_footprint = - transformVector(vehicle_footprint_, autoware_universe_utils::pose2transform(p.point.pose)); - const auto obj_polygon = autoware_universe_utils::toPolygon2d(object); + transformVector(vehicle_footprint_, autoware::universe_utils::pose2transform(p.point.pose)); + const auto obj_polygon = autoware::universe_utils::toPolygon2d(object); const double distance = boost::geometry::distance(obj_polygon, transformed_vehicle_footprint); if (distance > parameters_.object_recognition_collision_check_hard_margins.back()) { continue; @@ -431,9 +431,9 @@ bool GoalSearcher::checkCollisionWithLongitudinalDistance( void GoalSearcher::createAreaPolygons( std::vector original_search_poses, const std::shared_ptr & planner_data) { - using autoware_universe_utils::MultiPolygon2d; - using autoware_universe_utils::Point2d; - using autoware_universe_utils::Polygon2d; + using autoware::universe_utils::MultiPolygon2d; + using autoware::universe_utils::Point2d; + using autoware::universe_utils::Polygon2d; const double vehicle_width = planner_data->parameters.vehicle_width; const double base_link2front = planner_data->parameters.base_link2front; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp index 098405f2378b5..901fe351fc68b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp @@ -428,7 +428,7 @@ void GoalPlannerModuleManager::updateModuleParams( // object_recognition_collision_check_hard_margins, maximum_deceleration, shift_sampling_num or // parking_policy, there seems to be a problem when we use a temp value to check these values. - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; auto & p = parameters_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp index 46b4c66a7c9fa..beb27c67833ea 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/shift_pull_over.cpp @@ -101,7 +101,7 @@ std::optional ShiftPullOver::cropPrevModulePath( const PathWithLaneId & prev_module_path, const Pose & shift_end_pose) const { // clip previous module path to shift end pose nearest segment index - const size_t shift_end_idx = autoware_motion_utils::findNearestSegmentIndex( + const size_t shift_end_idx = autoware::motion_utils::findNearestSegmentIndex( prev_module_path.points, shift_end_pose.position); std::vector clipped_points{ prev_module_path.points.begin(), prev_module_path.points.begin() + shift_end_idx}; @@ -111,10 +111,10 @@ std::optional ShiftPullOver::cropPrevModulePath( // add projected shift end pose to clipped points PathPointWithLaneId projected_point = clipped_points.back(); - const double offset = autoware_motion_utils::calcSignedArcLength( + const double offset = autoware::motion_utils::calcSignedArcLength( prev_module_path.points, shift_end_idx, shift_end_pose.position); projected_point.point.pose = - autoware_universe_utils::calcOffsetPose(clipped_points.back().point.pose, offset, 0, 0); + autoware::universe_utils::calcOffsetPose(clipped_points.back().point.pose, offset, 0, 0); clipped_points.push_back(projected_point); auto clipped_prev_module_path = prev_module_path; clipped_prev_module_path.points = clipped_points; @@ -131,7 +131,7 @@ std::optional ShiftPullOver::generatePullOverPath( // shift end pose is longitudinal offset from goal pose to improve parking angle accuracy const Pose shift_end_pose = - autoware_universe_utils::calcOffsetPose(goal_pose, -after_shift_straight_distance, 0, 0); + autoware::universe_utils::calcOffsetPose(goal_pose, -after_shift_straight_distance, 0, 0); // calculate lateral shift of previous module path terminal pose from road lane reference path const auto road_lane_reference_path_to_shift_end = utils::resamplePathWithSpline( @@ -162,7 +162,7 @@ std::optional ShiftPullOver::generatePullOverPath( const Pose & shift_end_pose_prev_module_path = processed_prev_module_path->points.back().point.pose; const double shift_end_road_to_target_distance = - autoware_universe_utils::inverseTransformPoint( + autoware::universe_utils::inverseTransformPoint( shift_end_pose.position, shift_end_pose_prev_module_path) .y; @@ -171,7 +171,7 @@ std::optional ShiftPullOver::generatePullOverPath( shift_end_road_to_target_distance, lateral_jerk, pull_over_velocity); const double before_shifted_pull_over_distance = calcBeforeShiftedArcLength( processed_prev_module_path.value(), pull_over_distance, shift_end_road_to_target_distance); - const auto shift_start_pose = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto shift_start_pose = autoware::motion_utils::calcLongitudinalOffsetPose( processed_prev_module_path->points, shift_end_pose_prev_module_path.position, -before_shifted_pull_over_distance); @@ -188,8 +188,8 @@ std::optional ShiftPullOver::generatePullOverPath( if (!path_shifter.generate(&shifted_path, offset_back)) { return {}; } - shifted_path.path.points = autoware_motion_utils::removeOverlapPoints(shifted_path.path.points); - autoware_motion_utils::insertOrientation(shifted_path.path.points, true); + shifted_path.path.points = autoware::motion_utils::removeOverlapPoints(shifted_path.path.points); + autoware::motion_utils::insertOrientation(shifted_path.path.points, true); // set same orientation, because the reference center line orientation is not same to the shifted_path.path.points.back().point.pose.orientation = shift_end_pose.orientation; @@ -309,7 +309,7 @@ double ShiftPullOver::calcBeforeShiftedArcLength( double before_arc_length{0.0}; double after_arc_length{0.0}; for (const auto & [k, segment_length] : - autoware_motion_utils::calcCurvatureAndArcLength(reversed_path.points)) { + autoware::motion_utils::calcCurvatureAndArcLength(reversed_path.points)) { // after shifted segment length const double after_segment_length = k > 0 ? segment_length * (1 + k * dr) : segment_length / (1 - k * dr); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp index f99a240f291a7..99bef9c243508 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp @@ -38,11 +38,11 @@ namespace autoware::behavior_path_planner::goal_planner_utils { -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerScale; -using autoware_universe_utils::createPoint; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerScale; +using autoware::universe_utils::createPoint; lanelet::ConstLanelets getPullOverLanes( const RouteHandler & route_handler, const bool left_side, const double backward_distance, @@ -116,9 +116,9 @@ lanelet::ConstLanelets generateBetweenEgoAndExpandedPullOverLanes( const double ego_length_to_front = wheel_base + front_overhang; const double ego_width_to_front = !left_side ? (-wheel_tread / 2.0 - side_overhang) : (wheel_tread / 2.0 + side_overhang); - autoware_universe_utils::Point2d front_edge_local{ego_length_to_front, ego_width_to_front}; - const auto front_edge_glob = autoware_universe_utils::transformPoint( - front_edge_local, autoware_universe_utils::pose2transform(ego_pose)); + autoware::universe_utils::Point2d front_edge_local{ego_length_to_front, ego_width_to_front}; + const auto front_edge_glob = autoware::universe_utils::transformPoint( + front_edge_local, autoware::universe_utils::pose2transform(ego_pose)); geometry_msgs::msg::Pose ego_front_pose; ego_front_pose.position = createPoint(front_edge_glob.x(), front_edge_glob.y(), ego_pose.position.z); @@ -180,8 +180,8 @@ PredictedObjects filterObjectsByLateralDistance( } MarkerArray createPullOverAreaMarkerArray( - const autoware_universe_utils::MultiPolygon2d area_polygons, const std_msgs::msg::Header & header, - const std_msgs::msg::ColorRGBA & color, const double z) + const autoware::universe_utils::MultiPolygon2d area_polygons, + const std_msgs::msg::Header & header, const std_msgs::msg::ColorRGBA & color, const double z) { MarkerArray marker_array{}; for (size_t i = 0; i < area_polygons.size(); ++i) { @@ -205,7 +205,7 @@ MarkerArray createPosesMarkerArray( MarkerArray msg{}; int32_t i = 0; for (const auto & pose : poses) { - Marker marker = autoware_universe_utils::createDefaultMarker( + Marker marker = autoware::universe_utils::createDefaultMarker( "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, i, Marker::ARROW, createMarkerScale(0.5, 0.25, 0.25), color); marker.pose = pose; @@ -305,11 +305,11 @@ double calcLateralDeviationBetweenPaths( { double lateral_deviation = 0.0; for (const auto & target_point : target_path.points) { - const size_t nearest_index = autoware_motion_utils::findNearestIndex( + const size_t nearest_index = autoware::motion_utils::findNearestIndex( reference_path.points, target_point.point.pose.position); lateral_deviation = std::max( lateral_deviation, - std::abs(autoware_universe_utils::calcLateralDeviation( + std::abs(autoware::universe_utils::calcLateralDeviation( reference_path.points[nearest_index].point.pose, target_point.point.pose.position))); } return lateral_deviation; @@ -326,7 +326,7 @@ bool isReferencePath( std::optional cropPath(const PathWithLaneId & path, const Pose & end_pose) { const size_t end_idx = - autoware_motion_utils::findNearestSegmentIndex(path.points, end_pose.position); + autoware::motion_utils::findNearestSegmentIndex(path.points, end_pose.position); std::vector clipped_points{ path.points.begin(), path.points.begin() + end_idx}; if (clipped_points.empty()) { @@ -336,9 +336,9 @@ std::optional cropPath(const PathWithLaneId & path, const Pose & // add projected end pose to clipped points PathPointWithLaneId projected_point = clipped_points.back(); const double offset = - autoware_motion_utils::calcSignedArcLength(path.points, end_idx, end_pose.position); + autoware::motion_utils::calcSignedArcLength(path.points, end_idx, end_pose.position); projected_point.point.pose = - autoware_universe_utils::calcOffsetPose(clipped_points.back().point.pose, offset, 0, 0); + autoware::universe_utils::calcOffsetPose(clipped_points.back().point.pose, offset, 0, 0); clipped_points.push_back(projected_point); auto clipped_path = path; clipped_path.points = clipped_points; @@ -354,7 +354,7 @@ PathWithLaneId cropForwardPoints( double sum_length = 0; for (size_t i = target_seg_idx + 1; i < points.size(); ++i) { const double seg_length = - autoware_universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); + autoware::universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); if (forward_length < sum_length + seg_length) { const auto cropped_points = std::vector{points.begin() + target_seg_idx, points.begin() + i}; @@ -393,7 +393,7 @@ PathWithLaneId extendPath( const auto & target_terminal_pose = target_path.points.back().point.pose; // generate clipped road lane reference path from previous module path terminal pose to shift end - const size_t target_path_terminal_idx = autoware_motion_utils::findNearestSegmentIndex( + const size_t target_path_terminal_idx = autoware::motion_utils::findNearestSegmentIndex( reference_path.points, target_terminal_pose.position); PathWithLaneId clipped_path = @@ -401,9 +401,9 @@ PathWithLaneId extendPath( // shift clipped path to previous module path terminal pose const double lateral_shift_from_reference_path = - autoware_motion_utils::calcLateralOffset(reference_path.points, target_terminal_pose.position); + autoware::motion_utils::calcLateralOffset(reference_path.points, target_terminal_pose.position); for (auto & p : clipped_path.points) { - p.point.pose = autoware_universe_utils::calcOffsetPose( + p.point.pose = autoware::universe_utils::calcOffsetPose( p.point.pose, 0, lateral_shift_from_reference_path, 0); } @@ -411,15 +411,15 @@ PathWithLaneId extendPath( const auto start_point = std::find_if(clipped_path.points.begin(), clipped_path.points.end(), [&](const auto & p) { const bool is_forward = - autoware_universe_utils::inverseTransformPoint(p.point.pose.position, target_terminal_pose) + autoware::universe_utils::inverseTransformPoint(p.point.pose.position, target_terminal_pose) .x > 0.0; - const bool is_close = autoware_universe_utils::calcDistance2d( + const bool is_close = autoware::universe_utils::calcDistance2d( p.point.pose.position, target_terminal_pose.position) < 0.1; return is_forward && !is_close; }); std::copy(start_point, clipped_path.points.end(), std::back_inserter(extended_path.points)); - extended_path.points = autoware_motion_utils::removeOverlapPoints(extended_path.points); + extended_path.points = autoware::motion_utils::removeOverlapPoints(extended_path.points); return extended_path; } @@ -429,9 +429,9 @@ PathWithLaneId extendPath( const Pose & extend_pose) { const auto & target_terminal_pose = target_path.points.back().point.pose; - const size_t target_path_terminal_idx = autoware_motion_utils::findNearestSegmentIndex( + const size_t target_path_terminal_idx = autoware::motion_utils::findNearestSegmentIndex( reference_path.points, target_terminal_pose.position); - const double extend_distance = autoware_motion_utils::calcSignedArcLength( + const double extend_distance = autoware::motion_utils::calcSignedArcLength( reference_path.points, target_path_terminal_idx, extend_pose.position); return extendPath(target_path, reference_path, extend_distance); @@ -445,7 +445,7 @@ std::vector createPathFootPrints( for (const auto & point : path.points) { const auto & pose = point.point.pose; footprints.push_back( - autoware_universe_utils::toFootprint(pose, base_to_front, base_to_rear, width)); + autoware::universe_utils::toFootprint(pose, base_to_front, base_to_rear, width)); } return footprints; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp index 89f5f715549bd..229f46f89377f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp @@ -37,7 +37,7 @@ namespace autoware::behavior_path_planner { using autoware::route_handler::Direction; -using autoware_universe_utils::StopWatch; +using autoware::universe_utils::StopWatch; using data::lane_change::PathSafetyStatus; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index 3162b99b441d1..4071c39568987 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -44,10 +44,10 @@ using autoware::behavior_path_planner::utils::path_safety_checker:: using autoware::behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; using autoware::behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon; using autoware::route_handler::Direction; +using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::PredictedPath; -using autoware_universe_utils::Polygon2d; using data::lane_change::LanesPolygon; using data::lane_change::PathSafetyStatus; using geometry_msgs::msg::Point; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 435769231e08c..0a5b31f9e32d2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -29,7 +29,7 @@ namespace autoware::behavior_path_planner { -using autoware_universe_utils::appendMarkerArray; +using autoware::universe_utils::appendMarkerArray; using utils::lane_change::assignToCandidate; LaneChangeInterface::LaneChangeInterface( @@ -352,9 +352,9 @@ void LaneChangeInterface::updateSteeringFactorPtr(const BehaviorModuleOutput & o const auto current_position = module_type_->getEgoPosition(); const auto status = module_type_->getLaneChangeStatus(); - const auto start_distance = autoware_motion_utils::calcSignedArcLength( + const auto start_distance = autoware::motion_utils::calcSignedArcLength( output.path.points, current_position, status.lane_change_path.info.shift_line.start.position); - const auto finish_distance = autoware_motion_utils::calcSignedArcLength( + const auto finish_distance = autoware::motion_utils::calcSignedArcLength( output.path.points, current_position, status.lane_change_path.info.shift_line.end.position); steering_factor_interface_ptr_->updateSteeringFactor( diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index 1e066d297f878..61ff54e8f99f3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -36,7 +36,7 @@ void LaneChangeModuleManager::init(rclcpp::Node * node) void LaneChangeModuleManager::initParams(rclcpp::Node * node) { - using autoware_universe_utils::getOrDeclareParameter; + using autoware::universe_utils::getOrDeclareParameter; LaneChangeParameters p{}; @@ -281,7 +281,7 @@ std::unique_ptr LaneChangeModuleManager::createNewSceneMod void LaneChangeModuleManager::updateModuleParams(const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; auto p = parameters_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index f00c68c8651fe..505bb3ef93340 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -37,7 +37,7 @@ namespace autoware::behavior_path_planner { -using autoware_motion_utils::calcSignedArcLength; +using autoware::motion_utils::calcSignedArcLength; using utils::lane_change::calcMinimumLaneChangeLength; using utils::lane_change::createLanesPolygon; using utils::path_safety_checker::isPolygonOverlapLanelet; @@ -182,12 +182,12 @@ TurnSignalInfo NormalLaneChange::get_current_turn_signal_info() const double buffer = next_lane_change_buffer + min_length_for_turn_signal_activation + base_to_front; - const double path_length = autoware_motion_utils::calcArcLength(path.points); + const double path_length = autoware::motion_utils::calcArcLength(path.points); const size_t current_nearest_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, nearest_dist_threshold, nearest_yaw_threshold); const double dist_to_terminal = utils::getDistanceToEndOfLane(current_pose, current_lanes); - const auto start_pose = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto start_pose = autoware::motion_utils::calcLongitudinalOffsetPose( path.points, 0, std::max(path_length - buffer, 0.0)); if (dist_to_terminal - base_to_front < buffer && start_pose) { // modify turn signal @@ -389,10 +389,10 @@ void NormalLaneChange::insertStopPoint( // calculate distance from path front to the stationary object polygon on the ego lane. const auto polygon = - autoware_universe_utils::toPolygon2d(object.initial_pose.pose, object.shape).outer(); + autoware::universe_utils::toPolygon2d(object.initial_pose.pose, object.shape).outer(); for (const auto & polygon_p : polygon) { - const auto p_fp = autoware_universe_utils::toMsg(polygon_p.to_3d()); - const auto lateral_fp = autoware_motion_utils::calcLateralOffset(path.points, p_fp); + const auto p_fp = autoware::universe_utils::toMsg(polygon_p.to_3d()); + const auto lateral_fp = autoware::motion_utils::calcLateralOffset(path.points, p_fp); // ignore if the point is around the ego path if (std::abs(lateral_fp) > planner_data_->parameters.vehicle_width) { @@ -442,7 +442,7 @@ void NormalLaneChange::insertStopPoint( // target_objects includes objects out of target lanes, so filter them out if (!boost::geometry::intersects( - autoware_universe_utils::toPolygon2d(o.initial_pose.pose, o.shape).outer(), + autoware::universe_utils::toPolygon2d(o.initial_pose.pose, o.shape).outer(), lanelet::utils::combineLaneletsShape(status_.target_lanes) .polygon2d() .basicPolygon())) { @@ -690,7 +690,7 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const return false; } - const auto nearest_idx = autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + const auto nearest_idx = autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( status_.lane_change_path.path.points, getEgoPose(), planner_data_->parameters.ego_nearest_dist_threshold, planner_data_->parameters.ego_nearest_yaw_threshold); @@ -729,7 +729,7 @@ bool NormalLaneChange::isAbleToStopSafely() const return false; } - const auto nearest_idx = autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + const auto nearest_idx = autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( status_.lane_change_path.path.points, getEgoPose(), planner_data_->parameters.ego_nearest_dist_threshold, planner_data_->parameters.ego_nearest_yaw_threshold); @@ -798,7 +798,7 @@ std::pair NormalLaneChange::calcCurrentMinMaxAcceleration() cons const auto vehicle_min_acc = std::max(p.min_acc, lane_change_parameters_->min_longitudinal_acc); const auto vehicle_max_acc = std::min(p.max_acc, lane_change_parameters_->max_longitudinal_acc); - const auto ego_seg_idx = autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + const auto ego_seg_idx = autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( prev_module_output_.path.points, getEgoPose(), p.ego_nearest_dist_threshold, p.ego_nearest_yaw_threshold); const auto max_path_velocity = @@ -915,7 +915,7 @@ PathWithLaneId NormalLaneChange::getPrepareSegment( auto prepare_segment = prev_module_output_.path; const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( prepare_segment.points, getEgoPose(), 3.0, 1.0); utils::clipPathLength(prepare_segment, current_seg_idx, prepare_length, backward_path_length); @@ -992,11 +992,11 @@ LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects( } const auto is_ahead_of_ego = [&path, ¤t_pose](const auto & object) { - const auto obj_polygon = autoware_universe_utils::toPolygon2d(object).outer(); + const auto obj_polygon = autoware::universe_utils::toPolygon2d(object).outer(); double max_dist_ego_to_obj = std::numeric_limits::lowest(); for (const auto & polygon_p : obj_polygon) { - const auto obj_p = autoware_universe_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); + const auto obj_p = autoware::universe_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); const auto dist_ego_to_obj = calcSignedArcLength(path.points, current_pose.position, obj_p); max_dist_ego_to_obj = std::max(dist_ego_to_obj, max_dist_ego_to_obj); } @@ -1084,11 +1084,11 @@ void NormalLaneChange::filterAheadTerminalObjects( // ignore object that are ahead of terminal lane change start utils::path_safety_checker::filterObjects(objects, [&](const PredictedObject & object) { - const auto obj_polygon = autoware_universe_utils::toPolygon2d(object).outer(); + const auto obj_polygon = autoware::universe_utils::toPolygon2d(object).outer(); // ignore object that are ahead of terminal lane change start auto distance_to_terminal_from_object = std::numeric_limits::max(); for (const auto & polygon_p : obj_polygon) { - const auto obj_p = autoware_universe_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); + const auto obj_p = autoware::universe_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); Pose polygon_pose; polygon_pose.position = obj_p; polygon_pose.orientation = object.kinematics.initial_pose_with_covariance.pose.orientation; @@ -1668,7 +1668,7 @@ std::optional NormalLaneChange::calcTerminalLaneChangePath( utils::getDistanceToEndOfLane(route_handler.getGoalPose(), current_lanes); } - const auto lane_changing_start_pose = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto lane_changing_start_pose = autoware::motion_utils::calcLongitudinalOffsetPose( prev_module_output_.path.points, current_lane_terminal_point, -(lane_change_buffer + next_lane_change_buffer + distance_to_terminal_from_goal)); @@ -1753,7 +1753,7 @@ std::optional NormalLaneChange::calcTerminalLaneChangePath( target_lane_reference_path, shift_length); auto reference_segment = prev_module_output_.path; - const double length_to_lane_changing_start = autoware_motion_utils::calcSignedArcLength( + const double length_to_lane_changing_start = autoware::motion_utils::calcSignedArcLength( reference_segment.points, reference_segment.points.front().point.pose.position, lane_changing_start_pose->position); utils::clipPathLength(reference_segment, 0, length_to_lane_changing_start, 0.0); @@ -1895,12 +1895,12 @@ bool NormalLaneChange::calcAbortPath() lanelet::utils::getLaneletLength2d(reference_lanelets) - minimum_lane_change_length, 0.0); const auto ref = route_handler->getCenterLinePath(reference_lanelets, s_start, s_end); - return autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( lane_changing_path.points, ref.points.back().point.pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); }); - const auto ego_pose_idx = autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + const auto ego_pose_idx = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( lane_changing_path.points, current_pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); const auto get_abort_idx_and_distance = [&](const double param_time) { @@ -1982,10 +1982,10 @@ bool NormalLaneChange::calcAbortPath() // reference_lane_segment = terminal_path->path; // } const auto return_pose = shifted_path.path.points.at(abort_return_idx).point.pose; - const auto seg_idx = autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + const auto seg_idx = autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( reference_lane_segment.points, return_pose, common_param.ego_nearest_dist_threshold, common_param.ego_nearest_yaw_threshold); - reference_lane_segment.points = autoware_motion_utils::cropPoints( + reference_lane_segment.points = autoware::motion_utils::cropPoints( reference_lane_segment.points, return_pose.position, seg_idx, common_param.forward_path_length, 0.0); } @@ -2080,7 +2080,7 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( utils::path_safety_checker::updateCollisionCheckDebugMap( debug_data, current_debug_data, is_safe); const auto & obj_pose = obj.initial_pose.pose; - const auto obj_polygon = autoware_universe_utils::toPolygon2d(obj_pose, obj.shape); + const auto obj_polygon = autoware::universe_utils::toPolygon2d(obj_pose, obj.shape); path_safety_status.is_object_coming_from_rear |= !utils::path_safety_checker::isTargetObjectFront( path, current_pose, common_parameters.vehicle_info, obj_polygon); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp index 78db0ba0a1b4f..9a553cf97af5c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp @@ -34,8 +34,8 @@ namespace marker_utils::lane_change_markers { -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerScale; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerScale; using geometry_msgs::msg::Point; MarkerArray showAllValidLaneChangePath(const std::vector & lanes, std::string && ns) @@ -172,7 +172,7 @@ MarkerArray createDebugMarkerArray( MarkerArray debug_marker; const auto add = [&debug_marker](const MarkerArray & added) { - autoware_universe_utils::appendMarkerArray(added, &debug_marker); + autoware::universe_utils::appendMarkerArray(added, &debug_marker); }; if (!debug_data.execution_area.points.empty()) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 7edd2d063348b..d989a1e6d301d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -58,11 +58,11 @@ namespace autoware::behavior_path_planner::utils::lane_change { using autoware::route_handler::RouteHandler; +using autoware::universe_utils::LineString2d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObjects; -using autoware_universe_utils::LineString2d; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; using geometry_msgs::msg::Pose; using tier4_planning_msgs::msg::PathWithLaneId; @@ -368,7 +368,7 @@ std::optional constructCandidatePath( LaneChangePath candidate_path; candidate_path.info = lane_change_info; - const auto lane_change_end_idx = autoware_motion_utils::findNearestIndex( + const auto lane_change_end_idx = autoware::motion_utils::findNearestIndex( shifted_path.path.points, candidate_path.info.lane_changing_end); if (!lane_change_end_idx) { @@ -385,7 +385,7 @@ std::optional constructCandidatePath( continue; } const auto nearest_idx = - autoware_motion_utils::findNearestIndex(target_segment.points, point.point.pose); + autoware::motion_utils::findNearestIndex(target_segment.points, point.point.pose); point.lane_ids = target_segment.points.at(*nearest_idx).lane_ids; } @@ -404,13 +404,13 @@ std::optional constructCandidatePath( std::prev(prepare_segment.points.end() - 1)->point.pose; const auto & lane_change_start_from_shifted = std::next(shifted_path.path.points.begin())->point.pose; - const auto yaw_diff2 = std::abs(autoware_universe_utils::normalizeRadian( + const auto yaw_diff2 = std::abs(autoware::universe_utils::normalizeRadian( tf2::getYaw(prepare_segment_second_last_point.orientation) - tf2::getYaw(lane_change_start_from_shifted.orientation))); - if (yaw_diff2 > autoware_universe_utils::deg2rad(5.0)) { + if (yaw_diff2 > autoware::universe_utils::deg2rad(5.0)) { RCLCPP_DEBUG( get_logger(), "Excessive yaw difference %.3f which exceeds the 5 degrees threshold.", - autoware_universe_utils::rad2deg(yaw_diff2)); + autoware::universe_utils::rad2deg(yaw_diff2)); return std::nullopt; } } @@ -473,10 +473,10 @@ ShiftLine getLaneChangingShiftLine( shift_line.end_shift_length = shift_length; shift_line.start = lane_changing_start_pose; shift_line.end = lane_changing_end_pose; - shift_line.start_idx = autoware_motion_utils::findNearestIndex( + shift_line.start_idx = autoware::motion_utils::findNearestIndex( reference_path.points, lane_changing_start_pose.position); - shift_line.end_idx = - autoware_motion_utils::findNearestIndex(reference_path.points, lane_changing_end_pose.position); + shift_line.end_idx = autoware::motion_utils::findNearestIndex( + reference_path.points, lane_changing_end_pose.position); return shift_line; } @@ -768,9 +768,9 @@ CandidateOutput assignToCandidate( CandidateOutput candidate_output; candidate_output.path_candidate = lane_change_path.path; candidate_output.lateral_shift = utils::lane_change::getLateralShift(lane_change_path); - candidate_output.start_distance_to_path_change = autoware_motion_utils::calcSignedArcLength( + candidate_output.start_distance_to_path_change = autoware::motion_utils::calcSignedArcLength( lane_change_path.path.points, ego_position, lane_change_path.info.shift_line.start.position); - candidate_output.finish_distance_to_path_change = autoware_motion_utils::calcSignedArcLength( + candidate_output.finish_distance_to_path_change = autoware::motion_utils::calcSignedArcLength( lane_change_path.path.points, ego_position, lane_change_path.info.shift_line.end.position); return candidate_output; @@ -807,7 +807,7 @@ std::vector convertToPredictedPath( lane_change_parameters.minimum_lane_changing_velocity; const auto nearest_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, vehicle_pose, common_parameters.ego_nearest_dist_threshold, common_parameters.ego_nearest_yaw_threshold); @@ -821,8 +821,8 @@ std::vector convertToPredictedPath( const double velocity = std::max(initial_velocity + prepare_acc * t, minimum_lane_changing_velocity); const double length = initial_velocity * t + 0.5 * prepare_acc * t * t; - const auto pose = - autoware_motion_utils::calcInterpolatedPose(path.points, vehicle_pose_frenet.length + length); + const auto pose = autoware::motion_utils::calcInterpolatedPose( + path.points, vehicle_pose_frenet.length + length); predicted_path.emplace_back(t, pose, velocity); } @@ -836,8 +836,8 @@ std::vector convertToPredictedPath( const double velocity = lane_changing_velocity + lane_changing_acc * delta_t; const double length = lane_changing_velocity * delta_t + 0.5 * lane_changing_acc * delta_t * delta_t + offset; - const auto pose = - autoware_motion_utils::calcInterpolatedPose(path.points, vehicle_pose_frenet.length + length); + const auto pose = autoware::motion_utils::calcInterpolatedPose( + path.points, vehicle_pose_frenet.length + length); predicted_path.emplace_back(t, pose, velocity); } @@ -870,7 +870,7 @@ bool isParkedObject( const auto & object_pose = object.initial_pose.pose; const auto object_closest_index = - autoware_motion_utils::findNearestIndex(path.points, object_pose.position); + autoware::motion_utils::findNearestIndex(path.points, object_pose.position); const auto object_closest_pose = path.points.at(object_closest_index).point.pose; lanelet::ConstLanelet closest_lanelet; @@ -879,7 +879,7 @@ bool isParkedObject( } const double lat_dist = - autoware_motion_utils::calcLateralOffset(path.points, object_pose.position); + autoware::motion_utils::calcLateralOffset(path.points, object_pose.position); lanelet::BasicLineString2d bound; double center_to_bound_buffer = 0.0; if (lat_dist > 0.0) { @@ -937,7 +937,7 @@ bool isParkedObject( const auto & obj_pose = object.initial_pose.pose; const auto & obj_shape = object.shape; - const auto obj_poly = autoware_universe_utils::toPolygon2d(obj_pose, obj_shape); + const auto obj_poly = autoware::universe_utils::toPolygon2d(obj_pose, obj_shape); const auto obj_point = obj_pose.position; double max_dist_to_bound = std::numeric_limits::lowest(); @@ -996,7 +996,7 @@ bool passParkedObject( const auto & leading_obj = objects.at(*leading_obj_idx); auto debug = utils::path_safety_checker::createObjectDebug(leading_obj); const auto leading_obj_poly = - autoware_universe_utils::toPolygon2d(leading_obj.initial_pose.pose, leading_obj.shape); + autoware::universe_utils::toPolygon2d(leading_obj.initial_pose.pose, leading_obj.shape); if (leading_obj_poly.outer().empty()) { return false; } @@ -1004,13 +1004,13 @@ bool passParkedObject( const auto & current_path_end = current_lane_path.points.back().point.pose.position; double min_dist_to_end_of_current_lane = std::numeric_limits::max(); for (const auto & point : leading_obj_poly.outer()) { - const auto obj_p = autoware_universe_utils::createPoint(point.x(), point.y(), 0.0); - const double dist = - autoware_motion_utils::calcSignedArcLength(current_lane_path.points, obj_p, current_path_end); + const auto obj_p = autoware::universe_utils::createPoint(point.x(), point.y(), 0.0); + const double dist = autoware::motion_utils::calcSignedArcLength( + current_lane_path.points, obj_p, current_path_end); min_dist_to_end_of_current_lane = std::min(dist, min_dist_to_end_of_current_lane); if (is_goal_in_route) { const auto goal_pose = route_handler.getGoalPose(); - const double dist_to_goal = autoware_motion_utils::calcSignedArcLength( + const double dist_to_goal = autoware::motion_utils::calcSignedArcLength( current_lane_path.points, obj_p, goal_pose.position); min_dist_to_end_of_current_lane = std::min(min_dist_to_end_of_current_lane, dist_to_goal); } @@ -1061,14 +1061,14 @@ std::optional getLeadingStaticObjectIdx( continue; } - const double dist_back_to_obj = autoware_motion_utils::calcSignedArcLength( + const double dist_back_to_obj = autoware::motion_utils::calcSignedArcLength( path.points, path_end.point.pose.position, obj_pose.position); if (dist_back_to_obj > 0.0) { // object is not on the lane change path continue; } - const double dist_lc_start_to_obj = autoware_motion_utils::calcSignedArcLength( + const double dist_lc_start_to_obj = autoware::motion_utils::calcSignedArcLength( path.points, lane_change_start.position, obj_pose.position); if (dist_lc_start_to_obj < 0.0) { // object is on the lane changing path or behind it. It will be detected in safety check @@ -1124,7 +1124,7 @@ ExtendedPredictedObject transform( } const auto obj_pose = object_recognition_utils::calcInterpolatedPose(path, t); if (obj_pose) { - const auto obj_polygon = autoware_universe_utils::toPolygon2d(*obj_pose, object.shape); + const auto obj_polygon = autoware::universe_utils::toPolygon2d(*obj_pose, object.shape); extended_object.predicted_paths.at(i).path.emplace_back( t, *obj_pose, obj_vel_norm, obj_polygon); } @@ -1167,7 +1167,7 @@ Polygon2d getEgoCurrentFootprint( const auto base_to_rear = ego_info.rear_overhang_m; const auto width = ego_info.vehicle_width_m; - return autoware_universe_utils::toFootprint(ego_pose, base_to_front, base_to_rear, width); + return autoware::universe_utils::toFootprint(ego_pose, base_to_front, base_to_rear, width); } bool isWithinIntersection( @@ -1255,13 +1255,13 @@ geometry_msgs::msg::Polygon createExecutionArea( const double lat_offset = width / 2.0 + additional_lat_offset; const auto p1 = - autoware_universe_utils::calcOffsetPose(pose, forward_lon_offset, lat_offset, 0.0); + autoware::universe_utils::calcOffsetPose(pose, forward_lon_offset, lat_offset, 0.0); const auto p2 = - autoware_universe_utils::calcOffsetPose(pose, forward_lon_offset, -lat_offset, 0.0); + autoware::universe_utils::calcOffsetPose(pose, forward_lon_offset, -lat_offset, 0.0); const auto p3 = - autoware_universe_utils::calcOffsetPose(pose, backward_lon_offset, -lat_offset, 0.0); + autoware::universe_utils::calcOffsetPose(pose, backward_lon_offset, -lat_offset, 0.0); const auto p4 = - autoware_universe_utils::calcOffsetPose(pose, backward_lon_offset, lat_offset, 0.0); + autoware::universe_utils::calcOffsetPose(pose, backward_lon_offset, lat_offset, 0.0); geometry_msgs::msg::Polygon polygon; polygon.points.push_back(create_point32(p1)); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_utils.cpp index a31172ac0050b..68547a491324d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_utils.cpp @@ -24,16 +24,16 @@ constexpr double epsilon = 1e-6; TEST(BehaviorPathPlanningLaneChangeUtilsTest, projectCurrentPoseToTarget) { geometry_msgs::msg::Pose ego_pose; - const auto ego_yaw = autoware_universe_utils::deg2rad(0.0); - ego_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(ego_yaw); - ego_pose.position = autoware_universe_utils::createPoint(0, 0, 0); + const auto ego_yaw = autoware::universe_utils::deg2rad(0.0); + ego_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(ego_yaw); + ego_pose.position = autoware::universe_utils::createPoint(0, 0, 0); geometry_msgs::msg::Pose obj_pose; - const auto obj_yaw = autoware_universe_utils::deg2rad(0.0); - obj_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(obj_yaw); - obj_pose.position = autoware_universe_utils::createPoint(-4, 3, 0); + const auto obj_yaw = autoware::universe_utils::deg2rad(0.0); + obj_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(obj_yaw); + obj_pose.position = autoware::universe_utils::createPoint(-4, 3, 0); - const auto result = autoware_universe_utils::inverseTransformPose(obj_pose, ego_pose); + const auto result = autoware::universe_utils::inverseTransformPose(obj_pose, ego_pose); EXPECT_NEAR(result.position.x, -4, epsilon); EXPECT_NEAR(result.position.y, 3, epsilon); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp index 1420926f32bd7..3c62cc241b323 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp @@ -88,30 +88,30 @@ class BehaviorPathPlannerNode : public rclcpp::Node private: // subscriber - autoware_universe_utils::InterProcessPollingSubscriber route_subscriber_{ + autoware::universe_utils::InterProcessPollingSubscriber route_subscriber_{ this, "~/input/route", rclcpp::QoS{1}.transient_local()}; - autoware_universe_utils::InterProcessPollingSubscriber vector_map_subscriber_{ + autoware::universe_utils::InterProcessPollingSubscriber vector_map_subscriber_{ this, "~/input/vector_map", rclcpp::QoS{1}.transient_local()}; - autoware_universe_utils::InterProcessPollingSubscriber velocity_subscriber_{ + autoware::universe_utils::InterProcessPollingSubscriber velocity_subscriber_{ this, "~/input/odometry"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber acceleration_subscriber_{this, "~/input/accel"}; - autoware_universe_utils::InterProcessPollingSubscriber scenario_subscriber_{ + autoware::universe_utils::InterProcessPollingSubscriber scenario_subscriber_{ this, "~/input/scenario"}; - autoware_universe_utils::InterProcessPollingSubscriber perception_subscriber_{ + autoware::universe_utils::InterProcessPollingSubscriber perception_subscriber_{ this, "~/input/perception"}; - autoware_universe_utils::InterProcessPollingSubscriber occupancy_grid_subscriber_{ + autoware::universe_utils::InterProcessPollingSubscriber occupancy_grid_subscriber_{ this, "~/input/occupancy_grid_map"}; - autoware_universe_utils::InterProcessPollingSubscriber costmap_subscriber_{ + autoware::universe_utils::InterProcessPollingSubscriber costmap_subscriber_{ this, "~/input/costmap"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber traffic_signals_subscriber_{this, "~/input/traffic_signals"}; - autoware_universe_utils::InterProcessPollingSubscriber lateral_offset_subscriber_{ + autoware::universe_utils::InterProcessPollingSubscriber lateral_offset_subscriber_{ this, "~/input/lateral_offset"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber operation_mode_subscriber_{ this, "/system/operation_mode/state", rclcpp::QoS{1}.transient_local()}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber external_limit_max_velocity_subscriber_{this, "/planning/scenario_planning/max_velocity"}; // publisher @@ -236,9 +236,9 @@ class BehaviorPathPlannerNode : public rclcpp::Node const std::shared_ptr & path_candidate_ptr, const bool is_ready, const std::shared_ptr & planner_data); - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; }; } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp index ecd9dd37c363a..a76284b70b7d8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp @@ -39,12 +39,12 @@ namespace autoware::behavior_path_planner { -using autoware_universe_utils::StopWatch; +using autoware::universe_utils::StopWatch; using tier4_planning_msgs::msg::PathWithLaneId; using tier4_planning_msgs::msg::StopReasonArray; using SceneModulePtr = std::shared_ptr; using SceneModuleManagerPtr = std::shared_ptr; -using DebugPublisher = autoware_universe_utils::DebugPublisher; +using DebugPublisher = autoware::universe_utils::DebugPublisher; using DebugDoubleMsg = tier4_debug_msgs::msg::Float64Stamped; using DebugStringMsg = tier4_debug_msgs::msg::StringStamped; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp index 378d8f9c5a5f2..0e586211bc9ee 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp @@ -114,9 +114,9 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod this, get_clock(), period_ns, std::bind(&BehaviorPathPlannerNode::run, this)); } - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } std::vector BehaviorPathPlannerNode::getWaitingApprovalModules() @@ -445,7 +445,7 @@ void BehaviorPathPlannerNode::run() const auto current_pose = planner_data_->self_odometry->pose.pose; if (!path->points.empty()) { const size_t current_seg_idx = planner_data_->findEgoSegmentIndex(path->points); - path->points = autoware_motion_utils::cropPoints( + path->points = autoware::motion_utils::cropPoints( path->points, current_pose.position, current_seg_idx, planner_data_->parameters.forward_path_length, planner_data_->parameters.backward_path_length + @@ -472,7 +472,7 @@ void BehaviorPathPlannerNode::run() if ( output.modified_goal && /* has changed modified goal */ ( - !planner_data_->prev_modified_goal || autoware_universe_utils::calcDistance2d( + !planner_data_->prev_modified_goal || autoware::universe_utils::calcDistance2d( planner_data_->prev_modified_goal->pose.position, output.modified_goal->pose.position) > 0.01)) { PoseWithUuidStamped modified_goal = *(output.modified_goal); @@ -566,29 +566,29 @@ void BehaviorPathPlannerNode::publish_turn_signal_debug_data(const TurnSignalDeb constexpr double scale_x = 1.0; constexpr double scale_y = 1.0; constexpr double scale_z = 1.0; - const auto scale = autoware_universe_utils::createMarkerScale(scale_x, scale_y, scale_z); + const auto scale = autoware::universe_utils::createMarkerScale(scale_x, scale_y, scale_z); const auto desired_section_color = - autoware_universe_utils::createMarkerColor(0.0, 1.0, 0.0, 0.999); + autoware::universe_utils::createMarkerColor(0.0, 1.0, 0.0, 0.999); const auto required_section_color = - autoware_universe_utils::createMarkerColor(1.0, 0.0, 1.0, 0.999); + autoware::universe_utils::createMarkerColor(1.0, 0.0, 1.0, 0.999); // intersection turn signal info { const auto & turn_signal_info = debug_data.intersection_turn_signal_info; - auto desired_start_marker = autoware_universe_utils::createDefaultMarker( + auto desired_start_marker = autoware::universe_utils::createDefaultMarker( "map", current_time, "intersection_turn_signal_desired_start", 0L, Marker::SPHERE, scale, desired_section_color); - auto desired_end_marker = autoware_universe_utils::createDefaultMarker( + auto desired_end_marker = autoware::universe_utils::createDefaultMarker( "map", current_time, "intersection_turn_signal_desired_end", 0L, Marker::SPHERE, scale, desired_section_color); desired_start_marker.pose = turn_signal_info.desired_start_point; desired_end_marker.pose = turn_signal_info.desired_end_point; - auto required_start_marker = autoware_universe_utils::createDefaultMarker( + auto required_start_marker = autoware::universe_utils::createDefaultMarker( "map", current_time, "intersection_turn_signal_required_start", 0L, Marker::SPHERE, scale, required_section_color); - auto required_end_marker = autoware_universe_utils::createDefaultMarker( + auto required_end_marker = autoware::universe_utils::createDefaultMarker( "map", current_time, "intersection_turn_signal_required_end", 0L, Marker::SPHERE, scale, required_section_color); required_start_marker.pose = turn_signal_info.required_start_point; @@ -604,19 +604,19 @@ void BehaviorPathPlannerNode::publish_turn_signal_debug_data(const TurnSignalDeb { const auto & turn_signal_info = debug_data.behavior_turn_signal_info; - auto desired_start_marker = autoware_universe_utils::createDefaultMarker( + auto desired_start_marker = autoware::universe_utils::createDefaultMarker( "map", current_time, "behavior_turn_signal_desired_start", 0L, Marker::CUBE, scale, desired_section_color); - auto desired_end_marker = autoware_universe_utils::createDefaultMarker( + auto desired_end_marker = autoware::universe_utils::createDefaultMarker( "map", current_time, "behavior_turn_signal_desired_end", 0L, Marker::CUBE, scale, desired_section_color); desired_start_marker.pose = turn_signal_info.desired_start_point; desired_end_marker.pose = turn_signal_info.desired_end_point; - auto required_start_marker = autoware_universe_utils::createDefaultMarker( + auto required_start_marker = autoware::universe_utils::createDefaultMarker( "map", current_time, "behavior_turn_signal_required_start", 0L, Marker::CUBE, scale, required_section_color); - auto required_end_marker = autoware_universe_utils::createDefaultMarker( + auto required_end_marker = autoware::universe_utils::createDefaultMarker( "map", current_time, "behavior_turn_signal_required_end", 0L, Marker::CUBE, scale, required_section_color); required_start_marker.pose = turn_signal_info.required_start_point; @@ -642,18 +642,18 @@ void BehaviorPathPlannerNode::publish_bounds(const PathWithLaneId & path) constexpr double color_a = 0.999; const auto current_time = path.header.stamp; - auto left_marker = autoware_universe_utils::createDefaultMarker( + auto left_marker = autoware::universe_utils::createDefaultMarker( "map", current_time, "left_bound", 0L, Marker::LINE_STRIP, - autoware_universe_utils::createMarkerScale(scale_x, scale_y, scale_z), - autoware_universe_utils::createMarkerColor(color_r, color_g, color_b, color_a)); + autoware::universe_utils::createMarkerScale(scale_x, scale_y, scale_z), + autoware::universe_utils::createMarkerColor(color_r, color_g, color_b, color_a)); for (const auto lb : path.left_bound) { left_marker.points.push_back(lb); } - auto right_marker = autoware_universe_utils::createDefaultMarker( + auto right_marker = autoware::universe_utils::createDefaultMarker( "map", current_time, "right_bound", 0L, Marker::LINE_STRIP, - autoware_universe_utils::createMarkerScale(scale_x, scale_y, scale_z), - autoware_universe_utils::createMarkerColor(color_r, color_g, color_b, color_a)); + autoware::universe_utils::createMarkerScale(scale_x, scale_y, scale_z), + autoware::universe_utils::createMarkerColor(color_r, color_g, color_b, color_a)); for (const auto rb : path.right_bound) { right_marker.points.push_back(rb); } @@ -744,7 +744,7 @@ Path BehaviorPathPlannerNode::convertToPath( return output; } - output = autoware_motion_utils::convertToPath( + output = autoware::motion_utils::convertToPath( *path_candidate_ptr); // header is replaced by the input one, so it is substituted again output.header = planner_data->route_handler->getRouteHeader(); @@ -830,7 +830,7 @@ void BehaviorPathPlannerNode::onLateralOffset(const LateralOffset::ConstSharedPt SetParametersResult BehaviorPathPlannerNode::onSetParam( const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; rcl_interfaces::msg::SetParametersResult result; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp index 71714cda9052d..e66eec2a1e0a4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp @@ -219,7 +219,7 @@ void PlannerManager::generateCombinedDrivableArea( const auto & di = output.drivable_area_info; constexpr double epsilon = 1e-3; - const auto is_driving_forward_opt = autoware_motion_utils::isDrivingForward(output.path.points); + const auto is_driving_forward_opt = autoware::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)) { @@ -466,10 +466,10 @@ void PlannerManager::publishDebugRootReferencePath( { using visualization_msgs::msg::Marker; MarkerArray array; - Marker m = autoware_universe_utils::createDefaultMarker( + Marker m = autoware::universe_utils::createDefaultMarker( "map", clock_.now(), "root_reference_path", 0UL, Marker::LINE_STRIP, - autoware_universe_utils::createMarkerScale(1.0, 1.0, 1.0), - autoware_universe_utils::createMarkerColor(1.0, 0.0, 0.0, 1.0)); + autoware::universe_utils::createMarkerScale(1.0, 1.0, 1.0), + autoware::universe_utils::createMarkerColor(1.0, 0.0, 0.0, 1.0)); for (const auto & p : reference_path.path.points) m.points.push_back(p.point.pose.position); array.markers.push_back(m); m.points.clear(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_utils.cpp index f79087d7df405..da8657c82c58e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_utils.cpp @@ -35,7 +35,7 @@ TEST(BehaviorPathPlanningUtilitiesBehaviorTest, vehiclePoseToFrenetOnStraightLin Pose vehicle_pose = autoware::behavior_path_planner::generateEgoSamplePose(10.7f, -1.7f, 0.0); const size_t vehicle_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, vehicle_pose, 3.0, 1.0); const auto vehicle_pose_frenet = autoware::behavior_path_planner::utils::convertToFrenetPoint( path.points, vehicle_pose.position, vehicle_seg_idx); @@ -51,7 +51,7 @@ TEST(BehaviorPathPlanningUtilitiesBehaviorTest, vehiclePoseToFrenetOnDiagonalLin Pose vehicle_pose = autoware::behavior_path_planner::generateEgoSamplePose(0.1f, 0.1f, 0.0); const size_t vehicle_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, vehicle_pose, 3.0, 1.0); const auto vehicle_pose_frenet = autoware::behavior_path_planner::utils::convertToFrenetPoint( path.points, vehicle_pose.position, vehicle_seg_idx); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp index ec9a67a40e052..0ec7841f77cfe 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp @@ -102,7 +102,7 @@ struct DrivableAreaInfo struct Obstacle { geometry_msgs::msg::Pose pose; - autoware_universe_utils::Polygon2d poly; + autoware::universe_utils::Polygon2d poly; bool is_left{true}; }; std::vector drivable_lanes{}; @@ -254,7 +254,7 @@ struct PlannerData template size_t findEgoIndex(const std::vector & points) const { - return autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( points, self_odometry->pose.pose, parameters.ego_nearest_dist_threshold, parameters.ego_nearest_yaw_threshold); } @@ -262,7 +262,7 @@ struct PlannerData template size_t findEgoSegmentIndex(const std::vector & points) const { - return autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( points, self_odometry->pose.pose, parameters.ego_nearest_dist_threshold, parameters.ego_nearest_yaw_threshold); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp index 898414c29eaa4..d11c3181526d2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -59,10 +59,10 @@ namespace autoware::behavior_path_planner using autoware::objects_of_interest_marker_interface::ColorName; using autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; using autoware::rtc_interface::RTCInterface; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::generateUUID; using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::SteeringFactor; -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::generateUUID; using steering_factor_interface::SteeringFactorInterface; using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; using tier4_planning_msgs::msg::PathWithLaneId; @@ -146,7 +146,7 @@ class SceneModuleInterface updateData(); const auto output = isWaitingApproval() ? planWaitingApproval() : plan(); try { - autoware_motion_utils::validateNonEmpty(output.path.points); + autoware::motion_utils::validateNonEmpty(output.path.points); } catch (const std::exception & ex) { throw std::invalid_argument("[" + name_ + "]" + ex.what()); } @@ -566,7 +566,7 @@ class SceneModuleInterface StopFactor stop_factor; stop_factor.stop_pose = stop_pose_.value(); - stop_factor.dist_to_stop_pose = autoware_motion_utils::calcSignedArcLength( + stop_factor.dist_to_stop_pose = autoware::motion_utils::calcSignedArcLength( path.points, getEgoPosition(), stop_pose_.value().position); stop_reason_.stop_factors.push_back(stop_factor); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp index 02e29e028f74c..5b9c0389e29c5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp @@ -36,10 +36,10 @@ namespace autoware::behavior_path_planner { -using autoware_motion_utils::createDeadLineVirtualWallMarker; -using autoware_motion_utils::createSlowDownVirtualWallMarker; -using autoware_motion_utils::createStopVirtualWallMarker; -using autoware_universe_utils::toHexString; +using autoware::motion_utils::createDeadLineVirtualWallMarker; +using autoware::motion_utils::createSlowDownVirtualWallMarker; +using autoware::motion_utils::createStopVirtualWallMarker; +using autoware::universe_utils::toHexString; using unique_identifier_msgs::msg::UUID; using SceneModulePtr = std::shared_ptr; using SceneModuleObserver = std::weak_ptr; @@ -111,7 +111,7 @@ class SceneModuleManagerInterface void publishVirtualWall() const { - using autoware_universe_utils::appendMarkerArray; + using autoware::universe_utils::appendMarkerArray; MarkerArray markers{}; @@ -155,7 +155,7 @@ class SceneModuleManagerInterface void publishMarker() const { - using autoware_universe_utils::appendMarkerArray; + using autoware::universe_utils::appendMarkerArray; MarkerArray info_markers{}; MarkerArray debug_markers{}; @@ -271,7 +271,7 @@ class SceneModuleManagerInterface protected: void initInterface(rclcpp::Node * node, const std::vector & rtc_types) { - using autoware_universe_utils::getOrDeclareParameter; + using autoware::universe_utils::getOrDeclareParameter; // init manager configuration { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/marker_utils/colors.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/marker_utils/colors.hpp index 4151f4dcacf19..f2318e9d5c1ad 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/marker_utils/colors.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/marker_utils/colors.hpp @@ -26,62 +26,62 @@ using std_msgs::msg::ColorRGBA; inline ColorRGBA red(float a = 0.99) { - return autoware_universe_utils::createMarkerColor(1., 0., 0., a); + return autoware::universe_utils::createMarkerColor(1., 0., 0., a); } inline ColorRGBA green(float a = 0.99) { - return autoware_universe_utils::createMarkerColor(0., 1., 0., a); + return autoware::universe_utils::createMarkerColor(0., 1., 0., a); } inline ColorRGBA blue(float a = 0.99) { - return autoware_universe_utils::createMarkerColor(0., 0., 1., a); + return autoware::universe_utils::createMarkerColor(0., 0., 1., a); } inline ColorRGBA yellow(float a = 0.99) { - return autoware_universe_utils::createMarkerColor(1., 1., 0., a); + return autoware::universe_utils::createMarkerColor(1., 1., 0., a); } inline ColorRGBA aqua(float a = 0.99) { - return autoware_universe_utils::createMarkerColor(0., 1., 1., a); + return autoware::universe_utils::createMarkerColor(0., 1., 1., a); } inline ColorRGBA magenta(float a = 0.99) { - return autoware_universe_utils::createMarkerColor(1., 0., 1., a); + return autoware::universe_utils::createMarkerColor(1., 0., 1., a); } inline ColorRGBA medium_orchid(float a = 0.99) { - return autoware_universe_utils::createMarkerColor(0.729, 0.333, 0.827, a); + return autoware::universe_utils::createMarkerColor(0.729, 0.333, 0.827, a); } inline ColorRGBA light_pink(float a = 0.99) { - return autoware_universe_utils::createMarkerColor(1., 0.713, 0.756, a); + return autoware::universe_utils::createMarkerColor(1., 0.713, 0.756, a); } inline ColorRGBA light_yellow(float a = 0.99) { - return autoware_universe_utils::createMarkerColor(1., 1., 0.878, a); + return autoware::universe_utils::createMarkerColor(1., 1., 0.878, a); } inline ColorRGBA light_steel_blue(float a = 0.99) { - return autoware_universe_utils::createMarkerColor(0.690, 0.768, 0.870, a); + return autoware::universe_utils::createMarkerColor(0.690, 0.768, 0.870, a); } inline ColorRGBA white(float a = 0.99) { - return autoware_universe_utils::createMarkerColor(1., 1., 1., a); + return autoware::universe_utils::createMarkerColor(1., 1., 1., a); } inline ColorRGBA grey(float a = 0.99) { - return autoware_universe_utils::createMarkerColor(.5, .5, .5, a); + return autoware::universe_utils::createMarkerColor(.5, .5, .5, a); } inline std::vector colors_list(float a = 0.99) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/marker_utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/marker_utils/utils.hpp index fc0efc38ae617..819800281fcc5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/marker_utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/marker_utils/utils.hpp @@ -40,9 +40,9 @@ using autoware::behavior_path_planner::utils::path_safety_checker::CollisionChec using autoware::behavior_path_planner::utils::path_safety_checker::CollisionCheckDebugPair; using autoware::behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject; using autoware::behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObjects; +using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::PredictedPath; -using autoware_universe_utils::Polygon2d; using geometry_msgs::msg::Point; using geometry_msgs::msg::Polygon; using geometry_msgs::msg::Pose; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/turn_signal_decider.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/turn_signal_decider.hpp index fa3236d7fd868..94ed8af3c82b4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/turn_signal_decider.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/turn_signal_decider.hpp @@ -239,8 +239,8 @@ class TurnSignalDecider const ShiftedPath & path, const ShiftLine & shift_line, const lanelet::ConstLanelets & lanes, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) const { - using autoware_universe_utils::pose2transform; - using autoware_universe_utils::transformVector; + using autoware::universe_utils::pose2transform; + using autoware::universe_utils::transformVector; using boost::geometry::intersects; const auto footprint = vehicle_info.createFootprint(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/drivable_area_expansion/types.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/drivable_area_expansion/types.hpp index de29886c27b4e..afe88ac04f302 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/drivable_area_expansion/types.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/drivable_area_expansion/types.hpp @@ -36,13 +36,13 @@ using geometry_msgs::msg::Pose; using tier4_planning_msgs::msg::PathPointWithLaneId; using tier4_planning_msgs::msg::PathWithLaneId; -using autoware_universe_utils::LineString2d; -using autoware_universe_utils::MultiLineString2d; -using autoware_universe_utils::MultiPoint2d; -using autoware_universe_utils::MultiPolygon2d; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; -using autoware_universe_utils::Segment2d; +using autoware::universe_utils::LineString2d; +using autoware::universe_utils::MultiLineString2d; +using autoware::universe_utils::MultiPoint2d; +using autoware::universe_utils::MultiPolygon2d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; +using autoware::universe_utils::Segment2d; using SegmentRtree = boost::geometry::index::rtree>; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp index 8dfc590230064..4fd6fce325f49 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp @@ -70,7 +70,7 @@ bool isCentroidWithinLanelet(const PredictedObject & object, const lanelet::Cons bool isPolygonOverlapLanelet(const PredictedObject & object, const lanelet::ConstLanelet & lanelet); bool isPolygonOverlapLanelet( - const PredictedObject & object, const autoware_universe_utils::Polygon2d & lanelet_polygon); + const PredictedObject & object, const autoware::universe_utils::Polygon2d & lanelet_polygon); bool isPolygonOverlapLanelet( const PredictedObject & object, const lanelet::BasicPolygon2d & lanelet_polygon); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp index 421c495555c3c..313f9df471938 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp @@ -31,8 +31,8 @@ namespace autoware::behavior_path_planner::utils::path_safety_checker { +using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::PredictedObject; -using autoware_universe_utils::Polygon2d; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp index 92b7bab5c26ba..3f1094dfd70b6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp @@ -32,13 +32,13 @@ namespace autoware::behavior_path_planner::utils::path_safety_checker { using autoware::behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug; +using autoware::universe_utils::calcYawDeviation; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; using autoware::vehicle_info_utils::VehicleInfo; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedPath; using autoware_perception_msgs::msg::Shape; -using autoware_universe_utils::calcYawDeviation; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp index 1e31bafe3fa0b..8164ef659b7b1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp @@ -29,7 +29,7 @@ #include namespace autoware::behavior_path_planner { -using autoware_universe_utils::generateUUID; +using autoware::universe_utils::generateUUID; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using tier4_planning_msgs::msg::PathPointWithLaneId; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp index 9196123c4e73a..5c1eee92c2a5d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp @@ -47,8 +47,8 @@ using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::PredictedPath; using autoware::route_handler::RouteHandler; -using autoware_universe_utils::LinearRing2d; -using autoware_universe_utils::Polygon2d; +using autoware::universe_utils::LinearRing2d; +using autoware::universe_utils::Polygon2d; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Vector3; @@ -93,11 +93,11 @@ FrenetPoint convertToFrenetPoint( FrenetPoint frenet_point; const double longitudinal_length = - autoware_motion_utils::calcLongitudinalOffsetToSegment(points, seg_idx, search_point_geom); + autoware::motion_utils::calcLongitudinalOffsetToSegment(points, seg_idx, search_point_geom); frenet_point.length = - autoware_motion_utils::calcSignedArcLength(points, 0, seg_idx) + longitudinal_length; + autoware::motion_utils::calcSignedArcLength(points, 0, seg_idx) + longitudinal_length; frenet_point.distance = - autoware_motion_utils::calcLateralOffset(points, search_point_geom, seg_idx); + autoware::motion_utils::calcLateralOffset(points, search_point_geom, seg_idx); return frenet_point; } @@ -147,7 +147,7 @@ bool checkCollisionWithExtraStoppingMargin( * @return Has collision or not */ bool checkCollisionBetweenPathFootprintsAndObjects( - const autoware_universe_utils::LinearRing2d & vehicle_footprint, const PathWithLaneId & ego_path, + const autoware::universe_utils::LinearRing2d & vehicle_footprint, const PathWithLaneId & ego_path, const PredictedObjects & dynamic_objects, const double margin); /** @@ -155,7 +155,7 @@ bool checkCollisionBetweenPathFootprintsAndObjects( * @return Has collision or not */ bool checkCollisionBetweenFootprintAndObjects( - const autoware_universe_utils::LinearRing2d & vehicle_footprint, const Pose & ego_pose, + const autoware::universe_utils::LinearRing2d & vehicle_footprint, const Pose & ego_pose, const PredictedObjects & dynamic_objects, const double margin); /** @@ -344,12 +344,12 @@ size_t findNearestSegmentIndex( const double yaw_threshold) { const auto nearest_idx = - autoware_motion_utils::findNearestSegmentIndex(points, pose, dist_threshold, yaw_threshold); + autoware::motion_utils::findNearestSegmentIndex(points, pose, dist_threshold, yaw_threshold); if (nearest_idx) { return nearest_idx.value(); } - return autoware_motion_utils::findNearestSegmentIndex(points, pose.position); + return autoware::motion_utils::findNearestSegmentIndex(points, pose.position); } } // namespace autoware::behavior_path_planner::utils diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp index 154ceb6dc6dd5..8c9b4ef35d5af 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp @@ -31,12 +31,12 @@ namespace marker_utils { using autoware::behavior_path_planner::utils::calcPathArcLengthArray; -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerOrientation; -using autoware_universe_utils::createMarkerScale; -using autoware_universe_utils::createPoint; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerOrientation; +using autoware::universe_utils::createMarkerScale; +using autoware::universe_utils::createPoint; using std_msgs::msg::ColorRGBA; using visualization_msgs::msg::Marker; @@ -49,13 +49,13 @@ void addFootprintMarker( const double base_to_rear = vehicle_info.rear_overhang_m; marker.points.push_back( - autoware_universe_utils::calcOffsetPose(pose, base_to_front, -half_width, 0.0).position); + autoware::universe_utils::calcOffsetPose(pose, base_to_front, -half_width, 0.0).position); marker.points.push_back( - autoware_universe_utils::calcOffsetPose(pose, base_to_front, half_width, 0.0).position); + autoware::universe_utils::calcOffsetPose(pose, base_to_front, half_width, 0.0).position); marker.points.push_back( - autoware_universe_utils::calcOffsetPose(pose, -base_to_rear, half_width, 0.0).position); + autoware::universe_utils::calcOffsetPose(pose, -base_to_rear, half_width, 0.0).position); marker.points.push_back( - autoware_universe_utils::calcOffsetPose(pose, -base_to_rear, -half_width, 0.0).position); + autoware::universe_utils::calcOffsetPose(pose, -base_to_rear, -half_width, 0.0).position); marker.points.push_back(marker.points.front()); } @@ -214,7 +214,7 @@ MarkerArray createShiftLengthMarkerArray( Marker marker = createDefaultMarker( "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, 0L, Marker::LINE_STRIP, createMarkerScale(0.1, 0.0, 0.0), createMarkerColor(r, g, b, 0.9)); - marker.pose.orientation = autoware_universe_utils::createMarkerOrientation(0, 0, 0, 1.0); + marker.pose.orientation = autoware::universe_utils::createMarkerOrientation(0, 0, 0, 1.0); marker.points.reserve(shift_distance.size()); for (size_t i = 0; i < shift_distance.size(); ++i) { @@ -271,7 +271,7 @@ MarkerArray createLaneletsAreaMarkerArray( "map", current_time, ns, static_cast(lanelet.id()), Marker::LINE_STRIP, createMarkerScale(0.1, 0.0, 0.0), createMarkerColor(r, g, b, 0.999)); - marker.pose.orientation = autoware_universe_utils::createMarkerOrientation(0, 0, 0, 1.0); + marker.pose.orientation = autoware::universe_utils::createMarkerOrientation(0, 0, 0, 1.0); if (!lanelet.polygon3d().empty()) { marker.points.reserve(lanelet.polygon3d().size() + 1); @@ -299,7 +299,7 @@ MarkerArray createPolygonMarkerArray( "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, static_cast(lane_id), Marker::LINE_STRIP, createMarkerScale(w, 0.0, 0.0), createMarkerColor(r, g, b, 0.8)); - marker.pose.orientation = autoware_universe_utils::createMarkerOrientation(0, 0, 0, 1.0); + marker.pose.orientation = autoware::universe_utils::createMarkerOrientation(0, 0, 0, 1.0); if (!polygon.points.empty()) { marker.points.reserve(polygon.points.size() + 1); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/turn_signal_decider.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/turn_signal_decider.cpp index 5a785a71b863d..73f81ce59844c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/turn_signal_decider.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/turn_signal_decider.cpp @@ -33,16 +33,16 @@ namespace autoware::behavior_path_planner { -using autoware_motion_utils::calcSignedArcLength; +using autoware::motion_utils::calcSignedArcLength; double calc_distance( const PathWithLaneId & path, const Pose & current_pose, const size_t current_seg_idx, const Pose & input_point, const double nearest_dist_threshold, const double nearest_yaw_threshold) { const size_t nearest_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, input_point, nearest_dist_threshold, nearest_yaw_threshold); - return autoware_motion_utils::calcSignedArcLength( + return autoware::motion_utils::calcSignedArcLength( path.points, current_pose.position, current_seg_idx, input_point.position, nearest_seg_idx); } @@ -83,8 +83,9 @@ TurnIndicatorsCommand TurnSignalDecider::getTurnSignal( } // Closest ego segment - const size_t ego_seg_idx = autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - extended_path.points, current_pose, nearest_dist_threshold, nearest_yaw_threshold); + const size_t ego_seg_idx = + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + extended_path.points, current_pose, nearest_dist_threshold, nearest_yaw_threshold); // Get closest intersection turn signal if exists const auto intersection_turn_signal_info = getIntersectionTurnSignalInfo( @@ -231,20 +232,20 @@ std::optional TurnSignalDecider::getIntersectionTurnSignalInfo( } const size_t front_nearest_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, lane_front_pose, nearest_dist_threshold, nearest_yaw_threshold); const size_t back_nearest_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, lane_back_pose, nearest_dist_threshold, nearest_yaw_threshold); // Distance from ego vehicle front pose to front point of the lane - const double dist_to_front_point = autoware_motion_utils::calcSignedArcLength( + const double dist_to_front_point = autoware::motion_utils::calcSignedArcLength( path.points, current_pose.position, current_seg_idx, lane_front_pose.position, front_nearest_seg_idx) - base_link2front_; // Distance from ego vehicle base link to the terminal point of the lane - const double dist_to_back_point = autoware_motion_utils::calcSignedArcLength( + const double dist_to_back_point = autoware::motion_utils::calcSignedArcLength( path.points, current_pose.position, current_seg_idx, lane_back_pose.position, back_nearest_seg_idx); @@ -280,9 +281,9 @@ std::optional TurnSignalDecider::getIntersectionTurnSignalInfo( const auto & turn_signal_info = signal_queue.front(); const auto & required_end_point = turn_signal_info.required_end_point; const size_t nearest_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, required_end_point, nearest_dist_threshold, nearest_yaw_threshold); - const double dist_to_end_point = autoware_motion_utils::calcSignedArcLength( + const double dist_to_end_point = autoware::motion_utils::calcSignedArcLength( path.points, current_pose.position, current_seg_idx, required_end_point.position, nearest_seg_idx); @@ -407,9 +408,9 @@ TurnSignalInfo TurnSignalDecider::overwrite_turn_signal( const auto get_distance = [&](const Pose & input_point) { const size_t nearest_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, input_point, nearest_dist_threshold, nearest_yaw_threshold); - return autoware_motion_utils::calcSignedArcLength( + return autoware::motion_utils::calcSignedArcLength( path.points, current_pose.position, current_seg_idx, input_point.position, nearest_seg_idx) - base_link2front_; @@ -434,9 +435,9 @@ TurnSignalInfo TurnSignalDecider::use_prior_turn_signal( { const auto get_distance = [&](const Pose & input_point) { const size_t nearest_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, input_point, nearest_dist_threshold, nearest_yaw_threshold); - return autoware_motion_utils::calcSignedArcLength( + return autoware::motion_utils::calcSignedArcLength( path.points, current_pose.position, current_seg_idx, input_point.position, nearest_seg_idx); }; @@ -557,9 +558,9 @@ geometry_msgs::msg::Pose TurnSignalDecider::get_required_end_point( for (size_t i = 0; i < centerline.size(); ++i) { converted_centerline.at(i).position = lanelet::utils::conversion::toGeomMsgPt(centerline[i]); } - autoware_motion_utils::insertOrientation(converted_centerline, true); + autoware::motion_utils::insertOrientation(converted_centerline, true); - const double length = autoware_motion_utils::calcArcLength(converted_centerline); + const double length = autoware::motion_utils::calcArcLength(converted_centerline); // Create resampling intervals const double resampling_interval = 1.0; @@ -569,20 +570,21 @@ geometry_msgs::msg::Pose TurnSignalDecider::get_required_end_point( } // Insert terminal point - if (length - resampling_arclength.back() < autoware_motion_utils::overlap_threshold) { + if (length - resampling_arclength.back() < autoware::motion_utils::overlap_threshold) { resampling_arclength.back() = length; } else { resampling_arclength.push_back(length); } const auto resampled_centerline = - autoware_motion_utils::resamplePoseVector(converted_centerline, resampling_arclength); + autoware::motion_utils::resamplePoseVector(converted_centerline, resampling_arclength); const double terminal_yaw = tf2::getYaw(resampled_centerline.back().orientation); for (size_t i = 0; i < resampled_centerline.size(); ++i) { const double yaw = tf2::getYaw(resampled_centerline.at(i).orientation); - const double yaw_diff = autoware_universe_utils::normalizeRadian(yaw - terminal_yaw); - if (std::fabs(yaw_diff) < autoware_universe_utils::deg2rad(intersection_angle_threshold_deg_)) { + const double yaw_diff = autoware::universe_utils::normalizeRadian(yaw - terminal_yaw); + if ( + std::fabs(yaw_diff) < autoware::universe_utils::deg2rad(intersection_angle_threshold_deg_)) { return resampled_centerline.at(i); } } @@ -597,9 +599,9 @@ void TurnSignalDecider::set_intersection_info( { const auto get_distance = [&](const Pose & input_point) { const size_t nearest_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, input_point, nearest_dist_threshold, nearest_yaw_threshold); - return autoware_motion_utils::calcSignedArcLength( + return autoware::motion_utils::calcSignedArcLength( path.points, current_pose.position, current_seg_idx, input_point.position, nearest_seg_idx); }; @@ -639,9 +641,9 @@ void TurnSignalDecider::initialize_intersection_info() geometry_msgs::msg::Quaternion TurnSignalDecider::calc_orientation( const Point & src_point, const Point & dst_point) { - const double pitch = autoware_universe_utils::calcElevationAngle(src_point, dst_point); - const double yaw = autoware_universe_utils::calcAzimuthAngle(src_point, dst_point); - return autoware_universe_utils::createQuaternionFromRPY(0.0, pitch, yaw); + const double pitch = autoware::universe_utils::calcElevationAngle(src_point, dst_point); + const double yaw = autoware::universe_utils::calcAzimuthAngle(src_point, dst_point); + return autoware::universe_utils::createQuaternionFromRPY(0.0, pitch, yaw); } std::pair TurnSignalDecider::getBehaviorTurnSignalInfo( @@ -652,7 +654,7 @@ std::pair TurnSignalDecider::getBehaviorTurnSignalInfo( const double current_shift_length, const bool is_driving_forward, const bool egos_lane_is_shifted, const bool override_ego_stopped_check, const bool is_pull_out) const { - using autoware_universe_utils::getPose; + using autoware::universe_utils::getPose; const auto & p = parameters; const auto & rh = route_handler; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/drivable_area_expansion.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/drivable_area_expansion.cpp index e3ebc07a8ce39..6e028cec2ed1b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/drivable_area_expansion.cpp @@ -50,8 +50,8 @@ void reuse_previous_poses( std::vector cropped_curvatures; const auto ego_is_behind = prev_poses.size() > 1 && - autoware_motion_utils::calcLongitudinalOffsetToSegment(prev_poses, 0, ego_point) < 0.0; - const auto ego_is_far = !prev_poses.empty() && autoware_universe_utils::calcDistance2d( + autoware::motion_utils::calcLongitudinalOffsetToSegment(prev_poses, 0, ego_point) < 0.0; + const auto ego_is_far = !prev_poses.empty() && autoware::universe_utils::calcDistance2d( ego_point, prev_poses.front()) < 0.0; // make sure the reused points are not behind the current original drivable area LineString2d left_bound; @@ -65,9 +65,9 @@ void reuse_previous_poses( if (!ego_is_behind && !ego_is_far && prev_poses.size() > 1 && !prev_poses_across_bounds) { const auto first_idx = - autoware_motion_utils::findNearestSegmentIndex(prev_poses, path.points.front().point.pose); - const auto deviation = - autoware_motion_utils::calcLateralOffset(prev_poses, path.points.front().point.pose.position); + autoware::motion_utils::findNearestSegmentIndex(prev_poses, path.points.front().point.pose); + const auto deviation = autoware::motion_utils::calcLateralOffset( + prev_poses, path.points.front().point.pose.position); if (first_idx && deviation < params.max_reuse_deviation) { LineString2d path_ls; for (const auto & p : path.points) path_ls.push_back(convert_point(p.point.pose.position)); @@ -87,27 +87,29 @@ void reuse_previous_poses( } if (cropped_poses.empty()) { const auto resampled_path_points = - autoware_motion_utils::resamplePath(path, params.resample_interval, true, true, false).points; + autoware::motion_utils::resamplePath(path, params.resample_interval, true, true, false) + .points; const auto cropped_path = params.max_path_arc_length <= 0.0 ? resampled_path_points - : autoware_motion_utils::cropForwardPoints( + : autoware::motion_utils::cropForwardPoints( resampled_path_points, resampled_path_points.front().point.pose.position, 0, params.max_path_arc_length); for (const auto & p : cropped_path) cropped_poses.push_back(p.point.pose); } else { - const auto initial_arc_length = autoware_motion_utils::calcArcLength(cropped_poses); - const auto max_path_arc_length = autoware_motion_utils::calcArcLength(path.points); - const auto first_arc_length = autoware_motion_utils::calcSignedArcLength( + const auto initial_arc_length = autoware::motion_utils::calcArcLength(cropped_poses); + const auto max_path_arc_length = autoware::motion_utils::calcArcLength(path.points); + const auto first_arc_length = autoware::motion_utils::calcSignedArcLength( path.points, path.points.front().point.pose.position, cropped_poses.back().position); for (auto arc_length = first_arc_length + params.resample_interval; (params.max_path_arc_length <= 0.0 || initial_arc_length + (arc_length - first_arc_length) <= params.max_path_arc_length) && arc_length <= max_path_arc_length; arc_length += params.resample_interval) - cropped_poses.push_back(autoware_motion_utils::calcInterpolatedPose(path.points, arc_length)); + cropped_poses.push_back( + autoware::motion_utils::calcInterpolatedPose(path.points, arc_length)); } - prev_poses = autoware_motion_utils::removeOverlapPoints(cropped_poses); + prev_poses = autoware::motion_utils::removeOverlapPoints(cropped_poses); prev_curvatures = cropped_curvatures; } @@ -162,7 +164,7 @@ void apply_arc_length_range_smoothing( auto arc_length = boost::geometry::distance( bound_projections[path_idx].point, convert_point(bound[bound_idx + 1])); const auto update_arc_length_and_bound_expansions = [&](auto idx) { - arc_length += autoware_universe_utils::calcDistance2d(bound[idx - 1], bound[idx]); + arc_length += autoware::universe_utils::calcDistance2d(bound[idx - 1], bound[idx]); bound_expansions[idx] = std::max(bound_expansions[idx], original_expansions[bound_idx]); }; for (auto up_bound_idx = bound_idx + 2; up_bound_idx < bound.size(); ++up_bound_idx) { @@ -201,7 +203,7 @@ void apply_bound_change_rate_limit( if (distances.empty()) return; const auto apply_max_vel = [&](auto & exp, const auto from, const auto to) { if (exp[from] > exp[to]) { - const auto arc_length = autoware_universe_utils::calcDistance2d(bound[from], bound[to]); + const auto arc_length = autoware::universe_utils::calcDistance2d(bound[from], bound[to]); const auto smoothed_dist = exp[from] - arc_length * max_rate; exp[to] = std::max(exp[to], smoothed_dist); } @@ -285,12 +287,12 @@ void expand_bound( for (auto idx = 1LU; idx < bound.size(); ++idx) { bool is_intersecting = false; for (auto succ_idx = idx + 1; succ_idx < bound.size(); ++succ_idx) { - const auto intersection = autoware_universe_utils::intersect( + const auto intersection = autoware::universe_utils::intersect( bound[idx - 1], bound[idx], bound[succ_idx - 1], bound[succ_idx]); if ( intersection && - autoware_universe_utils::calcDistance2d(*intersection, bound[idx - 1]) < 1e-3 && - autoware_universe_utils::calcDistance2d(*intersection, bound[idx]) < 1e-3) { + autoware::universe_utils::calcDistance2d(*intersection, bound[idx - 1]) < 1e-3 && + autoware::universe_utils::calcDistance2d(*intersection, bound[idx]) < 1e-3) { idx = succ_idx; is_intersecting = true; } @@ -303,7 +305,7 @@ void expand_bound( std::vector calculate_smoothed_curvatures( const std::vector & poses, const size_t smoothing_window_size) { - const auto curvatures = autoware_motion_utils::calcCurvature(poses); + const auto curvatures = autoware::motion_utils::calcCurvature(poses); std::vector smoothed_curvatures(curvatures.size()); for (auto i = 0UL; i < curvatures.size(); ++i) { auto sum = 0.0; @@ -364,7 +366,7 @@ void expand_drivable_area( { // skip if no bounds or not enough points to calculate path curvature if (path.points.size() < 3 || path.left_bound.empty() || path.right_bound.empty()) return; - autoware_universe_utils::StopWatch stop_watch; + autoware::universe_utils::StopWatch stop_watch; stop_watch.tic("overall"); stop_watch.tic("preprocessing"); const auto & params = planner_data->drivable_area_expansion_parameters; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/footprints.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/footprints.cpp index b01669871276a..a25a33c1668fa 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/footprints.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/footprints.cpp @@ -37,7 +37,7 @@ Polygon2d create_footprint(const geometry_msgs::msg::Pose & pose, const Polygon2 { const auto angle = tf2::getYaw(pose.orientation); return translate_polygon( - autoware_universe_utils::rotatePolygon(base_footprint, angle), pose.position.x, + autoware::universe_utils::rotatePolygon(base_footprint, angle), pose.position.x, pose.position.y); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index b045304d56b41..f304fff9ce450 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -55,8 +55,8 @@ std::vector removeSharpPoints(const std::vector & points) const auto product = std::inner_product(vec_1to2.begin(), vec_1to2.end(), vec_3to2.begin(), 0.0); - const auto dist_1to2 = autoware_universe_utils::calcDistance3d(p1, p2); - const auto dist_3to2 = autoware_universe_utils::calcDistance3d(p3, p2); + const auto dist_1to2 = autoware::universe_utils::calcDistance3d(p1, p2); + const auto dist_3to2 = autoware::universe_utils::calcDistance3d(p3, p2); constexpr double epsilon = 1e-3; @@ -82,15 +82,15 @@ template size_t findNearestSegmentIndexFromLateralDistance( const std::vector & points, const geometry_msgs::msg::Point & target_point) { - using autoware_universe_utils::calcAzimuthAngle; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::normalizeRadian; + using autoware::universe_utils::calcAzimuthAngle; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::normalizeRadian; std::optional closest_idx{std::nullopt}; double min_lateral_dist = std::numeric_limits::max(); for (size_t seg_idx = 0; seg_idx < points.size() - 1; ++seg_idx) { const double lon_dist = - autoware_motion_utils::calcLongitudinalOffsetToSegment(points, seg_idx, target_point); + autoware::motion_utils::calcLongitudinalOffsetToSegment(points, seg_idx, target_point); const double segment_length = calcDistance2d(points.at(seg_idx), points.at(seg_idx + 1)); const double lat_dist = [&]() { if (lon_dist < 0.0) { @@ -99,7 +99,7 @@ size_t findNearestSegmentIndexFromLateralDistance( if (segment_length < lon_dist) { return calcDistance2d(points.at(seg_idx + 1), target_point); } - return std::abs(autoware_motion_utils::calcLateralOffset(points, target_point, seg_idx)); + return std::abs(autoware::motion_utils::calcLateralOffset(points, target_point, seg_idx)); }(); if (lat_dist < min_lateral_dist) { closest_idx = seg_idx; @@ -111,7 +111,7 @@ size_t findNearestSegmentIndexFromLateralDistance( return *closest_idx; } - return autoware_motion_utils::findNearestSegmentIndex(points, target_point); + return autoware::motion_utils::findNearestSegmentIndex(points, target_point); } template @@ -119,9 +119,9 @@ size_t findNearestSegmentIndexFromLateralDistance( const std::vector & points, const geometry_msgs::msg::Pose & target_point, const double yaw_threshold) { - using autoware_universe_utils::calcAzimuthAngle; - using autoware_universe_utils::calcDistance2d; - using autoware_universe_utils::normalizeRadian; + using autoware::universe_utils::calcAzimuthAngle; + using autoware::universe_utils::calcDistance2d; + using autoware::universe_utils::normalizeRadian; std::optional closest_idx{std::nullopt}; double min_lateral_dist = std::numeric_limits::max(); @@ -132,7 +132,7 @@ size_t findNearestSegmentIndexFromLateralDistance( if (yaw_threshold < std::abs(yaw)) { continue; } - const double lon_dist = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const double lon_dist = autoware::motion_utils::calcLongitudinalOffsetToSegment( points, seg_idx, target_point.position); const double segment_length = calcDistance2d(points.at(seg_idx), points.at(seg_idx + 1)); const double lat_dist = [&]() { @@ -143,7 +143,7 @@ size_t findNearestSegmentIndexFromLateralDistance( return calcDistance2d(points.at(seg_idx + 1), target_point.position); } return std::abs( - autoware_motion_utils::calcLateralOffset(points, target_point.position, seg_idx)); + autoware::motion_utils::calcLateralOffset(points, target_point.position, seg_idx)); }(); if (lat_dist < min_lateral_dist) { closest_idx = seg_idx; @@ -155,7 +155,7 @@ size_t findNearestSegmentIndexFromLateralDistance( return *closest_idx; } - return autoware_motion_utils::findNearestSegmentIndex(points, target_point.position); + return autoware::motion_utils::findNearestSegmentIndex(points, target_point.position); } bool checkHasSameLane( @@ -177,9 +177,9 @@ geometry_msgs::msg::Point calcLongitudinalOffsetStartPoint( const std::vector & points, const geometry_msgs::msg::Pose & pose, const size_t nearest_segment_idx, const double offset) { - const double offset_length = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const double offset_length = autoware::motion_utils::calcLongitudinalOffsetToSegment( points, nearest_segment_idx, pose.position); - const auto offset_point = autoware_motion_utils::calcLongitudinalOffsetPoint( + const auto offset_point = autoware::motion_utils::calcLongitudinalOffsetPoint( points, nearest_segment_idx, offset_length + offset); return offset_point ? offset_point.value() : points.at(nearest_segment_idx); @@ -189,9 +189,9 @@ geometry_msgs::msg::Point calcLongitudinalOffsetGoalPoint( const std::vector & points, const geometry_msgs::msg::Pose & pose, const size_t nearest_segment_idx, const double offset) { - const double offset_length = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const double offset_length = autoware::motion_utils::calcLongitudinalOffsetToSegment( points, nearest_segment_idx, pose.position); - const auto offset_point = autoware_motion_utils::calcLongitudinalOffsetPoint( + const auto offset_point = autoware::motion_utils::calcLongitudinalOffsetPoint( points, nearest_segment_idx, offset_length + offset); return offset_point ? offset_point.value() : points.at(nearest_segment_idx + 1); @@ -246,7 +246,7 @@ std::optional> intersectBound( static_cast(bound.size()) - 1, static_cast(std::max(seg_idx1, seg_idx2)) + 1 + 5)); for (int i = start_idx; i < static_cast(end_idx); ++i) { const auto intersect_point = - autoware_universe_utils::intersect(p1, p2, bound.at(i), bound.at(i + 1)); + autoware::universe_utils::intersect(p1, p2, bound.at(i), bound.at(i + 1)); if (intersect_point) { std::pair result; result.first = static_cast(i); @@ -262,7 +262,7 @@ double calcSquaredDistanceFromPointToSegment( const geometry_msgs::msg::Point & segment_end_point, const geometry_msgs::msg::Point & target_point) { - using autoware_universe_utils::calcSquaredDistance2d; + using autoware::universe_utils::calcSquaredDistance2d; const auto & a = segment_start_point; const auto & b = segment_end_point; @@ -294,10 +294,10 @@ PolygonPoint transformBoundFrenetCoordinate( const size_t min_dist_seg_idx = std::distance( dist_to_bound_segment_vec.begin(), std::min_element(dist_to_bound_segment_vec.begin(), dist_to_bound_segment_vec.end())); - const double lon_dist_to_segment = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const double lon_dist_to_segment = autoware::motion_utils::calcLongitudinalOffsetToSegment( bound_points, min_dist_seg_idx, target_point); const double lat_dist_to_segment = - autoware_motion_utils::calcLateralOffset(bound_points, target_point, min_dist_seg_idx); + autoware::motion_utils::calcLateralOffset(bound_points, target_point, min_dist_seg_idx); return PolygonPoint{target_point, min_dist_seg_idx, lon_dist_to_segment, lat_dist_to_segment}; } @@ -343,7 +343,7 @@ std::vector generatePolygonInsideBounds( if (!intersection) { continue; } - const double lon_dist = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const double lon_dist = autoware::motion_utils::calcLongitudinalOffsetToSegment( bound, intersection->first, intersection->second); const auto intersect_point = PolygonPoint{intersection->second, intersection->first, lon_dist, 0.0}; @@ -437,7 +437,7 @@ std::vector concatenateTwoPolygons( double min_dist_to_intersection = std::numeric_limits::max(); PolygonPoint closest_intersect_point; for (size_t i = 0; i < get_in_poly().size() - 1; ++i) { - const auto intersection = autoware_universe_utils::intersect( + const auto intersection = autoware::universe_utils::intersect( get_out_poly().at(curr_idx).point, get_out_poly().at(next_idx).point, get_in_poly().at(i).point, get_in_poly().at(i + 1).point); if (!intersection) { @@ -454,7 +454,7 @@ std::vector concatenateTwoPolygons( const auto intersect_point = PolygonPoint{*intersection, 0, 0.0, 0.0}; const double dist_to_intersection = - autoware_universe_utils::calcDistance2d(get_out_poly().at(curr_idx).point, *intersection); + autoware::universe_utils::calcDistance2d(get_out_poly().at(curr_idx).point, *intersection); if (dist_to_intersection < min_dist_to_intersection) { closest_idx = i; min_dist_to_intersection = dist_to_intersection; @@ -568,7 +568,7 @@ std::vector getPolygonPointsInsideBounds( // add start and end points projected to bound if necessary if (inside_polygon.at(start_idx).lat_dist_to_bound != 0.0) { // not on bound auto start_point = inside_polygon.at(start_idx); - const auto start_point_on_bound = autoware_motion_utils::calcLongitudinalOffsetPoint( + const auto start_point_on_bound = autoware::motion_utils::calcLongitudinalOffsetPoint( bound, start_point.bound_seg_idx, start_point.lon_dist_to_segment); if (start_point_on_bound) { start_point.point = start_point_on_bound.value(); @@ -577,7 +577,7 @@ std::vector getPolygonPointsInsideBounds( } if (inside_polygon.at(end_idx).lat_dist_to_bound != 0.0) { // not on bound auto end_point = inside_polygon.at(end_idx); - const auto end_point_on_bound = autoware_motion_utils::calcLongitudinalOffsetPoint( + const auto end_point_on_bound = autoware::motion_utils::calcLongitudinalOffsetPoint( bound, end_point.bound_seg_idx, end_point.lon_dist_to_segment); if (end_point_on_bound) { end_point.point = end_point_on_bound.value(); @@ -605,7 +605,7 @@ std::vector updateBoundary( const auto & start_poly = polygon.front(); const auto & end_poly = polygon.back(); - const double front_offset = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const double front_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( updated_bound, start_poly.bound_seg_idx, start_poly.point); const size_t removed_start_idx = @@ -640,7 +640,7 @@ std::vector updateBoundary( namespace autoware::behavior_path_planner::utils { -using autoware_universe_utils::Point2d; +using autoware::universe_utils::Point2d; std::optional getOverlappedLaneletId(const std::vector & lanes) { @@ -852,7 +852,7 @@ void generateDrivableArea( PathWithLaneId & path, const double vehicle_length, const double offset, const bool is_driving_forward) { - using autoware_universe_utils::calcOffsetPose; + using autoware::universe_utils::calcOffsetPose; // remove path points which is close to the previous point PathWithLaneId resampled_path{}; @@ -864,7 +864,7 @@ void generateDrivableArea( const auto & prev_point = resampled_path.points.back().point.pose.position; const auto & curr_point = path.points.at(i).point.pose.position; const double signed_arc_length = - autoware_motion_utils::calcSignedArcLength(path.points, prev_point, curr_point); + autoware::motion_utils::calcSignedArcLength(path.points, prev_point, curr_point); if (signed_arc_length > resample_interval) { resampled_path.points.push_back(path.points.at(i)); } @@ -873,7 +873,7 @@ void generateDrivableArea( // add last point of path if enough far from the one of resampled path constexpr double th_last_point_distance = 0.3; if ( - autoware_universe_utils::calcDistance2d( + autoware::universe_utils::calcDistance2d( resampled_path.points.back().point.pose.position, path.points.back().point.pose.position) > th_last_point_distance) { resampled_path.points.push_back(path.points.back()); @@ -946,7 +946,7 @@ void generateDrivableArea( p_line.push_back(p2); bool intersection_found = false; for (size_t j = i + 2; j < bound.size() - 1; j++) { - const double distance = autoware_universe_utils::calcDistance2d(bound.at(i), bound.at(j)); + const double distance = autoware::universe_utils::calcDistance2d(bound.at(i), bound.at(j)); if (distance > intersection_check_distance) { break; } @@ -1040,12 +1040,12 @@ void extractObstaclesFromDrivableArea( const auto & obj_pos = obstacle.pose.position; // get edge points of the object - const size_t nearest_path_idx = - autoware_motion_utils::findNearestIndex(path.points, obj_pos); // to get z for object polygon + const size_t nearest_path_idx = autoware::motion_utils::findNearestIndex( + path.points, obj_pos); // to get z for object polygon std::vector edge_points; for (int i = 0; i < static_cast(obstacle.poly.outer().size()) - 1; ++i) { // NOTE: There is a duplicated points - edge_points.push_back(autoware_universe_utils::createPoint( + edge_points.push_back(autoware::universe_utils::createPoint( obstacle.poly.outer().at(i).x(), obstacle.poly.outer().at(i).y(), path.points.at(nearest_path_idx).point.pose.position.z)); } @@ -1302,9 +1302,9 @@ std::pair, bool> getBoundWithFreeSpaceAreas( const std::vector & other_side_bound, const std::shared_ptr planner_data, const bool is_left) { - using autoware_universe_utils::getPose; - using autoware_universe_utils::pose2transform; - using autoware_universe_utils::transformVector; + using autoware::universe_utils::getPose; + using autoware::universe_utils::pose2transform; + using autoware::universe_utils::transformVector; using lanelet::utils::to2D; using lanelet::utils::conversion::toGeomMsgPt; using lanelet::utils::conversion::toLaneletPoint; @@ -1382,12 +1382,12 @@ std::pair, bool> getBoundWithFreeSpaceAreas( return bound; } - const auto p_offset = autoware_universe_utils::calcOffsetPose( + const auto p_offset = autoware::universe_utils::calcOffsetPose( ego_pose, (trim_behind_bound ? -100.0 : 100.0), (is_left ? 0.1 : -0.1), 0.0); std::vector ret; for (size_t i = 1; i < bound.size(); ++i) { - const auto intersect = autoware_universe_utils::intersect( + const auto intersect = autoware::universe_utils::intersect( ego_pose.position, p_offset.position, toGeomMsgPt(bound.at(i - 1)), toGeomMsgPt(bound.at(i))); @@ -1492,7 +1492,7 @@ std::vector postProcess( const auto cp = lanelet::utils::conversion::toGeomMsgPt(bound_p); if (bound.empty()) { bound.push_back(cp); - } else if (autoware_universe_utils::calcDistance2d(cp, bound.back()) > overlap_threshold) { + } else if (autoware::universe_utils::calcDistance2d(cp, bound.back()) > overlap_threshold) { bound.push_back(cp); } } @@ -1557,7 +1557,7 @@ std::vector postProcess( const auto start_idx = [&]() { const size_t current_seg_idx = planner_data->findEgoSegmentIndex(path.points); - const auto cropped_path_points = autoware_motion_utils::cropPoints( + const auto cropped_path_points = autoware::motion_utils::cropPoints( path.points, current_pose.position, current_seg_idx, planner_data->parameters.forward_path_length, planner_data->parameters.backward_path_length + planner_data->parameters.input_path_interval); @@ -1596,7 +1596,8 @@ std::vector postProcess( // Insert middle points for (size_t i = start_idx + 1; i <= goal_idx; ++i) { const auto & next_point = tmp_bound.at(i); - const double dist = autoware_universe_utils::calcDistance2d(processed_bound.back(), next_point); + const double dist = + autoware::universe_utils::calcDistance2d(processed_bound.back(), next_point); if (dist > overlap_threshold) { processed_bound.push_back(next_point); } @@ -1604,7 +1605,7 @@ std::vector postProcess( // Insert a goal point if ( - autoware_universe_utils::calcDistance2d(processed_bound.back(), goal_point) > + autoware::universe_utils::calcDistance2d(processed_bound.back(), goal_point) > overlap_threshold) { processed_bound.push_back(goal_point); } @@ -1619,7 +1620,7 @@ std::vector calcBound( const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas, const bool enable_expanding_freespace_areas, const bool is_left, const bool is_driving_forward) { - using autoware_motion_utils::removeOverlapPoints; + using autoware::motion_utils::removeOverlapPoints; const auto & route_handler = planner_data->route_handler; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp index 875de7ff18400..e4f1919b08dbc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp @@ -21,9 +21,9 @@ namespace autoware::behavior_path_planner { -using autoware_universe_utils::createQuaternionFromYaw; -using autoware_universe_utils::normalizeRadian; -using autoware_universe_utils::transformPose; +using autoware::universe_utils::createQuaternionFromYaw; +using autoware::universe_utils::normalizeRadian; +using autoware::universe_utils::transformPose; int discretizeAngle(const double theta, const int theta_size) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp index 92d955edb4542..113b87f4c0032 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp @@ -31,11 +31,11 @@ #include #include -using autoware_universe_utils::calcDistance2d; -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::inverseTransformPoint; -using autoware_universe_utils::normalizeRadian; -using autoware_universe_utils::transformPose; +using autoware::universe_utils::calcDistance2d; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::inverseTransformPoint; +using autoware::universe_utils::normalizeRadian; +using autoware::universe_utils::transformPose; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using lanelet::utils::getArcCoordinates; @@ -70,7 +70,7 @@ PathWithLaneId GeometricParallelParking::getFullPath() const } PathWithLaneId filtered_path = path; - filtered_path.points = autoware_motion_utils::removeOverlapPoints(filtered_path.points); + filtered_path.points = autoware::motion_utils::removeOverlapPoints(filtered_path.points); return filtered_path; } @@ -132,10 +132,10 @@ std::vector GeometricParallelParking::generatePullOverPaths( // check the continuity of straight path and arc path const Pose & road_path_last_pose = straight_path.points.back().point.pose; const Pose & arc_path_first_pose = arc_paths.front().points.front().point.pose; - const double yaw_diff = std::abs(autoware_universe_utils::normalizeRadian( + const double yaw_diff = std::abs(autoware::universe_utils::normalizeRadian( tf2::getYaw(road_path_last_pose.orientation) - tf2::getYaw(arc_path_first_pose.orientation))); const double distance = calcDistance2d(road_path_last_pose, arc_path_first_pose); - if (yaw_diff > autoware_universe_utils::deg2rad(5.0) || distance > 0.1) { + if (yaw_diff > autoware::universe_utils::deg2rad(5.0) || distance > 0.1) { return std::vector{}; } @@ -282,10 +282,10 @@ bool GeometricParallelParking::planPullOut( // check the continuity of straight path and arc path const Pose & road_path_first_pose = road_center_line_path.points.front().point.pose; const Pose & arc_path_last_pose = arc_paths.back().points.back().point.pose; - const double yaw_diff = std::abs(autoware_universe_utils::normalizeRadian( + const double yaw_diff = std::abs(autoware::universe_utils::normalizeRadian( tf2::getYaw(road_path_first_pose.orientation) - tf2::getYaw(arc_path_last_pose.orientation))); const double distance = calcDistance2d(road_path_first_pose, arc_path_last_pose); - if (yaw_diff > autoware_universe_utils::deg2rad(5.0) || distance > 0.1) { + if (yaw_diff > autoware::universe_utils::deg2rad(5.0) || distance > 0.1) { continue; } @@ -299,7 +299,7 @@ bool GeometricParallelParking::planPullOut( paths.back().points.end(), road_center_line_path.points.begin() + 1, // to avoid overlapped point road_center_line_path.points.end()); - paths.back().points = autoware_motion_utils::removeOverlapPoints(paths.back().points); + paths.back().points = autoware::motion_utils::removeOverlapPoints(paths.back().points); // if the end point is the goal, set the velocity to 0 if (path_terminal_is_goal) { @@ -399,7 +399,7 @@ std::vector GeometricParallelParking::planOneTrial( // combine road and shoulder lanes // cut the road lanes up to start_pose to prevent unintended processing for overlapped lane lanelet::ConstLanelets lanes{}; - autoware_universe_utils::Point2d start_point2d(start_pose.position.x, start_pose.position.y); + autoware::universe_utils::Point2d start_point2d(start_pose.position.x, start_pose.position.y); for (const auto & lane : road_lanes) { if (boost::geometry::within(start_point2d, lane.polygon2d().basicPolygon())) { lanes.push_back(lane); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp index 3a9f70c16fb35..69b0deb8c4c5d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp @@ -22,7 +22,7 @@ namespace autoware::behavior_path_planner::utils::parking_departure { -using autoware_motion_utils::calcDecelDistWithJerkAndAccConstraints; +using autoware::motion_utils::calcDecelDistWithJerkAndAccConstraints; std::optional calcFeasibleDecelDistance( std::shared_ptr planner_data, const double acc_lim, const double jerk_lim, @@ -58,7 +58,7 @@ void modifyVelocityByDirection( auto pair_itr = std::begin(terminal_vel_acc_pairs); for (; path_itr != std::end(paths); ++path_itr, ++pair_itr) { - const auto is_driving_forward = autoware_motion_utils::isDrivingForward(path_itr->points); + const auto is_driving_forward = autoware::motion_utils::isDrivingForward(path_itr->points); // If the number of points in the path is less than 2, don't insert stop velocity and // set pairs_terminal_velocity_and_accel to 0 @@ -144,7 +144,7 @@ std::optional generateFeasibleStopPath( } // set stop point - const auto stop_idx = autoware_motion_utils::insertStopPoint( + const auto stop_idx = autoware::motion_utils::insertStopPoint( planner_data->self_odometry->pose.pose, *min_stop_distance, current_path.points); if (!stop_idx) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp index ca72be6fa1568..469be03eb905c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp @@ -39,7 +39,7 @@ bool position_filter( const geometry_msgs::msg::Point & current_pose, const double forward_distance, const double backward_distance) { - const auto dist_ego_to_obj = autoware_motion_utils::calcSignedArcLength( + const auto dist_ego_to_obj = autoware::motion_utils::calcSignedArcLength( path_points, current_pose, object.kinematics.initial_pose_with_covariance.pose.position); return (backward_distance < dist_ego_to_obj && dist_ego_to_obj < forward_distance); @@ -71,16 +71,16 @@ bool isPolygonOverlapLanelet(const PredictedObject & object, const lanelet::Cons } bool isPolygonOverlapLanelet( - const PredictedObject & object, const autoware_universe_utils::Polygon2d & lanelet_polygon) + const PredictedObject & object, const autoware::universe_utils::Polygon2d & lanelet_polygon) { - const auto object_polygon = autoware_universe_utils::toPolygon2d(object); + const auto object_polygon = autoware::universe_utils::toPolygon2d(object); return !boost::geometry::disjoint(lanelet_polygon, object_polygon); } bool isPolygonOverlapLanelet( const PredictedObject & object, const lanelet::BasicPolygon2d & lanelet_polygon) { - const auto object_polygon = autoware_universe_utils::toPolygon2d(object); + const auto object_polygon = autoware::universe_utils::toPolygon2d(object); return !boost::geometry::disjoint(lanelet_polygon, object_polygon); } @@ -273,8 +273,8 @@ std::vector createPredictedPath( length = current_velocity * t_with_delay + 0.5 * acceleration * t_with_delay * t_with_delay; } - const auto pose = - autoware_motion_utils::calcInterpolatedPose(path_points, vehicle_pose_frenet.length + length); + const auto pose = autoware::motion_utils::calcInterpolatedPose( + path_points, vehicle_pose_frenet.length + length); predicted_path.emplace_back(t, pose, velocity); } @@ -315,7 +315,7 @@ ExtendedPredictedObject transform( for (double t = 0.0; t < safety_check_time_horizon + 1e-3; t += safety_check_time_resolution) { const auto obj_pose = object_recognition_utils::calcInterpolatedPose(path, t); if (obj_pose) { - const auto obj_polygon = autoware_universe_utils::toPolygon2d(*obj_pose, object.shape); + const auto obj_polygon = autoware::universe_utils::toPolygon2d(*obj_pose, object.shape); extended_object.predicted_paths[i].path.emplace_back( t, *obj_pose, obj_velocity, obj_polygon); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp index 57ce48c540046..7bb8c13aa65fb 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp @@ -55,13 +55,13 @@ bool isTargetObjectFront( { const double base_to_front = vehicle_info.max_longitudinal_offset_m; const auto ego_offset_pose = - autoware_universe_utils::calcOffsetPose(ego_pose, base_to_front, 0.0, 0.0); + autoware::universe_utils::calcOffsetPose(ego_pose, base_to_front, 0.0, 0.0); // check all edges in the polygon const auto obj_polygon_outer = obj_polygon.outer(); for (const auto & obj_edge : obj_polygon_outer) { - const auto obj_point = autoware_universe_utils::createPoint(obj_edge.x(), obj_edge.y(), 0.0); - if (autoware_universe_utils::calcLongitudinalDeviation(ego_offset_pose, obj_point) > 0.0) { + const auto obj_point = autoware::universe_utils::createPoint(obj_edge.x(), obj_edge.y(), 0.0); + if (autoware::universe_utils::calcLongitudinalDeviation(ego_offset_pose, obj_point) > 0.0) { return true; } } @@ -75,13 +75,13 @@ bool isTargetObjectFront( { const double base_to_front = vehicle_info.max_longitudinal_offset_m; const auto ego_point = - autoware_universe_utils::calcOffsetPose(ego_pose, base_to_front, 0.0, 0.0).position; + autoware::universe_utils::calcOffsetPose(ego_pose, base_to_front, 0.0, 0.0).position; // check all edges in the polygon const auto obj_polygon_outer = obj_polygon.outer(); for (const auto & obj_edge : obj_polygon_outer) { - const auto obj_point = autoware_universe_utils::createPoint(obj_edge.x(), obj_edge.y(), 0.0); - if (autoware_motion_utils::isTargetPointFront(path.points, ego_point, obj_point)) { + const auto obj_point = autoware::universe_utils::createPoint(obj_edge.x(), obj_edge.y(), 0.0); + if (autoware::motion_utils::isTargetPointFront(path.points, ego_point, obj_point)) { return true; } } @@ -111,13 +111,13 @@ Polygon2d createExtendedPolygon( } const auto p1 = - autoware_universe_utils::calcOffsetPose(base_link_pose, forward_lon_offset, lat_offset, 0.0); + autoware::universe_utils::calcOffsetPose(base_link_pose, forward_lon_offset, lat_offset, 0.0); const auto p2 = - autoware_universe_utils::calcOffsetPose(base_link_pose, forward_lon_offset, -lat_offset, 0.0); + autoware::universe_utils::calcOffsetPose(base_link_pose, forward_lon_offset, -lat_offset, 0.0); const auto p3 = - autoware_universe_utils::calcOffsetPose(base_link_pose, backward_lon_offset, -lat_offset, 0.0); + autoware::universe_utils::calcOffsetPose(base_link_pose, backward_lon_offset, -lat_offset, 0.0); const auto p4 = - autoware_universe_utils::calcOffsetPose(base_link_pose, backward_lon_offset, lat_offset, 0.0); + autoware::universe_utils::calcOffsetPose(base_link_pose, backward_lon_offset, lat_offset, 0.0); Polygon2d polygon; appendPointToPolygon(polygon, p1.position); @@ -125,16 +125,16 @@ Polygon2d createExtendedPolygon( appendPointToPolygon(polygon, p3.position); appendPointToPolygon(polygon, p4.position); appendPointToPolygon(polygon, p1.position); - return autoware_universe_utils::isClockwise(polygon) + return autoware::universe_utils::isClockwise(polygon) ? polygon - : autoware_universe_utils::inverseClockwise(polygon); + : autoware::universe_utils::inverseClockwise(polygon); } Polygon2d createExtendedPolygon( const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug) { - const auto obj_polygon = autoware_universe_utils::toPolygon2d(obj_pose, shape); + const auto obj_polygon = autoware::universe_utils::toPolygon2d(obj_pose, shape); if (obj_polygon.outer().empty()) { return obj_polygon; } @@ -145,8 +145,8 @@ Polygon2d createExtendedPolygon( double min_y = std::numeric_limits::max(); const auto obj_polygon_outer = obj_polygon.outer(); for (const auto & polygon_p : obj_polygon_outer) { - const auto obj_p = autoware_universe_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); - const auto transformed_p = autoware_universe_utils::inverseTransformPoint(obj_p, obj_pose); + const auto obj_p = autoware::universe_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); + const auto transformed_p = autoware::universe_utils::inverseTransformPoint(obj_p, obj_pose); max_x = std::max(transformed_p.x, max_x); min_x = std::min(transformed_p.x, min_x); @@ -168,13 +168,13 @@ Polygon2d createExtendedPolygon( } const auto p1 = - autoware_universe_utils::calcOffsetPose(obj_pose, forward_lon_offset, left_lat_offset, 0.0); + autoware::universe_utils::calcOffsetPose(obj_pose, forward_lon_offset, left_lat_offset, 0.0); const auto p2 = - autoware_universe_utils::calcOffsetPose(obj_pose, forward_lon_offset, right_lat_offset, 0.0); + autoware::universe_utils::calcOffsetPose(obj_pose, forward_lon_offset, right_lat_offset, 0.0); const auto p3 = - autoware_universe_utils::calcOffsetPose(obj_pose, backward_lon_offset, right_lat_offset, 0.0); + autoware::universe_utils::calcOffsetPose(obj_pose, backward_lon_offset, right_lat_offset, 0.0); const auto p4 = - autoware_universe_utils::calcOffsetPose(obj_pose, backward_lon_offset, left_lat_offset, 0.0); + autoware::universe_utils::calcOffsetPose(obj_pose, backward_lon_offset, left_lat_offset, 0.0); Polygon2d polygon; appendPointToPolygon(polygon, p1.position); @@ -182,9 +182,9 @@ Polygon2d createExtendedPolygon( appendPointToPolygon(polygon, p3.position); appendPointToPolygon(polygon, p4.position); appendPointToPolygon(polygon, p1.position); - return autoware_universe_utils::isClockwise(polygon) + return autoware::universe_utils::isClockwise(polygon) ? polygon - : autoware_universe_utils::inverseClockwise(polygon); + : autoware::universe_utils::inverseClockwise(polygon); } Polygon2d createExtendedPolygonAlongPath( @@ -208,7 +208,7 @@ Polygon2d createExtendedPolygonAlongPath( debug.lat_offset = lat_offset; } - const auto lon_offset_pose = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto lon_offset_pose = autoware::motion_utils::calcLongitudinalOffsetPose( planned_path.points, base_link_pose.position, lon_length); if (!lon_offset_pose.has_value()) { return createExtendedPolygon( @@ -216,57 +216,57 @@ Polygon2d createExtendedPolygonAlongPath( } const size_t start_idx = - autoware_motion_utils::findNearestSegmentIndex(planned_path.points, base_link_pose.position); - const size_t end_idx = autoware_motion_utils::findNearestSegmentIndex( + autoware::motion_utils::findNearestSegmentIndex(planned_path.points, base_link_pose.position); + const size_t end_idx = autoware::motion_utils::findNearestSegmentIndex( planned_path.points, lon_offset_pose.value().position); Polygon2d polygon; { - const auto p_offset = - autoware_universe_utils::calcOffsetPose(base_link_pose, backward_lon_offset, lat_offset, 0.0); + const auto p_offset = autoware::universe_utils::calcOffsetPose( + base_link_pose, backward_lon_offset, lat_offset, 0.0); appendPointToPolygon(polygon, p_offset.position); } for (size_t i = start_idx + 1; i < end_idx + 1; ++i) { - const auto p = autoware_universe_utils::getPose(planned_path.points.at(i)); - const auto p_offset = autoware_universe_utils::calcOffsetPose(p, 0.0, lat_offset, 0.0); + const auto p = autoware::universe_utils::getPose(planned_path.points.at(i)); + const auto p_offset = autoware::universe_utils::calcOffsetPose(p, 0.0, lat_offset, 0.0); appendPointToPolygon(polygon, p_offset.position); } { - const auto p_offset = autoware_universe_utils::calcOffsetPose( + const auto p_offset = autoware::universe_utils::calcOffsetPose( lon_offset_pose.value(), base_to_front, lat_offset, 0.0); appendPointToPolygon(polygon, p_offset.position); } { - const auto p_offset = autoware_universe_utils::calcOffsetPose( + const auto p_offset = autoware::universe_utils::calcOffsetPose( lon_offset_pose.value(), base_to_front, -lat_offset, 0.0); appendPointToPolygon(polygon, p_offset.position); } for (size_t i = end_idx; i > start_idx; --i) { - const auto p = autoware_universe_utils::getPose(planned_path.points.at(i)); - const auto p_offset = autoware_universe_utils::calcOffsetPose(p, 0.0, -lat_offset, 0.0); + const auto p = autoware::universe_utils::getPose(planned_path.points.at(i)); + const auto p_offset = autoware::universe_utils::calcOffsetPose(p, 0.0, -lat_offset, 0.0); appendPointToPolygon(polygon, p_offset.position); } { - const auto p_offset = autoware_universe_utils::calcOffsetPose( + const auto p_offset = autoware::universe_utils::calcOffsetPose( base_link_pose, backward_lon_offset, -lat_offset, 0.0); appendPointToPolygon(polygon, p_offset.position); } { - const auto p_offset = - autoware_universe_utils::calcOffsetPose(base_link_pose, backward_lon_offset, lat_offset, 0.0); + const auto p_offset = autoware::universe_utils::calcOffsetPose( + base_link_pose, backward_lon_offset, lat_offset, 0.0); appendPointToPolygon(polygon, p_offset.position); } - return autoware_universe_utils::isClockwise(polygon) + return autoware::universe_utils::isClockwise(polygon) ? polygon - : autoware_universe_utils::inverseClockwise(polygon); + : autoware::universe_utils::inverseClockwise(polygon); } std::vector createExtendedPolygonsFromPoseWithVelocityStamped( @@ -283,7 +283,7 @@ std::vector createExtendedPolygonsFromPoseWithVelocityStamped( const double width = vehicle_info.vehicle_width_m + lat_margin * 2; const auto polygon = - autoware_universe_utils::toFootprint(pose, base_to_front, base_to_rear, width); + autoware::universe_utils::toFootprint(pose, base_to_front, base_to_rear, width); polygons.push_back(polygon); } @@ -350,7 +350,7 @@ std::optional calcInterpolatedPoseWithVelocity( const double time_step = pt.time - prev_pt.time; const double ratio = std::clamp(offset / time_step, 0.0, 1.0); const auto interpolated_pose = - autoware_universe_utils::calcInterpolatedPose(prev_pt.pose, pt.pose, ratio, false); + autoware::universe_utils::calcInterpolatedPose(prev_pt.pose, pt.pose, ratio, false); const double interpolated_velocity = interpolation::lerp(prev_pt.velocity, pt.velocity, ratio); return PoseWithVelocityStamped{relative_time, interpolated_pose, interpolated_velocity}; @@ -378,7 +378,7 @@ std::optional getInterpolatedPoseWithVelocity const auto & velocity = interpolation_result->velocity; const auto ego_polygon = - autoware_universe_utils::toFootprint(pose, base_to_front, base_to_rear, width); + autoware::universe_utils::toFootprint(pose, base_to_front, base_to_rear, width); return PoseWithVelocityAndPolygonStamped{current_time, pose, velocity, ego_polygon}; } @@ -406,7 +406,7 @@ std::optional getInterpolatedPoseWithVelocity const auto & pose = interpolation_result->pose; const auto & velocity = interpolation_result->velocity; - const auto obj_polygon = autoware_universe_utils::toPolygon2d(pose, shape); + const auto obj_polygon = autoware::universe_utils::toPolygon2d(pose, shape); return PoseWithVelocityAndPolygonStamped{current_time, pose, velocity, obj_polygon}; } @@ -692,10 +692,10 @@ CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj) CollisionCheckDebug debug; debug.current_obj_pose = obj.initial_pose.pose; debug.extended_obj_polygon = - autoware_universe_utils::toPolygon2d(obj.initial_pose.pose, obj.shape); + autoware::universe_utils::toPolygon2d(obj.initial_pose.pose, obj.shape); debug.obj_shape = obj.shape; debug.current_twist = obj.initial_twist.twist; - return {autoware_universe_utils::toBoostUUID(obj.uuid), debug}; + return {autoware::universe_utils::toBoostUUID(obj.uuid), debug}; } void updateCollisionCheckDebugMap( diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp index fa2c45b74942e..9572e5a92605f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp @@ -51,10 +51,10 @@ std::string toStr(const std::vector & v) namespace autoware::behavior_path_planner { -using autoware_motion_utils::findNearestIndex; -using autoware_motion_utils::insertOrientation; -using autoware_motion_utils::removeFirstInvalidOrientationPoints; -using autoware_motion_utils::removeOverlapPoints; +using autoware::motion_utils::findNearestIndex; +using autoware::motion_utils::insertOrientation; +using autoware::motion_utils::removeFirstInvalidOrientationPoints; +using autoware::motion_utils::removeOverlapPoints; void PathShifter::setPath(const PathWithLaneId & path) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp index 1e2ceac5cd19a..46ca155d04daa 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp @@ -49,8 +49,8 @@ std::vector calcPathArcLengthArray( out.push_back(sum); for (size_t i = bounded_start + 1; i < bounded_end; ++i) { - sum += - autoware_universe_utils::calcDistance2d(path.points.at(i).point, path.points.at(i - 1).point); + sum += autoware::universe_utils::calcDistance2d( + path.points.at(i).point, path.points.at(i - 1).point); out.push_back(sum); } return out; @@ -98,7 +98,7 @@ PathWithLaneId resamplePathWithSpline( // Get lane ids that are not duplicated std::vector s_in; std::unordered_set unique_lane_ids; - const auto s_vec = autoware_motion_utils::calcSignedArcLengthPartialSum( + const auto s_vec = autoware::motion_utils::calcSignedArcLengthPartialSum( transformed_path, 0, transformed_path.size()); for (size_t i = 0; i < path.points.size(); ++i) { const double s = s_vec.at(i); @@ -130,7 +130,7 @@ PathWithLaneId resamplePathWithSpline( // Insert Stop Point const auto closest_stop_dist = - autoware_motion_utils::calcDistanceToForwardStopPoint(transformed_path); + autoware::motion_utils::calcDistanceToForwardStopPoint(transformed_path); if (closest_stop_dist) { const auto close_indices = find_almost_same_values(s_out, *closest_stop_dist); if (close_indices) { @@ -153,7 +153,7 @@ PathWithLaneId resamplePathWithSpline( std::sort(s_out.begin(), s_out.end()); - return autoware_motion_utils::resamplePath(path, s_out); + return autoware::motion_utils::resamplePath(path, s_out); } size_t getIdxByArclength( @@ -163,7 +163,7 @@ size_t getIdxByArclength( throw std::runtime_error("[getIdxByArclength] path points must be > 0"); } - using autoware_universe_utils::calcDistance2d; + using autoware::universe_utils::calcDistance2d; double sum_length = 0.0; if (signed_arc >= 0.0) { for (size_t i = target_idx; i < path.points.size() - 1; ++i) { @@ -185,7 +185,7 @@ size_t getIdxByArclength( return 0; } -// TODO(murooka) This function should be replaced with autoware_motion_utils::cropPoints +// TODO(murooka) This function should be replaced with autoware::motion_utils::cropPoints void clipPathLength( PathWithLaneId & path, const size_t target_idx, const double forward, const double backward) { @@ -202,7 +202,7 @@ void clipPathLength( path.points = clipped_points; } -// TODO(murooka) This function should be replaced with autoware_motion_utils::cropPoints +// TODO(murooka) This function should be replaced with autoware::motion_utils::cropPoints void clipPathLength( PathWithLaneId & path, const size_t target_idx, const BehaviorPathPlannerParameters & params) { @@ -412,7 +412,7 @@ std::vector dividePath( void correctDividedPathVelocity(std::vector & divided_paths) { for (auto & path : divided_paths) { - const auto is_driving_forward = autoware_motion_utils::isDrivingForward(path.points); + const auto is_driving_forward = autoware::motion_utils::isDrivingForward(path.points); // If the number of points in the path is less than 2, don't correct the velocity if (!is_driving_forward) { continue; @@ -472,7 +472,7 @@ std::vector interpolatePose( std::vector interpolated_poses{}; // output const std::vector base_s{ - 0, autoware_universe_utils::calcDistance2d(start_pose.position, end_pose.position)}; + 0, autoware::universe_utils::calcDistance2d(start_pose.position, end_pose.position)}; const std::vector base_x{start_pose.position.x, end_pose.position.x}; const std::vector base_y{start_pose.position.y, end_pose.position.y}; std::vector new_s; @@ -490,7 +490,7 @@ std::vector interpolatePose( std::sin(tf2::getYaw(end_pose.orientation)), new_s); for (size_t i = 0; i < interpolated_x.size(); ++i) { Pose pose{}; - pose = autoware_universe_utils::calcInterpolatedPose( + pose = autoware::universe_utils::calcInterpolatedPose( end_pose, start_pose, (base_s.back() - new_s.at(i)) / base_s.back()); pose.position.x = interpolated_x.at(i); pose.position.y = interpolated_y.at(i); @@ -509,14 +509,14 @@ Pose getUnshiftedEgoPose(const Pose & ego_pose, const ShiftedPath & prev_path) // un-shifted for current ideal pose const auto closest_idx = - autoware_motion_utils::findNearestIndex(prev_path.path.points, ego_pose.position); + autoware::motion_utils::findNearestIndex(prev_path.path.points, ego_pose.position); // NOTE: Considering avoidance by motion, we set unshifted_pose as previous path instead of // ego_pose. auto unshifted_pose = - autoware_motion_utils::calcInterpolatedPoint(prev_path.path, ego_pose).point.pose; + autoware::motion_utils::calcInterpolatedPoint(prev_path.path, ego_pose).point.pose; - unshifted_pose = autoware_universe_utils::calcOffsetPose( + unshifted_pose = autoware::universe_utils::calcOffsetPose( unshifted_pose, 0.0, -prev_path.shift_length.at(closest_idx), 0.0); unshifted_pose.orientation = ego_pose.orientation; @@ -574,7 +574,7 @@ PathWithLaneId combinePath(const PathWithLaneId & path1, const PathWithLaneId & path.points.insert(path.points.end(), next(path2.points.begin()), path2.points.end()); PathWithLaneId filtered_path = path; - filtered_path.points = autoware_motion_utils::removeOverlapPoints(filtered_path.points); + filtered_path.points = autoware::motion_utils::removeOverlapPoints(filtered_path.points); return filtered_path; } @@ -616,10 +616,10 @@ BehaviorModuleOutput getReferencePath( // NOTE: In order to keep backward_path_length at least, resampling interval is added to the // backward. const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( reference_path.points, no_shift_pose, p.ego_nearest_dist_threshold, p.ego_nearest_yaw_threshold); - reference_path.points = autoware_motion_utils::cropPoints( + reference_path.points = autoware::motion_utils::cropPoints( reference_path.points, no_shift_pose.position, current_seg_idx, p.forward_path_length, p.backward_path_length + p.input_path_interval); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp index db41e59e63dbb..40802558c0b38 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp @@ -18,7 +18,7 @@ namespace autoware::behavior_path_planner::utils::traffic_light { -using autoware_motion_utils::calcSignedArcLength; +using autoware::motion_utils::calcSignedArcLength; double getDistanceToNextTrafficLight( const Pose & current_pose, const lanelet::ConstLanelets & lanelets) @@ -99,7 +99,7 @@ std::optional calcDistanceToRedTrafficLight( const auto z = 0.5 * (stop_line.front().z() + stop_line.back().z()); return calcSignedArcLength( - path.points, ego_pos, autoware_universe_utils::createPoint(x, y, z)); + path.points, ego_pos, autoware::universe_utils::createPoint(x, y, z)); } } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp index c6a6256ef43c1..55a6c6ff39d30 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp @@ -43,11 +43,11 @@ double calcInterpolatedZ( const tier4_planning_msgs::msg::PathWithLaneId & input, const geometry_msgs::msg::Point target_pos, const size_t seg_idx) { - const double closest_to_target_dist = autoware_motion_utils::calcSignedArcLength( + const double closest_to_target_dist = autoware::motion_utils::calcSignedArcLength( input.points, input.points.at(seg_idx).point.pose.position, target_pos); // TODO(murooka) implement calcSignedArcLength(points, idx, point) const double seg_dist = - autoware_motion_utils::calcSignedArcLength(input.points, seg_idx, seg_idx + 1); + autoware::motion_utils::calcSignedArcLength(input.points, seg_idx, seg_idx + 1); const double closest_z = input.points.at(seg_idx).point.pose.position.z; const double next_z = input.points.at(seg_idx + 1).point.pose.position.z; @@ -62,7 +62,7 @@ double calcInterpolatedVelocity( const tier4_planning_msgs::msg::PathWithLaneId & input, const size_t seg_idx) { const double seg_dist = - autoware_motion_utils::calcSignedArcLength(input.points, seg_idx, seg_idx + 1); + autoware::motion_utils::calcSignedArcLength(input.points, seg_idx, seg_idx + 1); const double closest_vel = input.points.at(seg_idx).point.longitudinal_velocity_mps; const double next_vel = input.points.at(seg_idx + 1).point.longitudinal_velocity_mps; @@ -73,10 +73,10 @@ double calcInterpolatedVelocity( namespace autoware::behavior_path_planner::utils { +using autoware::universe_utils::LineString2d; +using autoware::universe_utils::Point2d; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::Shape; -using autoware_universe_utils::LineString2d; -using autoware_universe_utils::Point2d; using geometry_msgs::msg::PoseWithCovarianceStamped; std::optional getPolygonByPoint( @@ -113,7 +113,7 @@ double getDistanceBetweenPredictedPaths( if (!ego_pose) { continue; } - double distance = autoware_universe_utils::calcDistance3d(*object_pose, *ego_pose); + double distance = autoware::universe_utils::calcDistance3d(*object_pose, *ego_pose); if (distance < min_distance) { min_distance = distance; } @@ -130,7 +130,7 @@ double getDistanceBetweenPredictedPathAndObject( double min_distance = std::numeric_limits::max(); rclcpp::Time ros_start_time = clock.now() + rclcpp::Duration::from_seconds(start_time); rclcpp::Time ros_end_time = clock.now() + rclcpp::Duration::from_seconds(end_time); - const auto obj_polygon = autoware_universe_utils::toPolygon2d(object); + const auto obj_polygon = autoware::universe_utils::toPolygon2d(object); for (double t = start_time; t < end_time; t += resolution) { const auto ego_pose = object_recognition_utils::calcInterpolatedPose(ego_path, t); if (!ego_pose) { @@ -147,7 +147,7 @@ double getDistanceBetweenPredictedPathAndObject( } bool checkCollisionBetweenPathFootprintsAndObjects( - const autoware_universe_utils::LinearRing2d & local_vehicle_footprint, + const autoware::universe_utils::LinearRing2d & local_vehicle_footprint, const PathWithLaneId & ego_path, const PredictedObjects & dynamic_objects, const double margin) { for (const auto & p : ego_path.points) { @@ -160,14 +160,14 @@ bool checkCollisionBetweenPathFootprintsAndObjects( } bool checkCollisionBetweenFootprintAndObjects( - const autoware_universe_utils::LinearRing2d & local_vehicle_footprint, const Pose & ego_pose, + const autoware::universe_utils::LinearRing2d & local_vehicle_footprint, const Pose & ego_pose, const PredictedObjects & dynamic_objects, const double margin) { const auto vehicle_footprint = - transformVector(local_vehicle_footprint, autoware_universe_utils::pose2transform(ego_pose)); + transformVector(local_vehicle_footprint, autoware::universe_utils::pose2transform(ego_pose)); for (const auto & object : dynamic_objects.objects) { - const auto obj_polygon = autoware_universe_utils::toPolygon2d(object); + const auto obj_polygon = autoware::universe_utils::toPolygon2d(object); const double distance = boost::geometry::distance(obj_polygon, vehicle_footprint); if (distance < margin) return true; } @@ -178,18 +178,18 @@ double calcLateralDistanceFromEgoToObject( const Pose & ego_pose, const double vehicle_width, const PredictedObject & dynamic_object) { double min_distance = std::numeric_limits::max(); - const auto obj_polygon = autoware_universe_utils::toPolygon2d(dynamic_object); + const auto obj_polygon = autoware::universe_utils::toPolygon2d(dynamic_object); const auto vehicle_left_pose = - autoware_universe_utils::calcOffsetPose(ego_pose, 0, vehicle_width / 2, 0); + autoware::universe_utils::calcOffsetPose(ego_pose, 0, vehicle_width / 2, 0); const auto vehicle_right_pose = - autoware_universe_utils::calcOffsetPose(ego_pose, 0, -vehicle_width / 2, 0); + autoware::universe_utils::calcOffsetPose(ego_pose, 0, -vehicle_width / 2, 0); for (const auto & p : obj_polygon.outer()) { - const auto point = autoware_universe_utils::createPoint(p.x(), p.y(), 0.0); + const auto point = autoware::universe_utils::createPoint(p.x(), p.y(), 0.0); const double signed_distance_from_left = - autoware_universe_utils::calcLateralDeviation(vehicle_left_pose, point); + autoware::universe_utils::calcLateralDeviation(vehicle_left_pose, point); const double signed_distance_from_right = - autoware_universe_utils::calcLateralDeviation(vehicle_right_pose, point); + autoware::universe_utils::calcLateralDeviation(vehicle_right_pose, point); if (signed_distance_from_left < 0.0 && signed_distance_from_right > 0.0) { // point is between left and right @@ -208,21 +208,21 @@ double calcLongitudinalDistanceFromEgoToObject( const PredictedObject & dynamic_object) { double min_distance = std::numeric_limits::max(); - const auto obj_polygon = autoware_universe_utils::toPolygon2d(dynamic_object); + const auto obj_polygon = autoware::universe_utils::toPolygon2d(dynamic_object); const auto vehicle_front_pose = - autoware_universe_utils::calcOffsetPose(ego_pose, base_link2front, 0, 0); + autoware::universe_utils::calcOffsetPose(ego_pose, base_link2front, 0, 0); const auto vehicle_rear_pose = - autoware_universe_utils::calcOffsetPose(ego_pose, base_link2rear, 0, 0); + autoware::universe_utils::calcOffsetPose(ego_pose, base_link2rear, 0, 0); for (const auto & p : obj_polygon.outer()) { - const auto point = autoware_universe_utils::createPoint(p.x(), p.y(), 0.0); + const auto point = autoware::universe_utils::createPoint(p.x(), p.y(), 0.0); // forward is positive const double signed_distance_from_front = - autoware_universe_utils::calcLongitudinalDeviation(vehicle_front_pose, point); + autoware::universe_utils::calcLongitudinalDeviation(vehicle_front_pose, point); // backward is positive const double signed_distance_from_rear = - -autoware_universe_utils::calcLongitudinalDeviation(vehicle_rear_pose, point); + -autoware::universe_utils::calcLongitudinalDeviation(vehicle_rear_pose, point); if (signed_distance_from_front < 0.0 && signed_distance_from_rear < 0.0) { // point is between front and rear @@ -254,7 +254,7 @@ std::vector calcObjectsDistanceToPath( { std::vector distance_array; for (const auto & obj : objects.objects) { - const auto obj_polygon = autoware_universe_utils::toPolygon2d(obj); + const auto obj_polygon = autoware::universe_utils::toPolygon2d(obj); LineString2d ego_path_line; ego_path_line.reserve(ego_path.points.size()); for (const auto & p : ego_path.points) { @@ -290,7 +290,7 @@ std::optional findIndexOutOfGoalSearchRange( const auto & lane_ids = points.at(i).lane_ids; const double dist_to_goal = - autoware_universe_utils::calcDistance2d(points.at(i).point.pose, goal); + autoware::universe_utils::calcDistance2d(points.at(i).point.pose, goal); const bool is_goal_lane_id_in_point = std::find(lane_ids.begin(), lane_ids.end(), goal_lane_id) != lane_ids.end(); if (dist_to_goal < max_dist && dist_to_goal < min_dist && is_goal_lane_id_in_point) { @@ -307,7 +307,7 @@ std::optional findIndexOutOfGoalSearchRange( // find index out of goal search range size_t min_dist_out_of_range_index = min_dist_index; for (int i = min_dist_index; 0 <= i; --i) { - const double dist = autoware_universe_utils::calcDistance2d(points.at(i).point, goal); + const double dist = autoware::universe_utils::calcDistance2d(points.at(i).point, goal); min_dist_out_of_range_index = i; if (max_dist < dist) { break; @@ -343,7 +343,7 @@ bool setGoal( PathPointWithLaneId pre_refined_goal{}; constexpr double goal_to_pre_goal_distance = -1.0; pre_refined_goal.point.pose = - autoware_universe_utils::calcOffsetPose(goal, goal_to_pre_goal_distance, 0.0, 0.0); + autoware::universe_utils::calcOffsetPose(goal, goal_to_pre_goal_distance, 0.0, 0.0); const size_t closest_seg_idx_for_pre_goal = findNearestSegmentIndex(input.points, pre_refined_goal.point.pose, 3.0, M_PI_4); pre_refined_goal.point.pose.position.z = @@ -441,7 +441,7 @@ PathWithLaneId refinePathForGoal( { PathWithLaneId filtered_path = input; PathWithLaneId path_with_goal; - filtered_path.points = autoware_motion_utils::removeOverlapPoints(filtered_path.points); + filtered_path.points = autoware::motion_utils::removeOverlapPoints(filtered_path.points); // always set zero velocity at the end of path for safety if (!filtered_path.points.empty()) { @@ -484,7 +484,7 @@ bool isInLaneletWithYawThreshold( const double pose_yaw = tf2::getYaw(current_pose.orientation); const double lanelet_angle = lanelet::utils::getLaneletAngle(lanelet, current_pose.position); const double angle_diff = - std::abs(autoware_universe_utils::normalizeRadian(lanelet_angle - pose_yaw)); + std::abs(autoware::universe_utils::normalizeRadian(lanelet_angle - pose_yaw)); return (angle_diff < std::abs(yaw_threshold)) && lanelet::utils::isInLanelet(current_pose, lanelet, radius); @@ -511,7 +511,7 @@ bool isEgoOutOfRoute( } // If ego vehicle is over goal on goal lane, return true - const double yaw_threshold = autoware_universe_utils::deg2rad(90); + const double yaw_threshold = autoware::universe_utils::deg2rad(90); if ( closest_road_lane.id() == goal_lane.id() && isInLaneletWithYawThreshold(self_pose, goal_lane, yaw_threshold)) { @@ -564,7 +564,7 @@ bool isEgoWithinOriginalLane( const auto base_link2front = common_param.base_link2front; const auto base_link2rear = common_param.base_link2rear; const auto vehicle_width = common_param.vehicle_width; - const auto vehicle_poly = autoware_universe_utils::toFootprint( + const auto vehicle_poly = autoware::universe_utils::toFootprint( current_pose, base_link2front, base_link2rear, vehicle_width); // Check if the ego vehicle is entirely within the lane with a given outer margin. @@ -782,7 +782,7 @@ PathPointWithLaneId insertStopPoint(const double length, PathWithLaneId & path) const size_t original_size = path.points.size(); // insert stop point - const auto insert_idx = autoware_motion_utils::insertStopPoint(length, path.points); + const auto insert_idx = autoware::motion_utils::insertStopPoint(length, path.points); if (!insert_idx) { return PathPointWithLaneId(); } @@ -851,16 +851,16 @@ std::optional getSignedDistanceFromBoundary( rear_left.y = vehicle_width / 2; front_left.x = base_link2front; front_left.y = vehicle_width / 2; - rear_corner_point = autoware_universe_utils::transformPoint(rear_left, vehicle_pose); - front_corner_point = autoware_universe_utils::transformPoint(front_left, vehicle_pose); + rear_corner_point = autoware::universe_utils::transformPoint(rear_left, vehicle_pose); + front_corner_point = autoware::universe_utils::transformPoint(front_left, vehicle_pose); } else { Point front_right, rear_right; rear_right.x = -base_link2rear; rear_right.y = -vehicle_width / 2; front_right.x = base_link2front; front_right.y = -vehicle_width / 2; - rear_corner_point = autoware_universe_utils::transformPoint(rear_right, vehicle_pose); - front_corner_point = autoware_universe_utils::transformPoint(front_right, vehicle_pose); + rear_corner_point = autoware::universe_utils::transformPoint(rear_right, vehicle_pose); + front_corner_point = autoware::universe_utils::transformPoint(front_right, vehicle_pose); } const auto combined_lane = lanelet::utils::combineLaneletsShape(lanelets); @@ -885,17 +885,17 @@ std::optional getSignedDistanceFromBoundary( const Point p2 = lanelet::utils::conversion::toGeomMsgPt(bound_line_2d[i + 1]); const Point inverse_p1 = - autoware_universe_utils::inverseTransformPoint(p1, vehicle_corner_pose); + autoware::universe_utils::inverseTransformPoint(p1, vehicle_corner_pose); const Point inverse_p2 = - autoware_universe_utils::inverseTransformPoint(p2, vehicle_corner_pose); + autoware::universe_utils::inverseTransformPoint(p2, vehicle_corner_pose); const double dx_p1 = inverse_p1.x; const double dx_p2 = inverse_p2.x; const double dy_p1 = inverse_p1.y; const double dy_p2 = inverse_p2.y; // Calculate the Euclidean distances between vehicle's corner and the current and next points. - const double distance1 = autoware_universe_utils::calcDistance2d(p1, vehicle_corner_point); - const double distance2 = autoware_universe_utils::calcDistance2d(p2, vehicle_corner_point); + const double distance1 = autoware::universe_utils::calcDistance2d(p1, vehicle_corner_point); + const double distance2 = autoware::universe_utils::calcDistance2d(p2, vehicle_corner_point); // If one of the bound points is behind and the other is in front of the vehicle corner point // and any of these points is closer than the current minimum distance, @@ -948,9 +948,9 @@ std::optional getSignedDistanceFromBoundary( bound_pose.orientation = vehicle_pose.orientation; const Point inverse_rear_point = - autoware_universe_utils::inverseTransformPoint(rear_corner_point, bound_pose); + autoware::universe_utils::inverseTransformPoint(rear_corner_point, bound_pose); const Point inverse_front_point = - autoware_universe_utils::inverseTransformPoint(front_corner_point, bound_pose); + autoware::universe_utils::inverseTransformPoint(front_corner_point, bound_pose); const double dx_rear = inverse_rear_point.x; const double dx_front = inverse_front_point.x; const double dy_rear = inverse_rear_point.y; @@ -1008,9 +1008,9 @@ Polygon2d toPolygon2d(const lanelet::ConstLanelet & lanelet) } polygon.outer().push_back(polygon.outer().front()); - return autoware_universe_utils::isClockwise(polygon) + return autoware::universe_utils::isClockwise(polygon) ? polygon - : autoware_universe_utils::inverseClockwise(polygon); + : autoware::universe_utils::inverseClockwise(polygon); } Polygon2d toPolygon2d(const lanelet::BasicPolygon2d & polygon) @@ -1021,8 +1021,9 @@ Polygon2d toPolygon2d(const lanelet::BasicPolygon2d & polygon) } ret.outer().push_back(ret.outer().front()); - return autoware_universe_utils::isClockwise(ret) ? ret - : autoware_universe_utils::inverseClockwise(ret); + return autoware::universe_utils::isClockwise(ret) + ? ret + : autoware::universe_utils::inverseClockwise(ret); } std::vector getTargetLaneletPolygons( @@ -1150,13 +1151,13 @@ PathWithLaneId getCenterLinePath( const auto raw_path_with_lane_id = route_handler.getCenterLinePath(lanelet_sequence, s_backward, s_forward, true); - auto resampled_path_with_lane_id = autoware_motion_utils::resamplePath( + auto resampled_path_with_lane_id = autoware::motion_utils::resamplePath( raw_path_with_lane_id, parameter.input_path_interval, parameter.enable_akima_spline_first); // convert centerline, which we consider as CoG center, to rear wheel center if (parameter.enable_cog_on_centerline) { const double rear_to_cog = parameter.vehicle_length / 2 - parameter.rear_overhang; - return autoware_motion_utils::convertToRearWheelCenter( + return autoware::motion_utils::convertToRearWheelCenter( resampled_path_with_lane_id, rear_to_cog); } @@ -1196,7 +1197,7 @@ PathWithLaneId setDecelerationVelocity( for (auto & point : reference_path.points) { const auto arclength_to_target = std::max( - 0.0, autoware_motion_utils::calcSignedArcLength( + 0.0, autoware::motion_utils::calcSignedArcLength( reference_path.points, point.point.pose.position, target_pose.position) + buffer); if (arclength_to_target > deceleration_interval) continue; @@ -1209,7 +1210,7 @@ PathWithLaneId setDecelerationVelocity( } const auto stop_point_length = - autoware_motion_utils::calcSignedArcLength(reference_path.points, 0, target_pose.position) + + autoware::motion_utils::calcSignedArcLength(reference_path.points, 0, target_pose.position) + buffer; constexpr double eps{0.01}; if (std::abs(target_velocity) < eps && stop_point_length > 0.0) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_safety_check.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_safety_check.cpp index 543fbecd1b38b..85a80eac8f215 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_safety_check.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_safety_check.cpp @@ -28,9 +28,9 @@ constexpr double epsilon = 1e-6; using autoware::behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::Shape; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; @@ -47,8 +47,8 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon) { Pose ego_pose; - ego_pose.position = autoware_universe_utils::createPoint(0.0, 0.0, 0.0); - ego_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(0.0); + ego_pose.position = autoware::universe_utils::createPoint(0.0, 0.0, 0.0); + ego_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(0.0); const double lon_length = 10.0; const double lat_margin = 2.0; @@ -75,8 +75,8 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon) { Pose ego_pose; - ego_pose.position = autoware_universe_utils::createPoint(3.0, 4.0, 0.0); - ego_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(0.0); + ego_pose.position = autoware::universe_utils::createPoint(3.0, 4.0, 0.0); + ego_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(0.0); const double lon_length = 10.0; const double lat_margin = 2.0; @@ -103,9 +103,9 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon) { Pose ego_pose; - ego_pose.position = autoware_universe_utils::createPoint(0.0, 0.0, 0.0); + ego_pose.position = autoware::universe_utils::createPoint(0.0, 0.0, 0.0); ego_pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(autoware_universe_utils::deg2rad(60)); + autoware::universe_utils::createQuaternionFromYaw(autoware::universe_utils::deg2rad(60)); const double lon_length = 10.0; const double lat_margin = 2.0; @@ -134,13 +134,13 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon) TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedObjPolygon) { using autoware::behavior_path_planner::utils::path_safety_checker::createExtendedPolygon; - using autoware_universe_utils::createPoint; - using autoware_universe_utils::createQuaternionFromYaw; + using autoware::universe_utils::createPoint; + using autoware::universe_utils::createQuaternionFromYaw; { Pose obj_pose; obj_pose.position = createPoint(0.0, 0.0, 0.0); - obj_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(0.0); + obj_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(0.0); Shape shape; shape.type = autoware_perception_msgs::msg::Shape::POLYGON; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_turn_signal.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_turn_signal.cpp index 1f5ec84a17331..b6149e3b5f99c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_turn_signal.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_turn_signal.cpp @@ -26,9 +26,9 @@ using autoware::behavior_path_planner::PathWithLaneId; using autoware::behavior_path_planner::Pose; using autoware::behavior_path_planner::TurnSignalDecider; using autoware::behavior_path_planner::TurnSignalInfo; +using autoware::universe_utils::createPoint; +using autoware::universe_utils::createQuaternionFromYaw; using autoware_planning_msgs::msg::PathPoint; -using autoware_universe_utils::createPoint; -using autoware_universe_utils::createQuaternionFromYaw; using autoware_vehicle_msgs::msg::HazardLightsCommand; using autoware_vehicle_msgs::msg::TurnIndicatorsCommand; using geometry_msgs::msg::Point; @@ -106,7 +106,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition1) { Pose current_pose = generateEgoSamplePose(5.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -118,7 +118,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition1) { Pose current_pose = generateEgoSamplePose(34.99f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -130,7 +130,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition1) { Pose current_pose = generateEgoSamplePose(40.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -142,7 +142,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition1) { Pose current_pose = generateEgoSamplePose(45.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -154,7 +154,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition1) { Pose current_pose = generateEgoSamplePose(48.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -166,7 +166,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition1) { Pose current_pose = generateEgoSamplePose(48.1f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -178,7 +178,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition1) { Pose current_pose = generateEgoSamplePose(50.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -190,7 +190,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition1) { Pose current_pose = generateEgoSamplePose(50.1f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -202,7 +202,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition1) { Pose current_pose = generateEgoSamplePose(65.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -214,7 +214,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition1) { Pose current_pose = generateEgoSamplePose(65.1f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -255,7 +255,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition2) { Pose current_pose = generateEgoSamplePose(5.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -267,7 +267,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition2) { Pose current_pose = generateEgoSamplePose(34.99f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -279,7 +279,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition2) { Pose current_pose = generateEgoSamplePose(40.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -291,7 +291,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition2) { Pose current_pose = generateEgoSamplePose(45.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -303,7 +303,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition2) { Pose current_pose = generateEgoSamplePose(50.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -315,7 +315,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition2) { Pose current_pose = generateEgoSamplePose(50.1f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -327,7 +327,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition2) { Pose current_pose = generateEgoSamplePose(65.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -368,7 +368,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition3) { Pose current_pose = generateEgoSamplePose(5.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -380,7 +380,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition3) { Pose current_pose = generateEgoSamplePose(29.9f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -392,7 +392,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition3) { Pose current_pose = generateEgoSamplePose(30.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -404,7 +404,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition3) { Pose current_pose = generateEgoSamplePose(33.9f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -416,7 +416,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition3) { Pose current_pose = generateEgoSamplePose(35.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -428,7 +428,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition3) { Pose current_pose = generateEgoSamplePose(44.9f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -440,7 +440,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition3) { Pose current_pose = generateEgoSamplePose(45.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -452,7 +452,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition3) { Pose current_pose = generateEgoSamplePose(49.9f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -464,7 +464,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition3) { Pose current_pose = generateEgoSamplePose(50.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, @@ -476,7 +476,7 @@ TEST(BehaviorPathPlanningTurnSignal, Condition3) { Pose current_pose = generateEgoSamplePose(65.0f, 0.0f, 0.0); const size_t current_seg_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( path.points, current_pose, 3.0, 1.0); const auto result_signal = turn_signal_decider.resolve_turn_signal( path, current_pose, current_seg_idx, intersection_signal_info, behavior_signal_info, diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp index 9ef227783bd9c..2b6f52998cb23 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp @@ -75,8 +75,8 @@ struct SamplingPlannerDebugData { std::vector sampled_candidates{}; size_t previous_sampled_candidates_nb = 0UL; - std::vector obstacles{}; - std::vector footprints{}; + std::vector obstacles{}; + std::vector footprints{}; }; class SamplingPlannerModule : public SceneModuleInterface { @@ -204,10 +204,10 @@ class SamplingPlannerModule : public SceneModuleInterface if (length_to_goal < epsilon) return isReferencePathSafe(); const auto nearest_index = - autoware_motion_utils::findNearestIndex(prev_module_reference_path->points, ego_pose); + autoware::motion_utils::findNearestIndex(prev_module_reference_path->points, ego_pose); if (!nearest_index) return false; auto toYaw = [](const geometry_msgs::msg::Quaternion & quat) -> double { - const auto rpy = autoware_universe_utils::getRPY(quat); + const auto rpy = autoware::universe_utils::getRPY(quat); return rpy.z; }; const auto quat = prev_module_reference_path->points[*nearest_index].point.pose.orientation; diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_parameters.hpp index 15a9e585a7690..f778eef981a92 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_parameters.hpp @@ -21,11 +21,11 @@ #include namespace autoware::behavior_path_planner { -using autoware_universe_utils::LinearRing2d; -using autoware_universe_utils::MultiPoint2d; -using autoware_universe_utils::MultiPolygon2d; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; +using autoware::universe_utils::LinearRing2d; +using autoware::universe_utils::MultiPoint2d; +using autoware::universe_utils::MultiPolygon2d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; struct SamplingPlannerParameters { // constraints.hard diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/util.hpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/util.hpp index c43d1fe601b5f..4408645b26095 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/util.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/util.hpp @@ -101,7 +101,7 @@ inline autoware::sampler_common::State getInitialState( { autoware::sampler_common::State initial_state; Point2d initial_state_pose{pose.position.x, pose.position.y}; - const auto rpy = autoware_universe_utils::getRPY(pose.orientation); + const auto rpy = autoware::universe_utils::getRPY(pose.orientation); initial_state.pose = initial_state_pose; initial_state.frenet = reference_spline.frenet({pose.position.x, pose.position.y}); initial_state.heading = rpy.z; diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/manager.cpp index 6ffd3ff116284..af8a538f894cc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/manager.cpp @@ -77,7 +77,7 @@ void SamplingPlannerModuleManager::init(rclcpp::Node * node) void SamplingPlannerModuleManager::updateModuleParams( [[maybe_unused]] const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; auto & p = parameters_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp index 0e8e56489d6d4..526a761e6957a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp @@ -16,13 +16,13 @@ namespace autoware::behavior_path_planner { -using autoware_motion_utils::calcSignedArcLength; -using autoware_motion_utils::findNearestIndex; -using autoware_motion_utils::findNearestSegmentIndex; -using autoware_universe_utils::calcDistance2d; -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::getPoint; -using autoware_universe_utils::Point2d; +using autoware::motion_utils::calcSignedArcLength; +using autoware::motion_utils::findNearestIndex; +using autoware::motion_utils::findNearestSegmentIndex; +using autoware::universe_utils::calcDistance2d; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::getPoint; +using autoware::universe_utils::Point2d; using geometry_msgs::msg::Point; namespace bg = boost::geometry; @@ -103,7 +103,7 @@ SamplingPlannerModule::SamplingPlannerModule( // [[maybe_unused]] const SoftConstraintsInputs & input_data) -> double { // if (path.points.empty()) return 0.0; // const auto & goal_pose_yaw = - // autoware_universe_utils::getRPY(input_data.goal_pose.orientation).z; const auto & + // autoware::universe_utils::getRPY(input_data.goal_pose.orientation).z; const auto & // last_point_yaw = path.yaws.back(); const double angle_difference = std::abs(last_point_yaw // - goal_pose_yaw); return angle_difference / (3.141519 / 4.0); // }); @@ -190,7 +190,7 @@ bool SamplingPlannerModule::isExecutionRequested() const return false; } - if (!autoware_motion_utils::isDrivingForward(getPreviousModuleOutput().reference_path.points)) { + if (!autoware::motion_utils::isDrivingForward(getPreviousModuleOutput().reference_path.points)) { RCLCPP_WARN(getLogger(), "Backward path is NOT supported. Just converting path to trajectory"); return false; } @@ -343,7 +343,7 @@ PathWithLaneId SamplingPlannerModule::convertFrenetPathToPathWithLaneID( point.lane_ids = path.points.at(i - 1).lane_ids; } if (reference_path_ptr) { - const auto idx = autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + const auto idx = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( reference_path_ptr->points, point.point.pose); const auto & closest_point = reference_path_ptr->points[idx]; point.point.longitudinal_velocity_mps = closest_point.point.longitudinal_velocity_mps; @@ -365,9 +365,9 @@ void SamplingPlannerModule::prepareConstraints( size_t i = 0; for (const auto & o : predicted_objects->objects) { if (o.kinematics.initial_twist_with_covariance.twist.linear.x < 0.5) { - const auto polygon = autoware_universe_utils::toPolygon2d(o); + const auto polygon = autoware::universe_utils::toPolygon2d(o); constraints.obstacle_polygons.push_back(polygon); - const auto box = boost::geometry::return_envelope(polygon); + const auto box = boost::geometry::return_envelope(polygon); constraints.rtree.insert(std::make_pair(box, i)); } i++; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/manager.cpp index ddc9c820a6667..2e8d7e98c11cf 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/manager.cpp @@ -48,7 +48,7 @@ void SideShiftModuleManager::init(rclcpp::Node * node) void SideShiftModuleManager::updateModuleParams( [[maybe_unused]] const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; [[maybe_unused]] auto p = parameters_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp index 065d15fbc8935..bcb972bf5dc8b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp @@ -28,11 +28,11 @@ namespace autoware::behavior_path_planner { -using autoware_motion_utils::calcSignedArcLength; -using autoware_motion_utils::findNearestIndex; -using autoware_motion_utils::findNearestSegmentIndex; -using autoware_universe_utils::calcDistance2d; -using autoware_universe_utils::getPoint; +using autoware::motion_utils::calcSignedArcLength; +using autoware::motion_utils::findNearestIndex; +using autoware::motion_utils::findNearestSegmentIndex; +using autoware::universe_utils::calcDistance2d; +using autoware::universe_utils::getPoint; using geometry_msgs::msg::Point; SideShiftModule::SideShiftModule( @@ -196,7 +196,7 @@ void SideShiftModule::updateData() double max_dist = 0.0; for (const auto & pnt : path_shifter_.getShiftLines()) { max_dist = - std::max(max_dist, autoware_universe_utils::calcDistance2d(getEgoPose(), pnt.start)); + std::max(max_dist, autoware::universe_utils::calcDistance2d(getEgoPose(), pnt.start)); } return max_dist; }(); @@ -373,7 +373,8 @@ double SideShiftModule::getClosestShiftLength() const } const auto ego_point = planner_data_->self_odometry->pose.pose.position; - const auto closest = autoware_motion_utils::findNearestIndex(prev_output_.path.points, ego_point); + const auto closest = + autoware::motion_utils::findNearestIndex(prev_output_.path.points, ego_point); return prev_output_.shift_length.at(closest); } @@ -396,7 +397,7 @@ BehaviorModuleOutput SideShiftModule::adjustDrivableArea(const ShiftedPath & pat auto output_path = path.path; const size_t current_seg_idx = planner_data_->findEgoSegmentIndex(output_path.points); const auto & current_pose = planner_data_->self_odometry->pose.pose; - output_path.points = autoware_motion_utils::cropPoints( + output_path.points = autoware::motion_utils::cropPoints( output_path.points, current_pose.position, current_seg_idx, p.forward_path_length, p.backward_path_length + p.input_path_interval); @@ -468,7 +469,7 @@ void SideShiftModule::setDebugMarkersVisualization() const debug_marker_.markers.clear(); const auto add = [this](const MarkerArray & added) { - autoware_universe_utils::appendMarkerArray(added, &debug_marker_); + autoware::universe_utils::appendMarkerArray(added, &debug_marker_); }; const auto add_shift_line_marker = [this, add]( diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp index 52675653e7b32..7b30745057743 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp @@ -30,7 +30,7 @@ namespace autoware::behavior_path_planner { -using autoware_universe_utils::LinearRing2d; +using autoware::universe_utils::LinearRing2d; using geometry_msgs::msg::Pose; using tier4_planning_msgs::msg::PathWithLaneId; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp index 8be6bc911634a..137a2c53321fc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp @@ -81,7 +81,7 @@ std::optional FreespacePullOut::plan( const size_t index = std::distance(last_path.points.begin(), it); if (index == 0) continue; const double distance = - autoware_universe_utils::calcDistance2d(end_pose.position, it->point.pose.position); + autoware::universe_utils::calcDistance2d(end_pose.position, it->point.pose.position); if (distance < th_end_distance) { last_path.points.erase(it, last_path.points.end()); break; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp index 6e4928e0fbb7f..f3239d41bc1b9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp @@ -22,9 +22,9 @@ #include -using autoware_motion_utils::findNearestIndex; -using autoware_universe_utils::calcDistance2d; -using autoware_universe_utils::calcOffsetPose; +using autoware::motion_utils::findNearestIndex; +using autoware::universe_utils::calcDistance2d; +using autoware::universe_utils::calcOffsetPose; using lanelet::utils::getArcCoordinates; namespace autoware::behavior_path_planner { @@ -92,14 +92,14 @@ std::optional GeometricPullOut::plan( // insert stop velocity to first arc path end output.partial_paths.front().points.back().point.longitudinal_velocity_mps = 0.0; const double arc_length_on_first_arc_path = - autoware_motion_utils::calcArcLength(output.partial_paths.front().points); + autoware::motion_utils::calcArcLength(output.partial_paths.front().points); const double time_to_center = arc_length_on_first_arc_path / (2 * velocity); const double average_velocity = arc_length_on_first_arc_path / (time_to_center * 2); const double average_acceleration = average_velocity / (time_to_center * 2); output.pairs_terminal_velocity_and_accel.push_back( std::make_pair(average_velocity, average_acceleration)); const double arc_length_on_second_arc_path = - autoware_motion_utils::calcArcLength(planner_.getArcPaths().at(1).points); + autoware::motion_utils::calcArcLength(planner_.getArcPaths().at(1).points); output.pairs_terminal_velocity_and_accel.push_back( std::make_pair(velocity, velocity * velocity / (2 * arc_length_on_second_arc_path))); } else { @@ -109,7 +109,7 @@ std::optional GeometricPullOut::plan( // Calculate the acceleration required to reach the forward parking velocity at the center of // the path, assuming constant acceleration and deceleration. - const double arc_length_on_path = autoware_motion_utils::calcArcLength(combined_path.points); + const double arc_length_on_path = autoware::motion_utils::calcArcLength(combined_path.points); output.pairs_terminal_velocity_and_accel.push_back( std::make_pair(velocity, velocity * velocity / 2 * arc_length_on_path)); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp index 0806978a7ef3f..9451bb3870648 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp @@ -351,7 +351,7 @@ void StartPlannerModuleManager::init(rclcpp::Node * node) void StartPlannerModuleManager::updateModuleParams( [[maybe_unused]] const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; auto & p = parameters_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp index c004596de6ff9..971c9a48e8b40 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp @@ -27,9 +27,9 @@ #include #include -using autoware_motion_utils::findNearestIndex; -using autoware_universe_utils::calcDistance2d; -using autoware_universe_utils::calcOffsetPose; +using autoware::motion_utils::findNearestIndex; +using autoware::universe_utils::calcDistance2d; +using autoware::universe_utils::calcOffsetPose; using lanelet::utils::getArcCoordinates; namespace autoware::behavior_path_planner { @@ -108,7 +108,7 @@ std::optional ShiftPullOut::plan( // narrow place. const size_t start_segment_idx = - autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( shift_path.points, start_pose, common_parameters.ego_nearest_dist_threshold, common_parameters.ego_nearest_yaw_threshold); @@ -125,17 +125,18 @@ std::optional ShiftPullOut::plan( if (cropped_path.points.size() < 2) return false; const double max_long_offset = parameters_.maximum_longitudinal_deviation; const size_t start_segment_idx_after_crop = - autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( cropped_path.points, start_pose); // if the start segment id after crop is not 0, then the cropping is not excessive if (start_segment_idx_after_crop != 0) return true; const auto long_offset_to_closest_point = - autoware_motion_utils::calcLongitudinalOffsetToSegment( + autoware::motion_utils::calcLongitudinalOffsetToSegment( cropped_path.points, start_segment_idx_after_crop, start_pose.position); - const auto long_offset_to_next_point = autoware_motion_utils::calcLongitudinalOffsetToSegment( - cropped_path.points, start_segment_idx_after_crop + 1, start_pose.position); + const auto long_offset_to_next_point = + autoware::motion_utils::calcLongitudinalOffsetToSegment( + cropped_path.points, start_segment_idx_after_crop + 1, start_pose.position); return std::abs(long_offset_to_closest_point - long_offset_to_next_point) < max_long_offset; }; @@ -174,7 +175,7 @@ bool ShiftPullOut::refineShiftedPathToStartPose( size_t iteration = 0; while (iteration < MAX_ITERATION) { const double lateral_offset = - autoware_motion_utils::calcLateralOffset(shifted_path.path.points, start_pose.position); + autoware::motion_utils::calcLateralOffset(shifted_path.path.points, start_pose.position); PathShifter path_shifter; path_shifter.setPath(shifted_path.path); @@ -196,7 +197,7 @@ bool ShiftPullOut::refineShiftedPathToStartPose( if (is_within_tolerance( lateral_offset, - autoware_motion_utils::calcLateralOffset(shifted_path.path.points, start_pose.position), + autoware::motion_utils::calcLateralOffset(shifted_path.path.points, start_pose.position), TOLERANCE)) { return true; } @@ -423,7 +424,7 @@ double ShiftPullOut::calcBeforeShiftedArcLength( double after_arc_length{0.0}; for (const auto & [k, segment_length] : - autoware_motion_utils::calcCurvatureAndArcLength(path.points)) { + autoware::motion_utils::calcCurvatureAndArcLength(path.points)) { // after shifted segment length const double after_segment_length = k < 0 ? segment_length * (1 - k * dr) : segment_length / (1 + k * dr); diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index 87e956f51fa1a..9400f3ff40286 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -41,9 +41,9 @@ using autoware::behavior_path_planner::utils::parking_departure::initializeCollisionCheckDebugMap; using autoware::behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject; -using autoware_motion_utils::calcLateralOffset; -using autoware_motion_utils::calcLongitudinalOffsetPose; -using autoware_universe_utils::calcOffsetPose; +using autoware::motion_utils::calcLateralOffset; +using autoware::motion_utils::calcLongitudinalOffsetPose; +using autoware::universe_utils::calcOffsetPose; // set as macro so that calling function name will be printed. // debug print is heavy. turn on only when debugging. @@ -274,7 +274,7 @@ bool StartPlannerModule::hasFinishedBackwardDriving() const // check ego car is close enough to pull out start pose and stopped const auto current_pose = planner_data_->self_odometry->pose.pose; const auto distance = - autoware_universe_utils::calcDistance2d(current_pose, status_.pull_out_start_pose); + autoware::universe_utils::calcDistance2d(current_pose, status_.pull_out_start_pose); const bool is_near = distance < parameters_->th_arrived_distance; const double ego_vel = utils::l2Norm(planner_data_->self_odometry->twist.twist.linear); @@ -383,7 +383,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const boundary_line.begin(), boundary_line.end(), [&boundary_path](const auto & boundary_point) { const double x = boundary_point.x(); const double y = boundary_point.y(); - boundary_path.push_back(autoware_universe_utils::createPoint(x, y, 0.0)); + boundary_path.push_back(autoware::universe_utils::createPoint(x, y, 0.0)); }); return std::fabs(calcLateralOffset(boundary_path, search_pose.position)); @@ -393,12 +393,12 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const const auto centerline_path = route_handler->getCenterLinePath(target_lanes, 0.0, std::numeric_limits::max()); const auto start_pose_nearest_segment_index = - autoware_motion_utils::findNearestSegmentIndex(centerline_path.points, start_pose); + autoware::motion_utils::findNearestSegmentIndex(centerline_path.points, start_pose); if (!start_pose_nearest_segment_index) return false; - const auto start_pose_point_msg = autoware_universe_utils::createPoint( + const auto start_pose_point_msg = autoware::universe_utils::createPoint( start_pose.position.x, start_pose.position.y, start_pose.position.z); - const auto starting_pose_lateral_offset = autoware_motion_utils::calcLateralOffset( + const auto starting_pose_lateral_offset = autoware::motion_utils::calcLateralOffset( centerline_path.points, start_pose_point_msg, start_pose_nearest_segment_index.value()); if (std::isnan(starting_pose_lateral_offset)) return false; @@ -413,7 +413,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const const bool ego_is_merging_from_the_left) -> std::optional> { const auto local_vehicle_footprint = vehicle_info_.createFootprint(); const auto vehicle_footprint = transformVector( - local_vehicle_footprint, autoware_universe_utils::pose2transform(current_pose)); + local_vehicle_footprint, autoware::universe_utils::pose2transform(current_pose)); double smallest_lateral_gap_between_ego_and_border = std::numeric_limits::max(); double corresponding_lateral_gap_with_other_lane_bound = std::numeric_limits::max(); @@ -505,7 +505,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const std::for_each( target_objects_on_lane.on_current_lane.begin(), target_objects_on_lane.on_current_lane.end(), [&](const auto & o) { - const auto arc_length = autoware_motion_utils::calcSignedArcLength( + const auto arc_length = autoware::motion_utils::calcSignedArcLength( centerline_path.points, current_pose.position, o.initial_pose.pose.position); if (arc_length > 0.0) return; if (std::abs(arc_length) >= std::abs(arc_length_to_closet_object)) return; @@ -524,7 +524,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const bool StartPlannerModule::isCloseToOriginalStartPose() const { const Pose start_pose = planner_data_->route_handler->getOriginalStartPose(); - return autoware_universe_utils::calcDistance2d( + return autoware::universe_utils::calcDistance2d( start_pose.position, planner_data_->self_odometry->pose.pose.position) > parameters_->th_arrived_distance; } @@ -532,7 +532,7 @@ bool StartPlannerModule::isCloseToOriginalStartPose() const bool StartPlannerModule::hasArrivedAtGoal() const { const Pose goal_pose = planner_data_->route_handler->getGoalPose(); - return autoware_universe_utils::calcDistance2d( + return autoware::universe_utils::calcDistance2d( goal_pose.position, planner_data_->self_odometry->pose.pose.position) < parameters_->th_arrived_distance; } @@ -684,10 +684,10 @@ BehaviorModuleOutput StartPlannerModule::plan() const auto steering_factor_direction = getSteeringFactorDirection(output); if (status_.driving_forward) { - const double start_distance = autoware_motion_utils::calcSignedArcLength( + const double start_distance = autoware::motion_utils::calcSignedArcLength( path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); - const double finish_distance = autoware_motion_utils::calcSignedArcLength( + const double finish_distance = autoware::motion_utils::calcSignedArcLength( path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.end_pose.position); updateRTCStatus(start_distance, finish_distance); @@ -698,7 +698,7 @@ BehaviorModuleOutput StartPlannerModule::plan() setDebugData(); return output; } - const double distance = autoware_motion_utils::calcSignedArcLength( + const double distance = autoware::motion_utils::calcSignedArcLength( path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); updateRTCStatus(0.0, distance); @@ -788,10 +788,10 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() const auto steering_factor_direction = getSteeringFactorDirection(output); if (status_.driving_forward) { - const double start_distance = autoware_motion_utils::calcSignedArcLength( + const double start_distance = autoware::motion_utils::calcSignedArcLength( stop_path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); - const double finish_distance = autoware_motion_utils::calcSignedArcLength( + const double finish_distance = autoware::motion_utils::calcSignedArcLength( stop_path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.end_pose.position); updateRTCStatus(start_distance, finish_distance); @@ -803,7 +803,7 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() return output; } - const double distance = autoware_motion_utils::calcSignedArcLength( + const double distance = autoware::motion_utils::calcSignedArcLength( stop_path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); updateRTCStatus(0.0, distance); @@ -909,7 +909,7 @@ bool StartPlannerModule::findPullOutPath( // if start_pose_candidate is far from refined_start_pose, backward driving is necessary constexpr double epsilon = 0.01; const double backwards_distance = - autoware_universe_utils::calcDistance2d(start_pose_candidate, refined_start_pose); + autoware::universe_utils::calcDistance2d(start_pose_candidate, refined_start_pose); const bool backward_is_unnecessary = backwards_distance < epsilon; planner->setCollisionCheckMargin(collision_check_margin); @@ -1236,7 +1236,7 @@ PredictedObjects StartPlannerModule::filterStopObjectsInPullOutLanes( bool StartPlannerModule::hasReachedFreespaceEnd() const { const auto & current_pose = planner_data_->self_odometry->pose.pose; - return autoware_universe_utils::calcDistance2d(current_pose, status_.pull_out_path.end_pose) < + return autoware::universe_utils::calcDistance2d(current_pose, status_.pull_out_path.end_pose) < parameters_->th_arrived_distance; } @@ -1278,8 +1278,8 @@ bool StartPlannerModule::hasFinishedCurrentPath() const auto current_path = getCurrentPath(); const auto current_path_end = current_path.points.back(); const auto self_pose = planner_data_->self_odometry->pose.pose; - const bool is_near_target = autoware_universe_utils::calcDistance2d(current_path_end, self_pose) < - parameters_->th_arrived_distance; + const bool is_near_target = autoware::universe_utils::calcDistance2d( + current_path_end, self_pose) < parameters_->th_arrived_distance; return is_near_target && isStopped(); } @@ -1290,10 +1290,10 @@ TurnSignalInfo StartPlannerModule::calcTurnSignalInfo() if (path.points.empty()) return getPreviousModuleOutput().turn_signal_info; const Pose & current_pose = planner_data_->self_odometry->pose.pose; - const auto shift_start_idx = - autoware_motion_utils::findNearestIndex(path.points, status_.pull_out_path.start_pose.position); + const auto shift_start_idx = autoware::motion_utils::findNearestIndex( + path.points, status_.pull_out_path.start_pose.position); const auto shift_end_idx = - autoware_motion_utils::findNearestIndex(path.points, status_.pull_out_path.end_pose.position); + autoware::motion_utils::findNearestIndex(path.points, status_.pull_out_path.end_pose.position); const lanelet::ConstLanelets current_lanes = utils::getCurrentLanes(planner_data_); const auto is_ignore_signal = [this](const lanelet::Id & id) { @@ -1333,7 +1333,7 @@ TurnSignalInfo StartPlannerModule::calcTurnSignalInfo() constexpr double distance_threshold = 1.0; const auto stop_point = status_.pull_out_path.partial_paths.front().points.back(); const double distance_from_ego_to_stop_point = - std::abs(autoware_motion_utils::calcSignedArcLength( + std::abs(autoware::motion_utils::calcSignedArcLength( path.points, stop_point.point.pose.position, current_pose.position)); return distance_from_ego_to_stop_point < distance_threshold; }); @@ -1446,7 +1446,7 @@ bool StartPlannerModule::isGoalBehindOfEgoInSameRouteSegment() const // Return true when the goal is located behind of ego. const auto ego_lane_path = rh->getCenterLinePath( lanelet::ConstLanelets{ego_lanelet}, 0.0, std::numeric_limits::max()); - const auto dist_ego_to_goal = autoware_motion_utils::calcSignedArcLength( + const auto dist_ego_to_goal = autoware::motion_utils::calcSignedArcLength( ego_lane_path.points, getEgoPosition(), rh->getGoalPose().position); const bool is_goal_behind_of_ego = (dist_ego_to_goal < 0.0); @@ -1559,9 +1559,9 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons void StartPlannerModule::setDebugData() { - using autoware_universe_utils::createDefaultMarker; - using autoware_universe_utils::createMarkerColor; - using autoware_universe_utils::createMarkerScale; + using autoware::universe_utils::createDefaultMarker; + using autoware::universe_utils::createMarkerColor; + using autoware::universe_utils::createMarkerScale; using lanelet::visualization::laneletsAsTriangleMarkerArray; using marker_utils::addFootprintMarker; using marker_utils::createFootprintMarkerArray; @@ -1585,7 +1585,7 @@ void StartPlannerModule::setDebugData() for (auto & marker : added.markers) { marker.lifetime = life_time; } - autoware_universe_utils::appendMarkerArray(added, &target_marker_array); + autoware::universe_utils::appendMarkerArray(added, &target_marker_array); }; debug_marker_.markers.clear(); @@ -1615,7 +1615,7 @@ void StartPlannerModule::setDebugData() {PlannerType::GEOMETRIC, parameters_->geometric_collision_check_distance_from_end}}; double collision_check_distance_from_end = collision_check_distances[status_.planner_type]; - const auto collision_check_end_pose = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto collision_check_end_pose = autoware::motion_utils::calcLongitudinalOffsetPose( getFullPath().points, status_.pull_out_path.end_pose.position, collision_check_distance_from_end); if (collision_check_end_pose) { @@ -1669,9 +1669,9 @@ void StartPlannerModule::setDebugData() PathWithLaneId path_shift_start_to_end{}; const auto shift_path = status_.pull_out_path.partial_paths.front(); { - const size_t pull_out_start_idx = autoware_motion_utils::findNearestIndex( + const size_t pull_out_start_idx = autoware::motion_utils::findNearestIndex( shift_path.points, status_.pull_out_path.start_pose.position); - const size_t pull_out_end_idx = autoware_motion_utils::findNearestIndex( + const size_t pull_out_end_idx = autoware::motion_utils::findNearestIndex( shift_path.points, status_.pull_out_path.end_pose.position); path_shift_start_to_end.points.insert( diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/util.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/util.cpp index 82eadd656ac30..3fe9524e34a17 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/util.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/util.cpp @@ -65,7 +65,7 @@ PathWithLaneId getBackwardPath( const double lateral_distance_to_shoulder_center = current_pose_arc_coords.distance; for (size_t i = 0; i < backward_path.points.size(); ++i) { auto & p = backward_path.points.at(i).point.pose; - p = autoware_universe_utils::calcOffsetPose(p, 0, lateral_distance_to_shoulder_center, 0); + p = autoware::universe_utils::calcOffsetPose(p, 0, lateral_distance_to_shoulder_center, 0); } } @@ -115,16 +115,16 @@ std::optional extractCollisionCheckSection( if (full_path.points.empty()) return std::nullopt; // Find the start index for collision check section based on the shift start pose const auto shift_start_idx = - autoware_motion_utils::findNearestIndex(full_path.points, path.start_pose.position); + autoware::motion_utils::findNearestIndex(full_path.points, path.start_pose.position); // Find the end index for collision check section based on the end pose and collision check // distance const auto collision_check_end_idx = [&]() -> size_t { - const auto end_pose_offset = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto end_pose_offset = autoware::motion_utils::calcLongitudinalOffsetPose( full_path.points, path.end_pose.position, collision_check_distance_from_end); return end_pose_offset - ? autoware_motion_utils::findNearestIndex(full_path.points, end_pose_offset->position) + ? autoware::motion_utils::findNearestIndex(full_path.points, end_pose_offset->position) : full_path.points.size() - 1; // Use the last point if offset pose is not calculable }(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp index 04870464c2777..8c46affbc64e3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp @@ -177,14 +177,14 @@ class AvoidanceHelper double getShift(const Point & p) const { validate(); - const auto idx = autoware_motion_utils::findNearestIndex(prev_reference_path_.points, p); + const auto idx = autoware::motion_utils::findNearestIndex(prev_reference_path_.points, p); return prev_spline_shift_path_.shift_length.at(idx); } double getLinearShift(const Point & p) const { validate(); - const auto idx = autoware_motion_utils::findNearestIndex(prev_reference_path_.points, p); + const auto idx = autoware::motion_utils::findNearestIndex(prev_reference_path_.points, p); return prev_linear_shift_path_.shift_length.at(idx); } @@ -278,7 +278,7 @@ class AvoidanceHelper } const auto start_idx = data_->findEgoIndex(path.points); - const auto distance = autoware_motion_utils::calcSignedArcLength( + const auto distance = autoware::motion_utils::calcSignedArcLength( path.points, start_idx, max_v_point_.value().first.position); return std::make_pair(distance, max_v_point_.value().second); } @@ -290,7 +290,7 @@ class AvoidanceHelper const auto & a_now = data_->self_acceleration->accel.accel.linear.x; const auto & a_lim = use_hard_constraints ? p->max_deceleration : p->nominal_deceleration; const auto & j_lim = use_hard_constraints ? p->max_jerk : p->nominal_jerk; - const auto ret = autoware_motion_utils::calcDecelDistWithJerkAndAccConstraints( + const auto ret = autoware::motion_utils::calcDecelDistWithJerkAndAccConstraints( getEgoSpeed(), target_velocity, a_now, a_lim, j_lim, -1.0 * j_lim); if (!!ret) { @@ -449,14 +449,14 @@ class AvoidanceHelper const auto x_max_accel = v_neg_jerk * t_max_accel + p->max_acceleration * std::pow(t_max_accel, 2.0) / 2.0; - const auto point = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto point = autoware::motion_utils::calcLongitudinalOffsetPose( path.points, getEgoPosition(), x_neg_jerk + x_max_accel); if (point.has_value()) { max_v_point_ = std::make_pair(point.value(), v_max); return; } - const auto x_end = autoware_motion_utils::calcSignedArcLength( + const auto x_end = autoware::motion_utils::calcSignedArcLength( path.points, getEgoPosition(), path.points.size() - 1); const auto t_end = (std::sqrt(v0 * v0 + 2.0 * p->max_acceleration * x_end) - v0) / p->max_acceleration; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp index 0000790a3adde..361fe60c21eb1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp @@ -26,8 +26,8 @@ namespace autoware::behavior_path_planner { +using autoware::universe_utils::getOrDeclareParameter; using autoware_perception_msgs::msg::ObjectClassification; -using autoware_universe_utils::getOrDeclareParameter; AvoidanceParameters getParameter(rclcpp::Node * node) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp index ecd83c31f32c8..f1769a45be530 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp @@ -115,7 +115,7 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface const auto ego_idx = planner_data_->findEgoIndex(path.points); for (const auto & left_shift : left_shift_array_) { - const double start_distance = autoware_motion_utils::calcSignedArcLength( + const double start_distance = autoware::motion_utils::calcSignedArcLength( path.points, ego_idx, left_shift.start_pose.position); const double finish_distance = start_distance + left_shift.relative_longitudinal; rtc_interface_ptr_map_.at("left")->updateCooperateStatus( @@ -128,7 +128,7 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface } for (const auto & right_shift : right_shift_array_) { - const double start_distance = autoware_motion_utils::calcSignedArcLength( + const double start_distance = autoware::motion_utils::calcSignedArcLength( path.points, ego_idx, right_shift.start_pose.position); const double finish_distance = start_distance + right_shift.relative_longitudinal; rtc_interface_ptr_map_.at("right")->updateCooperateStatus( diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp index 0ac860fc41882..cfbd3f89308ac 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/type_alias.hpp @@ -53,22 +53,22 @@ using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; using tier4_rtc_msgs::msg::State; // tier4 utils functions -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::calcDistance2d; -using autoware_universe_utils::calcLateralDeviation; -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::calcYawDeviation; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerScale; -using autoware_universe_utils::createPoint; -using autoware_universe_utils::createQuaternionFromRPY; -using autoware_universe_utils::getPoint; -using autoware_universe_utils::getPose; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; -using autoware_universe_utils::pose2transform; -using autoware_universe_utils::toHexString; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::calcDistance2d; +using autoware::universe_utils::calcLateralDeviation; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::calcYawDeviation; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerScale; +using autoware::universe_utils::createPoint; +using autoware::universe_utils::createQuaternionFromRPY; +using autoware::universe_utils::getPoint; +using autoware::universe_utils::getPose; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; +using autoware::universe_utils::pose2transform; +using autoware::universe_utils::toHexString; } // namespace autoware::behavior_path_planner #endif // AUTOWARE__BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__TYPE_ALIAS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp index b5c64ec9959aa..a7db41bf3b617 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp @@ -681,7 +681,7 @@ std::string toStrInfo(const autoware::behavior_path_planner::AvoidLineArray & ap } std::string toStrInfo(const autoware::behavior_path_planner::AvoidLine & ap) { - using autoware_universe_utils::toHexString; + using autoware::universe_utils::toHexString; std::stringstream pids; for (const auto pid : ap.parent_ids) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp index 0ca2b9c4e0d21..2d02f33e19870 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp @@ -28,8 +28,8 @@ namespace autoware::behavior_path_planner { void StaticObstacleAvoidanceModuleManager::init(rclcpp::Node * node) { + using autoware::universe_utils::getOrDeclareParameter; using autoware_perception_msgs::msg::ObjectClassification; - using autoware_universe_utils::getOrDeclareParameter; // init manager interface initInterface(node, {"left", "right"}); @@ -42,8 +42,8 @@ void StaticObstacleAvoidanceModuleManager::init(rclcpp::Node * node) void StaticObstacleAvoidanceModuleManager::updateModuleParams( const std::vector & parameters) { + using autoware::universe_utils::updateParam; using autoware_perception_msgs::msg::ObjectClassification; - using autoware_universe_utils::updateParam; auto p = parameters_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 6600846ce04a1..bbdb8078aadf9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -278,7 +278,7 @@ void StaticObstacleAvoidanceModule::fillFundamentalData( // arclength from ego pose (used in many functions) data.arclength_from_ego = utils::calcPathArcLengthArray( data.reference_path, 0, data.reference_path.points.size(), - autoware_motion_utils::calcSignedArcLength(data.reference_path.points, getEgoPosition(), 0)); + autoware::motion_utils::calcSignedArcLength(data.reference_path.points, getEgoPosition(), 0)); data.to_return_point = utils::static_obstacle_avoidance::calcDistanceToReturnDeadLine( data.current_lanelets, data.reference_path_rough, planner_data_, parameters_); @@ -378,7 +378,7 @@ ObjectData StaticObstacleAvoidanceModule::createObjectData( const auto & path_points = data.reference_path.points; const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; const auto object_closest_index = - autoware_motion_utils::findNearestIndex(path_points, object_pose.position); + autoware::motion_utils::findNearestIndex(path_points, object_pose.position); const auto object_closest_pose = path_points.at(object_closest_index).point.pose; const auto object_type = utils::getHighestProbLabel(object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); @@ -424,7 +424,7 @@ bool StaticObstacleAvoidanceModule::canYieldManeuver(const AvoidancePlanningData const auto registered_lines = path_shifter_.getShiftLines(); if (!registered_lines.empty()) { const size_t idx = planner_data_->findEgoIndex(path_shifter_.getReferencePath().points); - const auto prepare_distance = autoware_motion_utils::calcSignedArcLength( + const auto prepare_distance = autoware::motion_utils::calcSignedArcLength( path_shifter_.getReferencePath().points, idx, registered_lines.front().start_idx); if (!helper_->isEnoughPrepareDistance(prepare_distance)) { RCLCPP_DEBUG( @@ -642,7 +642,7 @@ void StaticObstacleAvoidanceModule::fillDebugData( const auto prepare_distance = helper_->getNominalPrepareDistance(); const auto total_avoid_distance = prepare_distance + avoidance_distance + constant_distance; - dead_pose_ = autoware_motion_utils::calcLongitudinalOffsetPose( + dead_pose_ = autoware::motion_utils::calcLongitudinalOffsetPose( data.reference_path.points, getEgoPosition(), o_front.longitudinal - total_avoid_distance); if (!dead_pose_) { @@ -755,7 +755,7 @@ bool StaticObstacleAvoidanceModule::isSafePath( auto current_debug_data = utils::path_safety_checker::createObjectDebug(object); const auto obj_polygon = - autoware_universe_utils::toPolygon2d(object.initial_pose.pose, object.shape); + autoware::universe_utils::toPolygon2d(object.initial_pose.pose, object.shape); const auto is_object_front = utils::path_safety_checker::isTargetObjectFront(getEgoPose(), obj_polygon, p.vehicle_info); @@ -812,7 +812,7 @@ PathWithLaneId StaticObstacleAvoidanceModule::extendBackwardLength( return a.start_idx < b.start_idx; }); return std::max( - max_dist, autoware_motion_utils::calcSignedArcLength( + max_dist, autoware::motion_utils::calcSignedArcLength( previous_path.points, lines.front().start.position, getEgoPosition())); }(); @@ -821,7 +821,7 @@ PathWithLaneId StaticObstacleAvoidanceModule::extendBackwardLength( planner_data_->parameters.backward_path_length, longest_dist_to_shift_point + extra_margin); const size_t orig_ego_idx = planner_data_->findEgoIndex(original_path.points); - const auto prev_ego_idx = autoware_motion_utils::findNearestSegmentIndex( + const auto prev_ego_idx = autoware::motion_utils::findNearestSegmentIndex( previous_path.points, getPose(original_path.points.at(orig_ego_idx)), std::numeric_limits::max(), planner_data_->parameters.ego_nearest_yaw_threshold); if (!prev_ego_idx) { @@ -832,7 +832,7 @@ PathWithLaneId StaticObstacleAvoidanceModule::extendBackwardLength( for (size_t i = 0; i < prev_ego_idx; ++i) { if ( backward_length > - autoware_motion_utils::calcSignedArcLength(previous_path.points, clip_idx, *prev_ego_idx)) { + autoware::motion_utils::calcSignedArcLength(previous_path.points, clip_idx, *prev_ego_idx)) { break; } clip_idx = i; @@ -925,7 +925,7 @@ BehaviorModuleOutput StaticObstacleAvoidanceModule::plan() constexpr double threshold = 1.0; const auto current_seg_idx = planner_data_->findEgoSegmentIndex(path.points); const auto lateral_deviation = - autoware_motion_utils::calcLateralOffset(path.points, getEgoPosition(), current_seg_idx); + autoware::motion_utils::calcLateralOffset(path.points, getEgoPosition(), current_seg_idx); return std::abs(lateral_deviation) > threshold; }; @@ -1471,7 +1471,7 @@ void StaticObstacleAvoidanceModule::insertReturnDeadLine( // Consider the difference in path length between the shifted path and original path (the path // that is shifted inward has a shorter distance to the end of the path than the other one.) const auto & to_reference_path_end = data.arclength_from_ego.back(); - const auto to_shifted_path_end = autoware_motion_utils::calcSignedArcLength( + const auto to_shifted_path_end = autoware::motion_utils::calcSignedArcLength( shifted_path.path.points, getEgoPosition(), shifted_path.path.points.size() - 1); const auto buffer = std::max(0.0, to_shifted_path_end - to_reference_path_end); @@ -1509,7 +1509,7 @@ void StaticObstacleAvoidanceModule::insertReturnDeadLine( const auto start_idx = planner_data_->findEgoIndex(shifted_path.path.points); for (size_t i = start_idx; i < shifted_path.path.points.size(); ++i) { const auto distance_from_ego = - autoware_motion_utils::calcSignedArcLength(shifted_path.path.points, start_idx, i); + autoware::motion_utils::calcSignedArcLength(shifted_path.path.points, start_idx, i); // slow down speed is inserted only in front of the object. const auto shift_longitudinal_distance = to_stop_line - distance_from_ego; @@ -1602,7 +1602,7 @@ void StaticObstacleAvoidanceModule::insertStopPoint( return shifted_path.path.points.size() - 1; }(); - const auto stop_distance = autoware_motion_utils::calcSignedArcLength( + const auto stop_distance = autoware::motion_utils::calcSignedArcLength( shifted_path.path.points, getEgoPosition(), stop_idx); // If we don't need to consider deceleration constraints, insert a deceleration point @@ -1715,7 +1715,7 @@ void StaticObstacleAvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_ const auto start_idx = planner_data_->findEgoIndex(shifted_path.path.points); for (size_t i = start_idx; i < shifted_path.path.points.size(); ++i) { const auto distance_from_ego = - autoware_motion_utils::calcSignedArcLength(shifted_path.path.points, start_idx, i); + autoware::motion_utils::calcSignedArcLength(shifted_path.path.points, start_idx, i); // slow down speed is inserted only in front of the object. const auto shift_longitudinal_distance = distance_to_object - distance_from_ego; @@ -1732,7 +1732,7 @@ void StaticObstacleAvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_ shifted_path.path.points.at(i).point.longitudinal_velocity_mps = std::min(v_original, v_insert); } - slow_pose_ = autoware_motion_utils::calcLongitudinalOffsetPose( + slow_pose_ = autoware::motion_utils::calcLongitudinalOffsetPose( shifted_path.path.points, start_idx, distance_to_object); } @@ -1759,7 +1759,7 @@ void StaticObstacleAvoidanceModule::insertAvoidanceVelocity(ShiftedPath & shifte const auto start_idx = planner_data_->findEgoIndex(shifted_path.path.points); for (size_t i = start_idx; i < shifted_path.path.points.size(); ++i) { const auto distance_from_ego = - autoware_motion_utils::calcSignedArcLength(shifted_path.path.points, start_idx, i); + autoware::motion_utils::calcSignedArcLength(shifted_path.path.points, start_idx, i); // slow down speed is inserted only in front of the object. const auto accel_distance = distance_to_accel_end_point - distance_from_ego; @@ -1779,7 +1779,7 @@ void StaticObstacleAvoidanceModule::insertAvoidanceVelocity(ShiftedPath & shifte shifted_path.path.points.at(i).point.longitudinal_velocity_mps = std::min(v_original, v_target); } - slow_pose_ = autoware_motion_utils::calcLongitudinalOffsetPose( + slow_pose_ = autoware::motion_utils::calcLongitudinalOffsetPose( shifted_path.path.points, start_idx, distance_to_accel_end_point); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp index 7580623cff714..a171ae9161041 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp @@ -355,7 +355,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( return false; } const auto goal_pose = data_->route_handler->getGoalPose(); - const double goal_longitudinal_distance = autoware_motion_utils::calcSignedArcLength( + const double goal_longitudinal_distance = autoware::motion_utils::calcSignedArcLength( data.reference_path.points, 0, goal_pose.position); const bool is_return_shift_to_goal = std::abs(al_return.end_longitudinal - goal_longitudinal_distance) < @@ -365,7 +365,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( } const auto & object_pos = o.object.kinematics.initial_pose_with_covariance.pose.position; const bool has_object_near_goal = - autoware_universe_utils::calcDistance2d(goal_pose.position, object_pos) < + autoware::universe_utils::calcDistance2d(goal_pose.position, object_pos) < parameters_->object_check_goal_distance; return has_object_near_goal; }(); @@ -1026,7 +1026,7 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( if (utils::isAllowedGoalModification(data_->route_handler)) { const auto has_object_near_goal = std::any_of(data.target_objects.begin(), data.target_objects.end(), [&](const auto & o) { - return autoware_universe_utils::calcDistance2d( + return autoware::universe_utils::calcDistance2d( data_->route_handler->getGoalPose().position, o.object.kinematics.initial_pose_with_covariance.pose.position) < parameters_->object_check_goal_distance; @@ -1097,7 +1097,7 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( if (utils::isAllowedGoalModification(data_->route_handler)) { const bool has_last_shift_near_goal = std::any_of(data.target_objects.begin(), data.target_objects.end(), [&](const auto & o) { - return autoware_universe_utils::calcDistance2d( + return autoware::universe_utils::calcDistance2d( last_sl.end.position, o.object.kinematics.initial_pose_with_covariance.pose.position) < parameters_->object_check_goal_distance; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 2704829ad6a11..05561318039b7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -56,7 +56,7 @@ geometry_msgs::msg::Point32 createPoint32(const double x, const double y, const } geometry_msgs::msg::Polygon toMsg( - const autoware_universe_utils::Polygon2d & polygon, const double z) + const autoware::universe_utils::Polygon2d & polygon, const double z) { geometry_msgs::msg::Polygon ret; for (const auto & p : polygon.outer()) { @@ -68,14 +68,14 @@ geometry_msgs::msg::Polygon toMsg( template size_t findFirstNearestIndex(const T & points, const geometry_msgs::msg::Point & point) { - autoware_motion_utils::validateNonEmpty(points); + autoware::motion_utils::validateNonEmpty(points); double min_dist = std::numeric_limits::max(); size_t min_idx = 0; bool decreasing = false; for (size_t i = 0; i < points.size(); ++i) { - const auto dist = autoware_universe_utils::calcSquaredDistance2d(points.at(i), point); + const auto dist = autoware::universe_utils::calcSquaredDistance2d(points.at(i), point); if (dist < min_dist) { decreasing = true; min_dist = dist; @@ -104,7 +104,7 @@ size_t findFirstNearestSegmentIndex(const T & points, const geometry_msgs::msg:: } const double signed_length = - autoware_motion_utils::calcLongitudinalOffsetToSegment(points, nearest_idx, point); + autoware::motion_utils::calcLongitudinalOffsetToSegment(points, nearest_idx, point); if (signed_length <= 0) { return nearest_idx - 1; @@ -119,7 +119,7 @@ double calcSignedArcLengthToFirstNearestPoint( const geometry_msgs::msg::Point & dst_point) { try { - autoware_motion_utils::validateNonEmpty(points); + autoware::motion_utils::validateNonEmpty(points); } catch (const std::exception & e) { std::cerr << e.what() << std::endl; return 0.0; @@ -129,11 +129,11 @@ double calcSignedArcLengthToFirstNearestPoint( const size_t dst_seg_idx = findFirstNearestSegmentIndex(points, dst_point); const double signed_length_on_traj = - autoware_motion_utils::calcSignedArcLength(points, src_seg_idx, dst_seg_idx); + autoware::motion_utils::calcSignedArcLength(points, src_seg_idx, dst_seg_idx); const double signed_length_src_offset = - autoware_motion_utils::calcLongitudinalOffsetToSegment(points, src_seg_idx, src_point); + autoware::motion_utils::calcLongitudinalOffsetToSegment(points, src_seg_idx, src_point); const double signed_length_dst_offset = - autoware_motion_utils::calcLongitudinalOffsetToSegment(points, dst_seg_idx, dst_point); + autoware::motion_utils::calcLongitudinalOffsetToSegment(points, dst_seg_idx, dst_point); return signed_length_on_traj - signed_length_src_offset + signed_length_dst_offset; } @@ -329,7 +329,7 @@ bool isWithinIntersection( return false; } - const auto object_polygon = autoware_universe_utils::toPolygon2d(object.object); + const auto object_polygon = autoware::universe_utils::toPolygon2d(object.object); const auto polygon = route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(area_id.c_str())); @@ -646,7 +646,7 @@ bool isNeverAvoidanceTarget( return true; } - const auto object_polygon = autoware_universe_utils::toPolygon2d(object.object); + const auto object_polygon = autoware::universe_utils::toPolygon2d(object.object); const auto is_disjoint_right_lane = boost::geometry::disjoint(object_polygon, right_lane.value().polygon2d().basicPolygon()); if (is_disjoint_right_lane) { @@ -669,7 +669,7 @@ bool isNeverAvoidanceTarget( return true; } - const auto object_polygon = autoware_universe_utils::toPolygon2d(object.object); + const auto object_polygon = autoware::universe_utils::toPolygon2d(object.object); const auto is_disjoint_left_lane = boost::geometry::disjoint(object_polygon, left_lane.value().polygon2d().basicPolygon()); if (is_disjoint_left_lane) { @@ -759,7 +759,7 @@ bool isSatisfiedWithCommonCondition( const auto ego_idx = planner_data->findEgoIndex(data.reference_path_rough.points); const auto to_goal_distance = rh->isInGoalRouteSection(data.current_lanelets.back()) - ? autoware_motion_utils::calcSignedArcLength( + ? autoware::motion_utils::calcSignedArcLength( data.reference_path_rough.points, ego_idx, data.reference_path_rough.points.size() - 1) : std::numeric_limits::max(); @@ -941,12 +941,12 @@ double getRoadShoulderDistance( ObjectData & object, const AvoidancePlanningData & data, const std::shared_ptr & planner_data) { - using autoware_universe_utils::Point2d; + using autoware::universe_utils::Point2d; using lanelet::utils::to2D; const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; const auto object_closest_index = - autoware_motion_utils::findNearestIndex(data.reference_path.points, object_pose.position); + autoware::motion_utils::findNearestIndex(data.reference_path.points, object_pose.position); const auto object_closest_pose = data.reference_path.points.at(object_closest_index).point.pose; const auto rh = planner_data->route_handler; @@ -969,7 +969,7 @@ double getRoadShoulderDistance( const auto p2 = calcOffsetPose(p_tmp, 0.0, (isOnRight(object) ? 100.0 : -100.0), 0.0).position; const auto opt_intersect = - autoware_universe_utils::intersect(p1.second, p2, bound.at(i - 1), bound.at(i)); + autoware::universe_utils::intersect(p1.second, p2, bound.at(i - 1), bound.at(i)); if (opt_intersect.has_value()) { intersects.emplace_back( @@ -987,7 +987,7 @@ double getRoadShoulderDistance( calcOffsetPose(p_tmp, 0.0, (isOnRight(object) ? -0.5 : 0.5) * envelope_polygon_width, 0.0) .position; const auto opt_intersect = - autoware_universe_utils::intersect(p1.second, p2, bound.at(i - 1), bound.at(i)); + autoware::universe_utils::intersect(p1.second, p2, bound.at(i - 1), bound.at(i)); if (opt_intersect.has_value()) { intersects.emplace_back( @@ -1036,8 +1036,8 @@ bool isWithinLanes( { const auto & rh = planner_data->route_handler; const auto & ego_pose = planner_data->self_odometry->pose.pose; - const auto transform = autoware_universe_utils::pose2transform(ego_pose); - const auto footprint = autoware_universe_utils::transformVector( + const auto transform = autoware::universe_utils::pose2transform(ego_pose); + const auto footprint = autoware::universe_utils::transformVector( planner_data->parameters.vehicle_info.createFootprint(), transform); lanelet::ConstLanelet closest_lanelet{}; @@ -1193,10 +1193,10 @@ void fillLongitudinalAndLengthByClosestEnvelopeFootprint( double min_distance = std::numeric_limits::max(); double max_distance = std::numeric_limits::lowest(); for (const auto & p : obj.envelope_poly.outer()) { - const auto point = autoware_universe_utils::createPoint(p.x(), p.y(), 0.0); + const auto point = autoware::universe_utils::createPoint(p.x(), p.y(), 0.0); // TODO(someone): search around first position where the ego should avoid the object. const double arc_length = - autoware_motion_utils::calcSignedArcLength(path.points, ego_pos, point); + autoware::motion_utils::calcSignedArcLength(path.points, ego_pos, point); min_distance = std::min(min_distance, arc_length); max_distance = std::max(max_distance, arc_length); } @@ -1211,9 +1211,9 @@ std::vector> calcEnvelopeOverhangDistance( std::vector> overhang_points{}; for (const auto & p : object_data.envelope_poly.outer()) { - const auto point = autoware_universe_utils::createPoint(p.x(), p.y(), 0.0); + const auto point = autoware::universe_utils::createPoint(p.x(), p.y(), 0.0); // TODO(someone): search around first position where the ego should avoid the object. - const auto idx = autoware_motion_utils::findNearestIndex(path.points, point); + const auto idx = autoware::motion_utils::findNearestIndex(path.points, point); const auto lateral = calcLateralDeviation(getPose(path.points.at(idx)), point); overhang_points.emplace_back(lateral, point); } @@ -1247,9 +1247,9 @@ Polygon2d createEnvelopePolygon( const Polygon2d & object_polygon, const Pose & closest_pose, const double envelope_buffer) { namespace bg = boost::geometry; - using autoware_universe_utils::expandPolygon; - using autoware_universe_utils::Point2d; - using autoware_universe_utils::Polygon2d; + using autoware::universe_utils::expandPolygon; + using autoware::universe_utils::Point2d; + using autoware::universe_utils::Polygon2d; using Box = bg::model::box; const auto toPolygon2d = [](const geometry_msgs::msg::Polygon & polygon) { @@ -1293,7 +1293,7 @@ Polygon2d createEnvelopePolygon( Polygon2d createEnvelopePolygon( const ObjectData & object_data, const Pose & closest_pose, const double envelope_buffer) { - const auto object_polygon = autoware_universe_utils::toPolygon2d(object_data.object); + const auto object_polygon = autoware::universe_utils::toPolygon2d(object_data.object); return createEnvelopePolygon(object_polygon, closest_pose, envelope_buffer); } @@ -1325,7 +1325,7 @@ std::vector generateObstaclePolygonsForDrivableArea( const double diff_poly_buffer = object.avoid_margin.value() - object_parameter.envelope_buffer_margin - vehicle_width / 2.0; const auto obj_poly = - autoware_universe_utils::expandPolygon(object.envelope_poly, diff_poly_buffer); + autoware::universe_utils::expandPolygon(object.envelope_poly, diff_poly_buffer); obstacles_for_drivable_area.push_back( {object.object.kinematics.initial_pose_with_covariance.pose, obj_poly, !isOnRight(object)}); } @@ -1385,7 +1385,7 @@ void insertDecelPoint( std::optional & p_out) { const auto decel_point = - autoware_motion_utils::calcLongitudinalOffsetPoint(path.points, p_src, offset); + autoware::motion_utils::calcLongitudinalOffsetPoint(path.points, p_src, offset); if (!decel_point) { // TODO(Satoshi OTA) Think later the process in the case of no decel point found. @@ -1393,9 +1393,9 @@ void insertDecelPoint( } const auto seg_idx = - autoware_motion_utils::findNearestSegmentIndex(path.points, decel_point.value()); + autoware::motion_utils::findNearestSegmentIndex(path.points, decel_point.value()); const auto insert_idx = - autoware_motion_utils::insertTargetPoint(seg_idx, decel_point.value(), path.points); + autoware::motion_utils::insertTargetPoint(seg_idx, decel_point.value(), path.points); if (!insert_idx) { // TODO(Satoshi OTA) Think later the process in the case of no decel point found. @@ -1457,7 +1457,7 @@ void fillObjectEnvelopePolygon( const auto multi_step_envelope_poly = createEnvelopePolygon(unions.front(), closest_pose, 0.0); - const auto object_polygon = autoware_universe_utils::toPolygon2d(object_data.object); + const auto object_polygon = autoware::universe_utils::toPolygon2d(object_data.object); const auto object_polygon_area = boost::geometry::area(object_polygon); const auto envelope_polygon_area = boost::geometry::area(multi_step_envelope_poly); @@ -1817,9 +1817,9 @@ void fillAdditionalInfoFromPoint(const AvoidancePlanningData & data, AvoidLineAr // calc longitudinal for (auto & sl : lines) { - sl.start_idx = autoware_motion_utils::findNearestIndex(path.points, sl.start.position); + sl.start_idx = autoware::motion_utils::findNearestIndex(path.points, sl.start.position); sl.start_longitudinal = arc.at(sl.start_idx); - sl.end_idx = autoware_motion_utils::findNearestIndex(path.points, sl.end.position); + sl.end_idx = autoware::motion_utils::findNearestIndex(path.points, sl.end.position); sl.end_longitudinal = arc.at(sl.end_idx); } } @@ -1868,7 +1868,7 @@ AvoidLineArray combineRawShiftLinesWithUniqueCheck( { // TODO(Horibe) parametrize const auto isSimilar = [](const AvoidLine & a, const AvoidLine & b) { - using autoware_universe_utils::calcDistance2d; + using autoware::universe_utils::calcDistance2d; if (calcDistance2d(a.start, b.start) > 1.0) { return false; } @@ -2117,7 +2117,7 @@ std::pair separateObjectsByPath( double next_longitudinal_distance = parameters->resample_interval_for_output; for (size_t i = 0; i < points_size; ++i) { const auto distance_from_ego = - autoware_motion_utils::calcSignedArcLength(reference_path.points, ego_idx, i); + autoware::motion_utils::calcSignedArcLength(reference_path.points, ego_idx, i); if (distance_from_ego > object_check_forward_distance) { break; } @@ -2155,7 +2155,7 @@ std::pair separateObjectsByPath( const auto objects = planner_data->dynamic_object->objects; std::for_each(objects.begin(), objects.end(), [&](const auto & object) { - const auto obj_polygon = autoware_universe_utils::toPolygon2d(object); + const auto obj_polygon = autoware::universe_utils::toPolygon2d(object); if (!within_detection_area(obj_polygon)) { other_objects.objects.push_back(object); } else { @@ -2365,7 +2365,7 @@ double calcDistanceToReturnDeadLine( if (planner_data->route_handler->isInGoalRouteSection(lanelets.back())) { const auto & ego_pos = planner_data->self_odometry->pose.pose.position; const auto to_goal_distance = - autoware_motion_utils::calcSignedArcLength(path.points, ego_pos, path.points.size() - 1); + autoware::motion_utils::calcSignedArcLength(path.points, ego_pos, path.points.size() - 1); distance_to_return_dead_line = std::min( distance_to_return_dead_line, to_goal_distance - parameters->dead_line_buffer_for_goal); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/debug.cpp index 31d90a7d7d708..714280daad38e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/debug.cpp @@ -27,10 +27,10 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerOrientation; -using autoware_universe_utils::createMarkerScale; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerOrientation; +using autoware::universe_utils::createMarkerScale; namespace { @@ -73,12 +73,12 @@ visualization_msgs::msg::MarkerArray createLaneletPolygonsMarkerArray( } // namespace -autoware_motion_utils::VirtualWalls BlindSpotModule::createVirtualWalls() +autoware::motion_utils::VirtualWalls BlindSpotModule::createVirtualWalls() { - autoware_motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWalls virtual_walls; if (debug_data_.virtual_wall_pose) { - autoware_motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWall wall; wall.text = "blind_spot"; wall.pose = debug_data_.virtual_wall_pose.value(); wall.ns = std::to_string(module_id_) + "_"; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp index e4b3a341a9b91..da4582dd1643f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp @@ -88,7 +88,7 @@ void BlindSpotModule::setRTCStatusByDecision( { setSafe(false); const auto & current_pose = planner_data_->current_odometry->pose; - setDistance(autoware_motion_utils::calcSignedArcLength( + setDistance(autoware::motion_utils::calcSignedArcLength( path.points, current_pose.position, decision.stop_line_idx)); return; } @@ -124,7 +124,7 @@ void BlindSpotModule::setRTCStatusByDecision( { setSafe(true); const auto & current_pose = planner_data_->current_odometry->pose; - setDistance(autoware_motion_utils::calcSignedArcLength( + setDistance(autoware::motion_utils::calcSignedArcLength( path.points, current_pose.position, decision.stop_line_idx)); return; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp index e51a55784b72c..f7e859a9085c7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp @@ -91,7 +91,7 @@ BlindSpotDecision BlindSpotModule::modifyPathVelocityDetail( /* calc closest index */ const auto & current_pose = planner_data_->current_odometry->pose; - const auto closest_idx = autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + const auto closest_idx = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( input_path.points, current_pose, planner_data_->ego_nearest_dist_threshold, planner_data_->ego_nearest_yaw_threshold); const auto stop_line_idx = @@ -256,7 +256,7 @@ std::optional BlindSpotModule::getSiblingStraightLanelet( static std::optional getFirstPointIntersectsLineByFootprint( const lanelet::ConstLineString2d & line, const InterpolatedPathInfo & interpolated_path_info, - const autoware_universe_utils::LinearRing2d & footprint, const double vehicle_length) + const autoware::universe_utils::LinearRing2d & footprint, const double vehicle_length) { const auto & path_ip = interpolated_path_info.path; const auto [lane_start, lane_end] = interpolated_path_info.lane_id_interval.value(); @@ -266,8 +266,8 @@ static std::optional getFirstPointIntersectsLineByFootprint( const auto line2d = line.basicLineString(); for (auto i = start; i <= lane_end; ++i) { const auto & base_pose = path_ip.points.at(i).point.pose; - const auto path_footprint = autoware_universe_utils::transformVector( - footprint, autoware_universe_utils::pose2transform(base_pose)); + const auto path_footprint = autoware::universe_utils::transformVector( + footprint, autoware::universe_utils::pose2transform(base_pose)); if (bg::intersects(path_footprint, line2d)) { return std::make_optional(i); } @@ -282,7 +282,7 @@ static std::optional getDuplicatedPointIdx( const auto & p = path.points.at(i).point.pose.position; constexpr double min_dist = 0.001; - if (autoware_universe_utils::calcDistance2d(p, point) < min_dist) { + if (autoware::universe_utils::calcDistance2d(p, point) < min_dist) { return i; } } @@ -299,7 +299,7 @@ static std::optional insertPointIndex( return duplicate_idx_opt.value(); } - const size_t closest_idx = autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + const size_t closest_idx = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( inout_path->points, in_pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); // vector.insert(i) inserts element on the left side of v[i] // the velocity need to be zero order hold(from prior point) @@ -361,12 +361,12 @@ std::optional> BlindSpotModule::generateStopLine( const geometry_msgs::msg::Point mid_point = geometry_msgs::build().x(mid_pt.x()).y(mid_pt.y()).z(mid_pt.z()); stop_idx_default_ip = stop_idx_critical_ip = - autoware_motion_utils::findNearestSegmentIndex(path_ip.points, mid_point); + autoware::motion_utils::findNearestSegmentIndex(path_ip.points, mid_point); /* // NOTE: it is not ambiguous when the curve starts on the left/right lanelet, so this module inserts stopline at the beginning of the lanelet for baselink stop_idx_default_ip = stop_idx_critical_ip = static_cast(std::max(0, - static_cast(autoware_motion_utils::findNearestSegmentIndex(path_ip.points, mid_point)) - + static_cast(autoware::motion_utils::findNearestSegmentIndex(path_ip.points, mid_point)) - baselink2front_dist)); */ } @@ -420,12 +420,12 @@ std::optional BlindSpotModule::isOverPassJudge( planner_data_->current_velocity->twist.linear.x, planner_data_->max_stop_acceleration_threshold, planner_data_->delay_response_time); const auto ego_segment_idx = - autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( input_path.points, current_pose, planner_data_->ego_nearest_dist_threshold, planner_data_->ego_nearest_yaw_threshold); const size_t stop_point_segment_idx = - autoware_motion_utils::findNearestSegmentIndex(input_path.points, stop_point_pose.position); - const auto distance_until_stop = autoware_motion_utils::calcSignedArcLength( + autoware::motion_utils::findNearestSegmentIndex(input_path.points, stop_point_pose.position); + const auto distance_until_stop = autoware::motion_utils::calcSignedArcLength( input_path.points, current_pose.position, ego_segment_idx, stop_point_pose.position, stop_point_segment_idx); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.hpp index 8c4cae6ba3993..7faf78cb2d979 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.hpp @@ -117,7 +117,7 @@ class BlindSpotModule : public SceneModuleInterface bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; - std::vector createVirtualWalls() override; + std::vector createVirtualWalls() override; private: // (semi) const variables diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/debug.cpp index 8e8686e984a40..d96256d2753ce 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/debug.cpp @@ -24,14 +24,14 @@ namespace autoware::behavior_velocity_planner { -using autoware_motion_utils::createSlowDownVirtualWallMarker; -using autoware_motion_utils::createStopVirtualWallMarker; -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerScale; -using autoware_universe_utils::createPoint; +using autoware::motion_utils::createSlowDownVirtualWallMarker; +using autoware::motion_utils::createStopVirtualWallMarker; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerScale; +using autoware::universe_utils::createPoint; using visualization_msgs::msg::Marker; namespace @@ -177,19 +177,19 @@ visualization_msgs::msg::MarkerArray createCrosswalkMarkers( } } // namespace -autoware_motion_utils::VirtualWalls CrosswalkModule::createVirtualWalls() +autoware::motion_utils::VirtualWalls CrosswalkModule::createVirtualWalls() { - autoware_motion_utils::VirtualWalls virtual_walls; - autoware_motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWall wall; wall.text = "crosswalk"; wall.ns = std::to_string(module_id_) + "_"; - wall.style = autoware_motion_utils::VirtualWallType::stop; + wall.style = autoware::motion_utils::VirtualWallType::stop; for (const auto & p : debug_data_.stop_poses) { wall.pose = calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); virtual_walls.push_back(wall); } - wall.style = autoware_motion_utils::VirtualWallType::slowdown; + wall.style = autoware::motion_utils::VirtualWallType::slowdown; wall.text += debug_data_.virtual_wall_suffix; for (const auto & p : debug_data_.slow_poses) { wall.pose = calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp index 398368ccd51e7..82cddc2c28f1e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp @@ -27,7 +27,7 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::getOrDeclareParameter; +using autoware::universe_utils::getOrDeclareParameter; using lanelet::autoware::Crosswalk; CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp index 444dd68767919..55aa4daed9f87 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp @@ -118,7 +118,7 @@ void clear_occlusions_behind_objects( object.kinematics.initial_pose_with_covariance.pose.position.y}; if (lanelet::geometry::distance2d(grid_map_position, object_position) < range) { lanelet::BasicPoints2d edge_points; - const auto object_polygon = autoware_universe_utils::toPolygon2d(object); + const auto object_polygon = autoware::universe_utils::toPolygon2d(object); for (const auto & edge_point : object_polygon.outer()) edge_points.push_back(edge_point); std::sort(edge_points.begin(), edge_points.end(), angle_cmp); // points.push_back(interpolate_point({object_position, edge_point}, 10.0 * range)); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 631f08ce8494e..786828d72dcb3 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -41,22 +41,22 @@ namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; -using autoware_motion_utils::calcArcLength; -using autoware_motion_utils::calcDecelDistWithJerkAndAccConstraints; -using autoware_motion_utils::calcLateralOffset; -using autoware_motion_utils::calcLongitudinalOffsetPoint; -using autoware_motion_utils::calcLongitudinalOffsetPose; -using autoware_motion_utils::calcSignedArcLength; -using autoware_motion_utils::calcSignedArcLengthPartialSum; -using autoware_motion_utils::findNearestSegmentIndex; -using autoware_motion_utils::insertTargetPoint; -using autoware_motion_utils::resamplePath; -using autoware_universe_utils::createPoint; -using autoware_universe_utils::getPose; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; -using autoware_universe_utils::pose2transform; -using autoware_universe_utils::toHexString; +using autoware::motion_utils::calcArcLength; +using autoware::motion_utils::calcDecelDistWithJerkAndAccConstraints; +using autoware::motion_utils::calcLateralOffset; +using autoware::motion_utils::calcLongitudinalOffsetPoint; +using autoware::motion_utils::calcLongitudinalOffsetPose; +using autoware::motion_utils::calcSignedArcLength; +using autoware::motion_utils::calcSignedArcLengthPartialSum; +using autoware::motion_utils::findNearestSegmentIndex; +using autoware::motion_utils::insertTargetPoint; +using autoware::motion_utils::resamplePath; +using autoware::universe_utils::createPoint; +using autoware::universe_utils::getPose; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; +using autoware::universe_utils::pose2transform; +using autoware::universe_utils::toHexString; namespace { @@ -85,7 +85,7 @@ void offsetPolygon2d( { for (const auto & polygon_point : polygon.points) { const auto offset_pos = - autoware_universe_utils::calcOffsetPose(origin_point, polygon_point.x, polygon_point.y, 0.0) + autoware::universe_utils::calcOffsetPose(origin_point, polygon_point.x, polygon_point.y, 0.0) .position; offset_polygon.outer().push_back(Point2d(offset_pos.x, offset_pos.y)); } @@ -99,7 +99,7 @@ Polygon2d createMultiStepPolygon( Polygon2d multi_step_polygon{}; for (size_t i = start_idx; i <= end_idx; ++i) { offsetPolygon2d( - autoware_universe_utils::getPose(obj_path_points.at(i)), polygon, multi_step_polygon); + autoware::universe_utils::getPose(obj_path_points.at(i)), polygon, multi_step_polygon); } Polygon2d hull_multi_step_polygon{}; @@ -385,9 +385,10 @@ std::optional CrosswalkModule::checkStopForCrosswalkUsers( const double base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; const double dist_ego2crosswalk = calcSignedArcLength(ego_path.points, ego_pos, path_intersects.front()); - const auto braking_distance_opt = autoware_motion_utils::calcDecelDistWithJerkAndAccConstraints( - ego_vel, 0.0, ego_acc, p.min_acc_for_no_stop_decision, p.max_jerk_for_no_stop_decision, - p.min_jerk_for_no_stop_decision); + const auto braking_distance_opt = + autoware::motion_utils::calcDecelDistWithJerkAndAccConstraints( + ego_vel, 0.0, ego_acc, p.min_acc_for_no_stop_decision, p.max_jerk_for_no_stop_decision, + p.min_jerk_for_no_stop_decision); const double braking_distance = braking_distance_opt ? *braking_distance_opt : 0.0; if ( dist_ego2crosswalk - base_link2front - braking_distance < @@ -414,7 +415,7 @@ std::optional CrosswalkModule::checkStopForCrosswalkUsers( if ( isVehicleType(object.classification) && ego_crosswalk_passage_direction && collision_point.crosswalk_passage_direction) { - const double direction_diff = autoware_universe_utils::normalizeRadian( + const double direction_diff = autoware::universe_utils::normalizeRadian( collision_point.crosswalk_passage_direction.value() - ego_crosswalk_passage_direction.value()); if (std::fabs(direction_diff) < planner_param_.vehicle_object_cross_angle_threshold) { @@ -648,14 +649,14 @@ std::optional CrosswalkModule::findEgoPassageDirectionAlongPath( auto findIntersectPoint = [&](const lanelet::ConstLineString3d line) -> std::optional> { const auto line_start = - autoware_universe_utils::createPoint(line.front().x(), line.front().y(), line.front().z()); + autoware::universe_utils::createPoint(line.front().x(), line.front().y(), line.front().z()); const auto line_end = - autoware_universe_utils::createPoint(line.back().x(), line.back().y(), line.back().z()); + autoware::universe_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 = - autoware_universe_utils::intersect(line_start, line_end, start, end); + autoware::universe_utils::intersect(line_start, line_end, start, end); intersect.has_value()) { return std::make_optional(std::make_pair(i, intersect.value())); } @@ -677,19 +678,19 @@ std::optional CrosswalkModule::findEgoPassageDirectionAlongPath( std::optional CrosswalkModule::findObjectPassageDirectionAlongVehicleLane( const autoware_perception_msgs::msg::PredictedPath & path) const { - using autoware_universe_utils::Segment2d; + using autoware::universe_utils::Segment2d; auto findIntersectPoint = [&](const lanelet::ConstLineString3d line) -> std::optional> { const auto line_start = - autoware_universe_utils::createPoint(line.front().x(), line.front().y(), line.front().z()); + autoware::universe_utils::createPoint(line.front().x(), line.front().y(), line.front().z()); const auto line_end = - autoware_universe_utils::createPoint(line.back().x(), line.back().y(), line.back().z()); + autoware::universe_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 = - autoware_universe_utils::intersect(line_start, line_end, start, end); + autoware::universe_utils::intersect(line_start, line_end, start, end); intersect.has_value()) { return std::make_optional(std::make_pair(i, intersect.value())); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 8d53b0a1fe4fd..491e0dadd4d80 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -49,12 +49,12 @@ namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; +using autoware::universe_utils::Polygon2d; +using autoware::universe_utils::StopWatch; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::TrafficLightElement; -using autoware_universe_utils::Polygon2d; -using autoware_universe_utils::StopWatch; using lanelet::autoware::Crosswalk; using tier4_api_msgs::msg::CrosswalkStatus; using tier4_planning_msgs::msg::PathWithLaneId; @@ -264,7 +264,7 @@ class CrosswalkModule : public SceneModuleInterface const bool is_object_away_from_path = !attention_area.outer().empty() && boost::geometry::distance( - autoware_universe_utils::fromMsg(position).to_2d(), attention_area) > 0.5; + autoware::universe_utils::fromMsg(position).to_2d(), attention_area) > 0.5; // add new object if (objects.count(uuid) == 0) { @@ -327,7 +327,7 @@ class CrosswalkModule : public SceneModuleInterface bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; - autoware_motion_utils::VirtualWalls createVirtualWalls() override; + autoware::motion_utils::VirtualWalls createVirtualWalls() override; private: // main functions diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/util.cpp index c2d9f8273cabe..93b9780445479 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/util.cpp @@ -48,10 +48,10 @@ namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; -using autoware_motion_utils::calcSignedArcLength; -using autoware_universe_utils::createPoint; -using autoware_universe_utils::Line2d; -using autoware_universe_utils::Point2d; +using autoware::motion_utils::calcSignedArcLength; +using autoware::universe_utils::createPoint; +using autoware::universe_utils::Line2d; +using autoware::universe_utils::Point2d; std::vector> getCrosswalksOnPath( const geometry_msgs::msg::Pose & current_pose, @@ -152,7 +152,7 @@ std::vector getPolygonIntersects( std::sort(intersects.begin(), intersects.end(), compare); - // convert autoware_universe_utils::Point2d to geometry::msg::Point + // convert autoware::universe_utils::Point2d to geometry::msg::Point std::vector geometry_points; for (const auto & p : intersects) { geometry_points.push_back(createPoint(p.x(), p.y(), ego_pos.z)); @@ -201,7 +201,7 @@ std::vector getLinestringIntersects( std::sort(intersects.begin(), intersects.end(), compare); - // convert autoware_universe_utils::Point2d to geometry::msg::Point + // convert autoware::universe_utils::Point2d to geometry::msg::Point std::vector geometry_points; for (const auto & p : intersects) { geometry_points.push_back(createPoint(p.x(), p.y(), ego_pos.z)); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/debug.cpp index 4eff964f96c60..87df2a620f717 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/debug.cpp @@ -31,10 +31,10 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerScale; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerScale; using std_msgs::msg::ColorRGBA; namespace @@ -171,21 +171,21 @@ visualization_msgs::msg::MarkerArray DetectionAreaModule::createDebugMarkerArray return wall_marker; } -autoware_motion_utils::VirtualWalls DetectionAreaModule::createVirtualWalls() +autoware::motion_utils::VirtualWalls DetectionAreaModule::createVirtualWalls() { - autoware_motion_utils::VirtualWalls virtual_walls; - autoware_motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWall wall; wall.text = "detection_area"; - wall.style = autoware_motion_utils::VirtualWallType::stop; + wall.style = autoware::motion_utils::VirtualWallType::stop; for (const auto & p : debug_data_.stop_poses) { - wall.pose = autoware_universe_utils::calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); + wall.pose = autoware::universe_utils::calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); virtual_walls.push_back(wall); } - wall.style = autoware_motion_utils::VirtualWallType::deadline; + wall.style = autoware::motion_utils::VirtualWallType::deadline; for (const auto & p : debug_data_.dead_line_poses) { - wall.pose = autoware_universe_utils::calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); + wall.pose = autoware::universe_utils::calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); virtual_walls.push_back(wall); } return virtual_walls; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp index 6bd0d2c3b274a..4887fd7423817 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp @@ -30,7 +30,7 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::getOrDeclareParameter; +using autoware::universe_utils::getOrDeclareParameter; using lanelet::autoware::DetectionArea; DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp index 954bbc988b1c3..7abd88d59f398 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp @@ -33,8 +33,8 @@ namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; -using autoware_motion_utils::calcLongitudinalOffsetPose; -using autoware_motion_utils::calcSignedArcLength; +using autoware::motion_utils::calcLongitudinalOffsetPose; +using autoware::motion_utils::calcSignedArcLength; DetectionAreaModule::DetectionAreaModule( const int64_t module_id, const int64_t lane_id, @@ -288,7 +288,7 @@ std::vector DetectionAreaModule::getObstaclePoints() (circle.first.y() - p.y) * (circle.first.y() - p.y); if (squared_dist <= circle.second) { if (bg::within(Point2d{p.x, p.y}, poly.basicPolygon())) { - obstacle_points.push_back(autoware_universe_utils::createPoint(p.x, p.y, p.z)); + obstacle_points.push_back(autoware::universe_utils::createPoint(p.x, p.y, p.z)); // get all obstacle point becomes high computation cost so skip if any point is found break; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp index 595ab663f8b01..5b15cc92f57b1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp @@ -73,7 +73,7 @@ class DetectionAreaModule : public SceneModuleInterface bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; - autoware_motion_utils::VirtualWalls createVirtualWalls() override; + autoware::motion_utils::VirtualWalls createVirtualWalls() override; private: LineString2d getStopLineGeometry2d() const; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/debug.cpp index 1543966e47276..a53b6e7cd7f92 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/debug.cpp @@ -33,10 +33,10 @@ namespace { -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerOrientation; -using autoware_universe_utils::createMarkerScale; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerOrientation; +using autoware::universe_utils::createMarkerScale; visualization_msgs::msg::MarkerArray createLaneletPolygonsMarkerArray( const std::vector & polygons, const std::string & ns, @@ -226,10 +226,10 @@ constexpr std::tuple light_blue() namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerOrientation; -using autoware_universe_utils::createMarkerScale; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerOrientation; +using autoware::universe_utils::createMarkerScale; visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray() { @@ -424,27 +424,27 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray( return debug_marker_array; } -autoware_motion_utils::VirtualWalls IntersectionModule::createVirtualWalls() +autoware::motion_utils::VirtualWalls IntersectionModule::createVirtualWalls() { - autoware_motion_utils::VirtualWalls virtual_walls; - autoware_motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWall wall; if (debug_data_.collision_stop_wall_pose) { - wall.style = autoware_motion_utils::VirtualWallType::stop; + wall.style = autoware::motion_utils::VirtualWallType::stop; wall.text = "intersection"; wall.ns = "intersection" + std::to_string(module_id_) + "_"; wall.pose = debug_data_.collision_stop_wall_pose.value(); virtual_walls.push_back(wall); } if (debug_data_.occlusion_first_stop_wall_pose) { - wall.style = autoware_motion_utils::VirtualWallType::stop; + wall.style = autoware::motion_utils::VirtualWallType::stop; wall.text = "intersection"; wall.ns = "intersection_occlusion_first_stop" + std::to_string(module_id_) + "_"; wall.pose = debug_data_.occlusion_first_stop_wall_pose.value(); virtual_walls.push_back(wall); } if (debug_data_.occlusion_stop_wall_pose) { - wall.style = autoware_motion_utils::VirtualWallType::stop; + wall.style = autoware::motion_utils::VirtualWallType::stop; wall.text = "intersection_occlusion"; if (debug_data_.static_occlusion_with_traffic_light_timeout) { std::stringstream timeout; @@ -457,7 +457,7 @@ autoware_motion_utils::VirtualWalls IntersectionModule::createVirtualWalls() virtual_walls.push_back(wall); } if (debug_data_.absence_traffic_light_creep_wall) { - wall.style = autoware_motion_utils::VirtualWallType::slowdown; + wall.style = autoware::motion_utils::VirtualWallType::slowdown; wall.text = "intersection_occlusion"; wall.ns = "intersection_occlusion" + std::to_string(module_id_) + "_"; wall.pose = debug_data_.absence_traffic_light_creep_wall.value(); @@ -483,13 +483,13 @@ visualization_msgs::msg::MarkerArray MergeFromPrivateRoadModule::createDebugMark return debug_marker_array; } -autoware_motion_utils::VirtualWalls MergeFromPrivateRoadModule::createVirtualWalls() +autoware::motion_utils::VirtualWalls MergeFromPrivateRoadModule::createVirtualWalls() { - autoware_motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWalls virtual_walls; const auto state = state_machine_.getState(); if (state == StateMachine::State::STOP) { - autoware_motion_utils::VirtualWall wall; - wall.style = autoware_motion_utils::VirtualWallType::stop; + autoware::motion_utils::VirtualWall wall; + wall.style = autoware::motion_utils::VirtualWallType::stop; wall.pose = debug_data_.virtual_wall_pose; wall.text = "merge_from_private_road"; virtual_walls.push_back(wall); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.cpp index 470464a6156b2..648fc611ac6b1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.cpp @@ -26,7 +26,7 @@ namespace autoware::behavior_velocity_planner void IntersectionLanelets::update( const bool is_prioritized, const InterpolatedPathInfo & interpolated_path_info, - const autoware_universe_utils::LinearRing2d & footprint, const double vehicle_length, + const autoware::universe_utils::LinearRing2d & footprint, const double vehicle_length, lanelet::routing::RoutingGraphPtr routing_graph_ptr) { is_prioritized_ = is_prioritized; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.hpp index af11033a454a7..f8110475e2782 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.hpp @@ -41,7 +41,7 @@ struct IntersectionLanelets */ void update( const bool is_prioritized, const InterpolatedPathInfo & interpolated_path_info, - const autoware_universe_utils::LinearRing2d & footprint, const double vehicle_length, + const autoware::universe_utils::LinearRing2d & footprint, const double vehicle_length, lanelet::routing::RoutingGraphPtr routing_graph_ptr); const lanelet::ConstLanelets & attention() const diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp index 5ec002535f1a1..3fa2dc3efb5b1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp @@ -30,7 +30,7 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::getOrDeclareParameter; +using autoware::universe_utils::getOrDeclareParameter; IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) : SceneModuleManagerInterfaceWithRTC( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/object_manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/object_manager.cpp index cc4b7cb0658be..650363c602b90 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/object_manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/object_manager.cpp @@ -38,15 +38,15 @@ std::string to_string(const unique_identifier_msgs::msg::UUID & uuid) return ss.str(); } -autoware_universe_utils::Polygon2d createOneStepPolygon( +autoware::universe_utils::Polygon2d createOneStepPolygon( const geometry_msgs::msg::Pose & prev_pose, const geometry_msgs::msg::Pose & next_pose, const autoware_perception_msgs::msg::Shape & shape) { namespace bg = boost::geometry; - const auto prev_poly = autoware_universe_utils::toPolygon2d(prev_pose, shape); - const auto next_poly = autoware_universe_utils::toPolygon2d(next_pose, shape); + const auto prev_poly = autoware::universe_utils::toPolygon2d(prev_pose, shape); + const auto next_poly = autoware::universe_utils::toPolygon2d(next_pose, shape); - autoware_universe_utils::Polygon2d one_step_poly; + autoware::universe_utils::Polygon2d one_step_poly; for (const auto & point : prev_poly.outer()) { one_step_poly.outer().push_back(point); } @@ -56,7 +56,7 @@ autoware_universe_utils::Polygon2d createOneStepPolygon( bg::correct(one_step_poly); - autoware_universe_utils::Polygon2d convex_one_step_poly; + autoware::universe_utils::Polygon2d convex_one_step_poly; bg::convex_hull(one_step_poly, convex_one_step_poly); return convex_one_step_poly; @@ -164,13 +164,13 @@ bool ObjectInfo::can_stop_before_ego_lane( const auto stopline = stopline_opt.value(); const auto stopline_p1 = stopline.front(); const auto stopline_p2 = stopline.back(); - const autoware_universe_utils::Point2d stopline_mid{ + const autoware::universe_utils::Point2d stopline_mid{ (stopline_p1.x() + stopline_p2.x()) / 2.0, (stopline_p1.y() + stopline_p2.y()) / 2.0}; const auto attention_lane_end = attention_lanelet.centerline().back(); - const autoware_universe_utils::LineString2d attention_lane_later_part( - {autoware_universe_utils::Point2d{stopline_mid.x(), stopline_mid.y()}, - autoware_universe_utils::Point2d{attention_lane_end.x(), attention_lane_end.y()}}); - std::vector ego_collision_points; + const autoware::universe_utils::LineString2d attention_lane_later_part( + {autoware::universe_utils::Point2d{stopline_mid.x(), stopline_mid.y()}, + autoware::universe_utils::Point2d{attention_lane_end.x(), attention_lane_end.y()}}); + std::vector ego_collision_points; bg::intersection( attention_lane_later_part, ego_lane.centerline2d().basicLineString(), ego_collision_points); if (ego_collision_points.empty()) { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp index 3a760d404c80b..274bbe5627b22 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -42,7 +42,7 @@ namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; -using autoware_motion_utils::VelocityFactorInterface; +using autoware::motion_utils::VelocityFactorInterface; IntersectionModule::IntersectionModule( const int64_t module_id, const int64_t lane_id, @@ -56,7 +56,7 @@ IntersectionModule::IntersectionModule( associative_ids_(associative_ids), turn_direction_(turn_direction), has_traffic_light_(has_traffic_light), - occlusion_uuid_(autoware_universe_utils::generateUUID()) + occlusion_uuid_(autoware::universe_utils::generateUUID()) { velocity_factor_.init(PlanningBehavior::INTERSECTION); @@ -342,7 +342,7 @@ DecisionResult IntersectionModule::modifyPathVelocityDetail( // Occluded // utility functions auto fromEgoDist = [&](const size_t index) { - return autoware_motion_utils::calcSignedArcLength(path->points, closest_idx, index); + return autoware::motion_utils::calcSignedArcLength(path->points, closest_idx, index); }; auto stoppedForDuration = [&](const size_t pos, const double duration, StateMachine & state_machine) { @@ -528,12 +528,12 @@ void prepareRTCByDecisionResult( const auto stopline_idx = result.stuck_stopline_idx; *default_safety = false; *default_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, stopline_idx); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, stopline_idx); *occlusion_safety = true; if (result.occlusion_stopline_idx) { const auto occlusion_stopline_idx = result.occlusion_stopline_idx.value(); *occlusion_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); } return; } @@ -549,7 +549,7 @@ void prepareRTCByDecisionResult( const auto stopline_idx = result.stuck_stopline_idx; *default_safety = false; *default_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, stopline_idx); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, stopline_idx); *occlusion_safety = true; return; } @@ -565,11 +565,11 @@ void prepareRTCByDecisionResult( const auto collision_stopline_idx = result.collision_stopline_idx; *default_safety = false; *default_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); const auto occlusion_stopline = result.occlusion_stopline_idx; *occlusion_safety = true; *occlusion_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline); return; } @@ -585,10 +585,10 @@ void prepareRTCByDecisionResult( const auto occlusion_stopline_idx = result.occlusion_stopline_idx; *default_safety = false; *default_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, first_stopline_idx); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, first_stopline_idx); *occlusion_safety = result.is_actually_occlusion_cleared; *occlusion_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); return; } @@ -604,10 +604,10 @@ void prepareRTCByDecisionResult( const auto occlusion_stopline_idx = result.occlusion_stopline_idx; *default_safety = true; *default_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); *occlusion_safety = result.is_actually_occlusion_cleared; *occlusion_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); return; } @@ -622,7 +622,7 @@ void prepareRTCByDecisionResult( const auto collision_stopline_idx = result.closest_idx; *default_safety = !result.collision_detected; *default_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); *occlusion_safety = result.is_actually_occlusion_cleared; *occlusion_distance = 0; return; @@ -640,10 +640,10 @@ void prepareRTCByDecisionResult( const auto occlusion_stopline_idx = result.occlusion_stopline_idx; *default_safety = false; *default_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); *occlusion_safety = result.is_actually_occlusion_cleared; *occlusion_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); return; } @@ -658,10 +658,10 @@ void prepareRTCByDecisionResult( const auto occlusion_stopline_idx = result.occlusion_stopline_idx; *default_safety = true; *default_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); *occlusion_safety = true; *occlusion_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); return; } @@ -677,10 +677,10 @@ void prepareRTCByDecisionResult( const auto occlusion_stopline_idx = result.occlusion_stopline_idx; *default_safety = !result.collision_detected; *default_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); *occlusion_safety = true; *occlusion_distance = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); return; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp index 6aa81162bea25..ea2e1a7ae16d7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -325,7 +325,7 @@ class IntersectionModule : public SceneModuleInterface /** @}*/ visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; - autoware_motion_utils::VirtualWalls createVirtualWalls() override; + autoware::motion_utils::VirtualWalls createVirtualWalls() override; const std::set & getAssociativeIds() const { return associative_ids_; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp index 041715b2dc1a9..739b1122be6a1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp @@ -111,7 +111,7 @@ void IntersectionModule::updateObjectInfoManagerArea() return false; } return bg::within( - autoware_universe_utils::Point2d{obj_pos.x, obj_pos.y}, intersection_area.value()); + autoware::universe_utils::Point2d{obj_pos.x, obj_pos.y}, intersection_area.value()); }(); std::optional attention_lanelet{std::nullopt}; std::optional stopline{std::nullopt}; @@ -311,7 +311,7 @@ void IntersectionModule::updateObjectInfoManagerCollision( for (auto i = begin; i <= end; ++i) { if (bg::intersects( polygon, - autoware_universe_utils::toPolygon2d(object_path.at(i), predicted_object.shape))) { + autoware::universe_utils::toPolygon2d(object_path.at(i), predicted_object.shape))) { collision_detected = true; break; } @@ -490,13 +490,13 @@ std::string IntersectionModule::generateDetectionBlameDiagnosis( "judge line({2} seconds before from now) given the estimated current velocity {3}[m/s]. " "ego was at x = {4}, y = {5} when it passed the 1st pass judge line so it is the fault " "of detection side that failed to detect around {6}[m] range at that time.\n", - past_position.x, // 0 - past_position.y, // 1 - time_diff, // 2 - object_info->observed_velocity(), // 3 - passed_1st_judge_line_pose.position.x, // 4 - passed_1st_judge_line_pose.position.y, // 5 - autoware_universe_utils::calcDistance2d(passed_1st_judge_line_pose, past_position) // 6 + past_position.x, // 0 + past_position.y, // 1 + time_diff, // 2 + object_info->observed_velocity(), // 3 + passed_1st_judge_line_pose.position.x, // 4 + passed_1st_judge_line_pose.position.y, // 5 + autoware::universe_utils::calcDistance2d(passed_1st_judge_line_pose, past_position) // 6 ); } } @@ -528,13 +528,13 @@ std::string IntersectionModule::generateDetectionBlameDiagnosis( "judge line({2} seconds before from now) given the estimated current velocity {3}[m/s]. " "ego was at x = {4}, y = {5} when it passed the 2nd pass judge line so it is the fault " "of detection side that failed to detect around {6}[m] range at that time.\n", - past_position.x, // 0 - past_position.y, // 1 - time_diff, // 2 - object_info->observed_velocity(), // 3 - passed_2nd_judge_line_pose.position.x, // 4 - passed_2nd_judge_line_pose.position.y, // 5 - autoware_universe_utils::calcDistance2d(passed_2nd_judge_line_pose, past_position) // 6 + past_position.x, // 0 + past_position.y, // 1 + time_diff, // 2 + object_info->observed_velocity(), // 3 + passed_2nd_judge_line_pose.position.x, // 4 + passed_2nd_judge_line_pose.position.y, // 5 + autoware::universe_utils::calcDistance2d(passed_2nd_judge_line_pose, past_position) // 6 ); } } @@ -614,10 +614,10 @@ std::string IntersectionModule::generateEgoRiskEvasiveDiagnosis( const auto [begin, end] = unsafe_interval.interval_position; const auto &p1 = unsafe_interval.path.at(begin).position, p2 = unsafe_interval.path.at(end).position; - const auto collision_pos = - autoware_universe_utils::createPoint((p1.x + p2.x) / 2, (p1.y + p2.y) / 2, (p1.z + p2.z) / 2); + const auto collision_pos = autoware::universe_utils::createPoint( + (p1.x + p2.x) / 2, (p1.y + p2.y) / 2, (p1.z + p2.z) / 2); const auto object_dist_to_margin_point = - autoware_universe_utils::calcDistance2d( + autoware::universe_utils::calcDistance2d( object_info->predicted_object().kinematics.initial_pose_with_covariance.pose.position, collision_pos) - planner_param_.collision_detection.avoid_collision_by_acceleration @@ -630,7 +630,7 @@ std::string IntersectionModule::generateEgoRiskEvasiveDiagnosis( object_dist_to_margin_point / std::max(min_vel, object_info->observed_velocity()); // ego side const double ego_dist_to_collision_pos = - autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, collision_pos); + autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, collision_pos); const auto ego_eta_to_collision_pos_it = std::lower_bound( ego_time_distance_array.begin(), ego_time_distance_array.end(), ego_dist_to_collision_pos, [](const auto & a, const double b) { return a.second < b; }); @@ -780,7 +780,7 @@ std::optional IntersectionModule::checkAngleForTargetLanelets( const double ll_angle = lanelet::utils::getLaneletAngle(ll, pose.position); const double pose_angle = tf2::getYaw(pose.orientation); const double angle_diff = - autoware_universe_utils::normalizeRadian(ll_angle - pose_angle, -M_PI); + autoware::universe_utils::normalizeRadian(ll_angle - pose_angle, -M_PI); if (consider_wrong_direction_vehicle) { if (std::fabs(angle_diff) > 1.57 || std::fabs(angle_diff) < detection_area_angle_thr) { return std::make_optional(i); @@ -898,7 +898,7 @@ IntersectionModule::TimeDistanceArray IntersectionModule::calcIntersectionPassin // NOTE: `reference_path` is resampled in `reference_smoothed_path`, so // `last_intersection_stopline_candidate_idx` makes no sense const auto smoothed_path_closest_idx = - autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( smoothed_reference_path.points, path.points.at(closest_idx).point.pose, planner_data_->ego_nearest_dist_threshold, planner_data_->ego_nearest_yaw_threshold); @@ -906,7 +906,7 @@ IntersectionModule::TimeDistanceArray IntersectionModule::calcIntersectionPassin if (upstream_stopline) { const auto upstream_stopline_point = reference_path.points.at(upstream_stopline.value()).point.pose; - return autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( smoothed_reference_path.points, upstream_stopline_point, planner_data_->ego_nearest_dist_threshold, planner_data_->ego_nearest_yaw_threshold); } else { @@ -918,7 +918,7 @@ IntersectionModule::TimeDistanceArray IntersectionModule::calcIntersectionPassin const auto & p1 = smoothed_reference_path.points.at(i); const auto & p2 = smoothed_reference_path.points.at(i + 1); - const double dist = autoware_universe_utils::calcDistance2d(p1, p2); + const double dist = autoware::universe_utils::calcDistance2d(p1, p2); dist_sum += dist; // use average velocity between p1 and p2 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp index f05b49a52b165..24e9a3b4a1793 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp @@ -151,7 +151,7 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion( auto findCommonCvPolygons = [&](const auto & area2d, std::vector> & cv_polygons) -> void { - autoware_universe_utils::Polygon2d area2d_poly; + autoware::universe_utils::Polygon2d area2d_poly; for (const auto & p : area2d) { area2d_poly.outer().emplace_back(p.x(), p.y()); } @@ -240,7 +240,7 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion( std::vector> blocking_polygons; for (const auto & blocking_attention_object_info : blocking_attention_objects) { const Polygon2d obj_poly = - autoware_universe_utils::toPolygon2d(blocking_attention_object_info->predicted_object()); + autoware::universe_utils::toPolygon2d(blocking_attention_object_info->predicted_object()); findCommonCvPolygons(obj_poly.outer(), blocking_polygons); } for (const auto & blocking_polygon : blocking_polygons) { @@ -321,7 +321,8 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion( for (auto i = lane_start_idx + 1; i <= lane_end_idx; i++) { const auto path_linestring_point = path_ip.points.at(i).point.pose.position; if ( - autoware_universe_utils::calcDistance2d(prev_path_linestring_point, path_linestring_point) < + autoware::universe_utils::calcDistance2d( + prev_path_linestring_point, path_linestring_point) < 1.0 /* rough tick for computational cost */) { continue; } @@ -405,9 +406,9 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion( division_index, std::distance(division.begin(), point_it), acc_dist, - autoware_universe_utils::createPoint(point_it->x(), point_it->y(), origin.z), - autoware_universe_utils::createPoint(projection_it->x(), projection_it->y(), origin.z), - autoware_universe_utils::createPoint( + autoware::universe_utils::createPoint(point_it->x(), point_it->y(), origin.z), + autoware::universe_utils::createPoint(projection_it->x(), projection_it->y(), origin.z), + autoware::universe_utils::createPoint( projection_it->x(), projection_it->y(), origin.z) /* initialize with projection point at first*/}; found_min_dist_for_this_division = true; @@ -416,7 +417,7 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion( // division previously in this iteration, and the iterated cells are still OCCLUDED since // then nearest_occlusion_point.visible_end = - autoware_universe_utils::createPoint(point_it->x(), point_it->y(), origin.z); + autoware::universe_utils::createPoint(point_it->x(), point_it->y(), origin.z); } } is_prev_occluded = (pixel == OCCLUDED); @@ -440,7 +441,7 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion( bg::correct(ego_occlusion_triangle); for (const auto & attention_object_info : object_info_manager_.allObjects()) { const auto obj_poly = - autoware_universe_utils::toPolygon2d(attention_object_info->predicted_object()); + autoware::universe_utils::toPolygon2d(attention_object_info->predicted_object()); if (bg::intersects(obj_poly, ego_occlusion_triangle)) { debug_data_.static_occlusion = false; return DynamicallyOccluded{min_dist}; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp index 42d91defe7569..1390104d98175 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp @@ -31,7 +31,7 @@ #include #include -namespace autoware_universe_utils +namespace autoware::universe_utils { template <> @@ -44,7 +44,7 @@ inline geometry_msgs::msg::Point getPoint(const lanelet::ConstPoint3d & p) return point; } -} // namespace autoware_universe_utils +} // namespace autoware::universe_utils namespace { @@ -74,7 +74,7 @@ lanelet::ConstLanelet generatePathLanelet( for (size_t i = start_idx; i <= end_idx; ++i) { const auto & p = path.points.at(i).point.pose; const auto & p_prev = path.points.at(prev_idx).point.pose; - if (i != start_idx && autoware_universe_utils::calcDistance2d(p_prev, p) < interval) { + if (i != start_idx && autoware::universe_utils::calcDistance2d(p_prev, p) < interval) { continue; } prev_idx = i; @@ -198,7 +198,7 @@ Result IntersectionModule::prepare const auto & path_ip = interpolated_path_info.path; const auto & path_ip_intersection_end = interpolated_path_info.lane_id_interval.value().second; - internal_debug_data_.distance = autoware_motion_utils::calcSignedArcLength( + internal_debug_data_.distance = autoware::motion_utils::calcSignedArcLength( path->points, current_pose.position, path_ip.points.at(path_ip_intersection_end).point.pose.position); @@ -275,9 +275,9 @@ Result IntersectionModule::prepare if (is_green_solid_on && !initial_green_light_observed_time_) { const auto assigned_lane_begin_point = assigned_lanelet.centerline().front(); const bool approached_assigned_lane = - autoware_motion_utils::calcSignedArcLength( + autoware::motion_utils::calcSignedArcLength( path->points, closest_idx, - autoware_universe_utils::createPoint( + autoware::universe_utils::createPoint( assigned_lane_begin_point.x(), assigned_lane_begin_point.y(), assigned_lane_begin_point.z())) < planner_param_.collision_detection.yield_on_green_traffic_light @@ -338,7 +338,7 @@ std::optional IntersectionModule::getStopLineIndexFromMap( stop_point_from_map.position.y = 0.5 * (p_start.y() + p_end.y()); stop_point_from_map.position.z = 0.5 * (p_start.z() + p_end.z()); - return autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( path.points, stop_point_from_map, planner_data_->ego_nearest_dist_threshold, planner_data_->ego_nearest_yaw_threshold); } @@ -381,8 +381,8 @@ std::optional IntersectionModule::generateIntersectionSto std::optional first_footprint_attention_centerline_ip_opt = std::nullopt; for (auto i = std::get<0>(lane_interval_ip); i < std::get<1>(lane_interval_ip); ++i) { const auto & base_pose = path_ip.points.at(i).point.pose; - const auto path_footprint = autoware_universe_utils::transformVector( - local_footprint, autoware_universe_utils::pose2transform(base_pose)); + const auto path_footprint = autoware::universe_utils::transformVector( + local_footprint, autoware::universe_utils::pose2transform(base_pose)); if (bg::intersects(path_footprint, first_attention_lane_centerline.basicLineString())) { // NOTE: maybe consideration of braking dist is necessary first_footprint_attention_centerline_ip_opt = i; @@ -413,7 +413,7 @@ std::optional IntersectionModule::generateIntersectionSto // (2) ego front stop line position on interpolated path const geometry_msgs::msg::Pose & current_pose = planner_data_->current_odometry->pose; - const auto closest_idx_ip = autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + const auto closest_idx_ip = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( path_ip.points, current_pose, planner_data_->ego_nearest_dist_threshold, planner_data_->ego_nearest_yaw_threshold); @@ -423,8 +423,8 @@ std::optional IntersectionModule::generateIntersectionSto // NOTE: if footprints[0] is already inside the attention area, invalid { const auto & base_pose0 = path_ip.points.at(default_stopline_ip).point.pose; - const auto path_footprint0 = autoware_universe_utils::transformVector( - local_footprint, autoware_universe_utils::pose2transform(base_pose0)); + const auto path_footprint0 = autoware::universe_utils::transformVector( + local_footprint, autoware::universe_utils::pose2transform(base_pose0)); if (bg::intersects( path_footprint0, lanelet::utils::to2D(first_attention_area).basicPolygon())) { occlusion_peeking_line_valid = false; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp index 124f679e00a5d..14baf6faa581a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp @@ -124,7 +124,7 @@ std::optional IntersectionModule::isStuckStatus( { const auto closest_idx = intersection_stoplines.closest_idx; auto fromEgoDist = [&](const size_t index) { - return autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, index); + return autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, index); }; const auto & intersection_lanelets = intersection_lanelets_.value(); // this is OK @@ -290,7 +290,7 @@ bool IntersectionModule::checkStuckVehicleInIntersection(const PathLanelets & pa } // check if the footprint is in the stuck detect area - const auto obj_footprint = autoware_universe_utils::toPolygon2d(object); + const auto obj_footprint = autoware::universe_utils::toPolygon2d(object); // NOTE: in order not to stop too much const bool is_in_stuck_area = bg::within( to_bg2d(object.kinematics.initial_pose_with_covariance.pose.position), @@ -310,7 +310,7 @@ std::optional IntersectionModule::isYieldStuckStatus( { const auto closest_idx = intersection_stoplines.closest_idx; auto fromEgoDist = [&](const size_t index) { - return autoware_motion_utils::calcSignedArcLength(path.points, closest_idx, index); + return autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, index); }; const auto & intersection_lanelets = intersection_lanelets_.value(); const auto default_stopline_idx = intersection_stoplines.default_stopline.value(); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp index dcbd41eccaec8..ddfd3b7d4cacd 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp @@ -53,7 +53,7 @@ MergeFromPrivateRoadModule::MergeFromPrivateRoadModule( static std::optional getFirstConflictingLanelet( const lanelet::ConstLanelets & conflicting_lanelets, const InterpolatedPathInfo & interpolated_path_info, - const autoware_universe_utils::LinearRing2d & footprint, const double vehicle_length) + const autoware::universe_utils::LinearRing2d & footprint, const double vehicle_length) { const auto & path_ip = interpolated_path_info.path; const auto [lane_start, end] = interpolated_path_info.lane_id_interval.value(); @@ -63,8 +63,8 @@ static std::optional getFirstConflictingLanelet( for (size_t i = start; i <= end; ++i) { const auto & pose = path_ip.points.at(i).point.pose; - const auto path_footprint = autoware_universe_utils::transformVector( - footprint, autoware_universe_utils::pose2transform(pose)); + const auto path_footprint = autoware::universe_utils::transformVector( + footprint, autoware::universe_utils::pose2transform(pose)); for (const auto & conflicting_lanelet : conflicting_lanelets) { const auto polygon_2d = conflicting_lanelet.polygon2d().basicPolygon(); const bool intersects = bg::intersects(polygon_2d, path_footprint); @@ -159,7 +159,7 @@ bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path, StopR velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN); - const double signed_arc_dist_to_stop_point = autoware_motion_utils::calcSignedArcLength( + const double signed_arc_dist_to_stop_point = autoware::motion_utils::calcSignedArcLength( path->points, current_pose.position, path->points.at(stopline_idx).point.pose.position); if ( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp index 4960c7ab9e8d5..a69297adea881 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp @@ -70,7 +70,7 @@ class MergeFromPrivateRoadModule : public SceneModuleInterface bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; - autoware_motion_utils::VirtualWalls createVirtualWalls() override; + autoware::motion_utils::VirtualWalls createVirtualWalls() override; const std::set & getAssociativeIds() const { return associative_ids_; } lanelet::ConstLanelets getAttentionLanelets() const; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp index e56b99486c93c..893ec646dba73 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp @@ -51,7 +51,7 @@ static std::optional getDuplicatedPointIdx( const auto & p = path.points.at(i).point.pose.position; constexpr double min_dist = 0.001; - if (autoware_universe_utils::calcDistance2d(p, point) < min_dist) { + if (autoware::universe_utils::calcDistance2d(p, point) < min_dist) { return i; } } @@ -68,7 +68,7 @@ std::optional insertPointIndex( return duplicate_idx_opt.value(); } - const size_t closest_idx = autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + const size_t closest_idx = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( inout_path->points, in_pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); // vector.insert(i) inserts element on the left side of v[i] // the velocity need to be zero order hold(from prior point) @@ -130,7 +130,7 @@ std::optional> findLaneIdsInterval( std::optional getFirstPointInsidePolygonByFootprint( const lanelet::CompoundPolygon3d & polygon, const InterpolatedPathInfo & interpolated_path_info, - const autoware_universe_utils::LinearRing2d & footprint, const double vehicle_length) + const autoware::universe_utils::LinearRing2d & footprint, const double vehicle_length) { const auto & path_ip = interpolated_path_info.path; const auto [lane_start, lane_end] = interpolated_path_info.lane_id_interval.value(); @@ -140,8 +140,8 @@ std::optional getFirstPointInsidePolygonByFootprint( const auto area_2d = lanelet::utils::to2D(polygon).basicPolygon(); for (auto i = start; i <= lane_end; ++i) { const auto & base_pose = path_ip.points.at(i).point.pose; - const auto path_footprint = autoware_universe_utils::transformVector( - footprint, autoware_universe_utils::pose2transform(base_pose)); + const auto path_footprint = autoware::universe_utils::transformVector( + footprint, autoware::universe_utils::pose2transform(base_pose)); if (bg::intersects(path_footprint, area_2d)) { return std::make_optional(i); } @@ -154,7 +154,7 @@ std::optional & polygons, const InterpolatedPathInfo & interpolated_path_info, - const autoware_universe_utils::LinearRing2d & footprint, const double vehicle_length) + const autoware::universe_utils::LinearRing2d & footprint, const double vehicle_length) { const auto & path_ip = interpolated_path_info.path; const auto [lane_start, lane_end] = interpolated_path_info.lane_id_interval.value(); @@ -164,8 +164,8 @@ getFirstPointInsidePolygonsByFootprint( for (size_t i = start; i <= lane_end; ++i) { const auto & pose = path_ip.points.at(i).point.pose; - const auto path_footprint = autoware_universe_utils::transformVector( - footprint, autoware_universe_utils::pose2transform(pose)); + const auto path_footprint = autoware::universe_utils::transformVector( + footprint, autoware::universe_utils::pose2transform(pose)); for (size_t j = 0; j < polygons.size(); ++j) { const auto area_2d = lanelet::utils::to2D(polygons.at(j)).basicPolygon(); const bool is_in_polygon = bg::intersects(area_2d, path_footprint); @@ -332,7 +332,7 @@ bool isBeforeTargetIndex( return static_cast(target_idx > closest_idx); } -std::optional getIntersectionArea( +std::optional getIntersectionArea( lanelet::ConstLanelet assigned_lane, lanelet::LaneletMapConstPtr lanelet_map_ptr) { const std::string area_id_str = assigned_lane.attributeOr("intersection_area", "else"); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp index 1907395b4baee..f89d6b0ea67ae 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.hpp @@ -87,7 +87,7 @@ bool isBeforeTargetIndex( const tier4_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx, const geometry_msgs::msg::Pose & current_pose, const size_t target_idx); -std::optional getIntersectionArea( +std::optional getIntersectionArea( lanelet::ConstLanelet assigned_lane, lanelet::LaneletMapConstPtr lanelet_map_ptr); /** @@ -125,7 +125,7 @@ mergeLaneletsByTopologicalSort( */ std::optional getFirstPointInsidePolygonByFootprint( const lanelet::CompoundPolygon3d & polygon, const InterpolatedPathInfo & interpolated_path_info, - const autoware_universe_utils::LinearRing2d & footprint, const double vehicle_length); + const autoware::universe_utils::LinearRing2d & footprint, const double vehicle_length); /** * @brief find the index of the first point where vehicle footprint intersects with the given @@ -136,7 +136,7 @@ std::optional & polygons, const InterpolatedPathInfo & interpolated_path_info, - const autoware_universe_utils::LinearRing2d & footprint, const double vehicle_length); + const autoware::universe_utils::LinearRing2d & footprint, const double vehicle_length); std::vector getPolygon3dFromLanelets( const lanelet::ConstLanelets & ll_vec); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/debug.cpp index 804d9109a7c1f..c0c04a0949ce8 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/debug.cpp @@ -23,11 +23,11 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerScale; -using autoware_universe_utils::createPoint; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerScale; +using autoware::universe_utils::createPoint; using visualization_msgs::msg::Marker; namespace @@ -71,18 +71,18 @@ visualization_msgs::msg::MarkerArray createNoDrivableLaneMarkers( } } // namespace -autoware_motion_utils::VirtualWalls NoDrivableLaneModule::createVirtualWalls() +autoware::motion_utils::VirtualWalls NoDrivableLaneModule::createVirtualWalls() { - autoware_motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWalls virtual_walls; const auto now = this->clock_->now(); if ( (state_ == State::APPROACHING) || (state_ == State::INSIDE_NO_DRIVABLE_LANE) || (state_ == State::STOPPED)) { - autoware_motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWall wall; wall.text = "no_drivable_lane"; - wall.style = autoware_motion_utils::VirtualWallType::stop; + wall.style = autoware::motion_utils::VirtualWallType::stop; wall.ns = std::to_string(module_id_) + "_"; wall.pose = debug_data_.stop_pose; virtual_walls.push_back(wall); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.cpp index 99b9dcc366eb4..9c6f2f50925c6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.cpp @@ -21,7 +21,7 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::getOrDeclareParameter; +using autoware::universe_utils::getOrDeclareParameter; NoDrivableLaneModuleManager::NoDrivableLaneModuleManager(rclcpp::Node & node) : SceneModuleManagerInterface(node, getModuleName()) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp index cf663d314a3c1..42d896fec8ab3 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp @@ -23,7 +23,7 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::createPoint; +using autoware::universe_utils::createPoint; NoDrivableLaneModule::NoDrivableLaneModule( const int64_t module_id, const int64_t lane_id, const PlannerParam & planner_param, @@ -58,7 +58,7 @@ bool NoDrivableLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason if (path_no_drivable_lane_polygon_intersection.first_intersection_point) { first_intersection_point = path_no_drivable_lane_polygon_intersection.first_intersection_point.value(); - distance_ego_first_intersection = autoware_motion_utils::calcSignedArcLength( + distance_ego_first_intersection = autoware::motion_utils::calcSignedArcLength( path->points, planner_data_->current_odometry->pose.position, first_intersection_point); distance_ego_first_intersection -= planner_data_->vehicle_info_.max_longitudinal_offset_m; } @@ -135,7 +135,7 @@ void NoDrivableLaneModule::handle_approaching_state(PathWithLaneId * path, StopR const double longitudinal_offset = -1.0 * (planner_param_.stop_margin + planner_data_->vehicle_info_.max_longitudinal_offset_m); - const auto op_target_point = autoware_motion_utils::calcLongitudinalOffsetPoint( + const auto op_target_point = autoware::motion_utils::calcLongitudinalOffsetPoint( path->points, first_intersection_point, longitudinal_offset); geometry_msgs::msg::Point target_point; @@ -145,17 +145,17 @@ void NoDrivableLaneModule::handle_approaching_state(PathWithLaneId * path, StopR } const auto target_segment_idx = - autoware_motion_utils::findNearestSegmentIndex(path->points, target_point); + autoware::motion_utils::findNearestSegmentIndex(path->points, target_point); const auto & op_target_point_idx = - autoware_motion_utils::insertTargetPoint(target_segment_idx, target_point, path->points, 5e-2); + autoware::motion_utils::insertTargetPoint(target_segment_idx, target_point, path->points, 5e-2); size_t target_point_idx; if (op_target_point_idx) { target_point_idx = op_target_point_idx.value(); } geometry_msgs::msg::Point stop_point = - autoware_universe_utils::getPoint(path->points.at(target_point_idx).point); + autoware::universe_utils::getPoint(path->points.at(target_point_idx).point); const auto & op_stop_pose = planning_utils::insertStopPoint(stop_point, target_segment_idx, *path); @@ -170,7 +170,7 @@ void NoDrivableLaneModule::handle_approaching_state(PathWithLaneId * path, StopR velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::APPROACHING); - const auto virtual_wall_pose = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto virtual_wall_pose = autoware::motion_utils::calcLongitudinalOffsetPose( path->points, stop_pose.position, debug_data_.base_link2front); debug_data_.stop_pose = virtual_wall_pose.value(); @@ -178,9 +178,9 @@ void NoDrivableLaneModule::handle_approaching_state(PathWithLaneId * path, StopR const size_t current_seg_idx = findEgoSegmentIndex(path->points); const auto intersection_segment_idx = - autoware_motion_utils::findNearestSegmentIndex(path->points, first_intersection_point); + autoware::motion_utils::findNearestSegmentIndex(path->points, first_intersection_point); const double signed_arc_dist_to_intersection_point = - autoware_motion_utils::calcSignedArcLength( + autoware::motion_utils::calcSignedArcLength( path->points, planner_data_->current_odometry->pose.position, current_seg_idx, first_intersection_point, intersection_segment_idx) - planner_data_->vehicle_info_.max_longitudinal_offset_m; @@ -216,14 +216,14 @@ void NoDrivableLaneModule::handle_inside_no_drivable_lane_state( // Get stop point and stop factor { tier4_planning_msgs::msg::StopFactor stop_factor; - const auto & stop_pose = autoware_universe_utils::getPose(path->points.at(0)); + const auto & stop_pose = autoware::universe_utils::getPose(path->points.at(0)); stop_factor.stop_pose = stop_pose; stop_factor.stop_factor_points.push_back(current_point); planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::APPROACHING); - const auto & virtual_wall_pose = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto & virtual_wall_pose = autoware::motion_utils::calcLongitudinalOffsetPose( path->points, stop_pose.position, debug_data_.base_link2front); debug_data_.stop_pose = virtual_wall_pose.value(); @@ -240,7 +240,7 @@ void NoDrivableLaneModule::handle_inside_no_drivable_lane_state( void NoDrivableLaneModule::handle_stopped_state(PathWithLaneId * path, StopReason * stop_reason) { - const auto & stopped_pose = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto & stopped_pose = autoware::motion_utils::calcLongitudinalOffsetPose( path->points, planner_data_->current_odometry->pose.position, 0.0); if (!stopped_pose) { @@ -265,7 +265,7 @@ void NoDrivableLaneModule::handle_stopped_state(PathWithLaneId * path, StopReaso velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::STOPPED); - const auto virtual_wall_pose = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto virtual_wall_pose = autoware::motion_utils::calcLongitudinalOffsetPose( path->points, stop_pose.position, debug_data_.base_link2front); debug_data_.stop_pose = virtual_wall_pose.value(); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp index d8425bdd2a292..1e8e93834f89e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp @@ -60,7 +60,7 @@ class NoDrivableLaneModule : public SceneModuleInterface bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; - autoware_motion_utils::VirtualWalls createVirtualWalls() override; + autoware::motion_utils::VirtualWalls createVirtualWalls() override; private: const int64_t lane_id_; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/util.cpp index 7aede9a509c79..1339fee207416 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/util.cpp @@ -32,8 +32,8 @@ using Point = bg::model::d2::point_xy; using Polygon = bg::model::polygon; using Line = bg::model::linestring; -using autoware_motion_utils::calcSignedArcLength; -using autoware_universe_utils::createPoint; +using autoware::motion_utils::calcSignedArcLength; +using autoware::universe_utils::createPoint; PathWithNoDrivableLanePolygonIntersection getPathIntersectionWithNoDrivableLanePolygon( const PathWithLaneId & ego_path, const lanelet::BasicPolygon2d & polygon, diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/debug.cpp index b587036d9027a..09f1908b107d5 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/debug.cpp @@ -34,10 +34,10 @@ namespace { const double marker_lifetime = 0.2; using DebugData = NoStoppingAreaModule::DebugData; -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerScale; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerScale; lanelet::BasicPoint3d getCentroidPoint(const lanelet::BasicPolygon3d & poly) { @@ -162,15 +162,15 @@ visualization_msgs::msg::MarkerArray NoStoppingAreaModule::createDebugMarkerArra return debug_marker_array; } -autoware_motion_utils::VirtualWalls NoStoppingAreaModule::createVirtualWalls() +autoware::motion_utils::VirtualWalls NoStoppingAreaModule::createVirtualWalls() { - autoware_motion_utils::VirtualWalls virtual_walls; - autoware_motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWall wall; wall.ns = std::to_string(module_id_) + "_"; wall.text = "no_stopping_area"; - wall.style = autoware_motion_utils::VirtualWallType::stop; + wall.style = autoware::motion_utils::VirtualWallType::stop; for (const auto & p : debug_data_.stop_poses) { - wall.pose = autoware_universe_utils::calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); + wall.pose = autoware::universe_utils::calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); virtual_walls.push_back(wall); } return virtual_walls; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.cpp index 773ec5f44411e..4ee711297b494 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.cpp @@ -30,7 +30,7 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::getOrDeclareParameter; +using autoware::universe_utils::getOrDeclareParameter; using lanelet::autoware::NoStoppingArea; NoStoppingAreaModuleManager::NoStoppingAreaModuleManager(rclcpp::Node & node) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp index 18169dfa1ba70..d007416dccb47 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp @@ -87,7 +87,7 @@ boost::optional NoStoppingAreaModule::getStopLineGeometry2d( std::vector collision_points; bg::intersection(area_poly, line, collision_points); if (!collision_points.empty()) { - const double yaw = autoware_universe_utils::calcAzimuthAngle(p0, p1); + const double yaw = autoware::universe_utils::calcAzimuthAngle(p0, p1); const double w = planner_data_->vehicle_info_.vehicle_width_m; const double l = stop_line_margin; stop_line.emplace_back( @@ -132,7 +132,7 @@ bool NoStoppingAreaModule::modifyPathVelocity(PathWithLaneId * path, StopReason return true; } const auto & stop_pose = stop_point->second; - setDistance(autoware_motion_utils::calcSignedArcLength( + setDistance(autoware::motion_utils::calcSignedArcLength( original_path.points, current_pose->pose.position, stop_pose.position)); if (planning_utils::isOverLine( original_path, current_pose->pose, stop_pose, planner_param_.dead_line_margin)) { @@ -229,7 +229,7 @@ bool NoStoppingAreaModule::checkStuckVehiclesInNoStoppingArea( continue; // not stop vehicle } // check if the footprint is in the stuck detect area - const Polygon2d obj_footprint = autoware_universe_utils::toPolygon2d(object); + const Polygon2d obj_footprint = autoware::universe_utils::toPolygon2d(object); const bool is_in_stuck_area = !bg::disjoint(obj_footprint, poly); if (is_in_stuck_area) { RCLCPP_DEBUG(logger_, "stuck vehicle found."); @@ -266,7 +266,7 @@ bool NoStoppingAreaModule::checkStopLinesInNoStoppingArea( } // judge if stop point p0 is near goal, by its distance to the path end. const double dist_to_path_end = - autoware_motion_utils::calcSignedArcLength(path.points, i, path.points.size() - 1); + autoware::motion_utils::calcSignedArcLength(path.points, i, path.points.size() - 1); if (dist_to_path_end < close_to_goal_distance) { // exit with false, cause position is near goal. return false; @@ -302,10 +302,10 @@ Polygon2d NoStoppingAreaModule::generateEgoNoStoppingAreaLanePolygon( auto & pp = interpolated_path.points; /* calc closest index */ const auto closest_idx_opt = - autoware_motion_utils::findNearestIndex(interpolated_path.points, ego_pose, 3.0, M_PI_4); + autoware::motion_utils::findNearestIndex(interpolated_path.points, ego_pose, 3.0, M_PI_4); if (!closest_idx_opt) { RCLCPP_WARN_SKIPFIRST_THROTTLE( - logger_, *clock_, 1000 /* ms */, "autoware_motion_utils::findNearestIndex fail"); + logger_, *clock_, 1000 /* ms */, "autoware::motion_utils::findNearestIndex fail"); return ego_area; } const size_t closest_idx = closest_idx_opt.value(); @@ -318,7 +318,7 @@ Polygon2d NoStoppingAreaModule::generateEgoNoStoppingAreaLanePolygon( } const auto no_stopping_area = no_stopping_area_reg_elem_.noStoppingAreas().front(); for (size_t i = closest_idx + num_ignore_nearest; i < pp.size() - 1; ++i) { - dist_from_start_sum += autoware_universe_utils::calcDistance2d(pp.at(i), pp.at(i - 1)); + dist_from_start_sum += autoware::universe_utils::calcDistance2d(pp.at(i), pp.at(i - 1)); const auto & p = pp.at(i).point.pose.position; if (bg::within(Point2d{p.x, p.y}, lanelet::utils::to2D(no_stopping_area).basicPolygon())) { is_in_area = true; @@ -339,10 +339,10 @@ Polygon2d NoStoppingAreaModule::generateEgoNoStoppingAreaLanePolygon( // decide end idx with extract distance size_t ego_area_end_idx = ego_area_start_idx; for (size_t i = ego_area_start_idx; i < pp.size() - 1; ++i) { - dist_from_start_sum += autoware_universe_utils::calcDistance2d(pp.at(i), pp.at(i - 1)); + dist_from_start_sum += autoware::universe_utils::calcDistance2d(pp.at(i), pp.at(i - 1)); const auto & p = pp.at(i).point.pose.position; if (!bg::within(Point2d{p.x, p.y}, lanelet::utils::to2D(no_stopping_area).basicPolygon())) { - dist_from_area_sum += autoware_universe_utils::calcDistance2d(pp.at(i), pp.at(i - 1)); + dist_from_area_sum += autoware::universe_utils::calcDistance2d(pp.at(i), pp.at(i - 1)); } if (dist_from_start_sum > extra_dist || dist_from_area_sum > margin) { break; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp index eead30b11f531..ae297d96c5afd 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp @@ -86,7 +86,7 @@ class NoStoppingAreaModule : public SceneModuleInterface bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; - autoware_motion_utils::VirtualWalls createVirtualWalls() override; + autoware::motion_utils::VirtualWalls createVirtualWalls() override; private: const int64_t lane_id_; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/debug.cpp index dff8ce1da9098..a32cb4018cda9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/debug.cpp @@ -30,12 +30,12 @@ namespace { using builtin_interfaces::msg::Time; using BasicPolygons = std::vector; -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerOrientation; -using autoware_universe_utils::createMarkerPosition; -using autoware_universe_utils::createMarkerScale; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerOrientation; +using autoware::universe_utils::createMarkerPosition; +using autoware::universe_utils::createMarkerScale; using occlusion_spot_utils::PossibleCollisionInfo; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; @@ -214,12 +214,12 @@ MarkerArray OcclusionSpotModule::createDebugMarkerArray() return debug_marker_array; } -autoware_motion_utils::VirtualWalls OcclusionSpotModule::createVirtualWalls() +autoware::motion_utils::VirtualWalls OcclusionSpotModule::createVirtualWalls() { - autoware_motion_utils::VirtualWalls virtual_walls; - autoware_motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWall wall; wall.text = "occlusion_spot"; - wall.style = autoware_motion_utils::VirtualWallType::slowdown; + wall.style = autoware::motion_utils::VirtualWallType::slowdown; for (size_t id = 0; id < debug_data_.debug_poses.size(); id++) { wall.pose = calcOffsetPose(debug_data_.debug_poses.at(id), debug_data_.baselink_to_front, 0.0, 0.0); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.cpp index 03124a0b81b43..783970c701262 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.cpp @@ -95,7 +95,7 @@ std::optional generateOcclusionPolygon( const Polygon2d & occupancy_poly, const Point2d & origin, const Point2d & min_theta_pos, const Point2d & max_theta_pos, const double ray_max_length = 100.0) { - using autoware_universe_utils::normalizeRadian; + using autoware::universe_utils::normalizeRadian; const double origin_x = origin.x(); const double origin_y = origin.y(); const double min_theta = @@ -134,7 +134,7 @@ std::optional generateOcclusionPolygon( Polygon2d generateOccupancyPolygon(const nav_msgs::msg::MapMetaData & info, const double r = 100) { - using autoware_universe_utils::calcOffsetPose; + using autoware::universe_utils::calcOffsetPose; // generate occupancy polygon from grid origin Polygon2d poly; // create counter clockwise poly poly.outer().emplace_back(to_bg2d(calcOffsetPose(info.origin, 0, 0, 0).position)); @@ -155,7 +155,7 @@ std::pair calcEdgePoint(const Polygon2d & foot_print, const Poin for (size_t i = 0; i < foot_print.outer().size(); i++) { const auto & f = foot_print.outer().at(i); PolarCoordinates polar = toPolarCoordinates(origin, f); - const double theta_norm = autoware_universe_utils::normalizeRadian(polar.theta, 0.0); + const double theta_norm = autoware::universe_utils::normalizeRadian(polar.theta, 0.0); if (theta_norm < min_theta) { min_theta = theta_norm; min_idx = i; @@ -183,7 +183,7 @@ std::optional generateOccupiedPolygon( Point transformFromMap2Grid(const TransformStamped & geom_tf_map2grid, const Point2d & p) { - Point geom_pt = autoware_universe_utils::createPoint(p.x(), p.y(), 0); + Point geom_pt = autoware::universe_utils::createPoint(p.x(), p.y(), 0); Point transformed_geom_pt; // from map coordinate to occupancy grid coordinate tf2::doTransform(geom_pt, transformed_geom_pt, geom_tf_map2grid); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.hpp index 60ef9c629d830..d716f17751dc0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.hpp @@ -55,11 +55,11 @@ using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; namespace grid_utils { +using autoware::universe_utils::LineString2d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; -using autoware_universe_utils::LineString2d; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; using geometry_msgs::msg::Point; using geometry_msgs::msg::TransformStamped; using nav_msgs::msg::MapMetaData; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp index f21d2bf6a743b..5e686cf648c50 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp @@ -27,7 +27,7 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::getOrDeclareParameter; +using autoware::universe_utils::getOrDeclareParameter; using occlusion_spot_utils::DETECTION_METHOD; using occlusion_spot_utils::PASS_JUDGE; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp index cade9f0614dc0..911842ddd57ed 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp @@ -41,7 +41,7 @@ namespace occlusion_spot_utils Polygon2d toFootprintPolygon(const PredictedObject & object, const double scale = 1.0) { const Pose & obj_pose = object.kinematics.initial_pose_with_covariance.pose; - Polygon2d obj_footprint = autoware_universe_utils::toPolygon2d(object); + Polygon2d obj_footprint = autoware::universe_utils::toPolygon2d(object); // upscale foot print for noise obj_footprint = upScalePolygon(obj_pose.position, obj_footprint, scale); return obj_footprint; @@ -126,7 +126,7 @@ void calcSlowDownPointsForPossibleCollision( const double dist_to_col = possible_collisions.at(collision_index).arc_lane_dist_at_collision.length; dist_along_next_path_point += - autoware_universe_utils::calcDistance2d(p_prev.pose.position, p_next.pose.position); + autoware::universe_utils::calcDistance2d(p_prev.pose.position, p_next.pose.position); // process if nearest possible collision is between current and next path point if (dist_along_path_point < dist_to_col) { for (; collision_index < possible_collisions.size(); collision_index++) { @@ -173,7 +173,8 @@ void clipPathByLength( double length_sum = 0; clipped.points.emplace_back(path.points.front()); for (int i = 1; i < static_cast(path.points.size()); i++) { - length_sum += autoware_universe_utils::calcDistance2d(path.points.at(i - 1), path.points.at(i)); + length_sum += + autoware::universe_utils::calcDistance2d(path.points.at(i - 1), path.points.at(i)); if (length_sum > max_length) return; clipped.points.emplace_back(path.points.at(i)); } @@ -248,7 +249,7 @@ void categorizeVehicles( lanelet::ArcCoordinates getOcclusionPoint( const PredictedObject & obj, const lanelet::ConstLineString2d & ll_string) { - const auto poly = autoware_universe_utils::toPolygon2d(obj); + const auto poly = autoware::universe_utils::toPolygon2d(obj); std::deque arcs; for (const auto & p : poly.outer()) { lanelet::BasicPoint2d obj_p = {p.x(), p.y()}; @@ -374,7 +375,7 @@ std::vector filterVehiclesByDetectionArea( // stuck points by predicted objects for (const auto & object : objs) { // check if the footprint is in the stuck detect area - const auto obj_footprint = autoware_universe_utils::toPolygon2d(object); + const auto obj_footprint = autoware::universe_utils::toPolygon2d(object); for (const auto & p : polys) { if (!bg::disjoint(obj_footprint, p)) { filtered_obj.emplace_back(object); @@ -402,7 +403,7 @@ bool generatePossibleCollisionsFromGridMap( param.detection_area.min_occlusion_spot_size); if (param.is_show_occlusion) { for (const auto & op : occlusion_spot_positions) { - Point p = autoware_universe_utils::createPoint( + Point p = autoware::universe_utils::createPoint( op[0], op[1], path.points.at(0).point.pose.position.z); debug_data.occlusion_points.emplace_back(p); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp index 27e3452832b59..b55869be8c902 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp @@ -110,12 +110,12 @@ bool OcclusionSpotModule::modifyPathVelocity( //! never change this interpolation interval(will affect module accuracy) splineInterpolate(clipped_path, 1.0, path_interpolated, logger_); const geometry_msgs::msg::Point start_point = path_interpolated.points.at(0).point.pose.position; - const auto ego_segment_idx = autoware_motion_utils::findNearestSegmentIndex( + const auto ego_segment_idx = autoware::motion_utils::findNearestSegmentIndex( path_interpolated.points, ego_pose, param_.dist_thr, param_.angle_thr); if (!ego_segment_idx) return true; const size_t start_point_segment_idx = - autoware_motion_utils::findNearestSegmentIndex(path_interpolated.points, start_point); - const auto offset = autoware_motion_utils::calcSignedArcLength( + autoware::motion_utils::findNearestSegmentIndex(path_interpolated.points, start_point); + const auto offset = autoware::motion_utils::calcSignedArcLength( path_interpolated.points, ego_pose.position, *ego_segment_idx, start_point, start_point_segment_idx); const double offset_from_start_to_ego = -offset; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp index 4df653c26fcef..b83051fb6b6ec 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp @@ -56,12 +56,12 @@ class OcclusionSpotModule : public SceneModuleInterface bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; - autoware_motion_utils::VirtualWalls createVirtualWalls() override; + autoware::motion_utils::VirtualWalls createVirtualWalls() override; private: // Parameter PlannerParam param_; - autoware_universe_utils::StopWatch stop_watch_; + autoware::universe_utils::StopWatch stop_watch_; std::vector partition_lanelets_; protected: diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp index b0f4a48b9dbdc..6bc9423b6dc96 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp @@ -85,7 +85,7 @@ TEST(compareTime, polygon_vs_line_iterator) } } const grid_map::Matrix & grid_data = grid["layer"]; - autoware_universe_utils::StopWatch stop_watch; + autoware::universe_utils::StopWatch stop_watch; stop_watch.tic("processing_time"); size_t count = 0; [[maybe_unused]] double time = 0; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp index 4ca0736ce8d7c..cbacbe625238e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp @@ -130,9 +130,9 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio planner_manager_.launchScenePlugin(*this, name); } - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } void BehaviorVelocityPlannerNode::onLoadPlugin( @@ -194,7 +194,7 @@ void BehaviorVelocityPlannerNode::processNoGroundPointCloud( Eigen::Affine3f affine = tf2::transformToEigen(transform.transform).cast(); pcl::PointCloud::Ptr pc_transformed(new pcl::PointCloud); if (!pc.empty()) { - autoware_universe_utils::transformPointCloud(pc, *pc_transformed, affine); + autoware::universe_utils::transformPointCloud(pc, *pc_transformed, affine); } planner_data_.no_ground_pointcloud = pc_transformed; @@ -379,7 +379,7 @@ autoware_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath( autoware_planning_msgs::msg::Path output_path_msg; // TODO(someone): support backward path - const auto is_driving_forward = autoware_motion_utils::isDrivingForward(input_path_msg->points); + const auto is_driving_forward = autoware::motion_utils::isDrivingForward(input_path_msg->points); is_driving_forward_ = is_driving_forward ? is_driving_forward.value() : is_driving_forward_; if (!is_driving_forward_) { RCLCPP_WARN_THROTTLE( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.hpp index 1db2766fdf686..fab047029e29c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.hpp @@ -69,30 +69,30 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_external_velocity_limit_; // polling subscribers - autoware_universe_utils::InterProcessPollingSubscriber< + autoware::universe_utils::InterProcessPollingSubscriber< autoware_perception_msgs::msg::PredictedObjects> sub_predicted_objects_{this, "~/input/dynamic_objects"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_no_ground_pointcloud_{ - this, "~/input/no_ground_pointcloud", autoware_universe_utils::SingleDepthSensorQoS()}; + this, "~/input/no_ground_pointcloud", autoware::universe_utils::SingleDepthSensorQoS()}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_vehicle_odometry_{this, "~/input/vehicle_odometry"}; - autoware_universe_utils::InterProcessPollingSubscriber< + autoware::universe_utils::InterProcessPollingSubscriber< geometry_msgs::msg::AccelWithCovarianceStamped> sub_acceleration_{this, "~/input/accel"}; - autoware_universe_utils::InterProcessPollingSubscriber< + autoware::universe_utils::InterProcessPollingSubscriber< autoware_perception_msgs::msg::TrafficLightGroupArray> sub_traffic_signals_{this, "~/input/traffic_signals"}; - autoware_universe_utils::InterProcessPollingSubscriber< + autoware::universe_utils::InterProcessPollingSubscriber< tier4_v2x_msgs::msg::VirtualTrafficLightStateArray> sub_virtual_traffic_light_states_{this, "~/input/virtual_traffic_light_states"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_occupancy_grid_{this, "~/input/occupancy_grid"}; void onTrigger(const tier4_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg); @@ -143,9 +143,9 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node const tier4_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg, const PlannerData & planner_data); - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; static constexpr int logger_throttle_interval = 3000; }; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp index e6300a2889a01..b09f00ce367dc 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp @@ -48,13 +48,13 @@ namespace autoware::behavior_velocity_planner { +using autoware::motion_utils::PlanningBehavior; +using autoware::motion_utils::VelocityFactor; using autoware::objects_of_interest_marker_interface::ColorName; using autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; using autoware::rtc_interface::RTCInterface; -using autoware_motion_utils::PlanningBehavior; -using autoware_motion_utils::VelocityFactor; -using autoware_universe_utils::DebugPublisher; -using autoware_universe_utils::getOrDeclareParameter; +using autoware::universe_utils::DebugPublisher; +using autoware::universe_utils::getOrDeclareParameter; using builtin_interfaces::msg::Time; using tier4_debug_msgs::msg::Float64Stamped; using tier4_planning_msgs::msg::PathWithLaneId; @@ -87,7 +87,7 @@ class SceneModuleInterface virtual bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) = 0; virtual visualization_msgs::msg::MarkerArray createDebugMarkerArray() = 0; - virtual std::vector createVirtualWalls() = 0; + virtual std::vector createVirtualWalls() = 0; int64_t getModuleId() const { return module_id_; } void setPlannerData(const std::shared_ptr & planner_data) @@ -130,7 +130,7 @@ class SceneModuleInterface std::shared_ptr planner_data_; std::optional infrastructure_command_; std::optional first_stop_path_point_index_; - autoware_motion_utils::VelocityFactorInterface velocity_factor_; + autoware::motion_utils::VelocityFactorInterface velocity_factor_; std::vector objects_of_interest_; void setSafe(const bool safe) @@ -197,7 +197,7 @@ class SceneModuleManagerInterface std::set registered_module_id_set_; std::shared_ptr planner_data_; - autoware_motion_utils::VirtualWallMarkerCreator virtual_wall_marker_creator_; + autoware::motion_utils::VirtualWallMarkerCreator virtual_wall_marker_creator_; std::optional first_stop_path_point_index_; rclcpp::Node & node_; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/arc_lane_util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/arc_lane_util.hpp index 09a9125ef0eac..77b7d25f9f46e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/arc_lane_util.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/arc_lane_util.hpp @@ -31,7 +31,7 @@ namespace autoware::behavior_velocity_planner { namespace { -geometry_msgs::msg::Point convertToGeomPoint(const autoware_universe_utils::Point2d & p) +geometry_msgs::msg::Point convertToGeomPoint(const autoware::universe_utils::Point2d & p) { geometry_msgs::msg::Point geom_p; geom_p.x = p.x(); @@ -46,7 +46,7 @@ namespace arc_lane_utils { using PathIndexWithPose = std::pair; // front index, pose using PathIndexWithPoint2d = - std::pair; // front index, point2d + std::pair; // front index, point2d using PathIndexWithPoint = std::pair; // front index, point2d using PathIndexWithOffset = std::pair; // front index, offset @@ -76,9 +76,9 @@ std::optional findCollisionSegment( } const auto & p1 = - autoware_universe_utils::getPoint(path.points.at(i)); // Point before collision point + autoware::universe_utils::getPoint(path.points.at(i)); // Point before collision point const auto & p2 = - autoware_universe_utils::getPoint(path.points.at(i + 1)); // Point after collision point + autoware::universe_utils::getPoint(path.points.at(i + 1)); // Point after collision point const auto collision_point = checkCollision(p1, p2, stop_line_p1, stop_line_p2); @@ -106,7 +106,8 @@ std::optional findForwardOffsetSegment( { double sum_length = 0.0; for (size_t i = base_idx; i < path.points.size() - 1; ++i) { - sum_length += autoware_universe_utils::calcDistance2d(path.points.at(i), path.points.at(i + 1)); + sum_length += + autoware::universe_utils::calcDistance2d(path.points.at(i), path.points.at(i + 1)); // If it's over offset point, return front index and remain offset length if (sum_length >= offset_length) { @@ -125,7 +126,8 @@ std::optional findBackwardOffsetSegment( double sum_length = 0.0; const auto start = static_cast(base_idx) - 1; for (std::int32_t i = start; i >= 0; --i) { - sum_length += autoware_universe_utils::calcDistance2d(path.points.at(i), path.points.at(i + 1)); + sum_length += + autoware::universe_utils::calcDistance2d(path.points.at(i), path.points.at(i + 1)); // If it's over offset point, return front index and remain offset length if (sum_length >= offset_length) { @@ -149,13 +151,13 @@ std::optional findOffsetSegment( return findForwardOffsetSegment( path, collision_idx, offset_length + - autoware_universe_utils::calcDistance2d(path.points.at(collision_idx), collision_point)); + autoware::universe_utils::calcDistance2d(path.points.at(collision_idx), collision_point)); } return findBackwardOffsetSegment( path, collision_idx + 1, -offset_length + - autoware_universe_utils::calcDistance2d(path.points.at(collision_idx + 1), collision_point)); + autoware::universe_utils::calcDistance2d(path.points.at(collision_idx + 1), collision_point)); } std::optional findOffsetSegment( @@ -185,8 +187,8 @@ geometry_msgs::msg::Pose calcTargetPose(const T & path, const PathIndexWithOffse target_pose.position.x = target_point_2d.x(); target_pose.position.y = target_point_2d.y(); target_pose.position.z = interpolated_z; - const double yaw = autoware_universe_utils::calcAzimuthAngle(p_front, p_back); - target_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(yaw); + const double yaw = autoware::universe_utils::calcAzimuthAngle(p_front, p_back); + target_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); return target_pose; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp index 608d136a418bb..696d4a41b7673 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp @@ -50,9 +50,9 @@ namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; -using Point2d = autoware_universe_utils::Point2d; -using LineString2d = autoware_universe_utils::LineString2d; -using Polygon2d = autoware_universe_utils::Polygon2d; +using Point2d = autoware::universe_utils::Point2d; +using LineString2d = autoware::universe_utils::LineString2d; +using Polygon2d = autoware::universe_utils::Polygon2d; template Point2d to_bg2d(const T & p) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp index 9dd3792e2799a..591a30928fd09 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp @@ -57,9 +57,9 @@ struct TrafficSignalStamped }; using Pose = geometry_msgs::msg::Pose; -using Point2d = autoware_universe_utils::Point2d; -using LineString2d = autoware_universe_utils::LineString2d; -using Polygon2d = autoware_universe_utils::Polygon2d; +using Point2d = autoware::universe_utils::Point2d; +using LineString2d = autoware::universe_utils::LineString2d; +using Polygon2d = autoware::universe_utils::Polygon2d; using BasicPolygons2d = std::vector; using Polygons2d = std::vector; using autoware_perception_msgs::msg::PredictedObjects; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp index edc67d4bbdc94..a0f30cd3e33cb 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -24,7 +24,7 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::StopWatch; +using autoware::universe_utils::StopWatch; SceneModuleInterface::SceneModuleInterface( const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock) @@ -41,7 +41,7 @@ size_t SceneModuleInterface::findEgoSegmentIndex( const std::vector & points) const { const auto & p = planner_data_; - return autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( points, p->current_odometry->pose, p->ego_nearest_dist_threshold); } @@ -77,7 +77,7 @@ size_t SceneModuleManagerInterface::findEgoSegmentIndex( const std::vector & points) const { const auto & p = planner_data_; - return autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( points, p->current_odometry->pose, p->ego_nearest_dist_threshold, p->ego_nearest_yaw_threshold); } @@ -236,7 +236,7 @@ UUID SceneModuleManagerInterfaceWithRTC::getUUID(const int64_t & module_id) cons void SceneModuleManagerInterfaceWithRTC::generateUUID(const int64_t & module_id) { - map_uuid_.insert({module_id, autoware_universe_utils::generateUUID()}); + map_uuid_.insert({module_id, autoware::universe_utils::generateUUID()}); } void SceneModuleManagerInterfaceWithRTC::removeUUID(const int64_t & module_id) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/debug.cpp index 9061508e6d77d..dfd201bac707c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/debug.cpp @@ -19,11 +19,11 @@ namespace autoware::behavior_velocity_planner { namespace debug { -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerOrientation; -using autoware_universe_utils::createMarkerScale; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerOrientation; +using autoware::universe_utils::createMarkerScale; visualization_msgs::msg::MarkerArray createPolygonMarkerArray( const geometry_msgs::msg::Polygon & polygon, const std::string & ns, const int64_t module_id, diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/path_utilization.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/path_utilization.cpp index 2581edd2c8278..62050d24e273d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/path_utilization.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/path_utilization.cpp @@ -34,7 +34,7 @@ bool splineInterpolate( return false; } - output = autoware_motion_utils::resamplePath(input, interval, false, true, true, false); + output = autoware::motion_utils::resamplePath(input, interval, false, true, true, false); return true; } @@ -68,7 +68,7 @@ autoware_planning_msgs::msg::Path interpolatePath( return path; } - double path_len = std::min(length, autoware_motion_utils::calcArcLength(path.points)); + double path_len = std::min(length, autoware::motion_utils::calcArcLength(path.points)); { double s = 0.0; for (size_t idx = 0; idx < path.points.size(); ++idx) { @@ -79,7 +79,7 @@ autoware_planning_msgs::msg::Path interpolatePath( v.push_back(path_point.longitudinal_velocity_mps); if (idx != 0) { const auto path_point_prev = path.points.at(idx - 1); - s += autoware_universe_utils::calcDistance2d(path_point_prev.pose, path_point.pose); + s += autoware::universe_utils::calcDistance2d(path_point_prev.pose, path_point.pose); } if (s > path_len) { break; @@ -122,7 +122,7 @@ autoware_planning_msgs::msg::Path interpolatePath( return path; } - return autoware_motion_utils::resamplePath(path, s_out); + return autoware::motion_utils::resamplePath(path, s_out); } autoware_planning_msgs::msg::Path filterLitterPathPoint( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp index 00b34fbcac61f..5900bd3531266 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp @@ -55,7 +55,7 @@ bool smoothPath( const auto & smoother = planner_data->velocity_smoother_; auto trajectory = - autoware_motion_utils::convertToTrajectoryPoints( + autoware::motion_utils::convertToTrajectoryPoints( in_path); const auto traj_lateral_acc_filtered = smoother->applyLateralAccelerationFilter(trajectory); @@ -67,7 +67,7 @@ bool smoothPath( traj_steering_rate_limited, v0, current_pose, planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); const size_t traj_resampled_closest = - autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( traj_resampled, current_pose, planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); std::vector debug_trajectories; @@ -87,7 +87,7 @@ bool smoothPath( autoware::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( traj_resampled_closest, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed); } - out_path = autoware_motion_utils::convertToPathWithLaneId(traj_smoothed); + out_path = autoware::motion_utils::convertToPathWithLaneId(traj_smoothed); return true; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp index 087e532b6e0df..457c3a1271e31 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp @@ -46,9 +46,9 @@ size_t calcPointIndexFromSegmentIndex( const size_t next_point_idx = seg_idx + 1; const double prev_dist = - autoware_universe_utils::calcDistance2d(point, points.at(prev_point_idx)); + autoware::universe_utils::calcDistance2d(point, points.at(prev_point_idx)); const double next_dist = - autoware_universe_utils::calcDistance2d(point, points.at(next_point_idx)); + autoware::universe_utils::calcDistance2d(point, points.at(next_point_idx)); if (prev_dist < next_dist) { return prev_point_idx; @@ -62,7 +62,7 @@ PathPoint getLerpPathPointWithLaneId(const PathPoint p0, const PathPoint p1, con { auto lerp = [](const double a, const double b, const double t) { return a + t * (b - a); }; PathPoint p; - p.pose = autoware_universe_utils::calcInterpolatedPose(p0, p1, ratio); + p.pose = autoware::universe_utils::calcInterpolatedPose(p0, p1, ratio); const double v = lerp(p0.longitudinal_velocity_mps, p1.longitudinal_velocity_mps, ratio); p.longitudinal_velocity_mps = v; return p; @@ -84,7 +84,7 @@ geometry_msgs::msg::Pose transformRelCoordinate2D( res.position.y = ((-1.0) * std::sin(yaw) * trans_p.x) + (std::cos(yaw) * trans_p.y); res.position.z = target.position.z - origin.position.z; res.orientation = - autoware_universe_utils::createQuaternionFromYaw(tf2::getYaw(target.orientation) - yaw); + autoware::universe_utils::createQuaternionFromYaw(tf2::getYaw(target.orientation) - yaw); return res; } @@ -95,16 +95,16 @@ namespace autoware::behavior_velocity_planner { namespace planning_utils { -using autoware_motion_utils::calcLongitudinalOffsetToSegment; -using autoware_motion_utils::calcSignedArcLength; -using autoware_motion_utils::validateNonEmpty; +using autoware::motion_utils::calcLongitudinalOffsetToSegment; +using autoware::motion_utils::calcSignedArcLength; +using autoware::motion_utils::validateNonEmpty; +using autoware::universe_utils::calcAzimuthAngle; +using autoware::universe_utils::calcDistance2d; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::calcSquaredDistance2d; +using autoware::universe_utils::createQuaternionFromYaw; +using autoware::universe_utils::getPoint; using autoware_planning_msgs::msg::PathPoint; -using autoware_universe_utils::calcAzimuthAngle; -using autoware_universe_utils::calcDistance2d; -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::calcSquaredDistance2d; -using autoware_universe_utils::createQuaternionFromYaw; -using autoware_universe_utils::getPoint; size_t calcSegmentIndexFromPointIndex( const std::vector & points, @@ -121,7 +121,7 @@ size_t calcSegmentIndexFromPointIndex( } const double offset_to_seg = - autoware_motion_utils::calcLongitudinalOffsetToSegment(points, idx, point); + autoware::motion_utils::calcLongitudinalOffsetToSegment(points, idx, point); if (0 < offset_to_seg) { return idx; } @@ -318,7 +318,7 @@ geometry_msgs::msg::Pose getAheadPose( for (size_t i = start_idx; i < path.points.size() - 1; ++i) { const geometry_msgs::msg::Pose p0 = path.points.at(i).point.pose; const geometry_msgs::msg::Pose p1 = path.points.at(i + 1).point.pose; - curr_dist += autoware_universe_utils::calcDistance2d(p0, p1); + curr_dist += autoware::universe_utils::calcDistance2d(p0, p1); if (curr_dist > ahead_dist) { const double dl = std::max(curr_dist - prev_dist, 0.0001 /* avoid 0 divide */); const double w_p0 = (curr_dist - ahead_dist) / dl; @@ -613,7 +613,7 @@ bool isOverLine( const tier4_planning_msgs::msg::PathWithLaneId & path, const geometry_msgs::msg::Pose & self_pose, const geometry_msgs::msg::Pose & line_pose, const double offset) { - return autoware_motion_utils::calcSignedArcLength( + return autoware::motion_utils::calcSignedArcLength( path.points, self_pose.position, line_pose.position) + offset < 0.0; @@ -626,8 +626,9 @@ std::optional insertDecelPoint( // TODO(tanaka): consider proper overlap threshold for inserting decel point const double overlap_threshold = 5e-2; // TODO(murooka): remove this function for u-turn and crossing-path - const size_t base_idx = autoware_motion_utils::findNearestSegmentIndex(output.points, stop_point); - const auto insert_idx = autoware_motion_utils::insertTargetPoint( + const size_t base_idx = + autoware::motion_utils::findNearestSegmentIndex(output.points, stop_point); + const auto insert_idx = autoware::motion_utils::insertTargetPoint( base_idx, stop_point, output.points, overlap_threshold); if (!insert_idx) { @@ -639,35 +640,36 @@ std::optional insertDecelPoint( output.points.at(i).point.longitudinal_velocity_mps = std::min(original_velocity, target_velocity); } - return autoware_universe_utils::getPose(output.points.at(insert_idx.value())); + return autoware::universe_utils::getPose(output.points.at(insert_idx.value())); } // TODO(murooka): remove this function for u-turn and crossing-path std::optional insertStopPoint( const geometry_msgs::msg::Point & stop_point, PathWithLaneId & output) { - const size_t base_idx = autoware_motion_utils::findNearestSegmentIndex(output.points, stop_point); + const size_t base_idx = + autoware::motion_utils::findNearestSegmentIndex(output.points, stop_point); const auto insert_idx = - autoware_motion_utils::insertStopPoint(base_idx, stop_point, output.points); + autoware::motion_utils::insertStopPoint(base_idx, stop_point, output.points); if (!insert_idx) { return {}; } - return autoware_universe_utils::getPose(output.points.at(insert_idx.value())); + return autoware::universe_utils::getPose(output.points.at(insert_idx.value())); } std::optional insertStopPoint( const geometry_msgs::msg::Point & stop_point, const size_t stop_seg_idx, PathWithLaneId & output) { const auto insert_idx = - autoware_motion_utils::insertStopPoint(stop_seg_idx, stop_point, output.points); + autoware::motion_utils::insertStopPoint(stop_seg_idx, stop_point, output.points); if (!insert_idx) { return {}; } - return autoware_universe_utils::getPose(output.points.at(insert_idx.value())); + return autoware::universe_utils::getPose(output.points.at(insert_idx.value())); } std::set getAssociativeIntersectionLanelets( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_utilization.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_utilization.cpp index a4ee3806417f7..ca5c57fd522c9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_utilization.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_utilization.cpp @@ -84,8 +84,8 @@ TEST(smoothDeceleration, calculateMaxSlowDownVelocity) TEST(specialInterpolation, specialInterpolation) { using autoware::behavior_velocity_planner::interpolatePath; - using autoware_motion_utils::calcSignedArcLength; - using autoware_motion_utils::searchZeroVelocityIndex; + using autoware::motion_utils::calcSignedArcLength; + using autoware::motion_utils::searchZeroVelocityIndex; using autoware_planning_msgs::msg::Path; using autoware_planning_msgs::msg::PathPoint; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp index bdd62fe6aa083..330a3443b4e5d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp @@ -20,13 +20,13 @@ #include #include -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerOrientation; -using autoware_universe_utils::createMarkerScale; -using autoware_universe_utils::createPoint; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerOrientation; +using autoware::universe_utils::createMarkerScale; +using autoware::universe_utils::createPoint; namespace autoware::behavior_velocity_planner { @@ -35,7 +35,7 @@ namespace RunOutDebug::TextWithPosition createDebugText( const std::string text, const geometry_msgs::msg::Pose pose, const float lateral_offset) { - const auto offset_pose = autoware_universe_utils::calcOffsetPose(pose, 0, lateral_offset, 0); + const auto offset_pose = autoware::universe_utils::calcOffsetPose(pose, 0, lateral_offset, 0); RunOutDebug::TextWithPosition text_with_position; text_with_position.text = text; @@ -136,7 +136,7 @@ void RunOutDebug::pushDetectionAreaPolygons(const Polygon2d & debug_polygon) { std::vector ros_points; for (const auto & p : debug_polygon.outer()) { - ros_points.push_back(autoware_universe_utils::createPoint(p.x(), p.y(), 0.0)); + ros_points.push_back(autoware::universe_utils::createPoint(p.x(), p.y(), 0.0)); } detection_area_polygons_.push_back(ros_points); @@ -146,7 +146,7 @@ void RunOutDebug::pushMandatoryDetectionAreaPolygons(const Polygon2d & debug_pol { std::vector ros_points; for (const auto & p : debug_polygon.outer()) { - ros_points.push_back(autoware_universe_utils::createPoint(p.x(), p.y(), 0.0)); + ros_points.push_back(autoware::universe_utils::createPoint(p.x(), p.y(), 0.0)); } mandatory_detection_area_polygons_.push_back(ros_points); @@ -186,12 +186,12 @@ visualization_msgs::msg::MarkerArray RunOutDebug::createVisualizationMarkerArray return visualization_marker_array; } -autoware_motion_utils::VirtualWalls RunOutDebug::createVirtualWalls() +autoware::motion_utils::VirtualWalls RunOutDebug::createVirtualWalls() { - autoware_motion_utils::VirtualWalls virtual_walls; - autoware_motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWall wall; wall.text = "run_out"; - wall.style = autoware_motion_utils::VirtualWallType::stop; + wall.style = autoware::motion_utils::VirtualWallType::stop; for (const auto & p : stop_pose_) { wall.pose = p; virtual_walls.push_back(wall); @@ -363,7 +363,7 @@ visualization_msgs::msg::MarkerArray RunOutModule::createDebugMarkerArray() return debug_ptr_->createVisualizationMarkerArray(); } -autoware_motion_utils::VirtualWalls RunOutModule::createVirtualWalls() +autoware::motion_utils::VirtualWalls RunOutModule::createVirtualWalls() { return debug_ptr_->createVirtualWalls(); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.hpp index 7aaa60e2e4b69..b9ea77fc91e8c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.hpp @@ -123,7 +123,7 @@ class RunOutDebug void publishEmptyPointCloud(); visualization_msgs::msg::MarkerArray createVisualizationMarkerArray(); void setHeight(const double height); - autoware_motion_utils::VirtualWalls createVirtualWalls(); + autoware::motion_utils::VirtualWalls createVirtualWalls(); private: visualization_msgs::msg::MarkerArray createVisualizationMarkerArrayFromDebugData( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp index 73e97a33ad8de..f75da2b5cc5de 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp @@ -38,16 +38,16 @@ namespace geometry_msgs::msg::Quaternion createQuaternionFacingToTrajectory( const PathPointsWithLaneId & path_points, const geometry_msgs::msg::Point & point) { - const auto nearest_idx = autoware_motion_utils::findNearestIndex(path_points, point); + const auto nearest_idx = autoware::motion_utils::findNearestIndex(path_points, point); const auto & nearest_pose = path_points.at(nearest_idx).point.pose; const auto longitudinal_offset = - autoware_universe_utils::calcLongitudinalDeviation(nearest_pose, point); + autoware::universe_utils::calcLongitudinalDeviation(nearest_pose, point); const auto vertical_point = - autoware_universe_utils::calcOffsetPose(nearest_pose, longitudinal_offset, 0, 0).position; - const auto azimuth_angle = autoware_universe_utils::calcAzimuthAngle(point, vertical_point); + autoware::universe_utils::calcOffsetPose(nearest_pose, longitudinal_offset, 0, 0).position; + const auto azimuth_angle = autoware::universe_utils::calcAzimuthAngle(point, vertical_point); - return autoware_universe_utils::createQuaternionFromYaw(azimuth_angle); + return autoware::universe_utils::createQuaternionFromYaw(azimuth_angle); } // create predicted path assuming that obstacles move with constant velocity @@ -60,7 +60,7 @@ std::vector createPredictedPath( for (size_t i = 0; i < path_size; i++) { const float travel_dist = max_velocity_mps * time_step * i; const auto predicted_pose = - autoware_universe_utils::calcOffsetPose(initial_pose, travel_dist, 0, 0); + autoware::universe_utils::calcOffsetPose(initial_pose, travel_dist, 0, 0); path_points.emplace_back(predicted_pose); } @@ -115,7 +115,7 @@ bool isAheadOf( const geometry_msgs::msg::Point & target_point, const geometry_msgs::msg::Pose & base_pose) { const auto longitudinal_deviation = - autoware_universe_utils::calcLongitudinalDeviation(base_pose, target_point); + autoware::universe_utils::calcLongitudinalDeviation(base_pose, target_point); const bool is_ahead = longitudinal_deviation > 0; return is_ahead; } @@ -136,7 +136,7 @@ pcl::PointCloud extractObstaclePointsWithinPolygon( pcl::PointCloud output_points; output_points.header = input_points.header; for (const auto & poly : polys) { - const auto bounding_box = bg::return_envelope(poly); + const auto bounding_box = bg::return_envelope(poly); for (const auto & p : input_points) { Point2d point(p.x, p.y); @@ -165,9 +165,9 @@ std::vector> groupPointsWithNearestSegmentIndex( points_with_index.resize(path_points.size()); for (const auto & p : input_points.points) { - const auto ros_point = autoware_universe_utils::createPoint(p.x, p.y, p.z); + const auto ros_point = autoware::universe_utils::createPoint(p.x, p.y, p.z); const size_t nearest_seg_idx = - autoware_motion_utils::findNearestSegmentIndex(path_points, ros_point); + autoware::motion_utils::findNearestSegmentIndex(path_points, ros_point); // if the point is ahead of end of the path, index should be path.size() - 1 if ( @@ -189,10 +189,10 @@ pcl::PointXYZ calculateLateralNearestPoint( { const auto lateral_nearest_point = std::min_element( input_points.points.begin(), input_points.points.end(), [&](const auto & p1, const auto & p2) { - const auto lateral_deviation_p1 = std::abs(autoware_universe_utils::calcLateralDeviation( - base_pose, autoware_universe_utils::createPoint(p1.x, p1.y, 0))); - const auto lateral_deviation_p2 = std::abs(autoware_universe_utils::calcLateralDeviation( - base_pose, autoware_universe_utils::createPoint(p2.x, p2.y, 0))); + const auto lateral_deviation_p1 = std::abs(autoware::universe_utils::calcLateralDeviation( + base_pose, autoware::universe_utils::createPoint(p1.x, p1.y, 0))); + const auto lateral_deviation_p2 = std::abs(autoware::universe_utils::calcLateralDeviation( + base_pose, autoware::universe_utils::createPoint(p2.x, p2.y, 0))); return lateral_deviation_p1 < lateral_deviation_p2; }); @@ -267,7 +267,7 @@ pcl::PointCloud transformPointCloud( pcl::PointCloud pointcloud_pcl; pcl::fromROSMsg(input_pointcloud, pointcloud_pcl); pcl::PointCloud pointcloud_pcl_transformed; - autoware_universe_utils::transformPointCloud( + autoware::universe_utils::transformPointCloud( pointcloud_pcl, pointcloud_pcl_transformed, transform_matrix); return pointcloud_pcl_transformed; @@ -366,8 +366,8 @@ std::vector DynamicObstacleCreatorForObject::createDynamicObsta dynamic_obstacle.pose = predicted_object.kinematics.initial_pose_with_covariance.pose; if (param_.assume_fixed_velocity) { - dynamic_obstacle.min_velocity_mps = autoware_universe_utils::kmph2mps(param_.min_vel_kmph); - dynamic_obstacle.max_velocity_mps = autoware_universe_utils::kmph2mps(param_.max_vel_kmph); + dynamic_obstacle.min_velocity_mps = autoware::universe_utils::kmph2mps(param_.min_vel_kmph); + dynamic_obstacle.max_velocity_mps = autoware::universe_utils::kmph2mps(param_.max_vel_kmph); } else { calculateMinAndMaxVelFromCovariance( predicted_object.kinematics.initial_twist_with_covariance, param_.std_dev_multiplier, @@ -409,8 +409,8 @@ std::vector DynamicObstacleCreatorForObjectWithoutPath::createD dynamic_obstacle.pose.orientation = createQuaternionFacingToTrajectory( dynamic_obstacle_data_.path.points, dynamic_obstacle.pose.position); - dynamic_obstacle.min_velocity_mps = autoware_universe_utils::kmph2mps(param_.min_vel_kmph); - dynamic_obstacle.max_velocity_mps = autoware_universe_utils::kmph2mps(param_.max_vel_kmph); + dynamic_obstacle.min_velocity_mps = autoware::universe_utils::kmph2mps(param_.min_vel_kmph); + dynamic_obstacle.max_velocity_mps = autoware::universe_utils::kmph2mps(param_.max_vel_kmph); dynamic_obstacle.classifications = predicted_object.classification; dynamic_obstacle.shape = predicted_object.shape; @@ -469,12 +469,12 @@ std::vector DynamicObstacleCreatorForPoints::createDynamicObsta // create pose facing the direction of the lane dynamic_obstacle.pose.position = - autoware_universe_utils::createPoint(point.x, point.y, point.z); + autoware::universe_utils::createPoint(point.x, point.y, point.z); dynamic_obstacle.pose.orientation = createQuaternionFacingToTrajectory( dynamic_obstacle_data_.path.points, dynamic_obstacle.pose.position); - dynamic_obstacle.min_velocity_mps = autoware_universe_utils::kmph2mps(param_.min_vel_kmph); - dynamic_obstacle.max_velocity_mps = autoware_universe_utils::kmph2mps(param_.max_vel_kmph); + dynamic_obstacle.min_velocity_mps = autoware::universe_utils::kmph2mps(param_.min_vel_kmph); + dynamic_obstacle.max_velocity_mps = autoware::universe_utils::kmph2mps(param_.max_vel_kmph); // create classification of points as pedestrian ObjectClassification classification; @@ -495,7 +495,7 @@ std::vector DynamicObstacleCreatorForPoints::createDynamicObsta param_.max_prediction_time); predicted_path.confidence = 1.0; dynamic_obstacle.predicted_paths.emplace_back(predicted_path); - dynamic_obstacle.uuid = autoware_universe_utils::generateUUID(); + dynamic_obstacle.uuid = autoware::universe_utils::generateUUID(); dynamic_obstacles.emplace_back(dynamic_obstacle); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp index 00a44a0cf625e..f2261aa8f4640 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp @@ -22,7 +22,7 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::getOrDeclareParameter; +using autoware::universe_utils::getOrDeclareParameter; RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node) : SceneModuleManagerInterface(node, getModuleName()) { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/path_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/path_utils.cpp index 7a3083e75f25c..2196cdec36886 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/path_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/path_utils.cpp @@ -26,7 +26,7 @@ geometry_msgs::msg::Point findLongitudinalNearestPoint( geometry_msgs::msg::Point min_dist_point{}; for (const auto & p : target_points) { - const float dist = autoware_motion_utils::calcSignedArcLength(points, src_point, p); + const float dist = autoware::motion_utils::calcSignedArcLength(points, src_point, p); if (dist < min_dist) { min_dist = dist; min_dist_point = p; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp index 11db6a604a30e..4cede13e56469 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp @@ -177,7 +177,7 @@ bool RunOutModule::modifyPathVelocity( insertStopPoint(last_stop_point_, *path); // debug debug_ptr_->setAccelReason(RunOutDebug::AccelReason::STOP); - debug_ptr_->pushStopPose(autoware_universe_utils::calcOffsetPose( + debug_ptr_->pushStopPose(autoware::universe_utils::calcOffsetPose( *last_stop_point_, planner_param_.vehicle_param.base_to_front, 0, 0)); } } @@ -222,7 +222,7 @@ std::optional RunOutModule::detectCollision( const auto & p2 = path.points.at(idx).point; const float prev_vel = std::max(p1.longitudinal_velocity_mps, planner_param_.run_out.min_vel_ego_kmph / 3.6f); - const float ds = autoware_universe_utils::calcDistance2d(p1, p2); + const float ds = autoware::universe_utils::calcDistance2d(p1, p2); // calculate travel time from nearest point to p2 travel_time += ds / prev_vel; @@ -272,9 +272,9 @@ std::optional RunOutModule::findNearestCollisionObstacle( std::sort( dynamic_obstacles.begin(), dynamic_obstacles.end(), [&path, &base_pose](const auto & lhs, const auto & rhs) -> bool { - const auto dist_lhs = autoware_motion_utils::calcSignedArcLength( + const auto dist_lhs = autoware::motion_utils::calcSignedArcLength( path.points, base_pose.position, lhs.pose.position); - const auto dist_rhs = autoware_motion_utils::calcSignedArcLength( + const auto dist_rhs = autoware::motion_utils::calcSignedArcLength( path.points, base_pose.position, rhs.pose.position); return dist_lhs < dist_rhs; @@ -316,10 +316,10 @@ std::optional RunOutModule::findNearestCollisionObstacle( float RunOutModule::calcCollisionPositionOfVehicleSide( const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Pose & base_pose) const { - const auto vehicle_front_pose = autoware_universe_utils::calcOffsetPose( + const auto vehicle_front_pose = autoware::universe_utils::calcOffsetPose( base_pose, planner_param_.vehicle_param.base_to_front, 0, 0); const auto longitudinal_offset_from_front = - std::abs(autoware_universe_utils::calcLongitudinalDeviation(vehicle_front_pose, point)); + std::abs(autoware::universe_utils::calcLongitudinalDeviation(vehicle_front_pose, point)); return longitudinal_offset_from_front; } @@ -341,7 +341,7 @@ std::vector RunOutModule::createVehiclePolygon( const double base_to_left = (planner_param_.vehicle_param.wheel_tread / 2.0) + planner_param_.vehicle_param.left_overhang; - using autoware_universe_utils::calcOffsetPose; + using autoware::universe_utils::calcOffsetPose; const auto p1 = calcOffsetPose(base_pose, base_to_front, base_to_left, 0.0); const auto p2 = calcOffsetPose(base_pose, base_to_front, -base_to_right, 0.0); const auto p3 = calcOffsetPose(base_pose, -base_to_rear, -base_to_right, 0.0); @@ -359,8 +359,8 @@ std::vector RunOutModule::createVehiclePolygon( std::vector RunOutModule::excludeObstaclesOnEgoPath( const std::vector & dynamic_obstacles, const PathWithLaneId & path) { - using autoware_motion_utils::findNearestIndex; - using autoware_universe_utils::calcOffsetPose; + using autoware::motion_utils::findNearestIndex; + using autoware::universe_utils::calcOffsetPose; if (!planner_param_.run_out.exclude_obstacles_already_in_path || path.points.empty()) { return dynamic_obstacles; } @@ -379,18 +379,18 @@ std::vector RunOutModule::excludeObstaclesOnEgoPath( } const auto object_position = o.pose.position; const auto closest_ego_pose = path.points.at(*idx).point.pose; - const auto vehicle_left_pose = autoware_universe_utils::calcOffsetPose( + const auto vehicle_left_pose = autoware::universe_utils::calcOffsetPose( closest_ego_pose, 0, vehicle_with_with_margin_halved, 0); - const auto vehicle_right_pose = autoware_universe_utils::calcOffsetPose( + const auto vehicle_right_pose = autoware::universe_utils::calcOffsetPose( closest_ego_pose, 0, -vehicle_with_with_margin_halved, 0); const double signed_distance_from_left = - autoware_universe_utils::calcLateralDeviation(vehicle_left_pose, object_position); + autoware::universe_utils::calcLateralDeviation(vehicle_left_pose, object_position); const double signed_distance_from_right = - autoware_universe_utils::calcLateralDeviation(vehicle_right_pose, object_position); + autoware::universe_utils::calcLateralDeviation(vehicle_right_pose, object_position); // If object is outside of the ego path, include it in list of possible target objects // It is also deleted from the path of objects inside ego path - const auto obstacle_uuid_hex = autoware_universe_utils::toHexString(o.uuid); + const auto obstacle_uuid_hex = autoware::universe_utils::toHexString(o.uuid); if (signed_distance_from_left > 0.0 || signed_distance_from_right < 0.0) { obstacles_outside_of_path.push_back(o); obstacle_in_ego_path_times_.erase(obstacle_uuid_hex); @@ -482,7 +482,7 @@ std::optional RunOutModule::calcPredictedObstaclePose( const auto & p1 = predicted_path.at(i - 1); const auto & p2 = predicted_path.at(i); - const float ds = autoware_universe_utils::calcDistance2d(p1, p2); + const float ds = autoware::universe_utils::calcDistance2d(p1, p2); const float dt = ds / velocity_mps; // apply linear interpolation between the predicted path points @@ -555,7 +555,7 @@ bool RunOutModule::checkCollisionWithCylinder( run_out_utils::createBoostPolyFromMsg(bounding_box_for_points); // check collision with 2d polygon - std::vector collision_points_bg; + std::vector collision_points_bg; bg::intersection(vehicle_polygon, bg_bounding_box_for_points, collision_points_bg); // no collision detected @@ -568,7 +568,7 @@ bool RunOutModule::checkCollisionWithCylinder( debug_ptr_->pushCollisionObstaclePolygons(bounding_box_for_points); for (const auto & p : collision_points_bg) { const auto p_msg = - autoware_universe_utils::createPoint(p.x(), p.y(), pose_with_range.pose_min.position.z); + autoware::universe_utils::createPoint(p.x(), p.y(), pose_with_range.pose_min.position.z); collision_points.emplace_back(p_msg); } @@ -581,30 +581,30 @@ std::vector RunOutModule::createBoundingBoxForRangedP const PoseWithRange & pose_with_range, const float x_offset, const float y_offset) const { const auto dist_p1_p2 = - autoware_universe_utils::calcDistance2d(pose_with_range.pose_min, pose_with_range.pose_max); + autoware::universe_utils::calcDistance2d(pose_with_range.pose_min, pose_with_range.pose_max); geometry_msgs::msg::Pose p_min_to_p_max; if (dist_p1_p2 < std::numeric_limits::epsilon()) { // can't calculate the angle if two points are the same p_min_to_p_max = pose_with_range.pose_min; } else { - const auto azimuth_angle = autoware_universe_utils::calcAzimuthAngle( + const auto azimuth_angle = autoware::universe_utils::calcAzimuthAngle( pose_with_range.pose_min.position, pose_with_range.pose_max.position); p_min_to_p_max.position = pose_with_range.pose_min.position; - p_min_to_p_max.orientation = autoware_universe_utils::createQuaternionFromYaw(azimuth_angle); + p_min_to_p_max.orientation = autoware::universe_utils::createQuaternionFromYaw(azimuth_angle); } std::vector poly; poly.emplace_back( - autoware_universe_utils::calcOffsetPose(p_min_to_p_max, dist_p1_p2 + x_offset, y_offset, 0.0) + autoware::universe_utils::calcOffsetPose(p_min_to_p_max, dist_p1_p2 + x_offset, y_offset, 0.0) .position); poly.emplace_back( - autoware_universe_utils::calcOffsetPose(p_min_to_p_max, dist_p1_p2 + x_offset, -y_offset, 0.0) + autoware::universe_utils::calcOffsetPose(p_min_to_p_max, dist_p1_p2 + x_offset, -y_offset, 0.0) .position); poly.emplace_back( - autoware_universe_utils::calcOffsetPose(p_min_to_p_max, -x_offset, -y_offset, 0.0).position); + autoware::universe_utils::calcOffsetPose(p_min_to_p_max, -x_offset, -y_offset, 0.0).position); poly.emplace_back( - autoware_universe_utils::calcOffsetPose(p_min_to_p_max, -x_offset, y_offset, 0.0).position); + autoware::universe_utils::calcOffsetPose(p_min_to_p_max, -x_offset, y_offset, 0.0).position); return poly; } @@ -620,7 +620,7 @@ bool RunOutModule::checkCollisionWithBoundingBox( const auto bg_bounding_box = run_out_utils::createBoostPolyFromMsg(bounding_box); // check collision with 2d polygon - std::vector collision_points_bg; + std::vector collision_points_bg; bg::intersection(vehicle_polygon, bg_bounding_box, collision_points_bg); // no collision detected @@ -633,7 +633,7 @@ bool RunOutModule::checkCollisionWithBoundingBox( debug_ptr_->pushCollisionObstaclePolygons(bounding_box); for (const auto & p : collision_points_bg) { const auto p_msg = - autoware_universe_utils::createPoint(p.x(), p.y(), pose_with_range.pose_min.position.z); + autoware::universe_utils::createPoint(p.x(), p.y(), pose_with_range.pose_min.position.z); collision_points.emplace_back(p_msg); } @@ -658,7 +658,7 @@ std::optional RunOutModule::calcStopPoint( } // calculate distance to collision with the obstacle - const float dist_to_collision_point = autoware_motion_utils::calcSignedArcLength( + const float dist_to_collision_point = autoware::motion_utils::calcSignedArcLength( path.points, current_pose.position, dynamic_obstacle->nearest_collision_point); const float dist_to_collision = dist_to_collision_point - planner_param_.vehicle_param.base_to_front; @@ -669,7 +669,7 @@ std::optional RunOutModule::calcStopPoint( // calculate the stop point for base link const float base_to_collision_point = planner_param_.run_out.stop_margin + planner_param_.vehicle_param.base_to_front; - const auto stop_point = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto stop_point = autoware::motion_utils::calcLongitudinalOffsetPose( path.points, dynamic_obstacle->nearest_collision_point, -base_to_collision_point, false); if (!stop_point) { RCLCPP_WARN_STREAM(logger_, "failed to calculate stop point."); @@ -678,7 +678,7 @@ std::optional RunOutModule::calcStopPoint( // debug debug_ptr_->setAccelReason(RunOutDebug::AccelReason::STOP); - debug_ptr_->pushStopPose(autoware_universe_utils::calcOffsetPose( + debug_ptr_->pushStopPose(autoware::universe_utils::calcOffsetPose( *stop_point, planner_param_.vehicle_param.base_to_front, 0, 0)); return stop_point; @@ -691,7 +691,7 @@ std::optional RunOutModule::calcStopPoint( const float planning_dec = jerk_dec < planner_param_.common.normal_min_jerk ? planner_param_.common.limit_min_acc : planner_param_.common.normal_min_acc; - auto stop_dist = autoware_motion_utils::calcDecelDistWithJerkAndAccConstraints( + auto stop_dist = autoware::motion_utils::calcDecelDistWithJerkAndAccConstraints( current_vel, target_vel, current_acc, planning_dec, jerk_acc, jerk_dec); if (!stop_dist) { RCLCPP_WARN_STREAM(logger_, "failed to calculate stop distance."); @@ -727,7 +727,7 @@ std::optional RunOutModule::calcStopPoint( // calculate the stop point for base link const float base_to_collision_point = planner_param_.run_out.stop_margin + planner_param_.vehicle_param.base_to_front; - const auto stop_point = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto stop_point = autoware::motion_utils::calcLongitudinalOffsetPose( path.points, dynamic_obstacle->nearest_collision_point, -base_to_collision_point, false); if (!stop_point) { RCLCPP_WARN_STREAM(logger_, "failed to calculate stop point."); @@ -736,7 +736,7 @@ std::optional RunOutModule::calcStopPoint( // debug debug_ptr_->setAccelReason(RunOutDebug::AccelReason::STOP); - debug_ptr_->pushStopPose(autoware_universe_utils::calcOffsetPose( + debug_ptr_->pushStopPose(autoware::universe_utils::calcOffsetPose( *stop_point, planner_param_.vehicle_param.base_to_front, 0, 0)); return stop_point; @@ -754,7 +754,7 @@ bool RunOutModule::insertStopPoint( // find nearest point index behind the stop point const auto nearest_seg_idx = - autoware_motion_utils::findNearestSegmentIndex(path.points, stop_point->position); + autoware::motion_utils::findNearestSegmentIndex(path.points, stop_point->position); auto insert_idx = nearest_seg_idx + 1; // if stop point is ahead of the end of the path, don't insert @@ -788,7 +788,7 @@ void RunOutModule::insertVelocityForState( state_input.current_velocity = current_vel; state_input.current_obstacle = dynamic_obstacle; state_input.dist_to_collision = - autoware_motion_utils::calcSignedArcLength( + autoware::motion_utils::calcSignedArcLength( smoothed_path.points, current_pose.position, dynamic_obstacle->nearest_collision_point) - planner_param.vehicle_param.base_to_front; @@ -857,14 +857,14 @@ void RunOutModule::insertApproachingVelocity( { // insert slow down velocity from nearest segment point const auto nearest_seg_idx = - autoware_motion_utils::findNearestSegmentIndex(output_path.points, current_pose.position); + autoware::motion_utils::findNearestSegmentIndex(output_path.points, current_pose.position); run_out_utils::insertPathVelocityFromIndexLimited( nearest_seg_idx, approaching_vel, output_path.points); // calculate stop point to insert 0 velocity const float base_to_collision_point = approach_margin + planner_param_.vehicle_param.base_to_front; - const auto stop_point = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto stop_point = autoware::motion_utils::calcLongitudinalOffsetPose( output_path.points, dynamic_obstacle.nearest_collision_point, -base_to_collision_point, false); if (!stop_point) { RCLCPP_WARN_STREAM(logger_, "failed to calculate stop point."); @@ -872,11 +872,11 @@ void RunOutModule::insertApproachingVelocity( } // debug - debug_ptr_->pushStopPose(autoware_universe_utils::calcOffsetPose( + debug_ptr_->pushStopPose(autoware::universe_utils::calcOffsetPose( *stop_point, planner_param_.vehicle_param.base_to_front, 0, 0)); const auto nearest_seg_idx_stop = - autoware_motion_utils::findNearestSegmentIndex(output_path.points, stop_point->position); + autoware::motion_utils::findNearestSegmentIndex(output_path.points, stop_point->position); auto insert_idx_stop = nearest_seg_idx_stop + 1; // to PathPointWithLaneId @@ -899,7 +899,7 @@ void RunOutModule::applyMaxJerkLimit( const auto stop_point = path.points.at(stop_point_idx.value()).point.pose.position; const auto dist_to_stop_point = - autoware_motion_utils::calcSignedArcLength(path.points, current_pose.position, stop_point); + autoware::motion_utils::calcSignedArcLength(path.points, current_pose.position, stop_point); // calculate desired velocity with limited jerk const auto jerk_limited_vel = planning_utils::calcDecelerationVelocityFromDistanceToTarget( @@ -982,15 +982,15 @@ void RunOutModule::publishDebugValue( const geometry_msgs::msg::Pose & current_pose) const { if (dynamic_obstacle) { - const auto lateral_dist = std::abs(autoware_motion_utils::calcLateralOffset( + const auto lateral_dist = std::abs(autoware::motion_utils::calcLateralOffset( path.points, dynamic_obstacle->pose.position)) - planner_param_.vehicle_param.width / 2.0; const auto longitudinal_dist_to_obstacle = - autoware_motion_utils::calcSignedArcLength( + autoware::motion_utils::calcSignedArcLength( path.points, current_pose.position, dynamic_obstacle->pose.position) - planner_param_.vehicle_param.base_to_front; - const float dist_to_collision_point = autoware_motion_utils::calcSignedArcLength( + const float dist_to_collision_point = autoware::motion_utils::calcSignedArcLength( path.points, current_pose.position, dynamic_obstacle->nearest_collision_point); const auto dist_to_collision = dist_to_collision_point - planner_param_.vehicle_param.base_to_front; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp index 80404b69232e1..1922cba9257ab 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp @@ -52,7 +52,7 @@ class RunOutModule : public SceneModuleInterface bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; - autoware_motion_utils::VirtualWalls createVirtualWalls() override; + autoware::motion_utils::VirtualWalls createVirtualWalls() override; void setPlannerParam(const PlannerParam & planner_param); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp index 3745c01f51dd3..537d647883ad4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp @@ -102,14 +102,14 @@ std::vector findLateralSameSidePoints( const geometry_msgs::msg::Point & target_point) { const auto signed_deviation = - autoware_universe_utils::calcLateralDeviation(base_pose, target_point); + autoware::universe_utils::calcLateralDeviation(base_pose, target_point); RCLCPP_DEBUG_STREAM( rclcpp::get_logger("findLateralSameSidePoints"), "signed dev of target: " << signed_deviation); std::vector same_side_points; for (const auto & p : points) { const auto signed_deviation_of_point = - autoware_universe_utils::calcLateralDeviation(base_pose, p); + autoware::universe_utils::calcLateralDeviation(base_pose, p); RCLCPP_DEBUG_STREAM( rclcpp::get_logger("findLateralSameSidePoints"), "signed dev of point: " << signed_deviation_of_point); @@ -127,7 +127,7 @@ std::vector findLateralSameSidePoints( bool isSamePoint(const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2) { - if (autoware_universe_utils::calcDistance2d(p1, p2) < std::numeric_limits::epsilon()) { + if (autoware::universe_utils::calcDistance2d(p1, p2) < std::numeric_limits::epsilon()) { return true; } @@ -184,15 +184,15 @@ bool pathIntersectsEgoCutLine( { if (path.size() < 2) return false; const auto p1 = - autoware_universe_utils::calcOffsetPose(ego_pose, 0.0, half_line_length, 0.0).position; + autoware::universe_utils::calcOffsetPose(ego_pose, 0.0, half_line_length, 0.0).position; const auto p2 = - autoware_universe_utils::calcOffsetPose(ego_pose, 0.0, -half_line_length, 0.0).position; + autoware::universe_utils::calcOffsetPose(ego_pose, 0.0, -half_line_length, 0.0).position; ego_cut_line = {p1, p2}; for (size_t i = 1; i < path.size(); ++i) { const auto & p3 = path.at(i).position; const auto & p4 = path.at(i - 1).position; - const auto intersection = autoware_universe_utils::intersect(p1, p2, p3, p4); + const auto intersection = autoware::universe_utils::intersect(p1, p2, p3, p4); if (intersection.has_value()) { return true; } @@ -218,7 +218,7 @@ std::vector excludeObstaclesOutSideOfLine( std::vector extracted_dynamic_obstacle; for (const auto & obstacle : dynamic_obstacles) { const auto obstacle_nearest_idx = - autoware_motion_utils::findNearestIndex(path_points, obstacle.pose.position); + autoware::motion_utils::findNearestIndex(path_points, obstacle.pose.position); const auto & obstacle_nearest_path_point = path_points.at(obstacle_nearest_idx).point.pose.position; @@ -255,7 +255,7 @@ PathPointsWithLaneId decimatePathPoints( for (size_t i = 1; i < input_path_points.size(); i++) { const auto p1 = input_path_points.at(i - 1); const auto p2 = input_path_points.at(i); - const auto dist = autoware_universe_utils::calcDistance2d(p1, p2); + const auto dist = autoware::universe_utils::calcDistance2d(p1, p2); dist_sum += dist; if (dist_sum > step) { @@ -273,7 +273,7 @@ PathWithLaneId trimPathFromSelfPose( const double trim_distance) { const size_t nearest_idx = - autoware_motion_utils::findNearestIndex(input.points, self_pose.position); + autoware::motion_utils::findNearestIndex(input.points, self_pose.position); PathWithLaneId output{}; output.header = input.header; @@ -285,7 +285,7 @@ PathWithLaneId trimPathFromSelfPose( if (i != nearest_idx) { dist_sum += - autoware_universe_utils::calcDistance2d(input.points.at(i - 1), input.points.at(i)); + autoware::universe_utils::calcDistance2d(input.points.at(i - 1), input.points.at(i)); } if (dist_sum > trim_distance) { @@ -329,7 +329,7 @@ PathPointWithLaneId createExtendPathPoint( { PathPointWithLaneId extend_path_point = goal_point; extend_path_point.point.pose = - autoware_universe_utils::calcOffsetPose(goal_point.point.pose, extend_distance, 0.0, 0.0); + autoware::universe_utils::calcOffsetPose(goal_point.point.pose, extend_distance, 0.0, 0.0); return extend_path_point; } @@ -381,7 +381,7 @@ Polygons2d createDetectionAreaPolygon( const float jerk_acc = std::abs(jerk_dec); const float planning_dec = jerk_dec < pp.common.normal_min_jerk ? pp.common.limit_min_acc : pp.common.normal_min_acc; - auto stop_dist = autoware_motion_utils::calcDecelDistWithJerkAndAccConstraints( + auto stop_dist = autoware::motion_utils::calcDecelDistWithJerkAndAccConstraints( initial_vel, target_vel, initial_acc, planning_dec, jerk_acc, jerk_dec); if (!stop_dist) { @@ -401,9 +401,10 @@ Polygons2d createDetectionAreaPolygon( da_range.left_overhang = pp.vehicle_param.left_overhang; da_range.max_lateral_distance = obstacle_vel_mps * pp.dynamic_obstacle.max_prediction_time; Polygons2d detection_area_poly; - const size_t ego_seg_idx = autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - path.points, pd.current_odometry->pose, pd.ego_nearest_dist_threshold, - pd.ego_nearest_yaw_threshold); + const size_t ego_seg_idx = + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + path.points, pd.current_odometry->pose, pd.ego_nearest_dist_threshold, + pd.ego_nearest_yaw_threshold); planning_utils::createDetectionAreaPolygons( detection_area_poly, path, pd.current_odometry->pose, ego_seg_idx, da_range, pp.dynamic_obstacle.max_vel_kmph / 3.6); @@ -425,7 +426,7 @@ Polygons2d createMandatoryDetectionAreaPolygon( const float jerk_acc = std::abs(jerk_dec); const float planning_dec = jerk_dec < pp.common.normal_min_jerk ? pp.common.limit_min_acc : pp.common.normal_min_acc; - auto stop_dist = autoware_motion_utils::calcDecelDistWithJerkAndAccConstraints( + auto stop_dist = autoware::motion_utils::calcDecelDistWithJerkAndAccConstraints( initial_vel, target_vel, initial_acc, planning_dec, jerk_acc, jerk_dec); if (!stop_dist) { @@ -443,9 +444,10 @@ Polygons2d createMandatoryDetectionAreaPolygon( da_range.left_overhang = pp.vehicle_param.left_overhang; da_range.max_lateral_distance = obstacle_vel_mps * pp.dynamic_obstacle.max_prediction_time; Polygons2d detection_area_poly; - const size_t ego_seg_idx = autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - path.points, pd.current_odometry->pose, pd.ego_nearest_dist_threshold, - pd.ego_nearest_yaw_threshold); + const size_t ego_seg_idx = + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + path.points, pd.current_odometry->pose, pd.ego_nearest_dist_threshold, + pd.ego_nearest_yaw_threshold); planning_utils::createDetectionAreaPolygons( detection_area_poly, path, pd.current_odometry->pose, ego_seg_idx, da_range, pp.dynamic_obstacle.max_vel_kmph / 3.6); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.hpp index 0b79b7bbb9a7d..5f5b7206551ef 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.hpp @@ -34,15 +34,15 @@ namespace autoware::behavior_velocity_planner namespace run_out_utils { namespace bg = boost::geometry; +using autoware::universe_utils::Box2d; +using autoware::universe_utils::LineString2d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; using autoware::vehicle_info_utils::VehicleInfo; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::Shape; using autoware_planning_msgs::msg::PathPoint; -using autoware_universe_utils::Box2d; -using autoware_universe_utils::LineString2d; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; using tier4_debug_msgs::msg::Float32Stamped; using tier4_planning_msgs::msg::PathWithLaneId; using PathPointsWithLaneId = std::vector; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp index 67f149124e3ff..29295f41cdf04 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp @@ -26,9 +26,9 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerScale; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerScale; namespace { @@ -96,16 +96,16 @@ visualization_msgs::msg::MarkerArray StopLineModule::createDebugMarkerArray() return debug_marker_array; } -autoware_motion_utils::VirtualWalls StopLineModule::createVirtualWalls() +autoware::motion_utils::VirtualWalls StopLineModule::createVirtualWalls() { - autoware_motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWalls virtual_walls; if (debug_data_.stop_pose && (state_ == State::APPROACH || state_ == State::STOPPED)) { - autoware_motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWall wall; wall.text = "stopline"; - wall.style = autoware_motion_utils::VirtualWallType::stop; + wall.style = autoware::motion_utils::VirtualWallType::stop; wall.ns = std::to_string(module_id_) + "_"; - wall.pose = autoware_universe_utils::calcOffsetPose( + wall.pose = autoware::universe_utils::calcOffsetPose( *debug_data_.stop_pose, debug_data_.base_link2front, 0.0, 0.0); virtual_walls.push_back(wall); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp index e510e6a32f7e3..97dcb88698868 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp @@ -23,7 +23,7 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::getOrDeclareParameter; +using autoware::universe_utils::getOrDeclareParameter; using lanelet::TrafficSign; StopLineModuleManager::StopLineModuleManager(rclcpp::Node & node) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp index e851d0c442dc4..6075706a672d0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp @@ -73,7 +73,7 @@ bool StopLineModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop const size_t stop_line_seg_idx = planning_utils::calcSegmentIndexFromPointIndex( path->points, stop_pose.position, stop_point_idx); const size_t current_seg_idx = findEgoSegmentIndex(path->points); - const double signed_arc_dist_to_stop_point = autoware_motion_utils::calcSignedArcLength( + const double signed_arc_dist_to_stop_point = autoware::motion_utils::calcSignedArcLength( path->points, planner_data_->current_odometry->pose.position, current_seg_idx, stop_pose.position, stop_line_seg_idx); switch (state_) { @@ -116,7 +116,7 @@ bool StopLineModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop case State::STOPPED: { // Change state after vehicle departure - const auto stopped_pose = autoware_motion_utils::calcLongitudinalOffsetPose( + const auto stopped_pose = autoware::motion_utils::calcLongitudinalOffsetPose( path->points, planner_data_->current_odometry->pose.position, 0.0); if (!stopped_pose) { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp index 7fc9492229cc9..b6b81f224c7be 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp @@ -86,7 +86,7 @@ class StopLineModule : public SceneModuleInterface bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; - autoware_motion_utils::VirtualWalls createVirtualWalls() override; + autoware::motion_utils::VirtualWalls createVirtualWalls() override; private: std::shared_ptr stopped_time_; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/README.md b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/README.md index 4c90b8dd291ca..5300bb3b4b5c1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/README.md +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/README.md @@ -26,7 +26,7 @@ The `TemplateModule` class serves as a foundation for creating a scene module wi #### `createVirtualWalls` Method -- The `createVirtualWalls` method creates virtual walls for the scene and returns them as `autoware_motion_utils::VirtualWalls`. In the provided code, it returns an empty `VirtualWalls` object. +- The `createVirtualWalls` method creates virtual walls for the scene and returns them as `autoware::motion_utils::VirtualWalls`. In the provided code, it returns an empty `VirtualWalls` object. - You should implement the logic to create virtual walls based on your module's requirements. ## `Manager` diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/manager.cpp index 768799382a27f..21c70ee41b8bf 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/manager.cpp @@ -28,7 +28,7 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::getOrDeclareParameter; +using autoware::universe_utils::getOrDeclareParameter; TemplateModuleManager::TemplateModuleManager(rclcpp::Node & node) : SceneModuleManagerInterface(node, getModuleName()) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp index 169381b819c47..0394b0c9e381f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp @@ -36,9 +36,9 @@ visualization_msgs::msg::MarkerArray TemplateModule::createDebugMarkerArray() return ma; }; -autoware_motion_utils::VirtualWalls TemplateModule::createVirtualWalls() +autoware::motion_utils::VirtualWalls TemplateModule::createVirtualWalls() { - autoware_motion_utils::VirtualWalls vw; + autoware::motion_utils::VirtualWalls vw; return vw; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp index b3eb7f65ba265..9789ee37aa669 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp @@ -57,11 +57,12 @@ class TemplateModule : public SceneModuleInterface * @brief Create virtual walls for the scene. * * This method is responsible for generating virtual walls for the scene and returning them as a - * `autoware_motion_utils::VirtualWalls` object. + * `autoware::motion_utils::VirtualWalls` object. * - * @return A `autoware_motion_utils::VirtualWalls` object representing virtual walls in the scene. + * @return A `autoware::motion_utils::VirtualWalls` object representing virtual walls in the + * scene. */ - autoware_motion_utils::VirtualWalls createVirtualWalls() override; + autoware::motion_utils::VirtualWalls createVirtualWalls() override; }; } // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/debug.cpp index 8dc7fd12a7bfc..d6d0505635079 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/debug.cpp @@ -32,22 +32,22 @@ visualization_msgs::msg::MarkerArray TrafficLightModule::createDebugMarkerArray( return debug_marker_array; } -autoware_motion_utils::VirtualWalls TrafficLightModule::createVirtualWalls() +autoware::motion_utils::VirtualWalls TrafficLightModule::createVirtualWalls() { - autoware_motion_utils::VirtualWalls virtual_walls; - autoware_motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWall wall; wall.text = "traffic_light"; wall.ns = std::to_string(module_id_) + "_"; - wall.style = autoware_motion_utils::VirtualWallType::deadline; + wall.style = autoware::motion_utils::VirtualWallType::deadline; for (const auto & p : debug_data_.dead_line_poses) { - wall.pose = autoware_universe_utils::calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); + wall.pose = autoware::universe_utils::calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); virtual_walls.push_back(wall); } - wall.style = autoware_motion_utils::VirtualWallType::stop; + wall.style = autoware::motion_utils::VirtualWallType::stop; for (const auto & p : debug_data_.stop_poses) { - wall.pose = autoware_universe_utils::calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); + wall.pose = autoware::universe_utils::calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); virtual_walls.push_back(wall); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp index 375533fee48f2..8f60f291131bd 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp @@ -26,7 +26,7 @@ #include namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::getOrDeclareParameter; +using autoware::universe_utils::getOrDeclareParameter; using lanelet::TrafficLight; TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp index 3d2b651af45f4..7770a480f8401 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp @@ -210,7 +210,7 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason * geometry_msgs::msg::Point stop_line_point_msg; stop_line_point_msg.x = stop_line_point.x(); stop_line_point_msg.y = stop_line_point.y(); - const double signed_arc_length_to_stop_point = autoware_motion_utils::calcSignedArcLength( + const double signed_arc_length_to_stop_point = autoware::motion_utils::calcSignedArcLength( input_path.points, self_pose->pose.position, stop_line_point_msg); setDistance(signed_arc_length_to_stop_point); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp index 6ac08f555fb26..387d6c1f23acf 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp @@ -74,7 +74,7 @@ class TrafficLightModule : public SceneModuleInterface bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; - autoware_motion_utils::VirtualWalls createVirtualWalls() override; + autoware::motion_utils::VirtualWalls createVirtualWalls() override; inline TrafficSignal getTrafficSignal() const { return looking_tl_state_; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/debug.cpp index 10ec9a7b961fd..1ad24cb48409d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/debug.cpp @@ -18,27 +18,27 @@ #include #include #include -using autoware_motion_utils::createStopVirtualWallMarker; -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerOrientation; -using autoware_universe_utils::createMarkerPosition; -using autoware_universe_utils::createMarkerScale; -using autoware_universe_utils::toMsg; +using autoware::motion_utils::createStopVirtualWallMarker; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerOrientation; +using autoware::universe_utils::createMarkerPosition; +using autoware::universe_utils::createMarkerScale; +using autoware::universe_utils::toMsg; using namespace std::literals::string_literals; namespace autoware::behavior_velocity_planner { namespace { -[[maybe_unused]] autoware_universe_utils::LinearRing3d createCircle( - const autoware_universe_utils::Point3d & p, const double radius, const size_t num_points = 50) +[[maybe_unused]] autoware::universe_utils::LinearRing3d createCircle( + const autoware::universe_utils::Point3d & p, const double radius, const size_t num_points = 50) { - autoware_universe_utils::LinearRing3d ring; // clockwise and closed + autoware::universe_utils::LinearRing3d ring; // clockwise and closed for (size_t i = 0; i < num_points; ++i) { - const double theta = i * (2 * autoware_universe_utils::pi / num_points); + const double theta = i * (2 * autoware::universe_utils::pi / num_points); const double x = p.x() + radius * std::sin(theta); const double y = p.y() + radius * std::cos(theta); ring.emplace_back(x, y, p.z()); @@ -51,13 +51,13 @@ namespace } } // namespace -autoware_motion_utils::VirtualWalls VirtualTrafficLightModule::createVirtualWalls() +autoware::motion_utils::VirtualWalls VirtualTrafficLightModule::createVirtualWalls() { - autoware_motion_utils::VirtualWalls virtual_walls; - autoware_motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWall wall; wall.text = "virtual_traffic_light"; wall.ns = std::to_string(module_id_) + "_"; - wall.style = autoware_motion_utils::VirtualWallType::stop; + wall.style = autoware::motion_utils::VirtualWallType::stop; const auto & d = module_data_; // virtual_wall_stop_line std::vector wall_poses; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp index 1009acaae768b..56f02529ddb3b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp @@ -33,7 +33,7 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::getOrDeclareParameter; +using autoware::universe_utils::getOrDeclareParameter; using lanelet::autoware::VirtualTrafficLight; namespace planning_utils = autoware::behavior_velocity_planner::planning_utils; @@ -49,7 +49,7 @@ VirtualTrafficLightModuleManager::VirtualTrafficLightModuleManager(rclcpp::Node p.dead_line_margin = getOrDeclareParameter(node, ns + ".dead_line_margin"); p.hold_stop_margin_distance = getOrDeclareParameter(node, ns + ".hold_stop_margin_distance"); - p.max_yaw_deviation_rad = autoware_universe_utils::deg2rad( + p.max_yaw_deviation_rad = autoware::universe_utils::deg2rad( getOrDeclareParameter(node, ns + ".max_yaw_deviation_deg")); p.check_timeout_after_stop_line = getOrDeclareParameter(node, ns + ".check_timeout_after_stop_line"); @@ -59,10 +59,10 @@ VirtualTrafficLightModuleManager::VirtualTrafficLightModuleManager(rclcpp::Node void VirtualTrafficLightModuleManager::launchNewModules( const tier4_planning_msgs::msg::PathWithLaneId & path) { - autoware_universe_utils::LineString2d ego_path_linestring; + autoware::universe_utils::LineString2d ego_path_linestring; for (const auto & path_point : path.points) { ego_path_linestring.push_back( - autoware_universe_utils::fromMsg(path_point.point.pose.position).to_2d()); + autoware::universe_utils::fromMsg(path_point.point.pose.position).to_2d()); } for (const auto & m : planning_utils::getRegElemMapOnPath( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp index 9988bbd3f6026..d27cc23223630 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp @@ -27,7 +27,7 @@ namespace autoware::behavior_velocity_planner { namespace { -using autoware_universe_utils::calcDistance2d; +using autoware::universe_utils::calcDistance2d; struct SegmentIndexWithPoint { @@ -46,17 +46,17 @@ tier4_v2x_msgs::msg::KeyValue createKeyValue(const std::string & key, const std: return tier4_v2x_msgs::build().key(key).value(value); } -autoware_universe_utils::LineString3d toAutowarePoints( +autoware::universe_utils::LineString3d toAutowarePoints( const lanelet::ConstLineString3d & line_string) { - autoware_universe_utils::LineString3d output; + autoware::universe_utils::LineString3d output; for (const auto & p : line_string) { output.emplace_back(p.x(), p.y(), p.z()); } return output; } -std::optional toAutowarePoints( +std::optional toAutowarePoints( const lanelet::Optional & line_string) { if (!line_string) { @@ -65,28 +65,28 @@ std::optional toAutowarePoints( return toAutowarePoints(*line_string); } -std::vector toAutowarePoints( +std::vector toAutowarePoints( const lanelet::ConstLineStrings3d & line_strings) { - std::vector output; + std::vector output; for (const auto & line_string : line_strings) { output.emplace_back(toAutowarePoints(line_string)); } return output; } -[[maybe_unused]] autoware_universe_utils::LineString2d to_2d( - const autoware_universe_utils::LineString3d & line_string) +[[maybe_unused]] autoware::universe_utils::LineString2d to_2d( + const autoware::universe_utils::LineString3d & line_string) { - autoware_universe_utils::LineString2d output; + autoware::universe_utils::LineString2d output; for (const auto & p : line_string) { output.emplace_back(p.x(), p.y()); } return output; } -autoware_universe_utils::Point3d calcCenter( - const autoware_universe_utils::LineString3d & line_string) +autoware::universe_utils::Point3d calcCenter( + const autoware::universe_utils::LineString3d & line_string) { const auto p1 = line_string.front(); const auto p2 = line_string.back(); @@ -97,10 +97,10 @@ autoware_universe_utils::Point3d calcCenter( geometry_msgs::msg::Pose calcHeadPose( const geometry_msgs::msg::Pose & base_link_pose, const double base_link_to_front) { - return autoware_universe_utils::calcOffsetPose(base_link_pose, base_link_to_front, 0.0, 0.0); + return autoware::universe_utils::calcOffsetPose(base_link_pose, base_link_to_front, 0.0, 0.0); } -geometry_msgs::msg::Point convertToGeomPoint(const autoware_universe_utils::Point3d & p) +geometry_msgs::msg::Point convertToGeomPoint(const autoware::universe_utils::Point3d & p) { geometry_msgs::msg::Point geom_p; geom_p.x = p.x(); @@ -111,7 +111,7 @@ geometry_msgs::msg::Point convertToGeomPoint(const autoware_universe_utils::Poin template std::optional findLastCollisionBeforeEndLine( - const T & points, const autoware_universe_utils::LineString3d & target_line, + const T & points, const autoware::universe_utils::LineString3d & target_line, const size_t end_line_idx) { const auto target_line_p1 = convertToGeomPoint(target_line.at(0)); @@ -119,8 +119,8 @@ std::optional findLastCollisionBeforeEndLine( for (size_t i = end_line_idx; 0 < i; --i) { // NOTE: size_t can be used since it will not be negative. - const auto & p1 = autoware_universe_utils::getPoint(points.at(i)); - const auto & p2 = autoware_universe_utils::getPoint(points.at(i - 1)); + const auto & p1 = autoware::universe_utils::getPoint(points.at(i)); + const auto & p2 = autoware::universe_utils::getPoint(points.at(i - 1)); const auto collision_point = arc_lane_utils::checkCollision(p1, p2, target_line_p1, target_line_p2); @@ -134,7 +134,7 @@ std::optional findLastCollisionBeforeEndLine( template std::optional findLastCollisionBeforeEndLine( - const T & points, const std::vector & lines, + const T & points, const std::vector & lines, const size_t end_line_idx) { for (const auto & line : lines) { @@ -158,7 +158,7 @@ std::optional insertStopVelocityAtCollision( const SegmentIndexWithPoint & collision, const double offset, tier4_planning_msgs::msg::PathWithLaneId * path) { - const auto collision_offset = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const auto collision_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( path->points, collision.index, collision.point); const auto offset_segment = @@ -410,7 +410,7 @@ bool VirtualTrafficLightModule::isBeforeStartLine(const size_t end_line_idx) const auto & ego_pose = planner_data_->current_odometry->pose; const size_t ego_seg_idx = findEgoSegmentIndex(module_data_.path.points); - const auto signed_arc_length = autoware_motion_utils::calcSignedArcLength( + const auto signed_arc_length = autoware::motion_utils::calcSignedArcLength( module_data_.path.points, ego_pose.position, ego_seg_idx, collision->point, collision_seg_idx) - planner_data_->vehicle_info_.max_longitudinal_offset_m; @@ -433,7 +433,7 @@ bool VirtualTrafficLightModule::isBeforeStopLine(const size_t end_line_idx) const auto & ego_pose = planner_data_->current_odometry->pose; const size_t ego_seg_idx = findEgoSegmentIndex(module_data_.path.points); - const auto signed_arc_length = autoware_motion_utils::calcSignedArcLength( + const auto signed_arc_length = autoware::motion_utils::calcSignedArcLength( module_data_.path.points, ego_pose.position, ego_seg_idx, collision->point, collision_seg_idx) - planner_data_->vehicle_info_.max_longitudinal_offset_m; @@ -461,7 +461,7 @@ bool VirtualTrafficLightModule::isAfterAnyEndLine(const size_t end_line_idx) const auto & ego_pose = planner_data_->current_odometry->pose; const size_t ego_seg_idx = findEgoSegmentIndex(module_data_.path.points); - const auto signed_arc_length = autoware_motion_utils::calcSignedArcLength( + const auto signed_arc_length = autoware::motion_utils::calcSignedArcLength( module_data_.path.points, ego_pose.position, ego_seg_idx, collision->point, collision_seg_idx) - planner_data_->vehicle_info_.max_longitudinal_offset_m; @@ -482,7 +482,7 @@ bool VirtualTrafficLightModule::isNearAnyEndLine(const size_t end_line_idx) const auto & ego_pose = planner_data_->current_odometry->pose; const size_t ego_seg_idx = findEgoSegmentIndex(module_data_.path.points); - const auto signed_arc_length = autoware_motion_utils::calcSignedArcLength( + const auto signed_arc_length = autoware::motion_utils::calcSignedArcLength( module_data_.path.points, ego_pose.position, ego_seg_idx, collision->point, collision_seg_idx) - planner_data_->vehicle_info_.max_longitudinal_offset_m; @@ -544,7 +544,7 @@ void VirtualTrafficLightModule::insertStopVelocityAtStopLine( path->points, collision->point, collision->index); const auto stop_distance = - autoware_motion_utils::calcSignedArcLength( + autoware::motion_utils::calcSignedArcLength( path->points, ego_pose.position, ego_seg_idx, collision.value().point, collision_seg_idx) + offset; const auto is_stopped = planner_data_->isVehicleStopped(); @@ -552,7 +552,7 @@ void VirtualTrafficLightModule::insertStopVelocityAtStopLine( if (stop_distance < planner_param_.hold_stop_margin_distance && is_stopped) { SegmentIndexWithPoint new_collision; const auto ego_pos_on_path = - autoware_motion_utils::calcLongitudinalOffsetPoint(path->points, ego_pose.position, 0.0); + autoware::motion_utils::calcLongitudinalOffsetPoint(path->points, ego_pose.position, 0.0); if (ego_pos_on_path) { new_collision.point = ego_pos_on_path.value(); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp index e26c581ae6777..2e208f344ef4e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp @@ -48,10 +48,10 @@ class VirtualTrafficLightModule : public SceneModuleInterface std::string instrument_type{}; std::string instrument_id{}; std::vector custom_tags{}; - autoware_universe_utils::Point3d instrument_center{}; - std::optional stop_line{}; - autoware_universe_utils::LineString3d start_line{}; - std::vector end_lines{}; + autoware::universe_utils::Point3d instrument_center{}; + std::optional stop_line{}; + autoware::universe_utils::LineString3d start_line{}; + std::vector end_lines{}; }; struct ModuleData @@ -82,7 +82,7 @@ class VirtualTrafficLightModule : public SceneModuleInterface bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; - autoware_motion_utils::VirtualWalls createVirtualWalls() override; + autoware::motion_utils::VirtualWalls createVirtualWalls() override; private: const int64_t lane_id_; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/debug.cpp index e575d6c1b7f03..59a4419087f18 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/debug.cpp @@ -25,14 +25,14 @@ namespace autoware::behavior_velocity_planner { -using autoware_motion_utils::createSlowDownVirtualWallMarker; -using autoware_motion_utils::createStopVirtualWallMarker; -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerScale; -using autoware_universe_utils::createPoint; +using autoware::motion_utils::createSlowDownVirtualWallMarker; +using autoware::motion_utils::createStopVirtualWallMarker; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerScale; +using autoware::universe_utils::createPoint; using visualization_msgs::msg::Marker; namespace @@ -74,14 +74,14 @@ visualization_msgs::msg::MarkerArray createWalkwayMarkers( } } // namespace -autoware_motion_utils::VirtualWalls WalkwayModule::createVirtualWalls() +autoware::motion_utils::VirtualWalls WalkwayModule::createVirtualWalls() { - autoware_motion_utils::VirtualWalls virtual_walls; - autoware_motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWall wall; wall.text = "walkway"; wall.ns = std::to_string(module_id_) + "_"; - wall.style = autoware_motion_utils::VirtualWallType::stop; + wall.style = autoware::motion_utils::VirtualWallType::stop; for (const auto & p : debug_data_.stop_poses) { wall.pose = calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); virtual_walls.push_back(wall); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.cpp index 821e37ae8c618..57763f88910e2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.cpp @@ -26,7 +26,7 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::getOrDeclareParameter; +using autoware::universe_utils::getOrDeclareParameter; using lanelet::autoware::Crosswalk; WalkwayModuleManager::WalkwayModuleManager(rclcpp::Node & node) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp index c876608a93df4..5a64daa0f95fc 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp @@ -22,11 +22,11 @@ namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; -using autoware_motion_utils::calcLongitudinalOffsetPose; -using autoware_motion_utils::calcSignedArcLength; -using autoware_motion_utils::findNearestSegmentIndex; -using autoware_universe_utils::createPoint; -using autoware_universe_utils::getPose; +using autoware::motion_utils::calcLongitudinalOffsetPose; +using autoware::motion_utils::calcSignedArcLength; +using autoware::motion_utils::findNearestSegmentIndex; +using autoware::universe_utils::createPoint; +using autoware::universe_utils::getPose; WalkwayModule::WalkwayModule( const int64_t module_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp index 6ad247720b714..44ca7f0404c54 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp @@ -49,7 +49,7 @@ class WalkwayModule : public SceneModuleInterface bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; - autoware_motion_utils::VirtualWalls createVirtualWalls() override; + autoware::motion_utils::VirtualWalls createVirtualWalls() override; private: const int64_t module_id_; diff --git a/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/debug.cpp b/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/debug.cpp index fca9d3c2ec799..91f44f50e4b53 100644 --- a/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/debug.cpp @@ -25,13 +25,13 @@ namespace autoware::behavior_velocity_planner { -using autoware_motion_utils::createSlowDownVirtualWallMarker; -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerScale; -using autoware_universe_utils::createPoint; +using autoware::motion_utils::createSlowDownVirtualWallMarker; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerScale; +using autoware::universe_utils::createPoint; using visualization_msgs::msg::Marker; namespace @@ -96,15 +96,15 @@ visualization_msgs::msg::MarkerArray createSpeedBumpMarkers( } } // namespace -autoware_motion_utils::VirtualWalls SpeedBumpModule::createVirtualWalls() +autoware::motion_utils::VirtualWalls SpeedBumpModule::createVirtualWalls() { - autoware_motion_utils::VirtualWalls virtual_walls; - autoware_motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWall wall; wall.text = "speed_bump"; wall.ns = std::to_string(module_id_) + "_"; - wall.style = autoware_motion_utils::VirtualWallType::slowdown; + wall.style = autoware::motion_utils::VirtualWallType::slowdown; for (const auto & p : debug_data_.slow_start_poses) { - wall.pose = autoware_universe_utils::calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); + wall.pose = autoware::universe_utils::calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); virtual_walls.push_back(wall); } return virtual_walls; diff --git a/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/manager.cpp b/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/manager.cpp index 2c753f6dd2fd2..9c6546a4748b1 100644 --- a/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/manager.cpp @@ -30,7 +30,7 @@ namespace autoware::behavior_velocity_planner { -using autoware_universe_utils::getOrDeclareParameter; +using autoware::universe_utils::getOrDeclareParameter; using lanelet::autoware::SpeedBump; SpeedBumpModuleManager::SpeedBumpModuleManager(rclcpp::Node & node) diff --git a/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/scene.cpp b/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/scene.cpp index 546aa0369b1f9..f0064a52891db 100644 --- a/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/scene.cpp @@ -22,8 +22,8 @@ namespace autoware::behavior_velocity_planner { -using autoware_motion_utils::calcSignedArcLength; -using autoware_universe_utils::createPoint; +using autoware::motion_utils::calcSignedArcLength; +using autoware::universe_utils::createPoint; using geometry_msgs::msg::Point32; diff --git a/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/scene.hpp b/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/scene.hpp index 504cfa243031e..75a7776d08cad 100644 --- a/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/scene.hpp @@ -59,7 +59,7 @@ class SpeedBumpModule : public SceneModuleInterface bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; - autoware_motion_utils::VirtualWalls createVirtualWalls() override; + autoware::motion_utils::VirtualWalls createVirtualWalls() override; private: int64_t module_id_; diff --git a/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/util.cpp b/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/util.cpp index 1e00c0ac92103..66f57001b3c73 100644 --- a/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/util.cpp +++ b/planning/behavior_velocity_planner/behavior_velocity_speed_bump_module/src/util.cpp @@ -40,11 +40,11 @@ using Point = bg::model::d2::point_xy; using Polygon = bg::model::polygon; using Line = bg::model::linestring; -using autoware_motion_utils::calcLongitudinalOffsetPoint; -using autoware_motion_utils::calcSignedArcLength; -using autoware_motion_utils::findNearestSegmentIndex; -using autoware_motion_utils::insertTargetPoint; -using autoware_universe_utils::createPoint; +using autoware::motion_utils::calcLongitudinalOffsetPoint; +using autoware::motion_utils::calcSignedArcLength; +using autoware::motion_utils::findNearestSegmentIndex; +using autoware::motion_utils::insertTargetPoint; +using autoware::universe_utils::createPoint; PathPolygonIntersectionStatus getPathPolygonIntersectionStatus( const PathWithLaneId & ego_path, const lanelet::BasicPolygon2d & polygon, diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/collision.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/collision.cpp index 783c3f880598f..349108c138650 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/collision.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/collision.cpp @@ -29,7 +29,7 @@ namespace autoware::motion_velocity_planner::dynamic_obstacle_stop std::optional find_closest_collision_point( const EgoData & ego_data, const geometry_msgs::msg::Pose & object_pose, - const autoware_universe_utils::Polygon2d & object_footprint) + const autoware::universe_utils::Polygon2d & object_footprint) { std::optional closest_collision_point; auto closest_dist = std::numeric_limits::max(); @@ -40,15 +40,15 @@ std::optional find_closest_collision_point( const auto traj_idx = rough_collision.second; const auto & ego_footprint = ego_data.trajectory_footprints[traj_idx]; const auto & ego_pose = ego_data.trajectory[traj_idx].pose; - const auto angle_diff = autoware_universe_utils::normalizeRadian( + const auto angle_diff = autoware::universe_utils::normalizeRadian( tf2::getYaw(ego_pose.orientation) - tf2::getYaw(object_pose.orientation)); if (std::abs(angle_diff) > (M_PI_2 + M_PI_4)) { // TODO(Maxime): make this angle a parameter - autoware_universe_utils::MultiPoint2d collision_points; + autoware::universe_utils::MultiPoint2d collision_points; boost::geometry::intersection( object_footprint.outer(), ego_footprint.outer(), collision_points); for (const auto & coll_p : collision_points) { auto p = geometry_msgs::msg::Point().set__x(coll_p.x()).set__y(coll_p.y()); - const auto dist_to_ego = autoware_motion_utils::calcSignedArcLength( + const auto dist_to_ego = autoware::motion_utils::calcSignedArcLength( ego_data.trajectory, ego_data.pose.position, p); if (dist_to_ego < closest_dist) { closest_dist = dist_to_ego; @@ -63,7 +63,7 @@ std::optional find_closest_collision_point( std::vector find_collisions( const EgoData & ego_data, const std::vector & objects, - const autoware_universe_utils::MultiPolygon2d & object_forward_footprints) + const autoware::universe_utils::MultiPolygon2d & object_forward_footprints) { std::vector collisions; for (auto object_idx = 0UL; object_idx < objects.size(); ++object_idx) { @@ -72,7 +72,7 @@ std::vector find_collisions( const auto collision = find_closest_collision_point(ego_data, object_pose, object_footprint); if (collision) { Collision c; - c.object_uuid = autoware_universe_utils::toHexString(objects[object_idx].object_id); + c.object_uuid = autoware::universe_utils::toHexString(objects[object_idx].object_id); c.point = *collision; collisions.push_back(c); } diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/collision.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/collision.hpp index 78413d2faacad..00e87c69d53fa 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/collision.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/collision.hpp @@ -30,7 +30,7 @@ namespace autoware::motion_velocity_planner::dynamic_obstacle_stop /// @return the collision point closest to ego (if any) std::optional find_closest_collision_point( const EgoData & ego_data, const geometry_msgs::msg::Pose & object_pose, - const autoware_universe_utils::Polygon2d & object_footprint); + const autoware::universe_utils::Polygon2d & object_footprint); /// @brief find the earliest collision along the ego trajectory /// @param [in] ego_data ego data including its trajectory and footprint @@ -40,7 +40,7 @@ std::optional find_closest_collision_point( std::vector find_collisions( const EgoData & ego_data, const std::vector & objects, - const autoware_universe_utils::MultiPolygon2d & obstacle_forward_footprints); + const autoware::universe_utils::MultiPolygon2d & obstacle_forward_footprints); } // namespace autoware::motion_velocity_planner::dynamic_obstacle_stop diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/debug.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/debug.cpp index eaa148111dc49..3209a3be028ea 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/debug.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/debug.cpp @@ -59,8 +59,8 @@ std::vector make_collision_markers( marker.ns = ns; marker.id = 0; marker.action = visualization_msgs::msg::Marker::ADD; - marker.scale = autoware_universe_utils::createMarkerScale(0.2, 0.2, 0.5); - marker.color = autoware_universe_utils::createMarkerColor(0.6, 0.0, 0.6, 1.0); + marker.scale = autoware::universe_utils::createMarkerScale(0.2, 0.2, 0.5); + marker.color = autoware::universe_utils::createMarkerColor(0.6, 0.0, 0.6, 1.0); for (const auto & [object_uuid, decision] : object_map) { marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; marker.text = object_uuid.substr(0, 5) + "\n"; @@ -85,7 +85,7 @@ std::vector make_collision_markers( } std::vector make_polygon_markers( - const autoware_universe_utils::MultiPolygon2d & footprints, const std::string & ns, + const autoware::universe_utils::MultiPolygon2d & footprints, const std::string & ns, const double z) { std::vector markers; @@ -96,8 +96,8 @@ std::vector make_polygon_markers( marker.id = 0; marker.type = visualization_msgs::msg::Marker::LINE_STRIP; marker.action = visualization_msgs::msg::Marker::ADD; - marker.scale = autoware_universe_utils::createMarkerScale(0.1, 0.1, 0.1); - marker.color = autoware_universe_utils::createMarkerColor(0.1, 1.0, 0.1, 0.8); + marker.scale = autoware::universe_utils::createMarkerScale(0.1, 0.1, 0.1); + marker.color = autoware::universe_utils::createMarkerColor(0.1, 1.0, 0.1, 0.8); for (const auto & footprint : footprints) { marker.points.clear(); for (const auto & p : footprint.outer()) { diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/debug.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/debug.hpp index 35656acb0b267..2018e3e9c53a0 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/debug.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/debug.hpp @@ -39,7 +39,7 @@ std::vector make_collision_markers( const ObjectStopDecisionMap & object_map, const std::string & ns, const double z, const rclcpp::Time & now); std::vector make_polygon_markers( - const autoware_universe_utils::MultiPolygon2d & footprints, const std::string & ns, + const autoware::universe_utils::MultiPolygon2d & footprints, const std::string & ns, const double z); } // namespace autoware::motion_velocity_planner::dynamic_obstacle_stop::debug diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp index fd8bf467ddc30..fde54a7041672 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp @@ -42,14 +42,14 @@ void DynamicObstacleStopModule::init(rclcpp::Node & node, const std::string & mo module_name_ = module_name; logger_ = node.get_logger().get_child(ns_); clock_ = node.get_clock(); - velocity_factor_interface_.init(autoware_motion_utils::PlanningBehavior::ROUTE_OBSTACLE); + velocity_factor_interface_.init(autoware::motion_utils::PlanningBehavior::ROUTE_OBSTACLE); debug_publisher_ = node.create_publisher("~/" + ns_ + "/debug_markers", 1); virtual_wall_publisher_ = node.create_publisher("~/" + ns_ + "/virtual_walls", 1); - using autoware_universe_utils::getOrDeclareParameter; + using autoware::universe_utils::getOrDeclareParameter; auto & p = params_; p.extra_object_width = getOrDeclareParameter(node, ns_ + ".extra_object_width"); p.minimum_object_velocity = getOrDeclareParameter(node, ns_ + ".minimum_object_velocity"); @@ -72,7 +72,7 @@ void DynamicObstacleStopModule::init(rclcpp::Node & node, const std::string & mo void DynamicObstacleStopModule::update_parameters(const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; auto & p = params_; updateParam(parameters, ns_ + ".extra_object_width", p.extra_object_width); updateParam(parameters, ns_ + ".minimum_object_velocity", p.minimum_object_velocity); @@ -95,26 +95,26 @@ VelocityPlanningResult DynamicObstacleStopModule::plan( debug_data_.reset_data(); if (ego_trajectory_points.size() < 2) return result; - autoware_universe_utils::StopWatch stopwatch; + autoware::universe_utils::StopWatch stopwatch; stopwatch.tic(); stopwatch.tic("preprocessing"); dynamic_obstacle_stop::EgoData ego_data; ego_data.pose = planner_data->current_odometry.pose.pose; ego_data.trajectory = ego_trajectory_points; - autoware_motion_utils::removeOverlapPoints(ego_data.trajectory); + autoware::motion_utils::removeOverlapPoints(ego_data.trajectory); ego_data.first_trajectory_idx = - autoware_motion_utils::findNearestSegmentIndex(ego_data.trajectory, ego_data.pose.position); + autoware::motion_utils::findNearestSegmentIndex(ego_data.trajectory, ego_data.pose.position); ego_data.longitudinal_offset_to_first_trajectory_idx = - autoware_motion_utils::calcLongitudinalOffsetToSegment( + autoware::motion_utils::calcLongitudinalOffsetToSegment( ego_data.trajectory, ego_data.first_trajectory_idx, ego_data.pose.position); - const auto min_stop_distance = autoware_motion_utils::calcDecelDistWithJerkAndAccConstraints( + const auto min_stop_distance = autoware::motion_utils::calcDecelDistWithJerkAndAccConstraints( planner_data->current_odometry.twist.twist.linear.x, 0.0, planner_data->current_acceleration.accel.accel.linear.x, planner_data->velocity_smoother_->getMinDecel(), planner_data->velocity_smoother_->getMaxJerk(), planner_data->velocity_smoother_->getMinJerk()) .value_or(0.0); - ego_data.earliest_stop_pose = autoware_motion_utils::calcLongitudinalOffsetPose( + ego_data.earliest_stop_pose = autoware::motion_utils::calcLongitudinalOffsetPose( ego_data.trajectory, ego_data.pose.position, min_stop_distance); dynamic_obstacle_stop::make_ego_footprint_rtree(ego_data, params_); @@ -141,13 +141,13 @@ VelocityPlanningResult DynamicObstacleStopModule::plan( dynamic_obstacle_stop::find_earliest_collision(object_map_, ego_data); const auto collisions_duration_us = stopwatch.toc("collisions"); if (earliest_collision) { - const auto arc_length_diff = autoware_motion_utils::calcSignedArcLength( + const auto arc_length_diff = autoware::motion_utils::calcSignedArcLength( ego_data.trajectory, *earliest_collision, ego_data.pose.position); const auto can_stop_before_limit = arc_length_diff < min_stop_distance - params_.ego_longitudinal_offset - params_.stop_distance_buffer; const auto stop_pose = can_stop_before_limit - ? autoware_motion_utils::calcLongitudinalOffsetPose( + ? autoware::motion_utils::calcLongitudinalOffsetPose( ego_data.trajectory, *earliest_collision, -params_.stop_distance_buffer - params_.ego_longitudinal_offset) : ego_data.earliest_stop_pose; @@ -156,11 +156,11 @@ VelocityPlanningResult DynamicObstacleStopModule::plan( result.stop_points.push_back(stop_pose->position); const auto stop_pose_reached = planner_data->current_odometry.twist.twist.linear.x < 1e-3 && - autoware_universe_utils::calcDistance2d(ego_data.pose, *stop_pose) < 1e-3; + autoware::universe_utils::calcDistance2d(ego_data.pose, *stop_pose) < 1e-3; velocity_factor_interface_.set( ego_trajectory_points, ego_data.pose, *stop_pose, - stop_pose_reached ? autoware_motion_utils::VelocityFactor::STOPPED - : autoware_motion_utils::VelocityFactor::APPROACHING, + stop_pose_reached ? autoware::motion_utils::VelocityFactor::STOPPED + : autoware::motion_utils::VelocityFactor::APPROACHING, "dynamic_obstacle_stop"); result.velocity_factor = velocity_factor_interface_.get(); create_virtual_walls(); @@ -207,10 +207,10 @@ visualization_msgs::msg::MarkerArray DynamicObstacleStopModule::create_debug_mar void DynamicObstacleStopModule::create_virtual_walls() { if (debug_data_.stop_pose) { - autoware_motion_utils::VirtualWall virtual_wall; + autoware::motion_utils::VirtualWall virtual_wall; virtual_wall.text = "dynamic_obstacle_stop"; virtual_wall.longitudinal_offset = params_.ego_longitudinal_offset; - virtual_wall.style = autoware_motion_utils::VirtualWallType::stop; + virtual_wall.style = autoware::motion_utils::VirtualWallType::stop; virtual_wall.pose = *debug_data_.stop_pose; virtual_wall_marker_creator.add_virtual_wall(virtual_wall); } diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/footprint.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/footprint.cpp index b4f2bdc55cea1..9695146a2ad38 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/footprint.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/footprint.cpp @@ -28,11 +28,11 @@ namespace autoware::motion_velocity_planner::dynamic_obstacle_stop { -autoware_universe_utils::MultiPolygon2d make_forward_footprints( +autoware::universe_utils::MultiPolygon2d make_forward_footprints( const std::vector & obstacles, const PlannerParam & params, const double hysteresis) { - autoware_universe_utils::MultiPolygon2d forward_footprints; + autoware::universe_utils::MultiPolygon2d forward_footprints; for (const auto & obstacle : obstacles) forward_footprints.push_back(project_to_pose( make_forward_footprint(obstacle, params, hysteresis), @@ -40,7 +40,7 @@ autoware_universe_utils::MultiPolygon2d make_forward_footprints( return forward_footprints; } -autoware_universe_utils::Polygon2d make_forward_footprint( +autoware::universe_utils::Polygon2d make_forward_footprint( const autoware_perception_msgs::msg::PredictedObject & obstacle, const PlannerParam & params, const double hysteresis) { @@ -49,7 +49,7 @@ autoware_universe_utils::Polygon2d make_forward_footprint( shape.x / 2.0 + obstacle.kinematics.initial_twist_with_covariance.twist.linear.x * params.time_horizon; const auto lateral_offset = (shape.y + params.extra_object_width) / 2.0 + hysteresis; - return autoware_universe_utils::Polygon2d{ + return autoware::universe_utils::Polygon2d{ {{longitudinal_offset, -lateral_offset}, {longitudinal_offset, lateral_offset}, {shape.x / 2.0, lateral_offset}, @@ -58,12 +58,12 @@ autoware_universe_utils::Polygon2d make_forward_footprint( {}}; } -autoware_universe_utils::Polygon2d project_to_pose( - const autoware_universe_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose) +autoware::universe_utils::Polygon2d project_to_pose( + const autoware::universe_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose) { const auto angle = tf2::getYaw(pose.orientation); - const auto rotated_footprint = autoware_universe_utils::rotatePolygon(base_footprint, angle); - autoware_universe_utils::Polygon2d footprint; + const auto rotated_footprint = autoware::universe_utils::rotatePolygon(base_footprint, angle); + autoware::universe_utils::Polygon2d footprint; for (const auto & p : rotated_footprint.outer()) footprint.outer().emplace_back(p.x() + pose.position.x, p.y() + pose.position.y); return footprint; @@ -72,10 +72,10 @@ autoware_universe_utils::Polygon2d project_to_pose( void make_ego_footprint_rtree(EgoData & ego_data, const PlannerParam & params) { for (const auto & p : ego_data.trajectory) - ego_data.trajectory_footprints.push_back(autoware_universe_utils::toFootprint( + ego_data.trajectory_footprints.push_back(autoware::universe_utils::toFootprint( p.pose, params.ego_longitudinal_offset, 0.0, params.ego_lateral_offset * 2.0)); for (auto i = 0UL; i < ego_data.trajectory_footprints.size(); ++i) { - const auto box = boost::geometry::return_envelope( + const auto box = boost::geometry::return_envelope( ego_data.trajectory_footprints[i]); ego_data.rtree.insert(std::make_pair(box, i)); } diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/footprint.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/footprint.hpp index 85a736869a7f8..01a112f85f4d9 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/footprint.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/footprint.hpp @@ -29,7 +29,7 @@ namespace autoware::motion_velocity_planner::dynamic_obstacle_stop /// @param [in] params parameters used to create the footprint /// @param [in] hysteresis [m] extra lateral distance to add to the footprints /// @return forward footprint of the obstacle -autoware_universe_utils::MultiPolygon2d make_forward_footprints( +autoware::universe_utils::MultiPolygon2d make_forward_footprints( const std::vector & obstacles, const PlannerParam & params, const double hysteresis); /// @brief create the footprint of the given obstacle and its projection over a fixed time horizon @@ -37,15 +37,16 @@ autoware_universe_utils::MultiPolygon2d make_forward_footprints( /// @param [in] params parameters used to create the footprint /// @param [in] hysteresis [m] extra lateral distance to add to the footprint /// @return forward footprint of the obstacle -autoware_universe_utils::Polygon2d make_forward_footprint( +autoware::universe_utils::Polygon2d make_forward_footprint( const autoware_perception_msgs::msg::PredictedObject & obstacle, const PlannerParam & params, const double hysteresis); /// @brief project a footprint to the given pose /// @param [in] base_footprint footprint to project /// @param [in] pose projection pose /// @return footprint projected to the given pose -autoware_universe_utils::Polygon2d project_to_pose( - const autoware_universe_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose); +autoware::universe_utils::Polygon2d project_to_pose( + const autoware::universe_utils::Polygon2d & base_footprint, + const geometry_msgs::msg::Pose & pose); /// @brief create the rtree indexing the ego footprint along the trajectory /// @param [inout] ego_data ego data with its trajectory and the rtree to populate /// @param [in] params parameters diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp index d227c2ae5d20c..0b78aa9707f53 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp @@ -46,13 +46,13 @@ std::vector filter_predicted_obj }) != o.classification.end(); }; const auto is_in_range = [&](const auto & o) { - const auto distance = std::abs(autoware_motion_utils::calcLateralOffset( + const auto distance = std::abs(autoware::motion_utils::calcLateralOffset( ego_data.trajectory, o.kinematics.initial_pose_with_covariance.pose.position)); return distance <= params.minimum_object_distance_from_ego_trajectory + params.ego_lateral_offset + o.shape.dimensions.y / 2.0 + hysteresis; }; const auto is_not_too_close = [&](const auto & o) { - const auto obj_arc_length = autoware_motion_utils::calcSignedArcLength( + const auto obj_arc_length = autoware::motion_utils::calcSignedArcLength( ego_data.trajectory, ego_data.pose.position, o.kinematics.initial_pose_with_covariance.pose.position); return obj_arc_length > ego_data.longitudinal_offset_to_first_trajectory_idx + @@ -62,7 +62,7 @@ std::vector filter_predicted_obj const auto & o_pose = o.kinematics.initial_pose_with_covariance.pose; const auto o_yaw = tf2::getYaw(o_pose.orientation); const auto ego_yaw = tf2::getYaw(ego_data.pose.orientation); - const auto yaw_diff = std::abs(autoware_universe_utils::normalizeRadian(o_yaw - ego_yaw)); + const auto yaw_diff = std::abs(autoware::universe_utils::normalizeRadian(o_yaw - ego_yaw)); const auto opposite_heading = yaw_diff > M_PI_2 + M_PI_4; const auto collision_distance_threshold = params.ego_lateral_offset + o.shape.dimensions.y / 2.0 + params.hysteresis; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp index f60349fbf7b9f..3f544c792d8e6 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp @@ -29,7 +29,7 @@ void update_object_map( if (auto search = object_map.find(collision.object_uuid); search != object_map.end()) { search->second.collision_detected = true; const auto is_closer_collision_point = - autoware_motion_utils::calcSignedArcLength( + autoware::motion_utils::calcSignedArcLength( trajectory, search->second.collision_point, collision.point) < 0.0; if (is_closer_collision_point) search->second.collision_point = collision.point; } else { @@ -53,7 +53,7 @@ std::optional find_earliest_collision( double earliest_collision_arc_length = std::numeric_limits::max(); for (auto & [object_uuid, decision] : object_map) { if (decision.should_be_avoided()) { - const auto arc_length = autoware_motion_utils::calcSignedArcLength( + const auto arc_length = autoware::motion_utils::calcSignedArcLength( ego_data.trajectory, ego_data.pose.position, decision.collision_point); if (arc_length < earliest_collision_arc_length) { earliest_collision_arc_length = arc_length; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/types.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/types.hpp index 0a286112010a7..294b789a679aa 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/types.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/types.hpp @@ -32,7 +32,7 @@ namespace autoware::motion_velocity_planner::dynamic_obstacle_stop { using TrajectoryPoints = std::vector; -using BoxIndexPair = std::pair; +using BoxIndexPair = std::pair; using Rtree = boost::geometry::index::rtree>; /// @brief parameters for the "out of lane" module @@ -57,7 +57,7 @@ struct EgoData size_t first_trajectory_idx{}; double longitudinal_offset_to_first_trajectory_idx; // [m] geometry_msgs::msg::Pose pose; - autoware_universe_utils::MultiPolygon2d trajectory_footprints; + autoware::universe_utils::MultiPolygon2d trajectory_footprints; Rtree rtree; std::optional earliest_stop_pose; }; @@ -65,9 +65,9 @@ struct EgoData /// @brief debug data struct DebugData { - autoware_universe_utils::MultiPolygon2d obstacle_footprints{}; + autoware::universe_utils::MultiPolygon2d obstacle_footprints{}; size_t prev_dynamic_obstacles_nb{}; - autoware_universe_utils::MultiPolygon2d ego_footprints{}; + autoware::universe_utils::MultiPolygon2d ego_footprints{}; size_t prev_ego_footprints_nb{}; std::optional stop_pose{}; size_t prev_collisions_nb{}; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.cpp index 21dfadbe11e8a..945b94782023b 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.cpp @@ -120,7 +120,7 @@ std::vector calculate_slowd TrajectoryPoints & trajectory, const CollisionChecker & collision_checker, const std::vector & projections, const std::vector & footprints, ProjectionParameters & projection_params, const VelocityParameters & velocity_params, - autoware_motion_utils::VirtualWalls & virtual_walls) + autoware::motion_utils::VirtualWalls & virtual_walls) { std::vector slowdown_intervals; double time = 0.0; @@ -129,7 +129,7 @@ std::vector calculate_slowd if (i > 0) { const auto & prev_point = trajectory[i - 1]; time += static_cast( - autoware_universe_utils::calcDistance2d(prev_point, trajectory_point) / + autoware::universe_utils::calcDistance2d(prev_point, trajectory_point) / prev_point.longitudinal_velocity_mps); } // First linestring is used to calculate distance @@ -150,7 +150,7 @@ std::vector calculate_slowd static_cast(*dist_to_collision - projection_params.extra_length), static_cast(projection_params.duration), velocity_params.min_velocity))); - autoware_motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWall wall; wall.pose = trajectory_point.pose; virtual_walls.push_back(wall); } diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.hpp index dc250af55df0b..aeeaabeb9b510 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.hpp @@ -122,7 +122,7 @@ std::vector calculate_slowd TrajectoryPoints & trajectory, const CollisionChecker & collision_checker, const std::vector & projections, const std::vector & footprints, ProjectionParameters & projection_params, const VelocityParameters & velocity_params, - autoware_motion_utils::VirtualWalls & virtual_walls); + autoware::motion_utils::VirtualWalls & virtual_walls); /// @brief copy the velocity profile of a downsampled trajectory to the original trajectory /// @param[in] downsampled_trajectory downsampled trajectory diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp index 1f621d935de38..2b78a2f1495bf 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp @@ -46,7 +46,7 @@ void ObstacleVelocityLimiterModule::init(rclcpp::Node & node, const std::string projection_params_ = obstacle_velocity_limiter::ProjectionParameters(node); obstacle_params_ = obstacle_velocity_limiter::ObstacleParameters(node); velocity_params_ = obstacle_velocity_limiter::VelocityParameters(node); - velocity_factor_interface_.init(autoware_motion_utils::PlanningBehavior::ROUTE_OBSTACLE); + velocity_factor_interface_.init(autoware::motion_utils::PlanningBehavior::ROUTE_OBSTACLE); debug_publisher_ = node.create_publisher("~/" + ns_ + "/debug_markers", 1); @@ -132,11 +132,11 @@ VelocityPlanningResult ObstacleVelocityLimiterModule::plan( const std::vector & ego_trajectory_points, const std::shared_ptr planner_data) { - autoware_universe_utils::StopWatch stopwatch; + autoware::universe_utils::StopWatch stopwatch; stopwatch.tic(); VelocityPlanningResult result; stopwatch.tic("preprocessing"); - const auto ego_idx = autoware_motion_utils::findNearestIndex( + const auto ego_idx = autoware::motion_utils::findNearestIndex( ego_trajectory_points, planner_data->current_odometry.pose.pose); if (!ego_idx) { RCLCPP_WARN_THROTTLE( @@ -183,7 +183,7 @@ VelocityPlanningResult ObstacleVelocityLimiterModule::plan( obstacle_params_); } const auto obstacles_us = stopwatch.toc("obstacles"); - autoware_motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWalls virtual_walls; stopwatch.tic("slowdowns"); result.slowdown_intervals = obstacle_velocity_limiter::calculate_slowdown_intervals( downsampled_traj_points, @@ -195,7 +195,7 @@ VelocityPlanningResult ObstacleVelocityLimiterModule::plan( for (auto & wall : virtual_walls) { wall.longitudinal_offset = vehicle_front_offset_; wall.text = ns_; - wall.style = autoware_motion_utils::VirtualWallType::slowdown; + wall.style = autoware::motion_utils::VirtualWallType::slowdown; } virtual_wall_marker_creator.add_virtual_walls(virtual_walls); virtual_wall_publisher_->publish(virtual_wall_marker_creator.create_markers(clock_->now())); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.cpp index 430c19c3d35ff..7498568be99fb 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/trajectory_preprocessing.cpp @@ -31,7 +31,7 @@ size_t calculateStartIndex( auto dist = 0.0; auto idx = ego_idx; while (idx + 1 < trajectory.size() && dist < start_distance) { - dist += autoware_universe_utils::calcDistance2d(trajectory[idx], trajectory[idx + 1]); + dist += autoware::universe_utils::calcDistance2d(trajectory[idx], trajectory[idx + 1]); ++idx; } return idx; @@ -46,7 +46,7 @@ size_t calculateEndIndex( auto idx = start_idx; while (idx + 1 < trajectory.size() && length < max_length && duration < max_duration) { const auto length_d = - autoware_universe_utils::calcDistance2d(trajectory[idx], trajectory[idx + 1]); + autoware::universe_utils::calcDistance2d(trajectory[idx], trajectory[idx + 1]); length += length_d; if (trajectory[idx].longitudinal_velocity_mps > 0.0) duration += length_d / trajectory[idx].longitudinal_velocity_mps; @@ -74,7 +74,7 @@ void calculateSteeringAngles(TrajectoryPoints & trajectory, const double wheel_b for (auto i = 1ul; i < trajectory.size(); ++i) { const auto & prev_point = trajectory[i - 1]; auto & point = trajectory[i]; - const auto dt = autoware_universe_utils::calcDistance2d(prev_point, point) / + const auto dt = autoware::universe_utils::calcDistance2d(prev_point, point) / prev_point.longitudinal_velocity_mps; t += dt; const auto heading = tf2::getYaw(point.pose.orientation); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/types.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/types.hpp index dcab3d8d1bcac..bd707402ce169 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/types.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/types.hpp @@ -35,13 +35,13 @@ using nav_msgs::msg::OccupancyGrid; using PointCloud = pcl::PointCloud; using TrajectoryPoints = std::vector; -using point_t = autoware_universe_utils::Point2d; -using multipoint_t = autoware_universe_utils::MultiPoint2d; -using polygon_t = autoware_universe_utils::Polygon2d; -using multi_polygon_t = autoware_universe_utils::MultiPolygon2d; -using segment_t = autoware_universe_utils::Segment2d; -using linestring_t = autoware_universe_utils::LineString2d; -using multi_linestring_t = autoware_universe_utils::MultiLineString2d; +using point_t = autoware::universe_utils::Point2d; +using multipoint_t = autoware::universe_utils::MultiPoint2d; +using polygon_t = autoware::universe_utils::Polygon2d; +using multi_polygon_t = autoware::universe_utils::MultiPolygon2d; +using segment_t = autoware::universe_utils::Segment2d; +using linestring_t = autoware::universe_utils::LineString2d; +using multi_linestring_t = autoware::universe_utils::MultiLineString2d; struct ObstacleMasks { diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_collision_distance.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_collision_distance.cpp index 0112de62f3950..ac07c62f62cf7 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_collision_distance.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_collision_distance.cpp @@ -400,7 +400,7 @@ TEST(TestCollisionDistance, createObjPolygons) object1.kinematics.initial_pose_with_covariance.pose.position.x = 0.0; object1.kinematics.initial_pose_with_covariance.pose.position.y = 0.0; object1.kinematics.initial_pose_with_covariance.pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(0.0); + autoware::universe_utils::createQuaternionFromYaw(0.0); object1.kinematics.initial_twist_with_covariance.twist.linear.x = 0.0; object1.shape.dimensions.x = 1.0; object1.shape.dimensions.y = 1.0; @@ -427,7 +427,7 @@ TEST(TestCollisionDistance, createObjPolygons) object2.kinematics.initial_pose_with_covariance.pose.position.x = 10.0; object2.kinematics.initial_pose_with_covariance.pose.position.y = 10.0; object2.kinematics.initial_pose_with_covariance.pose.orientation = - autoware_universe_utils::createQuaternionFromYaw(M_PI_2); + autoware::universe_utils::createQuaternionFromYaw(M_PI_2); object2.kinematics.initial_twist_with_covariance.twist.linear.x = 2.0; object2.shape.dimensions.x = 2.0; object2.shape.dimensions.y = 1.0; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp index 8ae3005c03b98..0c793c9f5798e 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp @@ -30,7 +30,7 @@ bool can_decelerate( const EgoData & ego_data, const TrajectoryPoint & point, const double target_vel) { // TODO(Maxime): use the library function - const auto dist_ahead_of_ego = autoware_motion_utils::calcSignedArcLength( + const auto dist_ahead_of_ego = autoware::motion_utils::calcSignedArcLength( ego_data.trajectory_points, ego_data.pose.position, point.pose.position); const auto acc_to_target_vel = (ego_data.velocity * ego_data.velocity - target_vel * target_vel) / (2 * dist_ahead_of_ego); @@ -39,18 +39,18 @@ bool can_decelerate( std::optional calculate_last_in_lane_pose( const EgoData & ego_data, const Slowdown & decision, - const autoware_universe_utils::Polygon2d & footprint, + const autoware::universe_utils::Polygon2d & footprint, const std::optional & prev_slowdown_point, const PlannerParam & params) { - const auto from_arc_length = autoware_motion_utils::calcSignedArcLength( + const auto from_arc_length = autoware::motion_utils::calcSignedArcLength( ego_data.trajectory_points, 0, ego_data.first_trajectory_idx); - const auto to_arc_length = autoware_motion_utils::calcSignedArcLength( + const auto to_arc_length = autoware::motion_utils::calcSignedArcLength( ego_data.trajectory_points, 0, decision.target_trajectory_idx); TrajectoryPoint interpolated_point; for (auto l = to_arc_length - params.precision; l > from_arc_length; l -= params.precision) { // TODO(Maxime): binary search interpolated_point.pose = - autoware_motion_utils::calcInterpolatedPose(ego_data.trajectory_points, l); + autoware::motion_utils::calcInterpolatedPose(ego_data.trajectory_points, l); const auto respect_decel_limit = !params.skip_if_over_max_decel || prev_slowdown_point || can_decelerate(ego_data, interpolated_point, decision.velocity); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp index 47ea84dd74a06..ee4897de86c5b 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp @@ -42,7 +42,7 @@ bool can_decelerate( /// @return the last pose that is not out of lane (if found) std::optional calculate_last_in_lane_pose( const EgoData & ego_data, const Slowdown & decision, - const autoware_universe_utils::Polygon2d & footprint, + const autoware::universe_utils::Polygon2d & footprint, const std::optional & prev_slowdown_point, const PlannerParam & params); /// @brief calculate the slowdown point to insert in the trajectory diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp index 3585ed9339f2c..d9a85e266f790 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp @@ -36,10 +36,10 @@ visualization_msgs::msg::Marker get_base_marker() base_marker.id = 0; base_marker.type = visualization_msgs::msg::Marker::LINE_STRIP; base_marker.action = visualization_msgs::msg::Marker::ADD; - base_marker.pose.position = autoware_universe_utils::createMarkerPosition(0.0, 0.0, 0); - base_marker.pose.orientation = autoware_universe_utils::createMarkerOrientation(0, 0, 0, 1.0); - base_marker.scale = autoware_universe_utils::createMarkerScale(0.1, 0.1, 0.1); - base_marker.color = autoware_universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); + base_marker.pose.position = autoware::universe_utils::createMarkerPosition(0.0, 0.0, 0); + base_marker.pose.orientation = autoware::universe_utils::createMarkerOrientation(0, 0, 0, 1.0); + base_marker.scale = autoware::universe_utils::createMarkerScale(0.1, 0.1, 0.1); + base_marker.color = autoware::universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); return base_marker; } void add_footprint_markers( @@ -52,7 +52,7 @@ void add_footprint_markers( debug_marker.points.clear(); for (const auto & p : f) debug_marker.points.push_back( - autoware_universe_utils::createMarkerPosition(p.x(), p.y(), z + 0.5)); + autoware::universe_utils::createMarkerPosition(p.x(), p.y(), z + 0.5)); debug_marker.points.push_back(debug_marker.points.front()); debug_marker_array.markers.push_back(debug_marker); debug_marker.id++; @@ -71,19 +71,19 @@ void add_current_overlap_marker( debug_marker.ns = "current_overlap"; debug_marker.points.clear(); for (const auto & p : current_footprint) - debug_marker.points.push_back(autoware_universe_utils::createMarkerPosition(p.x(), p.y(), z)); + debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition(p.x(), p.y(), z)); if (!debug_marker.points.empty()) debug_marker.points.push_back(debug_marker.points.front()); if (current_overlapped_lanelets.empty()) - debug_marker.color = autoware_universe_utils::createMarkerColor(0.1, 1.0, 0.1, 0.5); + debug_marker.color = autoware::universe_utils::createMarkerColor(0.1, 1.0, 0.1, 0.5); else - debug_marker.color = autoware_universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); + debug_marker.color = autoware::universe_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); debug_marker_array.markers.push_back(debug_marker); debug_marker.id++; for (const auto & ll : current_overlapped_lanelets) { debug_marker.points.clear(); for (const auto & p : ll.polygon3d()) debug_marker.points.push_back( - autoware_universe_utils::createMarkerPosition(p.x(), p.y(), p.z() + 0.5)); + autoware::universe_utils::createMarkerPosition(p.x(), p.y(), p.z() + 0.5)); debug_marker.points.push_back(debug_marker.points.front()); debug_marker_array.markers.push_back(debug_marker); debug_marker.id++; @@ -106,7 +106,7 @@ void add_lanelet_markers( // add a small z offset to draw above the lanelet map for (const auto & p : ll.polygon3d()) debug_marker.points.push_back( - autoware_universe_utils::createMarkerPosition(p.x(), p.y(), p.z() + 0.1)); + autoware::universe_utils::createMarkerPosition(p.x(), p.y(), p.z() + 0.1)); debug_marker.points.push_back(debug_marker.points.front()); debug_marker_array.markers.push_back(debug_marker); debug_marker.id++; @@ -123,20 +123,20 @@ void add_range_markers( { auto debug_marker = get_base_marker(); debug_marker.ns = "ranges"; - debug_marker.color = autoware_universe_utils::createMarkerColor(0.2, 0.9, 0.1, 0.5); + debug_marker.color = autoware::universe_utils::createMarkerColor(0.2, 0.9, 0.1, 0.5); for (const auto & range : ranges) { debug_marker.points.clear(); debug_marker.points.push_back( trajectory_points[first_ego_idx + range.entering_trajectory_idx].pose.position); - debug_marker.points.push_back(autoware_universe_utils::createMarkerPosition( + debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( range.entering_point.x(), range.entering_point.y(), z)); for (const auto & overlap : range.debug.overlaps) { - debug_marker.points.push_back(autoware_universe_utils::createMarkerPosition( + debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( overlap.min_overlap_point.x(), overlap.min_overlap_point.y(), z)); - debug_marker.points.push_back(autoware_universe_utils::createMarkerPosition( + debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( overlap.max_overlap_point.x(), overlap.max_overlap_point.y(), z)); } - debug_marker.points.push_back(autoware_universe_utils::createMarkerPosition( + debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( range.exiting_point.x(), range.exiting_point.y(), z)); debug_marker.points.push_back( trajectory_points[first_ego_idx + range.exiting_trajectory_idx].pose.position); @@ -156,12 +156,12 @@ void add_decision_markers( debug_marker.action = debug_marker.ADD; debug_marker.id = 0; debug_marker.ns = "decisions"; - debug_marker.color = autoware_universe_utils::createMarkerColor(0.9, 0.1, 0.1, 1.0); + debug_marker.color = autoware::universe_utils::createMarkerColor(0.9, 0.1, 0.1, 1.0); debug_marker.points.clear(); for (const auto & range : ranges) { debug_marker.type = debug_marker.LINE_STRIP; if (range.debug.decision) { - debug_marker.points.push_back(autoware_universe_utils::createMarkerPosition( + debug_marker.points.push_back(autoware::universe_utils::createMarkerPosition( range.entering_point.x(), range.entering_point.y(), z)); debug_marker.points.push_back( range.debug.object->kinematics.initial_pose_with_covariance.pose.position); @@ -210,15 +210,16 @@ visualization_msgs::msg::MarkerArray create_debug_marker_array(const DebugData & debug_data.prev_current_overlapped_lanelets); debug::add_lanelet_markers( debug_marker_array, debug_data.trajectory_lanelets, "trajectory_lanelets", - autoware_universe_utils::createMarkerColor(0.1, 0.1, 1.0, 0.5), + autoware::universe_utils::createMarkerColor(0.1, 0.1, 1.0, 0.5), debug_data.prev_trajectory_lanelets); debug::add_lanelet_markers( debug_marker_array, debug_data.ignored_lanelets, "ignored_lanelets", - autoware_universe_utils::createMarkerColor(0.7, 0.7, 0.2, 0.5), + autoware::universe_utils::createMarkerColor(0.7, 0.7, 0.2, 0.5), debug_data.prev_ignored_lanelets); debug::add_lanelet_markers( debug_marker_array, debug_data.other_lanelets, "other_lanelets", - autoware_universe_utils::createMarkerColor(0.4, 0.4, 0.7, 0.5), debug_data.prev_other_lanelets); + autoware::universe_utils::createMarkerColor(0.4, 0.4, 0.7, 0.5), + debug_data.prev_other_lanelets); debug::add_range_markers( debug_marker_array, debug_data.ranges, debug_data.trajectory_points, debug_data.first_trajectory_idx, z, debug_data.prev_ranges); @@ -226,14 +227,14 @@ visualization_msgs::msg::MarkerArray create_debug_marker_array(const DebugData & return debug_marker_array; } -autoware_motion_utils::VirtualWalls create_virtual_walls( +autoware::motion_utils::VirtualWalls create_virtual_walls( const DebugData & debug_data, const PlannerParam & params) { - autoware_motion_utils::VirtualWalls virtual_walls; - autoware_motion_utils::VirtualWall wall; + autoware::motion_utils::VirtualWalls virtual_walls; + autoware::motion_utils::VirtualWall wall; wall.text = "out_of_lane"; wall.longitudinal_offset = params.front_offset; - wall.style = autoware_motion_utils::VirtualWallType::slowdown; + wall.style = autoware::motion_utils::VirtualWallType::slowdown; for (const auto & slowdown : debug_data.slowdowns) { wall.pose = slowdown.point.pose; virtual_walls.push_back(wall); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp index 02f66a27079ae..ea225442443c8 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp @@ -24,7 +24,7 @@ namespace autoware::motion_velocity_planner::out_of_lane::debug { visualization_msgs::msg::MarkerArray create_debug_marker_array(const DebugData & debug_data); -autoware_motion_utils::VirtualWalls create_virtual_walls( +autoware::motion_utils::VirtualWalls create_virtual_walls( const DebugData & debug_data, const PlannerParam & params); } // namespace autoware::motion_velocity_planner::out_of_lane::debug diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp index 667bd714a848f..fc487a2626b88 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp @@ -33,7 +33,7 @@ namespace autoware::motion_velocity_planner::out_of_lane { double distance_along_trajectory(const EgoData & ego_data, const size_t target_idx) { - return autoware_motion_utils::calcSignedArcLength( + return autoware::motion_utils::calcSignedArcLength( ego_data.trajectory_points, ego_data.pose.position, ego_data.first_trajectory_idx + target_idx); } @@ -80,18 +80,19 @@ std::optional> object_time_to_range( auto worst_exit_time = std::optional(); for (const auto & predicted_path : object.kinematics.predicted_paths) { - const auto unique_path_points = autoware_motion_utils::removeOverlapPoints(predicted_path.path); + const auto unique_path_points = + autoware::motion_utils::removeOverlapPoints(predicted_path.path); if (unique_path_points.size() < 2) continue; const auto time_step = rclcpp::Duration(predicted_path.time_step).seconds(); const auto enter_point = geometry_msgs::msg::Point().set__x(range.entering_point.x()).set__y(range.entering_point.y()); const auto enter_segment_idx = - autoware_motion_utils::findNearestSegmentIndex(unique_path_points, enter_point); - const auto enter_offset = autoware_motion_utils::calcLongitudinalOffsetToSegment( + autoware::motion_utils::findNearestSegmentIndex(unique_path_points, enter_point); + const auto enter_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( unique_path_points, enter_segment_idx, enter_point); - const auto enter_lat_dist = std::abs( - autoware_motion_utils::calcLateralOffset(unique_path_points, enter_point, enter_segment_idx)); - const auto enter_segment_length = autoware_universe_utils::calcDistance2d( + const auto enter_lat_dist = std::abs(autoware::motion_utils::calcLateralOffset( + unique_path_points, enter_point, enter_segment_idx)); + const auto enter_segment_length = autoware::universe_utils::calcDistance2d( unique_path_points[enter_segment_idx], unique_path_points[enter_segment_idx + 1]); const auto enter_offset_ratio = enter_offset / enter_segment_length; const auto enter_time = @@ -100,12 +101,12 @@ std::optional> object_time_to_range( const auto exit_point = geometry_msgs::msg::Point().set__x(range.exiting_point.x()).set__y(range.exiting_point.y()); const auto exit_segment_idx = - autoware_motion_utils::findNearestSegmentIndex(unique_path_points, exit_point); - const auto exit_offset = autoware_motion_utils::calcLongitudinalOffsetToSegment( + autoware::motion_utils::findNearestSegmentIndex(unique_path_points, exit_point); + const auto exit_offset = autoware::motion_utils::calcLongitudinalOffsetToSegment( unique_path_points, exit_segment_idx, exit_point); const auto exit_lat_dist = std::abs( - autoware_motion_utils::calcLateralOffset(unique_path_points, exit_point, exit_segment_idx)); - const auto exit_segment_length = autoware_universe_utils::calcDistance2d( + autoware::motion_utils::calcLateralOffset(unique_path_points, exit_point, exit_segment_idx)); + const auto exit_segment_length = autoware::universe_utils::calcDistance2d( unique_path_points[exit_segment_idx], unique_path_points[exit_segment_idx + 1]); const auto exit_offset_ratio = exit_offset / static_cast(exit_segment_length); const auto exit_time = @@ -314,7 +315,7 @@ bool should_not_enter( for (const auto & object : inputs.objects.objects) { RCLCPP_DEBUG( logger, "\t\t[%s] going at %2.2fm/s", - autoware_universe_utils::toHexString(object.object_id).c_str(), + autoware::universe_utils::toHexString(object.object_id).c_str(), object.kinematics.initial_twist_with_covariance.twist.linear.x); if (object.kinematics.initial_twist_with_covariance.twist.linear.x < params.objects_min_vel) { RCLCPP_DEBUG(logger, " SKIP (velocity bellow threshold %2.2fm/s)\n", params.objects_min_vel); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp index b864d6d0eb56f..ecc10df43c792 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp @@ -50,7 +50,7 @@ void cut_predicted_path_beyond_line( auto cut_idx = stop_line_idx; double arc_length = 0; while (cut_idx > 0 && arc_length < object_front_overhang) { - arc_length += autoware_universe_utils::calcDistance2d( + arc_length += autoware::universe_utils::calcDistance2d( predicted_path.path[cut_idx], predicted_path.path[cut_idx - 1]); --cut_idx; } @@ -114,10 +114,10 @@ autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( auto filtered_object = object; const auto is_invalid_predicted_path = [&](const auto & predicted_path) { const auto is_low_confidence = predicted_path.confidence < params.objects_min_confidence; - const auto no_overlap_path = autoware_motion_utils::removeOverlapPoints(predicted_path.path); + const auto no_overlap_path = autoware::motion_utils::removeOverlapPoints(predicted_path.path); if (no_overlap_path.size() <= 1) return true; - const auto lat_offset_to_current_ego = - std::abs(autoware_motion_utils::calcLateralOffset(no_overlap_path, ego_data.pose.position)); + const auto lat_offset_to_current_ego = std::abs( + autoware::motion_utils::calcLateralOffset(no_overlap_path, ego_data.pose.position)); const auto is_crossing_ego = lat_offset_to_current_ego <= object.shape.dimensions.y / 2.0 + std::max( diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp index f411485a0750f..f5d68c4fa9bba 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp @@ -26,10 +26,10 @@ namespace autoware::motion_velocity_planner::out_of_lane { -autoware_universe_utils::Polygon2d make_base_footprint( +autoware::universe_utils::Polygon2d make_base_footprint( const PlannerParam & p, const bool ignore_offset) { - autoware_universe_utils::Polygon2d base_footprint; + autoware::universe_utils::Polygon2d base_footprint; const auto front_offset = ignore_offset ? 0.0 : p.extra_front_offset; const auto rear_offset = ignore_offset ? 0.0 : p.extra_rear_offset; const auto right_offset = ignore_offset ? 0.0 : p.extra_right_offset; @@ -43,10 +43,10 @@ autoware_universe_utils::Polygon2d make_base_footprint( } lanelet::BasicPolygon2d project_to_pose( - const autoware_universe_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose) + const autoware::universe_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose) { const auto angle = tf2::getYaw(pose.orientation); - const auto rotated_footprint = autoware_universe_utils::rotatePolygon(base_footprint, angle); + const auto rotated_footprint = autoware::universe_utils::rotatePolygon(base_footprint, angle); lanelet::BasicPolygon2d footprint; for (const auto & p : rotated_footprint.outer()) footprint.emplace_back(p.x() + pose.position.x, p.y() + pose.position.y); @@ -66,14 +66,14 @@ std::vector calculate_trajectory_footprints( i < ego_data.trajectory_points.size() && length < range; ++i) { const auto & trajectory_pose = ego_data.trajectory_points[i].pose; const auto angle = tf2::getYaw(trajectory_pose.orientation); - const auto rotated_footprint = autoware_universe_utils::rotatePolygon(base_footprint, angle); + const auto rotated_footprint = autoware::universe_utils::rotatePolygon(base_footprint, angle); lanelet::BasicPolygon2d footprint; for (const auto & p : rotated_footprint.outer()) footprint.emplace_back( p.x() + trajectory_pose.position.x, p.y() + trajectory_pose.position.y); trajectory_footprints.push_back(footprint); if (i + 1 < ego_data.trajectory_points.size()) - length += autoware_universe_utils::calcDistance2d( + length += autoware::universe_utils::calcDistance2d( trajectory_pose, ego_data.trajectory_points[i + 1].pose); } return trajectory_footprints; @@ -84,7 +84,7 @@ lanelet::BasicPolygon2d calculate_current_ego_footprint( { const auto base_footprint = make_base_footprint(params, ignore_offset); const auto angle = tf2::getYaw(ego_data.pose.orientation); - const auto rotated_footprint = autoware_universe_utils::rotatePolygon(base_footprint, angle); + const auto rotated_footprint = autoware::universe_utils::rotatePolygon(base_footprint, angle); lanelet::BasicPolygon2d footprint; for (const auto & p : rotated_footprint.outer()) footprint.emplace_back(p.x() + ego_data.pose.position.x, p.y() + ego_data.pose.position.y); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp index bbcdd7b84dd18..ebe7ab0fa9d7f 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp @@ -30,14 +30,15 @@ namespace out_of_lane /// @param [in] ignore_offset optional parameter, if true, ignore the "extra offsets" to build the /// footprint /// @return base ego footprint -autoware_universe_utils::Polygon2d make_base_footprint( +autoware::universe_utils::Polygon2d make_base_footprint( const PlannerParam & p, const bool ignore_offset = false); /// @brief project a footprint to the given pose /// @param [in] base_footprint footprint to project /// @param [in] pose projection pose /// @return footprint projected to the given pose lanelet::BasicPolygon2d project_to_pose( - const autoware_universe_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose); + const autoware::universe_utils::Polygon2d & base_footprint, + const geometry_msgs::msg::Pose & pose); /// @brief calculate the trajectory footprints /// @details the resulting polygon follows the format used by the lanelet library: clockwise order /// and implicit closing edge diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp index 60d627a4b8c5d..bfa38e544227f 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp @@ -91,7 +91,7 @@ lanelet::ConstLanelets calculate_ignored_lanelets( lanelet::ConstLanelets ignored_lanelets; // ignore lanelets directly behind ego const auto behind = - autoware_universe_utils::calcOffsetPose(ego_data.pose, params.rear_offset, 0.0, 0.0); + autoware::universe_utils::calcOffsetPose(ego_data.pose, params.rear_offset, 0.0, 0.0); const lanelet::BasicPoint2d behind_point(behind.position.x, behind.position.y); const auto behind_lanelets = lanelet::geometry::findWithin2d( route_handler->getLaneletMapPtr()->laneletLayer, behind_point, 0.0); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index dfcfd53575627..f6d81f6f036d0 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -50,7 +50,7 @@ void OutOfLaneModule::init(rclcpp::Node & node, const std::string & module_name) logger_ = node.get_logger(); clock_ = node.get_clock(); init_parameters(node); - velocity_factor_interface_.init(autoware_motion_utils::PlanningBehavior::ROUTE_OBSTACLE); + velocity_factor_interface_.init(autoware::motion_utils::PlanningBehavior::ROUTE_OBSTACLE); debug_publisher_ = node.create_publisher("~/" + ns_ + "/debug_markers", 1); @@ -59,7 +59,7 @@ void OutOfLaneModule::init(rclcpp::Node & node, const std::string & module_name) } void OutOfLaneModule::init_parameters(rclcpp::Node & node) { - using autoware_universe_utils::getOrDeclareParameter; + using autoware::universe_utils::getOrDeclareParameter; auto & pp = params_; pp.mode = getOrDeclareParameter(node, ns_ + ".mode"); @@ -109,7 +109,7 @@ void OutOfLaneModule::init_parameters(rclcpp::Node & node) void OutOfLaneModule::update_parameters(const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; auto & pp = params_; updateParam(parameters, ns_ + ".mode", pp.mode); updateParam(parameters, ns_ + ".skip_if_already_overlapping", pp.skip_if_already_overlapping); @@ -151,13 +151,13 @@ VelocityPlanningResult OutOfLaneModule::plan( const std::shared_ptr planner_data) { VelocityPlanningResult result; - autoware_universe_utils::StopWatch stopwatch; + autoware::universe_utils::StopWatch stopwatch; stopwatch.tic(); out_of_lane::EgoData ego_data; ego_data.pose = planner_data->current_odometry.pose.pose; ego_data.trajectory_points = ego_trajectory_points; ego_data.first_trajectory_idx = - autoware_motion_utils::findNearestSegmentIndex(ego_trajectory_points, ego_data.pose.position); + autoware::motion_utils::findNearestSegmentIndex(ego_trajectory_points, ego_data.pose.position); ego_data.velocity = planner_data->current_odometry.twist.twist.linear.x; ego_data.max_decel = planner_data->velocity_smoother_->getMinDecel(); stopwatch.tic("calculate_trajectory_footprints"); @@ -234,9 +234,9 @@ VelocityPlanningResult OutOfLaneModule::plan( if ( point_to_insert && prev_inserted_point_ && prev_inserted_point_->slowdown.velocity <= point_to_insert->slowdown.velocity) { - const auto arc_length = autoware_motion_utils::calcSignedArcLength( + const auto arc_length = autoware::motion_utils::calcSignedArcLength( ego_trajectory_points, 0LU, point_to_insert->point.pose.position); - const auto prev_arc_length = autoware_motion_utils::calcSignedArcLength( + const auto prev_arc_length = autoware::motion_utils::calcSignedArcLength( ego_trajectory_points, 0LU, prev_inserted_point_->point.pose.position); return prev_arc_length < arc_length; } @@ -244,10 +244,10 @@ VelocityPlanningResult OutOfLaneModule::plan( }(); if (should_use_prev_inserted_point) { // if the trajectory changed the prev point is no longer on the trajectory so we project it - const auto insert_arc_length = autoware_motion_utils::calcSignedArcLength( + const auto insert_arc_length = autoware::motion_utils::calcSignedArcLength( ego_trajectory_points, 0LU, prev_inserted_point_->point.pose.position); prev_inserted_point_->point.pose = - autoware_motion_utils::calcInterpolatedPose(ego_trajectory_points, insert_arc_length); + autoware::motion_utils::calcInterpolatedPose(ego_trajectory_points, insert_arc_length); point_to_insert = prev_inserted_point_; } if (point_to_insert) { @@ -261,12 +261,12 @@ VelocityPlanningResult OutOfLaneModule::plan( point_to_insert->point.pose.position, point_to_insert->point.pose.position, point_to_insert->slowdown.velocity); - const auto is_approaching = autoware_motion_utils::calcSignedArcLength( + const auto is_approaching = autoware::motion_utils::calcSignedArcLength( ego_trajectory_points, ego_data.pose.position, point_to_insert->point.pose.position) > 0.1 && ego_data.velocity > 0.1; - const auto status = is_approaching ? autoware_motion_utils::VelocityFactor::APPROACHING - : autoware_motion_utils::VelocityFactor::STOPPED; + const auto status = is_approaching ? autoware::motion_utils::VelocityFactor::APPROACHING + : autoware::motion_utils::VelocityFactor::STOPPED; velocity_factor_interface_.set( ego_trajectory_points, ego_data.pose, point_to_insert->point.pose, status, "out_of_lane"); result.velocity_factor = velocity_factor_interface_.get(); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp index 79db6b25e7ce5..535510453b8ba 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp @@ -40,11 +40,11 @@ class PluginModuleInterface const std::vector & ego_trajectory_points, const std::shared_ptr planner_data) = 0; virtual std::string get_module_name() const = 0; - autoware_motion_utils::VelocityFactorInterface velocity_factor_interface_; + autoware::motion_utils::VelocityFactorInterface velocity_factor_interface_; rclcpp::Logger logger_ = rclcpp::get_logger(""); rclcpp::Publisher::SharedPtr debug_publisher_; rclcpp::Publisher::SharedPtr virtual_wall_publisher_; - autoware_motion_utils::VirtualWallMarkerCreator virtual_wall_marker_creator{}; + autoware::motion_utils::VirtualWallMarkerCreator virtual_wall_marker_creator{}; }; } // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index 76d401a8cfe56..714b6fd948a32 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -102,9 +102,9 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions & set_param_callback_ = this->add_on_set_parameters_callback( std::bind(&MotionVelocityPlannerNode::on_set_param, this, std::placeholders::_1)); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } void MotionVelocityPlannerNode::on_load_plugin( @@ -193,7 +193,7 @@ MotionVelocityPlannerNode::process_no_ground_pointcloud( Eigen::Affine3f affine = tf2::transformToEigen(transform.transform).cast(); pcl::PointCloud::Ptr pc_transformed(new pcl::PointCloud); - if (!pc.empty()) autoware_universe_utils::transformPointCloud(pc, *pc_transformed, affine); + if (!pc.empty()) autoware::universe_utils::transformPointCloud(pc, *pc_transformed, affine); return *pc_transformed; } @@ -284,9 +284,9 @@ void MotionVelocityPlannerNode::insert_stop( const geometry_msgs::msg::Point & stop_point) const { const auto seg_idx = - autoware_motion_utils::findNearestSegmentIndex(trajectory.points, stop_point); + autoware::motion_utils::findNearestSegmentIndex(trajectory.points, stop_point); const auto insert_idx = - autoware_motion_utils::insertTargetPoint(seg_idx, stop_point, trajectory.points); + autoware::motion_utils::insertTargetPoint(seg_idx, stop_point, trajectory.points); if (insert_idx) { for (auto idx = *insert_idx; idx < trajectory.points.size(); ++idx) trajectory.points[idx].longitudinal_velocity_mps = 0.0; @@ -300,13 +300,13 @@ void MotionVelocityPlannerNode::insert_slowdown( const autoware::motion_velocity_planner::SlowdownInterval & slowdown_interval) const { const auto from_seg_idx = - autoware_motion_utils::findNearestSegmentIndex(trajectory.points, slowdown_interval.from); - const auto from_insert_idx = autoware_motion_utils::insertTargetPoint( + autoware::motion_utils::findNearestSegmentIndex(trajectory.points, slowdown_interval.from); + const auto from_insert_idx = autoware::motion_utils::insertTargetPoint( from_seg_idx, slowdown_interval.from, trajectory.points); const auto to_seg_idx = - autoware_motion_utils::findNearestSegmentIndex(trajectory.points, slowdown_interval.to); + autoware::motion_utils::findNearestSegmentIndex(trajectory.points, slowdown_interval.to); const auto to_insert_idx = - autoware_motion_utils::insertTargetPoint(to_seg_idx, slowdown_interval.to, trajectory.points); + autoware::motion_utils::insertTargetPoint(to_seg_idx, slowdown_interval.to, trajectory.points); if (from_insert_idx && to_insert_idx) { for (auto idx = *from_insert_idx; idx <= *to_insert_idx; ++idx) trajectory.points[idx].longitudinal_velocity_mps = 0.0; @@ -336,7 +336,7 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s traj_steering_rate_limited, v0, current_pose, planner_data.ego_nearest_dist_threshold, planner_data.ego_nearest_yaw_threshold); const size_t traj_resampled_closest = - autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( traj_resampled, current_pose, planner_data.ego_nearest_dist_threshold, planner_data.ego_nearest_yaw_threshold); std::vector debug_trajectories; @@ -389,7 +389,7 @@ autoware_planning_msgs::msg::Trajectory MotionVelocityPlannerNode::generate_traj rcl_interfaces::msg::SetParametersResult MotionVelocityPlannerNode::on_set_param( const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; { std::unique_lock lk(mutex_); // for planner_manager_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp index 42c34a9a8c68d..7b771d0b04442 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp @@ -62,23 +62,23 @@ class MotionVelocityPlannerNode : public rclcpp::Node // subscriber rclcpp::Subscription::SharedPtr sub_trajectory_; - autoware_universe_utils::InterProcessPollingSubscriber< + autoware::universe_utils::InterProcessPollingSubscriber< autoware_perception_msgs::msg::PredictedObjects> sub_predicted_objects_{this, "~/input/dynamic_objects"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_no_ground_pointcloud_{ - this, "~/input/no_ground_pointcloud", autoware_universe_utils::SingleDepthSensorQoS()}; - autoware_universe_utils::InterProcessPollingSubscriber + this, "~/input/no_ground_pointcloud", autoware::universe_utils::SingleDepthSensorQoS()}; + autoware::universe_utils::InterProcessPollingSubscriber sub_vehicle_odometry_{this, "~/input/vehicle_odometry"}; - autoware_universe_utils::InterProcessPollingSubscriber< + autoware::universe_utils::InterProcessPollingSubscriber< geometry_msgs::msg::AccelWithCovarianceStamped> sub_acceleration_{this, "~/input/accel"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_occupancy_grid_{this, "~/input/occupancy_grid"}; - autoware_universe_utils::InterProcessPollingSubscriber< + autoware::universe_utils::InterProcessPollingSubscriber< autoware_perception_msgs::msg::TrafficLightGroupArray> sub_traffic_signals_{this, "~/input/traffic_signals"}; - autoware_universe_utils::InterProcessPollingSubscriber< + autoware::universe_utils::InterProcessPollingSubscriber< tier4_v2x_msgs::msg::VirtualTrafficLightStateArray> sub_virtual_traffic_light_states_{this, "~/input/virtual_traffic_light_states"}; rclcpp::Subscription::SharedPtr sub_lanelet_map_; @@ -138,9 +138,9 @@ class MotionVelocityPlannerNode : public rclcpp::Node autoware_planning_msgs::msg::Trajectory generate_trajectory( autoware::motion_velocity_planner::TrajectoryPoints input_trajectory_points); - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; }; } // namespace autoware::motion_velocity_planner diff --git a/planning/obstacle_stop_planner/include/obstacle_stop_planner/debug_marker.hpp b/planning/obstacle_stop_planner/include/obstacle_stop_planner/debug_marker.hpp index 54c12ed0ef543..2585c8a1141de 100644 --- a/planning/obstacle_stop_planner/include/obstacle_stop_planner/debug_marker.hpp +++ b/planning/obstacle_stop_planner/include/obstacle_stop_planner/debug_marker.hpp @@ -108,10 +108,10 @@ class ObstacleStopPlannerDebugNode explicit ObstacleStopPlannerDebugNode(rclcpp::Node * node, const double base_link2front); ~ObstacleStopPlannerDebugNode() {} bool pushPolygon( - const autoware_universe_utils::Polygon2d & polygon, const double z, const PolygonType & type); + const autoware::universe_utils::Polygon2d & polygon, const double z, const PolygonType & type); bool pushPolygon(const std::vector & polygon, const PolygonType & type); bool pushPolyhedron( - const autoware_universe_utils::Polygon2d & polyhedron, const double z_min, const double z_max, + const autoware::universe_utils::Polygon2d & polyhedron, const double z_min, const double z_max, const PolygonType & type); bool pushPolyhedron(const std::vector & polyhedron, const PolygonType & type); bool pushPose(const Pose & pose, const PoseType & type); diff --git a/planning/obstacle_stop_planner/include/obstacle_stop_planner/node.hpp b/planning/obstacle_stop_planner/include/obstacle_stop_planner/node.hpp index 2a50cfd2e24e8..6d4f341de6071 100644 --- a/planning/obstacle_stop_planner/include/obstacle_stop_planner/node.hpp +++ b/planning/obstacle_stop_planner/include/obstacle_stop_planner/node.hpp @@ -77,13 +77,13 @@ using nav_msgs::msg::Odometry; using sensor_msgs::msg::PointCloud2; using std_msgs::msg::Header; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; +using autoware::universe_utils::StopWatch; using autoware::vehicle_info_utils::VehicleInfo; using autoware_perception_msgs::msg::PredictedObjects; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; -using autoware_universe_utils::StopWatch; using tier4_debug_msgs::msg::BoolStamped; using tier4_debug_msgs::msg::Float32MultiArrayStamped; using tier4_debug_msgs::msg::Float32Stamped; @@ -315,9 +315,9 @@ class ObstacleStopPlannerNode : public rclcpp::Node return ret; } - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; - std::unique_ptr published_time_publisher_; + std::unique_ptr published_time_publisher_; }; } // namespace motion_planning diff --git a/planning/obstacle_stop_planner/include/obstacle_stop_planner/planner_utils.hpp b/planning/obstacle_stop_planner/include/obstacle_stop_planner/planner_utils.hpp index bdd2a0a403fcb..c195ff0cc55f3 100644 --- a/planning/obstacle_stop_planner/include/obstacle_stop_planner/planner_utils.hpp +++ b/planning/obstacle_stop_planner/include/obstacle_stop_planner/planner_utils.hpp @@ -45,10 +45,10 @@ using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseArray; using std_msgs::msg::Header; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; using autoware::vehicle_info_utils::VehicleInfo; using autoware_planning_msgs::msg::TrajectoryPoint; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; using TrajectoryPoints = std::vector; using PointCloud = pcl::PointCloud; diff --git a/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp b/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp index 1f01bf4417319..e9058f234e98f 100644 --- a/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp +++ b/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp @@ -367,7 +367,7 @@ void AdaptiveCruiseController::calcDistanceToNearestPointOnPath( double dist_to_point = 0; // get distance from self to next nearest point dist_to_point += - autoware_motion_utils::calcSignedArcLength(trajectory, self_pose.position, size_t(1)); + autoware::motion_utils::calcSignedArcLength(trajectory, self_pose.position, size_t(1)); // add distance from next self-nearest-point(=idx:0) to prev point of nearest_point_idx for (int i = 1; i < nearest_point_idx - 1; i++) { @@ -459,7 +459,7 @@ void AdaptiveCruiseController::calculateProjectedVelocityFromObject( object.kinematics.initial_twist_with_covariance.twist.linear.x); *velocity = - obj_vel_norm * std::cos(autoware_universe_utils::normalizeRadian(obj_vel_yaw - traj_yaw)); + obj_vel_norm * std::cos(autoware::universe_utils::normalizeRadian(obj_vel_yaw - traj_yaw)); debug_values_.data.at(DBGVAL::ESTIMATED_VEL_OBJ) = *velocity; } @@ -685,8 +685,8 @@ void AdaptiveCruiseController::insertMaxVelocityToPath( double dist_to_first_point = 0.0; if (output_trajectory->size() > 1) { - dist_to_first_point = - autoware_motion_utils::calcSignedArcLength(*output_trajectory, self_pose.position, size_t(1)); + dist_to_first_point = autoware::motion_utils::calcSignedArcLength( + *output_trajectory, self_pose.position, size_t(1)); } double margin_to_insert = dist_to_collision_point * param_.margin_rate_to_change_vel; diff --git a/planning/obstacle_stop_planner/src/debug_marker.cpp b/planning/obstacle_stop_planner/src/debug_marker.cpp index 835417f33a4c0..bbb8dadbcee9d 100644 --- a/planning/obstacle_stop_planner/src/debug_marker.cpp +++ b/planning/obstacle_stop_planner/src/debug_marker.cpp @@ -27,16 +27,16 @@ #include #include -using autoware_motion_utils::createDeletedSlowDownVirtualWallMarker; -using autoware_motion_utils::createDeletedStopVirtualWallMarker; -using autoware_motion_utils::createSlowDownVirtualWallMarker; -using autoware_motion_utils::createStopVirtualWallMarker; -using autoware_universe_utils::appendMarkerArray; -using autoware_universe_utils::calcOffsetPose; -using autoware_universe_utils::createDefaultMarker; -using autoware_universe_utils::createMarkerColor; -using autoware_universe_utils::createMarkerScale; -using autoware_universe_utils::createPoint; +using autoware::motion_utils::createDeletedSlowDownVirtualWallMarker; +using autoware::motion_utils::createDeletedStopVirtualWallMarker; +using autoware::motion_utils::createSlowDownVirtualWallMarker; +using autoware::motion_utils::createStopVirtualWallMarker; +using autoware::universe_utils::appendMarkerArray; +using autoware::universe_utils::calcOffsetPose; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerColor; +using autoware::universe_utils::createMarkerScale; +using autoware::universe_utils::createPoint; namespace motion_planning { @@ -54,7 +54,7 @@ ObstacleStopPlannerDebugNode::ObstacleStopPlannerDebugNode( } bool ObstacleStopPlannerDebugNode::pushPolygon( - const autoware_universe_utils::Polygon2d & polygon, const double z, const PolygonType & type) + const autoware::universe_utils::Polygon2d & polygon, const double z, const PolygonType & type) { std::vector eigen_polygon; for (const auto & point : polygon.outer()) { @@ -100,7 +100,7 @@ bool ObstacleStopPlannerDebugNode::pushPolygon( } bool ObstacleStopPlannerDebugNode::pushPolyhedron( - const autoware_universe_utils::Polygon2d & polyhedron, const double z_min, const double z_max, + const autoware::universe_utils::Polygon2d & polyhedron, const double z_min, const double z_max, const PolygonType & type) { std::vector eigen_polyhedron; diff --git a/planning/obstacle_stop_planner/src/node.cpp b/planning/obstacle_stop_planner/src/node.cpp index db39b31241456..f3814a2a06a52 100644 --- a/planning/obstacle_stop_planner/src/node.cpp +++ b/planning/obstacle_stop_planner/src/node.cpp @@ -40,17 +40,17 @@ namespace motion_planning { -using autoware_motion_utils::calcLongitudinalOffsetPose; -using autoware_motion_utils::calcLongitudinalOffsetToSegment; -using autoware_motion_utils::calcSignedArcLength; -using autoware_motion_utils::findFirstNearestIndexWithSoftConstraints; -using autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints; +using autoware::motion_utils::calcLongitudinalOffsetPose; +using autoware::motion_utils::calcLongitudinalOffsetToSegment; +using autoware::motion_utils::calcSignedArcLength; +using autoware::motion_utils::findFirstNearestIndexWithSoftConstraints; +using autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints; +using autoware::universe_utils::calcDistance2d; +using autoware::universe_utils::createPoint; +using autoware::universe_utils::getPoint; +using autoware::universe_utils::getPose; +using autoware::universe_utils::getRPY; using autoware_perception_msgs::msg::PredictedObject; -using autoware_universe_utils::calcDistance2d; -using autoware_universe_utils::createPoint; -using autoware_universe_utils::getPoint; -using autoware_universe_utils::getPose; -using autoware_universe_utils::getRPY; ObstacleStopPlannerNode::ObstacleStopPlannerNode(const rclcpp::NodeOptions & node_options) : Node("obstacle_stop_planner", node_options) @@ -245,9 +245,9 @@ ObstacleStopPlannerNode::ObstacleStopPlannerNode(const rclcpp::NodeOptions & nod std::bind(&ObstacleStopPlannerNode::onExpandStopRange, this, std::placeholders::_1), createSubscriptionOptions(this)); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); } void ObstacleStopPlannerNode::onPointCloud(const PointCloud2::ConstSharedPtr input_msg) @@ -327,7 +327,7 @@ void ObstacleStopPlannerNode::onTrigger(const Trajectory::ConstSharedPtr input_m // TODO(someone): support backward path const auto is_driving_forward = - autoware_motion_utils::isDrivingForwardWithTwist(input_msg->points); + autoware::motion_utils::isDrivingForwardWithTwist(input_msg->points); is_driving_forward_ = is_driving_forward ? is_driving_forward.value() : is_driving_forward_; if (!is_driving_forward_) { RCLCPP_WARN_THROTTLE( @@ -343,11 +343,11 @@ void ObstacleStopPlannerNode::onTrigger(const Trajectory::ConstSharedPtr input_m Trajectory output_trajectory = *input_msg; TrajectoryPoints output_trajectory_points = - autoware_motion_utils::convertToTrajectoryPointArray(*input_msg); + autoware::motion_utils::convertToTrajectoryPointArray(*input_msg); // trim trajectory from self pose TrajectoryPoints base_trajectory = trimTrajectoryWithIndexFromSelfPose( - autoware_motion_utils::convertToTrajectoryPointArray(*input_msg), planner_data.current_pose, + autoware::motion_utils::convertToTrajectoryPointArray(*input_msg), planner_data.current_pose, planner_data.trajectory_trim_index); // extend trajectory to consider obstacles after the goal @@ -379,7 +379,7 @@ void ObstacleStopPlannerNode::onTrigger(const Trajectory::ConstSharedPtr input_m resetExternalVelocityLimit(current_acc, current_vel); } - auto trajectory = autoware_motion_utils::convertToTrajectory(output_trajectory_points); + auto trajectory = autoware::motion_utils::convertToTrajectory(output_trajectory_points); publishDebugData(planner_data, current_acc, current_vel); trajectory.header = input_msg->header; @@ -1557,10 +1557,10 @@ void ObstacleStopPlannerNode::filterObstacles( // Check is it near to trajectory const double max_length = calcObstacleMaxLength(object.shape); - const size_t seg_idx = autoware_motion_utils::findNearestSegmentIndex( + const size_t seg_idx = autoware::motion_utils::findNearestSegmentIndex( traj, object.kinematics.initial_pose_with_covariance.pose.position); - const auto p_front = autoware_universe_utils::getPoint(traj.at(seg_idx)); - const auto p_back = autoware_universe_utils::getPoint(traj.at(seg_idx + 1)); + const auto p_front = autoware::universe_utils::getPoint(traj.at(seg_idx)); + const auto p_back = autoware::universe_utils::getPoint(traj.at(seg_idx + 1)); const auto & p_target = object.kinematics.initial_pose_with_covariance.pose.position; const Eigen::Vector3d segment_vec{p_back.x - p_front.x, p_back.y - p_front.y, 0.0}; const Eigen::Vector3d target_vec{p_target.x - p_front.x, p_target.y - p_front.y, 0.0}; diff --git a/planning/obstacle_stop_planner/src/planner_utils.cpp b/planning/obstacle_stop_planner/src/planner_utils.cpp index 3a4839aed7a36..fd8922c500318 100644 --- a/planning/obstacle_stop_planner/src/planner_utils.cpp +++ b/planning/obstacle_stop_planner/src/planner_utils.cpp @@ -32,13 +32,13 @@ namespace motion_planning { -using autoware_motion_utils::calcDecelDistWithJerkAndAccConstraints; -using autoware_motion_utils::findFirstNearestIndexWithSoftConstraints; -using autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints; +using autoware::motion_utils::calcDecelDistWithJerkAndAccConstraints; +using autoware::motion_utils::findFirstNearestIndexWithSoftConstraints; +using autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints; +using autoware::universe_utils::calcDistance2d; +using autoware::universe_utils::getRPY; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; -using autoware_universe_utils::calcDistance2d; -using autoware_universe_utils::getRPY; std::optional> calcFeasibleMarginAndVelocity( const SlowDownParam & slow_down_param, const double dist_baselink_to_obstacle, @@ -327,40 +327,40 @@ void createOneStepPolygon( { // base step appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(base_step_pose, longitudinal_offset, width, 0.0) + autoware::universe_utils::calcOffsetPose(base_step_pose, longitudinal_offset, width, 0.0) .position); appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(base_step_pose, longitudinal_offset, -width, 0.0) + autoware::universe_utils::calcOffsetPose(base_step_pose, longitudinal_offset, -width, 0.0) .position); appendPointToPolygon( - polygon, autoware_universe_utils::calcOffsetPose(base_step_pose, -rear_overhang, -width, 0.0) + polygon, autoware::universe_utils::calcOffsetPose(base_step_pose, -rear_overhang, -width, 0.0) .position); appendPointToPolygon( - polygon, - autoware_universe_utils::calcOffsetPose(base_step_pose, -rear_overhang, width, 0.0).position); + polygon, autoware::universe_utils::calcOffsetPose(base_step_pose, -rear_overhang, width, 0.0) + .position); } { // next step appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(next_step_pose, longitudinal_offset, width, 0.0) + autoware::universe_utils::calcOffsetPose(next_step_pose, longitudinal_offset, width, 0.0) .position); appendPointToPolygon( polygon, - autoware_universe_utils::calcOffsetPose(next_step_pose, longitudinal_offset, -width, 0.0) + autoware::universe_utils::calcOffsetPose(next_step_pose, longitudinal_offset, -width, 0.0) .position); appendPointToPolygon( - polygon, autoware_universe_utils::calcOffsetPose(next_step_pose, -rear_overhang, -width, 0.0) + polygon, autoware::universe_utils::calcOffsetPose(next_step_pose, -rear_overhang, -width, 0.0) .position); appendPointToPolygon( - polygon, - autoware_universe_utils::calcOffsetPose(next_step_pose, -rear_overhang, width, 0.0).position); + polygon, autoware::universe_utils::calcOffsetPose(next_step_pose, -rear_overhang, width, 0.0) + .position); } - polygon = autoware_universe_utils::isClockwise(polygon) + polygon = autoware::universe_utils::isClockwise(polygon) ? polygon - : autoware_universe_utils::inverseClockwise(polygon); + : autoware::universe_utils::inverseClockwise(polygon); boost::geometry::convex_hull(polygon, hull_polygon); } @@ -552,7 +552,7 @@ double getNearestPointAndDistanceForPredictedObject( bool is_init = false; for (const auto & p : points.poses) { - double norm = autoware_universe_utils::calcDistance2d(p, base_pose); + double norm = autoware::universe_utils::calcDistance2d(p, base_pose); if (norm < min_norm || !is_init) { min_norm = norm; *nearest_collision_point = p.position; @@ -627,9 +627,9 @@ Polygon2d convertBoundingBoxObjectToGeometryPolygon( object_polygon.outer().emplace_back(p4_obj.x(), p4_obj.y()); object_polygon.outer().push_back(object_polygon.outer().front()); - object_polygon = autoware_universe_utils::isClockwise(object_polygon) + object_polygon = autoware::universe_utils::isClockwise(object_polygon) ? object_polygon - : autoware_universe_utils::inverseClockwise(object_polygon); + : autoware::universe_utils::inverseClockwise(object_polygon); return object_polygon; } @@ -650,9 +650,9 @@ Polygon2d convertCylindricalObjectToGeometryPolygon( } object_polygon.outer().push_back(object_polygon.outer().front()); - object_polygon = autoware_universe_utils::isClockwise(object_polygon) + object_polygon = autoware::universe_utils::isClockwise(object_polygon) ? object_polygon - : autoware_universe_utils::inverseClockwise(object_polygon); + : autoware::universe_utils::inverseClockwise(object_polygon); return object_polygon; } @@ -670,9 +670,9 @@ Polygon2d convertPolygonObjectToGeometryPolygon( object_polygon.outer().emplace_back(tf_obj.x(), tf_obj.y()); } object_polygon.outer().push_back(object_polygon.outer().front()); - object_polygon = autoware_universe_utils::isClockwise(object_polygon) + object_polygon = autoware::universe_utils::isClockwise(object_polygon) ? object_polygon - : autoware_universe_utils::inverseClockwise(object_polygon); + : autoware::universe_utils::inverseClockwise(object_polygon); return object_polygon; } @@ -692,7 +692,7 @@ std::optional getObstacleFromUuid( bool isFrontObstacle(const Pose & ego_pose, const geometry_msgs::msg::Point & obstacle_pos) { - const auto yaw = autoware_universe_utils::getRPY(ego_pose).z; + const auto yaw = autoware::universe_utils::getRPY(ego_pose).z; const Eigen::Vector2d base_pose_vec(std::cos(yaw), std::sin(yaw)); const Eigen::Vector2d obstacle_vec( obstacle_pos.x - ego_pose.position.x, obstacle_pos.y - ego_pose.position.y); diff --git a/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp b/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp index 0aae35126e8ab..1f05fc93138a2 100644 --- a/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp +++ b/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp @@ -176,7 +176,7 @@ void calculateCartesian( pose.position.x = it->x(); pose.position.y = it->y(); pose.position.z = 0.0; - pose.orientation = autoware_universe_utils::createQuaternionFromRPY(0.0, 0.0, yaw); + pose.orientation = autoware::universe_utils::createQuaternionFromRPY(0.0, 0.0, yaw); path.poses.push_back(pose); } path.yaws.push_back(path.yaws.back()); diff --git a/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/common_structs.hpp b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/common_structs.hpp index 9fdf7191a911d..101d135dcf8bf 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/common_structs.hpp +++ b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/common_structs.hpp @@ -80,7 +80,7 @@ struct TimeKeeper std::string accumulated_msg = "\n"; std::stringstream latest_stream; - autoware_universe_utils::StopWatch< + autoware::universe_utils::StopWatch< std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> stop_watch_; }; @@ -89,8 +89,8 @@ struct DebugData { std::vector sampled_candidates{}; size_t previous_sampled_candidates_nb = 0UL; - std::vector obstacles{}; - std::vector footprints{}; + std::vector obstacles{}; + std::vector footprints{}; }; struct TrajectoryParam @@ -103,7 +103,7 @@ struct TrajectoryParam void onParam(const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; // common updateParam(parameters, "common.output_delta_arc_length", output_delta_arc_length); @@ -123,7 +123,7 @@ struct EgoNearestParam void onParam(const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; updateParam(parameters, "ego_nearest_dist_threshold", dist_threshold); updateParam(parameters, "ego_nearest_yaw_threshold", yaw_threshold); } diff --git a/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/node.hpp b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/node.hpp index ceab5229b36d4..ac0686d177dfb 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/node.hpp +++ b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/node.hpp @@ -62,9 +62,9 @@ class PathSampler : public rclcpp::Node // interface subscriber rclcpp::Subscription::SharedPtr path_sub_; - autoware_universe_utils::InterProcessPollingSubscriber odom_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber odom_sub_{ this, "~/input/odometry"}; - autoware_universe_utils::InterProcessPollingSubscriber objects_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber objects_sub_{ this, "~/input/objects"}; // debug publisher diff --git a/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/geometry_utils.hpp b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/geometry_utils.hpp index 51b28e7b3f2d6..a27dd1576c90d 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/geometry_utils.hpp +++ b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/geometry_utils.hpp @@ -42,8 +42,8 @@ namespace geometry_utils template bool isSamePoint(const T1 & t1, const T2 & t2) { - const auto p1 = autoware_universe_utils::getPoint(t1); - const auto p2 = autoware_universe_utils::getPoint(t2); + const auto p1 = autoware::universe_utils::getPoint(t1); + const auto p2 = autoware::universe_utils::getPoint(t2); constexpr double epsilon = 1e-6; if (epsilon < std::abs(p1.x - p2.x) || epsilon < std::abs(p1.y - p2.y)) { diff --git a/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/trajectory_utils.hpp b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/trajectory_utils.hpp index b3838ad8c44f5..edcb8c2b22061 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/trajectory_utils.hpp +++ b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/trajectory_utils.hpp @@ -47,12 +47,12 @@ std::optional getPointIndexAfter( } double sum_length = - -autoware_motion_utils::calcLongitudinalOffsetToSegment(points, target_seg_idx, target_pos); + -autoware::motion_utils::calcLongitudinalOffsetToSegment(points, target_seg_idx, target_pos); // search forward if (sum_length < offset) { for (size_t i = target_seg_idx + 1; i < points.size(); ++i) { - sum_length += autoware_universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); + sum_length += autoware::universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); if (offset < sum_length) { return i - 1; } @@ -64,7 +64,7 @@ std::optional getPointIndexAfter( // search backward for (size_t i = target_seg_idx; 0 < i; --i) { // NOTE: use size_t since i is always positive value - sum_length -= autoware_universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); + sum_length -= autoware::universe_utils::calcDistance2d(points.at(i), points.at(i - 1)); if (sum_length < offset) { return i - 1; } @@ -77,7 +77,7 @@ template TrajectoryPoint convertToTrajectoryPoint(const T & point) { TrajectoryPoint traj_point; - traj_point.pose = autoware_universe_utils::getPose(point); + traj_point.pose = autoware::universe_utils::getPose(point); traj_point.longitudinal_velocity_mps = point.longitudinal_velocity_mps; traj_point.lateral_velocity_mps = point.lateral_velocity_mps; traj_point.heading_rate_rps = point.heading_rate_rps; @@ -126,7 +126,7 @@ size_t findEgoIndex( const std::vector & points, const geometry_msgs::msg::Pose & ego_pose, const EgoNearestParam & ego_nearest_param) { - return autoware_motion_utils::findFirstNearestIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( points, ego_pose, ego_nearest_param.dist_threshold, ego_nearest_param.yaw_threshold); } @@ -135,7 +135,7 @@ size_t findEgoSegmentIndex( const std::vector & points, const geometry_msgs::msg::Pose & ego_pose, const EgoNearestParam & ego_nearest_param) { - return autoware_motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + return autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( points, ego_pose, ego_nearest_param.dist_threshold, ego_nearest_param.yaw_threshold); } @@ -152,13 +152,13 @@ std::optional updateFrontPointForFix( { // calculate front point to insert in points as a fixed point const size_t front_seg_idx_for_fix = trajectory_utils::findEgoSegmentIndex( - points_for_fix, autoware_universe_utils::getPose(points.front()), ego_nearest_param); + points_for_fix, autoware::universe_utils::getPose(points.front()), ego_nearest_param); const size_t front_point_idx_for_fix = front_seg_idx_for_fix; const auto & front_fix_point = points_for_fix.at(front_point_idx_for_fix); // check if the points_for_fix is longer in front than points const double lon_offset_to_prev_front = - autoware_motion_utils::calcSignedArcLength(points, 0, front_fix_point.pose.position); + autoware::motion_utils::calcSignedArcLength(points, 0, front_fix_point.pose.position); if (0 < lon_offset_to_prev_front) { RCLCPP_WARN( rclcpp::get_logger("autoware_path_sampler.trajectory_utils"), @@ -166,7 +166,7 @@ std::optional updateFrontPointForFix( return std::nullopt; } - const double dist = autoware_universe_utils::calcDistance2d(points.front(), front_fix_point); + const double dist = autoware::universe_utils::calcDistance2d(points.front(), front_fix_point); // check if deviation is not too large constexpr double max_lat_error = 3.0; diff --git a/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp b/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp index 0d68ac455ff94..15d7e883a31d2 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp +++ b/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp @@ -144,7 +144,7 @@ PathSampler::PathSampler(const rclcpp::NodeOptions & node_options) rcl_interfaces::msg::SetParametersResult PathSampler::onParam( const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; updateParam(parameters, "constraints.hard.max_curvature", params_.constraints.hard.max_curvature); updateParam(parameters, "constraints.hard.min_curvature", params_.constraints.hard.min_curvature); @@ -239,7 +239,7 @@ void PathSampler::onPath(const Path::SharedPtr path_ptr) // 0. return if path is backward // TODO(Maxime): support backward path - if (!autoware_motion_utils::isDrivingForward(path_ptr->points)) { + if (!autoware::motion_utils::isDrivingForward(path_ptr->points)) { RCLCPP_WARN_THROTTLE( get_logger(), *get_clock(), 5000, "Backward path is NOT supported. Just converting path to trajectory"); @@ -251,13 +251,13 @@ void PathSampler::onPath(const Path::SharedPtr path_ptr) // 3. extend trajectory to connect the optimized trajectory and the following path smoothly if (!generated_traj_points.empty()) { const auto output_traj_msg = - autoware_motion_utils::convertToTrajectory(generated_traj_points, path_ptr->header); + autoware::motion_utils::convertToTrajectory(generated_traj_points, path_ptr->header); traj_pub_->publish(output_traj_msg); } else { auto stopping_traj = trajectory_utils::convertToTrajectoryPoints(planner_data.traj_points); for (auto & p : stopping_traj) p.longitudinal_velocity_mps = 0.0; const auto output_traj_msg = - autoware_motion_utils::convertToTrajectory(stopping_traj, path_ptr->header); + autoware::motion_utils::convertToTrajectory(stopping_traj, path_ptr->header); traj_pub_->publish(output_traj_msg); } @@ -318,14 +318,14 @@ void PathSampler::copyZ( to_traj.front().pose.position.z = from_traj.front().pose.position.z; if (from_traj.size() < 2 || to_traj.size() < 2) return; auto from = from_traj.begin() + 1; - auto s_from = autoware_universe_utils::calcDistance2d(from->pose, std::next(from)->pose); + auto s_from = autoware::universe_utils::calcDistance2d(from->pose, std::next(from)->pose); auto s_to = 0.0; auto s_from_prev = 0.0; for (auto to = to_traj.begin() + 1; to + 1 != to_traj.end(); ++to) { - s_to += autoware_universe_utils::calcDistance2d(std::prev(to)->pose, to->pose); + s_to += autoware::universe_utils::calcDistance2d(std::prev(to)->pose, to->pose); for (; s_from < s_to && from + 1 != from_traj.end(); ++from) { s_from_prev = s_from; - s_from += autoware_universe_utils::calcDistance2d(from->pose, std::next(from)->pose); + s_from += autoware::universe_utils::calcDistance2d(from->pose, std::next(from)->pose); } const auto ratio = (s_to - s_from_prev) / (s_from - s_from_prev); to->pose.position.z = std::prev(from)->pose.position.z + @@ -341,8 +341,8 @@ void PathSampler::copyVelocity( if (to_traj.empty() || from_traj.empty()) return; const auto closest_fn = [&](const auto & p1, const auto & p2) { - return autoware_universe_utils::calcDistance2d(p1.pose, ego_pose) <= - autoware_universe_utils::calcDistance2d(p2.pose, ego_pose); + return autoware::universe_utils::calcDistance2d(p1.pose, ego_pose) <= + autoware::universe_utils::calcDistance2d(p2.pose, ego_pose); }; const auto first_from = std::min_element(from_traj.begin(), from_traj.end() - 1, closest_fn); const auto first_to = std::min_element(to_traj.begin(), to_traj.end() - 1, closest_fn); @@ -352,14 +352,14 @@ void PathSampler::copyVelocity( to->longitudinal_velocity_mps = first_from->longitudinal_velocity_mps; auto from = first_from; - auto s_from = autoware_universe_utils::calcDistance2d(from->pose, std::next(from)->pose); + auto s_from = autoware::universe_utils::calcDistance2d(from->pose, std::next(from)->pose); auto s_to = 0.0; auto s_from_prev = 0.0; for (; to + 1 != to_traj.end(); ++to) { - s_to += autoware_universe_utils::calcDistance2d(to->pose, std::next(to)->pose); + s_to += autoware::universe_utils::calcDistance2d(to->pose, std::next(to)->pose); for (; s_from < s_to && from + 1 != from_traj.end(); ++from) { s_from_prev = s_from; - s_from += autoware_universe_utils::calcDistance2d(from->pose, std::next(from)->pose); + s_from += autoware::universe_utils::calcDistance2d(from->pose, std::next(from)->pose); } if ( from->longitudinal_velocity_mps == 0.0 || std::prev(from)->longitudinal_velocity_mps == 0.0) { @@ -532,7 +532,7 @@ void PathSampler::publishVirtualWall(const geometry_msgs::msg::Pose & stop_pose) { time_keeper_ptr_->tic(__func__); - const auto virtual_wall_marker = autoware_motion_utils::createStopVirtualWallMarker( + const auto virtual_wall_marker = autoware::motion_utils::createStopVirtualWallMarker( stop_pose, "outside drivable area", now(), 0, vehicle_info_.max_longitudinal_offset_m); virtual_wall_pub_->publish(virtual_wall_marker); diff --git a/planning/sampling_based_planner/autoware_path_sampler/src/prepare_inputs.cpp b/planning/sampling_based_planner/autoware_path_sampler/src/prepare_inputs.cpp index 4d6f2dbd1e008..06e8ab9042207 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/src/prepare_inputs.cpp +++ b/planning/sampling_based_planner/autoware_path_sampler/src/prepare_inputs.cpp @@ -40,7 +40,7 @@ void prepareConstraints( constraints.obstacle_polygons = autoware::sampler_common::MultiPolygon2d(); for (const auto & o : predicted_objects.objects) if (o.kinematics.initial_twist_with_covariance.twist.linear.x < 0.5) // TODO(Maxime): param - constraints.obstacle_polygons.push_back(autoware_universe_utils::toPolygon2d(o)); + constraints.obstacle_polygons.push_back(autoware::universe_utils::toPolygon2d(o)); constraints.dynamic_obstacles = {}; // TODO(Maxime): not implemented // TODO(Maxime): directly use lines instead of polygon diff --git a/planning/sampling_based_planner/autoware_path_sampler/src/utils/trajectory_utils.cpp b/planning/sampling_based_planner/autoware_path_sampler/src/utils/trajectory_utils.cpp index 2676d223d9ffe..c8ca80b95d284 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/src/utils/trajectory_utils.cpp +++ b/planning/sampling_based_planner/autoware_path_sampler/src/utils/trajectory_utils.cpp @@ -46,12 +46,12 @@ void compensateLastPose( const geometry_msgs::msg::Pose last_traj_pose = traj_points.back().pose; - const double dist = - autoware_universe_utils::calcDistance2d(last_path_point.pose.position, last_traj_pose.position); + const double dist = autoware::universe_utils::calcDistance2d( + last_path_point.pose.position, last_traj_pose.position); const double norm_diff_yaw = [&]() { const double diff_yaw = tf2::getYaw(last_path_point.pose.orientation) - tf2::getYaw(last_traj_pose.orientation); - return autoware_universe_utils::normalizeRadian(diff_yaw); + return autoware::universe_utils::normalizeRadian(diff_yaw); }(); if (dist > delta_dist_threshold || std::fabs(norm_diff_yaw) > delta_yaw_threshold) { traj_points.push_back(convertToTrajectoryPoint(last_path_point)); @@ -63,10 +63,10 @@ std::vector resampleTrajectoryPoints( { constexpr bool enable_resampling_stop_point = true; - const auto traj = autoware_motion_utils::convertToTrajectory(traj_points); - const auto resampled_traj = autoware_motion_utils::resampleTrajectory( + const auto traj = autoware::motion_utils::convertToTrajectory(traj_points); + const auto resampled_traj = autoware::motion_utils::resampleTrajectory( traj, interval, false, true, true, enable_resampling_stop_point); - return autoware_motion_utils::convertToTrajectoryPointArray(resampled_traj); + return autoware::motion_utils::convertToTrajectoryPointArray(resampled_traj); } // NOTE: stop point will not be resampled @@ -75,17 +75,17 @@ std::vector resampleTrajectoryPointsWithoutStopPoint( { constexpr bool enable_resampling_stop_point = false; - const auto traj = autoware_motion_utils::convertToTrajectory(traj_points); - const auto resampled_traj = autoware_motion_utils::resampleTrajectory( + const auto traj = autoware::motion_utils::convertToTrajectory(traj_points); + const auto resampled_traj = autoware::motion_utils::resampleTrajectory( traj, interval, false, true, true, enable_resampling_stop_point); - return autoware_motion_utils::convertToTrajectoryPointArray(resampled_traj); + return autoware::motion_utils::convertToTrajectoryPointArray(resampled_traj); } void insertStopPoint( std::vector & traj_points, const geometry_msgs::msg::Pose & input_stop_pose, const size_t stop_seg_idx) { - const double offset_to_segment = autoware_motion_utils::calcLongitudinalOffsetToSegment( + const double offset_to_segment = autoware::motion_utils::calcLongitudinalOffsetToSegment( traj_points, stop_seg_idx, input_stop_pose.position); const auto traj_spline = SplineInterpolationPoints2d(traj_points); diff --git a/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/structures.hpp b/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/structures.hpp index de58b02a75623..29b3f5a8fc145 100644 --- a/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/structures.hpp +++ b/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/structures.hpp @@ -38,13 +38,13 @@ namespace autoware::sampler_common { -using autoware_universe_utils::LinearRing2d; -using autoware_universe_utils::MultiPoint2d; -using autoware_universe_utils::MultiPolygon2d; -using autoware_universe_utils::Point2d; -using autoware_universe_utils::Polygon2d; +using autoware::universe_utils::LinearRing2d; +using autoware::universe_utils::MultiPoint2d; +using autoware::universe_utils::MultiPolygon2d; +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; -typedef std::pair BoxIndexPair; +typedef std::pair BoxIndexPair; typedef boost::geometry::index::rtree> Rtree; /// @brief data about constraint check results of a given path diff --git a/sensing/imu_corrector/src/gyro_bias_estimation_module.cpp b/sensing/imu_corrector/src/gyro_bias_estimation_module.cpp index cdad454452f5c..7bd6b38490495 100644 --- a/sensing/imu_corrector/src/gyro_bias_estimation_module.cpp +++ b/sensing/imu_corrector/src/gyro_bias_estimation_module.cpp @@ -52,15 +52,15 @@ geometry_msgs::msg::Vector3 calculate_error_rpy( const geometry_msgs::msg::Vector3 & gyro_bias) { const geometry_msgs::msg::Vector3 rpy_0 = - autoware_universe_utils::getRPY(pose_list.front().pose.orientation); + autoware::universe_utils::getRPY(pose_list.front().pose.orientation); const geometry_msgs::msg::Vector3 rpy_1 = - autoware_universe_utils::getRPY(pose_list.back().pose.orientation); + autoware::universe_utils::getRPY(pose_list.back().pose.orientation); const geometry_msgs::msg::Vector3 d_rpy = integrate_orientation(gyro_list, gyro_bias); geometry_msgs::msg::Vector3 error_rpy; - error_rpy.x = autoware_universe_utils::normalizeRadian(-rpy_1.x + rpy_0.x + d_rpy.x); - error_rpy.y = autoware_universe_utils::normalizeRadian(-rpy_1.y + rpy_0.y + d_rpy.y); - error_rpy.z = autoware_universe_utils::normalizeRadian(-rpy_1.z + rpy_0.z + d_rpy.z); + error_rpy.x = autoware::universe_utils::normalizeRadian(-rpy_1.x + rpy_0.x + d_rpy.x); + error_rpy.y = autoware::universe_utils::normalizeRadian(-rpy_1.y + rpy_0.y + d_rpy.y); + error_rpy.z = autoware::universe_utils::normalizeRadian(-rpy_1.z + rpy_0.z + d_rpy.z); return error_rpy; } diff --git a/sensing/imu_corrector/src/gyro_bias_estimator.cpp b/sensing/imu_corrector/src/gyro_bias_estimator.cpp index 6ec5c9f64a623..278d2dfc28e59 100644 --- a/sensing/imu_corrector/src/gyro_bias_estimator.cpp +++ b/sensing/imu_corrector/src/gyro_bias_estimator.cpp @@ -59,7 +59,7 @@ GyroBiasEstimator::GyroBiasEstimator(const rclcpp::NodeOptions & options) this->get_node_base_interface()->get_context()); this->get_node_timers_interface()->add_timer(timer_, nullptr); - transform_listener_ = std::make_shared(this); + transform_listener_ = std::make_shared(this); // initialize diagnostics_info_ { @@ -150,10 +150,10 @@ void GyroBiasEstimator::timer_callback() // Check if the vehicle is moving straight const geometry_msgs::msg::Vector3 rpy_0 = - autoware_universe_utils::getRPY(pose_buf.front().pose.orientation); + autoware::universe_utils::getRPY(pose_buf.front().pose.orientation); const geometry_msgs::msg::Vector3 rpy_1 = - autoware_universe_utils::getRPY(pose_buf.back().pose.orientation); - const double yaw_diff = std::abs(autoware_universe_utils::normalizeRadian(rpy_1.z - rpy_0.z)); + autoware::universe_utils::getRPY(pose_buf.back().pose.orientation); + const double yaw_diff = std::abs(autoware::universe_utils::normalizeRadian(rpy_1.z - rpy_0.z)); const double time_diff = (t1_rclcpp_time - t0_rclcpp_time).seconds(); const double yaw_vel = yaw_diff / time_diff; const bool is_straight = (yaw_vel < straight_motion_ang_vel_upper_limit_); diff --git a/sensing/imu_corrector/src/gyro_bias_estimator.hpp b/sensing/imu_corrector/src/gyro_bias_estimator.hpp index 7f8d5e9084ce6..1313f2cb06507 100644 --- a/sensing/imu_corrector/src/gyro_bias_estimator.hpp +++ b/sensing/imu_corrector/src/gyro_bias_estimator.hpp @@ -76,7 +76,7 @@ class GyroBiasEstimator : public rclcpp::Node std::optional gyro_bias_; - std::shared_ptr transform_listener_; + std::shared_ptr transform_listener_; std::string imu_frame_; diff --git a/sensing/imu_corrector/src/imu_corrector_core.cpp b/sensing/imu_corrector/src/imu_corrector_core.cpp index cc4efe1ba2f22..f96bab16443fe 100644 --- a/sensing/imu_corrector/src/imu_corrector_core.cpp +++ b/sensing/imu_corrector/src/imu_corrector_core.cpp @@ -25,7 +25,7 @@ std::array transformCovariance(const std::array & cov) { - using COV_IDX = autoware_universe_utils::xyz_covariance_index::XYZ_COV_IDX; + using COV_IDX = autoware::universe_utils::xyz_covariance_index::XYZ_COV_IDX; double max_cov = 0.0; max_cov = std::max(max_cov, cov[COV_IDX::X_X]); @@ -57,7 +57,7 @@ ImuCorrector::ImuCorrector(const rclcpp::NodeOptions & options) : rclcpp::Node("imu_corrector", options), output_frame_(declare_parameter("base_link", "base_link")) { - transform_listener_ = std::make_shared(this); + transform_listener_ = std::make_shared(this); angular_velocity_offset_x_imu_link_ = declare_parameter("angular_velocity_offset_x", 0.0); angular_velocity_offset_y_imu_link_ = declare_parameter("angular_velocity_offset_y", 0.0); diff --git a/sensing/imu_corrector/src/imu_corrector_core.hpp b/sensing/imu_corrector/src/imu_corrector_core.hpp index 45f7b4e6142b2..0dacab4651477 100644 --- a/sensing/imu_corrector/src/imu_corrector_core.hpp +++ b/sensing/imu_corrector/src/imu_corrector_core.hpp @@ -31,7 +31,7 @@ namespace imu_corrector { class ImuCorrector : public rclcpp::Node { - using COV_IDX = autoware_universe_utils::xyz_covariance_index::XYZ_COV_IDX; + using COV_IDX = autoware::universe_utils::xyz_covariance_index::XYZ_COV_IDX; public: explicit ImuCorrector(const rclcpp::NodeOptions & options); @@ -53,7 +53,7 @@ class ImuCorrector : public rclcpp::Node double accel_stddev_imu_link_; - std::shared_ptr transform_listener_; + std::shared_ptr transform_listener_; std::string output_frame_; }; diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp index 22fbbd09bd8fc..86c4ed5943540 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp @@ -185,8 +185,8 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node const std::string & original_topic_name, const std::string & postfix); /** \brief processing time publisher. **/ - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr debug_publisher_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr debug_publisher_; }; } // namespace pointcloud_preprocessor diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp index bd67759d3d7a6..ead66d98b8be7 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp @@ -172,8 +172,8 @@ class PointCloudConcatenationComponent : public rclcpp::Node void checkConcatStatus(diagnostic_updater::DiagnosticStatusWrapper & stat); /** \brief processing time publisher. **/ - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr debug_publisher_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr debug_publisher_; }; } // namespace pointcloud_preprocessor diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp index 4b018f22aa60a..80abba9b5d1a5 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp @@ -69,8 +69,8 @@ class DistortionCorrectorComponent : public rclcpp::Node rclcpp::Subscription::SharedPtr twist_sub_; rclcpp::Publisher::SharedPtr undistorted_points_pub_; - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr debug_publisher_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr debug_publisher_; tf2_ros::Buffer tf2_buffer_{get_clock()}; tf2_ros::TransformListener tf2_listener_{tf2_buffer_}; diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp index 23deceaf29c21..ce003f58dcc49 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp @@ -177,9 +177,9 @@ class Filter : public rclcpp::Node std::mutex mutex_; /** \brief processing time publisher. **/ - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr debug_publisher_; - std::unique_ptr published_time_publisher_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr debug_publisher_; + std::unique_ptr published_time_publisher_; /** \brief Virtual abstract filter method. To be implemented by every child. * \param input the input point cloud dataset. diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp index c89c97269fd2e..4153cee7695f8 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp @@ -182,8 +182,8 @@ class PointCloudDataSynchronizerComponent : public rclcpp::Node const std::string & original_topic_name, const std::string & postfix); /** \brief processing time publisher. **/ - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr debug_publisher_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr debug_publisher_; }; } // namespace pointcloud_preprocessor diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp index b3ab34da2726f..7b27d35509a98 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp @@ -40,9 +40,9 @@ #include #include -using autoware_universe_utils::LinearRing2d; -using autoware_universe_utils::MultiPoint2d; -using autoware_universe_utils::Point2d; +using autoware::universe_utils::LinearRing2d; +using autoware::universe_utils::MultiPoint2d; +using autoware::universe_utils::Point2d; namespace pointcloud_preprocessor { diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp index cd34c63b50de7..d376a47ae8ab0 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp @@ -26,7 +26,7 @@ #include -using autoware_universe_utils::MultiPoint2d; +using autoware::universe_utils::MultiPoint2d; namespace pointcloud_preprocessor { diff --git a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp index bd96ef9d215bd..e998a79b27f77 100644 --- a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp @@ -75,8 +75,8 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro { // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ = std::make_unique(this, "concatenate_data_synchronizer"); stop_watch_ptr_->tic("cyclic_time"); diff --git a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp index d442a91a91c5a..3586b7c999776 100644 --- a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp +++ b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp @@ -37,8 +37,8 @@ PointCloudConcatenationComponent::PointCloudConcatenationComponent( { // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ = std::make_unique(this, "concatenate_pointclouds_debug"); stop_watch_ptr_->tic("cyclic_time"); diff --git a/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp index 79632b7a4111c..620e9e42a6864 100644 --- a/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp @@ -62,8 +62,8 @@ CropBoxFilterComponent::CropBoxFilterComponent(const rclcpp::NodeOptions & optio { // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ = std::make_unique(this, this->get_name()); stop_watch_ptr_->tic("cyclic_time"); diff --git a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index 7b9ed5f30a3d8..e7aa1f24409e6 100644 --- a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -28,8 +28,8 @@ DistortionCorrectorComponent::DistortionCorrectorComponent(const rclcpp::NodeOpt { // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ = std::make_unique(this, "distortion_corrector"); stop_watch_ptr_->tic("cyclic_time"); @@ -290,11 +290,11 @@ bool DistortionCorrectorComponent::undistortPointCloud( theta += w * time_offset; baselink_quat.setValue( - 0, 0, autoware_universe_utils::sin(theta * 0.5f), - autoware_universe_utils::cos(theta * 0.5f)); // baselink_quat.setRPY(0.0, 0.0, theta); + 0, 0, autoware::universe_utils::sin(theta * 0.5f), + autoware::universe_utils::cos(theta * 0.5f)); // baselink_quat.setRPY(0.0, 0.0, theta); const float dis = v * time_offset; - x += dis * autoware_universe_utils::cos(theta); - y += dis * autoware_universe_utils::sin(theta); + x += dis * autoware::universe_utils::cos(theta); + y += dis * autoware::universe_utils::sin(theta); baselink_tf_odom.setOrigin(tf2::Vector3(x, y, 0.0)); baselink_tf_odom.setRotation(baselink_quat); diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp b/sensing/pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp index 2114810b8934c..83c9058fd5fa5 100644 --- a/sensing/pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp +++ b/sensing/pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp @@ -57,8 +57,8 @@ PickupBasedVoxelGridDownsampleFilterComponent::PickupBasedVoxelGridDownsampleFil { // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ = std::make_unique(this, this->get_name()); stop_watch_ptr_->tic("cyclic_time"); diff --git a/sensing/pointcloud_preprocessor/src/filter.cpp b/sensing/pointcloud_preprocessor/src/filter.cpp index d289aa9c95ea1..c9bb6dfc0fc66 100644 --- a/sensing/pointcloud_preprocessor/src/filter.cpp +++ b/sensing/pointcloud_preprocessor/src/filter.cpp @@ -103,7 +103,7 @@ pointcloud_preprocessor::Filter::Filter( std::bind(&Filter::filterParamCallback, this, std::placeholders::_1)); published_time_publisher_ = - std::make_unique(this); + std::make_unique(this); RCLCPP_DEBUG(this->get_logger(), "[Filter Constructor] successfully created."); } diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp index 975c04c9089d6..e05f44240b53a 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp @@ -29,8 +29,8 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions { // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ = std::make_unique(this, "ring_outlier_filter"); outlier_pointcloud_publisher_ = diff --git a/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp b/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp index 42a1ef68d0f68..099e5757ffc0a 100644 --- a/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp @@ -46,8 +46,8 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent( { // initialize debug tool { - using autoware_universe_utils::DebugPublisher; - using autoware_universe_utils::StopWatch; + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; stop_watch_ptr_ = std::make_unique>(); debug_publisher_ = std::make_unique(this, "time_synchronizer"); stop_watch_ptr_->tic("cyclic_time"); diff --git a/sensing/pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp b/sensing/pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp index d35aca8decc28..def7652848642 100644 --- a/sensing/pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp +++ b/sensing/pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp @@ -16,7 +16,7 @@ namespace { -autoware_universe_utils::Box2d calcBoundingBox( +autoware::universe_utils::Box2d calcBoundingBox( const pcl::PointCloud::ConstPtr & input_cloud) { MultiPoint2d candidate_points; @@ -24,11 +24,11 @@ autoware_universe_utils::Box2d calcBoundingBox( candidate_points.emplace_back(p.x, p.y); } - return boost::geometry::return_envelope(candidate_points); + return boost::geometry::return_envelope(candidate_points); } lanelet::ConstPolygons3d calcIntersectedPolygons( - const autoware_universe_utils::Box2d & bounding_box, const lanelet::ConstPolygons3d & polygons) + const autoware::universe_utils::Box2d & bounding_box, const lanelet::ConstPolygons3d & polygons) { lanelet::ConstPolygons3d intersected_polygons; for (const auto & polygon : polygons) { diff --git a/sensing/radar_static_pointcloud_filter/include/radar_static_pointcloud_filter/radar_static_pointcloud_filter_node.hpp b/sensing/radar_static_pointcloud_filter/include/radar_static_pointcloud_filter/radar_static_pointcloud_filter_node.hpp index ee9acbddf93b1..72a78f35251f7 100644 --- a/sensing/radar_static_pointcloud_filter/include/radar_static_pointcloud_filter/radar_static_pointcloud_filter_node.hpp +++ b/sensing/radar_static_pointcloud_filter/include/radar_static_pointcloud_filter/radar_static_pointcloud_filter_node.hpp @@ -51,7 +51,7 @@ class RadarStaticPointcloudFilterNode : public rclcpp::Node // Subscriber message_filters::Subscriber sub_radar_{}; message_filters::Subscriber sub_odometry_{}; - std::shared_ptr transform_listener_; + std::shared_ptr transform_listener_; using SyncPolicy = message_filters::sync_policies::ApproximateTime; using Sync = message_filters::Synchronizer; diff --git a/sensing/radar_static_pointcloud_filter/src/radar_static_pointcloud_filter_node/radar_static_pointcloud_filter_node.cpp b/sensing/radar_static_pointcloud_filter/src/radar_static_pointcloud_filter_node/radar_static_pointcloud_filter_node.cpp index e148ed275af30..985f30c8e34b5 100644 --- a/sensing/radar_static_pointcloud_filter/src/radar_static_pointcloud_filter_node/radar_static_pointcloud_filter_node.cpp +++ b/sensing/radar_static_pointcloud_filter/src/radar_static_pointcloud_filter_node/radar_static_pointcloud_filter_node.cpp @@ -96,7 +96,7 @@ RadarStaticPointcloudFilterNode::RadarStaticPointcloudFilterNode( node_param_.doppler_velocity_sd = declare_parameter("doppler_velocity_sd"); // Subscriber - transform_listener_ = std::make_shared(this); + transform_listener_ = std::make_shared(this); sub_radar_.subscribe(this, "~/input/radar", rclcpp::QoS{1}.get_rmw_qos_profile()); sub_odometry_.subscribe(this, "~/input/odometry", rclcpp::QoS{1}.get_rmw_qos_profile()); diff --git a/simulator/dummy_perception_publisher/src/node.cpp b/simulator/dummy_perception_publisher/src/node.cpp index 184bef8c96820..b479d7c36bb42 100644 --- a/simulator/dummy_perception_publisher/src/node.cpp +++ b/simulator/dummy_perception_publisher/src/node.cpp @@ -93,7 +93,7 @@ ObjectInfo::ObjectInfo( } const auto current_pose = - autoware_universe_utils::calcOffsetPose(initial_pose, move_distance, 0.0, 0.0); + autoware::universe_utils::calcOffsetPose(initial_pose, move_distance, 0.0, 0.0); // calculate tf from map to moved_object geometry_msgs::msg::Transform ros_map2moved_object; 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 a6c5a1eae4f7f..71c89fcf4df42 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 @@ -59,7 +59,7 @@ nav_msgs::msg::Odometry to_odometry( nav_msgs::msg::Odometry odometry; odometry.pose.pose.position.x = vehicle_model_ptr->getX(); odometry.pose.pose.position.y = vehicle_model_ptr->getY(); - odometry.pose.pose.orientation = autoware_universe_utils::createQuaternionFromRPY( + odometry.pose.pose.orientation = autoware::universe_utils::createQuaternionFromRPY( 0.0, ego_pitch_angle, vehicle_model_ptr->getYaw()); odometry.twist.twist.linear.x = vehicle_model_ptr->getVx(); odometry.twist.twist.angular.z = vehicle_model_ptr->getWz(); @@ -304,8 +304,8 @@ rcl_interfaces::msg::SetParametersResult SimplePlanningSimulator::on_parameter( result.reason = "success"; try { - autoware_universe_utils::updateParam(parameters, "x_stddev", x_stddev_); - autoware_universe_utils::updateParam(parameters, "y_stddev", y_stddev_); + autoware::universe_utils::updateParam(parameters, "x_stddev", x_stddev_); + autoware::universe_utils::updateParam(parameters, "y_stddev", y_stddev_); } catch (const rclcpp::exceptions::InvalidParameterTypeException & e) { result.successful = false; result.reason = e.what(); @@ -323,7 +323,7 @@ double SimplePlanningSimulator::calculate_ego_pitch() const geometry_msgs::msg::Pose ego_pose; ego_pose.position.x = ego_x; ego_pose.position.y = ego_y; - ego_pose.orientation = autoware_universe_utils::createQuaternionFromYaw(ego_yaw); + ego_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(ego_yaw); // calculate prev/next point of lanelet centerline nearest to ego pose. lanelet::Lanelet ego_lanelet; @@ -333,7 +333,7 @@ double SimplePlanningSimulator::calculate_ego_pitch() const } const auto centerline_points = convert_centerline_to_points(ego_lanelet); const size_t ego_seg_idx = - autoware_motion_utils::findNearestSegmentIndex(centerline_points, ego_pose.position); + autoware::motion_utils::findNearestSegmentIndex(centerline_points, ego_pose.position); const auto & prev_point = centerline_points.at(ego_seg_idx); const auto & next_point = centerline_points.at(ego_seg_idx + 1); @@ -398,7 +398,7 @@ void SimplePlanningSimulator::on_timer() // add estimate covariance { - using COV_IDX = autoware_universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; current_odometry_.pose.covariance[COV_IDX::X_X] = x_stddev_; current_odometry_.pose.covariance[COV_IDX::Y_Y] = y_stddev_; } @@ -553,7 +553,7 @@ void SimplePlanningSimulator::add_measurement_noise( odom.twist.twist.linear.x += velocity_noise; double yaw = tf2::getYaw(odom.pose.pose.orientation); yaw += static_cast((*n.rpy_dist_)(*n.rand_engine_)); - odom.pose.pose.orientation = autoware_universe_utils::createQuaternionFromYaw(yaw); + odom.pose.pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); vel.longitudinal_velocity += static_cast(velocity_noise); @@ -686,7 +686,7 @@ void SimplePlanningSimulator::publish_acceleration() msg.accel.accel.linear.x = vehicle_model_ptr_->getAx(); msg.accel.accel.linear.y = vehicle_model_ptr_->getWz() * vehicle_model_ptr_->getVx(); - using COV_IDX = autoware_universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; constexpr auto COV = 0.001; msg.accel.covariance.at(COV_IDX::X_X) = COV; // linear x msg.accel.covariance.at(COV_IDX::Y_Y) = COV; // linear y @@ -699,7 +699,7 @@ void SimplePlanningSimulator::publish_acceleration() void SimplePlanningSimulator::publish_imu() { - using COV_IDX = autoware_universe_utils::xyz_covariance_index::XYZ_COV_IDX; + using COV_IDX = autoware::universe_utils::xyz_covariance_index::XYZ_COV_IDX; sensor_msgs::msg::Imu imu; imu.header.frame_id = "base_link"; diff --git a/system/default_ad_api/src/motion.hpp b/system/default_ad_api/src/motion.hpp index 25949adbc39df..053e9b2427a10 100644 --- a/system/default_ad_api/src/motion.hpp +++ b/system/default_ad_api/src/motion.hpp @@ -34,7 +34,7 @@ class MotionNode : public rclcpp::Node explicit MotionNode(const rclcpp::NodeOptions & options); private: - autoware_motion_utils::VehicleStopChecker vehicle_stop_checker_; + autoware::motion_utils::VehicleStopChecker vehicle_stop_checker_; rclcpp::TimerBase::SharedPtr timer_; rclcpp::CallbackGroup::SharedPtr group_cli_; Srv srv_accept_; diff --git a/system/default_ad_api/src/planning.cpp b/system/default_ad_api/src/planning.cpp index 6fd27c4963f66..374316e19e6b1 100644 --- a/system/default_ad_api/src/planning.cpp +++ b/system/default_ad_api/src/planning.cpp @@ -137,7 +137,7 @@ void PlanningNode::on_timer() const auto & stop_point = factor.pose.position; const auto & points = trajectory_->points; factor.distance = - autoware_motion_utils::calcSignedArcLength(points, curr_point, stop_point); + autoware::motion_utils::calcSignedArcLength(points, curr_point, stop_point); } } } diff --git a/system/default_ad_api/src/planning.hpp b/system/default_ad_api/src/planning.hpp index 7e754efc4855f..929eb517afa2e 100644 --- a/system/default_ad_api/src/planning.hpp +++ b/system/default_ad_api/src/planning.hpp @@ -48,7 +48,7 @@ class PlanningNode : public rclcpp::Node std::vector steering_factors_; rclcpp::TimerBase::SharedPtr timer_; - using VehicleStopChecker = autoware_motion_utils::VehicleStopCheckerBase; + using VehicleStopChecker = autoware::motion_utils::VehicleStopCheckerBase; using Trajectory = planning_interface::Trajectory::Message; using KinematicState = localization_interface::KinematicState::Message; void on_trajectory(const Trajectory::ConstSharedPtr msg); diff --git a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp b/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp index c20bcda5a6b70..e46c6e4341284 100644 --- a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp +++ b/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp @@ -66,8 +66,8 @@ rcl_interfaces::msg::SetParametersResult DummyDiagPublisher::paramCallback( auto prev_status_str = status_str; auto is_active = true; try { - autoware_universe_utils::updateParam(parameters, status_prefix_str, status_str); - autoware_universe_utils::updateParam(parameters, is_active_prefix_str, is_active); + autoware::universe_utils::updateParam(parameters, status_prefix_str, status_str); + autoware::universe_utils::updateParam(parameters, is_active_prefix_str, is_active); } catch (const rclcpp::exceptions::InvalidParameterTypeException & e) { result.successful = false; result.reason = e.what(); diff --git a/system/emergency_handler/include/emergency_handler/emergency_handler_core.hpp b/system/emergency_handler/include/emergency_handler/emergency_handler_core.hpp index 798da2374b62a..b77797b2a4205 100644 --- a/system/emergency_handler/include/emergency_handler/emergency_handler_core.hpp +++ b/system/emergency_handler/include/emergency_handler/emergency_handler_core.hpp @@ -63,14 +63,14 @@ class EmergencyHandler : public rclcpp::Node sub_hazard_status_stamped_; rclcpp::Subscription::SharedPtr sub_prev_control_command_; // Subscribers without callback - autoware_universe_utils::InterProcessPollingSubscriber sub_odom_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_odom_{ this, "~/input/odometry"}; - autoware_universe_utils::InterProcessPollingSubscriber< + autoware::universe_utils::InterProcessPollingSubscriber< autoware_vehicle_msgs::msg::ControlModeReport> sub_control_mode_{this, "~/input/control_mode"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_mrm_comfortable_stop_status_{this, "~/input/mrm/comfortable_stop/status"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_mrm_emergency_stop_status_{this, "~/input/mrm/emergency_stop/status"}; autoware_system_msgs::msg::HazardStatusStamped::ConstSharedPtr hazard_status_stamped_; diff --git a/system/mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp b/system/mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp index e6bac26677be5..5c1ca5e04de0e 100644 --- a/system/mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp +++ b/system/mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp @@ -59,7 +59,7 @@ MrmEmergencyStopOperator::MrmEmergencyStopOperator(const rclcpp::NodeOptions & n rcl_interfaces::msg::SetParametersResult MrmEmergencyStopOperator::onParameter( const std::vector & parameters) { - using autoware_universe_utils::updateParam; + using autoware::universe_utils::updateParam; updateParam(parameters, "target_acceleration", params_.target_acceleration); updateParam(parameters, "target_jerk", params_.target_jerk); diff --git a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp b/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp index feb01bfa22d3f..c908ca1a62ee2 100644 --- a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp +++ b/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp @@ -72,18 +72,18 @@ class MrmHandler : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_operation_mode_availability_; // Subscribers without callback - autoware_universe_utils::InterProcessPollingSubscriber sub_odom_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_odom_{ this, "~/input/odometry"}; - autoware_universe_utils::InterProcessPollingSubscriber< + autoware::universe_utils::InterProcessPollingSubscriber< autoware_vehicle_msgs::msg::ControlModeReport> sub_control_mode_{this, "~/input/control_mode"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_mrm_pull_over_status_{this, "~/input/mrm/pull_over/status"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_mrm_comfortable_stop_status_{this, "~/input/mrm/comfortable_stop/status"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber sub_mrm_emergency_stop_status_{this, "~/input/mrm/emergency_stop/status"}; - autoware_universe_utils::InterProcessPollingSubscriber< + autoware::universe_utils::InterProcessPollingSubscriber< autoware_adapi_v1_msgs::msg::OperationModeState> sub_operation_mode_state_{this, "~/input/api/operation_mode/state"}; diff --git a/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp b/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp index 8795d12718325..dbb1db027b149 100644 --- a/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp +++ b/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp @@ -147,7 +147,7 @@ class AutowareErrorMonitor : public rclcpp::Node void loggingErrors(const autoware_system_msgs::msg::HazardStatus & diag_array); - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; }; #endif // SYSTEM_ERROR_MONITOR__SYSTEM_ERROR_MONITOR_CORE_HPP_ diff --git a/system/system_error_monitor/src/system_error_monitor_core.cpp b/system/system_error_monitor/src/system_error_monitor_core.cpp index d00426137221f..1daa4624ec934 100644 --- a/system/system_error_monitor/src/system_error_monitor_core.cpp +++ b/system/system_error_monitor/src/system_error_monitor_core.cpp @@ -265,7 +265,7 @@ AutowareErrorMonitor::AutowareErrorMonitor(const rclcpp::NodeOptions & options) timer_ = rclcpp::create_timer( this, get_clock(), period_ns, std::bind(&AutowareErrorMonitor::onTimer, this)); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); } void AutowareErrorMonitor::loadRequiredModules(const std::string & key) diff --git a/system/system_monitor/src/ntp_monitor/ntp_monitor.cpp b/system/system_monitor/src/ntp_monitor/ntp_monitor.cpp index 4cacfb5f9770f..4e697fa18ec50 100644 --- a/system/system_monitor/src/ntp_monitor/ntp_monitor.cpp +++ b/system/system_monitor/src/ntp_monitor/ntp_monitor.cpp @@ -126,7 +126,7 @@ void NTPMonitor::checkOffset(diagnostic_updater::DiagnosticStatusWrapper & stat) void NTPMonitor::onTimer() { // Start to measure elapsed time - autoware_universe_utils::StopWatch stop_watch; + autoware::universe_utils::StopWatch stop_watch; stop_watch.tic("execution_time"); std::string error_str; diff --git a/system/system_monitor/src/process_monitor/process_monitor.cpp b/system/system_monitor/src/process_monitor/process_monitor.cpp index 55636c7893d5d..2ab3e053225eb 100644 --- a/system/system_monitor/src/process_monitor/process_monitor.cpp +++ b/system/system_monitor/src/process_monitor/process_monitor.cpp @@ -517,7 +517,7 @@ void ProcessMonitor::onTimer() bool is_top_error = false; // Start to measure elapsed time - autoware_universe_utils::StopWatch stop_watch; + autoware::universe_utils::StopWatch stop_watch; stop_watch.tic("execution_time"); int out_fd[2]; diff --git a/tools/reaction_analyzer/src/reaction_analyzer_node.cpp b/tools/reaction_analyzer/src/reaction_analyzer_node.cpp index 79e64ba514bfe..e890a5208bf22 100644 --- a/tools/reaction_analyzer/src/reaction_analyzer_node.cpp +++ b/tools/reaction_analyzer/src/reaction_analyzer_node.cpp @@ -205,7 +205,7 @@ void ReactionAnalyzerNode::spawn_obstacle(const geometry_msgs::msg::Point & ego_ } } else { if ( - autoware_universe_utils::calcDistance3d(ego_pose, entity_pose_.position) < + autoware::universe_utils::calcDistance3d(ego_pose, entity_pose_.position) < node_params_.spawn_distance_threshold) { if (!spawn_object_cmd_) { spawn_object_cmd_ = true; @@ -394,7 +394,7 @@ bool ReactionAnalyzerNode::check_ego_init_correctly( } constexpr double deviation_threshold = 0.1; - const auto deviation = autoware_universe_utils::calcPoseDeviation( + const auto deviation = autoware::universe_utils::calcPoseDeviation( ground_truth_pose_ptr->pose, odometry_ptr->pose.pose); const bool is_position_initialized_correctly = deviation.longitudinal < deviation_threshold && deviation.lateral < deviation_threshold && diff --git a/tools/reaction_analyzer/src/subscriber.cpp b/tools/reaction_analyzer/src/subscriber.cpp index b58c80c67f67a..02d7a3872953a 100644 --- a/tools/reaction_analyzer/src/subscriber.cpp +++ b/tools/reaction_analyzer/src/subscriber.cpp @@ -260,13 +260,13 @@ void SubscriberBase::on_trajectory( return; } - const auto nearest_seg_idx = autoware_motion_utils::findNearestSegmentIndex( + const auto nearest_seg_idx = autoware::motion_utils::findNearestSegmentIndex( msg_ptr->points, current_odometry_ptr->pose.pose.position); const auto nearest_objects_seg_idx = - autoware_motion_utils::findNearestIndex(msg_ptr->points, entity_pose_.position); + autoware::motion_utils::findNearestIndex(msg_ptr->points, entity_pose_.position); - const auto zero_vel_idx = autoware_motion_utils::searchZeroVelocityIndex( + const auto zero_vel_idx = autoware::motion_utils::searchZeroVelocityIndex( msg_ptr->points, nearest_seg_idx, nearest_objects_seg_idx); if (zero_vel_idx) { @@ -299,7 +299,7 @@ void SubscriberBase::on_trajectory( return; } - const auto nearest_seg_idx = autoware_motion_utils::findNearestSegmentIndex( + const auto nearest_seg_idx = autoware::motion_utils::findNearestSegmentIndex( msg_ptr->points, current_odometry_ptr->pose.pose.position); // find the target index which we will search for zero velocity @@ -310,7 +310,7 @@ void SubscriberBase::on_trajectory( } const auto target_idx = tmp_target_idx; const auto zero_vel_idx = - autoware_motion_utils::searchZeroVelocityIndex(msg_ptr->points, nearest_seg_idx, target_idx); + autoware::motion_utils::searchZeroVelocityIndex(msg_ptr->points, nearest_seg_idx, target_idx); if (zero_vel_idx) { RCLCPP_INFO(node_->get_logger(), "%s reacted with published time", node_name.c_str()); diff --git a/tools/reaction_analyzer/src/utils.cpp b/tools/reaction_analyzer/src/utils.cpp index a07743417fa80..3ecadb96ee34d 100644 --- a/tools/reaction_analyzer/src/utils.cpp +++ b/tools/reaction_analyzer/src/utils.cpp @@ -136,8 +136,8 @@ visualization_msgs::msg::Marker create_polyhedron_marker(const EntityParams & pa tf2::Quaternion quaternion; quaternion.setRPY( - autoware_universe_utils::deg2rad(params.roll), autoware_universe_utils::deg2rad(params.pitch), - autoware_universe_utils::deg2rad(params.yaw)); + autoware::universe_utils::deg2rad(params.roll), autoware::universe_utils::deg2rad(params.pitch), + autoware::universe_utils::deg2rad(params.yaw)); marker.pose.orientation = tf2::toMsg(quaternion); marker.scale.x = 0.1; // Line width @@ -224,7 +224,7 @@ size_t get_index_after_distance( size_t target_id = curr_id; double current_distance = 0.0; for (size_t traj_id = curr_id + 1; traj_id < traj.points.size(); ++traj_id) { - current_distance = autoware_universe_utils::calcDistance3d(traj.points.at(traj_id), curr_p); + current_distance = autoware::universe_utils::calcDistance3d(traj.points.at(traj_id), curr_p); if (current_distance >= distance) { break; } @@ -286,9 +286,9 @@ geometry_msgs::msg::Pose create_entity_pose(const EntityParams & entity_params) tf2::Quaternion entity_q_orientation; entity_q_orientation.setRPY( - autoware_universe_utils::deg2rad(entity_params.roll), - autoware_universe_utils::deg2rad(entity_params.pitch), - autoware_universe_utils::deg2rad(entity_params.yaw)); + autoware::universe_utils::deg2rad(entity_params.roll), + autoware::universe_utils::deg2rad(entity_params.pitch), + autoware::universe_utils::deg2rad(entity_params.yaw)); entity_pose.orientation = tf2::toMsg(entity_q_orientation); return entity_pose; } @@ -302,9 +302,9 @@ geometry_msgs::msg::Pose pose_params_to_pose(const PoseParams & pose_params) tf2::Quaternion pose_q_orientation; pose_q_orientation.setRPY( - autoware_universe_utils::deg2rad(pose_params.roll), - autoware_universe_utils::deg2rad(pose_params.pitch), - autoware_universe_utils::deg2rad(pose_params.yaw)); + autoware::universe_utils::deg2rad(pose_params.roll), + autoware::universe_utils::deg2rad(pose_params.pitch), + autoware::universe_utils::deg2rad(pose_params.yaw)); pose.orientation = tf2::toMsg(pose_q_orientation); return pose; } @@ -316,9 +316,9 @@ PointCloud2::SharedPtr create_entity_pointcloud_ptr( tf2::Quaternion entity_q_orientation; entity_q_orientation.setRPY( - autoware_universe_utils::deg2rad(entity_params.roll), - autoware_universe_utils::deg2rad(entity_params.pitch), - autoware_universe_utils::deg2rad(entity_params.yaw)); + autoware::universe_utils::deg2rad(entity_params.roll), + autoware::universe_utils::deg2rad(entity_params.pitch), + autoware::universe_utils::deg2rad(entity_params.yaw)); tf2::Transform tf(entity_q_orientation); const auto origin = tf2::Vector3(entity_params.x, entity_params.y, entity_params.z); tf.setOrigin(origin); @@ -395,7 +395,7 @@ bool search_pointcloud_near_pose( return std::any_of( pcl_pointcloud.points.begin(), pcl_pointcloud.points.end(), [pose, search_radius](const auto & point) { - return autoware_universe_utils::calcDistance3d(pose.position, point) <= search_radius; + return autoware::universe_utils::calcDistance3d(pose.position, point) <= search_radius; }); } @@ -406,7 +406,7 @@ bool search_predicted_objects_near_pose( return std::any_of( predicted_objects.objects.begin(), predicted_objects.objects.end(), [pose, search_radius](const PredictedObject & object) { - return autoware_universe_utils::calcDistance3d( + return autoware::universe_utils::calcDistance3d( pose.position, object.kinematics.initial_pose_with_covariance.pose.position) <= search_radius; }); @@ -420,7 +420,7 @@ bool search_detected_objects_near_pose( return std::any_of( detected_objects.objects.begin(), detected_objects.objects.end(), [pose, search_radius](const DetectedObject & object) { - return autoware_universe_utils::calcDistance3d( + return autoware::universe_utils::calcDistance3d( pose.position, object.kinematics.pose_with_covariance.pose.position) <= search_radius; }); @@ -433,7 +433,7 @@ bool search_tracked_objects_near_pose( return std::any_of( tracked_objects.objects.begin(), tracked_objects.objects.end(), [pose, search_radius](const TrackedObject & object) { - return autoware_universe_utils::calcDistance3d( + return autoware::universe_utils::calcDistance3d( pose.position, object.kinematics.pose_with_covariance.pose.position) <= search_radius; }); diff --git a/vehicle/autoware_accel_brake_map_calibrator/include/autoware_accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp b/vehicle/autoware_accel_brake_map_calibrator/include/autoware_accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp index 6446511db4c29..39d81c26961bb 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/include/autoware_accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp +++ b/vehicle/autoware_accel_brake_map_calibrator/include/autoware_accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp @@ -88,7 +88,7 @@ using DataStampedPtr = std::shared_ptr; class AccelBrakeMapCalibrator : public rclcpp::Node { private: - std::shared_ptr transform_listener_; + std::shared_ptr transform_listener_; std::string csv_default_map_dir_; rclcpp::Publisher::SharedPtr original_map_occ_pub_; rclcpp::Publisher::SharedPtr update_map_occ_pub_; @@ -107,13 +107,13 @@ class AccelBrakeMapCalibrator : public rclcpp::Node rclcpp::Publisher::SharedPtr map_error_ratio_pub_; rclcpp::Publisher::SharedPtr calibration_status_pub_; - autoware_universe_utils::InterProcessPollingSubscriber steer_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber steer_sub_{ this, "~/input/steer"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber actuation_status_sub_{this, "~/input/actuation_status"}; - autoware_universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber actuation_cmd_sub_{this, "~/input/actuation_cmd"}; - autoware_universe_utils::InterProcessPollingSubscriber velocity_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber velocity_sub_{ this, "~/input/velocity"}; // Service @@ -374,7 +374,7 @@ class AccelBrakeMapCalibrator : public rclcpp::Node COMMAND = 1, }; - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; public: explicit AccelBrakeMapCalibrator(const rclcpp::NodeOptions & node_options); diff --git a/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp b/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp index 15d7473d9f00a..6a88d5c61a2d8 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp +++ b/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp @@ -32,7 +32,7 @@ namespace autoware::accel_brake_map_calibrator AccelBrakeMapCalibrator::AccelBrakeMapCalibrator(const rclcpp::NodeOptions & node_options) : Node("accel_brake_map_calibrator", node_options) { - transform_listener_ = std::make_shared(this); + transform_listener_ = std::make_shared(this); // get parameter update_hz_ = declare_parameter("update_hz", 10.0); covariance_ = declare_parameter("initial_covariance", 0.05); @@ -217,7 +217,7 @@ AccelBrakeMapCalibrator::AccelBrakeMapCalibrator(const rclcpp::NodeOptions & nod init_timer(1.0 / update_hz_); init_output_csv_timer(30.0); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); } void AccelBrakeMapCalibrator::init_output_csv_timer(double period_s) diff --git a/vehicle/autoware_external_cmd_converter/include/autoware_external_cmd_converter/node.hpp b/vehicle/autoware_external_cmd_converter/include/autoware_external_cmd_converter/node.hpp index 2f1c0ac74b9a5..c219c162d6b37 100644 --- a/vehicle/autoware_external_cmd_converter/include/autoware_external_cmd_converter/node.hpp +++ b/vehicle/autoware_external_cmd_converter/include/autoware_external_cmd_converter/node.hpp @@ -60,11 +60,11 @@ class ExternalCmdConverterNode : public rclcpp::Node emergency_stop_heartbeat_sub_; // Polling Subscriber - autoware_universe_utils::InterProcessPollingSubscriber velocity_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber velocity_sub_{ this, "in/odometry"}; - autoware_universe_utils::InterProcessPollingSubscriber shift_cmd_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber shift_cmd_sub_{ this, "in/shift_cmd"}; - autoware_universe_utils::InterProcessPollingSubscriber gate_mode_sub_{ + autoware::universe_utils::InterProcessPollingSubscriber gate_mode_sub_{ this, "in/current_gate_mode"}; void on_external_cmd(const ExternalControlCommand::ConstSharedPtr cmd_ptr); diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp index b807e74fc27cf..181b7926337dc 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp +++ b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp @@ -78,9 +78,9 @@ class RawVehicleCommandConverterNode : public rclcpp::Node //!< @brief subscriber for vehicle command rclcpp::Subscription::SharedPtr sub_control_cmd_; // polling subscribers - autoware_universe_utils::InterProcessPollingSubscriber sub_odometry_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_odometry_{ this, "~/input/odometry"}; - autoware_universe_utils::InterProcessPollingSubscriber sub_steering_{ + autoware::universe_utils::InterProcessPollingSubscriber sub_steering_{ this, "~/input/steering"}; rclcpp::TimerBase::SharedPtr timer_; @@ -117,7 +117,7 @@ class RawVehicleCommandConverterNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_pub_steer_pid_; DebugValues debug_steer_; - std::unique_ptr logger_configure_; + std::unique_ptr logger_configure_; }; } // namespace autoware::raw_vehicle_cmd_converter diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp index ce783cfcd32e4..c4d7ea11bbcf3 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp +++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp @@ -81,7 +81,7 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode( debug_pub_steer_pid_ = create_publisher( "/vehicle/raw_vehicle_cmd_converter/debug/steer_pid", 1); - logger_configure_ = std::make_unique(this); + logger_configure_ = std::make_unique(this); } void RawVehicleCommandConverterNode::publishActuationCmd() diff --git a/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp b/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp index 0fcc5fcf28863..e951f11e49ab7 100644 --- a/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp +++ b/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp @@ -47,8 +47,8 @@ struct VehicleInfo double min_height_offset_m; double max_height_offset_m; - autoware_universe_utils::LinearRing2d createFootprint(const double margin = 0.0) const; - autoware_universe_utils::LinearRing2d createFootprint( + autoware::universe_utils::LinearRing2d createFootprint(const double margin = 0.0) const; + autoware::universe_utils::LinearRing2d createFootprint( const double lat_margin, const double lon_margin) const; }; diff --git a/vehicle/autoware_vehicle_info_utils/src/vehicle_info.cpp b/vehicle/autoware_vehicle_info_utils/src/vehicle_info.cpp index 665ee61fa67ff..db223663f1145 100644 --- a/vehicle/autoware_vehicle_info_utils/src/vehicle_info.cpp +++ b/vehicle/autoware_vehicle_info_utils/src/vehicle_info.cpp @@ -16,16 +16,16 @@ namespace autoware::vehicle_info_utils { -autoware_universe_utils::LinearRing2d VehicleInfo::createFootprint(const double margin) const +autoware::universe_utils::LinearRing2d VehicleInfo::createFootprint(const double margin) const { return createFootprint(margin, margin); } -autoware_universe_utils::LinearRing2d VehicleInfo::createFootprint( +autoware::universe_utils::LinearRing2d VehicleInfo::createFootprint( const double lat_margin, const double lon_margin) const { - using autoware_universe_utils::LinearRing2d; - using autoware_universe_utils::Point2d; + using autoware::universe_utils::LinearRing2d; + using autoware::universe_utils::Point2d; const double x_front = front_overhang_m + wheel_base_m + lon_margin; const double x_center = wheel_base_m / 2.0; From 45c068ae926d144fb471434a0d5b26b84f2daa55 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 20 Jun 2024 12:00:31 +0900 Subject: [PATCH 032/217] refactor(livox): apply clang-tidy check (#7551) livox Signed-off-by: Mamoru Sobue --- .../src/livox_tag_filter_node/livox_tag_filter_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sensing/livox/livox_tag_filter/src/livox_tag_filter_node/livox_tag_filter_node.cpp b/sensing/livox/livox_tag_filter/src/livox_tag_filter_node/livox_tag_filter_node.cpp index f3216fdcd9b6a..9a131db7d3c8e 100644 --- a/sensing/livox/livox_tag_filter/src/livox_tag_filter_node/livox_tag_filter_node.cpp +++ b/sensing/livox/livox_tag_filter/src/livox_tag_filter_node/livox_tag_filter_node.cpp @@ -20,7 +20,7 @@ #include #include -struct LivoxPoint +struct EIGEN_ALIGN16 LivoxPoint { float x; float y; @@ -28,7 +28,7 @@ struct LivoxPoint float intensity; std::uint8_t tag; std::uint8_t line; -} EIGEN_ALIGN16; +}; POINT_CLOUD_REGISTER_POINT_STRUCT( LivoxPoint, (float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)( From 5a539f49827227ef8d0d49aeb8ce85be500a9f9b Mon Sep 17 00:00:00 2001 From: Autumn60 <37181352+Autumn60@users.noreply.github.com> Date: Thu, 20 Jun 2024 13:55:09 +0900 Subject: [PATCH 033/217] feat(path_distance_calculator): change to read topic by polling (#7318) replace Subscription to InterProcessPollingSubscriber Signed-off-by: Autumn60 Co-authored-by: Autumn60 Co-authored-by: Tomoya Kimura --- .../src/path_distance_calculator.cpp | 5 +---- .../src/path_distance_calculator.hpp | 5 +++-- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/common/path_distance_calculator/src/path_distance_calculator.cpp b/common/path_distance_calculator/src/path_distance_calculator.cpp index 47dd8258de5bb..833c806cdd6db 100644 --- a/common/path_distance_calculator/src/path_distance_calculator.cpp +++ b/common/path_distance_calculator/src/path_distance_calculator.cpp @@ -25,15 +25,12 @@ PathDistanceCalculator::PathDistanceCalculator(const rclcpp::NodeOptions & options) : Node("path_distance_calculator", options), self_pose_listener_(this) { - sub_path_ = create_subscription( - "~/input/path", rclcpp::QoS(1), - [this](const autoware_planning_msgs::msg::Path::SharedPtr msg) { path_ = msg; }); pub_dist_ = create_publisher("~/output/distance", rclcpp::QoS(1)); using std::chrono_literals::operator""s; timer_ = rclcpp::create_timer(this, get_clock(), 1s, [this]() { - const auto path = path_; + const auto path = sub_path_.takeData(); const auto pose = self_pose_listener_.getCurrentPose(); if (!pose) { RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5000, "no pose"); diff --git a/common/path_distance_calculator/src/path_distance_calculator.hpp b/common/path_distance_calculator/src/path_distance_calculator.hpp index 8e8fbf8d6a019..6624f316401df 100644 --- a/common/path_distance_calculator/src/path_distance_calculator.hpp +++ b/common/path_distance_calculator/src/path_distance_calculator.hpp @@ -15,6 +15,7 @@ #ifndef PATH_DISTANCE_CALCULATOR_HPP_ #define PATH_DISTANCE_CALCULATOR_HPP_ +#include #include #include @@ -27,11 +28,11 @@ class PathDistanceCalculator : public rclcpp::Node explicit PathDistanceCalculator(const rclcpp::NodeOptions & options); private: - rclcpp::Subscription::SharedPtr sub_path_; + autoware::universe_utils::InterProcessPollingSubscriber + sub_path_{this, "~/input/path"}; rclcpp::Publisher::SharedPtr pub_dist_; rclcpp::TimerBase::SharedPtr timer_; autoware::universe_utils::SelfPoseListener self_pose_listener_; - autoware_planning_msgs::msg::Path::SharedPtr path_; }; #endif // PATH_DISTANCE_CALCULATOR_HPP_ From d2d45f2bb1ebc349349c7ed91922eab8e35bdd20 Mon Sep 17 00:00:00 2001 From: Autumn60 <37181352+Autumn60@users.noreply.github.com> Date: Thu, 20 Jun 2024 14:07:25 +0900 Subject: [PATCH 034/217] refactor(goal_distance_calculator): narrow variable scopes and change to read topic by polling (#7434) * delete unnecessary member Signed-off-by: Autumn60 * replace rclcpp::Subscription to autoware_utils::InterProcessPollingSubscriber Signed-off-by: Autumn60 * format by clang-format Signed-off-by: Autumn60 * delete unnecessary callback func Signed-off-by: Autumn60 * refactor goal_distance_calculator_node Signed-off-by: Autumn60 * clang format Signed-off-by: Autumn60 --------- Signed-off-by: Autumn60 Co-authored-by: Autumn60 Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> --- .../goal_distance_calculator_node.hpp | 18 ++--- .../src/goal_distance_calculator_node.cpp | 66 ++++++++----------- 2 files changed, 33 insertions(+), 51 deletions(-) diff --git a/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator_node.hpp b/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator_node.hpp index 037841a505017..602688ffe51d7 100644 --- a/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator_node.hpp +++ b/common/goal_distance_calculator/include/goal_distance_calculator/goal_distance_calculator_node.hpp @@ -18,6 +18,7 @@ #include "goal_distance_calculator/goal_distance_calculator.hpp" #include +#include #include #include @@ -44,16 +45,9 @@ class GoalDistanceCalculatorNode : public rclcpp::Node private: // Subscriber - rclcpp::Subscription::SharedPtr sub_initial_pose_; autoware::universe_utils::SelfPoseListener self_pose_listener_; - rclcpp::Subscription::SharedPtr sub_route_; - - // Data Buffer - geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_; - autoware_planning_msgs::msg::LaneletRoute::SharedPtr route_; - - // Callback - void onRoute(const autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr & msg); + autoware::universe_utils::InterProcessPollingSubscriber + sub_route_{this, "/planning/mission_planning/route"}; // Publisher autoware::universe_utils::DebugPublisher debug_publisher_; @@ -61,8 +55,8 @@ class GoalDistanceCalculatorNode : public rclcpp::Node // Timer rclcpp::TimerBase::SharedPtr timer_; - bool isDataReady(); - bool isDataTimeout(); + bool tryGetCurrentPose(geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose); + bool tryGetRoute(autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr route); void onTimer(); // Parameter @@ -70,8 +64,6 @@ class GoalDistanceCalculatorNode : public rclcpp::Node Param param_; // Core - Input input_; - Output output_; std::unique_ptr goal_distance_calculator_; }; } // namespace goal_distance_calculator diff --git a/common/goal_distance_calculator/src/goal_distance_calculator_node.cpp b/common/goal_distance_calculator/src/goal_distance_calculator_node.cpp index 8e4e4c90bc470..24d54ee2fcf87 100644 --- a/common/goal_distance_calculator/src/goal_distance_calculator_node.cpp +++ b/common/goal_distance_calculator/src/goal_distance_calculator_node.cpp @@ -33,12 +33,6 @@ GoalDistanceCalculatorNode::GoalDistanceCalculatorNode(const rclcpp::NodeOptions self_pose_listener_(this), debug_publisher_(this, "goal_distance_calculator") { - using std::placeholders::_1; - - static constexpr std::size_t queue_size = 1; - rclcpp::QoS durable_qos(queue_size); - durable_qos.transient_local(); - // Node Parameter node_param_.update_rate = declare_parameter("update_rate"); node_param_.oneshot = declare_parameter("oneshot"); @@ -47,11 +41,6 @@ GoalDistanceCalculatorNode::GoalDistanceCalculatorNode(const rclcpp::NodeOptions goal_distance_calculator_ = std::make_unique(); goal_distance_calculator_->setParam(param_); - // Subscriber - sub_route_ = create_subscription( - "/planning/mission_planning/route", queue_size, - [&](const autoware_planning_msgs::msg::LaneletRoute::SharedPtr msg_ptr) { route_ = msg_ptr; }); - // Wait for first self pose self_pose_listener_.waitForFirstPose(); @@ -62,53 +51,54 @@ GoalDistanceCalculatorNode::GoalDistanceCalculatorNode(const rclcpp::NodeOptions goal_distance_calculator_ = std::make_unique(); } -bool GoalDistanceCalculatorNode::isDataReady() +bool GoalDistanceCalculatorNode::tryGetCurrentPose( + geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose) { - if (!current_pose_) { - RCLCPP_INFO_THROTTLE( - this->get_logger(), *this->get_clock(), 5000, "waiting for current_pose..."); - return false; - } - - if (!route_) { - RCLCPP_INFO_THROTTLE(this->get_logger(), *this->get_clock(), 5000, "waiting for route msg..."); - return false; - } - + auto current_pose_tmp = self_pose_listener_.getCurrentPose(); + if (!current_pose_tmp) return false; + current_pose = current_pose_tmp; return true; } -bool GoalDistanceCalculatorNode::isDataTimeout() +bool GoalDistanceCalculatorNode::tryGetRoute( + autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr route) { - constexpr double th_pose_timeout = 1.0; - const auto pose_time_diff = rclcpp::Time(current_pose_->header.stamp) - now(); - if (pose_time_diff.seconds() > th_pose_timeout) { - RCLCPP_WARN_THROTTLE(this->get_logger(), *this->get_clock(), 1000, "pose is timeout..."); - return true; - } - return false; + auto route_tmp = sub_route_.takeData(); + if (!route_tmp) return false; + route = route_tmp; + return true; } void GoalDistanceCalculatorNode::onTimer() { - current_pose_ = self_pose_listener_.getCurrentPose(); + Input input = Input(); - if (!isDataReady()) { + if (!tryGetCurrentPose(input.current_pose)) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), 5000, "waiting for current_pose..."); return; } - if (isDataTimeout()) { + if (!tryGetRoute(input.route)) { + RCLCPP_INFO_THROTTLE(this->get_logger(), *this->get_clock(), 5000, "waiting for route msg..."); return; } - input_.current_pose = current_pose_; - input_.route = route_; + // Check pose timeout + { + constexpr double th_pose_timeout = 1.0; + const auto pose_time_diff = rclcpp::Time(input.current_pose->header.stamp) - now(); + if (pose_time_diff.seconds() > th_pose_timeout) { + RCLCPP_WARN_THROTTLE(this->get_logger(), *this->get_clock(), 1000, "pose is timeout..."); + return; + } + } - output_ = goal_distance_calculator_->update(input_); + Output output = goal_distance_calculator_->update(input); { using autoware::universe_utils::rad2deg; - const auto & deviation = output_.goal_deviation; + const auto & deviation = output.goal_deviation; debug_publisher_.publish( "deviation/lateral", deviation.lateral); From f8d2f2d72fcfb71c49df7a8af5c7fba0174c4f50 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Thu, 20 Jun 2024 14:25:09 +0900 Subject: [PATCH 035/217] fix(autoware_behavior_velocity_planner_common): fix unusedScopedObject bug (#7570) Signed-off-by: Ryuta Kambe --- .../src/utilization/util.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp index 457c3a1271e31..89aac01c716a6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp @@ -418,7 +418,7 @@ double findReachTime( return j * t * t * t / 6.0 + a * t * t / 2.0 + v * t - d; }; if (f(min, j, a, v, d) > 0 || f(max, j, a, v, d) < 0) { - std::logic_error("[behavior_velocity](findReachTime): search range is invalid"); + throw std::logic_error("[behavior_velocity](findReachTime): search range is invalid"); } const double eps = 1e-5; const int warn_iter = 100; @@ -450,7 +450,7 @@ double calcDecelerationVelocityFromDistanceToTarget( const double current_velocity, const double distance_to_target) { if (max_slowdown_jerk > 0 || max_slowdown_accel > 0) { - std::logic_error("max_slowdown_jerk and max_slowdown_accel should be negative"); + throw std::logic_error("max_slowdown_jerk and max_slowdown_accel should be negative"); } // case0: distance to target is behind ego if (distance_to_target <= 0) return current_velocity; From 59740155aa7c396dd078afb0184745b28291ef75 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 20 Jun 2024 14:40:39 +0900 Subject: [PATCH 036/217] refactor(obstacle_cruise_planner): apply clang-tidy check (#7553) obstacle_cruise Signed-off-by: Mamoru Sobue --- .../src/planner_interface.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp b/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp index 343cb720fb802..18e0fc7f5bb03 100644 --- a/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp @@ -598,8 +598,9 @@ std::vector PlannerInterface::generateSlowDownTrajectory( obstacle.uuid.c_str()); continue; } - const auto [dist_to_slow_down_start, dist_to_slow_down_end, feasible_slow_down_vel] = - *dist_vec_to_slow_down; + const auto dist_to_slow_down_start = std::get<0>(*dist_vec_to_slow_down); + const auto dist_to_slow_down_end = std::get<1>(*dist_vec_to_slow_down); + const auto feasible_slow_down_vel = std::get<2>(*dist_vec_to_slow_down); // calculate slow down end distance, and insert slow down velocity // NOTE: slow_down_start_idx will not be wrong since inserted back point is after inserted From 822d5b581b73d961975e562429cb42786af4fd13 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 20 Jun 2024 14:40:52 +0900 Subject: [PATCH 037/217] refactor(behavior_velocity_intersection): apply clang-tidy check (#7552) intersection Signed-off-by: Mamoru Sobue --- .../src/scene_intersection_collision.cpp | 4 +++- .../utilization/util.hpp | 11 +---------- .../src/utilization/util.cpp | 11 +++++++++++ 3 files changed, 15 insertions(+), 11 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp index 739b1122be6a1..906d39a9b127f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp @@ -265,7 +265,9 @@ void IntersectionModule::updateObjectInfoManagerCollision( continue; } const auto & object_passage_interval = object_passage_interval_opt.value(); - const auto [object_enter_time, object_exit_time] = object_passage_interval.interval_time; + const auto object_enter_exit_time = object_passage_interval.interval_time; + const auto object_enter_time = std::get<0>(object_enter_exit_time); + const auto object_exit_time = std::get<1>(object_enter_exit_time); const auto ego_start_itr = std::lower_bound( time_distance_array.begin(), time_distance_array.end(), object_enter_time - collision_start_margin_time, diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp index 591a30928fd09..5f1c17ea1b815 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp @@ -228,17 +228,8 @@ std::set getAssociativeIntersectionLanelets( lanelet::ConstLanelet lane, const lanelet::LaneletMapPtr lanelet_map, const lanelet::routing::RoutingGraphPtr routing_graph); -template

))^Oxts*3OGfy9i_* z78yO&Dxdsld-gk${qYjx0O)BxEUdEq>y>o#_Q1){Fl6gIen;bHRVJp*NW+DtwL9d3 z@OIk%dY*5p(V zmv!g#f<$+3585^lqG5&G`8yVPj>-a=sqo+GY7o+gZNpRu%~VF|gX+68{1C z{dqYj(j_x{md4}=`8Bmw_Q?GD3_iNYv!j)rzmMu3)4#+hW#k1CAHk3O%l;~#I+(N< zs|+p2Uy;P?zBt_cx>(TsO~$eymC@85w?yU(%!*%ozugoxYiQ2qiCrs*K`!n4pEp0k zfz~995F_S03`*Db`6!(hRyPCf)YYkq)aQH^+q-BYJdeZ6@z?5~f0(D-PRg-C$`wST z^499t6fRV3syND7xtfoZS3SUFUY;?+G(szrJIm!#c?$kkH0s$+7V?NL?MFkG^ZC|U zBXHZ60;i*SuQ6a`$;smIM6oz`o=OYR8P9+FtK;WJ`&EcM<*({kNbc3rQ$M?gA-;ng zwFtj=(W2kee6kjPVg9Y65&8);l6Xw9%&j3bHS~2X#&X)XL3O_;rvt8?U~asPsE2`+ z-lfAESCPGeW`)QBSG1Lp+ghnkw<0;+EdR4lyOB+Ho?~ft_+xQpQ}x=P(I2bQ1!X_h zv^bD5COzZ$ear5c`qbMXR5LE5-Y)yOy$$_9I$fjoUC5c6Rz|(%)WU;A1%~B2csU^z z+XJ4H!rI>CV6*4juPqilF8nS9iw#ooM!=8Lb`2fe|}c(-k`*!cAPoRR5n$XO>4 zxh35#RwF*=2>G4<-dXHAC~&?l%?~yHXp0T%%wP@t7WQ6H7f6JZpDCl_2*v?>-VVNy zYChE&sITamz-888nh(QjrqV7Mzl%yd~~rHy>20QfI~T0E7` z6nNU765Gy8_|Q5sW-v9p`MIlTRBO_AtJTQ-X;v5$-H=eY$Tng;Dpi3FlJl~hdrA&Q zbo2!`~m+JpFfQX(9CINvjI;>C$$^*_U5l)9|52A%B#&Jo*b?%`{A|Z zKyyv}5zhY07iUDc=t!Qt=d<;-zeN&5RftUhmi9I5>F0kB4Y+2I8zKx3c04WM+0P-C zRzJZ;i$7lHV|CT+esm{Q{_lnRX3zTNhgTK~l? z23RCRa2>lI`*#!BpNdHp=MK=C>4EUnfmWx1Q7Pvx&l;ZEK9$!Ay-k1M=cBj>ocanj zZ*1l!mg(9T#7|HT7wBIHA~{?1PHEm=X}C~?>lxYNECCoUAoh?Pm#(6SADgg|6>w?u-aG zc&gmV3*^KLoFrgDd2PmtEuJAd=zf6KbUg+hONu=5uV{Z))P5hC&bF6F3d$9m8-IOt zl{yjd)lZd(#N0exK@F)8iJsyJ4slop%A8DouXzXgb9noS!g}8@gMB&9ipcpzM0c4< zzf*x3)-5)rW;00jde(`F^+UWp?- zq7Zo#{kIDP$u*jfAID5a{RO&C7An~O+YC$4%y2gTj_5BlOosryZwW^1(uPLybr?kc zSnXPkORkVpp%YPl2&p_NY{6QfiU3nN{q?`kU{k{5SQA9AnNnRI;?Z7C(j8 zGn(zbV1AByQ4B`hwW)^l%8*;5^!6|jCatFQy>xjg3zO6gmtIxitHXK@n$NOLt-S)C z+y8jfi}qsiN9^fK)l~;hU4~sBk?goU{yq5~@Y0`bA;$-@Lp6FmsYdpA;z?K+^V;9? zF#;Y|uOQX*as7_+ri#e#aMT`cqeyq;msqh5WtYk_zik2+B#-qD+=ajUu6!G48_;wm z_5YeoT`2tpo}z1{K%4A zNls=F2@?WKhRh4T+0hoLMWUJ{&CJ(KwUf?hbQ>n+JsF=_Ewwv~+83H)$Vx)JY<@j_ zIxwSZQ5kO_4I}EB9|1SS89E4PauM>c?^l;Wm(1cxAqNT*q)o2-TZ9J{`NSVJr)oIW zW+t>Z-pwp4^;5t0r8>FDw$4K zT8Z>F?&#k%-LP*N-ZcH*apyXceY?$UZSCrWy#&{!#dk%+Zr8E5lyO|j#}~ngecQ(b z*S)XzZ;N=qgJYKrW@eU6>iv#vSDv506r9cr@aUUqQ0Dgx0WNQES{5gMBW)E!@X@BIK;uUba7- zJ?|PF?^9V0gcL4#76v=>pVOY4OgZy1=g{S-)e|E4O*3bFt@c^R7g%$3AqLC!Xk_Bz zV>>b@WssF36=B3_9(WjRaGGrsrP(%4dVoSH490!EKOD3Un>|tOr8fX14iuMef{L07 z(b7BV#fuk1lt=$;zX)tCJaFO$)j8sfMJFX_Tl`?vvuOrkM-ol^#vr!c^Ov0 zVOg1(=VV0NBTjT?t04g1Vs@a?z;0GTQt}C21`2Qa`UyKR0OiGK{j<00eSkV+9*#`- zbMLWh)j<)cPm)ctR@uv5x?wH7QcYpCNG80xHmm>~^xszt;==xFP_*Q}QXZwCbz z0Cl8JP%cLXea!IMHRN^9DQhL+!^Kd!mZ6UN;9b9Vv9ggJ~?RO7yu^-cQ>Rd?|4jq zAT2WC$$wL!@Gcq0?$d=N zpn5l5<3Er8eD%r3?6B7|2_S{F1vD2N)1FHO^fFmZ0;J|#_^uWLNcif^{J^-pQIP5?Mdan_C;ztfj>{&XNr zOhL=%UiZ}HHK&5u2DE!xxO?n zP$wNBB6|P=DLOF`T2)KqbiMoV{KRY@ZXH#%xMc2X8kk@&&=D_h0^rGL#l8P@39V`E zzakI+Z9V~pe%i6&jn!kE0c*RKmd z8f1T%8DO4}XcDsm>fX|4JT^bE26t)}RUg(e_-E^+R70>iTxbvnQ2CgAjaPScbUZ{B z!D1^{UT8`IjBA&)qumpgBTTd+WeE!pqsHim|Irwi zFWv(X`)7q@fL4L;f^)rkV^paTrh5OOsn|G$&6D?39O(?s+#r;8DA?d&Z@bEeeboV& z4)q}3er#CM&od2DIr-Wjl^_kZn|-#ql;~RKzud*os|%o&!obR7(F0{LAj$$8l$nAQ zd}8s86NTivYTc`Hj%WWoN2)3}G%r=ds7LVu)HrB?;tL?o`9_7#^^p@mj;d1kjekd9 zG0oOKFe`@*V)Euq?WX~P-*|Ic(ryp$K?do+g#M&bccNx3kW#NcX-!AEpV3q;k=-m2 ziHNh*NHsU*c6&$YPKuvKPqq%a#uk3L7HI4+;90;q+p$Xr z&s_(%;X3U$eDsVaYtjjdKmFYjpu^asY!&aYl0`HoFaL9|5wj8LQ~PZ?$Ov!i^A^jE z>vmd2ce?Vu#(|-1~sL2%Xz}pkA#&^Y8e4al`V?D>q;pOC39OC*(PISYr zHLHz&n{!q3;EvkLFj{C`2iMe_$R{$0yw!`VV=py_LMV6Y&h!QX_**bL+f;%zaoSdg z^-_Vi>+Ar!C4a5GYCa$KDk>2!cc%GImC2BgmWL>fZ3X=l6@V%;Wti@FEitu(9$V`e zHP>@HDHjV|3OI*i5x-ZJ5;17}W{a-65w&EEd>dVcI}f};jKTxImn7kT&^654VpvB8Usx^rM_kvmzFD6#-OgpbPx_UL|{( zOqTnFLqLuQ>V0>CL!|I4#$&SmRxqDyeP`>p7Me<$a<_GqR?x(Bjeg>SqSYKIR!o!f)RukSOyRb(duTSR}sxerd)cJk_!6=P`lS&4mf7F z7k{V)Ze5yew8@=atvaL_tOn9^5ppwI2vjTq3G#{Z$EW)c;bPBXVzPP-ZWzJg7(jo| z9v=z#vR3M${R#^3_$@r83Y&Nn*la7a@!-rTt#*$jL#n)bc)f={1?xD!fpH+?0CWSK z)_gnnl2GPj>FmM*9dTCJfJ*A--w=enSDVWuJ%8{_AK~d{$p#5Gu`)@t>xk_AI!)sw z{oHndQV7DN@AP(lpx{jFtG-MC*W#~&bBtgoPR(lSdLUGMS)VO1eHUTUguHvx9D3x` zG?!QBt#QZfpklh=+T7CQ&SRKZTE5_SgmLl6%1TC*)JCj%q1ogzCFg94U-K=d_HYIz zS>m1~ei4hQi+4Q<8HJE4&P9s75v3<5DqAaYqHLe~xb{&qO9bke!}b#~LIrX==O}>)MJ-xBCGbQC&0<`n@-gJXl_|x%dA0V=xdy&GuB4TeUo#0L?Jm zGQC^cWTBs$_|3iUD`NZg!jAlLy&vrdCnfi$-5DVEVo7UT=gR)8d|Z7_7i8_Y*20zq z&9{59TdXQ@{iv%|W;st5Q7??H9>aDKx(*Hpb0(uchuQFeaqB(Z=c7uJwaFgZ9;VHR285il;Em9@uv2F?J7UPZ? zC=(k2Q(;LXi-c6yL`D1ps3qu$x$X z%2oPj`tJWWqq!iB2nc)p)U&)rN1m+j4@}*5i0~`OQ!)Ys5b zus|t5cYQ%=r7oXJke{a^P{4wkD11FS3f%UoFCk2`MhDdLXgHNYWJ4GwgP!U9<(ww- z4!>Dx#g+0}Q!n+XV;O+8p>#m_GH8Rglcehc_K|zm`>zG{zYvdT7DfF(EDDE$+A^P4 z*C{#eS|PQh#e@>io2>bXb0+!0`&_!t`soN4juQ9O!9_v-58xn@szQLKKxRSMDP0t+8(@Q{T*98KN}NvH)O|&_-fBA?ebc%u?QdGv9%p^I|yz-$IIM!;Z zsa?2D!r(xXyy4?;R&2ywV~ZR`i7L-!p(@={lYFEd#e(8*M|9zCd!r=V(Xn~$f#-el z0M|A2tI6K^bfzPmoc09)04TrsVZ{y891FnJJL#_*ztUgU1~e5M`~wCkfWQ%QmCP!1 z!ErCX^tSWKRcI=7Ob)2PF?fFGfzXjU=jF}*alwPdY=QhoFn8T3-_d`Gn!L}Gc_VJ1 zaB#7*rVEZYHiDpJ{47W@nR}p+R+Pm;A?bl!;YV_odGE(1KLG)SqS@)H=vS{Csv?O@ zfUOu9a+II0>y$3AdM~ZTd4vzOAzZAV&Am%fk>&B`gZq5ejuOFHMcy zEj)-oiFGC^0ohPMqJI*tLgZlkM^cCfJ$c%Y-U6M>wSpqQlx0AQ-H;~K)m$9e`X_Nw7YZCU=F?G}0NJxbC$6w3 z9Y7IeH=byxat9gEK!(3IaV`%SF~){B{#R!>@bG)gV5PYK<`Yv*rF^5m?ZbHGIS6Z3 zI1_(TAAhIxbuZB_xh6S@pZ!;U49E>elX<3K`A~)Uh3VbbgO32&o%B^q2K@ipj)!(0 zs*>tXLuW*K-QoE2vNB*a*m2)#Mg*#f^U!Q9|Jd%l;1ONL z?X5q$JN;M_6(Gb{4utpsK&t{ws6oItllOm~LHdtE^*xX;hnQ z1eLZHq16fs0jvWmLX;r^0tu+7s1>bM6oi0SQGtLmnS>!06%m0b%8-zNG6aPLWJnk? zy!{2yN?31Q?_0ig-+l3~Px1}>?6dc8@3YVOo#UwoPC^)LxwDnFBla6IgsZ?vuV@1? z4K^w6tgji_4BMH0y_5B|+o))7N*6e1{WFil_s5Gpu#N$WC#*kxU%>cvPqYhq_{%4l zb-$2`t8G@?=&0N=>)0-2d2KRDNM)S~Iy76?NcV8;0ol_;S)|7=8JqKMy@_Pj)yu}< zR8;#g4I1QF*A_b`tohL{L7g*$&l*mG?UQkpk7vE>TV${Erq2;&9M-6|&WJ;fQcLAt z&Paqo){WRWm*bT0S9oY#c260fMAdk+KK7{w?d{ZP?9KKN7-og<5U=vsDPJkKhK}qJ z=W$f09;#gKO=r_L`~no0h3ky6q6M%E)>GIPtkN2WBvqkcq zbIMgSp&L-hrnvuM%lf?WP1Fmqe8@b$&M!rOH1A>^0272 zKY=X9bHR~Z2Od)1td4^$AGVDc_>KLw1=!Lp4M|_)?sMYerJsK=4Jy2twOCy}@Z2r5-%hOr z+Rjfe2c)#$ZuDNi#`Strai7UZf+Q*Zgu-Sd`|cGmUeiHHiIY*gZxvRTFAwd zG2R~TU0ZZ)?slJ*v0e2i6d9p0d#-9)asPE zljUK!BTNlW<6*Wv*Wy%c3PN9FCM7;nQ~Ptuf*1iu)@R`_OY8|CbEHP=^?z&>e@c)L z>C(q+_IY(f>-N{}zH@13uiJbVr4rr#Bw#bQO8V${^_J(<%_Kwj*@A|WG!Cgb((jwS zg=EyPsdSMYq0rge^p)GszxEI<1b(?i;xEQz1eIJ+!)S9%Y+rkbWy`EOYy+2qT9Bl#b43))ZQA|s`mhuWVe)?THa=eKpdkQAf7VV@h7xit_YJ z#O=6W2t*XscALb&@^+d(zeC7Rl;-%`4xBCk33wxW-U*dkxXQPk(_Pb@OUte4qO_AW zs}rj(iZ(J#8`-;K1nTJFqTdUHeDBjESB`KA9{r!+`+<`D&6t6zM9&5(W-o7qlU&oZ zmju_>On2?1ke78Iw%3W?or+?&CV5jcB+VYu>&5tTe8CFV+3b zno~y^rE|h|(SH9+9PO36Kvc3N6*i83<28&Ux~`o84Z971q4wLC;3w!kOM~lO=HVPt zjxzSnrR7Ev+XZwsr;uAGEfbcp!%)eOH|#ztY>*~A8fxa(37c0+oJS?jl;=4WX8D)Y%oVNbcdWXd6`3!= zjHcr}=;?eyO9zg*S~I^`$nv}Akx`*=tk+2gaw($BSR{ zV=N+`U)dhnv4Xq@--IKe+7f4691yD;(b~^@utvF}5{#^FPIB*III=ChP$FbwCFZfGk-MuS-pR&fk>LFC@&jdYOLC6!2XztqC-y;?D6rcpRw+|cH0$O6@Na9wW)Oy}HUQB&DYgOB6N7f1N zzTeIDxdT^Bh$l*`(zNrx(3raKYt1^AFrjFxn#| zx%S^6OByjjyZ#hlF`?TC4>u;?Vt3a>3WE4pN^t>lP6j{0kFtk6Jdkd}_usZH)gWZx zu|J&k#E+^2R(|;vi$UEvKej)61LXT|og~O1N_;BQoAMDyl zpi54nSa95JL6^6$Y@Z8hm#^K+wzKT-O_H7_A80y22#=^omp(tD&#J7p$;IF~A#`am zue4HMr(BAkkBy?Duekpt}z4!77ntOyeTSiL?>9|PePEDFFq13uy zfqFdDC*vM~!z3*9{v?d7Fx?v$Ia156O%~<}2e6|B!mRT7wT613xdS_Wlb+f2J=d{_ zOFEa38@Qs+_rQUhW|$ync0t}#O3BD8;r>NE-RpHtl0#nv&Zx0|eOGwR$@Z20I;cML z`JA5c`aV*XbTo-nUD|R`cyL9v`{T{NG19M0$V~yogLUnLSP~D#4kC{>=}MNJkjGRc z8cnsiz_@DQH>h{IcQF8KG)IFwnk<^R#WC7wo$2cchLtImv?_4Ic!FYJ1 zlK@OiEJyDOG9R&ruX8}9er%D8cpz}ob|LO%2C>5zH@c%2ru+(RTmOT9A>A$?3ES+A zan_4HZxba&&&-2Mr99HBjpVK7`1teZS>Cc|-ex4bkyPm;tyf!aeoHtcx~h-eXEgl4 ziRFauJHt8Nq^@I=15sO>otrG_wtZ~di6%?nNbF0IIC|f4)AO=n;3YS6`?(@Yr|*_E z@<5BUu_aYwE=};sI3CJd41YE@-v7)AO%oS%XEr59h7T8VN9x)O*AT>w!}nj(&5MHz z3q$bLc0(?yLq2;&W}jwzv3K`s+&X zk_(?ix;u>vm~#_APaox- zzHmJ7zR424om$k&$6~SJt@?Q9@Y=-YrjpUHnl8&>Z>LAn4Gql^l^!gz__Yx}aZ3nu z1$i)27=)JfH}~Ra)DV)jtI?&H@QOwB^TnfhqVGNINHvPx|0YhUs%;0;E`P}0^EM?J zvxewzX0Pfwm%WcPA{F(Fy!1^D*^C;!6jZmHbx79Gs82VN4VA~s4B3sm7(7vn*0s2< zF-Ib5E{!Y?O0L}i#CzPUJ?Z(4&H4Jn{pYeH{*(+@^YTi?m8DIC+r8kZF8;}$(UJ#o z`RB)bA&TLswImn=yBfbUM+Eg4OFtD4PoDSLY z+}}lK>oHcczh0Oo?{CaBU#gt|@ksr0Kw#8u zi0Y{YQ#mDFy&A3lFDZ1vUXm!*#is3!j!iE^n1&W^=c6SL;_@Kh_OUTGL101tq3>q7 zc3#cV|6%OEduASU9A687bejC0lMD7s2J7MQcoCiLExzZShxkX@e1c=c#z=oH^sIe%t)NUAV5XPxbh63H!@&?M-&G zQYh%;e|b$sUtsJs8e%k|eGm}8a@Hl8z}a_4CT=M2@DgQ$m-1n;Wl%Qz=60u1I266A zSU@L>im3IE=6N0%KFW#|HCu^T=c+xv$JK;Y2eHy-*o6vgDPPm)AhEcLhGQ4t%BEXA zDlSNGFSYG^fE#%1R8w5uc<|hg!Y8>|yAMIGtzbk;j8m9qGk-Um4L{j?wqWADSYG|> zOKs|PMtb7CZoP02JtBwhK|&*(N)lTtYdfyZSr|8D6;$=@a5K4y8&D64U}HIn4X$kqb0I$5$kH^I zwY2e!hFUV=7)!lN%j;P|#E~Z9M&6|r^$AHjrBbmr3uRssO39DMyiV2CqxnYEhzd$2 z?9wC~EM$si0UinBBBTT{v27=zX$D{H^hG=;`YMwnnY|>~Xe8btl}`W7pbZHy26CB)9QLt&}sfjm(!gK&Gb#|^m5XKl|pPIo;3jb7> zrp39AzZWzCfRLxdVWde|k_ZD6RkfFDT9_EY)AiSwzjSUWHcg%wx8a>kNBdN^W8*Xg zM84B=?OYn1?&T0ealpUAyq>QJKhcIT*fD(dXDoD5hpZvV5V!Q z&~@b@M6xH4J%HHpuBnOcodKBLC)TgunASJhN4@}LbG+Mq8fjh%BD=)QwR7=2nzpw8 zfkZ^KLB*#SpMhk{193kZGAG^wR6VYf;8|GpB<|5PLQ}EJ;K$knZ&I+zer*7Q}@a9#Vcd- zTckQz-DGlT%z5$WudZvio+LClf_)r4*7yZt%yMfQfs)imHjg>loS2w`+f^p<>D*r? zY061xiNQkObnqfZ@0iVct9`H$!dJ4uKq~a1A8$;e-uqySr_SVVMAREPre2Ha|Aqe6 zo5y;wlI)or?lzeb9swgfc`504Fv7C2P9%LQ_mdBCZ?LLD^SpbDu;Atyleqb3;N_@w z)f>JClzKkqhNT*EY@olG%t&m(0d4=NLfknzcuZA`HvJQph;iS2f*lbU_8}hof%g8P zz!@7Or~_MUJ6riNtpvXEmxD)B$8><{XOqD6cJRXT2aR8W7g`pL!D###w!7IVB9(p0 z(I|()qqksVKZqaZWBz*hgZmE<)I*Q;;&&Hwmyc*A<2Y>vxb^Xz{hy3Dc2t`|O1NT} z^_d14_h;59Sk0<&WGoCyA(VgkSIn2?-SbBx&c}214+QG~D4vI;nwbx`^*yD(QuOxd z<>2hw+q(Y%NPz#}I@QC24-(*5XgHY-*{A-9%TgE&?rb~;B zp@3O=ZJZ>AOoNKC!IFJWNQwQySPU7>{?Nb%y6OU8_^8o&5Dy@Ibuy6t4nW$q;S`Kn zqtA?iw8&eY?|ocMK(Z?Klc(1v10J8L;1@HOqhOvu10W0hfu#K}8lAxWq%%0z>z_^n zx9X5*YihB7Lg4n+7~D!tKh(RC%=-g+f^*ja-{s)pxi#VQbCYBvQ>P(G&w^b?<%4c{ zvV&D-BmdX4k@4)i2pP_Ov^eumSRyir?XPJ6h}p=vz4rm6e?Xl1z-acNBh&wfLyues z(ZTwX07_&L-vEm>Ns8$6^uyUjbhs4dA;sXJEXmzw(k*!%DC?qa(f0CF!l!AclKnV% z8y<>#UpyZc|6YBHyBrQ6R@^|sdEYPAR-0)7LOMZNBGh&hL ztCmB&t-1ZrxiJEr;@x)fE4*==N3RD}Z+YD4MUqb8KWUcosddr{O=+e<w;H?1-I$GstR%<1i1dxurKp&9ow*Uscm} zk~$0I0SOSY>JLBDneRS!WnWTL2w}M8_VyG{Cvu)6Ek}A;OZkq|o zUp|{0i!L#Z*fudUL*1_Dw zN(yl)qPooO(WdC&wW$6-Eh3o)UgBze-bNRczd;YTj*EM~mj4?zwCs>W#86H4UYHWr zxDv9gcSUyS&e1aT&>?KY^Q+E@taP-D8d4PGF-aBd^g^h~9k49Io@mRnQl zTE}A14ylR9u&{0PTRpxpn(slK6%G3mkVh7PX&m#CZjA{besacON$|q(I;7V5et(=? z0`Y!%h%Zc0z>*Rz4oeS;?kIFj0AJjl{Qj-bB`Gk+P*_ThMZR`=8KmPgj8}Q3>TCSy zMS*KZ=tOx`q66WbfoB>m5mDDb8-BXeG^oY#lywHj1Z-l4D?acTQtY%vf+FM-%(=9D zD25c`h#=T-qpf0lNzh(W&>W+&Vu|JsWQd*OrrL^b%;)bH~abk$(9J-o42ZU+iF2kNy^us;`@; z_<#?xUSW4E$^ucwP+Q<@R0=c8AO%qp4rb#gsEFweh1BLII1L91sq=b|1O%$wd9B4U z_UQ|Zf$RH<6EJ_k)Xe!4kB-Pyx-^CPn^p(Kt+QjqDcuy5Rj2sC$;DtnW(Rn3I3s(S z6E&gN)Hik3Ro6`7J|j>~8cj@u8j%Z9y$(EARDyhH+8A8wefeDfwI~Oxr5EU4sfk@iNfc1lR>cP_69888?k2?}of8pA z9Wrq3tefGAxEXzXCDuE*>x3#X9~%J6iZ!NwsU7NQWgXQL8WS+nGK}hAWv$Yxh)55? zLMzwqDno2{CM;H3HzlavG&o3-R;x?`=vaF4mkmKbtvSZLx(LT*Lg^L@%(n1~aBU*mnVG?`3d^Yd(VT zm;eeXm%Le-zPioEKX=+mE@1s(K}U_X;AeX@ddtN2Ax zzc4gBMqn6QHwgL(F^H>DtafKQf-`KyW^dY`2$+%5KH&@S-ZHSgqbHi8<>;tS>*}8Yxs9)RMzLv( zVDE{MFvTbIVYZ0=cn;1Ek$315(BDYW+z)CB%r6VTrN48%+dWbUkjkiODZfUOAE9u z_F^N-^bH57I@5EI~&`DX^Q zWO31hD@JKd=Yv-7){P)GfwVOx6I8h`c%@uiQ$P>Orhv%Ijh&RZ`I~9lF@hi3GZizF z&whcL(B8gkXQ&B9gTdsNxdGg}{6mPgr3w?TmP%|B_#+cK}ZQg$|CnfFHnMz za;ELQ;7Hmn$?>WmlG-1AN?z>KT-mc5|EVjA!U7Nq8BLZL(2M)vOe^; zwfxGVnQ~}0Q@LlTJL6vtf*ZOL6reCoCqQ9?b!EkPsmuL?;7S6Z74ctq$^X0m< zc9l%Uwq5|5SM}Ns1|t4xpgL~6BPenx>>>xafnXhqv@kEYzvTSwQ8_KlB)+^9T95GN z_~J{7G{hFzlZAi{ScuR_{+J?8^_XGo39K;H%2wces!T!?d<0A(-hv<>MEvi7GjiPr z@0H3PbSX3q-njbR#;S<0^68RnxZityQ>2_(bhfg!8OSrh2@~Lm8x$44A4qe>R)uoL z!b3GF(@b+FkQR?bwI7HHuvVEQ@#=ugH0X@AoR)e8XfvB~P}xlWNIF}Wc0DCb(TD2c z{_I795=6X~iuTu7ATa^y5|2WsD=Pjr@F%#5Y&pkqrz)xQy!uoiZaWmtkD7#I z8UzwhAIz5%gMJ3`+|q_5w@#d-mJfn46$y55PP!JSem344k+Zk0Z^$Zz$pJzkJ&9ba zXk<;m7wf6=m-F{-MWMlR4+G=%3!gAg=rqP8RuA+&f#;4Haz^TP;2P<6SDOaYr7v+H z*zQRz;TyQ$FP1JRq=p8DiS>bY2HX-(b>JieE`G3l(T+u*vNz}sebZHn_FdYQ@TG0}Efov(tzsr%6Ep4ba(&W&HqQZ8ON))Hud(RRKxC};83ZBn`4*?{QG|GhBXuipM(De*XPjc literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/return_before_stop_line.png b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/images/traffic_light/return_before_stop_line.png new file mode 100644 index 0000000000000000000000000000000000000000..7e0bdd704ce58acf310bbb296fd3019fddae56d6 GIT binary patch literal 118035 zcmeEu2SC%;_P-lP-2)X7taVkHVakjwQ34`MmIwjDOc)7)umqo5Kx>^S#5zzB5El@Z zRsk0f2cSa0f> zU3a7A)-huQsAI-V*fV(&oOyOD`Xc-@)_beYhB5JZORC3=G1H}LZKJyTIy$>Kj9G!x z=>N4sTGEN)O)|18?`%u*vUT?sCp%E#6kK4e(3P znN0JAe|;6?Y~*Ctz%RUqhns_$gWYClm{(gC2SduCM>cOXCg`n@)_~t`&aMvdkB$S; zm4Y78aPp$K!x?QUDJgMD^glRhWb0__>a%N zPXQ^?D{xvXB=K-7`ae#C$67cb+XC6xlPk1vD->`m6!E+t8#J&V(knJ7@CJ3}FmRL~TYH87Ep1^x`3V_+tCUmY)74<`b}-oXu~v-jbW%AMYLy5T7BVqZ39WSdGq_Iong6`tMbcmhYzpo!{u-OmZ5SSxQc^|BAcq zz|FjscstqJQ|SHAW2Xl1RzD{P_~}KVz<7f;bMWPXo7{ah9NZAQ2l&XF2Sjo7&wl2H z*Jow=E5m`jVrpRPMjH^kei^3v4ahLC1Cw%RcWehXfXYyvf$w^@b`EY^DBjN0eg(3l zP^lDm&|)`qVS_EvmE=XCk?l1oZWJW@_70A=G&f+^=MnI3&LpIIREh_jwe|MsmkUQ{ zUj!-}unF-4XF*Z=&!C}fskVSF{S--Sd;5@9NN@0U2Oeu|*{CmV;kQA?&diraWJo&O zZrmzK)TH?6;p}ntezG`%pR5njo#;bw!P5yEiVS;qqOf-zp+(TFz=nKur<=eF5u*HchICNZb9qW=;m!~yplh{NX6z6?EMEoVK(?~e$Anh*W1=i)(vR#Lp13#On^oc^ej4- z(KnKz>mwSC5sg}Y`Wi9}m`4W9W1tE5YQiq_AJ@;qOkYxW<5oX&Gg*d(yP}^RJY&Cc zlan18(XrKSv!<2|j0fZ6CH4Jea0F*p646~zvj3VZeY24+$yUeI!$R6g643^0^nm-$@&2r?KJ4J^gyxq<}V{5AUaM>2w4duW92)g{?WySduyAe7Kz=(*_nB3bU&5fTj$1IZ)O5m`MK z5|Z;_I--l|2+`ft#a?5BB+*@)MwGSyG?G-*CHKo8=#->|5y=o&q#M4Z7JKQEJAOw$#zE1W!CKSL_Se>h^uBNUu?11lPqYZv` zxUJYV17o}gteRqB=0>*N2xthJXJD)gJJye(*e?3X_z^&x9WZp#LSsq7GcpKakR%(x zwZB9i$b}XTsPofvG57mBsnd6skw*CUSExf0O_0(Bw9|7jl>8g11BsOZg#L@v;q+Wg zB!N2E6#NPBz#xUKz#XtBm`{T2E1CITfove0`)ksx3%hHA)76ml18eR3*E|SU@JDrVpE+wx1j+aV zOE?P7_RIFafUBD3;7?-`jOo$WarNu{DiXrf0kr6B88N=}n!ya?M z8sZl`GX@_*6Qs5u&%k!c;1G%qvtN8iB7p@kN8WuuG7cRHdFs-9(0pK|uka%DHFaS> zND%p%BTU8(wl#XjqxJVqz?$j~a3B2sem`>9I!EKAny~icYi@{Tp*e=HbK~R`C#a1cxQ}cjsSTF!@m;^q`@zi=7Y(jpbX?fhG2w; z3=;5Dg(`x0TJ)&A26dvJD3p8=Aki84i)4a0%Wq9YXP&t{nb!jljN z@b!8Jj{{yN=nZx+W_Jc1V_7Es0Xy_{UU`282+LL>FT6j_MA@o880Tv;LcYLv6vs&d zY79YOkl|5gtA_XvC}Z*$C4yj#qDzEAi1UU+;X0u7*5EJY z(~!NxBn``v8tXzX><=QGucHkIm?ot^B!4^VTp#j7fIfsENL&9l+F(DCZ}^w^COZ(l z{f%^?9IoGA+)r8HJLVz$y*$%}3J%E0Uz4>VxrD!uZ@P5IQPBV5eqwPfcx}Ac5c$+t zj62L)_2)VCq=_g`+F#RxUr;aO75AWE=fJD<@+lu;r+&YN`K6Mn;{b(qs+S*BGkGJ* zDdKnq$br(aoUD|%oV4WUKfF2VU#hZFQqnTw1NB#@Ayrvfd2xBHd@U_$%c}^JKF^6t zm0wdeg?o5K*WX_kYIYb_o8?vief~!aq8>8Hsj>aN!lIXyo`D5Vl<_6!0IlJI0b2B@JX-iL^@AcG?%ZEI$VGjvx(Mvtzm3B^=nEpX|< z5NaCI;reKcs37WYbiHjGAc;?sv){JKd$Wc_RN*<>Z5!xN3Z$U2 z>c})Hw&p>lKrK{EhGYbmjG_HbIIE$Etxg+OA<;Ks24U~#S4lqi*!Cvs- z1j6Z&jxV9VM1}EogDVtRsQr$vt2Y!^X!>R(Dwuaa!Zvd%!3;UBy1w=<+O~E^lBldH zNid?*Z8aqO&pS){+G>L1@1iYDF!i89i5T29Ltj134HP{TP{DaUV{Hm=JYO?+Ntnx! zrmv~xP0;zz&htVNSBWNLNPk@~>Fv5d&5m0)LghCo9WTIX61LqLJ9XJQYV7SK@+*aTy1lGfk8Bk!< zghY)Io&gRG>>S<~#)Fg+v^+p@51qrbmjUTzbl+z!Ccy3*!o6Bx&{0wp4@SuZN^S#m zjY#4RtWrafyv2p?V*zafdN^p(V91~r8{7tH2%_3Lld=9N)a3E+Fj@+dvXY+-5YKK& zODZae<7E1$A7rfL6?iQ~gAJ9moQ$|EY#y>m{}DUIqw{~&PW|b|9Z4unV?|u7<;B(4 z$-&IjZyU%Uw2-)3m{~C3-+?9>o?XzEw{Um!w$t>W*-6W~8Q}DxsI2H^VN7v>#09hm z=t_M)XCws;I$Pa{?obpobCWcHf}jCT63KIa^AD159aDEA$T&11VYbeM*Z8wd+RX*V z$J%drcg z2G;Te^B}b0*{gor!9T&#Zv%Cpu=WG9DRGtk%zUCIJI~TJc{~n8hQxI3+wM!0I3~6LBcvfJL#gKv?Whov& z4>lTdyg=zcVlZTRT>2jkZ2r8#Ao$_?b62AePQZ|C^0AdRp<0LO{ilHV2p&iIQ>vY2H;u-nV`Y7Gk|UcDW5}^ekFwv;)^-p7rqRr|Hl3x z33bfc8DpJA0IHBHGq!*(Ed=JK(D{iO2@K#3G)dk7!ceP0085fVpl_h*gw-Gj?gY38 zYO==R2iG=+KtASPAYewp1=al z)YNtKJ%|tpLq9Rrn~RO6qmQHv>&d|+40CFR^($e$KmRQOfs~Y-xGcQFA}u8)FDD~E z4Ctj4r1=893{G4|TABx~L!cffj+5t||Bt{uFNgLmJ{Z>6|1CZk)UH3OIOJP=&>ydS ziw{r?@P8>j@S;#{c`qr6DgL`sO!6}F3gU{qcgzM#BMJ~i{9g$ecv-LCvmiv8mk;*- zCwh6)fozXQ@9{xak4z!M+hiM@sPIY_P7__k-UP#LMf~@sdQn_IzorK@oqF8zGr4fJ(oxIdyoejptF zJTvI#kc2AL){Epo{R@+VoYr-Z*ONJ20H*JyxS1i^dl2L7#fOMQXoQrcu)!d3_R$-{0s7+!!OW-9id$u03z%$ zae3^u_b-?wBm4WPh3?$q;N=W8_+j;u-$gQ>SoZ4^5CKBPix2+yz)embpns^@m6ifi zJYaSQu;5>SXtGdL8a}n8?8vGAyKzmP-!cYsaCF%7&(Td*hNt}l=q5R6n?^Uue=orC zBykYH>1@@~(g#d8f^0kfsNIDFH?jUSi|@`%4UL+Hi+e_fxDyo>@$pbzf~`n>m2NKZarmE`r| z404>L28`ig&uPGi7|`l}Yp;+L&pHp<+!5P3YOk2zb`7;X*iL`3J>rs|ZBf7Z!Sx%J z-!nky+HgC9Y)ijYl9W;a+4*9XWMwfw{Ga;Lqp(WX&dx!bPhp|F?9Sr{rdm%>m=~4 zhi^5jZ#64a6Z=-P>aR`pfBEIVre^h@aIoa%q{J1!l(2Xn)Mq0gDc6*y z1u^z;_}{7pvFm@rbJo_Dl$6r|uV~Q5{u^`2a*{Z3BR+e_!<`IS+0RY$gSYm-&td+G z?)p(X%x1jz3cwrZlfU`Aas9G1B2Dr?=a53`RvuvB^Pgd|f|D8ccE!KK2mM_NKIfhW zyx{*6uIR{qTO9)flt>#Iy+Z(vzHm1vM7QOAA~SY3fV@4|BxQw7f%iXv430mFE1xMIKUq!me6(4&&$F11#NT#J=TL`ei;Sv z;pK^cZ`jW(4E=d`Ng^abhJ%vm|0)~CL6M77X zBOb5v_RsP@JcIhLP4vjazDW)XL8WAQ#(dEJ4phAc@9n_30c`kJY%CVR{*y0v4n((K zzLGk)q=8)>_*!fK1>OU|a8P0NA<#R5)bKH5M907z5yrmT>o|V5tZ9B9ngqs8E>y=i zWlg%(a#4Mj@!{{J*ZgF6cmKUpdWS;PuRmTg?H`g8F5mfHW7_wJL-3ZT<{z20^3*tm zt@t=&oBgYg9=j(x$FJ!1PluO`Q>^l8qcoPOMyD<~IHs$v?50|NWkMsXJ^n*?bH18L z#^hO|>O0j%CLa>Qtt5Bl#Yy-*rxlv7%J9yq4-`GzzMR|@A6I^E?^4Di4Y%95g;L&a zb!j5;zrB#yc3o6Xi1kQ1+Usd@q7?1Ttv%CxmB&rM#v3#C%a8Gb+wg2*g(!nLXrk@o zLdn~^T%t|cx%A*raz-jnanQZ}Pph}WO|43jW6_l#=FFnb#h;)aVp`5|3oV|?nsQhe zzjN>e=ppvDvG}CK*w!7`fw(BQvPXY1>r;aPOhaF}N`3ePm$$34+G-0~$ zxj%)^rfv=;cv#})$KF^zVi^+_uNCFW`P^Q52+jRw;sj1w*%Z8dSEtg}Y`WPNnW-Mz$+0<5s4s z!8DvxXNIp?oymYjcM6}x7B^?gWY&J>=Jncau_9eN=N68c)(aflxvzfel8{?-;c%1&!+0;OlGaPw=y}789CPdmXg8p|i-Cs!M32DEO=evnPT>5sV{VBlo3OKP^2l{(Po2yPvyKy3jzrK0 zSldY7@J%U(iYwBCZ%Xk^DZW{Xq4wyTQhc)%-`uBRzQ;GE_@)%!l;WFGfIIyyruY_9 zd<(RPMycPF;#;8oE&DVyj{0UPzGa`jrDTV>jNg>vn^JsJif>BMZz@CnkJKq1DRNai zA1-g|S{1c#RkZK-QGso*qo&2(`uI4p^XdXqW5%T5%$0uSk$Wd`8XH@&u8-j+{ro^))p1imQIOH#2*$ zYWHv3=p5S7=&~Rt)AG~Q?}k^Bp!k;v^`NGYhp@sF2g-CDzk>RjC7}&7gFft1s6S|P zsF<97TP~pSRY3De>f4Y+j!&_P+)<|GqV!!OD@}_rtgFBx5#|+qToJcQstJ z>0>PEG3c8&O;FtGyR^qY#y&8$qzIqai3k_g4m$v~uhxPCG4iDz8dm=Gw>@8k$!pg} z3kJqr|8=V8hZr?s0lm{dyPPRsf|p;Dbbpv{2J2hA5*F)rZs}gM*zHiW&F!kcY{~9v zj_zCX!eIRx$J{e13w+Kg4@1D8YXJ-ufA1ddHljhPf9N0|8A zue&E!>b{7{A*VJ*3D=d>CPa*1ML19u9h`A8uyD6v_I2C)oBU_slVmL9SB@B*J03P+ z=JC4OXh+^kpn5W8gK%g=R7FlseNx$W^#&l(@}Y>kN(nE_1)6Pxpts`MAfmBpmyOq)$_l`Y(- z=v}E<+nC-vhw3j@6Eu?W9w-R5y||;Y7G~|Vx=V*s0pbJtdjw6LngjmNeOhd zV!U?nBZ^D)^v+$C9VTD0r91L`go<3-D`G^HS|qdBd#n7&o#ZYDW=9;aHw0$08!=w1 zAH&mY5_7Uw2-;YUiSj7l-*hA*NQUxs#ih(om662Ez_vBLx&HK5%knytf@?qBoWfFB zMbj7}fr#B9s?f*L<@9>#F%KH5ttU^3m@8YfM6xolog+xk zjTCII%8w|FwzO#$3Ao--^*%5zqq8QliG421A+D^VxYKp7;dwjmv_7(5v`t}faNBDV z@rl@-eT8LamhQKcyHd;QKQ&HTKoz*LD0~Oj z66Whmq?R9uUuK!;Q+a5SR28ds{nRARQufr;`#OjA?OJId{yinh#=r5lSxM*F#(5&C zm2X^$J*`EJZ3_~7)0xFa`tl=Hk&6TN<}YaQMC{E+>@80Ck=xr{r54fNc*`gx=}CNQ z_M@0H&!yhYHBg>Sit^Ncn*262T&>wfqJ);jVa-VG3#hr$bj&+nEIeaJ<x(C{ zTaM}KHRYH!%V4wjt>jdI%~#vdOnI1Dd+~W=BeFCq2=|om-YR0>QX?1 zw-mX%BizwFtHkuBd*E51F7b(YDzzm=Ut$hb>6n-B2+bH1asoOZN~a=Xxk9M#!NhDn zRU)(QhQi0)`~11Kd$Ux#8d9wunm%;zi!Ujpx9h8RydB%K@!fmjR|m4=M5+U_t79Z+ z&b6tunCO6yA62(&{&qfG`9^ZX&Am(JbP>)Zm*i8uLzu;3$6XO<3F{OPo#6Edsk(T?P|2?ZdYl4vo_p!S%Z&%?-OeY zZri5kfrAj4M^dMuI=en6&fgI@(Q*ZK`;^B{WeJ`M4mzV8$Oxf71+9x|dsX4E%(CqL zn@)0(mW==*%Bown_@&L}pd9zwI@6cwbqCgN_c^p;S3}2?x#gGF7%|r07=`fpv)y}= zD^>)*^Q_eoP6~SGX=2mdkcOLaMrKV^z{f{+|1j%pdJ;-DvGfw>vybngFXoB7*F6G;qUU(h`m5*wa!aFVkY$CH>N9u?bqHYu+0u6y4cYIAS!{g#oamJ60Q zGTp{N2kqBpKu^ES8MNuFxUxv4n)Jr7!ZJ&nitGr9AQIU+<9K(|len_;N~DI86WyxT z_$2XSX#qYIj*zq>S+4k}^T+p27g>7KF+X0ITB{>rqejw~DiTj^SiCCQ>+x3HRMu_F zQz0YwYw|jvF#S73Ia?knZ)`k~?cUc=a_XjI)`!{4T?ABud%IuRcGU~!(|V@MKLGo& zpzkKrGWFP^eXyosO9pRB7(>Qh(9z~nKjB>sho*_|t6p{1_-+G8+!?<@^V?dg)eq(p z0fDjt>eUulu;c3Ae1|nw4INB0U~l{hOwK#C(LNN=zGD${4((5^%w4+!0olU!R44Z% zC%VNsh4iXB8Jp?PPB1NtZ!f}{*@iCl3th;|E2VKl$+bCRGt0c5jH7*cd(X2-rTyhn z-xD(fS2tw#_1fjF2(G)qwCpNaba=!XnGq8M_L4;;%FaV)8M6#&oBZ}9W>>*x@%_XI z#Y^hel=RkeR&7Fp$_E{vVzCA=u6B6_eHCiiV~?(!AH0C-nz?>F>Khz7bPIUY#W_#f zxxfXkJc5w0A~9}MTb4w2X8H#uZ?o-w?>l;D1~1$-Y5G;!k8O>92Ffk9HiEbYaBe&w z80t)6-7Y=(+t77mQ~X0DrEW$4t_-ZcVNnb?TbT<2b2GTVy!yCXS_d1j;e8OSn@J)t6H&5=EVVy7@?SD%c((m^i_jGHK{QIpK@uf~`ziNaM24dA^=+_Huz=-~PE3 z*+OLSZc>+Fy@W%#2X0ULcub0`kQ7U(b9Rw8x8G4}*mt|oBG!i;-1#Ef?$vS2Y}~X3 zlUcWm!};k#+Kru!?AAS)?^K4AHDUc;rc%$lqr@VPPpoi@ds69Q|N4}wt=^x6L7$HD z8)Kc3I=j_w=n$zd@|1EigPIQB-lgi-*^>OWyLlq#jeEBGP=Ut;;y5%XikCf{kF8}E z5(BM5MQ;49=bM_4pY`_ME@CN%o-=jrwJmGw&O%5cu+$gYJ_}60(- ztoL#}64evis+e7OlG4S3I_`@sxGQMwrR$cMwcz%>-g-)~P-Cf2v0YS{+?&-wACE@Q z3vOF}!u96&yGGiZS-x7}X-wOIrX28&1vrVsoa}4nH>bYU6T&TZgX~A?t$;HXNNN2?R*dhiOGY7VF}eh@%_&V<@=UTeS2iNPWD6`sc=%) z!{y=oo=Bu#J6V+m=#sutZ*}iFZlR;rBz`{8fpMYng8x9`GJqp9SU6Jd0pzc*iVl!A zwWbwxG_+@mtc_2$6T7R^m`v<07tCDkm{R3mc92faNMTwY%w0ILWpk%G31p3=AOAh* za>yhkFcOIk`1Uj2dHWknyf%jfWPulunQ*5jAtpMA;dz&{W7qWZ8cGmOuGHhc-MX@K zmaRT#48CsL+L``UXX)9eNM{U14U~F2I$q_dZCC6d$aCh+ZRaGNB(_Hc{GhK~{R2Mf zW8A`#WA0R^1F`h&@hBPzIRq(zLnj1h(`K^ryPF~s%T&AOJxs07@INCH$aw$OW_|rF zh1#dMgNm2VdTa=&BZ|zWt}Qz-mJhg4SBY|cs@}UGka)NaaN5^z(FD%9NVhrnOF!j} z^LrK{A8!$mpwf;d1Qu32j!g)k4xT$ZjuBbkT!$$UbcI%$h%uvq`?( zgAZ_Vz`S!JKVf~!_CJbp9a+hO*?G&jOFcV&^UQjGLU3+y&-2X{aS#+Q>RcY7JO|Pk zG|%4D($;ts0hi|sQIc(&+HLRe&AIma=0UYGNjiDS^}gP$=p2KSvvdfjp1(*DT(@mj z+aQhj>y-ff2^UWUowpZ9xiHq_sZKWg;e3DP3 z6h^_YMe}j66en<@urH`NbY9`3PqSXv+AcW?du(5A{H?-E7?}DrZq4 zC$^9xy#Ch70Ei4DT;tR4NVlZ7mEg#!t%c>?iV!ZaYU3?OOY=ldL))s)Kr+lZqCxk4 zEo+fCX2$XXx}uJ*Oh3mg7EWRopFI)FCmwof0yeSM@u?Qt4Hf8P_t!t&vIp?5_3dDc0GyCs(C#i$QPj`C{XlSx zDto5FWAUt-s|Pd3x6KUh&=_kS!%ThS5}Sn_qNlf=RKa2D6VV%KRM~1^{`%_P90kvt z*$6wAW)s4i2rf(Z1MB9>`InJL@Y{0j2fyx~RuQMMw@{p$cS=dV(3;M%i-%0p^^R2V za{Fdp8fmh)BCz$rKJ~gN0n(1V&jc`GoZjQz!Yq(BAI#zom$p^#jDE4?G<5!FutUcm zTXyDx66}Nj(yRz0L4+9(BU{T8#SxddDKLZg^9%CxsHqhTsHx3fvco1o7KH_XK;s-r zL1u@E+~R!QqorHe_2HK6`n)FvNNnM@!4K8|C51FxCFamX0RX71A}}-{UrdJoB+N#> zN;B(nEF@x!a!(#a<1iov)^z%DYU1o3z*yW~#_>{Ic+k$&q`=pEZ2rUQ}kqhvBdRis5!@HJM*czA6GWE4ZFt@b1HiAkBdz{aC@s?8Dakh=7VtLKa`GMluVInq*I%!4Lf=6d6Usnjugb)(4X@AC^<`B*tM#GO*d z$j9v9-sb3>E}M=c`Eg~@#hogwIEhhvWZ}ZNl?|um6Bc%6M^eJ!9mN>wmfh0?vy0_8 zG8VzXPs)1Tt-9(df;T6#j>SE=$4_z~Z$4vR?p{oCbU<=);?fnoXW;3vN0wJK<%mQS zm|BWuwC@rzo{`baeb#h${7jVlKj3F-?l6C}v4W6$n&+W~a@W*LL7dBxTtB`y^R&#G z%BQD{o_a#Glcg=>{sY%EWB&LN*aE1f4_1{2JiPj$^kmlBYsq$pIK+r?ekZJb_8&D+ zx$X5K_|va~<;ZWV?D#da*EOxLr%`Zp0Z3P4rkeixrU&CbUB5pwBE9`}jMoQ>RUmE2 z$JhA_yz5emwtGG}qBE6sjFL5m4_8@`z8XMPdq^=mrloxs+K?q^v!p1XIdbAh@coIe zKKyoUms-c$T~d(B6RUg`a8Rtge6#rM(Gj{F{N<$#?l}~-RHT;m1ziK{c6&^4(Z1PD zsbxLllcq18rRSsn0;{;UB~$a`5`-%A!p66iWp*@w&X9J6PMl_U^IYV*<|txz zSlE>pms(qt`K0Sb**}2k(JgLShnD>Tf@8>*JiOER=IZ22^){C7H)&4;mgyaD`o}=d z*0Yuvt|F(}`fKAOVI@bs5?RXjrbdIV=O@Zv2#8p9`|(mVKTAE{*`QdxbG%(cYms1d zPfbzA0+GH~ISBN|m$xh%Vcf@#dju-`?%fPju?e{fA)DpO}Rc;&q&yE21T_1ggjBh{m!XTp1CN5#R+$+)EuFSsFj%L}S?LxH)nL$-E zO+OyXS8mpGYYL}7i0%hA-=EBApd}nk&Ftd5!8d+9H!}-L7nv`uAe9`kCc4Y2sgZnANq)ww;J)(w zidB01&R^22uEwn!c)9scd23?aJgC~740^7+`5ZZk4g)si6NP}|YkmMeEqt+y#6%Soiv;e^8bmqvmSYq*7;L`P(l2D?^B z*+x|7)=%OyC-(m#1_ry+`lSnb&zt)Q3F-;r#{){q^!$^ z=NII|;ADqMd0F!6=`auq{cyNWCHHmY)=BLcfNv+FIke;5Nud#PV z+>*5Uo;vC6=?94oGtO&gog$rW{V8Pv=dqc?7(RL<0WY*O6p=9;D1=opi+>sbu8@)g zDRGxA-#5O1+Fl{O@=k_EQtR!eY@wW|uWz1EJc?X=AwDj?(;e`)>v|aL(Tv+RKrq}z zy9{-vi7yM4eENFY1=%J+G32%7`idVPW=YXeMd8yivuvo99RD;2(t>@NwtS)+M{uxn zOA}(Snkqg?su3lvr?KX5wKQyhv?|)FPW8Qa^g+*xoK?m5)07$y?V6$N(G+1$#z@b2 z9 z9rn*&M1t!4!HizVhlk7QmEw)rY@OyZ7T<0%mxX=F;NABSmEE}Fkbi13 z+nrE$fVJwZubmb6zMEC_)?RC16_cghIzGJDF4Vsx3x%ZQpu985b2pMx>(iAqhACUOV^Il3fkI z=tO(on#+k1Vm-$5 zk>!g(*~MopDYT6*2{3H2HY+k_3Pj8XC7mkCsDprbXjyH%kj9?xsyjOM#ph9#485ig zLmi~NE?`|6v*G~0n@C|sKJ|Qf4iuU@! zT}S{4R2DvpnZVKi*@|Dq0eVi77Sm&}?_x}Z0VZ-)l((|$mpK;4P2hZVtLt+}NN*3nAEEF|On&l?d!et~xGSHeRh{%C5^HWbtElAX@|j6S7rwIaTuucG z?bCii#j$ByP1xz3S7XcB8Z*{>n4!#No(%YK&rd^~*qIPm@9Ozft;eXzW`<%5`xQO2 zhtYW`lx(2L8Ck|;=EFX!S|;bL06wXK4Es?suQL6+>XUMyb4buvr0>D1^5jWD^3~>~ zs6{A=U%tpd_5IJU9Ez;{J8wWZKZ<^e{GiSk9d89xx4aEoEc;`gLhUt-H=af@*;#_t z#@#2pGd~`CTc#|AGdUy9haGq-uA}xNnBFp^pr!@YOJmXEMo4ENaA?v zT!SQ(N}x7ADdr5HNSuvIFVSKp6)2q(jpFbm8)$jBQlFHs>e-wtFSyetv*o#O?WM@d zu#^Wa5vm_Iy4`Fo%*q_d6x5BjtA~_(X3?rBj}2p!`^E}9Pz$QWVVy|31-CEE5usZ( zQQBV9%M@C!-)Ho?p;QZJq)IU((EeH6(Lwu{iS{pZtjQ!!->2xl{bx(tGsb;rO$ZKr z3VA0}==Mp&FSmm>vqTiNJ+bM%;d^`$j+DLc$a4Q)tIhIRHgyQ$avfQ$)*XJ7aFscNLqf{mtL&qWD$<_g;i-;AUM@&aurD