From cc9512be8c16138b9e8dd1da7c623a657b3f14c1 Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Fri, 7 Jun 2024 13:03:14 +0900 Subject: [PATCH 01/65] fix(yabloc): suppress no viable conversion error (#7299) * use tier4_autoware_utils instead of yabloc::Color Signed-off-by: Kento Yabuuchi * use static_cast to convert Color to RGBA Signed-off-by: Kento Yabuuchi * use tier4_autoware_utils instead of yabloc::Color Signed-off-by: Kento Yabuuchi * use static_cast to convert Color to RGBA Signed-off-by: Kento Yabuuchi * style(pre-commit): autofix --------- Signed-off-by: Kento Yabuuchi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization/yabloc/yabloc_common/package.xml | 1 + .../src/ll2_decomposer/ll2_decomposer_core.cpp | 6 +++--- .../src/common/particle_visualize_node.cpp | 3 ++- .../yabloc/yabloc_particle_filter/src/common/visualize.cpp | 3 ++- .../src/gnss_corrector/gnss_corrector_core.cpp | 2 +- .../src/ll2_cost_map/hierarchical_cost_map.cpp | 4 ++-- .../yabloc_pose_initializer/src/camera/marker_module.cpp | 3 ++- 7 files changed, 13 insertions(+), 9 deletions(-) diff --git a/localization/yabloc/yabloc_common/package.xml b/localization/yabloc/yabloc_common/package.xml index de675da5cc2d4..d4c8b71fa6b66 100644 --- a/localization/yabloc/yabloc_common/package.xml +++ b/localization/yabloc/yabloc_common/package.xml @@ -29,6 +29,7 @@ sophus std_msgs tf2_ros + tier4_autoware_utils visualization_msgs ament_lint_auto 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 d0dfc87067f7f..1126d6260b911 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 @@ -15,7 +15,7 @@ #include "yabloc_common/ll2_decomposer/ll2_decomposer.hpp" #include -#include +#include #include #include @@ -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 = common::Color(0.6f, 0.6f, 0.6f, 0.999f); + marker.color = tier4_autoware_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 = common::Color(0.4f, 0.4f, 0.8f, 0.999f); + marker.color = tier4_autoware_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_particle_filter/src/common/particle_visualize_node.cpp b/localization/yabloc/yabloc_particle_filter/src/common/particle_visualize_node.cpp index 90cd62883e339..e6e59a836f6db 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 @@ -93,7 +93,8 @@ class ParticleVisualize : public rclcpp::Node marker.scale.y = 0.1; marker.scale.z = 0.1; - marker.color = common::color_scale::rainbow(bound_weight(p.weight)); + marker.color = + 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/common/visualize.cpp b/localization/yabloc/yabloc_particle_filter/src/common/visualize.cpp index 955ed84fdea2d..888baf0bea0ac 100644 --- a/localization/yabloc/yabloc_particle_filter/src/common/visualize.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/common/visualize.cpp @@ -45,7 +45,8 @@ void ParticleVisualizer::publish(const ParticleArray & msg) marker.scale.x = 0.3; marker.scale.y = 0.1; marker.scale.z = 0.1; - marker.color = common::color_scale::rainbow(boundWeight(p.weight)); + marker.color = + static_cast(common::color_scale::rainbow(boundWeight(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/gnss_corrector/gnss_corrector_core.cpp b/localization/yabloc/yabloc_particle_filter/src/gnss_corrector/gnss_corrector_core.cpp index b321986240b69..e8c8890561a7f 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 @@ -136,7 +136,7 @@ void GnssParticleCorrector::publish_marker(const Eigen::Vector3f & position, boo marker.pose.position.z = latest_height_.data; float prob = i / 4.0f; - marker.color = common::color_scale::rainbow(prob); + 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)); 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 ebd9c424edf5e..62d8ed826b373 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 @@ -18,7 +18,7 @@ #include #include -#include +#include #include @@ -169,7 +169,7 @@ HierarchicalCostMap::MarkerArray HierarchicalCostMap::show_map_range() const marker.header.frame_id = "map"; marker.id = id++; marker.type = Marker::LINE_STRIP; - marker.color = common::Color(0, 0, 1.0f, 1.0f); + marker.color = tier4_autoware_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/localization/yabloc/yabloc_pose_initializer/src/camera/marker_module.cpp b/localization/yabloc/yabloc_pose_initializer/src/camera/marker_module.cpp index c6c34f0e28a42..8a5fc65e2fac3 100644 --- a/localization/yabloc/yabloc_pose_initializer/src/camera/marker_module.cpp +++ b/localization/yabloc/yabloc_pose_initializer/src/camera/marker_module.cpp @@ -42,7 +42,8 @@ void MarkerModule::publish_marker( marker.type = Marker::ARROW; marker.id = i; marker.ns = "arrow"; - marker.color = common::color_scale::rainbow(normalize(scores.at(i))); + marker.color = + static_cast(common::color_scale::rainbow(normalize(scores.at(i)))); marker.color.a = 0.5; marker.pose.position.x = position.x(); From d54e1ff0aba56bf5b9fbbde93d76d8cb41f26b2d Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 7 Jun 2024 13:22:15 +0900 Subject: [PATCH 02/65] feat(obstacle_curise): revert lateral stop margin for unknown objects (#7230) Signed-off-by: Yuki Takagi --- .../config/obstacle_cruise_planner.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml index 2ccd000657948..08cee3d58152e 100644 --- a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml +++ b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml @@ -88,7 +88,7 @@ stop: max_lat_margin: 0.3 # lateral margin between the obstacles except for unknown and ego's footprint - max_lat_margin_against_unknown: -0.3 # lateral margin between the unknown obstacles and ego's footprint + max_lat_margin_against_unknown: 0.3 # lateral margin between the unknown obstacles and ego's footprint crossing_obstacle: collision_time_margin : 4.0 # time threshold of collision between obstacle adn ego for cruise or stop [s] From 9202dabc91ebf764090e951a60a6e018fb322a63 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Fri, 7 Jun 2024 13:22:40 +0900 Subject: [PATCH 03/65] chore(mrm_comfortable_stop_operator): remove unused main file (#7191) Signed-off-by: Takagi, Isamu --- .../mrm_comfortable_stop_operator_node.cpp | 27 ------------------- 1 file changed, 27 deletions(-) delete mode 100644 system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_node.cpp diff --git a/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_node.cpp b/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_node.cpp deleted file mode 100644 index 03bad4198776d..0000000000000 --- a/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_node.cpp +++ /dev/null @@ -1,27 +0,0 @@ -// Copyright 2022 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp" - -#include - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - auto node = std::make_shared(); - rclcpp::spin(node); - rclcpp::shutdown(); - - return 0; -} From c672f861cd1adbb8f5fff580a46bb370b12cf9e0 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 7 Jun 2024 13:27:22 +0900 Subject: [PATCH 04/65] refactor(sampling_based_planner): add autoware prefix (#7348) Signed-off-by: Maxime CLEMENT --- .github/CODEOWNERS | 8 +- .../motion_planning.launch.xml | 2 +- planning/.pages | 8 +- planning/behavior_path_planner/package.xml | 4 +- .../sampling_planner_module.hpp | 28 +++--- .../sampling_planner_parameters.hpp | 8 +- .../util.hpp | 22 +++-- .../package.xml | 6 +- .../src/sampling_planner_module.cpp | 98 ++++++++++--------- .../CMakeLists.txt | 4 +- .../README.md | 0 .../autoware_bezier_sampler}/bezier.hpp | 10 +- .../bezier_sampling.hpp | 16 +-- .../package.xml | 4 +- .../src/bezier.cpp | 6 +- .../src/bezier_sampling.cpp | 8 +- .../CMakeLists.txt | 4 +- .../README.md | 0 .../autoware_frenet_planner}/conversions.hpp | 14 +-- .../frenet_planner.hpp | 33 ++++--- .../autoware_frenet_planner}/polynomials.hpp | 10 +- .../autoware_frenet_planner}/structures.hpp | 50 +++++----- .../launch/frenet_planner.launch | 2 +- .../package.xml | 6 +- .../src/frenet_planner/frenet_planner.cpp | 33 ++++--- .../src/frenet_planner/polynomials.cpp | 6 +- .../CMakeLists.txt | 8 +- .../README.md | 0 .../autoware_path_sampler}/common_structs.hpp | 18 ++-- .../include/autoware_path_sampler}/node.hpp | 34 ++++--- .../autoware_path_sampler}/parameters.hpp | 14 +-- .../autoware_path_sampler/path_generation.hpp | 52 ++++++++++ .../autoware_path_sampler}/prepare_inputs.hpp | 28 +++--- .../autoware_path_sampler}/type_alias.hpp | 10 +- .../utils/geometry_utils.hpp | 14 +-- .../utils/trajectory_utils.hpp | 23 ++--- .../package.xml | 6 +- .../src/node.cpp | 50 +++++----- .../src/path_generation.cpp | 47 ++++----- .../src/prepare_inputs.cpp | 32 +++--- .../src/utils/trajectory_utils.cpp | 8 +- .../CMakeLists.txt | 6 +- .../README.md | 0 .../constraints/footprint.hpp | 12 +-- .../constraints/hard_constraint.hpp | 12 +-- .../constraints/map_constraints.hpp | 12 +-- .../constraints/soft_constraint.hpp | 14 +-- .../autoware_sampler_common}/structures.hpp | 10 +- .../transform/spline_transform.hpp | 14 +-- .../package.xml | 2 +- .../sampler_common/constraints/footprint.cpp | 8 +- .../constraints/hard_constraint.cpp | 8 +- .../constraints/soft_constraint.cpp | 10 +- .../transform/spline_transform.cpp | 6 +- .../test/test_structures.cpp | 8 +- .../test/test_transform.cpp | 14 +-- .../include/path_sampler/path_generation.hpp | 52 ---------- 57 files changed, 474 insertions(+), 448 deletions(-) rename planning/sampling_based_planner/{bezier_sampler => autoware_bezier_sampler}/CMakeLists.txt (80%) rename planning/sampling_based_planner/{bezier_sampler => autoware_bezier_sampler}/README.md (100%) rename planning/sampling_based_planner/{bezier_sampler/include/bezier_sampler => autoware_bezier_sampler/include/autoware_bezier_sampler}/bezier.hpp (94%) rename planning/sampling_based_planner/{bezier_sampler/include/bezier_sampler => autoware_bezier_sampler/include/autoware_bezier_sampler}/bezier_sampling.hpp (80%) rename planning/sampling_based_planner/{bezier_sampler => autoware_bezier_sampler}/package.xml (89%) rename planning/sampling_based_planner/{bezier_sampler => autoware_bezier_sampler}/src/bezier.cpp (96%) rename planning/sampling_based_planner/{bezier_sampler => autoware_bezier_sampler}/src/bezier_sampling.cpp (94%) rename planning/sampling_based_planner/{frenet_planner => autoware_frenet_planner}/CMakeLists.txt (78%) rename planning/sampling_based_planner/{frenet_planner => autoware_frenet_planner}/README.md (100%) rename planning/sampling_based_planner/{frenet_planner/include/frenet_planner => autoware_frenet_planner/include/autoware_frenet_planner}/conversions.hpp (81%) rename planning/sampling_based_planner/{frenet_planner/include/frenet_planner => autoware_frenet_planner/include/autoware_frenet_planner}/frenet_planner.hpp (67%) rename planning/sampling_based_planner/{frenet_planner/include/frenet_planner => autoware_frenet_planner/include/autoware_frenet_planner}/polynomials.hpp (88%) rename planning/sampling_based_planner/{frenet_planner/include/frenet_planner => autoware_frenet_planner/include/autoware_frenet_planner}/structures.hpp (73%) rename planning/sampling_based_planner/{frenet_planner => autoware_frenet_planner}/launch/frenet_planner.launch (78%) rename planning/sampling_based_planner/{frenet_planner => autoware_frenet_planner}/package.xml (76%) rename planning/sampling_based_planner/{frenet_planner => autoware_frenet_planner}/src/frenet_planner/frenet_planner.cpp (89%) rename planning/sampling_based_planner/{frenet_planner => autoware_frenet_planner}/src/frenet_planner/polynomials.cpp (94%) rename planning/sampling_based_planner/{path_sampler => autoware_path_sampler}/CMakeLists.txt (52%) rename planning/sampling_based_planner/{path_sampler => autoware_path_sampler}/README.md (100%) rename planning/sampling_based_planner/{path_sampler/include/path_sampler => autoware_path_sampler/include/autoware_path_sampler}/common_structs.hpp (87%) rename planning/sampling_based_planner/{path_sampler/include/path_sampler => autoware_path_sampler/include/autoware_path_sampler}/node.hpp (77%) rename planning/sampling_based_planner/{path_sampler/include/path_sampler => autoware_path_sampler/include/autoware_path_sampler}/parameters.hpp (77%) create mode 100644 planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/path_generation.hpp rename planning/sampling_based_planner/{path_sampler/include/path_sampler => autoware_path_sampler/include/autoware_path_sampler}/prepare_inputs.hpp (64%) rename planning/sampling_based_planner/{path_sampler/include/path_sampler => autoware_path_sampler/include/autoware_path_sampler}/type_alias.hpp (88%) rename planning/sampling_based_planner/{path_sampler/include/path_sampler => autoware_path_sampler/include/autoware_path_sampler}/utils/geometry_utils.hpp (81%) rename planning/sampling_based_planner/{path_sampler/include/path_sampler => autoware_path_sampler/include/autoware_path_sampler}/utils/trajectory_utils.hpp (90%) rename planning/sampling_based_planner/{path_sampler => autoware_path_sampler}/package.xml (92%) rename planning/sampling_based_planner/{path_sampler => autoware_path_sampler}/src/node.cpp (94%) rename planning/sampling_based_planner/{path_sampler => autoware_path_sampler}/src/path_generation.cpp (72%) rename planning/sampling_based_planner/{path_sampler => autoware_path_sampler}/src/prepare_inputs.cpp (84%) rename planning/sampling_based_planner/{path_sampler => autoware_path_sampler}/src/utils/trajectory_utils.cpp (95%) rename planning/sampling_based_planner/{sampler_common => autoware_sampler_common}/CMakeLists.txt (81%) rename planning/sampling_based_planner/{sampler_common => autoware_sampler_common}/README.md (100%) rename planning/sampling_based_planner/{sampler_common/include/sampler_common => autoware_sampler_common/include/autoware_sampler_common}/constraints/footprint.hpp (73%) rename planning/sampling_based_planner/{sampler_common/include/sampler_common => autoware_sampler_common/include/autoware_sampler_common}/constraints/hard_constraint.hpp (73%) rename planning/sampling_based_planner/{sampler_common/include/sampler_common => autoware_sampler_common/include/autoware_sampler_common}/constraints/map_constraints.hpp (80%) rename planning/sampling_based_planner/{sampler_common/include/sampler_common => autoware_sampler_common/include/autoware_sampler_common}/constraints/soft_constraint.hpp (74%) rename planning/sampling_based_planner/{sampler_common/include/sampler_common => autoware_sampler_common/include/autoware_sampler_common}/structures.hpp (98%) rename planning/sampling_based_planner/{sampler_common/include/sampler_common => autoware_sampler_common/include/autoware_sampler_common}/transform/spline_transform.hpp (88%) rename planning/sampling_based_planner/{sampler_common => autoware_sampler_common}/package.xml (94%) rename planning/sampling_based_planner/{sampler_common => autoware_sampler_common}/src/sampler_common/constraints/footprint.cpp (87%) rename planning/sampling_based_planner/{sampler_common => autoware_sampler_common}/src/sampler_common/constraints/hard_constraint.cpp (89%) rename planning/sampling_based_planner/{sampler_common => autoware_sampler_common}/src/sampler_common/constraints/soft_constraint.cpp (85%) rename planning/sampling_based_planner/{sampler_common => autoware_sampler_common}/src/sampler_common/transform/spline_transform.cpp (98%) rename planning/sampling_based_planner/{sampler_common => autoware_sampler_common}/test/test_structures.cpp (96%) rename planning/sampling_based_planner/{sampler_common => autoware_sampler_common}/test/test_transform.cpp (85%) delete mode 100644 planning/sampling_based_planner/path_sampler/include/path_sampler/path_generation.hpp diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 1ee1d82297baf..603ddac6802a6 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -194,10 +194,10 @@ planning/planning_validator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp planning/route_handler/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp zulfaqar.azmi@tier4.jp planning/rtc_interface/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp taiki.tanaka@tier4.jp planning/rtc_replayer/** fumiya.watanabe@tier4.jp taiki.tanaka@tier4.jp -planning/sampling_based_planner/bezier_sampler/** maxime.clement@tier4.jp -planning/sampling_based_planner/frenet_planner/** maxime.clement@tier4.jp -planning/sampling_based_planner/path_sampler/** maxime.clement@tier4.jp -planning/sampling_based_planner/sampler_common/** maxime.clement@tier4.jp +planning/sampling_based_planner/autoware_bezier_sampler/** maxime.clement@tier4.jp +planning/sampling_based_planner/autoware_frenet_planner/** maxime.clement@tier4.jp +planning/sampling_based_planner/autoware_path_sampler/** maxime.clement@tier4.jp +planning/sampling_based_planner/autoware_sampler_common/** maxime.clement@tier4.jp planning/scenario_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/autoware_surround_obstacle_checker/** satoshi.ota@tier4.jp sensing/gnss_poser/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 5fcbfe512e3e1..b5173d6a98b2e 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -80,7 +80,7 @@ - + diff --git a/planning/.pages b/planning/.pages index 4f1d928252185..f7acd1b5efad5 100644 --- a/planning/.pages +++ b/planning/.pages @@ -56,10 +56,10 @@ nav: - 'About Path Smoother': planning/path_smoother - 'Elastic Band': planning/path_smoother/docs/eb - 'Sampling Based Planner': - - 'Path Sample': planning/sampling_based_planner/path_sampler - - 'Common library': planning/sampling_based_planner/sampler_common - - 'Frenet Planner': planning/sampling_based_planner/frenet_planner - - 'Bezier Sampler': planning/sampling_based_planner/bezier_sampler + - 'Path Sample': planning/sampling_based_planner/autoware_path_sampler + - 'Common library': planning/sampling_based_planner/autoware_sampler_common + - 'Frenet Planner': planning/sampling_based_planner/autoware_frenet_planner + - 'Bezier Sampler': planning/sampling_based_planner/autoware_bezier_sampler - 'Surround Obstacle Checker': - 'About Surround Obstacle Checker': planning/autoware_surround_obstacle_checker - 'About Surround Obstacle Checker (Japanese)': planning/autoware_surround_obstacle_checker/surround_obstacle_checker-design.ja diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index e4fe3d0e9d3e4..a646621e5b089 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -38,13 +38,14 @@ autoware_adapi_v1_msgs autoware_behavior_path_planner_common + autoware_frenet_planner + autoware_path_sampler autoware_perception_msgs autoware_planning_msgs autoware_planning_test_manager autoware_vehicle_msgs behaviortree_cpp_v3 freespace_planning_algorithms - frenet_planner geometry_msgs interpolation lane_departure_checker @@ -54,7 +55,6 @@ magic_enum motion_utils object_recognition_utils - path_sampler pluginlib rclcpp rclcpp_components diff --git a/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_module.hpp b/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_module.hpp index 3f3d144952d8e..0a5dec8d07b4f 100644 --- a/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_module.hpp +++ b/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_module.hpp @@ -21,19 +21,19 @@ #include "autoware_behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "autoware_behavior_path_planner_common/utils/path_utils.hpp" #include "autoware_behavior_path_planner_common/utils/utils.hpp" +#include "autoware_bezier_sampler/bezier_sampling.hpp" +#include "autoware_frenet_planner/frenet_planner.hpp" +#include "autoware_sampler_common/constraints/footprint.hpp" +#include "autoware_sampler_common/constraints/hard_constraint.hpp" +#include "autoware_sampler_common/constraints/soft_constraint.hpp" +#include "autoware_sampler_common/structures.hpp" +#include "autoware_sampler_common/transform/spline_transform.hpp" #include "behavior_path_sampling_planner_module/sampling_planner_parameters.hpp" #include "behavior_path_sampling_planner_module/util.hpp" -#include "bezier_sampler/bezier_sampling.hpp" -#include "frenet_planner/frenet_planner.hpp" #include "lanelet2_extension/utility/query.hpp" #include "lanelet2_extension/utility/utilities.hpp" #include "motion_utils/trajectory/path_with_lane_id.hpp" #include "rclcpp/rclcpp.hpp" -#include "sampler_common/constraints/footprint.hpp" -#include "sampler_common/constraints/hard_constraint.hpp" -#include "sampler_common/constraints/soft_constraint.hpp" -#include "sampler_common/structures.hpp" -#include "sampler_common/transform/spline_transform.hpp" #include "tier4_autoware_utils/geometry/boost_geometry.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include "tier4_autoware_utils/math/constants.hpp" @@ -73,7 +73,7 @@ struct SamplingPlannerData struct SamplingPlannerDebugData { - std::vector sampled_candidates{}; + std::vector sampled_candidates{}; size_t previous_sampled_candidates_nb = 0UL; std::vector obstacles{}; std::vector footprints{}; @@ -231,25 +231,25 @@ class SamplingPlannerModule : public SceneModuleInterface void updateDebugMarkers(); void prepareConstraints( - sampler_common::Constraints & constraints, + autoware::sampler_common::Constraints & constraints, const PredictedObjects::ConstSharedPtr & predicted_objects, const std::vector & left_bound, const std::vector & right_bound) const; - frenet_planner::SamplingParameters prepareSamplingParameters( - const sampler_common::State & initial_state, - const sampler_common::transform::Spline2D & path_spline, + autoware::frenet_planner::SamplingParameters prepareSamplingParameters( + const autoware::sampler_common::State & initial_state, + const autoware::sampler_common::transform::Spline2D & path_spline, const SamplingPlannerInternalParameters & internal_params_); PathWithLaneId convertFrenetPathToPathWithLaneID( - const frenet_planner::Path frenet_path, const lanelet::ConstLanelets & lanelets, + const autoware::frenet_planner::Path frenet_path, const lanelet::ConstLanelets & lanelets, const double path_z); // member // std::shared_ptr params_; std::shared_ptr internal_params_; vehicle_info_util::VehicleInfo vehicle_info_{}; - std::optional prev_sampling_path_ = std::nullopt; + std::optional prev_sampling_path_ = std::nullopt; // move to utils void extendOutputDrivableArea( diff --git a/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_parameters.hpp b/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_parameters.hpp index 6e00fefe89574..4ddfbf436ffaf 100644 --- a/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_parameters.hpp +++ b/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_parameters.hpp @@ -15,8 +15,8 @@ #ifndef BEHAVIOR_PATH_SAMPLING_PLANNER_MODULE__SAMPLING_PLANNER_PARAMETERS_HPP_ #define BEHAVIOR_PATH_SAMPLING_PLANNER_MODULE__SAMPLING_PLANNER_PARAMETERS_HPP_ -#include "bezier_sampler/bezier_sampling.hpp" -#include "sampler_common/structures.hpp" +#include "autoware_bezier_sampler/bezier_sampling.hpp" +#include "autoware_sampler_common/structures.hpp" #include namespace behavior_path_planner @@ -78,12 +78,12 @@ struct Sampling std::vector target_lateral_positions{}; int nb_target_lateral_positions{}; Frenet frenet; - bezier_sampler::SamplingParameters bezier{}; + autoware::bezier_sampler::SamplingParameters bezier{}; }; struct SamplingPlannerInternalParameters { - sampler_common::Constraints constraints; + autoware::sampler_common::Constraints constraints; Sampling sampling; Preprocessing preprocessing{}; }; diff --git a/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/util.hpp b/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/util.hpp index ac8ba788cb9bd..2825ead2a9fee 100644 --- a/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/util.hpp +++ b/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/util.hpp @@ -14,8 +14,8 @@ #ifndef BEHAVIOR_PATH_SAMPLING_PLANNER_MODULE__UTIL_HPP_ #define BEHAVIOR_PATH_SAMPLING_PLANNER_MODULE__UTIL_HPP_ -#include "sampler_common/structures.hpp" -#include "sampler_common/transform/spline_transform.hpp" +#include "autoware_sampler_common/structures.hpp" +#include "autoware_sampler_common/transform/spline_transform.hpp" #include @@ -40,18 +40,20 @@ struct SoftConstraintsInputs lanelet::ConstLanelets closest_lanelets_to_goal; behavior_path_planner::PlanResult reference_path; behavior_path_planner::PlanResult prev_module_path; - std::optional prev_path; + std::optional prev_path; lanelet::ConstLanelets current_lanes; }; using SoftConstraintsFunctionVector = std::vector>; + autoware::sampler_common::Path &, const autoware::sampler_common::Constraints &, + const SoftConstraintsInputs &)>>; using HardConstraintsFunctionVector = std::vector>; + autoware::sampler_common::Path &, const autoware::sampler_common::Constraints &, + const MultiPoint2d &)>>; inline std::vector evaluateSoftConstraints( - sampler_common::Path & path, const sampler_common::Constraints & constraints, + autoware::sampler_common::Path & path, const autoware::sampler_common::Constraints & constraints, const SoftConstraintsFunctionVector & soft_constraints_functions, const SoftConstraintsInputs & input_data) { @@ -71,7 +73,7 @@ inline std::vector evaluateSoftConstraints( } inline std::vector evaluateHardConstraints( - sampler_common::Path & path, const sampler_common::Constraints & constraints, + autoware::sampler_common::Path & path, const autoware::sampler_common::Constraints & constraints, const MultiPoint2d & footprint, const HardConstraintsFunctionVector & hard_constraints) { std::vector constraints_results; @@ -86,11 +88,11 @@ inline std::vector evaluateHardConstraints( return constraints_results; } -inline sampler_common::State getInitialState( +inline autoware::sampler_common::State getInitialState( const geometry_msgs::msg::Pose & pose, - const sampler_common::transform::Spline2D & reference_spline) + const autoware::sampler_common::transform::Spline2D & reference_spline) { - sampler_common::State initial_state; + autoware::sampler_common::State initial_state; Point2d initial_state_pose{pose.position.x, pose.position.y}; const auto rpy = tier4_autoware_utils::getRPY(pose.orientation); initial_state.pose = initial_state_pose; diff --git a/planning/behavior_path_sampling_planner_module/package.xml b/planning/behavior_path_sampling_planner_module/package.xml index e6fb0d4d0f573..0583056db4293 100644 --- a/planning/behavior_path_sampling_planner_module/package.xml +++ b/planning/behavior_path_sampling_planner_module/package.xml @@ -14,17 +14,17 @@ autoware_cmake autoware_behavior_path_planner_common + autoware_bezier_sampler + autoware_frenet_planner + autoware_path_sampler autoware_perception_msgs autoware_planning_msgs autoware_planning_test_manager autoware_vehicle_msgs - bezier_sampler - frenet_planner geometry_msgs interpolation lanelet2_extension motion_utils - path_sampler pluginlib rclcpp rclcpp_components diff --git a/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp b/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp index 4b0ecdcd24e14..8788b446e4384 100644 --- a/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp +++ b/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp @@ -44,14 +44,16 @@ SamplingPlannerModule::SamplingPlannerModule( // check if the path is empty hard_constraints_.emplace_back( []( - sampler_common::Path & path, [[maybe_unused]] const sampler_common::Constraints & constraints, + autoware::sampler_common::Path & path, + [[maybe_unused]] const autoware::sampler_common::Constraints & constraints, [[maybe_unused]] const MultiPoint2d & footprint) -> bool { return !path.points.empty() && !path.poses.empty(); }); hard_constraints_.emplace_back( []( - sampler_common::Path & path, const sampler_common::Constraints & constraints, + autoware::sampler_common::Path & path, + const autoware::sampler_common::Constraints & constraints, const MultiPoint2d & footprint) -> bool { if (!footprint.empty()) { path.constraint_results.inside_drivable_area = @@ -71,7 +73,8 @@ SamplingPlannerModule::SamplingPlannerModule( hard_constraints_.emplace_back( []( - sampler_common::Path & path, const sampler_common::Constraints & constraints, + autoware::sampler_common::Path & path, + const autoware::sampler_common::Constraints & constraints, [[maybe_unused]] const MultiPoint2d & footprint) -> bool { if (path.curvatures.empty()) { path.constraint_results.valid_curvature = false; @@ -96,8 +99,8 @@ SamplingPlannerModule::SamplingPlannerModule( // Yaw difference soft constraint cost -> Considering implementation // soft_constraints_.emplace_back( // [&]( - // sampler_common::Path & path, [[maybe_unused]] const sampler_common::Constraints & - // constraints, + // autoware::sampler_common::Path & path, [[maybe_unused]] const + // autoware::sampler_common::Constraints & constraints, // [[maybe_unused]] const SoftConstraintsInputs & input_data) -> double { // if (path.points.empty()) return 0.0; // const auto & goal_pose_yaw = @@ -109,7 +112,8 @@ SamplingPlannerModule::SamplingPlannerModule( // Remaining path length soft_constraints_.emplace_back( [&]( - sampler_common::Path & path, [[maybe_unused]] const sampler_common::Constraints & constraints, + autoware::sampler_common::Path & path, + [[maybe_unused]] const autoware::sampler_common::Constraints & constraints, [[maybe_unused]] const SoftConstraintsInputs & input_data) -> double { if (path.points.empty()) return 0.0; if (path.poses.empty()) return 0.0; @@ -142,8 +146,8 @@ SamplingPlannerModule::SamplingPlannerModule( // Distance to centerline soft_constraints_.emplace_back( [&]( - [[maybe_unused]] sampler_common::Path & path, - [[maybe_unused]] const sampler_common::Constraints & constraints, + [[maybe_unused]] autoware::sampler_common::Path & path, + [[maybe_unused]] const autoware::sampler_common::Constraints & constraints, [[maybe_unused]] const SoftConstraintsInputs & input_data) -> double { if (path.poses.empty()) return 0.0; const auto & last_pose = path.poses.back(); @@ -159,7 +163,8 @@ SamplingPlannerModule::SamplingPlannerModule( // // Curvature cost soft_constraints_.emplace_back( []( - sampler_common::Path & path, [[maybe_unused]] const sampler_common::Constraints & constraints, + autoware::sampler_common::Path & path, + [[maybe_unused]] const autoware::sampler_common::Constraints & constraints, [[maybe_unused]] const SoftConstraintsInputs & input_data) -> double { if (path.curvatures.empty()) return std::numeric_limits::max(); @@ -244,7 +249,7 @@ bool SamplingPlannerModule::isReferencePathSafe() const std::vector hard_constraints_results; auto transform_to_sampling_path = [](const PlanResult plan) { - sampler_common::Path path; + autoware::sampler_common::Path path; for (size_t i = 0; i < plan->points.size(); ++i) { const auto x = plan->points[i].point.pose.position.x; const auto y = plan->points[i].point.pose.position.y; @@ -258,17 +263,20 @@ bool SamplingPlannerModule::isReferencePathSafe() const } return path; }; - sampler_common::Path reference_path = transform_to_sampling_path(prev_module_reference_path); - const auto footprint = sampler_common::constraints::buildFootprintPoints( + autoware::sampler_common::Path reference_path = + transform_to_sampling_path(prev_module_reference_path); + const auto footprint = autoware::sampler_common::constraints::buildFootprintPoints( reference_path, internal_params_->constraints); behavior_path_planner::HardConstraintsFunctionVector hard_constraints_reference_path; hard_constraints_reference_path.emplace_back( []( - sampler_common::Path & path, const sampler_common::Constraints & constraints, + autoware::sampler_common::Path & path, + const autoware::sampler_common::Constraints & constraints, const MultiPoint2d & footprint) -> bool { path.constraint_results.collision_free = - !sampler_common::constraints::has_collision(footprint, constraints.obstacle_polygons); + !autoware::sampler_common::constraints::has_collision( + footprint, constraints.obstacle_polygons); return path.constraint_results.collision_free; }); evaluateHardConstraints( @@ -295,7 +303,7 @@ SamplingPlannerData SamplingPlannerModule::createPlannerData( } PathWithLaneId SamplingPlannerModule::convertFrenetPathToPathWithLaneID( - const frenet_planner::Path frenet_path, const lanelet::ConstLanelets & lanelets, + const autoware::frenet_planner::Path frenet_path, const lanelet::ConstLanelets & lanelets, const double path_z) { auto quaternion_from_rpy = [](double roll, double pitch, double yaw) -> tf2::Quaternion { @@ -348,12 +356,12 @@ PathWithLaneId SamplingPlannerModule::convertFrenetPathToPathWithLaneID( } void SamplingPlannerModule::prepareConstraints( - sampler_common::Constraints & constraints, + autoware::sampler_common::Constraints & constraints, const PredictedObjects::ConstSharedPtr & predicted_objects, const std::vector & left_bound, const std::vector & right_bound) const { - constraints.obstacle_polygons = sampler_common::MultiPolygon2d(); + constraints.obstacle_polygons = autoware::sampler_common::MultiPolygon2d(); constraints.rtree.clear(); size_t i = 0; for (const auto & o : predicted_objects->objects) { @@ -370,7 +378,7 @@ void SamplingPlannerModule::prepareConstraints( // TODO(Maxime): directly use lines instead of polygon - sampler_common::Polygon2d drivable_area_polygon; + autoware::sampler_common::Polygon2d drivable_area_polygon; for (const auto & p : right_bound) { drivable_area_polygon.outer().emplace_back(p.x, p.y); } @@ -392,7 +400,7 @@ BehaviorModuleOutput SamplingPlannerModule::plan() if (reference_path_ptr->points.empty()) { return {}; } - auto reference_spline = [&]() -> sampler_common::transform::Spline2D { + auto reference_spline = [&]() -> autoware::sampler_common::transform::Spline2D { std::vector x; std::vector y; x.reserve(reference_path_ptr->points.size()); @@ -404,19 +412,19 @@ BehaviorModuleOutput SamplingPlannerModule::plan() return {x, y}; }(); - frenet_planner::FrenetState frenet_initial_state; - frenet_planner::SamplingParameters sampling_parameters; + autoware::frenet_planner::FrenetState frenet_initial_state; + autoware::frenet_planner::SamplingParameters sampling_parameters; const auto & pose = planner_data_->self_odometry->pose.pose; - sampler_common::State initial_state = + autoware::sampler_common::State initial_state = behavior_path_planner::getInitialState(pose, reference_spline); sampling_parameters = prepareSamplingParameters(initial_state, reference_spline, *internal_params_); auto set_frenet_state = []( - const sampler_common::State & initial_state, - const sampler_common::transform::Spline2D & reference_spline, - frenet_planner::FrenetState & frenet_initial_state) + const autoware::sampler_common::State & initial_state, + const autoware::sampler_common::transform::Spline2D & reference_spline, + autoware::frenet_planner::FrenetState & frenet_initial_state) { frenet_initial_state.position = initial_state.frenet; @@ -496,14 +504,16 @@ BehaviorModuleOutput SamplingPlannerModule::plan() const int path_divisions = internal_params_->sampling.previous_path_reuse_points_nb; const bool is_extend_previous_path = path_divisions > 0; - std::vector frenet_paths; + std::vector frenet_paths; // Extend prev path if (prev_path_is_valid && is_extend_previous_path) { - frenet_planner::Path prev_path_frenet = prev_sampling_path_.value(); + autoware::frenet_planner::Path prev_path_frenet = prev_sampling_path_.value(); frenet_paths.push_back(prev_path_frenet); - auto get_subset = [](const frenet_planner::Path & path, size_t offset) -> frenet_planner::Path { - frenet_planner::Path s; + auto get_subset = []( + const autoware::frenet_planner::Path & path, + size_t offset) -> autoware::frenet_planner::Path { + autoware::frenet_planner::Path s; s.points = {path.points.begin(), path.points.begin() + offset}; s.curvatures = {path.curvatures.begin(), path.curvatures.begin() + offset}; s.yaws = {path.yaws.begin(), path.yaws.begin() + offset}; @@ -512,7 +522,7 @@ BehaviorModuleOutput SamplingPlannerModule::plan() return s; }; - sampler_common::State current_state; + autoware::sampler_common::State current_state; current_state.pose = {ego_pose.position.x, ego_pose.position.y}; const auto closest_iter = std::min_element( @@ -537,22 +547,22 @@ BehaviorModuleOutput SamplingPlannerModule::plan() const auto reused_path = get_subset(prev_path_frenet, reuse_idx); geometry_msgs::msg::Pose future_pose = reused_path.poses.back(); - sampler_common::State future_state = + autoware::sampler_common::State future_state = behavior_path_planner::getInitialState(future_pose, reference_spline); - frenet_planner::FrenetState frenet_reuse_state; + autoware::frenet_planner::FrenetState frenet_reuse_state; set_frenet_state(future_state, reference_spline, frenet_reuse_state); - frenet_planner::SamplingParameters extension_sampling_parameters = + autoware::frenet_planner::SamplingParameters extension_sampling_parameters = prepareSamplingParameters(future_state, reference_spline, *internal_params_); - auto extension_frenet_paths = frenet_planner::generatePaths( + auto extension_frenet_paths = autoware::frenet_planner::generatePaths( reference_spline, frenet_reuse_state, extension_sampling_parameters); for (auto & p : extension_frenet_paths) { if (!p.points.empty()) frenet_paths.push_back(reused_path.extend(p)); } } } else { - frenet_paths = - frenet_planner::generatePaths(reference_spline, frenet_initial_state, sampling_parameters); + frenet_paths = autoware::frenet_planner::generatePaths( + reference_spline, frenet_initial_state, sampling_parameters); } const auto path_for_calculating_bounds = getPreviousModuleOutput().reference_path; @@ -587,8 +597,8 @@ BehaviorModuleOutput SamplingPlannerModule::plan() std::vector> hard_constraints_results_full; std::vector> soft_constraints_results_full; for (auto & path : frenet_paths) { - const auto footprint = - sampler_common::constraints::buildFootprintPoints(path, internal_params_->constraints); + const auto footprint = autoware::sampler_common::constraints::buildFootprintPoints( + path, internal_params_->constraints); std::vector hard_constraints_results = evaluateHardConstraints(path, internal_params_->constraints, footprint, hard_constraints_); path.constraint_results.valid_curvature = true; @@ -598,7 +608,7 @@ BehaviorModuleOutput SamplingPlannerModule::plan() soft_constraints_results_full.push_back(soft_constraints_results); } - std::vector candidate_paths; + std::vector candidate_paths; const auto move_to_paths = [&candidate_paths](auto & paths_to_move) { candidate_paths.insert( candidate_paths.end(), std::make_move_iterator(paths_to_move.begin()), @@ -917,9 +927,9 @@ DrivableLanes SamplingPlannerModule::generateExpandDrivableLanes( return current_drivable_lanes; } -frenet_planner::SamplingParameters SamplingPlannerModule::prepareSamplingParameters( - const sampler_common::State & initial_state, - const sampler_common::transform::Spline2D & path_spline, +autoware::frenet_planner::SamplingParameters SamplingPlannerModule::prepareSamplingParameters( + const autoware::sampler_common::State & initial_state, + const autoware::sampler_common::transform::Spline2D & path_spline, const SamplingPlannerInternalParameters & params_) { // calculate target lateral positions @@ -953,10 +963,10 @@ frenet_planner::SamplingParameters SamplingPlannerModule::prepareSamplingParamet } else { target_lateral_positions = params_.sampling.target_lateral_positions; } - frenet_planner::SamplingParameters sampling_parameters; + autoware::frenet_planner::SamplingParameters sampling_parameters; sampling_parameters.resolution = params_.sampling.resolution; const auto max_s = path_spline.lastS(); - frenet_planner::SamplingParameter p; + autoware::frenet_planner::SamplingParameter p; for (const auto target_length : params_.sampling.target_lengths) { p.target_state.position.s = std::min(max_s, path_spline.frenet(initial_state.pose).s + std::max(0.0, target_length)); diff --git a/planning/sampling_based_planner/bezier_sampler/CMakeLists.txt b/planning/sampling_based_planner/autoware_bezier_sampler/CMakeLists.txt similarity index 80% rename from planning/sampling_based_planner/bezier_sampler/CMakeLists.txt rename to planning/sampling_based_planner/autoware_bezier_sampler/CMakeLists.txt index 76d0fc99843f1..8d5bd554ab282 100644 --- a/planning/sampling_based_planner/bezier_sampler/CMakeLists.txt +++ b/planning/sampling_based_planner/autoware_bezier_sampler/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(bezier_sampler) +project(autoware_bezier_sampler) find_package(autoware_cmake REQUIRED) autoware_package() @@ -7,7 +7,7 @@ autoware_package() find_package(eigen3_cmake_module REQUIRED) find_package(Eigen3 REQUIRED) -ament_auto_add_library(bezier_sampler SHARED +ament_auto_add_library(autoware_bezier_sampler SHARED src/bezier.cpp src/bezier_sampling.cpp ) diff --git a/planning/sampling_based_planner/bezier_sampler/README.md b/planning/sampling_based_planner/autoware_bezier_sampler/README.md similarity index 100% rename from planning/sampling_based_planner/bezier_sampler/README.md rename to planning/sampling_based_planner/autoware_bezier_sampler/README.md diff --git a/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier.hpp b/planning/sampling_based_planner/autoware_bezier_sampler/include/autoware_bezier_sampler/bezier.hpp similarity index 94% rename from planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier.hpp rename to planning/sampling_based_planner/autoware_bezier_sampler/include/autoware_bezier_sampler/bezier.hpp index 93c6ec6b87f36..5d16c55d793af 100644 --- a/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier.hpp +++ b/planning/sampling_based_planner/autoware_bezier_sampler/include/autoware_bezier_sampler/bezier.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEZIER_SAMPLER__BEZIER_HPP_ -#define BEZIER_SAMPLER__BEZIER_HPP_ +#ifndef AUTOWARE_BEZIER_SAMPLER__BEZIER_HPP_ +#define AUTOWARE_BEZIER_SAMPLER__BEZIER_HPP_ #include #include -namespace bezier_sampler +namespace autoware::bezier_sampler { // Coefficients for matrix calculation of the quintic Bézier curve. @@ -70,6 +70,6 @@ class Bezier /// @brief calculate the curvature for the given parameter t [[nodiscard]] double curvature(const double t) const; }; -} // namespace bezier_sampler +} // namespace autoware::bezier_sampler -#endif // BEZIER_SAMPLER__BEZIER_HPP_ +#endif // AUTOWARE_BEZIER_SAMPLER__BEZIER_HPP_ diff --git a/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier_sampling.hpp b/planning/sampling_based_planner/autoware_bezier_sampler/include/autoware_bezier_sampler/bezier_sampling.hpp similarity index 80% rename from planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier_sampling.hpp rename to planning/sampling_based_planner/autoware_bezier_sampler/include/autoware_bezier_sampler/bezier_sampling.hpp index 18df9dcb796d8..a832ef1f5cd39 100644 --- a/planning/sampling_based_planner/bezier_sampler/include/bezier_sampler/bezier_sampling.hpp +++ b/planning/sampling_based_planner/autoware_bezier_sampler/include/autoware_bezier_sampler/bezier_sampling.hpp @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEZIER_SAMPLER__BEZIER_SAMPLING_HPP_ -#define BEZIER_SAMPLER__BEZIER_SAMPLING_HPP_ +#ifndef AUTOWARE_BEZIER_SAMPLER__BEZIER_SAMPLING_HPP_ +#define AUTOWARE_BEZIER_SAMPLER__BEZIER_SAMPLING_HPP_ -#include +#include +#include #include #include -#include #include -namespace bezier_sampler +namespace autoware::bezier_sampler { struct SamplingParameters { @@ -38,13 +38,13 @@ struct SamplingParameters /// @details from Section IV of A. Artuñedoet al.: Real-Time Motion Planning Approach for Automated /// Driving in Urban Environments std::vector sample( - const sampler_common::State & initial, const sampler_common::State & final, + const autoware::sampler_common::State & initial, const autoware::sampler_common::State & final, const SamplingParameters & params); /// @brief generate a Bezier curve for the given states, velocities, and accelerations Bezier generate( const Eigen::Vector2d & initial_pose, const Eigen::Vector2d & final_pose, const Eigen::Vector2d & initial_velocity, const Eigen::Vector2d & initial_acceleration, const Eigen::Vector2d & final_velocity, const Eigen::Vector2d & final_acceleration); -} // namespace bezier_sampler +} // namespace autoware::bezier_sampler -#endif // BEZIER_SAMPLER__BEZIER_SAMPLING_HPP_ +#endif // AUTOWARE_BEZIER_SAMPLER__BEZIER_SAMPLING_HPP_ diff --git a/planning/sampling_based_planner/bezier_sampler/package.xml b/planning/sampling_based_planner/autoware_bezier_sampler/package.xml similarity index 89% rename from planning/sampling_based_planner/bezier_sampler/package.xml rename to planning/sampling_based_planner/autoware_bezier_sampler/package.xml index efe65e830871a..62dce46816119 100644 --- a/planning/sampling_based_planner/bezier_sampler/package.xml +++ b/planning/sampling_based_planner/autoware_bezier_sampler/package.xml @@ -1,6 +1,6 @@ - bezier_sampler + autoware_bezier_sampler 0.0.1 Package to sample trajectories using Bézier curves Maxime CLEMENT @@ -11,8 +11,8 @@ autoware_cmake + autoware_sampler_common eigen - sampler_common ament_cmake_ros ament_lint_auto diff --git a/planning/sampling_based_planner/bezier_sampler/src/bezier.cpp b/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier.cpp similarity index 96% rename from planning/sampling_based_planner/bezier_sampler/src/bezier.cpp rename to planning/sampling_based_planner/autoware_bezier_sampler/src/bezier.cpp index fc4c09840f507..9a882ad06659a 100644 --- a/planning/sampling_based_planner/bezier_sampler/src/bezier.cpp +++ b/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include -namespace bezier_sampler +namespace autoware::bezier_sampler { Bezier::Bezier(Eigen::Matrix control_points) : control_points_(std::move(control_points)) @@ -117,4 +117,4 @@ double Bezier::heading(const double t) const return std::atan2(vel.y(), vel.x()); } -} // namespace bezier_sampler +} // namespace autoware::bezier_sampler diff --git a/planning/sampling_based_planner/bezier_sampler/src/bezier_sampling.cpp b/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier_sampling.cpp similarity index 94% rename from planning/sampling_based_planner/bezier_sampler/src/bezier_sampling.cpp rename to planning/sampling_based_planner/autoware_bezier_sampler/src/bezier_sampling.cpp index a9fa318980250..e9a1a9ef32de5 100644 --- a/planning/sampling_based_planner/bezier_sampler/src/bezier_sampling.cpp +++ b/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier_sampling.cpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include -namespace bezier_sampler +namespace autoware::bezier_sampler { std::vector sample( - const sampler_common::State & initial, const sampler_common::State & final, + const autoware::sampler_common::State & initial, const autoware::sampler_common::State & final, const SamplingParameters & params) { std::vector curves; @@ -75,4 +75,4 @@ Bezier generate( (1.0 / 20.0) * final_acceleration.transpose(); return Bezier(control_points); } -} // namespace bezier_sampler +} // namespace autoware::bezier_sampler diff --git a/planning/sampling_based_planner/frenet_planner/CMakeLists.txt b/planning/sampling_based_planner/autoware_frenet_planner/CMakeLists.txt similarity index 78% rename from planning/sampling_based_planner/frenet_planner/CMakeLists.txt rename to planning/sampling_based_planner/autoware_frenet_planner/CMakeLists.txt index 0d7918daa215b..f928702a387b9 100644 --- a/planning/sampling_based_planner/frenet_planner/CMakeLists.txt +++ b/planning/sampling_based_planner/autoware_frenet_planner/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(frenet_planner) +project(autoware_frenet_planner) find_package(autoware_cmake REQUIRED) autoware_package() @@ -7,7 +7,7 @@ autoware_package() find_package(eigen3_cmake_module REQUIRED) find_package(Eigen3 REQUIRED) -ament_auto_add_library(frenet_planner SHARED +ament_auto_add_library(autoware_frenet_planner SHARED DIRECTORY src/ ) diff --git a/planning/sampling_based_planner/frenet_planner/README.md b/planning/sampling_based_planner/autoware_frenet_planner/README.md similarity index 100% rename from planning/sampling_based_planner/frenet_planner/README.md rename to planning/sampling_based_planner/autoware_frenet_planner/README.md diff --git a/planning/sampling_based_planner/frenet_planner/include/frenet_planner/conversions.hpp b/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/conversions.hpp similarity index 81% rename from planning/sampling_based_planner/frenet_planner/include/frenet_planner/conversions.hpp rename to planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/conversions.hpp index f8575d8f65936..dc504ba1386eb 100644 --- a/planning/sampling_based_planner/frenet_planner/include/frenet_planner/conversions.hpp +++ b/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/conversions.hpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FRENET_PLANNER__CONVERSIONS_HPP_ -#define FRENET_PLANNER__CONVERSIONS_HPP_ +#ifndef AUTOWARE_FRENET_PLANNER__CONVERSIONS_HPP_ +#define AUTOWARE_FRENET_PLANNER__CONVERSIONS_HPP_ -#include "frenet_planner/polynomials.hpp" +#include "autoware_frenet_planner/polynomials.hpp" -#include +#include #include -namespace frenet_planner +namespace autoware::frenet_planner { /// @brief calculate the lengths and yaws vectors of the given trajectory @@ -44,6 +44,6 @@ inline void calculateLengthsAndYaws(Trajectory & trajectory) const auto last_yaw = trajectory.yaws.empty() ? 0.0 : trajectory.yaws.back(); trajectory.yaws.push_back(last_yaw); } -} // namespace frenet_planner +} // namespace autoware::frenet_planner -#endif // FRENET_PLANNER__CONVERSIONS_HPP_ +#endif // AUTOWARE_FRENET_PLANNER__CONVERSIONS_HPP_ diff --git a/planning/sampling_based_planner/frenet_planner/include/frenet_planner/frenet_planner.hpp b/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/frenet_planner.hpp similarity index 67% rename from planning/sampling_based_planner/frenet_planner/include/frenet_planner/frenet_planner.hpp rename to planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/frenet_planner.hpp index 7d60214a52722..88eb2f3244e40 100644 --- a/planning/sampling_based_planner/frenet_planner/include/frenet_planner/frenet_planner.hpp +++ b/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/frenet_planner.hpp @@ -12,34 +12,34 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FRENET_PLANNER__FRENET_PLANNER_HPP_ -#define FRENET_PLANNER__FRENET_PLANNER_HPP_ +#ifndef AUTOWARE_FRENET_PLANNER__FRENET_PLANNER_HPP_ +#define AUTOWARE_FRENET_PLANNER__FRENET_PLANNER_HPP_ -#include "frenet_planner/structures.hpp" -#include "sampler_common/structures.hpp" -#include "sampler_common/transform/spline_transform.hpp" +#include "autoware_frenet_planner/structures.hpp" +#include "autoware_sampler_common/structures.hpp" +#include "autoware_sampler_common/transform/spline_transform.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" #include #include -namespace frenet_planner +namespace autoware::frenet_planner { /// @brief generate trajectories relative to the reference for the given initial state and sampling /// parameters std::vector generateTrajectories( - const sampler_common::transform::Spline2D & reference_spline, const FrenetState & initial_state, - const SamplingParameters & sampling_parameters); + const autoware::sampler_common::transform::Spline2D & reference_spline, + const FrenetState & initial_state, const SamplingParameters & sampling_parameters); /// @brief generate trajectories relative to the reference for the given initial state and sampling /// parameters std::vector generateLowVelocityTrajectories( - const sampler_common::transform::Spline2D & reference_spline, const FrenetState & initial_state, - const SamplingParameters & sampling_parameters); + const autoware::sampler_common::transform::Spline2D & reference_spline, + const FrenetState & initial_state, const SamplingParameters & sampling_parameters); /// @brief generate paths relative to the reference for the given initial state and sampling /// parameters std::vector generatePaths( - const sampler_common::transform::Spline2D & reference_spline, const FrenetState & initial_state, - const SamplingParameters & sampling_parameters); + const autoware::sampler_common::transform::Spline2D & reference_spline, + const FrenetState & initial_state, const SamplingParameters & sampling_parameters); /// @brief generate a candidate path /// @details one polynomial for lateral motion (d) is calculated over the longitudinal displacement /// (s): d(s). @@ -58,11 +58,12 @@ Trajectory generateLowVelocityCandidate( const FrenetState & initial_state, const FrenetState & target_state, const double duration, const double time_resolution); /// @brief calculate the cartesian frame of the given path -void calculateCartesian(const sampler_common::transform::Spline2D & reference, Path & path); +void calculateCartesian( + const autoware::sampler_common::transform::Spline2D & reference, Path & path); /// @brief calculate the cartesian frame of the given trajectory void calculateCartesian( - const sampler_common::transform::Spline2D & reference, Trajectory & trajectory); + const autoware::sampler_common::transform::Spline2D & reference, Trajectory & trajectory); -} // namespace frenet_planner +} // namespace autoware::frenet_planner -#endif // FRENET_PLANNER__FRENET_PLANNER_HPP_ +#endif // AUTOWARE_FRENET_PLANNER__FRENET_PLANNER_HPP_ diff --git a/planning/sampling_based_planner/frenet_planner/include/frenet_planner/polynomials.hpp b/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/polynomials.hpp similarity index 88% rename from planning/sampling_based_planner/frenet_planner/include/frenet_planner/polynomials.hpp rename to planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/polynomials.hpp index 65157c76d5db3..02217ef8ad444 100644 --- a/planning/sampling_based_planner/frenet_planner/include/frenet_planner/polynomials.hpp +++ b/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/polynomials.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FRENET_PLANNER__POLYNOMIALS_HPP_ -#define FRENET_PLANNER__POLYNOMIALS_HPP_ +#ifndef AUTOWARE_FRENET_PLANNER__POLYNOMIALS_HPP_ +#define AUTOWARE_FRENET_PLANNER__POLYNOMIALS_HPP_ -namespace frenet_planner +namespace autoware::frenet_planner { class Polynomial { @@ -50,6 +50,6 @@ class Polynomial /// @brief Get the jerk at the given time [[nodiscard]] double jerk(const double t) const; }; -} // namespace frenet_planner +} // namespace autoware::frenet_planner -#endif // FRENET_PLANNER__POLYNOMIALS_HPP_ +#endif // AUTOWARE_FRENET_PLANNER__POLYNOMIALS_HPP_ diff --git a/planning/sampling_based_planner/frenet_planner/include/frenet_planner/structures.hpp b/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/structures.hpp similarity index 73% rename from planning/sampling_based_planner/frenet_planner/include/frenet_planner/structures.hpp rename to planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/structures.hpp index c44cb5d814d71..d2a71d06a7933 100644 --- a/planning/sampling_based_planner/frenet_planner/include/frenet_planner/structures.hpp +++ b/planning/sampling_based_planner/autoware_frenet_planner/include/autoware_frenet_planner/structures.hpp @@ -12,52 +12,54 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FRENET_PLANNER__STRUCTURES_HPP_ -#define FRENET_PLANNER__STRUCTURES_HPP_ +#ifndef AUTOWARE_FRENET_PLANNER__STRUCTURES_HPP_ +#define AUTOWARE_FRENET_PLANNER__STRUCTURES_HPP_ -#include "frenet_planner/polynomials.hpp" +#include "autoware_frenet_planner/polynomials.hpp" -#include +#include #include #include -namespace frenet_planner +namespace autoware::frenet_planner { struct FrenetState { - sampler_common::FrenetPoint position = {0, 0}; + autoware::sampler_common::FrenetPoint position = {0, 0}; double lateral_velocity{}; double longitudinal_velocity{}; double lateral_acceleration{}; double longitudinal_acceleration{}; }; -struct Path : sampler_common::Path +struct Path : autoware::sampler_common::Path { - std::vector frenet_points{}; + std::vector frenet_points{}; std::optional lateral_polynomial{}; Path() = default; - explicit Path(const sampler_common::Path & path) : sampler_common::Path(path) {} + explicit Path(const autoware::sampler_common::Path & path) : autoware::sampler_common::Path(path) + { + } void clear() override { - sampler_common::Path::clear(); + autoware::sampler_common::Path::clear(); frenet_points.clear(); lateral_polynomial.reset(); } void reserve(const size_t size) override { - sampler_common::Path::reserve(size); + autoware::sampler_common::Path::reserve(size); frenet_points.reserve(size); } [[nodiscard]] Path extend(const Path & path) const { - Path extended_traj(sampler_common::Path::extend(path)); + Path extended_traj(autoware::sampler_common::Path::extend(path)); extended_traj.frenet_points.insert( extended_traj.frenet_points.end(), frenet_points.begin(), frenet_points.end()); extended_traj.frenet_points.insert( @@ -69,7 +71,7 @@ struct Path : sampler_common::Path [[nodiscard]] Path * subset(const size_t from_idx, const size_t to_idx) const override { - auto * subpath = new Path(*sampler_common::Path::subset(from_idx, to_idx)); + auto * subpath = new Path(*autoware::sampler_common::Path::subset(from_idx, to_idx)); assert(to_idx >= from_idx); subpath->reserve(to_idx - from_idx); @@ -87,19 +89,22 @@ struct SamplingParameter FrenetState target_state; }; -struct Trajectory : sampler_common::Trajectory +struct Trajectory : autoware::sampler_common::Trajectory { - std::vector frenet_points{}; + std::vector frenet_points{}; std::optional lateral_polynomial{}; std::optional longitudinal_polynomial{}; SamplingParameter sampling_parameter; Trajectory() = default; - explicit Trajectory(const sampler_common::Trajectory & traj) : sampler_common::Trajectory(traj) {} + explicit Trajectory(const autoware::sampler_common::Trajectory & traj) + : autoware::sampler_common::Trajectory(traj) + { + } void clear() override { - sampler_common::Trajectory::clear(); + autoware::sampler_common::Trajectory::clear(); frenet_points.clear(); lateral_polynomial.reset(); longitudinal_polynomial.reset(); @@ -107,13 +112,13 @@ struct Trajectory : sampler_common::Trajectory void reserve(const size_t size) override { - sampler_common::Trajectory::reserve(size); + autoware::sampler_common::Trajectory::reserve(size); frenet_points.reserve(size); } [[nodiscard]] Trajectory extend(const Trajectory & traj) const { - Trajectory extended_traj(sampler_common::Trajectory::extend(traj)); + Trajectory extended_traj(autoware::sampler_common::Trajectory::extend(traj)); extended_traj.frenet_points.insert( extended_traj.frenet_points.end(), frenet_points.begin(), frenet_points.end()); extended_traj.frenet_points.insert( @@ -126,7 +131,8 @@ struct Trajectory : sampler_common::Trajectory [[nodiscard]] Trajectory * subset(const size_t from_idx, const size_t to_idx) const override { - auto * sub_trajectory = new Trajectory(*sampler_common::Trajectory::subset(from_idx, to_idx)); + auto * sub_trajectory = + new Trajectory(*autoware::sampler_common::Trajectory::subset(from_idx, to_idx)); assert(to_idx >= from_idx); sub_trajectory->reserve(to_idx - from_idx); @@ -151,6 +157,6 @@ struct SamplingParameters std::vector parameters; double resolution; }; -} // namespace frenet_planner +} // namespace autoware::frenet_planner -#endif // FRENET_PLANNER__STRUCTURES_HPP_ +#endif // AUTOWARE_FRENET_PLANNER__STRUCTURES_HPP_ diff --git a/planning/sampling_based_planner/frenet_planner/launch/frenet_planner.launch b/planning/sampling_based_planner/autoware_frenet_planner/launch/frenet_planner.launch similarity index 78% rename from planning/sampling_based_planner/frenet_planner/launch/frenet_planner.launch rename to planning/sampling_based_planner/autoware_frenet_planner/launch/frenet_planner.launch index 9570d488eaecc..69e5961b9cdb8 100644 --- a/planning/sampling_based_planner/frenet_planner/launch/frenet_planner.launch +++ b/planning/sampling_based_planner/autoware_frenet_planner/launch/frenet_planner.launch @@ -3,7 +3,7 @@ - + diff --git a/planning/sampling_based_planner/frenet_planner/package.xml b/planning/sampling_based_planner/autoware_frenet_planner/package.xml similarity index 76% rename from planning/sampling_based_planner/frenet_planner/package.xml rename to planning/sampling_based_planner/autoware_frenet_planner/package.xml index c378c6ae25e9b..1ba7c8a148007 100644 --- a/planning/sampling_based_planner/frenet_planner/package.xml +++ b/planning/sampling_based_planner/autoware_frenet_planner/package.xml @@ -1,8 +1,8 @@ - frenet_planner + autoware_frenet_planner 0.0.1 - The frenet_planner package for trajectory generation in Frenet frame + The autoware_frenet_planner package for trajectory generation in Frenet frame Maxime CLEMENT Maxime CLEMENT Apache License 2.0 @@ -12,7 +12,7 @@ autoware_cmake autoware_auto_common - sampler_common + autoware_sampler_common ament_cmake_ros ament_lint_auto diff --git a/planning/sampling_based_planner/frenet_planner/src/frenet_planner/frenet_planner.cpp b/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp similarity index 89% rename from planning/sampling_based_planner/frenet_planner/src/frenet_planner/frenet_planner.cpp rename to planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp index 6f0bef882743c..ba3156c6b085d 100644 --- a/planning/sampling_based_planner/frenet_planner/src/frenet_planner/frenet_planner.cpp +++ b/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "frenet_planner/frenet_planner.hpp" +#include "autoware_frenet_planner/frenet_planner.hpp" #include +#include +#include +#include +#include +#include #include -#include -#include -#include -#include -#include #include "autoware_planning_msgs/msg/path.hpp" #include @@ -31,11 +31,11 @@ #include #include -namespace frenet_planner +namespace autoware::frenet_planner { std::vector generateTrajectories( - const sampler_common::transform::Spline2D & reference_spline, const FrenetState & initial_state, - const SamplingParameters & sampling_parameters) + const autoware::sampler_common::transform::Spline2D & reference_spline, + const FrenetState & initial_state, const SamplingParameters & sampling_parameters) { std::vector trajectories; trajectories.reserve(sampling_parameters.parameters.size()); @@ -54,8 +54,8 @@ std::vector generateTrajectories( } std::vector generateLowVelocityTrajectories( - const sampler_common::transform::Spline2D & reference_spline, const FrenetState & initial_state, - const SamplingParameters & sampling_parameters) + const autoware::sampler_common::transform::Spline2D & reference_spline, + const FrenetState & initial_state, const SamplingParameters & sampling_parameters) { std::vector trajectories; trajectories.reserve(sampling_parameters.parameters.size()); @@ -73,8 +73,8 @@ std::vector generateLowVelocityTrajectories( } std::vector generatePaths( - const sampler_common::transform::Spline2D & reference_spline, const FrenetState & initial_state, - const SamplingParameters & sampling_parameters) + const autoware::sampler_common::transform::Spline2D & reference_spline, + const FrenetState & initial_state, const SamplingParameters & sampling_parameters) { std::vector candidates; candidates.reserve(sampling_parameters.parameters.size()); @@ -148,7 +148,8 @@ Path generateCandidate( return path; } -void calculateCartesian(const sampler_common::transform::Spline2D & reference, Path & path) +void calculateCartesian( + const autoware::sampler_common::transform::Spline2D & reference, Path & path) { if (!path.frenet_points.empty()) { path.points.reserve(path.frenet_points.size()); @@ -191,7 +192,7 @@ void calculateCartesian(const sampler_common::transform::Spline2D & reference, P } } void calculateCartesian( - const sampler_common::transform::Spline2D & reference, Trajectory & trajectory) + const autoware::sampler_common::transform::Spline2D & reference, Trajectory & trajectory) { if (!trajectory.frenet_points.empty()) { trajectory.points.reserve(trajectory.frenet_points.size()); @@ -240,4 +241,4 @@ void calculateCartesian( } } -} // namespace frenet_planner +} // namespace autoware::frenet_planner diff --git a/planning/sampling_based_planner/frenet_planner/src/frenet_planner/polynomials.cpp b/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/polynomials.cpp similarity index 94% rename from planning/sampling_based_planner/frenet_planner/src/frenet_planner/polynomials.cpp rename to planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/polynomials.cpp index 13f71dc88f9d6..b785255cd856c 100644 --- a/planning/sampling_based_planner/frenet_planner/src/frenet_planner/polynomials.cpp +++ b/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/polynomials.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include -#include -namespace frenet_planner +namespace autoware::frenet_planner { // @brief Create a polynomial connecting the given initial and target configuration over the given // duration @@ -72,4 +72,4 @@ double Polynomial::jerk(const double t) const const double t2 = t * t; return 60 * a_ * t2 + 24 * b_ * t + 6 * c_; } -} // namespace frenet_planner +} // namespace autoware::frenet_planner diff --git a/planning/sampling_based_planner/path_sampler/CMakeLists.txt b/planning/sampling_based_planner/autoware_path_sampler/CMakeLists.txt similarity index 52% rename from planning/sampling_based_planner/path_sampler/CMakeLists.txt rename to planning/sampling_based_planner/autoware_path_sampler/CMakeLists.txt index 5a5b99f0aff3a..170646b0c0c9a 100644 --- a/planning/sampling_based_planner/path_sampler/CMakeLists.txt +++ b/planning/sampling_based_planner/autoware_path_sampler/CMakeLists.txt @@ -1,16 +1,16 @@ cmake_minimum_required(VERSION 3.14) -project(path_sampler) +project(autoware_path_sampler) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_library(path_sampler SHARED +ament_auto_add_library(autoware_path_sampler SHARED DIRECTORY src ) # register node -rclcpp_components_register_node(path_sampler - PLUGIN "path_sampler::PathSampler" +rclcpp_components_register_node(autoware_path_sampler + PLUGIN "autoware::path_sampler::PathSampler" EXECUTABLE path_sampler_exe ) diff --git a/planning/sampling_based_planner/path_sampler/README.md b/planning/sampling_based_planner/autoware_path_sampler/README.md similarity index 100% rename from planning/sampling_based_planner/path_sampler/README.md rename to planning/sampling_based_planner/autoware_path_sampler/README.md diff --git a/planning/sampling_based_planner/path_sampler/include/path_sampler/common_structs.hpp b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/common_structs.hpp similarity index 87% rename from planning/sampling_based_planner/path_sampler/include/path_sampler/common_structs.hpp rename to planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/common_structs.hpp index 7cf88cb75e13a..5a8183d8e5926 100644 --- a/planning/sampling_based_planner/path_sampler/include/path_sampler/common_structs.hpp +++ b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/common_structs.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SAMPLER__COMMON_STRUCTS_HPP_ -#define PATH_SAMPLER__COMMON_STRUCTS_HPP_ +#ifndef AUTOWARE_PATH_SAMPLER__COMMON_STRUCTS_HPP_ +#define AUTOWARE_PATH_SAMPLER__COMMON_STRUCTS_HPP_ -#include "path_sampler/type_alias.hpp" +#include "autoware_path_sampler/type_alias.hpp" +#include "autoware_sampler_common/structures.hpp" #include "rclcpp/rclcpp.hpp" -#include "sampler_common/structures.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" @@ -28,7 +28,7 @@ #include #include -namespace path_sampler +namespace autoware::path_sampler { struct PlannerData { @@ -61,7 +61,7 @@ struct TimeKeeper latest_stream.str(""); if (enable_calculation_time_info) { - RCLCPP_INFO_STREAM(rclcpp::get_logger("path_sampler.time"), msg); + RCLCPP_INFO_STREAM(rclcpp::get_logger("autoware_path_sampler.time"), msg); } } @@ -87,7 +87,7 @@ struct TimeKeeper struct DebugData { - std::vector sampled_candidates{}; + std::vector sampled_candidates{}; size_t previous_sampled_candidates_nb = 0UL; std::vector obstacles{}; std::vector footprints{}; @@ -131,6 +131,6 @@ struct EgoNearestParam double dist_threshold{0.0}; double yaw_threshold{0.0}; }; -} // namespace path_sampler +} // namespace autoware::path_sampler -#endif // PATH_SAMPLER__COMMON_STRUCTS_HPP_ +#endif // AUTOWARE_PATH_SAMPLER__COMMON_STRUCTS_HPP_ diff --git a/planning/sampling_based_planner/path_sampler/include/path_sampler/node.hpp b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/node.hpp similarity index 77% rename from planning/sampling_based_planner/path_sampler/include/path_sampler/node.hpp rename to planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/node.hpp index ab9bc71bc79e4..e44c38aed2b53 100644 --- a/planning/sampling_based_planner/path_sampler/include/path_sampler/node.hpp +++ b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/node.hpp @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SAMPLER__NODE_HPP_ -#define PATH_SAMPLER__NODE_HPP_ +#ifndef AUTOWARE_PATH_SAMPLER__NODE_HPP_ +#define AUTOWARE_PATH_SAMPLER__NODE_HPP_ -#include "path_sampler/common_structs.hpp" -#include "path_sampler/parameters.hpp" -#include "path_sampler/type_alias.hpp" +#include "autoware_path_sampler/common_structs.hpp" +#include "autoware_path_sampler/parameters.hpp" +#include "autoware_path_sampler/type_alias.hpp" +#include "autoware_sampler_common/transform/spline_transform.hpp" #include "rclcpp/rclcpp.hpp" -#include "sampler_common/transform/spline_transform.hpp" #include "vehicle_info_util/vehicle_info_util.hpp" -#include +#include #include #include @@ -30,7 +30,7 @@ #include #include -namespace path_sampler +namespace autoware::path_sampler { class PathSampler : public rclcpp::Node { @@ -54,7 +54,7 @@ class PathSampler : public rclcpp::Node PredictedObjects::SharedPtr in_objects_ptr_ = std::make_shared(); // variables for previous information - std::optional prev_path_; + std::optional prev_path_; // interface publisher rclcpp::Publisher::SharedPtr traj_pub_; @@ -86,8 +86,9 @@ class PathSampler : public rclcpp::Node const std::vector & traj_points, const std::vector & optimized_points) const; void resetPreviousData(); - sampler_common::State getPlanningState( - sampler_common::State & state, const sampler_common::transform::Spline2D & path_spline) const; + autoware::sampler_common::State getPlanningState( + autoware::sampler_common::State & state, + const autoware::sampler_common::transform::Spline2D & path_spline) const; // sub-functions of generateTrajectory void copyZ( @@ -95,13 +96,14 @@ class PathSampler : public rclcpp::Node void copyVelocity( const std::vector & from_traj, std::vector & to_traj, const geometry_msgs::msg::Pose & ego_pose); - sampler_common::Path generatePath(const PlannerData & planner_data); - std::vector generateCandidatesFromPreviousPath( - const PlannerData & planner_data, const sampler_common::transform::Spline2D & path_spline); + autoware::sampler_common::Path generatePath(const PlannerData & planner_data); + std::vector generateCandidatesFromPreviousPath( + const PlannerData & planner_data, + const autoware::sampler_common::transform::Spline2D & path_spline); std::vector generateTrajectoryPoints(const PlannerData & planner_data); void publishVirtualWall(const geometry_msgs::msg::Pose & stop_pose) const; void publishDebugMarker(const std::vector & traj_points) const; }; -} // namespace path_sampler +} // namespace autoware::path_sampler -#endif // PATH_SAMPLER__NODE_HPP_ +#endif // AUTOWARE_PATH_SAMPLER__NODE_HPP_ diff --git a/planning/sampling_based_planner/path_sampler/include/path_sampler/parameters.hpp b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/parameters.hpp similarity index 77% rename from planning/sampling_based_planner/path_sampler/include/path_sampler/parameters.hpp rename to planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/parameters.hpp index 03887d8357e0d..0ce0ea875c066 100644 --- a/planning/sampling_based_planner/path_sampler/include/path_sampler/parameters.hpp +++ b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/parameters.hpp @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SAMPLER__PARAMETERS_HPP_ -#define PATH_SAMPLER__PARAMETERS_HPP_ +#ifndef AUTOWARE_PATH_SAMPLER__PARAMETERS_HPP_ +#define AUTOWARE_PATH_SAMPLER__PARAMETERS_HPP_ -#include "bezier_sampler/bezier_sampling.hpp" -#include "sampler_common/structures.hpp" +#include "autoware_bezier_sampler/bezier_sampling.hpp" +#include "autoware_sampler_common/structures.hpp" #include struct Parameters { - sampler_common::Constraints constraints; + autoware::sampler_common::Constraints constraints; struct { bool enable_frenet{}; @@ -37,7 +37,7 @@ struct Parameters std::vector target_lateral_velocities{}; std::vector target_lateral_accelerations{}; } frenet; - bezier_sampler::SamplingParameters bezier{}; + autoware::bezier_sampler::SamplingParameters bezier{}; } sampling; struct @@ -54,4 +54,4 @@ struct Parameters } path_reuse{}; }; -#endif // PATH_SAMPLER__PARAMETERS_HPP_ +#endif // AUTOWARE_PATH_SAMPLER__PARAMETERS_HPP_ diff --git a/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/path_generation.hpp b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/path_generation.hpp new file mode 100644 index 0000000000000..ef234f1d8207a --- /dev/null +++ b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/path_generation.hpp @@ -0,0 +1,52 @@ +// Copyright 2023 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_PATH_SAMPLER__PATH_GENERATION_HPP_ +#define AUTOWARE_PATH_SAMPLER__PATH_GENERATION_HPP_ + +#include "autoware_bezier_sampler/bezier_sampling.hpp" +#include "autoware_frenet_planner/structures.hpp" +#include "autoware_path_sampler/parameters.hpp" +#include "autoware_sampler_common/constraints/hard_constraint.hpp" +#include "autoware_sampler_common/structures.hpp" +#include "autoware_sampler_common/transform/spline_transform.hpp" + +#include + +#include + +namespace autoware::path_sampler +{ +/** + * @brief generate candidate paths for the given problem inputs + * @param [in] initial_state initial ego state + * @param [in] path_spline spline of the reference path + * @param [in] base_length base length of the reuse path (= 0.0 if not reusing a previous path) + * @param [in] params parameters + * @return candidate paths + */ +std::vector generateCandidatePaths( + const autoware::sampler_common::State & initial_state, + const autoware::sampler_common::transform::Spline2D & path_spline, const double base_length, + const Parameters & params); + +std::vector generateBezierPaths( + const autoware::sampler_common::State & initial_state, const double base_length, + const autoware::sampler_common::transform::Spline2D & path_spline, const Parameters & params); +std::vector generateFrenetPaths( + const autoware::sampler_common::State & initial_state, const double base_length, + const autoware::sampler_common::transform::Spline2D & path_spline, const Parameters & params); +} // namespace autoware::path_sampler + +#endif // AUTOWARE_PATH_SAMPLER__PATH_GENERATION_HPP_ diff --git a/planning/sampling_based_planner/path_sampler/include/path_sampler/prepare_inputs.hpp b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/prepare_inputs.hpp similarity index 64% rename from planning/sampling_based_planner/path_sampler/include/path_sampler/prepare_inputs.hpp rename to planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/prepare_inputs.hpp index a9a2728b27c49..1b10be1121481 100644 --- a/planning/sampling_based_planner/path_sampler/include/path_sampler/prepare_inputs.hpp +++ b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/prepare_inputs.hpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SAMPLER__PREPARE_INPUTS_HPP_ -#define PATH_SAMPLER__PREPARE_INPUTS_HPP_ +#ifndef AUTOWARE_PATH_SAMPLER__PREPARE_INPUTS_HPP_ +#define AUTOWARE_PATH_SAMPLER__PREPARE_INPUTS_HPP_ -#include "frenet_planner/structures.hpp" -#include "path_sampler/parameters.hpp" -#include "path_sampler/type_alias.hpp" -#include "sampler_common/transform/spline_transform.hpp" +#include "autoware_frenet_planner/structures.hpp" +#include "autoware_path_sampler/parameters.hpp" +#include "autoware_path_sampler/type_alias.hpp" +#include "autoware_sampler_common/transform/spline_transform.hpp" #include #include @@ -35,20 +35,20 @@ #include #include -namespace path_sampler +namespace autoware::path_sampler { /// @brief prepare constraints void prepareConstraints( - sampler_common::Constraints & constraints, const PredictedObjects & predicted_objects, + autoware::sampler_common::Constraints & constraints, const PredictedObjects & predicted_objects, const std::vector & left_bound, const std::vector & right_bound); /// @brief prepare sampling parameters to generate Frenet paths -frenet_planner::SamplingParameters prepareSamplingParameters( - const sampler_common::State & initial_state, const double base_length, - const sampler_common::transform::Spline2D & path_spline, const Parameters & params); +autoware::frenet_planner::SamplingParameters prepareSamplingParameters( + const autoware::sampler_common::State & initial_state, const double base_length, + const autoware::sampler_common::transform::Spline2D & path_spline, const Parameters & params); /// @brief prepare the 2D spline representation of the given Path message -sampler_common::transform::Spline2D preparePathSpline( +autoware::sampler_common::transform::Spline2D preparePathSpline( const std::vector & path_msg, const bool smooth_path); -} // namespace path_sampler +} // namespace autoware::path_sampler -#endif // PATH_SAMPLER__PREPARE_INPUTS_HPP_ +#endif // AUTOWARE_PATH_SAMPLER__PREPARE_INPUTS_HPP_ diff --git a/planning/sampling_based_planner/path_sampler/include/path_sampler/type_alias.hpp b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/type_alias.hpp similarity index 88% rename from planning/sampling_based_planner/path_sampler/include/path_sampler/type_alias.hpp rename to planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/type_alias.hpp index 90e655c086444..95d833c4df47d 100644 --- a/planning/sampling_based_planner/path_sampler/include/path_sampler/type_alias.hpp +++ b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/type_alias.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SAMPLER__TYPE_ALIAS_HPP_ -#define PATH_SAMPLER__TYPE_ALIAS_HPP_ +#ifndef AUTOWARE_PATH_SAMPLER__TYPE_ALIAS_HPP_ +#define AUTOWARE_PATH_SAMPLER__TYPE_ALIAS_HPP_ #include "autoware_perception_msgs/msg/predicted_objects.hpp" #include "autoware_planning_msgs/msg/path.hpp" @@ -28,7 +28,7 @@ #include "tier4_debug_msgs/msg/string_stamped.hpp" #include "visualization_msgs/msg/marker_array.hpp" -namespace path_sampler +namespace autoware::path_sampler { // std_msgs using std_msgs::msg::Header; @@ -46,6 +46,6 @@ using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; // debug using tier4_debug_msgs::msg::StringStamped; -} // namespace path_sampler +} // namespace autoware::path_sampler -#endif // PATH_SAMPLER__TYPE_ALIAS_HPP_ +#endif // AUTOWARE_PATH_SAMPLER__TYPE_ALIAS_HPP_ diff --git a/planning/sampling_based_planner/path_sampler/include/path_sampler/utils/geometry_utils.hpp b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/geometry_utils.hpp similarity index 81% rename from planning/sampling_based_planner/path_sampler/include/path_sampler/utils/geometry_utils.hpp rename to planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/geometry_utils.hpp index 875b81b9cd49a..abd2fa367bc7b 100644 --- a/planning/sampling_based_planner/path_sampler/include/path_sampler/utils/geometry_utils.hpp +++ b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/geometry_utils.hpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SAMPLER__UTILS__GEOMETRY_UTILS_HPP_ -#define PATH_SAMPLER__UTILS__GEOMETRY_UTILS_HPP_ +#ifndef AUTOWARE_PATH_SAMPLER__UTILS__GEOMETRY_UTILS_HPP_ +#define AUTOWARE_PATH_SAMPLER__UTILS__GEOMETRY_UTILS_HPP_ +#include "autoware_path_sampler/common_structs.hpp" +#include "autoware_path_sampler/type_alias.hpp" #include "eigen3/Eigen/Core" #include "interpolation/linear_interpolation.hpp" #include "interpolation/spline_interpolation.hpp" #include "interpolation/spline_interpolation_points_2d.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "path_sampler/common_structs.hpp" -#include "path_sampler/type_alias.hpp" #include "vehicle_info_util/vehicle_info_util.hpp" #include "autoware_planning_msgs/msg/path_point.hpp" @@ -35,7 +35,7 @@ #include #include -namespace path_sampler +namespace autoware::path_sampler { namespace geometry_utils { @@ -52,5 +52,5 @@ bool isSamePoint(const T1 & t1, const T2 & t2) return true; } } // namespace geometry_utils -} // namespace path_sampler -#endif // PATH_SAMPLER__UTILS__GEOMETRY_UTILS_HPP_ +} // namespace autoware::path_sampler +#endif // AUTOWARE_PATH_SAMPLER__UTILS__GEOMETRY_UTILS_HPP_ diff --git a/planning/sampling_based_planner/path_sampler/include/path_sampler/utils/trajectory_utils.hpp b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/trajectory_utils.hpp similarity index 90% rename from planning/sampling_based_planner/path_sampler/include/path_sampler/utils/trajectory_utils.hpp rename to planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/trajectory_utils.hpp index a036dcfe638c2..4f346ae910f44 100644 --- a/planning/sampling_based_planner/path_sampler/include/path_sampler/utils/trajectory_utils.hpp +++ b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/utils/trajectory_utils.hpp @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SAMPLER__UTILS__TRAJECTORY_UTILS_HPP_ -#define PATH_SAMPLER__UTILS__TRAJECTORY_UTILS_HPP_ +#ifndef AUTOWARE_PATH_SAMPLER__UTILS__TRAJECTORY_UTILS_HPP_ +#define AUTOWARE_PATH_SAMPLER__UTILS__TRAJECTORY_UTILS_HPP_ +#include "autoware_path_sampler/common_structs.hpp" +#include "autoware_path_sampler/type_alias.hpp" +#include "autoware_sampler_common/structures.hpp" #include "eigen3/Eigen/Core" #include "interpolation/linear_interpolation.hpp" #include "interpolation/spline_interpolation.hpp" #include "interpolation/spline_interpolation_points_2d.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "path_sampler/common_structs.hpp" -#include "path_sampler/type_alias.hpp" -#include "sampler_common/structures.hpp" #include "autoware_planning_msgs/msg/path_point.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" @@ -33,7 +33,7 @@ #include #include -namespace path_sampler +namespace autoware::path_sampler { namespace trajectory_utils { @@ -95,7 +95,8 @@ std::vector convertToTrajectoryPoints(const std::vector & po return traj_points; } -inline std::vector convertToTrajectoryPoints(const sampler_common::Path & path) +inline std::vector convertToTrajectoryPoints( + const autoware::sampler_common::Path & path) { std::vector traj_points; for (auto i = 0UL; i < path.points.size(); ++i) { @@ -160,7 +161,7 @@ std::optional updateFrontPointForFix( motion_utils::calcSignedArcLength(points, 0, front_fix_point.pose.position); if (0 < lon_offset_to_prev_front) { RCLCPP_WARN( - rclcpp::get_logger("path_sampler.trajectory_utils"), + rclcpp::get_logger("autoware_path_sampler.trajectory_utils"), "Fixed point will not be inserted due to the error during calculation."); return std::nullopt; } @@ -171,7 +172,7 @@ std::optional updateFrontPointForFix( constexpr double max_lat_error = 3.0; if (max_lat_error < dist) { RCLCPP_WARN( - rclcpp::get_logger("path_sampler.trajectory_utils"), + rclcpp::get_logger("autoware_path_sampler.trajectory_utils"), "New Fixed point is too far from points %f [m]", dist); } @@ -193,5 +194,5 @@ void insertStopPoint( std::vector & traj_points, const geometry_msgs::msg::Pose & input_stop_pose, const size_t stop_seg_idx); } // namespace trajectory_utils -} // namespace path_sampler -#endif // PATH_SAMPLER__UTILS__TRAJECTORY_UTILS_HPP_ +} // namespace autoware::path_sampler +#endif // AUTOWARE_PATH_SAMPLER__UTILS__TRAJECTORY_UTILS_HPP_ diff --git a/planning/sampling_based_planner/path_sampler/package.xml b/planning/sampling_based_planner/autoware_path_sampler/package.xml similarity index 92% rename from planning/sampling_based_planner/path_sampler/package.xml rename to planning/sampling_based_planner/autoware_path_sampler/package.xml index a57ff6e6033f6..011da8d469607 100644 --- a/planning/sampling_based_planner/path_sampler/package.xml +++ b/planning/sampling_based_planner/autoware_path_sampler/package.xml @@ -1,7 +1,7 @@ - path_sampler + autoware_path_sampler 0.1.0 Package for the sampling-based path planner Maxime CLEMENT @@ -13,10 +13,10 @@ autoware_cmake + autoware_bezier_sampler + autoware_frenet_planner autoware_perception_msgs autoware_planning_msgs - bezier_sampler - frenet_planner geometry_msgs interpolation motion_utils diff --git a/planning/sampling_based_planner/path_sampler/src/node.cpp b/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp similarity index 94% rename from planning/sampling_based_planner/path_sampler/src/node.cpp rename to planning/sampling_based_planner/autoware_path_sampler/src/node.cpp index 97bafb68c47a8..a82c1b6a52a26 100644 --- a/planning/sampling_based_planner/path_sampler/src/node.cpp +++ b/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp @@ -12,25 +12,25 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "path_sampler/node.hpp" - +#include "autoware_path_sampler/node.hpp" + +#include "autoware_path_sampler/path_generation.hpp" +#include "autoware_path_sampler/prepare_inputs.hpp" +#include "autoware_path_sampler/utils/geometry_utils.hpp" +#include "autoware_path_sampler/utils/trajectory_utils.hpp" +#include "autoware_sampler_common/constraints/hard_constraint.hpp" +#include "autoware_sampler_common/constraints/soft_constraint.hpp" #include "interpolation/spline_interpolation_points_2d.hpp" #include "motion_utils/marker/marker_helper.hpp" #include "motion_utils/trajectory/conversion.hpp" -#include "path_sampler/path_generation.hpp" -#include "path_sampler/prepare_inputs.hpp" -#include "path_sampler/utils/geometry_utils.hpp" -#include "path_sampler/utils/trajectory_utils.hpp" #include "rclcpp/time.hpp" -#include "sampler_common/constraints/hard_constraint.hpp" -#include "sampler_common/constraints/soft_constraint.hpp" #include #include #include -namespace path_sampler +namespace autoware::path_sampler { namespace { @@ -220,8 +220,9 @@ void PathSampler::objectsCallback(const PredictedObjects::SharedPtr msg) in_objects_ptr_ = msg; } -sampler_common::State PathSampler::getPlanningState( - sampler_common::State & state, const sampler_common::transform::Spline2D & path_spline) const +autoware::sampler_common::State PathSampler::getPlanningState( + autoware::sampler_common::State & state, + const autoware::sampler_common::transform::Spline2D & path_spline) const { state.frenet = path_spline.frenet(state.pose); if (params_.preprocessing.force_zero_deviation) { @@ -390,13 +391,14 @@ std::vector PathSampler::generateTrajectory(const PlannerData & return generated_traj_points; } -std::vector PathSampler::generateCandidatesFromPreviousPath( - const PlannerData & planner_data, const sampler_common::transform::Spline2D & path_spline) +std::vector PathSampler::generateCandidatesFromPreviousPath( + const PlannerData & planner_data, + const autoware::sampler_common::transform::Spline2D & path_spline) { - std::vector candidates; + std::vector candidates; if (!prev_path_ || prev_path_->points.size() < 2) return candidates; // Update previous path - sampler_common::State current_state; + autoware::sampler_common::State current_state; current_state.pose = {planner_data.ego_pose.position.x, planner_data.ego_pose.position.y}; current_state.heading = tf2::getYaw(planner_data.ego_pose.orientation); const auto closest_iter = std::min_element( @@ -419,7 +421,7 @@ std::vector PathSampler::generateCandidatesFromPreviousPat const auto reuse_step = prev_path_length / params_.sampling.previous_path_reuse_points_nb; for (double reuse_length = reuse_step; reuse_length <= prev_path_length; reuse_length += reuse_step) { - sampler_common::State reuse_state; + autoware::sampler_common::State reuse_state; size_t reuse_idx = 0; for (reuse_idx = 0; reuse_idx + 1 < prev_path_->lengths.size() && prev_path_->lengths[reuse_idx] < reuse_length; @@ -438,13 +440,13 @@ std::vector PathSampler::generateCandidatesFromPreviousPat return candidates; } -sampler_common::Path PathSampler::generatePath(const PlannerData & planner_data) +autoware::sampler_common::Path PathSampler::generatePath(const PlannerData & planner_data) { time_keeper_ptr_->tic(__func__); - sampler_common::Path generated_path{}; + autoware::sampler_common::Path generated_path{}; if (prev_path_ && prev_path_->points.size() > 1) { - sampler_common::constraints::checkHardConstraints(*prev_path_, params_.constraints); + autoware::sampler_common::constraints::checkHardConstraints(*prev_path_, params_.constraints); if (prev_path_->constraint_results.isValid()) { const auto prev_path_spline = preparePathSpline(trajectory_utils::convertToTrajectoryPoints(*prev_path_), false); @@ -460,7 +462,7 @@ sampler_common::Path PathSampler::generatePath(const PlannerData & planner_data) } const auto path_spline = preparePathSpline(planner_data.traj_points, params_.preprocessing.smooth_reference); - sampler_common::State current_state; + autoware::sampler_common::State current_state; current_state.pose = {planner_data.ego_pose.position.x, planner_data.ego_pose.position.y}; current_state.heading = tf2::getYaw(planner_data.ego_pose.orientation); @@ -476,9 +478,9 @@ sampler_common::Path PathSampler::generatePath(const PlannerData & planner_data) debug_data_.footprints.clear(); for (auto & path : candidate_paths) { const auto footprint = - sampler_common::constraints::checkHardConstraints(path, params_.constraints); + autoware::sampler_common::constraints::checkHardConstraints(path, params_.constraints); debug_data_.footprints.push_back(footprint); - sampler_common::constraints::calculateCost(path, params_.constraints, path_spline); + autoware::sampler_common::constraints::calculateCost(path, params_.constraints, path_spline); } const auto best_path_idx = [](const auto & paths) { auto min_cost = std::numeric_limits::max(); @@ -701,7 +703,7 @@ std::vector PathSampler::extendTrajectory( time_keeper_ptr_->toc(__func__, " "); return resampled_traj_points; } -} // namespace path_sampler +} // namespace autoware::path_sampler #include "rclcpp_components/register_node_macro.hpp" -RCLCPP_COMPONENTS_REGISTER_NODE(path_sampler::PathSampler) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::path_sampler::PathSampler) diff --git a/planning/sampling_based_planner/path_sampler/src/path_generation.cpp b/planning/sampling_based_planner/autoware_path_sampler/src/path_generation.cpp similarity index 72% rename from planning/sampling_based_planner/path_sampler/src/path_generation.cpp rename to planning/sampling_based_planner/autoware_path_sampler/src/path_generation.cpp index 2d1587c7b45a3..63ca5e18f423b 100644 --- a/planning/sampling_based_planner/path_sampler/src/path_generation.cpp +++ b/planning/sampling_based_planner/autoware_path_sampler/src/path_generation.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "path_sampler/path_generation.hpp" +#include "autoware_path_sampler/path_generation.hpp" -#include "sampler_common/structures.hpp" +#include "autoware_sampler_common/structures.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -29,14 +29,14 @@ #include #include -namespace path_sampler +namespace autoware::path_sampler { -std::vector generateCandidatePaths( - const sampler_common::State & initial_state, - const sampler_common::transform::Spline2D & path_spline, const double base_length, +std::vector generateCandidatePaths( + const autoware::sampler_common::State & initial_state, + const autoware::sampler_common::transform::Spline2D & path_spline, const double base_length, const Parameters & params) { - std::vector paths; + std::vector paths; const auto move_to_paths = [&](auto & paths_to_move) { paths.insert( paths.end(), std::make_move_iterator(paths_to_move.begin()), @@ -53,27 +53,27 @@ std::vector generateCandidatePaths( } return paths; } -std::vector generateBezierPaths( - const sampler_common::State & initial_state, const double base_length, - const sampler_common::transform::Spline2D & path_spline, const Parameters & params) +std::vector generateBezierPaths( + const autoware::sampler_common::State & initial_state, const double base_length, + const autoware::sampler_common::transform::Spline2D & path_spline, const Parameters & params) { const auto initial_s = path_spline.frenet(initial_state.pose).s; const auto max_s = path_spline.lastS(); - std::vector bezier_paths; + std::vector bezier_paths; for (const auto target_length : params.sampling.target_lengths) { if (target_length <= base_length) continue; const auto target_s = std::min(max_s, initial_s + target_length - base_length); if (target_s >= max_s) break; - sampler_common::State target_state{}; + autoware::sampler_common::State target_state{}; target_state.pose = path_spline.cartesian({target_s, 0}); target_state.curvature = path_spline.curvature(target_s); target_state.heading = path_spline.yaw(target_s); const auto bezier_samples = - bezier_sampler::sample(initial_state, target_state, params.sampling.bezier); + autoware::bezier_sampler::sample(initial_state, target_state, params.sampling.bezier); const auto step = std::min(0.1, params.sampling.resolution / target_length); for (const auto & bezier : bezier_samples) { - sampler_common::Path path; + autoware::sampler_common::Path path; path.lengths.push_back(0.0); for (double t = 0.0; t <= 1.0; t += step) { const auto x_y = bezier.valueM(t); @@ -93,14 +93,14 @@ std::vector generateBezierPaths( return bezier_paths; } -std::vector generateFrenetPaths( - const sampler_common::State & initial_state, const double base_length, - const sampler_common::transform::Spline2D & path_spline, const Parameters & params) +std::vector generateFrenetPaths( + const autoware::sampler_common::State & initial_state, const double base_length, + const autoware::sampler_common::transform::Spline2D & path_spline, const Parameters & params) { const auto sampling_parameters = prepareSamplingParameters(initial_state, base_length, path_spline, params); - frenet_planner::FrenetState initial_frenet_state; + autoware::frenet_planner::FrenetState initial_frenet_state; initial_frenet_state.position = path_spline.frenet(initial_state.pose); const auto s = initial_frenet_state.position.s; const auto d = initial_frenet_state.position.d; @@ -121,6 +121,7 @@ std::vector generateFrenetPaths( ((1 - path_curvature * d) / (cos_yaw * cos_yaw)) * (initial_state.curvature * ((1 - path_curvature * d) / cos_yaw) - path_curvature); } - return frenet_planner::generatePaths(path_spline, initial_frenet_state, sampling_parameters); + return autoware::frenet_planner::generatePaths( + path_spline, initial_frenet_state, sampling_parameters); } -} // namespace path_sampler +} // namespace autoware::path_sampler diff --git a/planning/sampling_based_planner/path_sampler/src/prepare_inputs.cpp b/planning/sampling_based_planner/autoware_path_sampler/src/prepare_inputs.cpp similarity index 84% rename from planning/sampling_based_planner/path_sampler/src/prepare_inputs.cpp rename to planning/sampling_based_planner/autoware_path_sampler/src/prepare_inputs.cpp index fd52764950ca9..64a09087666ff 100644 --- a/planning/sampling_based_planner/path_sampler/src/prepare_inputs.cpp +++ b/planning/sampling_based_planner/autoware_path_sampler/src/prepare_inputs.cpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "path_sampler/prepare_inputs.hpp" +#include "autoware_path_sampler/prepare_inputs.hpp" -#include "frenet_planner/structures.hpp" -#include "path_sampler/utils/geometry_utils.hpp" -#include "sampler_common/structures.hpp" -#include "sampler_common/transform/spline_transform.hpp" +#include "autoware_frenet_planner/structures.hpp" +#include "autoware_path_sampler/utils/geometry_utils.hpp" +#include "autoware_sampler_common/structures.hpp" +#include "autoware_sampler_common/transform/spline_transform.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include @@ -29,22 +29,22 @@ #include #include -namespace path_sampler +namespace autoware::path_sampler { void prepareConstraints( - sampler_common::Constraints & constraints, const PredictedObjects & predicted_objects, + autoware::sampler_common::Constraints & constraints, const PredictedObjects & predicted_objects, const std::vector & left_bound, const std::vector & right_bound) { - constraints.obstacle_polygons = sampler_common::MultiPolygon2d(); + 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(tier4_autoware_utils::toPolygon2d(o)); constraints.dynamic_obstacles = {}; // TODO(Maxime): not implemented // TODO(Maxime): directly use lines instead of polygon - sampler_common::Polygon2d drivable_area_polygon; + autoware::sampler_common::Polygon2d drivable_area_polygon; for (const auto & p : right_bound) drivable_area_polygon.outer().emplace_back(p.x, p.y); for (auto it = left_bound.rbegin(); it != left_bound.rend(); ++it) drivable_area_polygon.outer().emplace_back(it->x, it->y); @@ -52,9 +52,9 @@ void prepareConstraints( constraints.drivable_polygons = {drivable_area_polygon}; } -frenet_planner::SamplingParameters prepareSamplingParameters( - const sampler_common::State & initial_state, const double base_length, - const sampler_common::transform::Spline2D & path_spline, const Parameters & params) +autoware::frenet_planner::SamplingParameters prepareSamplingParameters( + const autoware::sampler_common::State & initial_state, const double base_length, + const autoware::sampler_common::transform::Spline2D & path_spline, const Parameters & params) { // calculate target lateral positions std::vector target_lateral_positions; @@ -87,10 +87,10 @@ frenet_planner::SamplingParameters prepareSamplingParameters( } else { target_lateral_positions = params.sampling.target_lateral_positions; } - frenet_planner::SamplingParameters sampling_parameters; + autoware::frenet_planner::SamplingParameters sampling_parameters; sampling_parameters.resolution = params.sampling.resolution; const auto max_s = path_spline.lastS(); - frenet_planner::SamplingParameter p; + autoware::frenet_planner::SamplingParameter p; for (const auto target_length : params.sampling.target_lengths) { p.target_state.position.s = std::min( max_s, path_spline.frenet(initial_state.pose).s + std::max(0.0, target_length - base_length)); @@ -109,7 +109,7 @@ frenet_planner::SamplingParameters prepareSamplingParameters( return sampling_parameters; } -sampler_common::transform::Spline2D preparePathSpline( +autoware::sampler_common::transform::Spline2D preparePathSpline( const std::vector & path, const bool smooth_path) { std::vector x; @@ -151,4 +151,4 @@ sampler_common::transform::Spline2D preparePathSpline( } return {x, y}; } -} // namespace path_sampler +} // namespace autoware::path_sampler diff --git a/planning/sampling_based_planner/path_sampler/src/utils/trajectory_utils.cpp b/planning/sampling_based_planner/autoware_path_sampler/src/utils/trajectory_utils.cpp similarity index 95% rename from planning/sampling_based_planner/path_sampler/src/utils/trajectory_utils.cpp rename to planning/sampling_based_planner/autoware_path_sampler/src/utils/trajectory_utils.cpp index 07bd4f32787de..d161d60bc724d 100644 --- a/planning/sampling_based_planner/path_sampler/src/utils/trajectory_utils.cpp +++ b/planning/sampling_based_planner/autoware_path_sampler/src/utils/trajectory_utils.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "path_sampler/utils/trajectory_utils.hpp" +#include "autoware_path_sampler/utils/trajectory_utils.hpp" +#include "autoware_path_sampler/utils/geometry_utils.hpp" #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" -#include "path_sampler/utils/geometry_utils.hpp" #include "tf2/utils.h" #include "autoware_planning_msgs/msg/path_point.hpp" @@ -31,7 +31,7 @@ #include #include -namespace path_sampler +namespace autoware::path_sampler { namespace trajectory_utils { @@ -107,4 +107,4 @@ void insertStopPoint( traj_points.insert(traj_points.begin() + stop_seg_idx + 1, additional_traj_point); } } // namespace trajectory_utils -} // namespace path_sampler +} // namespace autoware::path_sampler diff --git a/planning/sampling_based_planner/sampler_common/CMakeLists.txt b/planning/sampling_based_planner/autoware_sampler_common/CMakeLists.txt similarity index 81% rename from planning/sampling_based_planner/sampler_common/CMakeLists.txt rename to planning/sampling_based_planner/autoware_sampler_common/CMakeLists.txt index 5e669a705201e..d82f38d3ec0c0 100644 --- a/planning/sampling_based_planner/sampler_common/CMakeLists.txt +++ b/planning/sampling_based_planner/autoware_sampler_common/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(sampler_common) +project(autoware_sampler_common) find_package(autoware_cmake REQUIRED) autoware_package() @@ -8,7 +8,7 @@ find_package(eigen3_cmake_module REQUIRED) find_package(Eigen3 REQUIRED) find_package(Boost REQUIRED) -ament_auto_add_library(sampler_common SHARED +ament_auto_add_library(autoware_sampler_common SHARED DIRECTORY src/ ) @@ -22,7 +22,7 @@ if(BUILD_TESTING) ) target_link_libraries(test_sampler_common - sampler_common + autoware_sampler_common ) endif() diff --git a/planning/sampling_based_planner/sampler_common/README.md b/planning/sampling_based_planner/autoware_sampler_common/README.md similarity index 100% rename from planning/sampling_based_planner/sampler_common/README.md rename to planning/sampling_based_planner/autoware_sampler_common/README.md diff --git a/planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/footprint.hpp b/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/constraints/footprint.hpp similarity index 73% rename from planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/footprint.hpp rename to planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/constraints/footprint.hpp index 061f922001a0f..52dd1a83bd99e 100644 --- a/planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/footprint.hpp +++ b/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/constraints/footprint.hpp @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SAMPLER_COMMON__CONSTRAINTS__FOOTPRINT_HPP_ -#define SAMPLER_COMMON__CONSTRAINTS__FOOTPRINT_HPP_ +#ifndef AUTOWARE_SAMPLER_COMMON__CONSTRAINTS__FOOTPRINT_HPP_ +#define AUTOWARE_SAMPLER_COMMON__CONSTRAINTS__FOOTPRINT_HPP_ -#include "sampler_common/structures.hpp" +#include "autoware_sampler_common/structures.hpp" -namespace sampler_common::constraints +namespace autoware::sampler_common::constraints { /// @brief Calculate the footprint of the given path /// @param path sequence of pose used to build the footprint /// @param constraints input constraint object containing vehicle footprint offsets /// @return the polygon footprint of the path MultiPoint2d buildFootprintPoints(const Path & path, const Constraints & constraints); -} // namespace sampler_common::constraints +} // namespace autoware::sampler_common::constraints -#endif // SAMPLER_COMMON__CONSTRAINTS__FOOTPRINT_HPP_ +#endif // AUTOWARE_SAMPLER_COMMON__CONSTRAINTS__FOOTPRINT_HPP_ diff --git a/planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/hard_constraint.hpp b/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/constraints/hard_constraint.hpp similarity index 73% rename from planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/hard_constraint.hpp rename to planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/constraints/hard_constraint.hpp index a314e83b065d7..6098e7c15d33d 100644 --- a/planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/hard_constraint.hpp +++ b/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/constraints/hard_constraint.hpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SAMPLER_COMMON__CONSTRAINTS__HARD_CONSTRAINT_HPP_ -#define SAMPLER_COMMON__CONSTRAINTS__HARD_CONSTRAINT_HPP_ +#ifndef AUTOWARE_SAMPLER_COMMON__CONSTRAINTS__HARD_CONSTRAINT_HPP_ +#define AUTOWARE_SAMPLER_COMMON__CONSTRAINTS__HARD_CONSTRAINT_HPP_ -#include "sampler_common/structures.hpp" +#include "autoware_sampler_common/structures.hpp" #include -namespace sampler_common::constraints +namespace autoware::sampler_common::constraints { /// @brief Check if the path satisfies the hard constraints MultiPoint2d checkHardConstraints(Path & path, const Constraints & constraints); @@ -27,6 +27,6 @@ bool has_collision( const double min_distance = 0.0); bool satisfyMinMax(const std::vector & values, const double min, const double max); -} // namespace sampler_common::constraints +} // namespace autoware::sampler_common::constraints -#endif // SAMPLER_COMMON__CONSTRAINTS__HARD_CONSTRAINT_HPP_ +#endif // AUTOWARE_SAMPLER_COMMON__CONSTRAINTS__HARD_CONSTRAINT_HPP_ diff --git a/planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/map_constraints.hpp b/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/constraints/map_constraints.hpp similarity index 80% rename from planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/map_constraints.hpp rename to planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/constraints/map_constraints.hpp index ed04d8104a904..7867efa1fa2db 100644 --- a/planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/map_constraints.hpp +++ b/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/constraints/map_constraints.hpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SAMPLER_COMMON__CONSTRAINTS__MAP_CONSTRAINTS_HPP_ -#define SAMPLER_COMMON__CONSTRAINTS__MAP_CONSTRAINTS_HPP_ +#ifndef AUTOWARE_SAMPLER_COMMON__CONSTRAINTS__MAP_CONSTRAINTS_HPP_ +#define AUTOWARE_SAMPLER_COMMON__CONSTRAINTS__MAP_CONSTRAINTS_HPP_ -#include "sampler_common/structures.hpp" +#include "autoware_sampler_common/structures.hpp" #include #include -namespace sampler_common::constraints +namespace autoware::sampler_common::constraints { struct MapConstraints { @@ -55,6 +55,6 @@ struct MapConstraints MultiPolygon2d drivable_polygons; std::vector polygon_costs; }; -} // namespace sampler_common::constraints +} // namespace autoware::sampler_common::constraints -#endif // SAMPLER_COMMON__CONSTRAINTS__MAP_CONSTRAINTS_HPP_ +#endif // AUTOWARE_SAMPLER_COMMON__CONSTRAINTS__MAP_CONSTRAINTS_HPP_ diff --git a/planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/soft_constraint.hpp b/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/constraints/soft_constraint.hpp similarity index 74% rename from planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/soft_constraint.hpp rename to planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/constraints/soft_constraint.hpp index 9fdb9fe137e49..290b6b6674e21 100644 --- a/planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/soft_constraint.hpp +++ b/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/constraints/soft_constraint.hpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SAMPLER_COMMON__CONSTRAINTS__SOFT_CONSTRAINT_HPP_ -#define SAMPLER_COMMON__CONSTRAINTS__SOFT_CONSTRAINT_HPP_ +#ifndef AUTOWARE_SAMPLER_COMMON__CONSTRAINTS__SOFT_CONSTRAINT_HPP_ +#define AUTOWARE_SAMPLER_COMMON__CONSTRAINTS__SOFT_CONSTRAINT_HPP_ -#include "sampler_common/structures.hpp" -#include "sampler_common/transform/spline_transform.hpp" +#include "autoware_sampler_common/structures.hpp" +#include "autoware_sampler_common/transform/spline_transform.hpp" -namespace sampler_common::constraints +namespace autoware::sampler_common::constraints { /// @brief calculate the curvature cost of the given path void calculateCurvatureCost(Path & path, const Constraints & constraints); @@ -30,6 +30,6 @@ void calculateLateralDeviationCost( /// @brief calculate the overall cost of the given path void calculateCost( Path & path, const Constraints & constraints, const transform::Spline2D & reference); -} // namespace sampler_common::constraints +} // namespace autoware::sampler_common::constraints -#endif // SAMPLER_COMMON__CONSTRAINTS__SOFT_CONSTRAINT_HPP_ +#endif // AUTOWARE_SAMPLER_COMMON__CONSTRAINTS__SOFT_CONSTRAINT_HPP_ diff --git a/planning/sampling_based_planner/sampler_common/include/sampler_common/structures.hpp b/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/structures.hpp similarity index 98% rename from planning/sampling_based_planner/sampler_common/include/sampler_common/structures.hpp rename to planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/structures.hpp index cef791a01df44..a3ba25b6594e9 100644 --- a/planning/sampling_based_planner/sampler_common/include/sampler_common/structures.hpp +++ b/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/structures.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SAMPLER_COMMON__STRUCTURES_HPP_ -#define SAMPLER_COMMON__STRUCTURES_HPP_ +#ifndef AUTOWARE_SAMPLER_COMMON__STRUCTURES_HPP_ +#define AUTOWARE_SAMPLER_COMMON__STRUCTURES_HPP_ #include "tier4_autoware_utils/geometry/boost_geometry.hpp" @@ -36,7 +36,7 @@ #include #include -namespace sampler_common +namespace autoware::sampler_common { using tier4_autoware_utils::LinearRing2d; using tier4_autoware_utils::MultiPoint2d; @@ -367,6 +367,6 @@ struct ReusableTrajectory Configuration planning_configuration; // planning configuration at the end of the trajectory }; -} // namespace sampler_common +} // namespace autoware::sampler_common -#endif // SAMPLER_COMMON__STRUCTURES_HPP_ +#endif // AUTOWARE_SAMPLER_COMMON__STRUCTURES_HPP_ diff --git a/planning/sampling_based_planner/sampler_common/include/sampler_common/transform/spline_transform.hpp b/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/transform/spline_transform.hpp similarity index 88% rename from planning/sampling_based_planner/sampler_common/include/sampler_common/transform/spline_transform.hpp rename to planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/transform/spline_transform.hpp index ce66141832dbf..c5f78c29cb13b 100644 --- a/planning/sampling_based_planner/sampler_common/include/sampler_common/transform/spline_transform.hpp +++ b/planning/sampling_based_planner/autoware_sampler_common/include/autoware_sampler_common/transform/spline_transform.hpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SAMPLER_COMMON__TRANSFORM__SPLINE_TRANSFORM_HPP_ -#define SAMPLER_COMMON__TRANSFORM__SPLINE_TRANSFORM_HPP_ +#ifndef AUTOWARE_SAMPLER_COMMON__TRANSFORM__SPLINE_TRANSFORM_HPP_ +#define AUTOWARE_SAMPLER_COMMON__TRANSFORM__SPLINE_TRANSFORM_HPP_ -#include "sampler_common/structures.hpp" +#include "autoware_sampler_common/structures.hpp" #include -namespace sampler_common::transform +namespace autoware::sampler_common::transform { -using sampler_common::FrenetPoint; +using autoware::sampler_common::FrenetPoint; class Spline { @@ -80,6 +80,6 @@ class Spline2D static std::vector arcLength( const std::vector & x, const std::vector & y); }; -} // namespace sampler_common::transform +} // namespace autoware::sampler_common::transform -#endif // SAMPLER_COMMON__TRANSFORM__SPLINE_TRANSFORM_HPP_ +#endif // AUTOWARE_SAMPLER_COMMON__TRANSFORM__SPLINE_TRANSFORM_HPP_ diff --git a/planning/sampling_based_planner/sampler_common/package.xml b/planning/sampling_based_planner/autoware_sampler_common/package.xml similarity index 94% rename from planning/sampling_based_planner/sampler_common/package.xml rename to planning/sampling_based_planner/autoware_sampler_common/package.xml index 321ca2fd43fef..a1462131d62ad 100644 --- a/planning/sampling_based_planner/sampler_common/package.xml +++ b/planning/sampling_based_planner/autoware_sampler_common/package.xml @@ -1,6 +1,6 @@ - sampler_common + autoware_sampler_common 0.0.1 Common classes and functions for sampling based planners Maxime CLEMENT diff --git a/planning/sampling_based_planner/sampler_common/src/sampler_common/constraints/footprint.cpp b/planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/constraints/footprint.cpp similarity index 87% rename from planning/sampling_based_planner/sampler_common/src/sampler_common/constraints/footprint.cpp rename to planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/constraints/footprint.cpp index 92c8ae65267db..1aafa598142a4 100644 --- a/planning/sampling_based_planner/sampler_common/src/sampler_common/constraints/footprint.cpp +++ b/planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/constraints/footprint.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "sampler_common/constraints/footprint.hpp" +#include "autoware_sampler_common/constraints/footprint.hpp" -#include "sampler_common/structures.hpp" +#include "autoware_sampler_common/structures.hpp" #include @@ -25,7 +25,7 @@ #include #include -namespace sampler_common::constraints +namespace autoware::sampler_common::constraints { namespace @@ -50,4 +50,4 @@ MultiPoint2d buildFootprintPoints(const Path & path, const Constraints & constra } return footprint; } -} // namespace sampler_common::constraints +} // namespace autoware::sampler_common::constraints diff --git a/planning/sampling_based_planner/sampler_common/src/sampler_common/constraints/hard_constraint.cpp b/planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/constraints/hard_constraint.cpp similarity index 89% rename from planning/sampling_based_planner/sampler_common/src/sampler_common/constraints/hard_constraint.cpp rename to planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/constraints/hard_constraint.cpp index 7bb29c8837723..9901b3979259c 100644 --- a/planning/sampling_based_planner/sampler_common/src/sampler_common/constraints/hard_constraint.cpp +++ b/planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/constraints/hard_constraint.cpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "sampler_common/constraints/hard_constraint.hpp" +#include "autoware_sampler_common/constraints/hard_constraint.hpp" -#include "sampler_common/constraints/footprint.hpp" +#include "autoware_sampler_common/constraints/footprint.hpp" #include #include #include -namespace sampler_common::constraints +namespace autoware::sampler_common::constraints { bool satisfyMinMax(const std::vector & values, const double min, const double max) { @@ -56,4 +56,4 @@ MultiPoint2d checkHardConstraints(Path & path, const Constraints & constraints) } return footprint; } -} // namespace sampler_common::constraints +} // namespace autoware::sampler_common::constraints diff --git a/planning/sampling_based_planner/sampler_common/src/sampler_common/constraints/soft_constraint.cpp b/planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/constraints/soft_constraint.cpp similarity index 85% rename from planning/sampling_based_planner/sampler_common/src/sampler_common/constraints/soft_constraint.cpp rename to planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/constraints/soft_constraint.cpp index b1d390e68c49f..71dff81929553 100644 --- a/planning/sampling_based_planner/sampler_common/src/sampler_common/constraints/soft_constraint.cpp +++ b/planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/constraints/soft_constraint.cpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "sampler_common/constraints/soft_constraint.hpp" +#include "autoware_sampler_common/constraints/soft_constraint.hpp" -#include "sampler_common/structures.hpp" -#include "sampler_common/transform/spline_transform.hpp" +#include "autoware_sampler_common/structures.hpp" +#include "autoware_sampler_common/transform/spline_transform.hpp" #include -namespace sampler_common::constraints +namespace autoware::sampler_common::constraints { void calculateCurvatureCost(Path & path, const Constraints & constraints) { @@ -51,4 +51,4 @@ void calculateCost( calculateLengthCost(path, constraints); calculateLateralDeviationCost(path, constraints, reference); } -} // namespace sampler_common::constraints +} // namespace autoware::sampler_common::constraints diff --git a/planning/sampling_based_planner/sampler_common/src/sampler_common/transform/spline_transform.cpp b/planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/transform/spline_transform.cpp similarity index 98% rename from planning/sampling_based_planner/sampler_common/src/sampler_common/transform/spline_transform.cpp rename to planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/transform/spline_transform.cpp index cf5f1e5478fe5..ce473b1768a54 100644 --- a/planning/sampling_based_planner/sampler_common/src/sampler_common/transform/spline_transform.cpp +++ b/planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/transform/spline_transform.cpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include #include #include #include -namespace sampler_common::transform +namespace autoware::sampler_common::transform { Spline::Spline(const std::vector & base_index, const std::vector & base_value) { @@ -312,4 +312,4 @@ double Spline2D::yaw(const double s) const return std::atan2(y_vel, x_vel); } -} // namespace sampler_common::transform +} // namespace autoware::sampler_common::transform diff --git a/planning/sampling_based_planner/sampler_common/test/test_structures.cpp b/planning/sampling_based_planner/autoware_sampler_common/test/test_structures.cpp similarity index 96% rename from planning/sampling_based_planner/sampler_common/test/test_structures.cpp rename to planning/sampling_based_planner/autoware_sampler_common/test/test_structures.cpp index 006768c9325e2..77496209290c1 100644 --- a/planning/sampling_based_planner/sampler_common/test/test_structures.cpp +++ b/planning/sampling_based_planner/autoware_sampler_common/test/test_structures.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include TEST(Path, extendPath) { - using sampler_common::Path; + using autoware::sampler_common::Path; Path traj1; Path traj2; Path traj3 = traj1.extend(traj2); @@ -43,7 +43,7 @@ TEST(Path, extendPath) TEST(Trajectory, resample) { constexpr auto eps = 1e-6; - using sampler_common::Trajectory; + using autoware::sampler_common::Trajectory; Trajectory t; t.reserve(2); @@ -103,7 +103,7 @@ TEST(Trajectory, resample) TEST(Trajectory, resampleTime) { constexpr auto eps = 1e-6; - using sampler_common::Trajectory; + using autoware::sampler_common::Trajectory; Trajectory t; t.reserve(2); diff --git a/planning/sampling_based_planner/sampler_common/test/test_transform.cpp b/planning/sampling_based_planner/autoware_sampler_common/test/test_transform.cpp similarity index 85% rename from planning/sampling_based_planner/sampler_common/test/test_transform.cpp rename to planning/sampling_based_planner/autoware_sampler_common/test/test_transform.cpp index d7998d7b8879e..6c5f43e929766 100644 --- a/planning/sampling_based_planner/sampler_common/test/test_transform.cpp +++ b/planning/sampling_based_planner/autoware_sampler_common/test/test_transform.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include @@ -24,13 +24,13 @@ constexpr auto TOL = 1E-6; // 1µm tolerance TEST(splineTransform, makeSpline2D) { - sampler_common::transform::Spline2D spline1({0.0, 1.0, 2.0}, {0.0, 1.0, 2.0}); - sampler_common::transform::Spline2D spline2({-10.0, 5.0, -2.0}, {99.0, 3.0, -20.0}); + autoware::sampler_common::transform::Spline2D spline1({0.0, 1.0, 2.0}, {0.0, 1.0, 2.0}); + autoware::sampler_common::transform::Spline2D spline2({-10.0, 5.0, -2.0}, {99.0, 3.0, -20.0}); } TEST(splineTransform, toFrenet) { - sampler_common::transform::Spline2D spline({0.0, 1.0, 2.0}, {0.0, 0.0, 0.0}); + autoware::sampler_common::transform::Spline2D spline({0.0, 1.0, 2.0}, {0.0, 0.0, 0.0}); auto frenet = spline.frenet({0.0, 0.0}); EXPECT_NEAR(frenet.s, 0.0, TOL); EXPECT_NEAR(frenet.d, 0.0, TOL); @@ -56,7 +56,7 @@ TEST(splineTransform, toFrenet) EXPECT_NEAR(frenet.s, 1.0, TOL); EXPECT_NEAR(frenet.d, -1.0, TOL); // EDGE CASE 90 deg angle - sampler_common::transform::Spline2D spline2({0.0, 1.0, 2.0}, {0.0, 1.0, 0.0}); + autoware::sampler_common::transform::Spline2D spline2({0.0, 1.0, 2.0}, {0.0, 1.0, 0.0}); frenet = spline2.frenet({1.0, 2.0}); EXPECT_NEAR(frenet.s, 1.0, TOL); EXPECT_NEAR(frenet.d, 1.0, TOL); @@ -64,7 +64,7 @@ TEST(splineTransform, toFrenet) TEST(splineTransform, toCartesian) { - sampler_common::transform::Spline2D spline({0.0, 1.0, 2.0}, {0.0, 0.0, 0.0}); + autoware::sampler_common::transform::Spline2D spline({0.0, 1.0, 2.0}, {0.0, 0.0, 0.0}); auto cart = spline.cartesian({1.0, 0.0}); EXPECT_NEAR(cart.x(), 1.0, TOL); EXPECT_NEAR(cart.y(), 0.0, TOL); @@ -85,7 +85,7 @@ TEST(splineTransform, benchFrenet) auto y = 0.0; std::generate(xs.begin(), xs.end(), [&]() { return ++x; }); std::generate(ys.begin(), ys.end(), [&]() { return ++y; }); - sampler_common::transform::Spline2D spline(xs, ys); + autoware::sampler_common::transform::Spline2D spline(xs, ys); auto points_distribution = std::uniform_real_distribution(0.0, static_cast(size)); constexpr auto nb_iter = 1e3; for (auto iter = 0; iter < nb_iter; ++iter) { diff --git a/planning/sampling_based_planner/path_sampler/include/path_sampler/path_generation.hpp b/planning/sampling_based_planner/path_sampler/include/path_sampler/path_generation.hpp deleted file mode 100644 index 448400236c9f8..0000000000000 --- a/planning/sampling_based_planner/path_sampler/include/path_sampler/path_generation.hpp +++ /dev/null @@ -1,52 +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 PATH_SAMPLER__PATH_GENERATION_HPP_ -#define PATH_SAMPLER__PATH_GENERATION_HPP_ - -#include "bezier_sampler/bezier_sampling.hpp" -#include "frenet_planner/structures.hpp" -#include "path_sampler/parameters.hpp" -#include "sampler_common/constraints/hard_constraint.hpp" -#include "sampler_common/structures.hpp" -#include "sampler_common/transform/spline_transform.hpp" - -#include - -#include - -namespace path_sampler -{ -/** - * @brief generate candidate paths for the given problem inputs - * @param [in] initial_state initial ego state - * @param [in] path_spline spline of the reference path - * @param [in] base_length base length of the reuse path (= 0.0 if not reusing a previous path) - * @param [in] params parameters - * @return candidate paths - */ -std::vector generateCandidatePaths( - const sampler_common::State & initial_state, - const sampler_common::transform::Spline2D & path_spline, const double base_length, - const Parameters & params); - -std::vector generateBezierPaths( - const sampler_common::State & initial_state, const double base_length, - const sampler_common::transform::Spline2D & path_spline, const Parameters & params); -std::vector generateFrenetPaths( - const sampler_common::State & initial_state, const double base_length, - const sampler_common::transform::Spline2D & path_spline, const Parameters & params); -} // namespace path_sampler - -#endif // PATH_SAMPLER__PATH_GENERATION_HPP_ From e24f48da29744f3e6bae5acd9286e9429c690026 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Fri, 7 Jun 2024 04:51:30 +0000 Subject: [PATCH 05/65] chore: update CODEOWNERS (#7165) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/CODEOWNERS | 27 +++++++++++++++------------ 1 file changed, 15 insertions(+), 12 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 603ddac6802a6..36b1af9887ed9 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -1,9 +1,9 @@ ### Automatically generated from package.xml ### common/autoware_ad_api_specs/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp common/autoware_auto_common/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -common/autoware_perception_rviz_plugin/** opensource@apex.ai satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taiki.tanaka@tier4.jp takeshi.miura@tier4.jp yoshi.ri@tier4.jp common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/** ahmed.ebrahim@leodrive.ai common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/** khalil@leodrive.ai +common/autoware_perception_rviz_plugin/** opensource@apex.ai satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taiki.tanaka@tier4.jp takeshi.miura@tier4.jp yoshi.ri@tier4.jp common/autoware_point_types/** taichi.higashide@tier4.jp common/autoware_testing/** adam.dabrowski@robotec.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp @@ -144,21 +144,26 @@ perception/traffic_light_map_based_detector/** shunsuke.miura@tier4.jp tao.zhong perception/traffic_light_multi_camera_fusion/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/traffic_light_occlusion_predictor/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/traffic_light_visualization/** tao.zhong@tier4.jp yukihiro.saito@tier4.jp +planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp planning/autoware_behavior_path_external_request_lane_change_module/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +planning/autoware_behavior_path_planner_common/** daniel.sanchez@tier4.jp fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +planning/autoware_behavior_path_static_obstacle_avoidance_module/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/autoware_behavior_velocity_planner/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/autoware_behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/autoware_behavior_velocity_template_module/** daniel.sanchez@tier4.jp planning/autoware_behavior_velocity_virtual_traffic_light_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/autoware_behavior_velocity_walkway_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp +planning/autoware_external_velocity_limit_selector/** satoshi.ota@tier4.jp shinnosuke.hirakawa@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/autoware_path_optimizer/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/autoware_planning_test_manager/** kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp +planning/autoware_planning_topic_converter/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp planning/autoware_remaining_distance_time_calculator/** ahmed.ebrahim@leodrive.ai planning/autoware_static_centerline_generator/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp +planning/autoware_velocity_smoother/** fumiya.watanabe@tier4.jp makoto.kurihara@tier4.jp satoshi.ota@tier4.jp takamasa.horibe@tier4.jp planning/behavior_path_avoidance_by_lane_change_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp -planning/behavior_path_avoidance_module/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp -planning/behavior_path_dynamic_avoidance_module/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp planning/behavior_path_goal_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_path_lane_change_module/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_planner/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp -planning/autoware_behavior_path_planner_common/** daniel.sanchez@tier4.jp fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_sampling_planner_module/** daniel.sanchez@tier4.jp maxime.clement@tier4.jp planning/autoware_behavior_path_side_shift_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_path_start_planner_module/** 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 @@ -172,24 +177,22 @@ planning/behavior_velocity_no_stopping_area_module/** kosuke.takeuchi@tier4.jp s planning/behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_out_of_lane_module/** maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner_common/** fumiya.watanabe@tier4.jp isamu.takagi@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -planning/autoware_behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_stop_line_module/** fumiya.watanabe@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp zhe.shen@tier4.jp planning/behavior_velocity_traffic_light_module/** mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/costmap_generator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp -planning/autoware_external_velocity_limit_selector/** satoshi.ota@tier4.jp shinnosuke.hirakawa@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/freespace_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/freespace_planning_algorithms/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/mission_planner/** isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp ryohsuke.mitsudome@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp -planning/motion_velocity_smoother/** fumiya.watanabe@tier4.jp makoto.kurihara@tier4.jp satoshi.ota@tier4.jp takamasa.horibe@tier4.jp +planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/** maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp +planning/motion_velocity_planner/autoware_motion_velocity_planner_common/** maxime.clement@tier4.jp +planning/motion_velocity_planner/autoware_motion_velocity_planner_node/** maxime.clement@tier4.jp planning/objects_of_interest_marker_interface/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp zulfaqar.azmi@tier4.jp -planning/obstacle_avoidance_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/obstacle_cruise_planner/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp planning/obstacle_stop_planner/** berkay@leodrive.ai bnk@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp planning/obstacle_velocity_limiter/** maxime.clement@tier4.jp planning/path_smoother/** maxime.clement@tier4.jp takayuki.murooka@tier4.jp planning/planning_test_utils/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp zulfaqar.azmi@tier4.jp -planning/autoware_planning_topic_converter/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp planning/planning_validator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp planning/route_handler/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp zulfaqar.azmi@tier4.jp planning/rtc_interface/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp taiki.tanaka@tier4.jp @@ -199,13 +202,13 @@ planning/sampling_based_planner/autoware_frenet_planner/** maxime.clement@tier4. planning/sampling_based_planner/autoware_path_sampler/** maxime.clement@tier4.jp planning/sampling_based_planner/autoware_sampler_common/** maxime.clement@tier4.jp planning/scenario_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -planning/autoware_surround_obstacle_checker/** satoshi.ota@tier4.jp +planning/autoware_surround_obstacle_checker/** go.sakayori@tier4.jp satoshi.ota@tier4.jp sensing/gnss_poser/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/image_diagnostics/** dai.nguyen@tier4.jp yoshi.ri@tier4.jp sensing/image_transport_decompressor/** kenzo.lobos@tier4.jp yukihiro.saito@tier4.jp sensing/imu_corrector/** koji.minoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/livox/livox_tag_filter/** kenzo.lobos@tier4.jp ryohsuke.mitsudome@tier4.jp -sensing/pointcloud_preprocessor/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp kenzo.lobos@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp yihsiang.fang@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp +sensing/pointcloud_preprocessor/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp david.wong@tier4.jp kenzo.lobos@tier4.jp kyoichi.sugahara@tier4.jp melike@leodrive.ai shunsuke.miura@tier4.jp yihsiang.fang@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp sensing/radar_scan_to_pointcloud2/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp sensing/radar_static_pointcloud_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp sensing/radar_threshold_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp @@ -240,9 +243,9 @@ system/topic_state_monitor/** ryohsuke.mitsudome@tier4.jp system/velodyne_monitor/** fumihito.ito@tier4.jp tools/reaction_analyzer/** berkay@leodrive.ai vehicle/accel_brake_map_calibrator/** taiki.tanaka@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp +vehicle/autoware_steer_offset_estimator/** taiki.tanaka@tier4.jp vehicle/external_cmd_converter/** takamasa.horibe@tier4.jp vehicle/raw_vehicle_cmd_converter/** makoto.kurihara@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp -vehicle/autoware_steer_offset_estimator/** taiki.tanaka@tier4.jp vehicle/vehicle_info_util/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp ### Copied from .github/CODEOWNERS-manual ### From e752cadf2ac200ef9f927f28336ce8e88cd4eb97 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 7 Jun 2024 14:22:15 +0900 Subject: [PATCH 06/65] refactor(behavior velocity intersection)!: prefix package and namespace with autoware_ (#7315) Signed-off-by: Mamoru Sobue --- planning/.pages | 2 +- .../CMakeLists.txt | 2 +- .../README.md | 0 .../config/intersection.param.yaml | 0 .../docs/data-structure.drawio.svg | 0 .../intersection-attention-ll-rr.drawio.svg | 0 .../intersection-attention-lr-rl.drawio.svg | 0 ...intersection-attention-straight.drawio.svg | 0 .../docs/intersection-attention.drawio.svg | 0 .../docs/intersection-stoplines.drawio.svg | 0 .../docs/intersection-topology.drawio.svg | 0 .../docs/merge_from_private.png | Bin .../docs/occlusion-with-tl.drawio.svg | 0 .../docs/occlusion-without-tl.drawio.svg | 0 .../docs/occlusion-wo-tl-creeping.png | Bin .../docs/occlusion_grid.drawio.svg | 0 .../docs/pass-judge-line.drawio.svg | 0 .../docs/signal-phase-group.drawio.svg | 0 .../docs/static-occlusion-timeout.png | Bin .../docs/stuck-vehicle.drawio.svg | 0 ...traffic-light-specific-behavior.drawio.svg | 0 .../docs/ttc.gif | Bin .../docs/ugly-intersection.drawio.svg | 0 .../docs/upstream-velocity.drawio.svg | 0 .../docs/yield-stuck.drawio.svg | 0 .../package.xml | 4 +- .../plugins.xml | 4 + .../scripts/ttc.py | 0 .../src/debug.cpp | 0 .../src/decision_result.cpp | 4 +- .../src/decision_result.hpp | 4 +- .../src/interpolated_path_info.hpp | 4 +- .../src/intersection_lanelets.cpp | 4 +- .../src/intersection_lanelets.hpp | 4 +- .../src/intersection_stoplines.hpp | 4 +- .../src/manager.cpp | 0 .../src/manager.hpp | 0 .../src/object_manager.cpp | 18 +-- .../src/object_manager.hpp | 9 +- .../src/result.hpp | 4 +- .../src/scene_intersection.cpp | 138 ++++++++---------- .../src/scene_intersection.hpp | 86 +++++------ .../src/scene_intersection_collision.cpp | 79 +++++----- .../src/scene_intersection_occlusion.cpp | 4 +- .../src/scene_intersection_prepare_data.cpp | 42 +++--- .../src/scene_intersection_stuck.cpp | 21 ++- .../src/scene_merge_from_private_road.cpp | 2 +- .../src/scene_merge_from_private_road.hpp | 0 .../src/util.cpp | 9 +- .../src/util.hpp | 7 +- .../README.md | 2 +- .../package.xml | 2 +- .../test/src/test_node_interface.cpp | 4 +- .../plugins.xml | 4 - 54 files changed, 212 insertions(+), 255 deletions(-) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/CMakeLists.txt (93%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/README.md (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/config/intersection.param.yaml (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/data-structure.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/intersection-attention-ll-rr.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/intersection-attention-lr-rl.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/intersection-attention-straight.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/intersection-attention.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/intersection-stoplines.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/intersection-topology.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/merge_from_private.png (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/occlusion-with-tl.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/occlusion-without-tl.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/occlusion-wo-tl-creeping.png (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/occlusion_grid.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/pass-judge-line.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/signal-phase-group.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/static-occlusion-timeout.png (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/stuck-vehicle.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/traffic-light-specific-behavior.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/ttc.gif (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/ugly-intersection.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/upstream-velocity.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/docs/yield-stuck.drawio.svg (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/package.xml (91%) create mode 100644 planning/autoware_behavior_velocity_intersection_module/plugins.xml rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/scripts/ttc.py (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/debug.cpp (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/decision_result.cpp (96%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/decision_result.hpp (97%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/interpolated_path_info.hpp (93%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/intersection_lanelets.cpp (97%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/intersection_lanelets.hpp (98%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/intersection_stoplines.hpp (95%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/manager.cpp (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/manager.hpp (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/object_manager.cpp (95%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/object_manager.hpp (96%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/result.hpp (93%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/scene_intersection.cpp (93%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/scene_intersection.hpp (89%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/scene_intersection_collision.cpp (94%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/scene_intersection_occlusion.cpp (99%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/scene_intersection_prepare_data.cpp (96%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/scene_intersection_stuck.cpp (95%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/scene_merge_from_private_road.cpp (99%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/scene_merge_from_private_road.hpp (100%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/util.cpp (97%) rename planning/{behavior_velocity_intersection_module => autoware_behavior_velocity_intersection_module}/src/util.hpp (95%) delete mode 100644 planning/behavior_velocity_intersection_module/plugins.xml diff --git a/planning/.pages b/planning/.pages index f7acd1b5efad5..29b0f6a2cde56 100644 --- a/planning/.pages +++ b/planning/.pages @@ -25,7 +25,7 @@ nav: - 'Crosswalk': planning/behavior_velocity_crosswalk_module - 'Detection Area': planning/behavior_velocity_detection_area_module - 'Dynamic Obstacle Stop': planning/behavior_velocity_dynamic_obstacle_stop_module - - 'Intersection': planning/behavior_velocity_intersection_module + - 'Intersection': planning/autoware_behavior_velocity_intersection_module - 'No Drivable Lane': planning/behavior_velocity_no_drivable_lane_module - 'No Stopping Area': planning/behavior_velocity_no_stopping_area_module - 'Occlusion Spot': planning/behavior_velocity_occlusion_spot_module diff --git a/planning/behavior_velocity_intersection_module/CMakeLists.txt b/planning/autoware_behavior_velocity_intersection_module/CMakeLists.txt similarity index 93% rename from planning/behavior_velocity_intersection_module/CMakeLists.txt rename to planning/autoware_behavior_velocity_intersection_module/CMakeLists.txt index c02b5a3852722..f3b31001978e9 100644 --- a/planning/behavior_velocity_intersection_module/CMakeLists.txt +++ b/planning/autoware_behavior_velocity_intersection_module/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(behavior_velocity_intersection_module) +project(autoware_behavior_velocity_intersection_module) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/planning/behavior_velocity_intersection_module/README.md b/planning/autoware_behavior_velocity_intersection_module/README.md similarity index 100% rename from planning/behavior_velocity_intersection_module/README.md rename to planning/autoware_behavior_velocity_intersection_module/README.md diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/autoware_behavior_velocity_intersection_module/config/intersection.param.yaml similarity index 100% rename from planning/behavior_velocity_intersection_module/config/intersection.param.yaml rename to planning/autoware_behavior_velocity_intersection_module/config/intersection.param.yaml diff --git a/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/data-structure.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/data-structure.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/intersection-attention-ll-rr.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/intersection-attention-ll-rr.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/intersection-attention-ll-rr.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/intersection-attention-ll-rr.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/intersection-attention-lr-rl.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/intersection-attention-lr-rl.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/intersection-attention-lr-rl.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/intersection-attention-lr-rl.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/intersection-attention-straight.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/intersection-attention-straight.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/intersection-attention-straight.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/intersection-attention-straight.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/intersection-stoplines.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/intersection-stoplines.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/intersection-stoplines.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/intersection-stoplines.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/intersection-topology.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/intersection-topology.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/intersection-topology.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/intersection-topology.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/merge_from_private.png b/planning/autoware_behavior_velocity_intersection_module/docs/merge_from_private.png similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/merge_from_private.png rename to planning/autoware_behavior_velocity_intersection_module/docs/merge_from_private.png diff --git a/planning/behavior_velocity_intersection_module/docs/occlusion-with-tl.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/occlusion-with-tl.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/occlusion-with-tl.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/occlusion-with-tl.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/occlusion-wo-tl-creeping.png b/planning/autoware_behavior_velocity_intersection_module/docs/occlusion-wo-tl-creeping.png similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/occlusion-wo-tl-creeping.png rename to planning/autoware_behavior_velocity_intersection_module/docs/occlusion-wo-tl-creeping.png diff --git a/planning/behavior_velocity_intersection_module/docs/occlusion_grid.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/occlusion_grid.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/occlusion_grid.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/occlusion_grid.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/pass-judge-line.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/pass-judge-line.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/pass-judge-line.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/pass-judge-line.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/signal-phase-group.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/signal-phase-group.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/signal-phase-group.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/signal-phase-group.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/static-occlusion-timeout.png b/planning/autoware_behavior_velocity_intersection_module/docs/static-occlusion-timeout.png similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/static-occlusion-timeout.png rename to planning/autoware_behavior_velocity_intersection_module/docs/static-occlusion-timeout.png diff --git a/planning/behavior_velocity_intersection_module/docs/stuck-vehicle.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/stuck-vehicle.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/stuck-vehicle.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/stuck-vehicle.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/traffic-light-specific-behavior.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/traffic-light-specific-behavior.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/traffic-light-specific-behavior.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/traffic-light-specific-behavior.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/ttc.gif b/planning/autoware_behavior_velocity_intersection_module/docs/ttc.gif similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/ttc.gif rename to planning/autoware_behavior_velocity_intersection_module/docs/ttc.gif diff --git a/planning/behavior_velocity_intersection_module/docs/ugly-intersection.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/ugly-intersection.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/ugly-intersection.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/ugly-intersection.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/upstream-velocity.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/upstream-velocity.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/upstream-velocity.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/upstream-velocity.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/docs/yield-stuck.drawio.svg b/planning/autoware_behavior_velocity_intersection_module/docs/yield-stuck.drawio.svg similarity index 100% rename from planning/behavior_velocity_intersection_module/docs/yield-stuck.drawio.svg rename to planning/autoware_behavior_velocity_intersection_module/docs/yield-stuck.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/package.xml b/planning/autoware_behavior_velocity_intersection_module/package.xml similarity index 91% rename from planning/behavior_velocity_intersection_module/package.xml rename to planning/autoware_behavior_velocity_intersection_module/package.xml index 3694a395b3a53..204a267594c03 100644 --- a/planning/behavior_velocity_intersection_module/package.xml +++ b/planning/autoware_behavior_velocity_intersection_module/package.xml @@ -1,9 +1,9 @@ - behavior_velocity_intersection_module + autoware_behavior_velocity_intersection_module 0.1.0 - The behavior_velocity_intersection_module package + The autoware_behavior_velocity_intersection_module package Mamoru Sobue Takayuki Murooka diff --git a/planning/autoware_behavior_velocity_intersection_module/plugins.xml b/planning/autoware_behavior_velocity_intersection_module/plugins.xml new file mode 100644 index 0000000000000..d30fbb46e050e --- /dev/null +++ b/planning/autoware_behavior_velocity_intersection_module/plugins.xml @@ -0,0 +1,4 @@ + + + + diff --git a/planning/behavior_velocity_intersection_module/scripts/ttc.py b/planning/autoware_behavior_velocity_intersection_module/scripts/ttc.py similarity index 100% rename from planning/behavior_velocity_intersection_module/scripts/ttc.py rename to planning/autoware_behavior_velocity_intersection_module/scripts/ttc.py diff --git a/planning/behavior_velocity_intersection_module/src/debug.cpp b/planning/autoware_behavior_velocity_intersection_module/src/debug.cpp similarity index 100% rename from planning/behavior_velocity_intersection_module/src/debug.cpp rename to planning/autoware_behavior_velocity_intersection_module/src/debug.cpp diff --git a/planning/behavior_velocity_intersection_module/src/decision_result.cpp b/planning/autoware_behavior_velocity_intersection_module/src/decision_result.cpp similarity index 96% rename from planning/behavior_velocity_intersection_module/src/decision_result.cpp rename to planning/autoware_behavior_velocity_intersection_module/src/decision_result.cpp index 7ed896d1b4b55..0dc0e3aab4b87 100644 --- a/planning/behavior_velocity_intersection_module/src/decision_result.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/decision_result.cpp @@ -14,7 +14,7 @@ #include "decision_result.hpp" -namespace behavior_velocity_planner::intersection +namespace behavior_velocity_planner { std::string formatDecisionResult(const DecisionResult & decision_result) { @@ -65,4 +65,4 @@ std::string formatDecisionResult(const DecisionResult & decision_result) return ""; } -} // namespace behavior_velocity_planner::intersection +} // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_intersection_module/src/decision_result.hpp b/planning/autoware_behavior_velocity_intersection_module/src/decision_result.hpp similarity index 97% rename from planning/behavior_velocity_intersection_module/src/decision_result.hpp rename to planning/autoware_behavior_velocity_intersection_module/src/decision_result.hpp index 5f642db3a462d..bf0b5520f7a32 100644 --- a/planning/behavior_velocity_intersection_module/src/decision_result.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/decision_result.hpp @@ -19,7 +19,7 @@ #include #include -namespace behavior_velocity_planner::intersection +namespace behavior_velocity_planner { /** @@ -172,6 +172,6 @@ using DecisionResult = std::variant< std::string formatDecisionResult(const DecisionResult & decision_result); -} // namespace behavior_velocity_planner::intersection +} // namespace behavior_velocity_planner #endif // DECISION_RESULT_HPP_ diff --git a/planning/behavior_velocity_intersection_module/src/interpolated_path_info.hpp b/planning/autoware_behavior_velocity_intersection_module/src/interpolated_path_info.hpp similarity index 93% rename from planning/behavior_velocity_intersection_module/src/interpolated_path_info.hpp rename to planning/autoware_behavior_velocity_intersection_module/src/interpolated_path_info.hpp index b6ae84aa8488b..c855164e24d5b 100644 --- a/planning/behavior_velocity_intersection_module/src/interpolated_path_info.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/interpolated_path_info.hpp @@ -23,7 +23,7 @@ #include #include -namespace behavior_velocity_planner::intersection +namespace behavior_velocity_planner { /** @@ -43,6 +43,6 @@ struct InterpolatedPathInfo std::optional> lane_id_interval{std::nullopt}; }; -} // namespace behavior_velocity_planner::intersection +} // namespace behavior_velocity_planner #endif // INTERPOLATED_PATH_INFO_HPP_ diff --git a/planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp b/planning/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.cpp similarity index 97% rename from planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp rename to planning/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.cpp index 555ea424dfef0..bf833ee07c155 100644 --- a/planning/behavior_velocity_intersection_module/src/intersection_lanelets.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.cpp @@ -21,7 +21,7 @@ #include -namespace behavior_velocity_planner::intersection +namespace behavior_velocity_planner { void IntersectionLanelets::update( @@ -79,4 +79,4 @@ void IntersectionLanelets::update( } } } -} // namespace behavior_velocity_planner::intersection +} // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_intersection_module/src/intersection_lanelets.hpp b/planning/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.hpp similarity index 98% rename from planning/behavior_velocity_intersection_module/src/intersection_lanelets.hpp rename to planning/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.hpp index 9624d375de122..3682787237d42 100644 --- a/planning/behavior_velocity_intersection_module/src/intersection_lanelets.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.hpp @@ -27,7 +27,7 @@ #include #include -namespace behavior_velocity_planner::intersection +namespace behavior_velocity_planner { /** @@ -190,6 +190,6 @@ struct PathLanelets // conflicting lanelets plus the next lane part of the // path }; -} // namespace behavior_velocity_planner::intersection +} // namespace behavior_velocity_planner #endif // INTERSECTION_LANELETS_HPP_ diff --git a/planning/behavior_velocity_intersection_module/src/intersection_stoplines.hpp b/planning/autoware_behavior_velocity_intersection_module/src/intersection_stoplines.hpp similarity index 95% rename from planning/behavior_velocity_intersection_module/src/intersection_stoplines.hpp rename to planning/autoware_behavior_velocity_intersection_module/src/intersection_stoplines.hpp index 99d79d4468b38..85876ffc98380 100644 --- a/planning/behavior_velocity_intersection_module/src/intersection_stoplines.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/intersection_stoplines.hpp @@ -17,7 +17,7 @@ #include -namespace behavior_velocity_planner::intersection +namespace behavior_velocity_planner { /** @@ -72,6 +72,6 @@ struct IntersectionStopLines */ size_t occlusion_wo_tl_pass_judge_line{0}; }; -} // namespace behavior_velocity_planner::intersection +} // namespace behavior_velocity_planner #endif // INTERSECTION_STOPLINES_HPP_ diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/autoware_behavior_velocity_intersection_module/src/manager.cpp similarity index 100% rename from planning/behavior_velocity_intersection_module/src/manager.cpp rename to planning/autoware_behavior_velocity_intersection_module/src/manager.cpp diff --git a/planning/behavior_velocity_intersection_module/src/manager.hpp b/planning/autoware_behavior_velocity_intersection_module/src/manager.hpp similarity index 100% rename from planning/behavior_velocity_intersection_module/src/manager.hpp rename to planning/autoware_behavior_velocity_intersection_module/src/manager.hpp diff --git a/planning/behavior_velocity_intersection_module/src/object_manager.cpp b/planning/autoware_behavior_velocity_intersection_module/src/object_manager.cpp similarity index 95% rename from planning/behavior_velocity_intersection_module/src/object_manager.cpp rename to planning/autoware_behavior_velocity_intersection_module/src/object_manager.cpp index d2c905673cee9..8ca860e23c111 100644 --- a/planning/behavior_velocity_intersection_module/src/object_manager.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/object_manager.cpp @@ -64,7 +64,7 @@ tier4_autoware_utils::Polygon2d createOneStepPolygon( } // namespace -namespace behavior_velocity_planner::intersection +namespace behavior_velocity_planner { namespace bg = boost::geometry; @@ -201,7 +201,7 @@ std::shared_ptr ObjectInfoManager::registerObject( const bool belong_intersection_area, const bool is_parked_vehicle) { if (objects_info_.count(uuid) == 0) { - auto object = std::make_shared(uuid); + auto object = std::make_shared(uuid); objects_info_[uuid] = object; } auto object = objects_info_[uuid]; @@ -219,7 +219,7 @@ std::shared_ptr ObjectInfoManager::registerObject( void ObjectInfoManager::registerExistingObject( const unique_identifier_msgs::msg::UUID & uuid, const bool belong_attention_area, const bool belong_intersection_area, const bool is_parked_vehicle, - std::shared_ptr object) + std::shared_ptr object) { objects_info_[uuid] = object; if (belong_attention_area) { @@ -249,7 +249,7 @@ std::vector> ObjectInfoManager::allObjects() const return all_objects; } -std::optional findPassageInterval( +std::optional findPassageInterval( const autoware_perception_msgs::msg::PredictedPath & predicted_path, const autoware_perception_msgs::msg::Shape & shape, const lanelet::BasicPolygon2d & ego_lane_poly, const std::optional & first_attention_lane_opt, @@ -284,25 +284,25 @@ std::optional findPassageInterval( if (lanelet::geometry::inside( first_attention_lane_opt.value(), lanelet::BasicPoint2d(first_itr->position.x, first_itr->position.y))) { - return intersection::CollisionInterval::LanePosition::FIRST; + return CollisionInterval::LanePosition::FIRST; } } if (second_attention_lane_opt) { if (lanelet::geometry::inside( second_attention_lane_opt.value(), lanelet::BasicPoint2d(first_itr->position.x, first_itr->position.y))) { - return intersection::CollisionInterval::LanePosition::SECOND; + return CollisionInterval::LanePosition::SECOND; } } - return intersection::CollisionInterval::LanePosition::ELSE; + return CollisionInterval::LanePosition::ELSE; }(); std::vector path; for (const auto & pose : predicted_path.path) { path.push_back(pose); } - return intersection::CollisionInterval{ + return CollisionInterval{ lane_position, path, {enter_idx, exit_idx}, {object_enter_time, object_exit_time}}; } -} // namespace behavior_velocity_planner::intersection +} // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_intersection_module/src/object_manager.hpp b/planning/autoware_behavior_velocity_intersection_module/src/object_manager.hpp similarity index 96% rename from planning/behavior_velocity_intersection_module/src/object_manager.hpp rename to planning/autoware_behavior_velocity_intersection_module/src/object_manager.hpp index 180496bd6b18d..3d1113656c3e3 100644 --- a/planning/behavior_velocity_intersection_module/src/object_manager.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/object_manager.hpp @@ -52,7 +52,7 @@ struct hash }; } // namespace std -namespace behavior_velocity_planner::intersection +namespace behavior_velocity_planner { /** @@ -234,8 +234,7 @@ class ObjectInfoManager void registerExistingObject( const unique_identifier_msgs::msg::UUID & uuid, const bool belong_attention_area, - const bool belong_intersection_area, const bool is_parked, - std::shared_ptr object); + const bool belong_intersection_area, const bool is_parked, std::shared_ptr object); void clearObjects(); @@ -282,12 +281,12 @@ class ObjectInfoManager /** * @brief return the CollisionInterval struct if the predicted path collides ego path geometrically */ -std::optional findPassageInterval( +std::optional findPassageInterval( const autoware_perception_msgs::msg::PredictedPath & predicted_path, const autoware_perception_msgs::msg::Shape & shape, const lanelet::BasicPolygon2d & ego_lane_poly, const std::optional & first_attention_lane_opt, const std::optional & second_attention_lane_opt); -} // namespace behavior_velocity_planner::intersection +} // namespace behavior_velocity_planner #endif // OBJECT_MANAGER_HPP_ diff --git a/planning/behavior_velocity_intersection_module/src/result.hpp b/planning/autoware_behavior_velocity_intersection_module/src/result.hpp similarity index 93% rename from planning/behavior_velocity_intersection_module/src/result.hpp rename to planning/autoware_behavior_velocity_intersection_module/src/result.hpp index 5d82183cee2fb..da89920e59a85 100644 --- a/planning/behavior_velocity_intersection_module/src/result.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/result.hpp @@ -18,7 +18,7 @@ #include #include -namespace behavior_velocity_planner::intersection +namespace behavior_velocity_planner { template @@ -48,6 +48,6 @@ Result make_err(Args &&... args) return Result(Error{std::forward(args)...}); } -} // namespace behavior_velocity_planner::intersection +} // namespace behavior_velocity_planner #endif // RESULT_HPP_ diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp similarity index 93% rename from planning/behavior_velocity_intersection_module/src/scene_intersection.cpp rename to planning/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp index c27483ea1fa51..8e50c140894e7 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -42,9 +42,6 @@ namespace behavior_velocity_planner { namespace bg = boost::geometry; -using intersection::make_err; -using intersection::make_ok; -using intersection::Result; using motion_utils::VelocityFactorInterface; IntersectionModule::IntersectionModule( @@ -105,8 +102,8 @@ bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason * prev_decision_result_ = decision_result; { - const std::string decision_type = "intersection" + std::to_string(module_id_) + " : " + - intersection::formatDecisionResult(decision_result); + const std::string decision_type = + "intersection" + std::to_string(module_id_) + " : " + formatDecisionResult(decision_result); internal_debug_data_.decision_type = decision_type; } @@ -147,7 +144,7 @@ static std::string formatOcclusionType(const IntersectionModule::OcclusionType & return "RTCOccluded"; } -intersection::DecisionResult IntersectionModule::modifyPathVelocityDetail( +DecisionResult IntersectionModule::modifyPathVelocityDetail( PathWithLaneId * path, [[maybe_unused]] StopReason * stop_reason) { const auto prepare_data = prepareIntersectionData(path); @@ -187,18 +184,18 @@ intersection::DecisionResult IntersectionModule::modifyPathVelocityDetail( // ego path has just entered the entry of this intersection // ========================================================================================== if (!intersection_lanelets.first_attention_area()) { - return intersection::InternalError{"attention area is empty"}; + return InternalError{"attention area is empty"}; } const auto first_attention_area = intersection_lanelets.first_attention_area().value(); const auto default_stopline_idx_opt = intersection_stoplines.default_stopline; if (!default_stopline_idx_opt) { - return intersection::InternalError{"default stop line is null"}; + return InternalError{"default stop line is null"}; } const auto default_stopline_idx = default_stopline_idx_opt.value(); const auto first_attention_stopline_idx_opt = intersection_stoplines.first_attention_stopline; const auto occlusion_peeking_stopline_idx_opt = intersection_stoplines.occlusion_peeking_stopline; if (!first_attention_stopline_idx_opt || !occlusion_peeking_stopline_idx_opt) { - return intersection::InternalError{"occlusion stop line is null"}; + return InternalError{"occlusion stop line is null"}; } const auto first_attention_stopline_idx = first_attention_stopline_idx_opt.value(); const auto occlusion_stopline_idx = occlusion_peeking_stopline_idx_opt.value(); @@ -275,9 +272,9 @@ intersection::DecisionResult IntersectionModule::modifyPathVelocityDetail( const auto closest_idx = intersection_stoplines.closest_idx; const std::string evasive_diag = generateEgoRiskEvasiveDiagnosis( *path, closest_idx, time_distance_array, too_late_detect_objects, misjudge_objects); - return intersection::OverPassJudge{safety_diag, evasive_diag}; + return OverPassJudge{safety_diag, evasive_diag}; } - return intersection::OverPassJudge{ + return OverPassJudge{ "no collision is detected", "ego can safely pass the intersection at this rate"}; } @@ -288,8 +285,7 @@ intersection::DecisionResult IntersectionModule::modifyPathVelocityDetail( // ========================================================================================== std::string safety_report = safety_diag; if (const bool collision_on_1st_attention_lane = - has_collision && - (collision_position == intersection::CollisionInterval::LanePosition::FIRST); + has_collision && (collision_position == CollisionInterval::LanePosition::FIRST); is_over_1st_pass_judge_line && is_over_2nd_pass_judge_line.has_value() && !is_over_2nd_pass_judge_line.value() && collision_on_1st_attention_lane) { safety_report += @@ -329,19 +325,18 @@ intersection::DecisionResult IntersectionModule::modifyPathVelocityDetail( collision_state_machine_.getState() == StateMachine::State::STOP; if (is_prioritized) { - return intersection::FullyPrioritized{ + return FullyPrioritized{ has_collision_with_margin, closest_idx, collision_stopline_idx, occlusion_stopline_idx, safety_report}; } // Safe if (!is_occlusion_state && !has_collision_with_margin) { - return intersection::Safe{ - closest_idx, collision_stopline_idx, occlusion_stopline_idx, occlusion_diag}; + return Safe{closest_idx, collision_stopline_idx, occlusion_stopline_idx, occlusion_diag}; } // Only collision if (!is_occlusion_state && has_collision_with_margin) { - return intersection::NonOccludedCollisionStop{ + return NonOccludedCollisionStop{ closest_idx, collision_stopline_idx, occlusion_stopline_idx, occlusion_diag}; } // Occluded @@ -400,16 +395,16 @@ intersection::DecisionResult IntersectionModule::modifyPathVelocityDetail( const auto closest_idx = intersection_stoplines.closest_idx; const std::string evasive_diag = generateEgoRiskEvasiveDiagnosis( *path, closest_idx, time_distance_array, too_late_detect_objects, misjudge_objects); - return intersection::OverPassJudge{ + return OverPassJudge{ "already passed maximum peeking line in the absence of traffic light.\n" + safety_report, evasive_diag}; } - return intersection::OverPassJudge{ + return OverPassJudge{ "already passed maximum peeking line in the absence of traffic light safely", "no evasive action required"}; } - return intersection::OccludedAbsenceTrafficLight{ + return OccludedAbsenceTrafficLight{ is_occlusion_cleared_with_margin, has_collision_with_margin, temporal_stop_before_attention_required, @@ -439,8 +434,7 @@ intersection::DecisionResult IntersectionModule::modifyPathVelocityDetail( const bool release_static_occlusion_stuck = (static_occlusion_timeout_state_machine_.getState() == StateMachine::State::GO); if (!has_collision_with_margin && release_static_occlusion_stuck) { - return intersection::Safe{ - closest_idx, collision_stopline_idx, occlusion_stopline_idx, occlusion_diag}; + return Safe{closest_idx, collision_stopline_idx, occlusion_stopline_idx, occlusion_diag}; } // occlusion_status is either STATICALLY_OCCLUDED or DYNAMICALLY_OCCLUDED const double max_timeout = @@ -453,7 +447,7 @@ intersection::DecisionResult IntersectionModule::modifyPathVelocityDetail( occlusion_stop_state_machine_.getDuration()) : (is_static_occlusion ? std::make_optional(max_timeout) : std::nullopt); if (has_collision_with_margin) { - return intersection::OccludedCollisionStop{ + return OccludedCollisionStop{ is_occlusion_cleared_with_margin, temporal_stop_before_attention_required, closest_idx, @@ -463,7 +457,7 @@ intersection::DecisionResult IntersectionModule::modifyPathVelocityDetail( static_occlusion_timeout, occlusion_diag}; } else { - return intersection::PeekingTowardOcclusion{ + return PeekingTowardOcclusion{ is_occlusion_cleared_with_margin, temporal_stop_before_attention_required, closest_idx, @@ -478,7 +472,7 @@ intersection::DecisionResult IntersectionModule::modifyPathVelocityDetail( (planner_param_.occlusion.temporal_stop_before_attention_area || !has_traffic_light_) ? first_attention_stopline_idx : occlusion_stopline_idx; - return intersection::FirstWaitBeforeOcclusion{ + return FirstWaitBeforeOcclusion{ is_occlusion_cleared_with_margin, closest_idx, default_stopline_idx, occlusion_stopline, occlusion_diag}; } @@ -505,7 +499,7 @@ void prepareRTCByDecisionResult( template <> void prepareRTCByDecisionResult( - [[maybe_unused]] const intersection::InternalError & result, + [[maybe_unused]] const InternalError & result, [[maybe_unused]] const tier4_planning_msgs::msg::PathWithLaneId & path, [[maybe_unused]] bool * default_safety, [[maybe_unused]] double * default_distance, [[maybe_unused]] bool * occlusion_safety, [[maybe_unused]] double * occlusion_distance) @@ -515,7 +509,7 @@ void prepareRTCByDecisionResult( template <> void prepareRTCByDecisionResult( - [[maybe_unused]] const intersection::OverPassJudge & result, + [[maybe_unused]] const OverPassJudge & result, [[maybe_unused]] const tier4_planning_msgs::msg::PathWithLaneId & path, [[maybe_unused]] bool * default_safety, [[maybe_unused]] double * default_distance, [[maybe_unused]] bool * occlusion_safety, [[maybe_unused]] double * occlusion_distance) @@ -525,7 +519,7 @@ void prepareRTCByDecisionResult( template <> void prepareRTCByDecisionResult( - const intersection::StuckStop & result, const tier4_planning_msgs::msg::PathWithLaneId & path, + const StuckStop & result, const tier4_planning_msgs::msg::PathWithLaneId & path, bool * default_safety, double * default_distance, bool * occlusion_safety, double * occlusion_distance) { @@ -545,9 +539,9 @@ void prepareRTCByDecisionResult( template <> void prepareRTCByDecisionResult( - const intersection::YieldStuckStop & result, - const tier4_planning_msgs::msg::PathWithLaneId & path, bool * default_safety, - double * default_distance, bool * occlusion_safety, [[maybe_unused]] double * occlusion_distance) + const YieldStuckStop & result, const tier4_planning_msgs::msg::PathWithLaneId & path, + bool * default_safety, double * default_distance, bool * occlusion_safety, + [[maybe_unused]] double * occlusion_distance) { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "YieldStuckStop"); const auto closest_idx = result.closest_idx; @@ -560,9 +554,9 @@ void prepareRTCByDecisionResult( template <> void prepareRTCByDecisionResult( - const intersection::NonOccludedCollisionStop & result, - const tier4_planning_msgs::msg::PathWithLaneId & path, bool * default_safety, - double * default_distance, bool * occlusion_safety, double * occlusion_distance) + const NonOccludedCollisionStop & result, const tier4_planning_msgs::msg::PathWithLaneId & path, + bool * default_safety, double * default_distance, bool * occlusion_safety, + double * occlusion_distance) { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "NonOccludedCollisionStop"); const auto closest_idx = result.closest_idx; @@ -579,9 +573,9 @@ void prepareRTCByDecisionResult( template <> void prepareRTCByDecisionResult( - const intersection::FirstWaitBeforeOcclusion & result, - const tier4_planning_msgs::msg::PathWithLaneId & path, bool * default_safety, - double * default_distance, bool * occlusion_safety, double * occlusion_distance) + const FirstWaitBeforeOcclusion & result, const tier4_planning_msgs::msg::PathWithLaneId & path, + bool * default_safety, double * default_distance, bool * occlusion_safety, + double * occlusion_distance) { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "FirstWaitBeforeOcclusion"); const auto closest_idx = result.closest_idx; @@ -598,9 +592,9 @@ void prepareRTCByDecisionResult( template <> void prepareRTCByDecisionResult( - const intersection::PeekingTowardOcclusion & result, - const tier4_planning_msgs::msg::PathWithLaneId & path, bool * default_safety, - double * default_distance, bool * occlusion_safety, double * occlusion_distance) + const PeekingTowardOcclusion & result, const tier4_planning_msgs::msg::PathWithLaneId & path, + bool * default_safety, double * default_distance, bool * occlusion_safety, + double * occlusion_distance) { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "PeekingTowardOcclusion"); const auto closest_idx = result.closest_idx; @@ -617,9 +611,9 @@ void prepareRTCByDecisionResult( template <> void prepareRTCByDecisionResult( - const intersection::OccludedAbsenceTrafficLight & result, - const tier4_planning_msgs::msg::PathWithLaneId & path, bool * default_safety, - double * default_distance, bool * occlusion_safety, double * occlusion_distance) + const OccludedAbsenceTrafficLight & result, const tier4_planning_msgs::msg::PathWithLaneId & path, + bool * default_safety, double * default_distance, bool * occlusion_safety, + double * occlusion_distance) { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "OccludedAbsenceTrafficLight"); const auto closest_idx = result.closest_idx; @@ -634,9 +628,9 @@ void prepareRTCByDecisionResult( template <> void prepareRTCByDecisionResult( - const intersection::OccludedCollisionStop & result, - const tier4_planning_msgs::msg::PathWithLaneId & path, bool * default_safety, - double * default_distance, bool * occlusion_safety, double * occlusion_distance) + const OccludedCollisionStop & result, const tier4_planning_msgs::msg::PathWithLaneId & path, + bool * default_safety, double * default_distance, bool * occlusion_safety, + double * occlusion_distance) { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "OccludedCollisionStop"); const auto closest_idx = result.closest_idx; @@ -653,9 +647,8 @@ void prepareRTCByDecisionResult( template <> void prepareRTCByDecisionResult( - const intersection::Safe & result, const tier4_planning_msgs::msg::PathWithLaneId & path, - bool * default_safety, double * default_distance, bool * occlusion_safety, - double * occlusion_distance) + const Safe & result, const tier4_planning_msgs::msg::PathWithLaneId & path, bool * default_safety, + double * default_distance, bool * occlusion_safety, double * occlusion_distance) { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "Safe"); const auto closest_idx = result.closest_idx; @@ -672,9 +665,9 @@ void prepareRTCByDecisionResult( template <> void prepareRTCByDecisionResult( - const intersection::FullyPrioritized & result, - const tier4_planning_msgs::msg::PathWithLaneId & path, bool * default_safety, - double * default_distance, bool * occlusion_safety, double * occlusion_distance) + const FullyPrioritized & result, const tier4_planning_msgs::msg::PathWithLaneId & path, + bool * default_safety, double * default_distance, bool * occlusion_safety, + double * occlusion_distance) { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "FullyPrioritized"); const auto closest_idx = result.closest_idx; @@ -690,8 +683,7 @@ void prepareRTCByDecisionResult( } void IntersectionModule::prepareRTCStatus( - const intersection::DecisionResult & decision_result, - const tier4_planning_msgs::msg::PathWithLaneId & path) + const DecisionResult & decision_result, const tier4_planning_msgs::msg::PathWithLaneId & path) { bool default_safety = true; double default_distance = std::numeric_limits::lowest(); @@ -705,7 +697,7 @@ void IntersectionModule::prepareRTCStatus( setSafe(default_safety); setDistance(default_distance); occlusion_first_stop_required_ = - std::holds_alternative(decision_result); + std::holds_alternative(decision_result); } template @@ -723,7 +715,7 @@ template <> void reactRTCApprovalByDecisionResult( [[maybe_unused]] const bool rtc_default_approved, [[maybe_unused]] const bool rtc_occlusion_approved, - [[maybe_unused]] const intersection::InternalError & decision_result, + [[maybe_unused]] const InternalError & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, [[maybe_unused]] const double baselink2front, [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path, @@ -738,7 +730,7 @@ template <> void reactRTCApprovalByDecisionResult( [[maybe_unused]] const bool rtc_default_approved, [[maybe_unused]] const bool rtc_occlusion_approved, - [[maybe_unused]] const intersection::OverPassJudge & decision_result, + [[maybe_unused]] const OverPassJudge & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, [[maybe_unused]] const double baselink2front, [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path, @@ -752,7 +744,7 @@ void reactRTCApprovalByDecisionResult( template <> void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, - const intersection::StuckStop & decision_result, + const StuckStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, VelocityFactorInterface * velocity_factor, @@ -799,7 +791,7 @@ void reactRTCApprovalByDecisionResult( template <> void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, - const intersection::YieldStuckStop & decision_result, + const YieldStuckStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, VelocityFactorInterface * velocity_factor, @@ -832,7 +824,7 @@ void reactRTCApprovalByDecisionResult( template <> void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, - const intersection::NonOccludedCollisionStop & decision_result, + const NonOccludedCollisionStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, VelocityFactorInterface * velocity_factor, @@ -876,7 +868,7 @@ void reactRTCApprovalByDecisionResult( template <> void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, - const intersection::FirstWaitBeforeOcclusion & decision_result, + const FirstWaitBeforeOcclusion & decision_result, const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) @@ -927,7 +919,7 @@ void reactRTCApprovalByDecisionResult( template <> void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, - const intersection::PeekingTowardOcclusion & decision_result, + const PeekingTowardOcclusion & decision_result, const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) @@ -983,7 +975,7 @@ void reactRTCApprovalByDecisionResult( template <> void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, - const intersection::OccludedCollisionStop & decision_result, + const OccludedCollisionStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, VelocityFactorInterface * velocity_factor, @@ -1031,7 +1023,7 @@ void reactRTCApprovalByDecisionResult( template <> void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, - const intersection::OccludedAbsenceTrafficLight & decision_result, + const OccludedAbsenceTrafficLight & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, VelocityFactorInterface * velocity_factor, @@ -1084,8 +1076,7 @@ void reactRTCApprovalByDecisionResult( template <> void reactRTCApprovalByDecisionResult( - const bool rtc_default_approved, const bool rtc_occlusion_approved, - const intersection::Safe & decision_result, + const bool rtc_default_approved, const bool rtc_occlusion_approved, const Safe & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, VelocityFactorInterface * velocity_factor, @@ -1128,7 +1119,7 @@ void reactRTCApprovalByDecisionResult( template <> void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, - const intersection::FullyPrioritized & decision_result, + const FullyPrioritized & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, VelocityFactorInterface * velocity_factor, @@ -1170,8 +1161,8 @@ void reactRTCApprovalByDecisionResult( } void IntersectionModule::reactRTCApproval( - const intersection::DecisionResult & decision_result, - tier4_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason) + const DecisionResult & decision_result, tier4_planning_msgs::msg::PathWithLaneId * path, + StopReason * stop_reason) { const double baselink2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; std::visit( @@ -1293,7 +1284,7 @@ void IntersectionModule::updateTrafficSignalObservation() IntersectionModule::PassJudgeStatus IntersectionModule::isOverPassJudgeLinesStatus( const tier4_planning_msgs::msg::PathWithLaneId & path, const bool is_occlusion_state, - const intersection::IntersectionStopLines & intersection_stoplines) + const IntersectionStopLines & intersection_stoplines) { const auto & current_pose = planner_data_->current_odometry->pose; const auto closest_idx = intersection_stoplines.closest_idx; @@ -1346,12 +1337,11 @@ IntersectionModule::PassJudgeStatus IntersectionModule::isOverPassJudgeLinesStat // as "was_safe" // ========================================================================================== const bool was_safe = [&]() { - if (std::holds_alternative(prev_decision_result_)) { + if (std::holds_alternative(prev_decision_result_)) { return true; } - if (std::holds_alternative(prev_decision_result_)) { - const auto & state = - std::get(prev_decision_result_); + if (std::holds_alternative(prev_decision_result_)) { + const auto & state = std::get(prev_decision_result_); return !state.collision_detected; } return false; diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp similarity index 89% rename from planning/behavior_velocity_intersection_module/src/scene_intersection.hpp rename to planning/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp index b86fd77491f54..b1cfcdee04fa6 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -295,11 +295,9 @@ class IntersectionModule : public SceneModuleInterface BLAME_AT_SECOND_PASS_JUDGE, }; const bool collision_detected; - const intersection::CollisionInterval::LanePosition collision_position; - const std::vector>> - too_late_detect_objects; - const std::vector>> - misjudge_objects; + const CollisionInterval::LanePosition collision_position; + const std::vector>> too_late_detect_objects; + const std::vector>> misjudge_objects; }; IntersectionModule( @@ -377,7 +375,7 @@ class IntersectionModule : public SceneModuleInterface */ //! cache IntersectionLanelets struct - std::optional intersection_lanelets_{std::nullopt}; + std::optional intersection_lanelets_{std::nullopt}; //! cache discretized occlusion detection lanelets std::optional> occlusion_attention_divisions_{ @@ -400,7 +398,7 @@ class IntersectionModule : public SceneModuleInterface bool is_permanent_go_{false}; //! for checking if ego is over the pass judge lines because previously the situation was SAFE - intersection::DecisionResult prev_decision_result_{intersection::InternalError{""}}; + DecisionResult prev_decision_result_{InternalError{""}}; //! flag if ego passed the 1st_pass_judge_line while peeking. If this is true, 1st_pass_judge_line //! is treated as the same position as occlusion_peeking_stopline @@ -427,7 +425,7 @@ class IntersectionModule : public SceneModuleInterface StateMachine collision_state_machine_; //! container for storing safety status of objects on the attention area - intersection::ObjectInfoManager object_info_manager_; + ObjectInfoManager object_info_manager_; /** @} */ private: @@ -506,21 +504,20 @@ class IntersectionModule : public SceneModuleInterface /** * @brief analyze traffic_light/occupancy/objects context and return DecisionResult */ - intersection::DecisionResult modifyPathVelocityDetail( - PathWithLaneId * path, StopReason * stop_reason); + DecisionResult modifyPathVelocityDetail(PathWithLaneId * path, StopReason * stop_reason); /** * @brief set RTC value according to calculated DecisionResult */ void prepareRTCStatus( - const intersection::DecisionResult &, const tier4_planning_msgs::msg::PathWithLaneId & path); + const DecisionResult &, const tier4_planning_msgs::msg::PathWithLaneId & path); /** * @brief act based on current RTC approval */ void reactRTCApproval( - const intersection::DecisionResult & decision_result, - tier4_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason); + const DecisionResult & decision_result, tier4_planning_msgs::msg::PathWithLaneId * path, + StopReason * stop_reason); /** @}*/ private: @@ -536,9 +533,9 @@ class IntersectionModule : public SceneModuleInterface */ struct BasicData { - intersection::InterpolatedPathInfo interpolated_path_info; - intersection::IntersectionStopLines intersection_stoplines; - intersection::PathLanelets path_lanelets; + InterpolatedPathInfo interpolated_path_info; + IntersectionStopLines intersection_stoplines; + PathLanelets path_lanelets; }; /** @@ -549,31 +546,30 @@ class IntersectionModule : public SceneModuleInterface * * To simplify modifyPathVelocityDetail(), this function is used at first */ - intersection::Result prepareIntersectionData( - PathWithLaneId * path); + Result prepareIntersectionData(PathWithLaneId * path); /** * @brief find the associated stopline road marking of assigned lanelet */ std::optional getStopLineIndexFromMap( - const intersection::InterpolatedPathInfo & interpolated_path_info, + const InterpolatedPathInfo & interpolated_path_info, lanelet::ConstLanelet assigned_lanelet) const; /** * @brief generate IntersectionStopLines */ - std::optional generateIntersectionStopLines( + std::optional generateIntersectionStopLines( lanelet::ConstLanelet assigned_lanelet, const lanelet::CompoundPolygon3d & first_conflicting_area, const lanelet::ConstLanelet & first_attention_lane, const std::optional & second_attention_area_opt, - const intersection::InterpolatedPathInfo & interpolated_path_info, + const InterpolatedPathInfo & interpolated_path_info, tier4_planning_msgs::msg::PathWithLaneId * original_path) const; /** * @brief generate IntersectionLanelets */ - intersection::IntersectionLanelets generateObjectiveLanelets( + IntersectionLanelets generateObjectiveLanelets( lanelet::LaneletMapConstPtr lanelet_map_ptr, lanelet::routing::RoutingGraphPtr routing_graph_ptr, const lanelet::ConstLanelet assigned_lanelet) const; @@ -581,9 +577,9 @@ class IntersectionModule : public SceneModuleInterface /** * @brief generate PathLanelets */ - std::optional generatePathLanelets( + std::optional generatePathLanelets( const lanelet::ConstLanelets & lanelets_on_path, - const intersection::InterpolatedPathInfo & interpolated_path_info, + const InterpolatedPathInfo & interpolated_path_info, const lanelet::CompoundPolygon3d & first_conflicting_area, const std::vector & conflicting_areas, const std::optional & first_attention_area, @@ -637,10 +633,9 @@ class IntersectionModule : public SceneModuleInterface * @attention this function has access to value() of intersection_lanelets_, * intersection_lanelets.first_conflicting_lane(). They are ensured in prepareIntersectionData() */ - std::optional isStuckStatus( + std::optional isStuckStatus( const tier4_planning_msgs::msg::PathWithLaneId & path, - const intersection::IntersectionStopLines & intersection_stoplines, - const intersection::PathLanelets & path_lanelets) const; + const IntersectionStopLines & intersection_stoplines, const PathLanelets & path_lanelets) const; bool isTargetStuckVehicleType( const autoware_perception_msgs::msg::PredictedObject & object) const; @@ -651,7 +646,7 @@ class IntersectionModule : public SceneModuleInterface /** * @brief check stuck */ - bool checkStuckVehicleInIntersection(const intersection::PathLanelets & path_lanelets) const; + bool checkStuckVehicleInIntersection(const PathLanelets & path_lanelets) const; /** @} */ private: @@ -667,16 +662,16 @@ class IntersectionModule : public SceneModuleInterface * @attention this function has access to value() of intersection_lanelets_, * intersection_stoplines.default_stopline, intersection_stoplines.first_attention_stopline */ - std::optional isYieldStuckStatus( + std::optional isYieldStuckStatus( const tier4_planning_msgs::msg::PathWithLaneId & path, - const intersection::InterpolatedPathInfo & interpolated_path_info, - const intersection::IntersectionStopLines & intersection_stoplines) const; + const InterpolatedPathInfo & interpolated_path_info, + const IntersectionStopLines & intersection_stoplines) const; /** * @brief check yield stuck */ bool checkYieldStuckVehicleInIntersection( - const intersection::InterpolatedPathInfo & interpolated_path_info, + const InterpolatedPathInfo & interpolated_path_info, const lanelet::ConstLanelets & attention_lanelets) const; /** @} */ @@ -698,15 +693,14 @@ class IntersectionModule : public SceneModuleInterface bool /* reconciled occlusion disapproval */> getOcclusionStatus( const TrafficPrioritizedLevel & traffic_prioritized_level, - const intersection::InterpolatedPathInfo & interpolated_path_info); + const InterpolatedPathInfo & interpolated_path_info); /** * @brief calculate detected occlusion status(NOT | STATICALLY | DYNAMICALLY) * @attention this function has access to value() of intersection_lanelets_, * intersection_lanelets.first_attention_area(), occlusion_attention_divisions_ */ - OcclusionType detectOcclusion( - const intersection::InterpolatedPathInfo & interpolated_path_info) const; + OcclusionType detectOcclusion(const InterpolatedPathInfo & interpolated_path_info) const; /** @} */ private: @@ -726,7 +720,7 @@ class IntersectionModule : public SceneModuleInterface */ PassJudgeStatus isOverPassJudgeLinesStatus( const tier4_planning_msgs::msg::PathWithLaneId & path, const bool is_occlusion_state, - const intersection::IntersectionStopLines & intersection_stoplines); + const IntersectionStopLines & intersection_stoplines); /** @} */ private: @@ -751,7 +745,7 @@ class IntersectionModule : public SceneModuleInterface * @attention this function has access to value() of intersection_lanelets_ */ void updateObjectInfoManagerCollision( - const intersection::PathLanelets & path_lanelets, const TimeDistanceArray & time_distance_array, + const PathLanelets & path_lanelets, const TimeDistanceArray & time_distance_array, const TrafficPrioritizedLevel & traffic_prioritized_level, const bool passed_1st_judge_line_first_time, const bool passed_2nd_judge_line_first_time, tier4_debug_msgs::msg::Float64MultiArrayStamped * object_ttc_time_array); @@ -768,20 +762,18 @@ class IntersectionModule : public SceneModuleInterface * @attention this function has access to value() of * intersection_stoplines.occlusion_peeking_stopline */ - std::optional isGreenPseudoCollisionStatus( + std::optional isGreenPseudoCollisionStatus( const size_t closest_idx, const size_t collision_stopline_idx, - const intersection::IntersectionStopLines & intersection_stoplines) const; + const IntersectionStopLines & intersection_stoplines) const; /** * @brief generate the message explaining why too_late_detect_objects/misjudge_objects exist and * blame past perception fault */ std::string generateDetectionBlameDiagnosis( - const std::vector< - std::pair>> & + const std::vector>> & too_late_detect_objects, - const std::vector< - std::pair>> & + const std::vector>> & misjudge_objects) const; /** @@ -791,11 +783,9 @@ class IntersectionModule : public SceneModuleInterface std::string generateEgoRiskEvasiveDiagnosis( const tier4_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx, const TimeDistanceArray & ego_time_distance_array, - const std::vector< - std::pair>> & + const std::vector>> & too_late_detect_objects, - const std::vector< - std::pair>> & + const std::vector>> & misjudge_objects) const; /** @@ -818,7 +808,7 @@ class IntersectionModule : public SceneModuleInterface */ TimeDistanceArray calcIntersectionPassingTime( const tier4_planning_msgs::msg::PathWithLaneId & path, const bool is_prioritized, - const intersection::IntersectionStopLines & intersection_stoplines, + const IntersectionStopLines & intersection_stoplines, tier4_debug_msgs::msg::Float64MultiArrayStamped * debug_ttc_array) const; /** @} */ diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection_collision.cpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp similarity index 94% rename from planning/behavior_velocity_intersection_module/src/scene_intersection_collision.cpp rename to planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp index 131081c5e8ca0..48387bc6aa398 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection_collision.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp @@ -140,7 +140,7 @@ void IntersectionModule::updateObjectInfoManagerArea() } void IntersectionModule::updateObjectInfoManagerCollision( - const intersection::PathLanelets & path_lanelets, + const PathLanelets & path_lanelets, const IntersectionModule::TimeDistanceArray & time_distance_array, const IntersectionModule::TrafficPrioritizedLevel & traffic_prioritized_level, const bool passed_1st_judge_line_first_time, const bool passed_2nd_judge_line_first_time, @@ -243,8 +243,8 @@ void IntersectionModule::updateObjectInfoManagerCollision( // path, both will be null, which is interpreted as SAFE. if any of the path is "normal", either // of them has value, not both // ========================================================================================== - std::optional unsafe_interval{std::nullopt}; - std::optional safe_interval{std::nullopt}; + std::optional unsafe_interval{std::nullopt}; + std::optional safe_interval{std::nullopt}; std::optional> object_debug_info{std::nullopt}; for (const auto & predicted_path_ptr : sorted_predicted_paths) { @@ -256,7 +256,7 @@ void IntersectionModule::updateObjectInfoManagerCollision( } cutPredictPathWithinDuration( planner_data_->predicted_objects->header.stamp, passing_time, &predicted_path); - const auto object_passage_interval_opt = intersection::findPassageInterval( + const auto object_passage_interval_opt = findPassageInterval( predicted_path, predicted_object.shape, ego_poly, intersection_lanelets.first_attention_lane(), intersection_lanelets.second_attention_lane()); @@ -362,27 +362,25 @@ void IntersectionModule::updateObjectInfoManagerCollision( } object_info->update_safety(unsafe_interval, safe_interval, safe_under_traffic_control); if (passed_1st_judge_line_first_time) { - object_info->setDecisionAt1stPassJudgeLinePassage(intersection::CollisionKnowledge{ + object_info->setDecisionAt1stPassJudgeLinePassage(CollisionKnowledge{ clock_->now(), // stamp unsafe_interval - ? intersection::CollisionKnowledge::SafeType::UNSAFE - : (safe_under_traffic_control - ? intersection::CollisionKnowledge::SafeType::SAFE_UNDER_TRAFFIC_CONTROL - : intersection::CollisionKnowledge::SafeType::SAFE), // safe - unsafe_interval ? unsafe_interval : safe_interval, // interval + ? CollisionKnowledge::SafeType::UNSAFE + : (safe_under_traffic_control ? CollisionKnowledge::SafeType::SAFE_UNDER_TRAFFIC_CONTROL + : CollisionKnowledge::SafeType::SAFE), // safe + unsafe_interval ? unsafe_interval : safe_interval, // interval predicted_object.kinematics.initial_twist_with_covariance.twist.linear .x // observed_velocity }); } if (passed_2nd_judge_line_first_time) { - object_info->setDecisionAt2ndPassJudgeLinePassage(intersection::CollisionKnowledge{ + object_info->setDecisionAt2ndPassJudgeLinePassage(CollisionKnowledge{ clock_->now(), // stamp unsafe_interval - ? intersection::CollisionKnowledge::SafeType::UNSAFE - : (safe_under_traffic_control - ? intersection::CollisionKnowledge::SafeType::SAFE_UNDER_TRAFFIC_CONTROL - : intersection::CollisionKnowledge::SafeType::SAFE), // safe - unsafe_interval ? unsafe_interval : safe_interval, // interval + ? CollisionKnowledge::SafeType::UNSAFE + : (safe_under_traffic_control ? CollisionKnowledge::SafeType::SAFE_UNDER_TRAFFIC_CONTROL + : CollisionKnowledge::SafeType::SAFE), // safe + unsafe_interval ? unsafe_interval : safe_interval, // interval predicted_object.kinematics.initial_twist_with_covariance.twist.linear .x // observed_velocity }); @@ -415,10 +413,9 @@ void IntersectionModule::cutPredictPathWithinDuration( } } -std::optional -IntersectionModule::isGreenPseudoCollisionStatus( +std::optional IntersectionModule::isGreenPseudoCollisionStatus( const size_t closest_idx, const size_t collision_stopline_idx, - const intersection::IntersectionStopLines & intersection_stoplines) const + const IntersectionStopLines & intersection_stoplines) const { // ========================================================================================== // if there are any vehicles on the attention area when ego entered the intersection on green @@ -440,7 +437,7 @@ IntersectionModule::isGreenPseudoCollisionStatus( }); if (exist_close_vehicles) { const auto occlusion_stopline_idx = intersection_stoplines.occlusion_peeking_stopline.value(); - return intersection::NonOccludedCollisionStop{ + return NonOccludedCollisionStop{ closest_idx, collision_stopline_idx, occlusion_stopline_idx, std::string("")}; } } @@ -448,11 +445,11 @@ IntersectionModule::isGreenPseudoCollisionStatus( } std::string IntersectionModule::generateDetectionBlameDiagnosis( - const std::vector>> & + const std::vector< + std::pair>> & too_late_detect_objects, - const std::vector>> & + const std::vector< + std::pair>> & misjudge_objects) const { std::string diag; @@ -598,11 +595,11 @@ std::string IntersectionModule::generateDetectionBlameDiagnosis( std::string IntersectionModule::generateEgoRiskEvasiveDiagnosis( const tier4_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx, const IntersectionModule::TimeDistanceArray & ego_time_distance_array, - const std::vector>> & + const std::vector< + std::pair>> & too_late_detect_objects, - [[maybe_unused]] const std::vector>> & + [[maybe_unused]] const std::vector< + std::pair>> & misjudge_objects) const { static constexpr double min_vel = 1e-2; @@ -684,9 +681,8 @@ IntersectionModule::CollisionStatus IntersectionModule::detectCollision( // that case is both "too late to stop" and "too late to go" for the planner. and basically // detection side is responsible for this fault // ========================================================================================== - std::vector>> - misjudge_objects; - std::vector>> + std::vector>> misjudge_objects; + std::vector>> too_late_detect_objects; for (const auto & object_info : object_info_manager_.attentionObjects()) { if (object_info->is_safe_under_traffic_control()) { @@ -709,14 +705,14 @@ IntersectionModule::CollisionStatus IntersectionModule::detectCollision( // visualized as "misjudge" // ========================================================================================== auto * debug_container = &debug_data_.unsafe_targets.objects; - if (unsafe_info.lane_position == intersection::CollisionInterval::LanePosition::FIRST) { + if (unsafe_info.lane_position == CollisionInterval::LanePosition::FIRST) { collision_at_first_lane = true; } else { collision_at_non_first_lane = true; } if ( is_over_1st_pass_judge_line && - unsafe_info.lane_position == intersection::CollisionInterval::LanePosition::FIRST) { + unsafe_info.lane_position == CollisionInterval::LanePosition::FIRST) { const auto & decision_at_1st_pass_judge_opt = object_info->decision_at_1st_pass_judge_line_passage(); if (!decision_at_1st_pass_judge_opt) { @@ -725,9 +721,7 @@ IntersectionModule::CollisionStatus IntersectionModule::detectCollision( debug_container = &debug_data_.too_late_detect_targets.objects; } else { const auto & decision_at_1st_pass_judge = decision_at_1st_pass_judge_opt.value(); - if ( - decision_at_1st_pass_judge.safe_type != - intersection::CollisionKnowledge::SafeType::UNSAFE) { + if (decision_at_1st_pass_judge.safe_type != CollisionKnowledge::SafeType::UNSAFE) { misjudge_objects.emplace_back( CollisionStatus::BlameType::BLAME_AT_FIRST_PASS_JUDGE, object_info); debug_container = &debug_data_.misjudge_targets.objects; @@ -747,9 +741,7 @@ IntersectionModule::CollisionStatus IntersectionModule::detectCollision( debug_container = &debug_data_.too_late_detect_targets.objects; } else { const auto & decision_at_2nd_pass_judge = decision_at_2nd_pass_judge_opt.value(); - if ( - decision_at_2nd_pass_judge.safe_type != - intersection::CollisionKnowledge::SafeType::UNSAFE) { + if (decision_at_2nd_pass_judge.safe_type != CollisionKnowledge::SafeType::UNSAFE) { misjudge_objects.emplace_back( CollisionStatus::BlameType::BLAME_AT_SECOND_PASS_JUDGE, object_info); debug_container = &debug_data_.misjudge_targets.objects; @@ -763,12 +755,11 @@ IntersectionModule::CollisionStatus IntersectionModule::detectCollision( debug_container->emplace_back(object_info->predicted_object()); } if (collision_at_first_lane) { - return { - true, intersection::CollisionInterval::FIRST, too_late_detect_objects, misjudge_objects}; + return {true, CollisionInterval::FIRST, too_late_detect_objects, misjudge_objects}; } else if (collision_at_non_first_lane) { - return {true, intersection::CollisionInterval::ELSE, too_late_detect_objects, misjudge_objects}; + return {true, CollisionInterval::ELSE, too_late_detect_objects, misjudge_objects}; } - return {false, intersection::CollisionInterval::ELSE, too_late_detect_objects, misjudge_objects}; + return {false, CollisionInterval::ELSE, too_late_detect_objects, misjudge_objects}; } std::optional IntersectionModule::checkAngleForTargetLanelets( @@ -811,7 +802,7 @@ std::optional IntersectionModule::checkAngleForTargetLanelets( IntersectionModule::TimeDistanceArray IntersectionModule::calcIntersectionPassingTime( const tier4_planning_msgs::msg::PathWithLaneId & path, const bool is_prioritized, - const intersection::IntersectionStopLines & intersection_stoplines, + const IntersectionStopLines & intersection_stoplines, tier4_debug_msgs::msg::Float64MultiArrayStamped * ego_ttc_array) const { const double intersection_velocity = diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp similarity index 99% rename from planning/behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp rename to planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp index b741d43bb025a..0fb6042e5aadb 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp @@ -34,7 +34,7 @@ std::tuple< bool /* reconciled occlusion disapproval */> IntersectionModule::getOcclusionStatus( const TrafficPrioritizedLevel & traffic_prioritized_level, - const intersection::InterpolatedPathInfo & interpolated_path_info) + const InterpolatedPathInfo & interpolated_path_info) { const auto & intersection_lanelets = intersection_lanelets_.value(); const auto & occlusion_attention_lanelets = intersection_lanelets.occlusion_attention(); @@ -99,7 +99,7 @@ IntersectionModule::getOcclusionStatus( } IntersectionModule::OcclusionType IntersectionModule::detectOcclusion( - const intersection::InterpolatedPathInfo & interpolated_path_info) const + const InterpolatedPathInfo & interpolated_path_info) const { const auto & intersection_lanelets = intersection_lanelets_.value(); const auto & adjacent_lanelets = intersection_lanelets.adjacent(); diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp similarity index 96% rename from planning/behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp rename to planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp index 9ea5360c3a176..d4466c1e9431b 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp @@ -161,12 +161,8 @@ namespace behavior_velocity_planner { namespace bg = boost::geometry; -using intersection::make_err; -using intersection::make_ok; -using intersection::Result; - -Result -IntersectionModule::prepareIntersectionData(PathWithLaneId * path) +Result IntersectionModule::prepareIntersectionData( + PathWithLaneId * path) { const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr(); const auto routing_graph_ptr = planner_data_->route_handler_->getRoutingGraphPtr(); @@ -191,13 +187,12 @@ IntersectionModule::prepareIntersectionData(PathWithLaneId * path) const auto interpolated_path_info_opt = util::generateInterpolatedPath( lane_id_, associative_ids_, *path, planner_param_.common.path_interpolation_ds, logger_); if (!interpolated_path_info_opt) { - return make_err( - "splineInterpolate failed"); + return make_err("splineInterpolate failed"); } const auto & interpolated_path_info = interpolated_path_info_opt.value(); if (!interpolated_path_info.lane_id_interval) { - return make_err( + return make_err( "Path has no interval on intersection lane " + std::to_string(lane_id_)); } @@ -231,8 +226,7 @@ IntersectionModule::prepareIntersectionData(PathWithLaneId * path) const auto & first_conflicting_lane_opt = intersection_lanelets.first_conflicting_lane(); if (conflicting_lanelets.empty() || !first_conflicting_area_opt || !first_conflicting_lane_opt) { // this is abnormal - return make_err( - "conflicting area is empty"); + return make_err("conflicting area is empty"); } const auto & first_conflicting_lane = first_conflicting_lane_opt.value(); const auto & first_conflicting_area = first_conflicting_area_opt.value(); @@ -250,7 +244,7 @@ IntersectionModule::prepareIntersectionData(PathWithLaneId * path) assigned_lanelet, first_conflicting_area, dummy_first_attention_lane, second_attention_area_opt, interpolated_path_info, path); if (!intersection_stoplines_opt) { - return make_err( + return make_err( "failed to generate intersection_stoplines"); } const auto & intersection_stoplines = intersection_stoplines_opt.value(); @@ -265,7 +259,7 @@ IntersectionModule::prepareIntersectionData(PathWithLaneId * path) lanelets_on_path, interpolated_path_info, first_conflicting_area, conflicting_area, first_attention_area_opt, intersection_lanelets.attention_area(), closest_idx); if (!path_lanelets_opt.has_value()) { - return make_err( + return make_err( "failed to generate PathLanelets"); } const auto & path_lanelets = path_lanelets_opt.value(); @@ -294,13 +288,12 @@ IntersectionModule::prepareIntersectionData(PathWithLaneId * path) } } - return make_ok( + return make_ok( interpolated_path_info, intersection_stoplines, path_lanelets); } std::optional IntersectionModule::getStopLineIndexFromMap( - const intersection::InterpolatedPathInfo & interpolated_path_info, - lanelet::ConstLanelet assigned_lanelet) const + const InterpolatedPathInfo & interpolated_path_info, lanelet::ConstLanelet assigned_lanelet) const { const auto & path = interpolated_path_info.path; const auto & lane_interval = interpolated_path_info.lane_id_interval.value(); @@ -350,12 +343,11 @@ std::optional IntersectionModule::getStopLineIndexFromMap( planner_data_->ego_nearest_yaw_threshold); } -std::optional -IntersectionModule::generateIntersectionStopLines( +std::optional IntersectionModule::generateIntersectionStopLines( lanelet::ConstLanelet assigned_lanelet, const lanelet::CompoundPolygon3d & first_conflicting_area, const lanelet::ConstLanelet & first_attention_lane, const std::optional & second_attention_area_opt, - const intersection::InterpolatedPathInfo & interpolated_path_info, + const InterpolatedPathInfo & interpolated_path_info, tier4_planning_msgs::msg::PathWithLaneId * original_path) const { const bool use_stuck_stopline = planner_param_.stuck_vehicle.use_stuck_stopline; @@ -555,7 +547,7 @@ IntersectionModule::generateIntersectionStopLines( intersection_stoplines_temp.default_stopline; } - intersection::IntersectionStopLines intersection_stoplines; + IntersectionStopLines intersection_stoplines; intersection_stoplines.closest_idx = intersection_stoplines_temp.closest_idx; if (stuck_stopline_valid) { intersection_stoplines.stuck_stopline = intersection_stoplines_temp.stuck_stopline; @@ -585,7 +577,7 @@ IntersectionModule::generateIntersectionStopLines( return intersection_stoplines; } -intersection::IntersectionLanelets IntersectionModule::generateObjectiveLanelets( +IntersectionLanelets IntersectionModule::generateObjectiveLanelets( lanelet::LaneletMapConstPtr lanelet_map_ptr, lanelet::routing::RoutingGraphPtr routing_graph_ptr, const lanelet::ConstLanelet assigned_lanelet) const { @@ -736,7 +728,7 @@ intersection::IntersectionLanelets IntersectionModule::generateObjectiveLanelets auto [attention_lanelets, original_attention_lanelet_sequences] = util::mergeLaneletsByTopologicalSort(detection_and_preceding_lanelets, routing_graph_ptr); - intersection::IntersectionLanelets result; + IntersectionLanelets result; result.attention_ = std::move(attention_lanelets); for (const auto & original_attention_lanelet_seq : original_attention_lanelet_sequences) { // NOTE: in mergeLaneletsByTopologicalSort(), sub_ids are empty checked, so it is ensured that @@ -786,9 +778,9 @@ intersection::IntersectionLanelets IntersectionModule::generateObjectiveLanelets return result; } -std::optional IntersectionModule::generatePathLanelets( +std::optional IntersectionModule::generatePathLanelets( const lanelet::ConstLanelets & lanelets_on_path, - const intersection::InterpolatedPathInfo & interpolated_path_info, + const InterpolatedPathInfo & interpolated_path_info, const lanelet::CompoundPolygon3d & first_conflicting_area, const std::vector & conflicting_areas, const std::optional & first_attention_area, @@ -804,7 +796,7 @@ std::optional IntersectionModule::generatePathLanele const auto assigned_lane_interval = assigned_lane_interval_opt.value(); const auto & path = interpolated_path_info.path; - intersection::PathLanelets path_lanelets; + PathLanelets path_lanelets; // prev path_lanelets.prev = ::getPrevLanelets(lanelets_on_path, associative_ids_); path_lanelets.all = path_lanelets.prev; diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp similarity index 95% rename from planning/behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp rename to planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp index 498a902c032db..c7de1805327c3 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp @@ -118,10 +118,9 @@ namespace behavior_velocity_planner { namespace bg = boost::geometry; -std::optional IntersectionModule::isStuckStatus( +std::optional IntersectionModule::isStuckStatus( const tier4_planning_msgs::msg::PathWithLaneId & path, - const intersection::IntersectionStopLines & intersection_stoplines, - const intersection::PathLanelets & path_lanelets) const + const IntersectionStopLines & intersection_stoplines, const PathLanelets & path_lanelets) const { const auto closest_idx = intersection_stoplines.closest_idx; auto fromEgoDist = [&](const size_t index) { @@ -162,8 +161,7 @@ std::optional IntersectionModule::isStuckStatus( } } if (stopline_idx) { - return intersection::StuckStop{ - closest_idx, stopline_idx.value(), occlusion_peeking_stopline_idx_opt}; + return StuckStop{closest_idx, stopline_idx.value(), occlusion_peeking_stopline_idx_opt}; } } } @@ -230,8 +228,7 @@ bool IntersectionModule::isTargetYieldStuckVehicleType( return false; } -bool IntersectionModule::checkStuckVehicleInIntersection( - const intersection::PathLanelets & path_lanelets) const +bool IntersectionModule::checkStuckVehicleInIntersection(const PathLanelets & path_lanelets) const { using lanelet::utils::getArcCoordinates; using lanelet::utils::getLaneletLength3d; @@ -306,10 +303,10 @@ bool IntersectionModule::checkStuckVehicleInIntersection( return false; } -std::optional IntersectionModule::isYieldStuckStatus( +std::optional IntersectionModule::isYieldStuckStatus( const tier4_planning_msgs::msg::PathWithLaneId & path, - const intersection::InterpolatedPathInfo & interpolated_path_info, - const intersection::IntersectionStopLines & intersection_stoplines) const + const InterpolatedPathInfo & interpolated_path_info, + const IntersectionStopLines & intersection_stoplines) const { const auto closest_idx = intersection_stoplines.closest_idx; auto fromEgoDist = [&](const size_t index) { @@ -342,14 +339,14 @@ std::optional IntersectionModule::isYieldStuckStat } } if (stopline_idx) { - return intersection::YieldStuckStop{closest_idx, stopline_idx.value(), std::string("")}; + return YieldStuckStop{closest_idx, stopline_idx.value(), std::string("")}; } } return std::nullopt; } bool IntersectionModule::checkYieldStuckVehicleInIntersection( - const intersection::InterpolatedPathInfo & interpolated_path_info, + const InterpolatedPathInfo & interpolated_path_info, const lanelet::ConstLanelets & attention_lanelets) const { const bool yield_stuck_detection_direction = [&]() { diff --git a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp similarity index 99% rename from planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp rename to planning/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp index 67da3c7a759fe..be8d94c3b306d 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp @@ -52,7 +52,7 @@ MergeFromPrivateRoadModule::MergeFromPrivateRoadModule( static std::optional getFirstConflictingLanelet( const lanelet::ConstLanelets & conflicting_lanelets, - const intersection::InterpolatedPathInfo & interpolated_path_info, + const InterpolatedPathInfo & interpolated_path_info, const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) { const auto & path_ip = interpolated_path_info.path; diff --git a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp similarity index 100% rename from planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp rename to planning/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/autoware_behavior_velocity_intersection_module/src/util.cpp similarity index 97% rename from planning/behavior_velocity_intersection_module/src/util.cpp rename to planning/autoware_behavior_velocity_intersection_module/src/util.cpp index 9c492e7a64cde..a083185786e42 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/util.cpp @@ -129,8 +129,7 @@ std::optional> findLaneIdsInterval( } std::optional getFirstPointInsidePolygonByFootprint( - const lanelet::CompoundPolygon3d & polygon, - const intersection::InterpolatedPathInfo & interpolated_path_info, + const lanelet::CompoundPolygon3d & polygon, const InterpolatedPathInfo & interpolated_path_info, const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) { const auto & path_ip = interpolated_path_info.path; @@ -154,7 +153,7 @@ std::optional> getFirstPointInsidePolygonsByFootprint( const std::vector & polygons, - const intersection::InterpolatedPathInfo & interpolated_path_info, + const InterpolatedPathInfo & interpolated_path_info, const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length) { const auto & path_ip = interpolated_path_info.path; @@ -356,12 +355,12 @@ bool hasAssociatedTrafficLight(lanelet::ConstLanelet lane) return tl_id.has_value(); } -std::optional generateInterpolatedPath( +std::optional generateInterpolatedPath( const lanelet::Id lane_id, const std::set & associative_lane_ids, const tier4_planning_msgs::msg::PathWithLaneId & input_path, const double ds, const rclcpp::Logger logger) { - intersection::InterpolatedPathInfo interpolated_path_info; + InterpolatedPathInfo interpolated_path_info; if (!splineInterpolate(input_path, ds, interpolated_path_info.path, logger)) { return std::nullopt; } diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/autoware_behavior_velocity_intersection_module/src/util.hpp similarity index 95% rename from planning/behavior_velocity_intersection_module/src/util.hpp rename to planning/autoware_behavior_velocity_intersection_module/src/util.hpp index 878253e6943a7..27200e663503d 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/util.hpp @@ -98,7 +98,7 @@ bool hasAssociatedTrafficLight(lanelet::ConstLanelet lane); /** * @brief interpolate PathWithLaneId */ -std::optional generateInterpolatedPath( +std::optional generateInterpolatedPath( const lanelet::Id lane_id, const std::set & associative_lane_ids, const tier4_planning_msgs::msg::PathWithLaneId & input_path, const double ds, const rclcpp::Logger logger); @@ -124,8 +124,7 @@ mergeLaneletsByTopologicalSort( * polygon */ std::optional getFirstPointInsidePolygonByFootprint( - const lanelet::CompoundPolygon3d & polygon, - const intersection::InterpolatedPathInfo & interpolated_path_info, + const lanelet::CompoundPolygon3d & polygon, const InterpolatedPathInfo & interpolated_path_info, const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length); /** @@ -136,7 +135,7 @@ std::optional> getFirstPointInsidePolygonsByFootprint( const std::vector & polygons, - const intersection::InterpolatedPathInfo & interpolated_path_info, + const InterpolatedPathInfo & interpolated_path_info, const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length); std::vector getPolygon3dFromLanelets( diff --git a/planning/autoware_behavior_velocity_planner/README.md b/planning/autoware_behavior_velocity_planner/README.md index af30de556b542..acf4c1ce78e56 100644 --- a/planning/autoware_behavior_velocity_planner/README.md +++ b/planning/autoware_behavior_velocity_planner/README.md @@ -11,7 +11,7 @@ It loads modules as plugins. Please refer to the links listed below for detail o - [Crosswalk](../behavior_velocity_crosswalk_module/README.md) - [Walkway](../autoware_behavior_velocity_walkway_module/README.md) - [Detection Area](../behavior_velocity_detection_area_module/README.md) -- [Intersection](../behavior_velocity_intersection_module/README.md) +- [Intersection](../autoware_behavior_velocity_intersection_module/README.md) - [MergeFromPrivate](../behavior_velocity_intersection_module/README.md#merge-from-private) - [Stop Line](../behavior_velocity_stop_line_module/README.md) - [Virtual Traffic Light](../autoware_behavior_velocity_virtual_traffic_light_module/README.md) diff --git a/planning/autoware_behavior_velocity_planner/package.xml b/planning/autoware_behavior_velocity_planner/package.xml index 576c4e92887cb..c90d4d01cbca5 100644 --- a/planning/autoware_behavior_velocity_planner/package.xml +++ b/planning/autoware_behavior_velocity_planner/package.xml @@ -65,6 +65,7 @@ ament_cmake_ros ament_lint_auto + autoware_behavior_velocity_intersection_module autoware_behavior_velocity_run_out_module autoware_behavior_velocity_virtual_traffic_light_module autoware_behavior_velocity_walkway_module @@ -72,7 +73,6 @@ behavior_velocity_blind_spot_module behavior_velocity_crosswalk_module behavior_velocity_detection_area_module - behavior_velocity_intersection_module behavior_velocity_no_drivable_lane_module behavior_velocity_no_stopping_area_module behavior_velocity_occlusion_spot_module diff --git a/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp index b21fd6cc0f168..2e971ed238751 100644 --- a/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp @@ -71,7 +71,7 @@ std::shared_ptr generateNode() module_names.emplace_back("behavior_velocity_planner::CrosswalkModulePlugin"); module_names.emplace_back("autoware::behavior_velocity_planner::WalkwayModulePlugin"); module_names.emplace_back("behavior_velocity_planner::TrafficLightModulePlugin"); - module_names.emplace_back("behavior_velocity_planner::IntersectionModulePlugin"); + module_names.emplace_back("autoware::behavior_velocity_planner::IntersectionModulePlugin"); module_names.emplace_back("behavior_velocity_planner::MergeFromPrivateModulePlugin"); module_names.emplace_back("behavior_velocity_planner::BlindSpotModulePlugin"); module_names.emplace_back("behavior_velocity_planner::DetectionAreaModulePlugin"); @@ -100,7 +100,7 @@ std::shared_ptr generateNode() get_behavior_velocity_module_config_no_prefix("crosswalk"), get_behavior_velocity_module_config("walkway"), get_behavior_velocity_module_config_no_prefix("detection_area"), - get_behavior_velocity_module_config_no_prefix("intersection"), + get_behavior_velocity_module_config("intersection"), get_behavior_velocity_module_config_no_prefix("no_stopping_area"), get_behavior_velocity_module_config_no_prefix("occlusion_spot"), get_behavior_velocity_module_config("run_out"), diff --git a/planning/behavior_velocity_intersection_module/plugins.xml b/planning/behavior_velocity_intersection_module/plugins.xml deleted file mode 100644 index 206f0324231ec..0000000000000 --- a/planning/behavior_velocity_intersection_module/plugins.xml +++ /dev/null @@ -1,4 +0,0 @@ - - - - From 9cb51d0f3d59417bab44b57ce04a63d9d7c3affa Mon Sep 17 00:00:00 2001 From: Autumn60 <37181352+Autumn60@users.noreply.github.com> Date: Fri, 7 Jun 2024 14:29:49 +0900 Subject: [PATCH 07/65] feat(emergency_handler, mrm_handler): change to read topic by polling (#7297) * replace Subscription to InterProcessPollingSubscriber Signed-off-by: Autumn60 * sort depend packages list in package.xml Signed-off-by: Autumn60 * fix end of file Signed-off-by: Autumn60 * clang format Signed-off-by: Autumn60 * chore: fix comments Signed-off-by: Autumn60 * replace Subscription to InterProcessPollingSubscriber (mrm_handler) Signed-off-by: Autumn60 --------- Signed-off-by: Autumn60 Co-authored-by: Autumn60 --- .../emergency_handler_core.hpp | 35 +++--- system/emergency_handler/package.xml | 1 + .../emergency_handler_core.cpp | 82 +++++-------- .../include/mrm_handler/mrm_handler_core.hpp | 49 ++++---- system/mrm_handler/package.xml | 1 + .../src/mrm_handler/mrm_handler_core.cpp | 116 +++++++----------- 6 files changed, 116 insertions(+), 168 deletions(-) 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 012bb55af3068..cd66cde64c9a5 100644 --- a/system/emergency_handler/include/emergency_handler/emergency_handler_core.hpp +++ b/system/emergency_handler/include/emergency_handler/emergency_handler_core.hpp @@ -20,6 +20,8 @@ #include // Autoware +#include + #include #include #include @@ -56,33 +58,26 @@ class EmergencyHandler : public rclcpp::Node explicit EmergencyHandler(const rclcpp::NodeOptions & options); private: - // Subscribers + // Subscribers with callback rclcpp::Subscription::SharedPtr sub_hazard_status_stamped_; rclcpp::Subscription::SharedPtr sub_prev_control_command_; - rclcpp::Subscription::SharedPtr sub_odom_; - rclcpp::Subscription::SharedPtr sub_control_mode_; - rclcpp::Subscription::SharedPtr - sub_mrm_comfortable_stop_status_; - rclcpp::Subscription::SharedPtr - sub_mrm_emergency_stop_status_; + // Subscribers without callback + tier4_autoware_utils::InterProcessPollingSubscriber sub_odom_{ + this, "~/input/odometry"}; + tier4_autoware_utils::InterProcessPollingSubscriber + sub_control_mode_{this, "~/input/control_mode"}; + tier4_autoware_utils::InterProcessPollingSubscriber + sub_mrm_comfortable_stop_status_{this, "~/input/mrm/comfortable_stop/status"}; + tier4_autoware_utils::InterProcessPollingSubscriber + sub_mrm_emergency_stop_status_{this, "~/input/mrm/emergency_stop/status"}; autoware_system_msgs::msg::HazardStatusStamped::ConstSharedPtr hazard_status_stamped_; autoware_control_msgs::msg::Control::ConstSharedPtr prev_control_command_; - nav_msgs::msg::Odometry::ConstSharedPtr odom_; - autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr control_mode_; - tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr mrm_comfortable_stop_status_; - tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr mrm_emergency_stop_status_; void onHazardStatusStamped( const autoware_system_msgs::msg::HazardStatusStamped::ConstSharedPtr msg); void onPrevControlCommand(const autoware_control_msgs::msg::Control::ConstSharedPtr msg); - void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg); - void onControlMode(const autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg); - void onMrmComfortableStopStatus( - const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg); - void onMrmEmergencyStopStatus( - const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg); // Publisher rclcpp::Publisher::SharedPtr pub_control_command_; @@ -135,9 +130,13 @@ class EmergencyHandler : public rclcpp::Node void updateMrmState(); void operateMrm(); autoware_adapi_v1_msgs::msg::MrmState::_behavior_type getCurrentMrmBehavior(); - bool isStopped(); + + bool isAutonomous(); bool isDrivingBackwards(); bool isEmergency(); + bool isStopped(); + bool isComfortableStopStatusAvailable(); + bool isEmergencyStopStatusAvailable(); }; #endif // EMERGENCY_HANDLER__EMERGENCY_HANDLER_CORE_HPP_ diff --git a/system/emergency_handler/package.xml b/system/emergency_handler/package.xml index aa2090c86edb8..f26080fd8ef56 100644 --- a/system/emergency_handler/package.xml +++ b/system/emergency_handler/package.xml @@ -21,6 +21,7 @@ rclcpp_components std_msgs std_srvs + tier4_autoware_utils tier4_system_msgs ament_lint_auto diff --git a/system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp b/system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp index ae3d60e32a445..b2ee12afc9c76 100644 --- a/system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp +++ b/system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp @@ -30,24 +30,13 @@ EmergencyHandler::EmergencyHandler(const rclcpp::NodeOptions & options) using std::placeholders::_1; - // Subscriber + // Subscribers with callback sub_hazard_status_stamped_ = create_subscription( "~/input/hazard_status", rclcpp::QoS{1}, std::bind(&EmergencyHandler::onHazardStatusStamped, this, _1)); sub_prev_control_command_ = create_subscription( "~/input/prev_control_command", rclcpp::QoS{1}, std::bind(&EmergencyHandler::onPrevControlCommand, this, _1)); - sub_odom_ = create_subscription( - "~/input/odometry", rclcpp::QoS{1}, std::bind(&EmergencyHandler::onOdometry, this, _1)); - // subscribe control mode - sub_control_mode_ = create_subscription( - "~/input/control_mode", rclcpp::QoS{1}, std::bind(&EmergencyHandler::onControlMode, this, _1)); - sub_mrm_comfortable_stop_status_ = create_subscription( - "~/input/mrm/comfortable_stop/status", rclcpp::QoS{1}, - std::bind(&EmergencyHandler::onMrmComfortableStopStatus, this, _1)); - sub_mrm_emergency_stop_status_ = create_subscription( - "~/input/mrm/emergency_stop/status", rclcpp::QoS{1}, - std::bind(&EmergencyHandler::onMrmEmergencyStopStatus, this, _1)); // Publisher pub_control_command_ = create_publisher( @@ -72,13 +61,6 @@ EmergencyHandler::EmergencyHandler(const rclcpp::NodeOptions & options) client_mrm_emergency_stop_group_); // Initialize - odom_ = std::make_shared(); - control_mode_ = std::make_shared(); - prev_control_command_ = - autoware_control_msgs::msg::Control::ConstSharedPtr(new autoware_control_msgs::msg::Control); - mrm_comfortable_stop_status_ = - std::make_shared(); - mrm_emergency_stop_status_ = std::make_shared(); mrm_state_.stamp = this->now(); mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::NORMAL; mrm_state_.behavior = autoware_adapi_v1_msgs::msg::MrmState::NONE; @@ -105,29 +87,6 @@ void EmergencyHandler::onPrevControlCommand( prev_control_command_ = autoware_control_msgs::msg::Control::ConstSharedPtr(control_command); } -void EmergencyHandler::onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg) -{ - odom_ = msg; -} - -void EmergencyHandler::onControlMode( - const autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg) -{ - control_mode_ = msg; -} - -void EmergencyHandler::onMrmComfortableStopStatus( - const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg) -{ - mrm_comfortable_stop_status_ = msg; -} - -void EmergencyHandler::onMrmEmergencyStopStatus( - const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg) -{ - mrm_emergency_stop_status_ = msg; -} - autoware_vehicle_msgs::msg::HazardLightsCommand EmergencyHandler::createHazardCmdMsg() { using autoware_vehicle_msgs::msg::HazardLightsCommand; @@ -293,17 +252,14 @@ bool EmergencyHandler::isDataReady() return false; } - if ( - param_.use_comfortable_stop && mrm_comfortable_stop_status_->state == - tier4_system_msgs::msg::MrmBehaviorStatus::NOT_AVAILABLE) { + if (param_.use_comfortable_stop && !isComfortableStopStatusAvailable()) { RCLCPP_INFO_THROTTLE( this->get_logger(), *this->get_clock(), std::chrono::milliseconds(5000).count(), "waiting for mrm comfortable stop to become available..."); return false; } - if ( - mrm_emergency_stop_status_->state == tier4_system_msgs::msg::MrmBehaviorStatus::NOT_AVAILABLE) { + if (!isEmergencyStopStatusAvailable()) { RCLCPP_INFO_THROTTLE( this->get_logger(), *this->get_clock(), std::chrono::milliseconds(5000).count(), "waiting for mrm emergency stop to become available..."); @@ -381,7 +337,7 @@ void EmergencyHandler::updateMrmState() const bool is_emergency = isEmergency(); // Get mode - const bool is_auto_mode = control_mode_->mode == ControlModeReport::AUTONOMOUS; + const bool is_auto_mode = isAutonomous(); // State Machine if (mrm_state_.state == MrmState::NORMAL) { @@ -447,6 +403,14 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type EmergencyHandler::getCurre return mrm_state_.behavior; } +bool EmergencyHandler::isAutonomous() +{ + using autoware_vehicle_msgs::msg::ControlModeReport; + auto mode = sub_control_mode_.takeData(); + if (mode == nullptr) return false; + return mode->mode == ControlModeReport::AUTONOMOUS; +} + bool EmergencyHandler::isEmergency() { return hazard_status_stamped_->status.emergency || @@ -455,14 +419,32 @@ bool EmergencyHandler::isEmergency() bool EmergencyHandler::isStopped() { + auto odom = sub_odom_.takeData(); + if (odom == nullptr) return false; constexpr auto th_stopped_velocity = 0.001; - return (std::abs(odom_->twist.twist.linear.x) < th_stopped_velocity); + return (std::abs(odom->twist.twist.linear.x) < th_stopped_velocity); +} + +bool EmergencyHandler::isComfortableStopStatusAvailable() +{ + auto status = sub_mrm_comfortable_stop_status_.takeData(); + if (status == nullptr) return false; + return status->state != tier4_system_msgs::msg::MrmBehaviorStatus::NOT_AVAILABLE; +} + +bool EmergencyHandler::isEmergencyStopStatusAvailable() +{ + auto status = sub_mrm_emergency_stop_status_.takeData(); + if (status == nullptr) return false; + return status->state != tier4_system_msgs::msg::MrmBehaviorStatus::NOT_AVAILABLE; } bool EmergencyHandler::isDrivingBackwards() { + auto odom = sub_odom_.takeData(); + if (odom == nullptr) return false; constexpr auto th_moving_backwards = -0.001; - return odom_->twist.twist.linear.x < th_moving_backwards; + return odom->twist.twist.linear.x < th_moving_backwards; } #include 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 7a160b6c531e9..33d8af5004c47 100644 --- a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp +++ b/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp @@ -22,6 +22,8 @@ #include // Autoware +#include + #include #include #include @@ -66,39 +68,28 @@ class MrmHandler : public rclcpp::Node // type enum RequestType { CALL, CANCEL }; - // Subscribers - rclcpp::Subscription::SharedPtr sub_odom_; - rclcpp::Subscription::SharedPtr sub_control_mode_; + // Subscribers with callback rclcpp::Subscription::SharedPtr sub_operation_mode_availability_; - rclcpp::Subscription::SharedPtr - sub_mrm_pull_over_status_; - rclcpp::Subscription::SharedPtr - sub_mrm_comfortable_stop_status_; - rclcpp::Subscription::SharedPtr - sub_mrm_emergency_stop_status_; - rclcpp::Subscription::SharedPtr - sub_operation_mode_state_; - - nav_msgs::msg::Odometry::ConstSharedPtr odom_; - autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr control_mode_; + // Subscribers without callback + tier4_autoware_utils::InterProcessPollingSubscriber sub_odom_{ + this, "~/input/odometry"}; + tier4_autoware_utils::InterProcessPollingSubscriber + sub_control_mode_{this, "~/input/control_mode"}; + tier4_autoware_utils::InterProcessPollingSubscriber + sub_mrm_pull_over_status_{this, "~/input/mrm/pull_over/status"}; + tier4_autoware_utils::InterProcessPollingSubscriber + sub_mrm_comfortable_stop_status_{this, "~/input/mrm/comfortable_stop/status"}; + tier4_autoware_utils::InterProcessPollingSubscriber + sub_mrm_emergency_stop_status_{this, "~/input/mrm/emergency_stop/status"}; + tier4_autoware_utils::InterProcessPollingSubscriber< + autoware_adapi_v1_msgs::msg::OperationModeState> + sub_operation_mode_state_{this, "~/input/api/operation_mode/state"}; + tier4_system_msgs::msg::OperationModeAvailability::ConstSharedPtr operation_mode_availability_; - tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr mrm_pull_over_status_; - tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr mrm_comfortable_stop_status_; - tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr mrm_emergency_stop_status_; - autoware_adapi_v1_msgs::msg::OperationModeState::ConstSharedPtr operation_mode_state_; - void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg); - void onControlMode(const autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg); void onOperationModeAvailability( const tier4_system_msgs::msg::OperationModeAvailability::ConstSharedPtr msg); - void onMrmPullOverStatus(const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg); - void onMrmComfortableStopStatus( - const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg); - void onMrmEmergencyStopStatus( - const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg); - void onOperationModeState( - const autoware_adapi_v1_msgs::msg::OperationModeState::ConstSharedPtr msg); // Publisher @@ -156,6 +147,10 @@ class MrmHandler : public rclcpp::Node bool isStopped(); bool isDrivingBackwards(); bool isEmergency() const; + bool isAutonomous(); + bool isPullOverStatusAvailable(); + bool isComfortableStopStatusAvailable(); + bool isEmergencyStopStatusAvailable(); bool isArrivedAtGoal(); }; diff --git a/system/mrm_handler/package.xml b/system/mrm_handler/package.xml index 2db22cecaa82d..5774cce3215a9 100644 --- a/system/mrm_handler/package.xml +++ b/system/mrm_handler/package.xml @@ -21,6 +21,7 @@ rclcpp_components std_msgs std_srvs + tier4_autoware_utils tier4_system_msgs ament_lint_auto 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 d70303a9801ac..44407c40c6787 100644 --- a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp +++ b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp @@ -36,28 +36,11 @@ MrmHandler::MrmHandler(const rclcpp::NodeOptions & options) : Node("mrm_handler" using std::placeholders::_1; - // Subscriber - sub_odom_ = create_subscription( - "~/input/odometry", rclcpp::QoS{1}, std::bind(&MrmHandler::onOdometry, this, _1)); - // subscribe control mode - sub_control_mode_ = create_subscription( - "~/input/control_mode", rclcpp::QoS{1}, std::bind(&MrmHandler::onControlMode, this, _1)); + // Subscribers with callback sub_operation_mode_availability_ = create_subscription( "~/input/operation_mode_availability", rclcpp::QoS{1}, std::bind(&MrmHandler::onOperationModeAvailability, this, _1)); - sub_mrm_pull_over_status_ = create_subscription( - "~/input/mrm/pull_over/status", rclcpp::QoS{1}, - std::bind(&MrmHandler::onMrmPullOverStatus, this, _1)); - sub_mrm_comfortable_stop_status_ = create_subscription( - "~/input/mrm/comfortable_stop/status", rclcpp::QoS{1}, - std::bind(&MrmHandler::onMrmComfortableStopStatus, this, _1)); - sub_mrm_emergency_stop_status_ = create_subscription( - "~/input/mrm/emergency_stop/status", rclcpp::QoS{1}, - std::bind(&MrmHandler::onMrmEmergencyStopStatus, this, _1)); - sub_operation_mode_state_ = create_subscription( - "~/input/api/operation_mode/state", rclcpp::QoS{1}, - std::bind(&MrmHandler::onOperationModeState, this, _1)); // Publisher pub_hazard_cmd_ = create_publisher( @@ -84,13 +67,6 @@ MrmHandler::MrmHandler(const rclcpp::NodeOptions & options) : Node("mrm_handler" client_mrm_emergency_stop_group_); // Initialize - odom_ = std::make_shared(); - control_mode_ = std::make_shared(); - mrm_pull_over_status_ = std::make_shared(); - mrm_comfortable_stop_status_ = - std::make_shared(); - mrm_emergency_stop_status_ = std::make_shared(); - operation_mode_state_ = std::make_shared(); mrm_state_.stamp = this->now(); mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::NORMAL; mrm_state_.behavior = autoware_adapi_v1_msgs::msg::MrmState::NONE; @@ -102,17 +78,6 @@ MrmHandler::MrmHandler(const rclcpp::NodeOptions & options) : Node("mrm_handler" this, get_clock(), update_period_ns, std::bind(&MrmHandler::onTimer, this)); } -void MrmHandler::onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg) -{ - odom_ = msg; -} - -void MrmHandler::onControlMode( - const autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg) -{ - control_mode_ = msg; -} - void MrmHandler::onOperationModeAvailability( const tier4_system_msgs::msg::OperationModeAvailability::ConstSharedPtr msg) { @@ -141,30 +106,6 @@ void MrmHandler::onOperationModeAvailability( operation_mode_availability_ = msg; } -void MrmHandler::onMrmPullOverStatus( - const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg) -{ - mrm_pull_over_status_ = msg; -} - -void MrmHandler::onMrmComfortableStopStatus( - const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg) -{ - mrm_comfortable_stop_status_ = msg; -} - -void MrmHandler::onMrmEmergencyStopStatus( - const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg) -{ - mrm_emergency_stop_status_ = msg; -} - -void MrmHandler::onOperationModeState( - const autoware_adapi_v1_msgs::msg::OperationModeState::ConstSharedPtr msg) -{ - operation_mode_state_ = msg; -} - void MrmHandler::publishHazardCmd() { using autoware_vehicle_msgs::msg::HazardLightsCommand; @@ -352,26 +293,21 @@ bool MrmHandler::isDataReady() return false; } - if ( - param_.use_pull_over && - mrm_pull_over_status_->state == tier4_system_msgs::msg::MrmBehaviorStatus::NOT_AVAILABLE) { + if (param_.use_pull_over && !isPullOverStatusAvailable()) { RCLCPP_INFO_THROTTLE( this->get_logger(), *this->get_clock(), std::chrono::milliseconds(5000).count(), "waiting for mrm pull over to become available..."); return false; } - if ( - param_.use_comfortable_stop && mrm_comfortable_stop_status_->state == - tier4_system_msgs::msg::MrmBehaviorStatus::NOT_AVAILABLE) { + if (param_.use_comfortable_stop && !isComfortableStopStatusAvailable()) { RCLCPP_INFO_THROTTLE( this->get_logger(), *this->get_clock(), std::chrono::milliseconds(5000).count(), "waiting for mrm comfortable stop to become available..."); return false; } - if ( - mrm_emergency_stop_status_->state == tier4_system_msgs::msg::MrmBehaviorStatus::NOT_AVAILABLE) { + if (!isEmergencyStopStatusAvailable()) { RCLCPP_INFO_THROTTLE( this->get_logger(), *this->get_clock(), std::chrono::milliseconds(5000).count(), "waiting for mrm emergency stop to become available..."); @@ -460,7 +396,7 @@ void MrmHandler::updateMrmState() } // Get mode - const bool is_auto_mode = control_mode_->mode == ControlModeReport::AUTONOMOUS; + const bool is_auto_mode = isAutonomous(); // State Machine switch (mrm_state_.state) { @@ -581,14 +517,18 @@ autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmB bool MrmHandler::isStopped() { + auto odom = sub_odom_.takeData(); + if (odom == nullptr) return false; constexpr auto th_stopped_velocity = 0.001; - return std::abs((odom_->twist.twist.linear.x < th_stopped_velocity) < th_stopped_velocity); + return (std::abs(odom->twist.twist.linear.x < th_stopped_velocity) < th_stopped_velocity); } bool MrmHandler::isDrivingBackwards() { + auto odom = sub_odom_.takeData(); + if (odom == nullptr) return false; constexpr auto th_moving_backwards = -0.001; - return odom_->twist.twist.linear.x < th_moving_backwards; + return odom->twist.twist.linear.x < th_moving_backwards; } bool MrmHandler::isEmergency() const @@ -597,11 +537,41 @@ bool MrmHandler::isEmergency() const is_operation_mode_availability_timeout; } +bool MrmHandler::isAutonomous() +{ + using autoware_vehicle_msgs::msg::ControlModeReport; + auto mode = sub_control_mode_.takeData(); + if (mode == nullptr) return false; + return mode->mode == ControlModeReport::AUTONOMOUS; +} + +bool MrmHandler::isPullOverStatusAvailable() +{ + auto status = sub_mrm_pull_over_status_.takeData(); + if (status == nullptr) return false; + return status->state != tier4_system_msgs::msg::MrmBehaviorStatus::NOT_AVAILABLE; +} + +bool MrmHandler::isComfortableStopStatusAvailable() +{ + auto status = sub_mrm_comfortable_stop_status_.takeData(); + if (status == nullptr) return false; + return status->state != tier4_system_msgs::msg::MrmBehaviorStatus::NOT_AVAILABLE; +} + +bool MrmHandler::isEmergencyStopStatusAvailable() +{ + auto status = sub_mrm_emergency_stop_status_.takeData(); + if (status == nullptr) return false; + return status->state != tier4_system_msgs::msg::MrmBehaviorStatus::NOT_AVAILABLE; +} + bool MrmHandler::isArrivedAtGoal() { using autoware_adapi_v1_msgs::msg::OperationModeState; - - return operation_mode_state_->mode == OperationModeState::STOP; + auto state = sub_operation_mode_state_.takeData(); + if (state == nullptr) return false; + return state->mode == OperationModeState::STOP; } #include From c85b83d211b92973bdf23b6ddb185f9e621217e2 Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Fri, 7 Jun 2024 14:44:31 +0900 Subject: [PATCH 08/65] fix(pose2twist): compute angular velocity through quaternion (#7322) * compute angular velocity from two quaternions Signed-off-by: Kento Yabuuchi * add test Signed-off-by: Kento Yabuuchi * add some comments Signed-off-by: Kento Yabuuchi * remove rpy description Signed-off-by: Kento Yabuuchi * fix typo Signed-off-by: Kento Yabuuchi * fix clang-tidy's warning Signed-off-by: Kento Yabuuchi --------- Signed-off-by: Kento Yabuuchi --- localization/pose2twist/CMakeLists.txt | 7 ++ localization/pose2twist/README.md | 2 +- .../include/pose2twist/pose2twist_core.hpp | 10 ++ .../pose2twist/src/pose2twist_core.cpp | 52 +++----- .../pose2twist/test/test_angular_velocity.cpp | 115 ++++++++++++++++++ 5 files changed, 151 insertions(+), 35 deletions(-) create mode 100644 localization/pose2twist/test/test_angular_velocity.cpp diff --git a/localization/pose2twist/CMakeLists.txt b/localization/pose2twist/CMakeLists.txt index 2a586aa9cd049..ee63d9f43559a 100644 --- a/localization/pose2twist/CMakeLists.txt +++ b/localization/pose2twist/CMakeLists.txt @@ -14,6 +14,13 @@ rclcpp_components_register_node(${PROJECT_NAME} EXECUTOR SingleThreadedExecutor ) +if(BUILD_TESTING) + find_package(ament_cmake_gtest REQUIRED) + ament_auto_add_gtest(test_angular_velocity + test/test_angular_velocity.cpp + ) +endif() + ament_auto_package( INSTALL_TO_SHARE launch diff --git a/localization/pose2twist/README.md b/localization/pose2twist/README.md index 07d9c37b710fc..f1f7d6408fafb 100644 --- a/localization/pose2twist/README.md +++ b/localization/pose2twist/README.md @@ -5,7 +5,7 @@ This `pose2twist` calculates the velocity from the input pose history. In addition to the computed twist, this node outputs the linear-x and angular-z components as a float message to simplify debugging. The `twist.linear.x` is calculated as `sqrt(dx * dx + dy * dy + dz * dz) / dt`, and the values in the `y` and `z` fields are zero. -The `twist.angular` is calculated as `d_roll / dt`, `d_pitch / dt` and `d_yaw / dt` for each field. +The `twist.angular` is calculated as `relative_rotation_vector / dt` for each field. ## Inputs / Outputs diff --git a/localization/pose2twist/include/pose2twist/pose2twist_core.hpp b/localization/pose2twist/include/pose2twist/pose2twist_core.hpp index 274fec47b3c32..d1ff6ee5ff8b6 100644 --- a/localization/pose2twist/include/pose2twist/pose2twist_core.hpp +++ b/localization/pose2twist/include/pose2twist/pose2twist_core.hpp @@ -21,6 +21,16 @@ #include #include +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +// Compute the relative rotation of q2 from q1 as a rotation vector +geometry_msgs::msg::Vector3 compute_relative_rotation_vector( + const tf2::Quaternion & q1, const tf2::Quaternion & q2); + class Pose2Twist : public rclcpp::Node { public: diff --git a/localization/pose2twist/src/pose2twist_core.cpp b/localization/pose2twist/src/pose2twist_core.cpp index f1106c15ebc0d..cdde78ed7e357 100644 --- a/localization/pose2twist/src/pose2twist_core.cpp +++ b/localization/pose2twist/src/pose2twist_core.cpp @@ -14,12 +14,6 @@ #include "pose2twist/pose2twist_core.hpp" -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif - #include #include #include @@ -41,29 +35,21 @@ Pose2Twist::Pose2Twist(const rclcpp::NodeOptions & options) : rclcpp::Node("pose "pose", queue_size, std::bind(&Pose2Twist::callback_pose, this, _1)); } -double calc_diff_for_radian(const double lhs_rad, const double rhs_rad) -{ - double diff_rad = lhs_rad - rhs_rad; - if (diff_rad > M_PI) { - diff_rad = diff_rad - 2 * M_PI; - } else if (diff_rad < -M_PI) { - diff_rad = diff_rad + 2 * M_PI; - } - return diff_rad; -} - -// x: roll, y: pitch, z: yaw -geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::Pose & pose) +tf2::Quaternion get_quaternion(const geometry_msgs::msg::PoseStamped::SharedPtr & pose_stamped_ptr) { - geometry_msgs::msg::Vector3 rpy; - tf2::Quaternion q(pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w); - tf2::Matrix3x3(q).getRPY(rpy.x, rpy.y, rpy.z); - return rpy; + const auto & orientation = pose_stamped_ptr->pose.orientation; + return tf2::Quaternion{orientation.x, orientation.y, orientation.z, orientation.w}; } -geometry_msgs::msg::Vector3 get_rpy(geometry_msgs::msg::PoseStamped::SharedPtr pose) +geometry_msgs::msg::Vector3 compute_relative_rotation_vector( + const tf2::Quaternion & q1, const tf2::Quaternion & q2) { - return get_rpy(pose->pose); + // If we define q2 as the rotation obtained by applying dq after applying q1, + // then q2 = q1 * dq . + // Therefore, dq = q1.inverse() * q2 . + const tf2::Quaternion diff_quaternion = q1.inverse() * q2; + const tf2::Vector3 axis = diff_quaternion.getAxis() * diff_quaternion.getAngle(); + return geometry_msgs::msg::Vector3{}.set__x(axis.x()).set__y(axis.y()).set__z(axis.z()); } geometry_msgs::msg::TwistStamped calc_twist( @@ -79,18 +65,16 @@ geometry_msgs::msg::TwistStamped calc_twist( return twist; } - const auto pose_a_rpy = get_rpy(pose_a); - const auto pose_b_rpy = get_rpy(pose_b); + const auto pose_a_quaternion = get_quaternion(pose_a); + const auto pose_b_quaternion = get_quaternion(pose_b); geometry_msgs::msg::Vector3 diff_xyz; - geometry_msgs::msg::Vector3 diff_rpy; + const geometry_msgs::msg::Vector3 relative_rotation_vector = + compute_relative_rotation_vector(pose_a_quaternion, pose_b_quaternion); diff_xyz.x = pose_b->pose.position.x - pose_a->pose.position.x; diff_xyz.y = pose_b->pose.position.y - pose_a->pose.position.y; diff_xyz.z = pose_b->pose.position.z - pose_a->pose.position.z; - diff_rpy.x = calc_diff_for_radian(pose_b_rpy.x, pose_a_rpy.x); - diff_rpy.y = calc_diff_for_radian(pose_b_rpy.y, pose_a_rpy.y); - diff_rpy.z = calc_diff_for_radian(pose_b_rpy.z, pose_a_rpy.z); geometry_msgs::msg::TwistStamped twist; twist.header = pose_b->header; @@ -99,9 +83,9 @@ geometry_msgs::msg::TwistStamped calc_twist( dt; twist.twist.linear.y = 0; twist.twist.linear.z = 0; - twist.twist.angular.x = diff_rpy.x / dt; - twist.twist.angular.y = diff_rpy.y / dt; - twist.twist.angular.z = diff_rpy.z / dt; + twist.twist.angular.x = relative_rotation_vector.x / dt; + twist.twist.angular.y = relative_rotation_vector.y / dt; + twist.twist.angular.z = relative_rotation_vector.z / dt; return twist; } diff --git a/localization/pose2twist/test/test_angular_velocity.cpp b/localization/pose2twist/test/test_angular_velocity.cpp new file mode 100644 index 0000000000000..bf2ca0a3ba5c2 --- /dev/null +++ b/localization/pose2twist/test/test_angular_velocity.cpp @@ -0,0 +1,115 @@ +// Copyright 2022 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "pose2twist/pose2twist_core.hpp" + +#include + +// 1e-3 radian = 0.057 degrees +constexpr double acceptable_error = 1e-3; + +TEST(AngularVelocityFromQuaternion, CheckMultiplicationOrder) +{ + // If we define q2 as the rotation obtained by applying dq after applying q1, then q2 = q1 * dq . + // + // IT IS NOT q2 = dq * q1 . + // + // This test checks that the multiplication order is correct. + + const tf2::Vector3 target_vector(1, 2, 3); + // initial state + // Now, car is facing to the +x direction + // z + // ^ y + // | ^ + // | / + // | / + // car -> x + // + // + // + + tf2::Quaternion q1; + q1.setRPY(0., 0., M_PI / 2.); // yaw = 90 degrees + const tf2::Vector3 initially_rotated_vector = tf2::quatRotate(q1, target_vector); + // after applying q1 + // Now, car is facing to the +y direction + // z + // ^ + // | y + // | ^ + // | / + // <--car x + // + // + // + EXPECT_NEAR(initially_rotated_vector.x(), -2., acceptable_error); + EXPECT_NEAR(initially_rotated_vector.y(), 1., acceptable_error); + EXPECT_NEAR(initially_rotated_vector.z(), 3., acceptable_error); + + tf2::Quaternion dq; + dq.setRPY(0., M_PI / 2., 0.); // pitch = 90 degrees + const tf2::Vector3 finally_rotated_vector = tf2::quatRotate(q1 * dq, target_vector); + // after applying dq + // Now, car is facing to the -z direction + // z y + // ^ + // / + // / + // / + // <--car x + // | + // v + // + EXPECT_NEAR(finally_rotated_vector.x(), -2., acceptable_error); + EXPECT_NEAR(finally_rotated_vector.y(), 3., acceptable_error); + EXPECT_NEAR(finally_rotated_vector.z(), -1., acceptable_error); + + // Failure case + { + const tf2::Vector3 false_rotated_vector = tf2::quatRotate(dq * q1, target_vector); + + EXPECT_FALSE(std::abs(false_rotated_vector.x() - (-2)) < acceptable_error); + EXPECT_FALSE(std::abs(false_rotated_vector.y() - (3)) < acceptable_error); + EXPECT_FALSE(std::abs(false_rotated_vector.z() - (-1)) < acceptable_error); + } +} + +TEST(AngularVelocityFromQuaternion, CheckNumericalValidity) +{ + auto test = [](const tf2::Vector3 & expected_axis, const double expected_angle) -> void { + tf2::Quaternion expected_q; + expected_q.setRotation(expected_axis, expected_angle); + + // Create a random initial quaternion + tf2::Quaternion initial_q; + initial_q.setRPY(0.2, 0.3, 0.4); + + // Calculate the final quaternion by rotating the initial quaternion by the expected + // quaternion + const tf2::Quaternion final_q = initial_q * expected_q; + + // Calculate the relative rotation between the initial and final quaternion + const geometry_msgs::msg::Vector3 rotation_vector = + compute_relative_rotation_vector(initial_q, final_q); + + EXPECT_NEAR(rotation_vector.x, expected_axis.x() * expected_angle, acceptable_error); + EXPECT_NEAR(rotation_vector.y, expected_axis.y() * expected_angle, acceptable_error); + EXPECT_NEAR(rotation_vector.z, expected_axis.z() * expected_angle, acceptable_error); + }; + + test(tf2::Vector3(1.0, 0.0, 0.0).normalized(), 0.1); // 0.1 radian = 5.7 degrees + test(tf2::Vector3(1.0, 1.0, 0.0).normalized(), -0.2); // 0.2 radian = 11.4 degrees + test(tf2::Vector3(1.0, 2.0, 3.0).normalized(), 0.3); // 0.3 radian = 17.2 degrees +} From 722e822293c09dce76d66c08286e5563f2e5d122 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 7 Jun 2024 15:07:00 +0900 Subject: [PATCH 09/65] chore(smart_mpc): add maitainers (#7346) Signed-off-by: kosuke55 --- control/smart_mpc_trajectory_follower/package.xml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/control/smart_mpc_trajectory_follower/package.xml b/control/smart_mpc_trajectory_follower/package.xml index 6cdd689c8bd5a..b25a7e2ce8dd6 100644 --- a/control/smart_mpc_trajectory_follower/package.xml +++ b/control/smart_mpc_trajectory_follower/package.xml @@ -7,6 +7,9 @@ Masayuki Aino + Kosuke Takeuchi + Takamasa Horibe + Takayuki Murooka Apache License 2.0 From 9c961a9e1977907845f874708feaa0caa157e893 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Fri, 7 Jun 2024 15:20:28 +0900 Subject: [PATCH 10/65] refactor(behavior_path_start_planner_module)!: prefix package and namespace with autoware (#7352) * change folder names Signed-off-by: Daniel Sanchez * change namespace Signed-off-by: Daniel Sanchez * add prefix in files Signed-off-by: Daniel Sanchez * add prefix to files outside the module Signed-off-by: Daniel Sanchez * add namespace to plugin Signed-off-by: Daniel Sanchez * Revert "add namespace to plugin" This reverts commit 8aeee4203385dbe76dcd06b8ef4ce116afdbad7c. Signed-off-by: Daniel Sanchez * Revert "change namespace" This reverts commit 8cf69f87612ea4084d66f83ca6a5a11da969d371. Signed-off-by: Daniel Sanchez * fix doc Signed-off-by: Daniel Sanchez * fix back doc Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .github/CODEOWNERS | 2 ++ planning/.pages | 2 +- .../CMakeLists.txt | 2 +- .../README.md | 0 .../config/start_planner.param.yaml | 0 ...lision_check_range_shift_pull_out.drawio.svg | 0 .../images/freespace_pull_out.png | Bin .../images/geometric_pull_out.drawio.svg | 0 .../images/geometric_pull_out_path.drawio.svg | 0 ...geometric_pull_out_path_with_back.drawio.svg | 0 .../images/priority_order.drawio.svg | 0 .../images/pull_out_after_back.drawio.svg | 0 .../images/pull_out_collision_check.drawio.svg | 0 .../images/shift_pull_out.drawio.svg | 0 .../images/shift_pull_out_path.drawio.svg | 0 ...hift_pull_out_path_from_road_lane.drawio.svg | 0 .../shift_pull_out_path_with_back.drawio.svg | 0 .../images/start_planner_example.png | Bin .../images/start_pose_candidate.drawio.svg | 0 .../data_structs.hpp | 6 +++--- .../debug.hpp | 8 ++++---- .../freespace_pull_out.hpp | 8 ++++---- .../geometric_pull_out.hpp | 10 +++++----- .../manager.hpp | 8 ++++---- .../pull_out_path.hpp | 6 +++--- .../pull_out_planner_base.hpp | 12 ++++++------ .../shift_pull_out.hpp | 10 +++++----- .../start_planner_module.hpp | 16 ++++++++-------- .../util.hpp | 8 ++++---- .../package.xml | 4 ++-- .../plugins.xml | 2 +- .../src/debug.cpp | 2 +- .../src/freespace_pull_out.cpp | 4 ++-- .../src/geometric_pull_out.cpp | 4 ++-- .../src/manager.cpp | 2 +- .../src/shift_pull_out.cpp | 4 ++-- .../src/start_planner_module.cpp | 6 +++--- .../src/util.cpp | 2 +- planning/behavior_path_planner/README.md | 2 +- 39 files changed, 66 insertions(+), 64 deletions(-) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/CMakeLists.txt (88%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/README.md (100%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/config/start_planner.param.yaml (100%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/images/collision_check_range_shift_pull_out.drawio.svg (100%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/images/freespace_pull_out.png (100%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/images/geometric_pull_out.drawio.svg (100%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/images/geometric_pull_out_path.drawio.svg (100%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/images/geometric_pull_out_path_with_back.drawio.svg (100%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/images/priority_order.drawio.svg (100%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/images/pull_out_after_back.drawio.svg (100%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/images/pull_out_collision_check.drawio.svg (100%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/images/shift_pull_out.drawio.svg (100%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/images/shift_pull_out_path.drawio.svg (100%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/images/shift_pull_out_path_from_road_lane.drawio.svg (100%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/images/shift_pull_out_path_with_back.drawio.svg (100%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/images/start_planner_example.png (100%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/images/start_pose_candidate.drawio.svg (100%) rename planning/{behavior_path_start_planner_module/include/behavior_path_start_planner_module => autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module}/data_structs.hpp (95%) rename planning/{behavior_path_start_planner_module/include/behavior_path_start_planner_module => autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module}/debug.hpp (80%) rename planning/{behavior_path_start_planner_module/include/behavior_path_start_planner_module => autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module}/freespace_pull_out.hpp (83%) rename planning/{behavior_path_start_planner_module/include/behavior_path_start_planner_module => autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module}/geometric_pull_out.hpp (79%) rename planning/{behavior_path_start_planner_module/include/behavior_path_start_planner_module => autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module}/manager.hpp (84%) rename planning/{behavior_path_start_planner_module/include/behavior_path_start_planner_module => autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module}/pull_out_path.hpp (83%) rename planning/{behavior_path_start_planner_module/include/behavior_path_start_planner_module => autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module}/pull_out_planner_base.hpp (89%) rename planning/{behavior_path_start_planner_module/include/behavior_path_start_planner_module => autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module}/shift_pull_out.hpp (85%) rename planning/{behavior_path_start_planner_module/include/behavior_path_start_planner_module => autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module}/start_planner_module.hpp (95%) rename planning/{behavior_path_start_planner_module/include/behavior_path_start_planner_module => autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module}/util.hpp (89%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/package.xml (91%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/plugins.xml (70%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/src/debug.cpp (94%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/src/freespace_pull_out.cpp (97%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/src/geometric_pull_out.cpp (97%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/src/manager.cpp (99%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/src/shift_pull_out.cpp (99%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/src/start_planner_module.cpp (99%) rename planning/{behavior_path_start_planner_module => autoware_behavior_path_start_planner_module}/src/util.cpp (98%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 36b1af9887ed9..d2d6fa2c56343 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -166,6 +166,8 @@ planning/behavior_path_lane_change_module/** fumiya.watanabe@tier4.jp kosuke.tak planning/behavior_path_planner/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_sampling_planner_module/** daniel.sanchez@tier4.jp maxime.clement@tier4.jp planning/autoware_behavior_path_side_shift_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/autoware_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/autoware_behavior_path_side_shift_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_path_start_planner_module/** 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_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/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 diff --git a/planning/.pages b/planning/.pages index 29b0f6a2cde56..7b932118b5010 100644 --- a/planning/.pages +++ b/planning/.pages @@ -15,7 +15,7 @@ nav: - 'Goal Planner': planning/behavior_path_goal_planner_module - 'Lane Change': planning/behavior_path_lane_change_module - 'Side Shift': planning/autoware_behavior_path_side_shift_module - - 'Start Planner': planning/behavior_path_start_planner_module + - 'Start Planner': planning/autoware_behavior_path_start_planner_module - 'Static Obstacle Avoidance': planning/autoware_behavior_path_static_obstacle_avoidance_module - 'Behavior Velocity Planner': - 'About Behavior Velocity': planning/autoware_behavior_velocity_planner diff --git a/planning/behavior_path_start_planner_module/CMakeLists.txt b/planning/autoware_behavior_path_start_planner_module/CMakeLists.txt similarity index 88% rename from planning/behavior_path_start_planner_module/CMakeLists.txt rename to planning/autoware_behavior_path_start_planner_module/CMakeLists.txt index 6bb2f76cb9842..b2882727f50d8 100644 --- a/planning/behavior_path_start_planner_module/CMakeLists.txt +++ b/planning/autoware_behavior_path_start_planner_module/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(behavior_path_start_planner_module) +project(autoware_behavior_path_start_planner_module) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/planning/behavior_path_start_planner_module/README.md b/planning/autoware_behavior_path_start_planner_module/README.md similarity index 100% rename from planning/behavior_path_start_planner_module/README.md rename to planning/autoware_behavior_path_start_planner_module/README.md diff --git a/planning/behavior_path_start_planner_module/config/start_planner.param.yaml b/planning/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml similarity index 100% rename from planning/behavior_path_start_planner_module/config/start_planner.param.yaml rename to planning/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml diff --git a/planning/behavior_path_start_planner_module/images/collision_check_range_shift_pull_out.drawio.svg b/planning/autoware_behavior_path_start_planner_module/images/collision_check_range_shift_pull_out.drawio.svg similarity index 100% rename from planning/behavior_path_start_planner_module/images/collision_check_range_shift_pull_out.drawio.svg rename to planning/autoware_behavior_path_start_planner_module/images/collision_check_range_shift_pull_out.drawio.svg diff --git a/planning/behavior_path_start_planner_module/images/freespace_pull_out.png b/planning/autoware_behavior_path_start_planner_module/images/freespace_pull_out.png similarity index 100% rename from planning/behavior_path_start_planner_module/images/freespace_pull_out.png rename to planning/autoware_behavior_path_start_planner_module/images/freespace_pull_out.png diff --git a/planning/behavior_path_start_planner_module/images/geometric_pull_out.drawio.svg b/planning/autoware_behavior_path_start_planner_module/images/geometric_pull_out.drawio.svg similarity index 100% rename from planning/behavior_path_start_planner_module/images/geometric_pull_out.drawio.svg rename to planning/autoware_behavior_path_start_planner_module/images/geometric_pull_out.drawio.svg diff --git a/planning/behavior_path_start_planner_module/images/geometric_pull_out_path.drawio.svg b/planning/autoware_behavior_path_start_planner_module/images/geometric_pull_out_path.drawio.svg similarity index 100% rename from planning/behavior_path_start_planner_module/images/geometric_pull_out_path.drawio.svg rename to planning/autoware_behavior_path_start_planner_module/images/geometric_pull_out_path.drawio.svg diff --git a/planning/behavior_path_start_planner_module/images/geometric_pull_out_path_with_back.drawio.svg b/planning/autoware_behavior_path_start_planner_module/images/geometric_pull_out_path_with_back.drawio.svg similarity index 100% rename from planning/behavior_path_start_planner_module/images/geometric_pull_out_path_with_back.drawio.svg rename to planning/autoware_behavior_path_start_planner_module/images/geometric_pull_out_path_with_back.drawio.svg diff --git a/planning/behavior_path_start_planner_module/images/priority_order.drawio.svg b/planning/autoware_behavior_path_start_planner_module/images/priority_order.drawio.svg similarity index 100% rename from planning/behavior_path_start_planner_module/images/priority_order.drawio.svg rename to planning/autoware_behavior_path_start_planner_module/images/priority_order.drawio.svg diff --git a/planning/behavior_path_start_planner_module/images/pull_out_after_back.drawio.svg b/planning/autoware_behavior_path_start_planner_module/images/pull_out_after_back.drawio.svg similarity index 100% rename from planning/behavior_path_start_planner_module/images/pull_out_after_back.drawio.svg rename to planning/autoware_behavior_path_start_planner_module/images/pull_out_after_back.drawio.svg diff --git a/planning/behavior_path_start_planner_module/images/pull_out_collision_check.drawio.svg b/planning/autoware_behavior_path_start_planner_module/images/pull_out_collision_check.drawio.svg similarity index 100% rename from planning/behavior_path_start_planner_module/images/pull_out_collision_check.drawio.svg rename to planning/autoware_behavior_path_start_planner_module/images/pull_out_collision_check.drawio.svg diff --git a/planning/behavior_path_start_planner_module/images/shift_pull_out.drawio.svg b/planning/autoware_behavior_path_start_planner_module/images/shift_pull_out.drawio.svg similarity index 100% rename from planning/behavior_path_start_planner_module/images/shift_pull_out.drawio.svg rename to planning/autoware_behavior_path_start_planner_module/images/shift_pull_out.drawio.svg diff --git a/planning/behavior_path_start_planner_module/images/shift_pull_out_path.drawio.svg b/planning/autoware_behavior_path_start_planner_module/images/shift_pull_out_path.drawio.svg similarity index 100% rename from planning/behavior_path_start_planner_module/images/shift_pull_out_path.drawio.svg rename to planning/autoware_behavior_path_start_planner_module/images/shift_pull_out_path.drawio.svg diff --git a/planning/behavior_path_start_planner_module/images/shift_pull_out_path_from_road_lane.drawio.svg b/planning/autoware_behavior_path_start_planner_module/images/shift_pull_out_path_from_road_lane.drawio.svg similarity index 100% rename from planning/behavior_path_start_planner_module/images/shift_pull_out_path_from_road_lane.drawio.svg rename to planning/autoware_behavior_path_start_planner_module/images/shift_pull_out_path_from_road_lane.drawio.svg diff --git a/planning/behavior_path_start_planner_module/images/shift_pull_out_path_with_back.drawio.svg b/planning/autoware_behavior_path_start_planner_module/images/shift_pull_out_path_with_back.drawio.svg similarity index 100% rename from planning/behavior_path_start_planner_module/images/shift_pull_out_path_with_back.drawio.svg rename to planning/autoware_behavior_path_start_planner_module/images/shift_pull_out_path_with_back.drawio.svg diff --git a/planning/behavior_path_start_planner_module/images/start_planner_example.png b/planning/autoware_behavior_path_start_planner_module/images/start_planner_example.png similarity index 100% rename from planning/behavior_path_start_planner_module/images/start_planner_example.png rename to planning/autoware_behavior_path_start_planner_module/images/start_planner_example.png diff --git a/planning/behavior_path_start_planner_module/images/start_pose_candidate.drawio.svg b/planning/autoware_behavior_path_start_planner_module/images/start_pose_candidate.drawio.svg similarity index 100% rename from planning/behavior_path_start_planner_module/images/start_pose_candidate.drawio.svg rename to planning/autoware_behavior_path_start_planner_module/images/start_pose_candidate.drawio.svg diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/data_structs.hpp similarity index 95% rename from planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp rename to planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/data_structs.hpp index d8b94bb33d00b..95c98c3c89733 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/data_structs.hpp @@ -13,8 +13,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__DATA_STRUCTS_HPP_ -#define BEHAVIOR_PATH_START_PLANNER_MODULE__DATA_STRUCTS_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__DATA_STRUCTS_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__DATA_STRUCTS_HPP_ #include "autoware_behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include "autoware_behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" @@ -134,4 +134,4 @@ struct StartPlannerParameters } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__DATA_STRUCTS_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/debug.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/debug.hpp similarity index 80% rename from planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/debug.hpp rename to planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/debug.hpp index 6aa5584807d90..c252a8f22eda5 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/debug.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/debug.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__DEBUG_HPP_ -#define BEHAVIOR_PATH_START_PLANNER_MODULE__DEBUG_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__DEBUG_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__DEBUG_HPP_ -#include "behavior_path_start_planner_module/data_structs.hpp" +#include "autoware_behavior_path_start_planner_module/data_structs.hpp" #include #include @@ -36,4 +36,4 @@ void updateSafetyCheckDebugData( } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__DEBUG_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__DEBUG_HPP_ diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/freespace_pull_out.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/freespace_pull_out.hpp similarity index 83% rename from planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/freespace_pull_out.hpp rename to planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/freespace_pull_out.hpp index 561ef337fa68c..df640b04e5a72 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/freespace_pull_out.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/freespace_pull_out.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__FREESPACE_PULL_OUT_HPP_ -#define BEHAVIOR_PATH_START_PLANNER_MODULE__FREESPACE_PULL_OUT_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__FREESPACE_PULL_OUT_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__FREESPACE_PULL_OUT_HPP_ -#include "behavior_path_start_planner_module/pull_out_planner_base.hpp" +#include "autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp" #include #include @@ -49,4 +49,4 @@ class FreespacePullOut : public PullOutPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__FREESPACE_PULL_OUT_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__FREESPACE_PULL_OUT_HPP_ diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/geometric_pull_out.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/geometric_pull_out.hpp similarity index 79% rename from planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/geometric_pull_out.hpp rename to planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/geometric_pull_out.hpp index ccf9e933f9383..5edde96ea4abf 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/geometric_pull_out.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/geometric_pull_out.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__GEOMETRIC_PULL_OUT_HPP_ -#define BEHAVIOR_PATH_START_PLANNER_MODULE__GEOMETRIC_PULL_OUT_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__GEOMETRIC_PULL_OUT_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__GEOMETRIC_PULL_OUT_HPP_ #include "autoware_behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" -#include "behavior_path_start_planner_module/pull_out_path.hpp" -#include "behavior_path_start_planner_module/pull_out_planner_base.hpp" +#include "autoware_behavior_path_start_planner_module/pull_out_path.hpp" +#include "autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp" #include @@ -43,4 +43,4 @@ class GeometricPullOut : public PullOutPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__GEOMETRIC_PULL_OUT_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__GEOMETRIC_PULL_OUT_HPP_ diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/manager.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/manager.hpp similarity index 84% rename from planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/manager.hpp rename to planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/manager.hpp index ac752918a0e32..a7fcd6d820202 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/manager.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/manager.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__MANAGER_HPP_ -#define BEHAVIOR_PATH_START_PLANNER_MODULE__MANAGER_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__MANAGER_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__MANAGER_HPP_ #include "autoware_behavior_path_planner_common/interface/scene_module_manager_interface.hpp" -#include "behavior_path_start_planner_module/start_planner_module.hpp" +#include "autoware_behavior_path_start_planner_module/start_planner_module.hpp" #include @@ -53,4 +53,4 @@ class StartPlannerModuleManager : public SceneModuleManagerInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__MANAGER_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_path.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/pull_out_path.hpp similarity index 83% rename from planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_path.hpp rename to planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/pull_out_path.hpp index f7f443c297c61..5674087cdb3df 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_path.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/pull_out_path.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PATH_HPP_ -#define BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PATH_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PATH_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PATH_HPP_ #include "autoware_behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -34,4 +34,4 @@ struct PullOutPath Pose end_pose{}; }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PATH_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PATH_HPP_ diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp similarity index 89% rename from planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp rename to planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp index f2c437883b8a1..8cbe3569d13fe 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_ -#define BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_ #include "autoware_behavior_path_planner_common/data_manager.hpp" #include "autoware_behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" -#include "behavior_path_start_planner_module/data_structs.hpp" -#include "behavior_path_start_planner_module/pull_out_path.hpp" -#include "behavior_path_start_planner_module/util.hpp" +#include "autoware_behavior_path_start_planner_module/data_structs.hpp" +#include "autoware_behavior_path_start_planner_module/pull_out_path.hpp" +#include "autoware_behavior_path_start_planner_module/util.hpp" #include #include @@ -102,4 +102,4 @@ class PullOutPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_ diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/shift_pull_out.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/shift_pull_out.hpp similarity index 85% rename from planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/shift_pull_out.hpp rename to planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/shift_pull_out.hpp index 3bded7ee99fbb..3092ca4f80e3f 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/shift_pull_out.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/shift_pull_out.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__SHIFT_PULL_OUT_HPP_ -#define BEHAVIOR_PATH_START_PLANNER_MODULE__SHIFT_PULL_OUT_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__SHIFT_PULL_OUT_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__SHIFT_PULL_OUT_HPP_ -#include "behavior_path_start_planner_module/pull_out_path.hpp" -#include "behavior_path_start_planner_module/pull_out_planner_base.hpp" +#include "autoware_behavior_path_start_planner_module/pull_out_path.hpp" +#include "autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp" #include @@ -61,4 +61,4 @@ class ShiftPullOut : public PullOutPlannerBase }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__SHIFT_PULL_OUT_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__SHIFT_PULL_OUT_HPP_ diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/start_planner_module.hpp similarity index 95% rename from planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp rename to planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/start_planner_module.hpp index c8e74009d267a..1883e10af3c62 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/start_planner_module.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_MODULE_HPP_ -#define BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_MODULE_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_MODULE_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_MODULE_HPP_ #include "autoware_behavior_path_planner_common/interface/scene_module_interface.hpp" #include "autoware_behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" @@ -21,11 +21,11 @@ #include "autoware_behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "autoware_behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" #include "autoware_behavior_path_planner_common/utils/utils.hpp" -#include "behavior_path_start_planner_module/data_structs.hpp" -#include "behavior_path_start_planner_module/freespace_pull_out.hpp" -#include "behavior_path_start_planner_module/geometric_pull_out.hpp" -#include "behavior_path_start_planner_module/pull_out_path.hpp" -#include "behavior_path_start_planner_module/shift_pull_out.hpp" +#include "autoware_behavior_path_start_planner_module/data_structs.hpp" +#include "autoware_behavior_path_start_planner_module/freespace_pull_out.hpp" +#include "autoware_behavior_path_start_planner_module/geometric_pull_out.hpp" +#include "autoware_behavior_path_start_planner_module/pull_out_path.hpp" +#include "autoware_behavior_path_start_planner_module/shift_pull_out.hpp" #include #include @@ -336,4 +336,4 @@ class StartPlannerModule : public SceneModuleInterface }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_MODULE_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_MODULE_HPP_ diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/util.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/util.hpp similarity index 89% rename from planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/util.hpp rename to planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/util.hpp index 9185873cfd770..b9f0b964ed428 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/util.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/util.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__UTIL_HPP_ -#define BEHAVIOR_PATH_START_PLANNER_MODULE__UTIL_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__UTIL_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__UTIL_HPP_ #include "autoware_behavior_path_planner_common/data_manager.hpp" #include "autoware_behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "autoware_behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "autoware_behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" -#include "behavior_path_start_planner_module/pull_out_path.hpp" +#include "autoware_behavior_path_start_planner_module/pull_out_path.hpp" #include @@ -55,4 +55,4 @@ std::optional extractCollisionCheckSection( const PullOutPath & path, const double collision_check_distance_from_end); } // namespace behavior_path_planner::start_planner_utils -#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__UTIL_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_START_PLANNER_MODULE__UTIL_HPP_ diff --git a/planning/behavior_path_start_planner_module/package.xml b/planning/autoware_behavior_path_start_planner_module/package.xml similarity index 91% rename from planning/behavior_path_start_planner_module/package.xml rename to planning/autoware_behavior_path_start_planner_module/package.xml index 23c57b6d6024a..8504241c908ce 100644 --- a/planning/behavior_path_start_planner_module/package.xml +++ b/planning/autoware_behavior_path_start_planner_module/package.xml @@ -1,9 +1,9 @@ - behavior_path_start_planner_module + autoware_behavior_path_start_planner_module 0.1.0 - The behavior_path_start_planner_module package + The autoware_behavior_path_start_planner_module package Kosuke Takeuchi Kyoichi Sugahara diff --git a/planning/behavior_path_start_planner_module/plugins.xml b/planning/autoware_behavior_path_start_planner_module/plugins.xml similarity index 70% rename from planning/behavior_path_start_planner_module/plugins.xml rename to planning/autoware_behavior_path_start_planner_module/plugins.xml index fde8b673be5bc..92498d5158ae5 100644 --- a/planning/behavior_path_start_planner_module/plugins.xml +++ b/planning/autoware_behavior_path_start_planner_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/behavior_path_start_planner_module/src/debug.cpp b/planning/autoware_behavior_path_start_planner_module/src/debug.cpp similarity index 94% rename from planning/behavior_path_start_planner_module/src/debug.cpp rename to planning/autoware_behavior_path_start_planner_module/src/debug.cpp index 0f95470d86d40..4b4aa7c386925 100644 --- a/planning/behavior_path_start_planner_module/src/debug.cpp +++ b/planning/autoware_behavior_path_start_planner_module/src/debug.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_start_planner_module/debug.hpp" +#include "autoware_behavior_path_start_planner_module/debug.hpp" namespace behavior_path_planner { diff --git a/planning/behavior_path_start_planner_module/src/freespace_pull_out.cpp b/planning/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp similarity index 97% rename from planning/behavior_path_start_planner_module/src/freespace_pull_out.cpp rename to planning/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp index d29047d23fffd..1dfacd45b5218 100644 --- a/planning/behavior_path_start_planner_module/src/freespace_pull_out.cpp +++ b/planning/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_start_planner_module/freespace_pull_out.hpp" +#include "autoware_behavior_path_start_planner_module/freespace_pull_out.hpp" #include "autoware_behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "autoware_behavior_path_planner_common/utils/path_utils.hpp" #include "autoware_behavior_path_planner_common/utils/utils.hpp" -#include "behavior_path_start_planner_module/util.hpp" +#include "autoware_behavior_path_start_planner_module/util.hpp" #include diff --git a/planning/behavior_path_start_planner_module/src/geometric_pull_out.cpp b/planning/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp similarity index 97% rename from planning/behavior_path_start_planner_module/src/geometric_pull_out.cpp rename to planning/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp index 18d02ade489e8..86d7de246c312 100644 --- a/planning/behavior_path_start_planner_module/src/geometric_pull_out.cpp +++ b/planning/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_start_planner_module/geometric_pull_out.hpp" +#include "autoware_behavior_path_start_planner_module/geometric_pull_out.hpp" #include "autoware_behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "autoware_behavior_path_planner_common/utils/path_utils.hpp" #include "autoware_behavior_path_planner_common/utils/utils.hpp" -#include "behavior_path_start_planner_module/util.hpp" +#include "autoware_behavior_path_start_planner_module/util.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include diff --git a/planning/behavior_path_start_planner_module/src/manager.cpp b/planning/autoware_behavior_path_start_planner_module/src/manager.cpp similarity index 99% rename from planning/behavior_path_start_planner_module/src/manager.cpp rename to planning/autoware_behavior_path_start_planner_module/src/manager.cpp index d5731f54224b6..23cca1ef05190 100644 --- a/planning/behavior_path_start_planner_module/src/manager.cpp +++ b/planning/autoware_behavior_path_start_planner_module/src/manager.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_start_planner_module/manager.hpp" +#include "autoware_behavior_path_start_planner_module/manager.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" diff --git a/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp b/planning/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp similarity index 99% rename from planning/behavior_path_start_planner_module/src/shift_pull_out.cpp rename to planning/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp index 298510126a4c3..d0a7b827a2285 100644 --- a/planning/behavior_path_start_planner_module/src/shift_pull_out.cpp +++ b/planning/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_start_planner_module/shift_pull_out.hpp" +#include "autoware_behavior_path_start_planner_module/shift_pull_out.hpp" #include "autoware_behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "autoware_behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "autoware_behavior_path_planner_common/utils/path_utils.hpp" #include "autoware_behavior_path_planner_common/utils/utils.hpp" -#include "behavior_path_start_planner_module/util.hpp" +#include "autoware_behavior_path_start_planner_module/util.hpp" #include "motion_utils/trajectory/path_with_lane_id.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp similarity index 99% rename from planning/behavior_path_start_planner_module/src/start_planner_module.cpp rename to planning/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index 82a4709c6b5be..c13afdf2b86df 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_start_planner_module/start_planner_module.hpp" +#include "autoware_behavior_path_start_planner_module/start_planner_module.hpp" #include "autoware_behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "autoware_behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "autoware_behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "autoware_behavior_path_planner_common/utils/path_utils.hpp" -#include "behavior_path_start_planner_module/debug.hpp" -#include "behavior_path_start_planner_module/util.hpp" +#include "autoware_behavior_path_start_planner_module/debug.hpp" +#include "autoware_behavior_path_start_planner_module/util.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include diff --git a/planning/behavior_path_start_planner_module/src/util.cpp b/planning/autoware_behavior_path_start_planner_module/src/util.cpp similarity index 98% rename from planning/behavior_path_start_planner_module/src/util.cpp rename to planning/autoware_behavior_path_start_planner_module/src/util.cpp index b1bcf59db86cb..51a6093936154 100644 --- a/planning/behavior_path_start_planner_module/src/util.cpp +++ b/planning/autoware_behavior_path_start_planner_module/src/util.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_start_planner_module/util.hpp" +#include "autoware_behavior_path_start_planner_module/util.hpp" #include "autoware_behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" #include "autoware_behavior_path_planner_common/utils/path_utils.hpp" diff --git a/planning/behavior_path_planner/README.md b/planning/behavior_path_planner/README.md index 08a3570b1a271..70190731ac1a7 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -33,7 +33,7 @@ Behavior Path Planner has following scene modules | Lane Change | this module is performed when it is necessary and a collision check with other vehicles is cleared. | [LINK](../behavior_path_lane_change_module/README.md) | | External Lane Change | WIP | LINK | | Goal Planner | this module is performed when ego-vehicle is in the road lane and goal is in the shoulder lane. ego-vehicle will stop at the goal. | [LINK](../behavior_path_goal_planner_module/README.md) | -| Start Planner | this module is performed when ego-vehicle is stationary and footprint of ego-vehicle is included in shoulder lane. This module ends when ego-vehicle merges into the road. | [LINK](../behavior_path_start_planner_module/README.md) | +| Start Planner | this module is performed when ego-vehicle is stationary and footprint of ego-vehicle is included in shoulder lane. This module ends when ego-vehicle merges into the road. | [LINK](../autoware_behavior_path_start_planner_module/README.md) | | Side Shift | (for remote control) shift the path to left or right according to an external instruction. | [LINK](../autoware_behavior_path_side_shift_module/README.md) | !!! Note From ce0fcf5608757fbb4429a20258e7523e4992f8ff Mon Sep 17 00:00:00 2001 From: Zhe Shen <80969277+HansOersted@users.noreply.github.com> Date: Fri, 7 Jun 2024 15:30:16 +0900 Subject: [PATCH 11/65] refactor(mpc_lateral_controller, trajectory_follower_node)!: prefix package and namespace with autoware (#7306) * add the prefix to the folder Signed-off-by: Zhe Shen * named to autoware_mpc_lateral_controller Signed-off-by: Zhe Shen * rename the folder in the include Signed-off-by: Zhe Shen * correct the package name in xml and CMakeLists Signed-off-by: Zhe Shen * correct the namespace and include Signed-off-by: Zhe Shen * change namespace and include in src/ Signed-off-by: Zhe Shen * change namespace and include in test/ Signed-off-by: Zhe Shen * fix the trajectory_follower_node Signed-off-by: Zhe Shen * undo rename to the namespace Signed-off-by: Zhe Shen * change the trajectory_follower_node, Controller.drawio.svg, and README.md Signed-off-by: Zhe Shen * fixed by pre-commit Signed-off-by: Zhe Shen * suppress the unnecessary line length detect Signed-off-by: Zhe Shen --------- Signed-off-by: Zhe Shen --- .../CMakeLists.txt | 2 +- .../README.md | 0 .../image/vehicle_error_kinematics.png | Bin .../image/vehicle_kinematics.png | Bin .../lowpass_filter.hpp | 6 +++--- .../autoware_mpc_lateral_controller}/mpc.hpp | 18 +++++++++--------- .../mpc_lateral_controller.hpp | 14 +++++++------- .../mpc_trajectory.hpp | 6 +++--- .../mpc_utils.hpp | 8 ++++---- .../qp_solver/qp_solver_interface.hpp | 6 +++--- .../qp_solver/qp_solver_osqp.hpp | 8 ++++---- .../qp_solver/qp_solver_unconstraint_fast.hpp | 8 ++++---- .../steering_offset/steering_offset.hpp | 6 +++--- .../steering_predictor.hpp | 6 +++--- .../vehicle_model_bicycle_dynamics.hpp | 8 ++++---- .../vehicle_model_bicycle_kinematics.hpp | 8 ++++---- ...icle_model_bicycle_kinematics_no_delay.hpp | 10 ++++++---- .../vehicle_model/vehicle_model_interface.hpp | 8 ++++---- .../model_predictive_control_algorithm.md | 0 .../package.xml | 2 +- .../lateral_controller_defaults.param.yaml | 0 .../src/lowpass_filter.cpp | 2 +- .../src/mpc.cpp | 4 ++-- .../src/mpc_lateral_controller.cpp | 12 ++++++------ .../src/mpc_trajectory.cpp | 2 +- .../src/mpc_utils.cpp | 2 +- .../src/qp_solver/qp_solver_osqp.cpp | 2 +- .../qp_solver/qp_solver_unconstraint_fast.cpp | 2 +- .../src/steering_offset/steering_offset.cpp | 2 +- .../src/steering_predictor.cpp | 2 +- .../vehicle_model_bicycle_dynamics.cpp | 2 +- .../vehicle_model_bicycle_kinematics.cpp | 2 +- ...icle_model_bicycle_kinematics_no_delay.cpp | 2 +- .../vehicle_model/vehicle_model_interface.cpp | 2 +- .../test/test_lowpass_filter.cpp | 2 +- .../test/test_mpc.cpp | 12 ++++++------ .../test/test_mpc_utils.cpp | 4 ++-- control/trajectory_follower_node/README.md | 2 +- .../design/media/Controller.drawio.svg | 2 +- control/trajectory_follower_node/package.xml | 2 +- .../src/controller_node.cpp | 2 +- .../test/test_controller_node.cpp | 2 +- 42 files changed, 96 insertions(+), 94 deletions(-) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/CMakeLists.txt (96%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/README.md (100%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/image/vehicle_error_kinematics.png (100%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/image/vehicle_kinematics.png (100%) rename control/{mpc_lateral_controller/include/mpc_lateral_controller => autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller}/lowpass_filter.hpp (95%) rename control/{mpc_lateral_controller/include/mpc_lateral_controller => autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller}/mpc.hpp (97%) rename control/{mpc_lateral_controller/include/mpc_lateral_controller => autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller}/mpc_lateral_controller.hpp (95%) rename control/{mpc_lateral_controller/include/mpc_lateral_controller => autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller}/mpc_trajectory.hpp (95%) rename control/{mpc_lateral_controller/include/mpc_lateral_controller => autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller}/mpc_utils.hpp (97%) rename control/{mpc_lateral_controller/include/mpc_lateral_controller => autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller}/qp_solver/qp_solver_interface.hpp (89%) rename control/{mpc_lateral_controller/include/mpc_lateral_controller => autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller}/qp_solver/qp_solver_osqp.hpp (88%) rename control/{mpc_lateral_controller/include/mpc_lateral_controller => autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller}/qp_solver/qp_solver_unconstraint_fast.hpp (87%) rename control/{mpc_lateral_controller/include/mpc_lateral_controller => autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller}/steering_offset/steering_offset.hpp (84%) rename control/{mpc_lateral_controller/include/mpc_lateral_controller => autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller}/steering_predictor.hpp (92%) rename control/{mpc_lateral_controller/include/mpc_lateral_controller => autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller}/vehicle_model/vehicle_model_bicycle_dynamics.hpp (92%) rename control/{mpc_lateral_controller/include/mpc_lateral_controller => autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller}/vehicle_model/vehicle_model_bicycle_kinematics.hpp (90%) rename control/{mpc_lateral_controller/include/mpc_lateral_controller => autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller}/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp (87%) rename control/{mpc_lateral_controller/include/mpc_lateral_controller => autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller}/vehicle_model/vehicle_model_interface.hpp (93%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/model_predictive_control_algorithm.md (100%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/package.xml (97%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/param/lateral_controller_defaults.param.yaml (100%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/src/lowpass_filter.cpp (98%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/src/mpc.cpp (99%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/src/mpc_lateral_controller.cpp (98%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/src/mpc_trajectory.cpp (97%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/src/mpc_utils.cpp (99%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/src/qp_solver/qp_solver_osqp.cpp (97%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/src/qp_solver/qp_solver_unconstraint_fast.cpp (93%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/src/steering_offset/steering_offset.cpp (95%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/src/steering_predictor.cpp (98%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/src/vehicle_model/vehicle_model_bicycle_dynamics.cpp (98%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/src/vehicle_model/vehicle_model_bicycle_kinematics.cpp (98%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/src/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.cpp (98%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/src/vehicle_model/vehicle_model_interface.cpp (94%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/test/test_lowpass_filter.cpp (98%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/test/test_mpc.cpp (97%) rename control/{mpc_lateral_controller => autoware_mpc_lateral_controller}/test/test_mpc_utils.cpp (95%) diff --git a/control/mpc_lateral_controller/CMakeLists.txt b/control/autoware_mpc_lateral_controller/CMakeLists.txt similarity index 96% rename from control/mpc_lateral_controller/CMakeLists.txt rename to control/autoware_mpc_lateral_controller/CMakeLists.txt index e4a3683ea1fdc..dff85d70419a1 100644 --- a/control/mpc_lateral_controller/CMakeLists.txt +++ b/control/autoware_mpc_lateral_controller/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(mpc_lateral_controller) +project(autoware_mpc_lateral_controller) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/control/mpc_lateral_controller/README.md b/control/autoware_mpc_lateral_controller/README.md similarity index 100% rename from control/mpc_lateral_controller/README.md rename to control/autoware_mpc_lateral_controller/README.md diff --git a/control/mpc_lateral_controller/image/vehicle_error_kinematics.png b/control/autoware_mpc_lateral_controller/image/vehicle_error_kinematics.png similarity index 100% rename from control/mpc_lateral_controller/image/vehicle_error_kinematics.png rename to control/autoware_mpc_lateral_controller/image/vehicle_error_kinematics.png diff --git a/control/mpc_lateral_controller/image/vehicle_kinematics.png b/control/autoware_mpc_lateral_controller/image/vehicle_kinematics.png similarity index 100% rename from control/mpc_lateral_controller/image/vehicle_kinematics.png rename to control/autoware_mpc_lateral_controller/image/vehicle_kinematics.png diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/lowpass_filter.hpp b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/lowpass_filter.hpp similarity index 95% rename from control/mpc_lateral_controller/include/mpc_lateral_controller/lowpass_filter.hpp rename to control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/lowpass_filter.hpp index 227bd0594312b..73cef7cddda39 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/lowpass_filter.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/lowpass_filter.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MPC_LATERAL_CONTROLLER__LOWPASS_FILTER_HPP_ -#define MPC_LATERAL_CONTROLLER__LOWPASS_FILTER_HPP_ +#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__LOWPASS_FILTER_HPP_ +#define AUTOWARE_MPC_LATERAL_CONTROLLER__LOWPASS_FILTER_HPP_ #include #include @@ -102,4 +102,4 @@ namespace MoveAverageFilter bool filt_vector(const int num, std::vector & u); } // namespace MoveAverageFilter } // namespace autoware::motion::control::mpc_lateral_controller -#endif // MPC_LATERAL_CONTROLLER__LOWPASS_FILTER_HPP_ +#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__LOWPASS_FILTER_HPP_ diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/mpc.hpp similarity index 97% rename from control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp rename to control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/mpc.hpp index 91b803dea36fa..03abae66e4986 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/mpc.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MPC_LATERAL_CONTROLLER__MPC_HPP_ -#define MPC_LATERAL_CONTROLLER__MPC_HPP_ - -#include "mpc_lateral_controller/lowpass_filter.hpp" -#include "mpc_lateral_controller/mpc_trajectory.hpp" -#include "mpc_lateral_controller/qp_solver/qp_solver_interface.hpp" -#include "mpc_lateral_controller/steering_predictor.hpp" -#include "mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp" +#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_HPP_ +#define AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_HPP_ + +#include "autoware_mpc_lateral_controller/lowpass_filter.hpp" +#include "autoware_mpc_lateral_controller/mpc_trajectory.hpp" +#include "autoware_mpc_lateral_controller/qp_solver/qp_solver_interface.hpp" +#include "autoware_mpc_lateral_controller/steering_predictor.hpp" +#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp" #include "rclcpp/rclcpp.hpp" #include "autoware_control_msgs/msg/lateral.hpp" @@ -525,4 +525,4 @@ class MPC }; // class MPC } // namespace autoware::motion::control::mpc_lateral_controller -#endif // MPC_LATERAL_CONTROLLER__MPC_HPP_ +#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_HPP_ diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/mpc_lateral_controller.hpp similarity index 95% rename from control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp rename to control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/mpc_lateral_controller.hpp index eb1d75f9508b3..e0775e1d09def 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_lateral_controller.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/mpc_lateral_controller.hpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MPC_LATERAL_CONTROLLER__MPC_LATERAL_CONTROLLER_HPP_ -#define MPC_LATERAL_CONTROLLER__MPC_LATERAL_CONTROLLER_HPP_ +#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_LATERAL_CONTROLLER_HPP_ +#define AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_LATERAL_CONTROLLER_HPP_ -#include "mpc_lateral_controller/mpc.hpp" -#include "mpc_lateral_controller/mpc_trajectory.hpp" -#include "mpc_lateral_controller/mpc_utils.hpp" -#include "mpc_lateral_controller/steering_offset/steering_offset.hpp" +#include "autoware_mpc_lateral_controller/mpc.hpp" +#include "autoware_mpc_lateral_controller/mpc_trajectory.hpp" +#include "autoware_mpc_lateral_controller/mpc_utils.hpp" +#include "autoware_mpc_lateral_controller/steering_offset/steering_offset.hpp" #include "rclcpp/rclcpp.hpp" #include "trajectory_follower_base/lateral_controller_base.hpp" @@ -281,4 +281,4 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase }; } // namespace autoware::motion::control::mpc_lateral_controller -#endif // MPC_LATERAL_CONTROLLER__MPC_LATERAL_CONTROLLER_HPP_ +#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_LATERAL_CONTROLLER_HPP_ diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_trajectory.hpp b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/mpc_trajectory.hpp similarity index 95% rename from control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_trajectory.hpp rename to control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/mpc_trajectory.hpp index eb624f39ae76b..4a0ae16bc9b1c 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_trajectory.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/mpc_trajectory.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MPC_LATERAL_CONTROLLER__MPC_TRAJECTORY_HPP_ -#define MPC_LATERAL_CONTROLLER__MPC_TRAJECTORY_HPP_ +#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_TRAJECTORY_HPP_ +#define AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_TRAJECTORY_HPP_ #include "tier4_autoware_utils/geometry/geometry.hpp" @@ -125,4 +125,4 @@ class MPCTrajectory } }; } // namespace autoware::motion::control::mpc_lateral_controller -#endif // MPC_LATERAL_CONTROLLER__MPC_TRAJECTORY_HPP_ +#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_TRAJECTORY_HPP_ diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_utils.hpp b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/mpc_utils.hpp similarity index 97% rename from control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_utils.hpp rename to control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/mpc_utils.hpp index 819d7fb89b8a7..e97a004438e4b 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/mpc_utils.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/mpc_utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MPC_LATERAL_CONTROLLER__MPC_UTILS_HPP_ -#define MPC_LATERAL_CONTROLLER__MPC_UTILS_HPP_ +#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_UTILS_HPP_ +#define AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_UTILS_HPP_ #include "rclcpp/rclcpp.hpp" #include "tf2/utils.h" @@ -26,7 +26,7 @@ #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #endif -#include "mpc_lateral_controller/mpc_trajectory.hpp" +#include "autoware_mpc_lateral_controller/mpc_trajectory.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_planning_msgs/msg/trajectory_point.hpp" @@ -230,4 +230,4 @@ void update_param( } // namespace MPCUtils } // namespace autoware::motion::control::mpc_lateral_controller -#endif // MPC_LATERAL_CONTROLLER__MPC_UTILS_HPP_ +#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__MPC_UTILS_HPP_ diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_interface.hpp b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/qp_solver/qp_solver_interface.hpp similarity index 89% rename from control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_interface.hpp rename to control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/qp_solver/qp_solver_interface.hpp index ca30bd30e4dd1..6447437d6c274 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_interface.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/qp_solver/qp_solver_interface.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_INTERFACE_HPP_ -#define MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_INTERFACE_HPP_ +#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_INTERFACE_HPP_ +#define AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_INTERFACE_HPP_ #include @@ -51,4 +51,4 @@ class QPSolverInterface virtual double getObjVal() const { return 0.0; } }; } // namespace autoware::motion::control::mpc_lateral_controller -#endif // MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_INTERFACE_HPP_ +#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_INTERFACE_HPP_ diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp similarity index 88% rename from control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp rename to control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp index 2611f94da324f..8c81092960097 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_OSQP_HPP_ -#define MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_OSQP_HPP_ +#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_OSQP_HPP_ +#define AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_OSQP_HPP_ -#include "mpc_lateral_controller/qp_solver/qp_solver_interface.hpp" +#include "autoware_mpc_lateral_controller/qp_solver/qp_solver_interface.hpp" #include "osqp_interface/osqp_interface.hpp" #include "rclcpp/rclcpp.hpp" @@ -62,4 +62,4 @@ class QPSolverOSQP : public QPSolverInterface rclcpp::Logger logger_; }; } // namespace autoware::motion::control::mpc_lateral_controller -#endif // MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_OSQP_HPP_ +#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_OSQP_HPP_ diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp similarity index 87% rename from control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp rename to control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp index ef337eaaa8528..15c8137b78890 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_ -#define MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_ +#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_ +#define AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_ -#include "mpc_lateral_controller/qp_solver/qp_solver_interface.hpp" +#include "autoware_mpc_lateral_controller/qp_solver/qp_solver_interface.hpp" namespace autoware::motion::control::mpc_lateral_controller { @@ -62,4 +62,4 @@ class QPSolverEigenLeastSquareLLT : public QPSolverInterface private: }; } // namespace autoware::motion::control::mpc_lateral_controller -#endif // MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_ +#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__QP_SOLVER__QP_SOLVER_UNCONSTRAINT_FAST_HPP_ diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/steering_offset/steering_offset.hpp b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/steering_offset/steering_offset.hpp similarity index 84% rename from control/mpc_lateral_controller/include/mpc_lateral_controller/steering_offset/steering_offset.hpp rename to control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/steering_offset/steering_offset.hpp index 494961ef679d2..707c1ce56a9a6 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/steering_offset/steering_offset.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/steering_offset/steering_offset.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MPC_LATERAL_CONTROLLER__STEERING_OFFSET__STEERING_OFFSET_HPP_ -#define MPC_LATERAL_CONTROLLER__STEERING_OFFSET__STEERING_OFFSET_HPP_ +#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__STEERING_OFFSET__STEERING_OFFSET_HPP_ +#define AUTOWARE_MPC_LATERAL_CONTROLLER__STEERING_OFFSET__STEERING_OFFSET_HPP_ #include @@ -45,4 +45,4 @@ class SteeringOffsetEstimator double steering_offset_ = 0.0; }; -#endif // MPC_LATERAL_CONTROLLER__STEERING_OFFSET__STEERING_OFFSET_HPP_ +#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__STEERING_OFFSET__STEERING_OFFSET_HPP_ diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/steering_predictor.hpp b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/steering_predictor.hpp similarity index 92% rename from control/mpc_lateral_controller/include/mpc_lateral_controller/steering_predictor.hpp rename to control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/steering_predictor.hpp index 16e9b165fb1a5..0c5f04497d058 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/steering_predictor.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/steering_predictor.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MPC_LATERAL_CONTROLLER__STEERING_PREDICTOR_HPP_ -#define MPC_LATERAL_CONTROLLER__STEERING_PREDICTOR_HPP_ +#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__STEERING_PREDICTOR_HPP_ +#define AUTOWARE_MPC_LATERAL_CONTROLLER__STEERING_PREDICTOR_HPP_ #include "rclcpp/rclcpp.hpp" @@ -81,4 +81,4 @@ class SteeringPredictor } // namespace autoware::motion::control::mpc_lateral_controller -#endif // MPC_LATERAL_CONTROLLER__STEERING_PREDICTOR_HPP_ +#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__STEERING_PREDICTOR_HPP_ diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp similarity index 92% rename from control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp rename to control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp index 488a3c7ab8be2..20787b1f281b5 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp @@ -44,10 +44,10 @@ * Tracking", Robotics Institute, Carnegie Mellon University, February 2009. */ -#ifndef MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_DYNAMICS_HPP_ -#define MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_DYNAMICS_HPP_ +#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_DYNAMICS_HPP_ +#define AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_DYNAMICS_HPP_ -#include "mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp" +#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp" #include #include @@ -122,4 +122,4 @@ class DynamicsBicycleModel : public VehicleModelInterface double m_cr; //!< @brief rear cornering power [N/rad] }; } // namespace autoware::motion::control::mpc_lateral_controller -#endif // MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_DYNAMICS_HPP_ +#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_DYNAMICS_HPP_ diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp similarity index 90% rename from control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp rename to control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp index e2f66e95ab0e3..91d3ea826c7d3 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp @@ -38,10 +38,10 @@ * */ -#ifndef MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_HPP_ -#define MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_HPP_ +#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_HPP_ +#define AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_HPP_ -#include "mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp" +#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp" #include #include @@ -106,4 +106,4 @@ class KinematicsBicycleModel : public VehicleModelInterface double m_steer_tau; //!< @brief steering time constant for 1d-model [s] }; } // namespace autoware::motion::control::mpc_lateral_controller -#endif // MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_HPP_ +#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_HPP_ diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp similarity index 87% rename from control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp rename to control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp index b503ad8eb1d13..5731a2025d833 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp @@ -35,10 +35,10 @@ * */ -#ifndef MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_NO_DELAY_HPP_ -#define MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_NO_DELAY_HPP_ +#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_NO_DELAY_HPP_ // NOLINT +#define AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_NO_DELAY_HPP_ // NOLINT -#include "mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp" +#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp" #include #include @@ -101,4 +101,6 @@ class KinematicsBicycleModelNoDelay : public VehicleModelInterface double m_steer_lim; //!< @brief steering angle limit [rad] }; } // namespace autoware::motion::control::mpc_lateral_controller -#endif // MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_NO_DELAY_HPP_ +// clang-format off +#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_NO_DELAY_HPP_ // NOLINT +// clang-format on diff --git a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp similarity index 93% rename from control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp rename to control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp index 68806ff5a00dc..9e2d14184d5e7 100644 --- a/control/mpc_lateral_controller/include/mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware_mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_ -#define MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_ +#ifndef AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_ +#define AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_ -#include "mpc_lateral_controller/mpc_trajectory.hpp" +#include "autoware_mpc_lateral_controller/mpc_trajectory.hpp" #include @@ -149,4 +149,4 @@ class VehicleModelInterface const MPCTrajectory & reference_trajectory, const double dt) const = 0; }; } // namespace autoware::motion::control::mpc_lateral_controller -#endif // MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_ +#endif // AUTOWARE_MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_INTERFACE_HPP_ diff --git a/control/mpc_lateral_controller/model_predictive_control_algorithm.md b/control/autoware_mpc_lateral_controller/model_predictive_control_algorithm.md similarity index 100% rename from control/mpc_lateral_controller/model_predictive_control_algorithm.md rename to control/autoware_mpc_lateral_controller/model_predictive_control_algorithm.md diff --git a/control/mpc_lateral_controller/package.xml b/control/autoware_mpc_lateral_controller/package.xml similarity index 97% rename from control/mpc_lateral_controller/package.xml rename to control/autoware_mpc_lateral_controller/package.xml index 000bddc65aa1f..3e62d69f6ebb6 100644 --- a/control/mpc_lateral_controller/package.xml +++ b/control/autoware_mpc_lateral_controller/package.xml @@ -1,7 +1,7 @@ - mpc_lateral_controller + autoware_mpc_lateral_controller 1.0.0 MPC-based lateral controller diff --git a/control/mpc_lateral_controller/param/lateral_controller_defaults.param.yaml b/control/autoware_mpc_lateral_controller/param/lateral_controller_defaults.param.yaml similarity index 100% rename from control/mpc_lateral_controller/param/lateral_controller_defaults.param.yaml rename to control/autoware_mpc_lateral_controller/param/lateral_controller_defaults.param.yaml diff --git a/control/mpc_lateral_controller/src/lowpass_filter.cpp b/control/autoware_mpc_lateral_controller/src/lowpass_filter.cpp similarity index 98% rename from control/mpc_lateral_controller/src/lowpass_filter.cpp rename to control/autoware_mpc_lateral_controller/src/lowpass_filter.cpp index 8fbf3488c5a2e..e3bbe78e2428b 100644 --- a/control/mpc_lateral_controller/src/lowpass_filter.cpp +++ b/control/autoware_mpc_lateral_controller/src/lowpass_filter.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mpc_lateral_controller/lowpass_filter.hpp" +#include "autoware_mpc_lateral_controller/lowpass_filter.hpp" #include diff --git a/control/mpc_lateral_controller/src/mpc.cpp b/control/autoware_mpc_lateral_controller/src/mpc.cpp similarity index 99% rename from control/mpc_lateral_controller/src/mpc.cpp rename to control/autoware_mpc_lateral_controller/src/mpc.cpp index 177c1e0854bfb..e6fa2ce3c0102 100644 --- a/control/mpc_lateral_controller/src/mpc.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mpc_lateral_controller/mpc.hpp" +#include "autoware_mpc_lateral_controller/mpc.hpp" +#include "autoware_mpc_lateral_controller/mpc_utils.hpp" #include "interpolation/linear_interpolation.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "mpc_lateral_controller/mpc_utils.hpp" #include "rclcpp/rclcpp.hpp" #include "tier4_autoware_utils/math/unit_conversion.hpp" diff --git a/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp similarity index 98% rename from control/mpc_lateral_controller/src/mpc_lateral_controller.cpp rename to control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp index 85d33a5e9f1c0..3d66078eed1f2 100644 --- a/control/mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mpc_lateral_controller/mpc_lateral_controller.hpp" +#include "autoware_mpc_lateral_controller/mpc_lateral_controller.hpp" +#include "autoware_mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp" +#include "autoware_mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp" +#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp" +#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp" +#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp" -#include "mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp" -#include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp" -#include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp" -#include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp" #include "tf2/utils.h" #include "tf2_ros/create_timer_ros.h" #include "vehicle_info_util/vehicle_info_util.hpp" diff --git a/control/mpc_lateral_controller/src/mpc_trajectory.cpp b/control/autoware_mpc_lateral_controller/src/mpc_trajectory.cpp similarity index 97% rename from control/mpc_lateral_controller/src/mpc_trajectory.cpp rename to control/autoware_mpc_lateral_controller/src/mpc_trajectory.cpp index b7fed942375e8..e84e6cf79a25a 100644 --- a/control/mpc_lateral_controller/src/mpc_trajectory.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_trajectory.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mpc_lateral_controller/mpc_trajectory.hpp" +#include "autoware_mpc_lateral_controller/mpc_trajectory.hpp" namespace autoware::motion::control::mpc_lateral_controller { diff --git a/control/mpc_lateral_controller/src/mpc_utils.cpp b/control/autoware_mpc_lateral_controller/src/mpc_utils.cpp similarity index 99% rename from control/mpc_lateral_controller/src/mpc_utils.cpp rename to control/autoware_mpc_lateral_controller/src/mpc_utils.cpp index 01a81d9015b47..1a0062372eb22 100644 --- a/control/mpc_lateral_controller/src/mpc_utils.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_utils.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mpc_lateral_controller/mpc_utils.hpp" +#include "autoware_mpc_lateral_controller/mpc_utils.hpp" #include "interpolation/linear_interpolation.hpp" #include "interpolation/spline_interpolation.hpp" diff --git a/control/mpc_lateral_controller/src/qp_solver/qp_solver_osqp.cpp b/control/autoware_mpc_lateral_controller/src/qp_solver/qp_solver_osqp.cpp similarity index 97% rename from control/mpc_lateral_controller/src/qp_solver/qp_solver_osqp.cpp rename to control/autoware_mpc_lateral_controller/src/qp_solver/qp_solver_osqp.cpp index 7c76d67e75aa3..66981b0c5c6d4 100644 --- a/control/mpc_lateral_controller/src/qp_solver/qp_solver_osqp.cpp +++ b/control/autoware_mpc_lateral_controller/src/qp_solver/qp_solver_osqp.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp" +#include "autoware_mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp" #include #include diff --git a/control/mpc_lateral_controller/src/qp_solver/qp_solver_unconstraint_fast.cpp b/control/autoware_mpc_lateral_controller/src/qp_solver/qp_solver_unconstraint_fast.cpp similarity index 93% rename from control/mpc_lateral_controller/src/qp_solver/qp_solver_unconstraint_fast.cpp rename to control/autoware_mpc_lateral_controller/src/qp_solver/qp_solver_unconstraint_fast.cpp index b0357138cd646..315e29d063aad 100644 --- a/control/mpc_lateral_controller/src/qp_solver/qp_solver_unconstraint_fast.cpp +++ b/control/autoware_mpc_lateral_controller/src/qp_solver/qp_solver_unconstraint_fast.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp" +#include "autoware_mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp" #include diff --git a/control/mpc_lateral_controller/src/steering_offset/steering_offset.cpp b/control/autoware_mpc_lateral_controller/src/steering_offset/steering_offset.cpp similarity index 95% rename from control/mpc_lateral_controller/src/steering_offset/steering_offset.cpp rename to control/autoware_mpc_lateral_controller/src/steering_offset/steering_offset.cpp index 60d4dd7901394..6425d5da5e941 100644 --- a/control/mpc_lateral_controller/src/steering_offset/steering_offset.cpp +++ b/control/autoware_mpc_lateral_controller/src/steering_offset/steering_offset.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mpc_lateral_controller/steering_offset/steering_offset.hpp" +#include "autoware_mpc_lateral_controller/steering_offset/steering_offset.hpp" #include #include diff --git a/control/mpc_lateral_controller/src/steering_predictor.cpp b/control/autoware_mpc_lateral_controller/src/steering_predictor.cpp similarity index 98% rename from control/mpc_lateral_controller/src/steering_predictor.cpp rename to control/autoware_mpc_lateral_controller/src/steering_predictor.cpp index 48d8fa8c47a97..759a36a16de62 100644 --- a/control/mpc_lateral_controller/src/steering_predictor.cpp +++ b/control/autoware_mpc_lateral_controller/src/steering_predictor.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mpc_lateral_controller/steering_predictor.hpp" +#include "autoware_mpc_lateral_controller/steering_predictor.hpp" namespace autoware::motion::control::mpc_lateral_controller { diff --git a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_dynamics.cpp b/control/autoware_mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_dynamics.cpp similarity index 98% rename from control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_dynamics.cpp rename to control/autoware_mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_dynamics.cpp index 2467b1f0c2311..d5272c48fcbdf 100644 --- a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_dynamics.cpp +++ b/control/autoware_mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_dynamics.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp" +#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp" #include diff --git a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics.cpp b/control/autoware_mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics.cpp similarity index 98% rename from control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics.cpp rename to control/autoware_mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics.cpp index cd52dd4f79314..97bcafb161cb0 100644 --- a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics.cpp +++ b/control/autoware_mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp" +#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp" #include diff --git a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.cpp b/control/autoware_mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.cpp similarity index 98% rename from control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.cpp rename to control/autoware_mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.cpp index 8f4510510aca9..d2857d8b42182 100644 --- a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.cpp +++ b/control/autoware_mpc_lateral_controller/src/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp" +#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp" #include diff --git a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_interface.cpp b/control/autoware_mpc_lateral_controller/src/vehicle_model/vehicle_model_interface.cpp similarity index 94% rename from control/mpc_lateral_controller/src/vehicle_model/vehicle_model_interface.cpp rename to control/autoware_mpc_lateral_controller/src/vehicle_model/vehicle_model_interface.cpp index f54a5e325bead..e1b17d3d96278 100644 --- a/control/mpc_lateral_controller/src/vehicle_model/vehicle_model_interface.cpp +++ b/control/autoware_mpc_lateral_controller/src/vehicle_model/vehicle_model_interface.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp" +#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp" namespace autoware::motion::control::mpc_lateral_controller { diff --git a/control/mpc_lateral_controller/test/test_lowpass_filter.cpp b/control/autoware_mpc_lateral_controller/test/test_lowpass_filter.cpp similarity index 98% rename from control/mpc_lateral_controller/test/test_lowpass_filter.cpp rename to control/autoware_mpc_lateral_controller/test/test_lowpass_filter.cpp index c68513586847b..bfb695cdeee8a 100644 --- a/control/mpc_lateral_controller/test/test_lowpass_filter.cpp +++ b/control/autoware_mpc_lateral_controller/test/test_lowpass_filter.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "autoware_mpc_lateral_controller/lowpass_filter.hpp" #include "gtest/gtest.h" -#include "mpc_lateral_controller/lowpass_filter.hpp" #include diff --git a/control/mpc_lateral_controller/test/test_mpc.cpp b/control/autoware_mpc_lateral_controller/test/test_mpc.cpp similarity index 97% rename from control/mpc_lateral_controller/test/test_mpc.cpp rename to control/autoware_mpc_lateral_controller/test/test_mpc.cpp index 7644fb28b0788..3fd4b010852c0 100644 --- a/control/mpc_lateral_controller/test/test_mpc.cpp +++ b/control/autoware_mpc_lateral_controller/test/test_mpc.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "autoware_mpc_lateral_controller/mpc.hpp" +#include "autoware_mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp" +#include "autoware_mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp" +#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp" +#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp" +#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp" #include "gtest/gtest.h" -#include "mpc_lateral_controller/mpc.hpp" -#include "mpc_lateral_controller/qp_solver/qp_solver_osqp.hpp" -#include "mpc_lateral_controller/qp_solver/qp_solver_unconstraint_fast.hpp" -#include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp" -#include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp" -#include "mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp" #include "rclcpp/rclcpp.hpp" #include "autoware_control_msgs/msg/lateral.hpp" diff --git a/control/mpc_lateral_controller/test/test_mpc_utils.cpp b/control/autoware_mpc_lateral_controller/test/test_mpc_utils.cpp similarity index 95% rename from control/mpc_lateral_controller/test/test_mpc_utils.cpp rename to control/autoware_mpc_lateral_controller/test/test_mpc_utils.cpp index 51cc7d55e4560..b55435dffd024 100644 --- a/control/mpc_lateral_controller/test/test_mpc_utils.cpp +++ b/control/autoware_mpc_lateral_controller/test/test_mpc_utils.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "autoware_mpc_lateral_controller/mpc_trajectory.hpp" +#include "autoware_mpc_lateral_controller/mpc_utils.hpp" #include "gtest/gtest.h" -#include "mpc_lateral_controller/mpc_trajectory.hpp" -#include "mpc_lateral_controller/mpc_utils.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_planning_msgs/msg/trajectory_point.hpp" diff --git a/control/trajectory_follower_node/README.md b/control/trajectory_follower_node/README.md index 3496284efd670..7b9e93e39fad9 100644 --- a/control/trajectory_follower_node/README.md +++ b/control/trajectory_follower_node/README.md @@ -45,7 +45,7 @@ struct LateralSyncData { } } -package mpc_lateral_controller { +package autoware_mpc_lateral_controller { class MPCLateralController { isReady(InputData) override run(InputData) override diff --git a/control/trajectory_follower_node/design/media/Controller.drawio.svg b/control/trajectory_follower_node/design/media/Controller.drawio.svg index 1152ef2b17f59..db4961922bd10 100644 --- a/control/trajectory_follower_node/design/media/Controller.drawio.svg +++ b/control/trajectory_follower_node/design/media/Controller.drawio.svg @@ -140,7 +140,7 @@
trajectory_follower/
- mpc_lateral_controller + autoware_mpc_lateral_controller
diff --git a/control/trajectory_follower_node/package.xml b/control/trajectory_follower_node/package.xml index 65446dfb3dd01..b7dd546eb4bca 100644 --- a/control/trajectory_follower_node/package.xml +++ b/control/trajectory_follower_node/package.xml @@ -21,10 +21,10 @@ autoware_adapi_v1_msgs autoware_control_msgs + autoware_mpc_lateral_controller autoware_planning_msgs autoware_vehicle_msgs motion_utils - mpc_lateral_controller pid_longitudinal_controller pure_pursuit rclcpp diff --git a/control/trajectory_follower_node/src/controller_node.cpp b/control/trajectory_follower_node/src/controller_node.cpp index 6fe63ca07de6f..f431be6612009 100644 --- a/control/trajectory_follower_node/src/controller_node.cpp +++ b/control/trajectory_follower_node/src/controller_node.cpp @@ -14,7 +14,7 @@ #include "trajectory_follower_node/controller_node.hpp" -#include "mpc_lateral_controller/mpc_lateral_controller.hpp" +#include "autoware_mpc_lateral_controller/mpc_lateral_controller.hpp" #include "pid_longitudinal_controller/pid_longitudinal_controller.hpp" #include "pure_pursuit/pure_pursuit_lateral_controller.hpp" #include "tier4_autoware_utils/ros/marker_helper.hpp" diff --git a/control/trajectory_follower_node/test/test_controller_node.cpp b/control/trajectory_follower_node/test/test_controller_node.cpp index 9bdf625226134..3bf47233f1f3f 100644 --- a/control/trajectory_follower_node/test/test_controller_node.cpp +++ b/control/trajectory_follower_node/test/test_controller_node.cpp @@ -53,7 +53,7 @@ rclcpp::NodeOptions makeNodeOptions(const bool enable_keep_stopped_until_steer_c const auto longitudinal_share_dir = ament_index_cpp::get_package_share_directory("pid_longitudinal_controller"); const auto lateral_share_dir = - ament_index_cpp::get_package_share_directory("mpc_lateral_controller"); + ament_index_cpp::get_package_share_directory("autoware_mpc_lateral_controller"); rclcpp::NodeOptions node_options; node_options.append_parameter_override("lateral_controller_mode", "mpc"); node_options.append_parameter_override("longitudinal_controller_mode", "pid"); From a3955e90cf849bb77f4f6e0444a6379b070d227f Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 7 Jun 2024 15:47:25 +0900 Subject: [PATCH 12/65] fix(static_obstacle_avoidance): return shift validation (#7229) fix(staatic_obstacle_avoidance): allow return shift approval even if return shift path is not within drivable area Signed-off-by: satoshi-ota --- .../src/scene.cpp | 49 ++++++++++++------- 1 file changed, 31 insertions(+), 18 deletions(-) diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 767c1d21dfc90..9972263cb4fd2 100644 --- a/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -1208,32 +1208,45 @@ bool StaticObstacleAvoidanceModule::isValidShiftLine( } } + const auto is_return_shift = + [](const double start_shift_length, const double end_shift_length, const double threshold) { + return std::abs(start_shift_length) > threshold && std::abs(end_shift_length) < threshold; + }; + // check if the vehicle is in road. (yaw angle is not considered) { const auto minimum_distance = 0.5 * planner_data_->parameters.vehicle_width + parameters_->hard_drivable_bound_margin - parameters_->max_deviation_from_lane; - const size_t start_idx = shift_lines.front().start_idx; - const size_t end_idx = shift_lines.back().end_idx; + for (const auto & shift_line : shift_lines) { + const size_t start_idx = shift_line.start_idx; + const size_t end_idx = shift_line.end_idx; - const auto path = shifter_for_validate.getReferencePath(); - const auto left_bound = lanelet::utils::to2D(toLineString3d(avoid_data_.left_bound)); - const auto right_bound = lanelet::utils::to2D(toLineString3d(avoid_data_.right_bound)); - for (size_t i = start_idx; i <= end_idx; ++i) { - const auto p = getPoint(path.points.at(i)); - lanelet::BasicPoint2d basic_point{p.x, p.y}; - - const auto shift_length = proposed_shift_path.shift_length.at(i); - const auto THRESHOLD = minimum_distance + std::abs(shift_length); + if (is_return_shift( + shift_line.start_shift_length, shift_line.end_shift_length, + parameters_->lateral_small_shift_threshold)) { + continue; + } - if ( - boost::geometry::distance(basic_point, (shift_length > 0.0 ? left_bound : right_bound)) < - THRESHOLD) { - RCLCPP_DEBUG_THROTTLE( - getLogger(), *clock_, 1000, - "following latest new shift line may cause deviation from drivable area."); - return false; + const auto path = shifter_for_validate.getReferencePath(); + const auto left_bound = lanelet::utils::to2D(toLineString3d(avoid_data_.left_bound)); + const auto right_bound = lanelet::utils::to2D(toLineString3d(avoid_data_.right_bound)); + for (size_t i = start_idx; i <= end_idx; ++i) { + const auto p = getPoint(path.points.at(i)); + lanelet::BasicPoint2d basic_point{p.x, p.y}; + + const auto shift_length = proposed_shift_path.shift_length.at(i); + const auto THRESHOLD = minimum_distance + std::abs(shift_length); + + if ( + boost::geometry::distance(basic_point, (shift_length > 0.0 ? left_bound : right_bound)) < + THRESHOLD) { + RCLCPP_DEBUG_THROTTLE( + getLogger(), *clock_, 1000, + "following latest new shift line may cause deviation from drivable area."); + return false; + } } } } From 6013a78e47cb384bb19dcaa3dd2aedecfb6f1910 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 7 Jun 2024 16:02:15 +0900 Subject: [PATCH 13/65] refactor(sampling_planner_module): use std::make_shared (#7226) Signed-off-by: Maxime CLEMENT --- .../src/sampling_planner_module.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp b/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp index 8788b446e4384..22187652bd663 100644 --- a/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp +++ b/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp @@ -37,8 +37,7 @@ SamplingPlannerModule::SamplingPlannerModule( : SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT vehicle_info_{vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()} { - internal_params_ = - std::shared_ptr(new SamplingPlannerInternalParameters{}); + internal_params_ = std::make_shared(); updateModuleParams(parameters); // check if the path is empty From 6669213383f90d49494b6625bfc41b0b26f1da99 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Fri, 7 Jun 2024 16:20:21 +0900 Subject: [PATCH 14/65] refactor(behavior_velocity_planner_common)!: prefix package and namespace with autoware (#7314) * refactor(behavior_velocity_planner_common): add autoware prefix Signed-off-by: Fumiya Watanabe * refactor(behavior_velocity_planner_common): fix run_out module Signed-off-by: Fumiya Watanabe * refactor(behavior_velocity_planner_common): fix for autoware_behavior_velocity_walkway_module Signed-off-by: Fumiya Watanabe * refactor(behavior_velocity_planner_common): remove unnecessary using Signed-off-by: Fumiya Watanabe --------- Signed-off-by: Fumiya Watanabe --- .github/CODEOWNERS | 3 ++- .../behavior_planning.launch.xml | 26 +++++++++---------- .../package.xml | 2 +- .../src/debug.cpp | 12 ++++----- .../src/decision_result.cpp | 4 +-- .../src/decision_result.hpp | 4 +-- .../src/interpolated_path_info.hpp | 4 +-- .../src/intersection_lanelets.cpp | 4 +-- .../src/intersection_lanelets.hpp | 4 +-- .../src/intersection_stoplines.hpp | 4 +-- .../src/manager.cpp | 15 ++++++----- .../src/manager.hpp | 10 +++---- .../src/object_manager.cpp | 4 +-- .../src/object_manager.hpp | 4 +-- .../src/result.hpp | 4 +-- .../src/scene_intersection.cpp | 8 +++--- .../src/scene_intersection.hpp | 8 +++--- .../src/scene_intersection_collision.cpp | 8 +++--- .../src/scene_intersection_occlusion.cpp | 4 +-- .../src/scene_intersection_prepare_data.cpp | 12 ++++----- .../src/scene_intersection_stuck.cpp | 6 ++--- .../src/scene_merge_from_private_road.cpp | 8 +++--- .../src/scene_merge_from_private_road.hpp | 8 +++--- .../src/util.cpp | 10 +++---- .../src/util.hpp | 4 +-- .../package.xml | 2 +- .../src/node.cpp | 8 +++--- .../src/node.hpp | 3 +-- .../src/planner_manager.cpp | 3 ++- .../src/planner_manager.hpp | 6 ++--- .../test/src/test_node_interface.cpp | 22 ++++++++-------- .../CMakeLists.txt | 2 +- .../README.md | 0 .../planner_data.hpp | 12 ++++----- .../plugin_interface.hpp | 12 ++++----- .../plugin_wrapper.hpp | 12 ++++----- .../scene_module_interface.hpp | 12 ++++----- .../utilization/arc_lane_util.hpp | 12 ++++----- .../utilization/boost_geometry_helper.hpp | 10 +++---- .../utilization/debug.hpp | 10 +++---- .../utilization/path_utilization.hpp | 10 +++---- .../utilization/state_machine.hpp | 10 +++---- .../utilization/trajectory_utils.hpp | 12 ++++----- .../utilization/util.hpp | 18 +++++++------ .../package.xml | 4 +-- .../src/scene_module_interface.cpp | 8 +++--- .../src/utilization/arc_lane_util.cpp | 6 ++--- .../src/utilization/boost_geometry_helper.cpp | 6 ++--- .../src/utilization/debug.cpp | 8 +++--- .../src/utilization/path_utilization.cpp | 6 ++--- .../src/utilization/trajectory_utils.cpp | 8 +++--- .../src/utilization/util.cpp | 16 +++++++----- .../test/src/test_arc_lane_util.cpp | 15 ++++++----- .../test/src/test_state_machine.cpp | 6 ++--- .../test/src/test_utilization.cpp | 13 +++++----- .../test/src/utils.hpp | 0 .../package.xml | 2 +- .../plugins.xml | 2 +- .../src/debug.hpp | 1 - .../src/dynamic_obstacle.cpp | 2 -- .../src/dynamic_obstacle.hpp | 8 +++--- .../src/manager.cpp | 3 +-- .../src/manager.hpp | 9 +++---- .../src/scene.cpp | 9 +++---- .../src/scene.hpp | 7 +---- .../src/utils.cpp | 3 --- .../src/utils.hpp | 6 ++--- .../package.xml | 2 +- .../src/manager.cpp | 2 +- .../src/manager.hpp | 11 ++++---- .../src/scene.hpp | 4 +-- .../package.xml | 2 +- .../plugins.xml | 2 +- .../src/manager.cpp | 6 ++--- .../src/manager.hpp | 9 +++---- .../src/scene.cpp | 12 +++------ .../src/scene.hpp | 6 +---- .../package.xml | 2 +- .../plugins.xml | 2 +- .../src/debug.cpp | 3 +-- .../src/manager.cpp | 8 ++---- .../src/manager.hpp | 9 +++---- .../src/scene_walkway.cpp | 10 +------ .../src/scene_walkway.hpp | 7 +---- .../package.xml | 2 +- .../plugins.xml | 2 +- .../src/debug.cpp | 8 +++--- .../src/decisions.cpp | 4 +-- .../src/manager.cpp | 11 ++++---- .../src/manager.hpp | 10 +++---- .../src/scene.cpp | 10 +++---- .../src/scene.hpp | 10 +++---- .../util.hpp | 6 ++--- .../package.xml | 2 +- .../plugins.xml | 2 +- .../src/debug.cpp | 6 ++--- .../src/manager.cpp | 9 ++++--- .../src/manager.hpp | 10 +++---- .../src/occluded_crosswalk.cpp | 8 +++--- .../src/occluded_crosswalk.hpp | 8 +++--- .../src/scene_crosswalk.cpp | 8 +++--- .../src/scene_crosswalk.hpp | 6 ++--- .../src/util.cpp | 17 +++++++----- .../package.xml | 2 +- .../plugins.xml | 2 +- .../src/debug.cpp | 8 +++--- .../src/manager.cpp | 9 ++++--- .../src/manager.hpp | 10 +++---- .../src/scene.cpp | 8 +++--- .../src/scene.hpp | 8 +++--- .../package.xml | 2 +- .../plugins.xml | 2 +- .../src/collision.cpp | 4 +-- .../src/collision.hpp | 4 +-- .../src/debug.cpp | 4 +-- .../src/debug.hpp | 4 +-- .../src/footprint.cpp | 4 +-- .../src/footprint.hpp | 4 +-- .../src/manager.cpp | 8 +++--- .../src/manager.hpp | 10 +++---- .../src/object_filtering.cpp | 4 +-- .../src/object_filtering.hpp | 4 +-- .../src/object_stop_decision.cpp | 4 +-- .../src/object_stop_decision.hpp | 4 +-- .../src/scene_dynamic_obstacle_stop.cpp | 8 +++--- .../src/scene_dynamic_obstacle_stop.hpp | 6 ++--- .../src/types.hpp | 4 +-- .../package.xml | 2 +- .../plugins.xml | 2 +- .../src/debug.cpp | 6 ++--- .../src/manager.cpp | 9 ++++--- .../src/manager.hpp | 10 +++---- .../src/scene.cpp | 6 ++--- .../src/scene.hpp | 6 ++--- .../src/util.cpp | 6 ++--- .../src/util.hpp | 4 +-- .../package.xml | 2 +- .../plugins.xml | 2 +- .../src/debug.cpp | 8 +++--- .../src/manager.cpp | 9 ++++--- .../src/manager.hpp | 10 +++---- .../src/scene_no_stopping_area.cpp | 10 +++---- .../src/scene_no_stopping_area.hpp | 10 +++---- .../package.xml | 2 +- .../plugins.xml | 2 +- .../src/debug.cpp | 8 +++--- .../src/grid_utils.cpp | 4 +-- .../src/grid_utils.hpp | 8 +++--- .../src/manager.cpp | 9 ++++--- .../src/manager.hpp | 10 +++---- .../src/occlusion_spot_utils.cpp | 8 +++--- .../src/occlusion_spot_utils.hpp | 6 ++--- .../src/risk_predictive_braking.cpp | 6 ++--- .../src/risk_predictive_braking.hpp | 4 +-- .../src/scene_occlusion_spot.cpp | 14 +++++----- .../src/scene_occlusion_spot.hpp | 8 +++--- .../test/src/test_grid_utils.cpp | 12 ++++----- .../test/src/test_occlusion_spot_utils.cpp | 14 +++++----- .../test/src/test_risk_predictive_braking.cpp | 2 +- .../test/src/utils.hpp | 9 ++++--- .../package.xml | 2 +- .../plugins.xml | 2 +- .../src/calculate_slowdown_points.hpp | 4 +-- .../src/debug.cpp | 4 +-- .../src/debug.hpp | 4 +-- .../src/decisions.cpp | 4 +-- .../src/decisions.hpp | 4 +-- .../src/filter_predicted_objects.cpp | 4 +-- .../src/filter_predicted_objects.hpp | 6 ++--- .../src/footprint.cpp | 4 +-- .../src/footprint.hpp | 4 +-- .../src/lanelets_selection.cpp | 6 ++--- .../src/lanelets_selection.hpp | 4 +-- .../src/manager.cpp | 9 ++++--- .../src/manager.hpp | 10 +++---- .../src/overlapping_range.cpp | 4 +-- .../src/overlapping_range.hpp | 4 +-- .../src/scene_out_of_lane.cpp | 8 +++--- .../src/scene_out_of_lane.hpp | 6 ++--- .../src/types.hpp | 4 +-- .../package.xml | 2 +- .../plugins.xml | 2 +- .../src/debug.cpp | 6 ++--- .../src/manager.cpp | 9 ++++--- .../src/manager.hpp | 10 +++---- .../src/scene.cpp | 4 +-- .../src/scene.hpp | 6 ++--- .../src/util.cpp | 6 ++--- .../src/util.hpp | 4 +-- .../package.xml | 2 +- .../plugins.xml | 2 +- .../src/debug.cpp | 6 ++--- .../src/manager.cpp | 7 ++--- .../src/manager.hpp | 10 +++---- .../src/scene.cpp | 8 +++--- .../src/scene.hpp | 10 +++---- .../package.xml | 2 +- .../plugins.xml | 2 +- .../src/debug.cpp | 6 ++--- .../src/manager.cpp | 9 ++++--- .../src/manager.hpp | 10 +++---- .../src/scene.cpp | 6 ++--- .../src/scene.hpp | 8 +++--- .../package.xml | 2 +- 204 files changed, 649 insertions(+), 682 deletions(-) rename planning/{behavior_velocity_planner_common => autoware_behavior_velocity_planner_common}/CMakeLists.txt (93%) rename planning/{behavior_velocity_planner_common => autoware_behavior_velocity_planner_common}/README.md (100%) rename planning/{behavior_velocity_planner_common/include/behavior_velocity_planner_common => autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common}/planner_data.hpp (93%) rename planning/{behavior_velocity_planner_common/include/behavior_velocity_planner_common => autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common}/plugin_interface.hpp (75%) rename planning/{behavior_velocity_planner_common/include/behavior_velocity_planner_common => autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common}/plugin_wrapper.hpp (78%) rename planning/{behavior_velocity_planner_common/include/behavior_velocity_planner_common => autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common}/scene_module_interface.hpp (95%) rename planning/{behavior_velocity_planner_common/include/behavior_velocity_planner_common => autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common}/utilization/arc_lane_util.hpp (94%) rename planning/{behavior_velocity_planner_common/include/behavior_velocity_planner_common => autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common}/utilization/boost_geometry_helper.hpp (88%) rename planning/{behavior_velocity_planner_common/include/behavior_velocity_planner_common => autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common}/utilization/debug.hpp (86%) rename planning/{behavior_velocity_planner_common/include/behavior_velocity_planner_common => autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common}/utilization/path_utilization.hpp (78%) rename planning/{behavior_velocity_planner_common/include/behavior_velocity_planner_common => autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common}/utilization/state_machine.hpp (87%) rename planning/{behavior_velocity_planner_common/include/behavior_velocity_planner_common => autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common}/utilization/trajectory_utils.hpp (76%) rename planning/{behavior_velocity_planner_common/include/behavior_velocity_planner_common => autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common}/utilization/util.hpp (93%) rename planning/{behavior_velocity_planner_common => autoware_behavior_velocity_planner_common}/package.xml (93%) rename planning/{behavior_velocity_planner_common => autoware_behavior_velocity_planner_common}/src/scene_module_interface.cpp (97%) rename planning/{behavior_velocity_planner_common => autoware_behavior_velocity_planner_common}/src/utilization/arc_lane_util.cpp (94%) rename planning/{behavior_velocity_planner_common => autoware_behavior_velocity_planner_common}/src/utilization/boost_geometry_helper.cpp (91%) rename planning/{behavior_velocity_planner_common => autoware_behavior_velocity_planner_common}/src/utilization/debug.cpp (94%) rename planning/{behavior_velocity_planner_common => autoware_behavior_velocity_planner_common}/src/utilization/path_utilization.cpp (96%) rename planning/{behavior_velocity_planner_common => autoware_behavior_velocity_planner_common}/src/utilization/trajectory_utils.cpp (93%) rename planning/{behavior_velocity_planner_common => autoware_behavior_velocity_planner_common}/src/utilization/util.cpp (97%) rename planning/{behavior_velocity_planner_common => autoware_behavior_velocity_planner_common}/test/src/test_arc_lane_util.cpp (93%) rename planning/{behavior_velocity_planner_common => autoware_behavior_velocity_planner_common}/test/src/test_state_machine.cpp (92%) rename planning/{behavior_velocity_planner_common => autoware_behavior_velocity_planner_common}/test/src/test_utilization.cpp (92%) rename planning/{behavior_velocity_planner_common => autoware_behavior_velocity_planner_common}/test/src/utils.hpp (100%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index d2d6fa2c56343..7a0c8f8893a39 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -178,7 +178,8 @@ planning/behavior_velocity_no_drivable_lane_module/** ahmed.ebrahim@leodrive.ai planning/behavior_velocity_no_stopping_area_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_out_of_lane_module/** maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -planning/behavior_velocity_planner_common/** fumiya.watanabe@tier4.jp isamu.takagi@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp +planning/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 +planning/autoware_behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_stop_line_module/** fumiya.watanabe@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp zhe.shen@tier4.jp planning/behavior_velocity_traffic_light_module/** mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 4cf0c541510ed..779ee5c7af34a 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -101,7 +101,7 @@ diff --git a/planning/autoware_behavior_velocity_intersection_module/package.xml b/planning/autoware_behavior_velocity_intersection_module/package.xml index 204a267594c03..401e53586c649 100644 --- a/planning/autoware_behavior_velocity_intersection_module/package.xml +++ b/planning/autoware_behavior_velocity_intersection_module/package.xml @@ -18,9 +18,9 @@ ament_cmake_auto autoware_cmake + autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs - behavior_velocity_planner_common fmt geometry_msgs interpolation diff --git a/planning/autoware_behavior_velocity_intersection_module/src/debug.cpp b/planning/autoware_behavior_velocity_intersection_module/src/debug.cpp index 252d7c2a9f61e..ab09ca2e6e746 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/debug.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/debug.cpp @@ -15,8 +15,8 @@ #include "scene_intersection.hpp" #include "scene_merge_from_private_road.hpp" -#include -#include +#include +#include #include #include @@ -45,7 +45,7 @@ visualization_msgs::msg::MarkerArray createLaneletPolygonsMarkerArray( visualization_msgs::msg::MarkerArray msg; int32_t i = 0; - int32_t uid = behavior_velocity_planner::planning_utils::bitShift(lane_id); + int32_t uid = autoware::behavior_velocity_planner::planning_utils::bitShift(lane_id); for (const auto & polygon : polygons) { visualization_msgs::msg::Marker marker{}; marker.header.frame_id = "map"; @@ -224,7 +224,7 @@ constexpr std::tuple light_blue() } } // namespace -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using tier4_autoware_utils::appendMarkerArray; using tier4_autoware_utils::createMarkerColor; @@ -472,7 +472,7 @@ visualization_msgs::msg::MarkerArray MergeFromPrivateRoadModule::createDebugMark const auto state = state_machine_.getState(); - int32_t uid = behavior_velocity_planner::planning_utils::bitShift(module_id_); + int32_t uid = autoware::behavior_velocity_planner::planning_utils::bitShift(module_id_); const auto now = this->clock_->now(); if (state == StateMachine::State::STOP) { appendMarkerArray( @@ -496,4 +496,4 @@ motion_utils::VirtualWalls MergeFromPrivateRoadModule::createVirtualWalls() } return virtual_walls; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/autoware_behavior_velocity_intersection_module/src/decision_result.cpp b/planning/autoware_behavior_velocity_intersection_module/src/decision_result.cpp index 0dc0e3aab4b87..5d1f1a1fcfca2 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/decision_result.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/decision_result.cpp @@ -14,7 +14,7 @@ #include "decision_result.hpp" -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { std::string formatDecisionResult(const DecisionResult & decision_result) { @@ -65,4 +65,4 @@ std::string formatDecisionResult(const DecisionResult & decision_result) return ""; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/autoware_behavior_velocity_intersection_module/src/decision_result.hpp b/planning/autoware_behavior_velocity_intersection_module/src/decision_result.hpp index bf0b5520f7a32..26f78616a7b61 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/decision_result.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/decision_result.hpp @@ -19,7 +19,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { /** @@ -172,6 +172,6 @@ using DecisionResult = std::variant< std::string formatDecisionResult(const DecisionResult & decision_result); -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // DECISION_RESULT_HPP_ diff --git a/planning/autoware_behavior_velocity_intersection_module/src/interpolated_path_info.hpp b/planning/autoware_behavior_velocity_intersection_module/src/interpolated_path_info.hpp index c855164e24d5b..d8bada002e37b 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/interpolated_path_info.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/interpolated_path_info.hpp @@ -23,7 +23,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { /** @@ -43,6 +43,6 @@ struct InterpolatedPathInfo std::optional> lane_id_interval{std::nullopt}; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // INTERPOLATED_PATH_INFO_HPP_ diff --git a/planning/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.cpp b/planning/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.cpp index bf833ee07c155..be7e9e25cc8bc 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.cpp @@ -21,7 +21,7 @@ #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { void IntersectionLanelets::update( @@ -79,4 +79,4 @@ void IntersectionLanelets::update( } } } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.hpp b/planning/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.hpp index 3682787237d42..a7ca5eb3b0bc1 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/intersection_lanelets.hpp @@ -27,7 +27,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { /** @@ -190,6 +190,6 @@ struct PathLanelets // conflicting lanelets plus the next lane part of the // path }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // INTERSECTION_LANELETS_HPP_ diff --git a/planning/autoware_behavior_velocity_intersection_module/src/intersection_stoplines.hpp b/planning/autoware_behavior_velocity_intersection_module/src/intersection_stoplines.hpp index 85876ffc98380..98325f0aa8735 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/intersection_stoplines.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/intersection_stoplines.hpp @@ -17,7 +17,7 @@ #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { /** @@ -72,6 +72,6 @@ struct IntersectionStopLines */ size_t occlusion_wo_tl_pass_judge_line{0}; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // INTERSECTION_STOPLINES_HPP_ diff --git a/planning/autoware_behavior_velocity_intersection_module/src/manager.cpp b/planning/autoware_behavior_velocity_intersection_module/src/manager.cpp index ac32ad553d2b7..8f540603791cb 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/manager.cpp @@ -14,8 +14,8 @@ #include "manager.hpp" -#include -#include +#include +#include #include #include @@ -28,7 +28,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using tier4_autoware_utils::getOrDeclareParameter; @@ -589,11 +589,12 @@ bool MergeFromPrivateModuleManager::hasSameParentLaneletAndTurnDirectionWithRegi return false; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #include PLUGINLIB_EXPORT_CLASS( - behavior_velocity_planner::IntersectionModulePlugin, behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::IntersectionModulePlugin, + autoware::behavior_velocity_planner::PluginInterface) PLUGINLIB_EXPORT_CLASS( - behavior_velocity_planner::MergeFromPrivateModulePlugin, - behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::MergeFromPrivateModulePlugin, + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/autoware_behavior_velocity_intersection_module/src/manager.hpp b/planning/autoware_behavior_velocity_intersection_module/src/manager.hpp index 7bbc8d51bbe9e..ecf6bb810f313 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/manager.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/manager.hpp @@ -18,9 +18,9 @@ #include "scene_intersection.hpp" #include "scene_merge_from_private_road.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -32,7 +32,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class IntersectionModuleManager : public SceneModuleManagerInterfaceWithRTC { @@ -90,6 +90,6 @@ class MergeFromPrivateModulePlugin : public PluginWrapper findPassageInterval( lane_position, path, {enter_idx, exit_idx}, {object_enter_time, object_exit_time}}; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/autoware_behavior_velocity_intersection_module/src/object_manager.hpp b/planning/autoware_behavior_velocity_intersection_module/src/object_manager.hpp index 3d1113656c3e3..0ba9947fdb318 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/object_manager.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/object_manager.hpp @@ -52,7 +52,7 @@ struct hash }; } // namespace std -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { /** @@ -287,6 +287,6 @@ std::optional findPassageInterval( const std::optional & first_attention_lane_opt, const std::optional & second_attention_lane_opt); -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // OBJECT_MANAGER_HPP_ diff --git a/planning/autoware_behavior_velocity_intersection_module/src/result.hpp b/planning/autoware_behavior_velocity_intersection_module/src/result.hpp index da89920e59a85..1a833b268a5d8 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/result.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/result.hpp @@ -18,7 +18,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { template @@ -48,6 +48,6 @@ Result make_err(Args &&... args) return Result(Error{std::forward(args)...}); } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // RESULT_HPP_ diff --git a/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp index 8e50c140894e7..beed0aab8e382 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -16,8 +16,8 @@ #include "util.hpp" -#include // for toGeomPoly -#include +#include // for toGeomPoly +#include #include #include #include @@ -38,7 +38,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -1412,4 +1412,4 @@ IntersectionModule::PassJudgeStatus IntersectionModule::isOverPassJudgeLinesStat safely_passed_1st_judge_line_first_time, safely_passed_2nd_judge_line_first_time}; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp index b1cfcdee04fa6..e25f41a18028a 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -22,8 +22,8 @@ #include "object_manager.hpp" #include "result.hpp" -#include -#include +#include +#include #include #include @@ -43,7 +43,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class IntersectionModule : public SceneModuleInterface @@ -818,6 +818,6 @@ class IntersectionModule : public SceneModuleInterface rclcpp::Publisher::SharedPtr object_ttc_pub_; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // SCENE_INTERSECTION_HPP_ diff --git a/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp index 48387bc6aa398..fb06ed9d811c8 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp @@ -15,8 +15,8 @@ #include "scene_intersection.hpp" #include "util.hpp" -#include // for toGeomPoly -#include // for smoothPath +#include // for toGeomPoly +#include // for smoothPath #include #include #include @@ -30,7 +30,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -964,4 +964,4 @@ IntersectionModule::TimeDistanceArray IntersectionModule::calcIntersectionPassin return time_distance_array; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp index 0fb6042e5aadb..c43f8617897b9 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp @@ -25,7 +25,7 @@ #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -449,4 +449,4 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion( debug_data_.static_occlusion = true; return StaticallyOccluded{min_dist}; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp index d4466c1e9431b..223e8eca84fe8 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp @@ -15,8 +15,8 @@ #include "scene_intersection.hpp" #include "util.hpp" -#include // for to_bg2d -#include // for planning_utils:: +#include // for to_bg2d +#include // for planning_utils:: #include #include // for lanelet::autoware::RoadMarking #include @@ -106,7 +106,7 @@ std::optional> getFirstPoi const auto & p = path.points.at(i).point.pose.position; for (const auto & polygon : polygons) { const auto polygon_2d = lanelet::utils::to2D(polygon); - is_in_lanelet = bg::within(behavior_velocity_planner::to_bg2d(p), polygon_2d); + is_in_lanelet = bg::within(autoware::behavior_velocity_planner::to_bg2d(p), polygon_2d); if (is_in_lanelet) { return std::make_optional>( i, polygon); @@ -122,7 +122,7 @@ std::optional> getFirstPoi const auto & p = path.points.at(i).point.pose.position; for (const auto & polygon : polygons) { const auto polygon_2d = lanelet::utils::to2D(polygon); - is_in_lanelet = bg::within(behavior_velocity_planner::to_bg2d(p), polygon_2d); + is_in_lanelet = bg::within(autoware::behavior_velocity_planner::to_bg2d(p), polygon_2d); if (is_in_lanelet) { return std::make_optional>( i, polygon); @@ -157,7 +157,7 @@ double getHighestCurvature(const lanelet::ConstLineString3d & centerline) } // namespace -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -907,4 +907,4 @@ std::vector IntersectionModule::generateDetectionLan return detection_divisions; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp index c7de1805327c3..eecb02d07c386 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp @@ -15,7 +15,7 @@ #include "scene_intersection.hpp" #include "util.hpp" -#include // for toGeomPoly +#include // for toGeomPoly #include #include @@ -114,7 +114,7 @@ lanelet::ConstLanelet createLaneletFromArcLength( } // namespace -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -422,4 +422,4 @@ bool IntersectionModule::checkYieldStuckVehicleInIntersection( } return false; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp index be8d94c3b306d..1aaed779e1b79 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp @@ -16,8 +16,8 @@ #include "util.hpp" -#include -#include +#include +#include #include #include #include @@ -32,7 +32,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -206,4 +206,4 @@ lanelet::ConstLanelets MergeFromPrivateRoadModule::getAttentionLanelets() const return attention_lanelets; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp b/planning/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp index 0b783cf2a7ebd..19e9ea44869ea 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp @@ -15,8 +15,8 @@ #ifndef SCENE_MERGE_FROM_PRIVATE_ROAD_HPP_ #define SCENE_MERGE_FROM_PRIVATE_ROAD_HPP_ -#include -#include +#include +#include #include #include @@ -35,7 +35,7 @@ * lanes before entering intersection */ -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class MergeFromPrivateRoadModule : public SceneModuleInterface { @@ -88,6 +88,6 @@ class MergeFromPrivateRoadModule : public SceneModuleInterface // Debug mutable DebugData debug_data_; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // SCENE_MERGE_FROM_PRIVATE_ROAD_HPP_ diff --git a/planning/autoware_behavior_velocity_intersection_module/src/util.cpp b/planning/autoware_behavior_velocity_intersection_module/src/util.cpp index a083185786e42..09f16bcada3c1 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/util.cpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/util.cpp @@ -16,9 +16,9 @@ #include "interpolated_path_info.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -40,7 +40,7 @@ #include #include -namespace behavior_velocity_planner::util +namespace autoware::behavior_velocity_planner::util { namespace bg = boost::geometry; @@ -399,4 +399,4 @@ std::vector getPolygon3dFromLanelets( return polys; } -} // namespace behavior_velocity_planner::util +} // namespace autoware::behavior_velocity_planner::util diff --git a/planning/autoware_behavior_velocity_intersection_module/src/util.hpp b/planning/autoware_behavior_velocity_intersection_module/src/util.hpp index 27200e663503d..ef826380afa69 100644 --- a/planning/autoware_behavior_velocity_intersection_module/src/util.hpp +++ b/planning/autoware_behavior_velocity_intersection_module/src/util.hpp @@ -30,7 +30,7 @@ #include #include -namespace behavior_velocity_planner::util +namespace autoware::behavior_velocity_planner::util { /** @@ -141,6 +141,6 @@ getFirstPointInsidePolygonsByFootprint( std::vector getPolygon3dFromLanelets( const lanelet::ConstLanelets & ll_vec); -} // namespace behavior_velocity_planner::util +} // namespace autoware::behavior_velocity_planner::util #endif // UTIL_HPP_ diff --git a/planning/autoware_behavior_velocity_planner/package.xml b/planning/autoware_behavior_velocity_planner/package.xml index c90d4d01cbca5..4d5dc17264df0 100644 --- a/planning/autoware_behavior_velocity_planner/package.xml +++ b/planning/autoware_behavior_velocity_planner/package.xml @@ -34,11 +34,11 @@ rosidl_default_generators + autoware_behavior_velocity_planner_common autoware_map_msgs autoware_perception_msgs autoware_planning_msgs autoware_velocity_smoother - behavior_velocity_planner_common diagnostic_msgs eigen geometry_msgs diff --git a/planning/autoware_behavior_velocity_planner/src/node.cpp b/planning/autoware_behavior_velocity_planner/src/node.cpp index ffbc4ef9174dc..59049ef7f07f3 100644 --- a/planning/autoware_behavior_velocity_planner/src/node.cpp +++ b/planning/autoware_behavior_velocity_planner/src/node.cpp @@ -14,8 +14,8 @@ #include "node.hpp" +#include #include -#include #include #include #include @@ -439,14 +439,14 @@ autoware_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath( // screening const auto filtered_path = - ::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path)); + autoware::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path)); // interpolation - const auto interpolated_path_msg = ::behavior_velocity_planner::interpolatePath( + const auto interpolated_path_msg = autoware::behavior_velocity_planner::interpolatePath( filtered_path, forward_path_length_, behavior_output_path_interval_); // check stop point - output_path_msg = ::behavior_velocity_planner::filterStopPathPoint(interpolated_path_msg); + output_path_msg = autoware::behavior_velocity_planner::filterStopPathPoint(interpolated_path_msg); output_path_msg.header.frame_id = "map"; output_path_msg.header.stamp = this->now(); diff --git a/planning/autoware_behavior_velocity_planner/src/node.hpp b/planning/autoware_behavior_velocity_planner/src/node.hpp index 62ceef5f04ea6..b2157bfb818ce 100644 --- a/planning/autoware_behavior_velocity_planner/src/node.hpp +++ b/planning/autoware_behavior_velocity_planner/src/node.hpp @@ -20,7 +20,7 @@ #include #include -#include +#include #include #include @@ -49,7 +49,6 @@ namespace autoware::behavior_velocity_planner using autoware_behavior_velocity_planner::srv::LoadPlugin; using autoware_behavior_velocity_planner::srv::UnloadPlugin; using autoware_map_msgs::msg::LaneletMapBin; -using ::behavior_velocity_planner::TrafficSignalStamped; using tier4_planning_msgs::msg::VelocityLimit; class BehaviorVelocityPlannerNode : public rclcpp::Node diff --git a/planning/autoware_behavior_velocity_planner/src/planner_manager.cpp b/planning/autoware_behavior_velocity_planner/src/planner_manager.cpp index f462fc963f17b..93209a10180be 100644 --- a/planning/autoware_behavior_velocity_planner/src/planner_manager.cpp +++ b/planning/autoware_behavior_velocity_planner/src/planner_manager.cpp @@ -50,7 +50,8 @@ diagnostic_msgs::msg::DiagnosticStatus makeStopReasonDiag( } // namespace BehaviorVelocityPlannerManager::BehaviorVelocityPlannerManager() -: plugin_loader_("autoware_behavior_velocity_planner", "behavior_velocity_planner::PluginInterface") +: plugin_loader_( + "autoware_behavior_velocity_planner", "autoware::behavior_velocity_planner::PluginInterface") { } diff --git a/planning/autoware_behavior_velocity_planner/src/planner_manager.hpp b/planning/autoware_behavior_velocity_planner/src/planner_manager.hpp index 9e7f2942bb067..73193a002918d 100644 --- a/planning/autoware_behavior_velocity_planner/src/planner_manager.hpp +++ b/planning/autoware_behavior_velocity_planner/src/planner_manager.hpp @@ -15,8 +15,8 @@ #ifndef PLANNER_MANAGER_HPP_ #define PLANNER_MANAGER_HPP_ -#include -#include +#include +#include #include #include @@ -38,8 +38,6 @@ namespace autoware::behavior_velocity_planner { -using ::behavior_velocity_planner::PlannerData; -using ::behavior_velocity_planner::PluginInterface; class BehaviorVelocityPlannerManager { diff --git a/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp index 2e971ed238751..cdff8af4ac56e 100644 --- a/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp @@ -68,21 +68,21 @@ std::shared_ptr generateNode() }; std::vector module_names; - module_names.emplace_back("behavior_velocity_planner::CrosswalkModulePlugin"); + module_names.emplace_back("autoware::behavior_velocity_planner::CrosswalkModulePlugin"); module_names.emplace_back("autoware::behavior_velocity_planner::WalkwayModulePlugin"); - module_names.emplace_back("behavior_velocity_planner::TrafficLightModulePlugin"); + module_names.emplace_back("autoware::behavior_velocity_planner::TrafficLightModulePlugin"); module_names.emplace_back("autoware::behavior_velocity_planner::IntersectionModulePlugin"); - module_names.emplace_back("behavior_velocity_planner::MergeFromPrivateModulePlugin"); - module_names.emplace_back("behavior_velocity_planner::BlindSpotModulePlugin"); - module_names.emplace_back("behavior_velocity_planner::DetectionAreaModulePlugin"); + module_names.emplace_back("autoware::behavior_velocity_planner::MergeFromPrivateModulePlugin"); + module_names.emplace_back("autoware::behavior_velocity_planner::BlindSpotModulePlugin"); + module_names.emplace_back("autoware::behavior_velocity_planner::DetectionAreaModulePlugin"); module_names.emplace_back("autoware::behavior_velocity_planner::VirtualTrafficLightModulePlugin"); - module_names.emplace_back("behavior_velocity_planner::NoStoppingAreaModulePlugin"); - module_names.emplace_back("behavior_velocity_planner::StopLineModulePlugin"); - module_names.emplace_back("behavior_velocity_planner::OcclusionSpotModulePlugin"); + module_names.emplace_back("autoware::behavior_velocity_planner::NoStoppingAreaModulePlugin"); + module_names.emplace_back("autoware::behavior_velocity_planner::StopLineModulePlugin"); + module_names.emplace_back("autoware::behavior_velocity_planner::OcclusionSpotModulePlugin"); module_names.emplace_back("autoware::behavior_velocity_planner::RunOutModulePlugin"); - module_names.emplace_back("behavior_velocity_planner::SpeedBumpModulePlugin"); - module_names.emplace_back("behavior_velocity_planner::OutOfLaneModulePlugin"); - module_names.emplace_back("behavior_velocity_planner::NoDrivableLaneModulePlugin"); + module_names.emplace_back("autoware::behavior_velocity_planner::SpeedBumpModulePlugin"); + module_names.emplace_back("autoware::behavior_velocity_planner::OutOfLaneModulePlugin"); + module_names.emplace_back("autoware::behavior_velocity_planner::NoDrivableLaneModulePlugin"); std::vector params; params.emplace_back("launch_modules", module_names); diff --git a/planning/behavior_velocity_planner_common/CMakeLists.txt b/planning/autoware_behavior_velocity_planner_common/CMakeLists.txt similarity index 93% rename from planning/behavior_velocity_planner_common/CMakeLists.txt rename to planning/autoware_behavior_velocity_planner_common/CMakeLists.txt index c8847164851e8..9cb992312f52a 100644 --- a/planning/behavior_velocity_planner_common/CMakeLists.txt +++ b/planning/autoware_behavior_velocity_planner_common/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(behavior_velocity_planner_common) +project(autoware_behavior_velocity_planner_common) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/planning/behavior_velocity_planner_common/README.md b/planning/autoware_behavior_velocity_planner_common/README.md similarity index 100% rename from planning/behavior_velocity_planner_common/README.md rename to planning/autoware_behavior_velocity_planner_common/README.md diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp similarity index 93% rename from planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp rename to planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp index 51511b94f3e33..907683998dd29 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp +++ b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ -#define BEHAVIOR_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ +#ifndef AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ +#define AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ #include "route_handler/route_handler.hpp" +#include #include -#include #include #include @@ -45,7 +45,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class BehaviorVelocityPlannerNode; struct PlannerData @@ -148,6 +148,6 @@ struct PlannerData return std::make_optional(traffic_light_id_map.at(id)); } }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner -#endif // BEHAVIOR_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ +#endif // AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/plugin_interface.hpp b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/plugin_interface.hpp similarity index 75% rename from planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/plugin_interface.hpp rename to planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/plugin_interface.hpp index dcdb4a7052cc0..86579f06790b2 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/plugin_interface.hpp +++ b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/plugin_interface.hpp @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_VELOCITY_PLANNER_COMMON__PLUGIN_INTERFACE_HPP_ -#define BEHAVIOR_VELOCITY_PLANNER_COMMON__PLUGIN_INTERFACE_HPP_ +#ifndef AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__PLUGIN_INTERFACE_HPP_ +#define AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__PLUGIN_INTERFACE_HPP_ -#include +#include #include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class PluginInterface @@ -38,6 +38,6 @@ class PluginInterface virtual const char * getModuleName() = 0; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner -#endif // BEHAVIOR_VELOCITY_PLANNER_COMMON__PLUGIN_INTERFACE_HPP_ +#endif // AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__PLUGIN_INTERFACE_HPP_ diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/plugin_wrapper.hpp b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/plugin_wrapper.hpp similarity index 78% rename from planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/plugin_wrapper.hpp rename to planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/plugin_wrapper.hpp index abb14dd8b2356..e82211937e55b 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/plugin_wrapper.hpp +++ b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/plugin_wrapper.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_VELOCITY_PLANNER_COMMON__PLUGIN_WRAPPER_HPP_ -#define BEHAVIOR_VELOCITY_PLANNER_COMMON__PLUGIN_WRAPPER_HPP_ +#ifndef AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__PLUGIN_WRAPPER_HPP_ +#define AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__PLUGIN_WRAPPER_HPP_ -#include +#include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { template @@ -48,6 +48,6 @@ class PluginWrapper : public PluginInterface std::unique_ptr scene_manager_; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner -#endif // BEHAVIOR_VELOCITY_PLANNER_COMMON__PLUGIN_WRAPPER_HPP_ +#endif // AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__PLUGIN_WRAPPER_HPP_ diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/scene_module_interface.hpp similarity index 95% rename from planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp rename to planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/scene_module_interface.hpp index 3e7992207f3f1..53b6e064d73b4 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/scene_module_interface.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_VELOCITY_PLANNER_COMMON__SCENE_MODULE_INTERFACE_HPP_ -#define BEHAVIOR_VELOCITY_PLANNER_COMMON__SCENE_MODULE_INTERFACE_HPP_ +#ifndef AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__SCENE_MODULE_INTERFACE_HPP_ +#define AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__SCENE_MODULE_INTERFACE_HPP_ -#include +#include #include #include #include @@ -45,7 +45,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using builtin_interfaces::msg::Time; @@ -276,6 +276,6 @@ class SceneModuleManagerInterfaceWithRTC : public SceneModuleManagerInterface } }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner -#endif // BEHAVIOR_VELOCITY_PLANNER_COMMON__SCENE_MODULE_INTERFACE_HPP_ +#endif // AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__SCENE_MODULE_INTERFACE_HPP_ diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/arc_lane_util.hpp b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/arc_lane_util.hpp similarity index 94% rename from planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/arc_lane_util.hpp rename to planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/arc_lane_util.hpp index c9d292536ac13..5ea1ae9fffcc1 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/arc_lane_util.hpp +++ b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/arc_lane_util.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__ARC_LANE_UTIL_HPP_ -#define BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__ARC_LANE_UTIL_HPP_ +#ifndef AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__ARC_LANE_UTIL_HPP_ +#define AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__ARC_LANE_UTIL_HPP_ -#include +#include #include #include @@ -27,7 +27,7 @@ #define EIGEN_MPL2_ONLY #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace { @@ -195,6 +195,6 @@ std::optional createTargetPoint( const size_t lane_id, const double margin, const double vehicle_offset); } // namespace arc_lane_utils -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner -#endif // BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__ARC_LANE_UTIL_HPP_ +#endif // AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__ARC_LANE_UTIL_HPP_ diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp similarity index 88% rename from planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp rename to planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp index bf238ecad55cb..22bba2b90dcc2 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp +++ b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__BOOST_GEOMETRY_HELPER_HPP_ -#define BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__BOOST_GEOMETRY_HELPER_HPP_ +#ifndef AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__BOOST_GEOMETRY_HELPER_HPP_ +#define AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__BOOST_GEOMETRY_HELPER_HPP_ #include @@ -46,7 +46,7 @@ BOOST_GEOMETRY_REGISTER_POINT_3D( autoware_planning_msgs::msg::TrajectoryPoint, double, cs::cartesian, pose.position.x, pose.position.y, pose.position.z) -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -77,6 +77,6 @@ Polygon2d upScalePolygon( geometry_msgs::msg::Polygon toGeomPoly(const Polygon2d & polygon); -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner -#endif // BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__BOOST_GEOMETRY_HELPER_HPP_ +#endif // AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__BOOST_GEOMETRY_HELPER_HPP_ diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/debug.hpp b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/debug.hpp similarity index 86% rename from planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/debug.hpp rename to planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/debug.hpp index ab44af265fbaa..c6e5d45ec4eb6 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/debug.hpp +++ b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/debug.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__DEBUG_HPP_ -#define BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__DEBUG_HPP_ +#ifndef AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__DEBUG_HPP_ +#define AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__DEBUG_HPP_ #include @@ -26,7 +26,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace debug { @@ -47,5 +47,5 @@ visualization_msgs::msg::MarkerArray createPointsMarkerArray( const int64_t module_id, const rclcpp::Time & now, const double x, const double y, const double z, const double r, const double g, const double b); } // namespace debug -} // namespace behavior_velocity_planner -#endif // BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__DEBUG_HPP_ +} // namespace autoware::behavior_velocity_planner +#endif // AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__DEBUG_HPP_ diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/path_utilization.hpp b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/path_utilization.hpp similarity index 78% rename from planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/path_utilization.hpp rename to planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/path_utilization.hpp index 55a82db1ae390..e9bccc42e1dc4 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/path_utilization.hpp +++ b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/path_utilization.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__PATH_UTILIZATION_HPP_ -#define BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__PATH_UTILIZATION_HPP_ +#ifndef AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__PATH_UTILIZATION_HPP_ +#define AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__PATH_UTILIZATION_HPP_ #include @@ -22,7 +22,7 @@ #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { bool splineInterpolate( const tier4_planning_msgs::msg::PathWithLaneId & input, const double interval, @@ -33,6 +33,6 @@ autoware_planning_msgs::msg::Path filterLitterPathPoint( const autoware_planning_msgs::msg::Path & path); autoware_planning_msgs::msg::Path filterStopPathPoint( const autoware_planning_msgs::msg::Path & path); -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner -#endif // BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__PATH_UTILIZATION_HPP_ +#endif // AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__PATH_UTILIZATION_HPP_ diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/state_machine.hpp b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/state_machine.hpp similarity index 87% rename from planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/state_machine.hpp rename to planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/state_machine.hpp index 73b0fa7d553a3..12dd4db930745 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/state_machine.hpp +++ b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/state_machine.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__STATE_MACHINE_HPP_ -#define BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__STATE_MACHINE_HPP_ +#ifndef AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__STATE_MACHINE_HPP_ +#define AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__STATE_MACHINE_HPP_ #include @@ -21,7 +21,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { /** * @brief Manage stop-go states with safety margin time. @@ -92,5 +92,5 @@ class StateMachine std::shared_ptr start_time_; //! first time received GO when STOP state }; -} // namespace behavior_velocity_planner -#endif // BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__STATE_MACHINE_HPP_ +} // namespace autoware::behavior_velocity_planner +#endif // AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__STATE_MACHINE_HPP_ diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/trajectory_utils.hpp b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/trajectory_utils.hpp similarity index 76% rename from planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/trajectory_utils.hpp rename to planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/trajectory_utils.hpp index 2aadb7883a857..c5040f055c243 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/trajectory_utils.hpp +++ b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/trajectory_utils.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__TRAJECTORY_UTILS_HPP_ -#define BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__TRAJECTORY_UTILS_HPP_ +#ifndef AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__TRAJECTORY_UTILS_HPP_ +#define AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__TRAJECTORY_UTILS_HPP_ -#include +#include #include #include @@ -26,7 +26,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; @@ -40,6 +40,6 @@ bool smoothPath( const PathWithLaneId & in_path, PathWithLaneId & out_path, const std::shared_ptr & planner_data); -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner -#endif // BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__TRAJECTORY_UTILS_HPP_ +#endif // AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__TRAJECTORY_UTILS_HPP_ diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/util.hpp b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/util.hpp similarity index 93% rename from planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/util.hpp rename to planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/util.hpp index 4ef4bb91a295d..2fe728847b8f2 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/utilization/util.hpp +++ b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/utilization/util.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__UTIL_HPP_ -#define BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__UTIL_HPP_ +#ifndef AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__UTIL_HPP_ +#define AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__UTIL_HPP_ #include @@ -35,7 +35,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { struct DetectionRange { @@ -155,11 +155,13 @@ std::unordered_map, lanelet::ConstLanelet> get std::vector unique_lane_ids; if (nearest_lane_id) { // Add subsequent lane_ids from nearest lane_id - unique_lane_ids = behavior_velocity_planner::planning_utils::getSubsequentLaneIdsSetOnPath( - path, *nearest_lane_id); + unique_lane_ids = + autoware::behavior_velocity_planner::planning_utils::getSubsequentLaneIdsSetOnPath( + path, *nearest_lane_id); } else { // Add all lane_ids in path - unique_lane_ids = behavior_velocity_planner::planning_utils::getSortedLaneIdsFromPath(path); + unique_lane_ids = + autoware::behavior_velocity_planner::planning_utils::getSortedLaneIdsFromPath(path); } for (const auto lane_id : unique_lane_ids) { @@ -239,6 +241,6 @@ lanelet::ConstLanelets getConstLaneletsFromIds( } } // namespace planning_utils -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner -#endif // BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__UTIL_HPP_ +#endif // AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__UTIL_HPP_ diff --git a/planning/behavior_velocity_planner_common/package.xml b/planning/autoware_behavior_velocity_planner_common/package.xml similarity index 93% rename from planning/behavior_velocity_planner_common/package.xml rename to planning/autoware_behavior_velocity_planner_common/package.xml index ba847d8b1f853..524387034e4b6 100644 --- a/planning/behavior_velocity_planner_common/package.xml +++ b/planning/autoware_behavior_velocity_planner_common/package.xml @@ -1,9 +1,9 @@ - behavior_velocity_planner_common + autoware_behavior_velocity_planner_common 0.1.0 - The behavior_velocity_planner_common package + The autoware_behavior_velocity_planner_common package Tomoya Kimura Shumpei Wakabayashi diff --git a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp b/planning/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp similarity index 97% rename from planning/behavior_velocity_planner_common/src/scene_module_interface.cpp rename to planning/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp index 3092d33418c8b..94cef496f4f75 100644 --- a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include +#include +#include #include #include #include @@ -21,7 +21,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using tier4_autoware_utils::StopWatch; @@ -281,4 +281,4 @@ void SceneModuleManagerInterfaceWithRTC::deleteExpiredModules( } } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner_common/src/utilization/arc_lane_util.cpp b/planning/autoware_behavior_velocity_planner_common/src/utilization/arc_lane_util.cpp similarity index 94% rename from planning/behavior_velocity_planner_common/src/utilization/arc_lane_util.cpp rename to planning/autoware_behavior_velocity_planner_common/src/utilization/arc_lane_util.cpp index e5705b1367e0e..d7e88f5f33901 100644 --- a/planning/behavior_velocity_planner_common/src/utilization/arc_lane_util.cpp +++ b/planning/autoware_behavior_velocity_planner_common/src/utilization/arc_lane_util.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include #include @@ -62,7 +62,7 @@ return p * v; */ } // namespace -namespace behavior_velocity_planner::arc_lane_utils +namespace autoware::behavior_velocity_planner::arc_lane_utils { double calcSignedDistance(const geometry_msgs::msg::Pose & p1, const geometry_msgs::msg::Point & p2) @@ -134,4 +134,4 @@ std::optional createTargetPoint( const auto front_idx = offset_segment->first; return std::make_pair(front_idx, target_pose); } -} // namespace behavior_velocity_planner::arc_lane_utils +} // namespace autoware::behavior_velocity_planner::arc_lane_utils diff --git a/planning/behavior_velocity_planner_common/src/utilization/boost_geometry_helper.cpp b/planning/autoware_behavior_velocity_planner_common/src/utilization/boost_geometry_helper.cpp similarity index 91% rename from planning/behavior_velocity_planner_common/src/utilization/boost_geometry_helper.cpp rename to planning/autoware_behavior_velocity_planner_common/src/utilization/boost_geometry_helper.cpp index 903cf5aab80e8..50f7cd269a904 100644 --- a/planning/behavior_velocity_planner_common/src/utilization/boost_geometry_helper.cpp +++ b/planning/autoware_behavior_velocity_planner_common/src/utilization/boost_geometry_helper.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { Polygon2d lines2polygon(const LineString2d & left_line, const LineString2d & right_line) @@ -63,4 +63,4 @@ geometry_msgs::msg::Polygon toGeomPoly(const Polygon2d & polygon) } return polygon_msg; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner_common/src/utilization/debug.cpp b/planning/autoware_behavior_velocity_planner_common/src/utilization/debug.cpp similarity index 94% rename from planning/behavior_velocity_planner_common/src/utilization/debug.cpp rename to planning/autoware_behavior_velocity_planner_common/src/utilization/debug.cpp index 00d746c56db85..a8e6828a048ae 100644 --- a/planning/behavior_velocity_planner_common/src/utilization/debug.cpp +++ b/planning/autoware_behavior_velocity_planner_common/src/utilization/debug.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include +#include +#include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace debug { @@ -124,4 +124,4 @@ visualization_msgs::msg::MarkerArray createPointsMarkerArray( return msg; } } // namespace debug -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner_common/src/utilization/path_utilization.cpp b/planning/autoware_behavior_velocity_planner_common/src/utilization/path_utilization.cpp similarity index 96% rename from planning/behavior_velocity_planner_common/src/utilization/path_utilization.cpp rename to planning/autoware_behavior_velocity_planner_common/src/utilization/path_utilization.cpp index fe956e9be9512..eb17242c06b1e 100644 --- a/planning/behavior_velocity_planner_common/src/utilization/path_utilization.cpp +++ b/planning/autoware_behavior_velocity_planner_common/src/utilization/path_utilization.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include #include #include @@ -23,7 +23,7 @@ constexpr double DOUBLE_EPSILON = 1e-6; -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { bool splineInterpolate( const tier4_planning_msgs::msg::PathWithLaneId & input, const double interval, @@ -168,4 +168,4 @@ autoware_planning_msgs::msg::Path filterStopPathPoint( } return filtered_path; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp b/planning/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp similarity index 93% rename from planning/behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp rename to planning/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp index ecc314bca2009..4d2ef59886ba7 100644 --- a/planning/behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp +++ b/planning/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -// #include +// #include #include "motion_utils/trajectory/conversion.hpp" +#include #include -#include #include #include @@ -33,7 +33,7 @@ #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; @@ -89,4 +89,4 @@ bool smoothPath( return true; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner_common/src/utilization/util.cpp b/planning/autoware_behavior_velocity_planner_common/src/utilization/util.cpp similarity index 97% rename from planning/behavior_velocity_planner_common/src/utilization/util.cpp rename to planning/autoware_behavior_velocity_planner_common/src/utilization/util.cpp index b724d01346f1e..4578676aeeee7 100644 --- a/planning/behavior_velocity_planner_common/src/utilization/util.cpp +++ b/planning/autoware_behavior_velocity_planner_common/src/utilization/util.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include +#include +#include #include #include @@ -89,7 +89,7 @@ geometry_msgs::msg::Pose transformRelCoordinate2D( } // namespace -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace planning_utils { @@ -545,11 +545,13 @@ std::vector getLaneletsOnPath( std::vector unique_lane_ids; if (nearest_lane_id) { // Add subsequent lane_ids from nearest lane_id - unique_lane_ids = behavior_velocity_planner::planning_utils::getSubsequentLaneIdsSetOnPath( - path, *nearest_lane_id); + unique_lane_ids = + autoware::behavior_velocity_planner::planning_utils::getSubsequentLaneIdsSetOnPath( + path, *nearest_lane_id); } else { // Add all lane_ids in path - unique_lane_ids = behavior_velocity_planner::planning_utils::getSortedLaneIdsFromPath(path); + unique_lane_ids = + autoware::behavior_velocity_planner::planning_utils::getSortedLaneIdsFromPath(path); } std::vector lanelets; @@ -692,4 +694,4 @@ std::set getAssociativeIntersectionLanelets( } } // namespace planning_utils -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner_common/test/src/test_arc_lane_util.cpp b/planning/autoware_behavior_velocity_planner_common/test/src/test_arc_lane_util.cpp similarity index 93% rename from planning/behavior_velocity_planner_common/test/src/test_arc_lane_util.cpp rename to planning/autoware_behavior_velocity_planner_common/test/src/test_arc_lane_util.cpp index fb2418ba9c829..b835aa0034ec4 100644 --- a/planning/behavior_velocity_planner_common/test/src/test_arc_lane_util.cpp +++ b/planning/autoware_behavior_velocity_planner_common/test/src/test_arc_lane_util.cpp @@ -14,17 +14,18 @@ #include "utils.hpp" -#include -#include +#include +#include #include #include -using PathIndexWithPoint2d = behavior_velocity_planner::arc_lane_utils::PathIndexWithPoint2d; -using LineString2d = behavior_velocity_planner::LineString2d; -using Point2d = behavior_velocity_planner::Point2d; -namespace arc_lane_utils = behavior_velocity_planner::arc_lane_utils; +using PathIndexWithPoint2d = + autoware::behavior_velocity_planner::arc_lane_utils::PathIndexWithPoint2d; +using LineString2d = autoware::behavior_velocity_planner::LineString2d; +using Point2d = autoware::behavior_velocity_planner::Point2d; +namespace arc_lane_utils = autoware::behavior_velocity_planner::arc_lane_utils; namespace { @@ -121,7 +122,7 @@ TEST(findOffsetSegment, case_backward_offset_segment) TEST(checkCollision, various_cases) { - using behavior_velocity_planner::arc_lane_utils::checkCollision; + using autoware::behavior_velocity_planner::arc_lane_utils::checkCollision; constexpr double epsilon = 1e-6; { // normal case with collision diff --git a/planning/behavior_velocity_planner_common/test/src/test_state_machine.cpp b/planning/autoware_behavior_velocity_planner_common/test/src/test_state_machine.cpp similarity index 92% rename from planning/behavior_velocity_planner_common/test/src/test_state_machine.cpp rename to planning/autoware_behavior_velocity_planner_common/test/src/test_state_machine.cpp index ac7c6655ced87..fe6a1e00496b1 100644 --- a/planning/behavior_velocity_planner_common/test/src/test_state_machine.cpp +++ b/planning/autoware_behavior_velocity_planner_common/test/src/test_state_machine.cpp @@ -14,7 +14,7 @@ #include "utils.hpp" -#include +#include #include #include @@ -23,8 +23,8 @@ #include #include -using StateMachine = behavior_velocity_planner::StateMachine; -using State = behavior_velocity_planner::StateMachine::State; +using StateMachine = autoware::behavior_velocity_planner::StateMachine; +using State = autoware::behavior_velocity_planner::StateMachine::State; int enumToInt(State s) { diff --git a/planning/behavior_velocity_planner_common/test/src/test_utilization.cpp b/planning/autoware_behavior_velocity_planner_common/test/src/test_utilization.cpp similarity index 92% rename from planning/behavior_velocity_planner_common/test/src/test_utilization.cpp rename to planning/autoware_behavior_velocity_planner_common/test/src/test_utilization.cpp index fbc5f5d709c5c..5e6c92b662820 100644 --- a/planning/behavior_velocity_planner_common/test/src/test_utilization.cpp +++ b/planning/autoware_behavior_velocity_planner_common/test/src/test_utilization.cpp @@ -15,9 +15,9 @@ #include "motion_utils/trajectory/trajectory.hpp" #include "utils.hpp" -#include -#include -#include +#include +#include +#include #include @@ -35,7 +35,7 @@ TEST(is_ahead_of, nominal) { - using behavior_velocity_planner::planning_utils::isAheadOf; + using autoware::behavior_velocity_planner::planning_utils::isAheadOf; geometry_msgs::msg::Pose target = test::generatePose(0); geometry_msgs::msg::Pose origin = test::generatePose(1); bool is_ahead = isAheadOf(target, origin); @@ -47,7 +47,8 @@ TEST(is_ahead_of, nominal) TEST(smoothDeceleration, calculateMaxSlowDownVelocity) { - using behavior_velocity_planner::planning_utils::calcDecelerationVelocityFromDistanceToTarget; + using autoware::behavior_velocity_planner::planning_utils:: + calcDecelerationVelocityFromDistanceToTarget; const double current_accel = 1.0; const double current_velocity = 5.0; const double max_slow_down_jerk = -1.0; @@ -82,9 +83,9 @@ TEST(smoothDeceleration, calculateMaxSlowDownVelocity) TEST(specialInterpolation, specialInterpolation) { + using autoware::behavior_velocity_planner::interpolatePath; using autoware_planning_msgs::msg::Path; using autoware_planning_msgs::msg::PathPoint; - using behavior_velocity_planner::interpolatePath; using motion_utils::calcSignedArcLength; using motion_utils::searchZeroVelocityIndex; diff --git a/planning/behavior_velocity_planner_common/test/src/utils.hpp b/planning/autoware_behavior_velocity_planner_common/test/src/utils.hpp similarity index 100% rename from planning/behavior_velocity_planner_common/test/src/utils.hpp rename to planning/autoware_behavior_velocity_planner_common/test/src/utils.hpp diff --git a/planning/autoware_behavior_velocity_run_out_module/package.xml b/planning/autoware_behavior_velocity_run_out_module/package.xml index cb2c2df58ffe2..330880b77d3da 100644 --- a/planning/autoware_behavior_velocity_run_out_module/package.xml +++ b/planning/autoware_behavior_velocity_run_out_module/package.xml @@ -19,10 +19,10 @@ autoware_cmake eigen3_cmake_module + autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs behavior_velocity_crosswalk_module - behavior_velocity_planner_common eigen geometry_msgs libboost-dev diff --git a/planning/autoware_behavior_velocity_run_out_module/plugins.xml b/planning/autoware_behavior_velocity_run_out_module/plugins.xml index 1ddcaf8e620e1..0fbaf5091d0f7 100644 --- a/planning/autoware_behavior_velocity_run_out_module/plugins.xml +++ b/planning/autoware_behavior_velocity_run_out_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/autoware_behavior_velocity_run_out_module/src/debug.hpp b/planning/autoware_behavior_velocity_run_out_module/src/debug.hpp index 3c6d475950e7c..c38dd63fadba9 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/debug.hpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/debug.hpp @@ -26,7 +26,6 @@ #include namespace autoware::behavior_velocity_planner { -using ::behavior_velocity_planner::Polygon2d; using sensor_msgs::msg::PointCloud2; using tier4_debug_msgs::msg::Float32MultiArrayStamped; using tier4_debug_msgs::msg::Int32Stamped; diff --git a/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp b/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp index d204c7ec6f2fc..5e8b0382a07c0 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp @@ -32,8 +32,6 @@ namespace autoware::behavior_velocity_planner { -using ::behavior_velocity_planner::Point2d; -using ::behavior_velocity_planner::splineInterpolate; namespace { // create quaternion facing to the nearest trajectory point diff --git a/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.hpp b/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.hpp index b7ed815829a2b..8fb79fb9d8eaa 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.hpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.hpp @@ -18,9 +18,9 @@ #include "debug.hpp" #include "utils.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -47,7 +47,6 @@ namespace autoware::behavior_velocity_planner using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::Shape; -using ::behavior_velocity_planner::PlannerData; using run_out_utils::DynamicObstacle; using run_out_utils::DynamicObstacleData; using run_out_utils::DynamicObstacleParam; @@ -56,7 +55,6 @@ using run_out_utils::PredictedPath; using tier4_planning_msgs::msg::PathPointWithLaneId; using tier4_planning_msgs::msg::PathWithLaneId; using PathPointsWithLaneId = std::vector; -using ::behavior_velocity_planner::Polygons2d; /** * @brief base class for creating dynamic obstacles from multiple types of input diff --git a/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp b/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp index 5ee50863fd162..002a49abae611 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp @@ -22,7 +22,6 @@ namespace autoware::behavior_velocity_planner { -using ::behavior_velocity_planner::SceneModuleManagerInterface; using tier4_autoware_utils::getOrDeclareParameter; RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node) : SceneModuleManagerInterface(node, getModuleName()) @@ -203,4 +202,4 @@ void RunOutModuleManager::setDynamicObstacleCreator( #include PLUGINLIB_EXPORT_CLASS( autoware::behavior_velocity_planner::RunOutModulePlugin, - behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/autoware_behavior_velocity_run_out_module/src/manager.hpp b/planning/autoware_behavior_velocity_run_out_module/src/manager.hpp index f0c49b99c99e5..8cdb17e21d74b 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/manager.hpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/manager.hpp @@ -17,17 +17,14 @@ #include "scene.hpp" -#include -#include -#include +#include +#include +#include #include namespace autoware::behavior_velocity_planner { -using ::behavior_velocity_planner::PluginWrapper; -using ::behavior_velocity_planner::SceneModuleInterface; -using ::behavior_velocity_planner::SceneModuleManagerInterface; class RunOutModuleManager : public SceneModuleManagerInterface { public: diff --git a/planning/autoware_behavior_velocity_run_out_module/src/scene.cpp b/planning/autoware_behavior_velocity_run_out_module/src/scene.cpp index 351ed8e7a09b8..e492bc99be615 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/scene.cpp @@ -17,8 +17,8 @@ #include "behavior_velocity_crosswalk_module/util.hpp" #include "path_utils.hpp" -#include -#include +#include +#include #include #include #include @@ -37,11 +37,8 @@ namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; -using ::behavior_velocity_planner::PlanningBehavior; using object_recognition_utils::convertLabelToString; -namespace planning_utils = ::behavior_velocity_planner::planning_utils; -using ::behavior_velocity_planner::getCrosswalksOnPath; -using ::behavior_velocity_planner::Polygon2d; +namespace planning_utils = autoware::behavior_velocity_planner::planning_utils; RunOutModule::RunOutModule( const int64_t module_id, const std::shared_ptr & planner_data, diff --git a/planning/autoware_behavior_velocity_run_out_module/src/scene.hpp b/planning/autoware_behavior_velocity_run_out_module/src/scene.hpp index 85da1340a5a5d..e3fd30a4e36ce 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/scene.hpp @@ -21,7 +21,7 @@ #include "state_machine.hpp" #include "utils.hpp" -#include +#include #include #include @@ -39,11 +39,6 @@ using tier4_debug_msgs::msg::Float32Stamped; using tier4_planning_msgs::msg::PathPointWithLaneId; using tier4_planning_msgs::msg::PathWithLaneId; using BasicPolygons2d = std::vector; -using ::behavior_velocity_planner::PathWithLaneId; -using ::behavior_velocity_planner::PlannerData; -using ::behavior_velocity_planner::Polygon2d; -using ::behavior_velocity_planner::SceneModuleInterface; -using ::behavior_velocity_planner::StopReason; class RunOutModule : public SceneModuleInterface { diff --git a/planning/autoware_behavior_velocity_run_out_module/src/utils.cpp b/planning/autoware_behavior_velocity_run_out_module/src/utils.cpp index ec1cd460e1bb0..ed745cbb92679 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/utils.cpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/utils.cpp @@ -35,9 +35,6 @@ #include namespace autoware::behavior_velocity_planner { -using ::behavior_velocity_planner::DetectionRange; -using ::behavior_velocity_planner::PathPointWithLaneId; -namespace planning_utils = ::behavior_velocity_planner::planning_utils; namespace run_out_utils { Polygon2d createBoostPolyFromMsg(const std::vector & input_poly) diff --git a/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp b/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp index 10f856b257a61..28bfa9569c66d 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp @@ -17,8 +17,8 @@ #include "tier4_autoware_utils/geometry/geometry.hpp" -#include -#include +#include +#include #include #include @@ -38,8 +38,6 @@ 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 ::behavior_velocity_planner::PlannerData; -using ::behavior_velocity_planner::Polygons2d; using tier4_autoware_utils::Box2d; using tier4_autoware_utils::LineString2d; using tier4_autoware_utils::Point2d; diff --git a/planning/autoware_behavior_velocity_template_module/package.xml b/planning/autoware_behavior_velocity_template_module/package.xml index a6bcbf5c34e76..eb6a6668fcee9 100644 --- a/planning/autoware_behavior_velocity_template_module/package.xml +++ b/planning/autoware_behavior_velocity_template_module/package.xml @@ -13,8 +13,8 @@ autoware_cmake eigen3_cmake_module + autoware_behavior_velocity_planner_common autoware_planning_msgs - behavior_velocity_planner_common eigen geometry_msgs lanelet2_extension diff --git a/planning/autoware_behavior_velocity_template_module/src/manager.cpp b/planning/autoware_behavior_velocity_template_module/src/manager.cpp index 8f6621aaab835..8aaf6be9bbfe9 100644 --- a/planning/autoware_behavior_velocity_template_module/src/manager.cpp +++ b/planning/autoware_behavior_velocity_template_module/src/manager.cpp @@ -61,4 +61,4 @@ TemplateModuleManager::getModuleExpiredFunction( #include PLUGINLIB_EXPORT_CLASS( autoware::behavior_velocity_planner::TemplateModulePlugin, - behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/autoware_behavior_velocity_template_module/src/manager.hpp b/planning/autoware_behavior_velocity_template_module/src/manager.hpp index 8e95f516c337d..b92913b2a95ce 100644 --- a/planning/autoware_behavior_velocity_template_module/src/manager.hpp +++ b/planning/autoware_behavior_velocity_template_module/src/manager.hpp @@ -17,9 +17,9 @@ #include "scene.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -37,7 +37,8 @@ namespace autoware::behavior_velocity_planner * * @param node A reference to the ROS node. */ -class TemplateModuleManager : public ::behavior_velocity_planner::SceneModuleManagerInterface +class TemplateModuleManager +: public autoware::behavior_velocity_planner::SceneModuleManagerInterface { public: explicit TemplateModuleManager(rclcpp::Node & node); @@ -85,7 +86,7 @@ class TemplateModuleManager : public ::behavior_velocity_planner::SceneModuleMan * Velocity Planner. */ class TemplateModulePlugin -: public ::behavior_velocity_planner::PluginWrapper +: public autoware::behavior_velocity_planner::PluginWrapper { }; diff --git a/planning/autoware_behavior_velocity_template_module/src/scene.hpp b/planning/autoware_behavior_velocity_template_module/src/scene.hpp index 3ce5ddbd8729d..0fc4e7dd9ae91 100644 --- a/planning/autoware_behavior_velocity_template_module/src/scene.hpp +++ b/planning/autoware_behavior_velocity_template_module/src/scene.hpp @@ -15,7 +15,7 @@ #ifndef SCENE_HPP_ #define SCENE_HPP_ -#include +#include #include #include @@ -23,8 +23,6 @@ namespace autoware::behavior_velocity_planner { -using ::behavior_velocity_planner::SceneModuleInterface; -using ::behavior_velocity_planner::StopReason; using tier4_planning_msgs::msg::PathWithLaneId; class TemplateModule : public SceneModuleInterface diff --git a/planning/autoware_behavior_velocity_virtual_traffic_light_module/package.xml b/planning/autoware_behavior_velocity_virtual_traffic_light_module/package.xml index cd35d4308c26a..cda3abbd0eee9 100644 --- a/planning/autoware_behavior_velocity_virtual_traffic_light_module/package.xml +++ b/planning/autoware_behavior_velocity_virtual_traffic_light_module/package.xml @@ -17,8 +17,8 @@ autoware_cmake autoware_adapi_v1_msgs + autoware_behavior_velocity_planner_common autoware_planning_msgs - behavior_velocity_planner_common geometry_msgs lanelet2_extension motion_utils diff --git a/planning/autoware_behavior_velocity_virtual_traffic_light_module/plugins.xml b/planning/autoware_behavior_velocity_virtual_traffic_light_module/plugins.xml index 2402fc13469b9..2e2abef259778 100644 --- a/planning/autoware_behavior_velocity_virtual_traffic_light_module/plugins.xml +++ b/planning/autoware_behavior_velocity_virtual_traffic_light_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp b/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp index 5a32cfd2f74f0..39dca1f8f6303 100644 --- a/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp +++ b/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp @@ -14,7 +14,7 @@ #include "manager.hpp" -#include +#include #include #include @@ -28,7 +28,7 @@ namespace autoware::behavior_velocity_planner { using lanelet::autoware::VirtualTrafficLight; using tier4_autoware_utils::getOrDeclareParameter; -namespace planning_utils = ::behavior_velocity_planner::planning_utils; +namespace planning_utils = autoware::behavior_velocity_planner::planning_utils; VirtualTrafficLightModuleManager::VirtualTrafficLightModuleManager(rclcpp::Node & node) : SceneModuleManagerInterface(node, getModuleName()) @@ -82,4 +82,4 @@ VirtualTrafficLightModuleManager::getModuleExpiredFunction( #include PLUGINLIB_EXPORT_CLASS( autoware::behavior_velocity_planner::VirtualTrafficLightModulePlugin, - behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.hpp b/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.hpp index c73bb0d706008..6b0436a4290ac 100644 --- a/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.hpp +++ b/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.hpp @@ -17,9 +17,9 @@ #include "scene.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -29,9 +29,6 @@ namespace autoware::behavior_velocity_planner { -using ::behavior_velocity_planner::PluginWrapper; -using ::behavior_velocity_planner::SceneModuleInterface; -using ::behavior_velocity_planner::SceneModuleManagerInterface; class VirtualTrafficLightModuleManager : public SceneModuleManagerInterface { public: diff --git a/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp b/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp index 7d91a954171dd..a87d8867adf7e 100644 --- a/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp +++ b/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp @@ -14,8 +14,8 @@ #include "scene.hpp" -#include -#include +#include +#include #include #include @@ -25,11 +25,6 @@ namespace autoware::behavior_velocity_planner { -using ::behavior_velocity_planner::PlanningBehavior; -using ::behavior_velocity_planner::SceneModuleInterface; -using ::behavior_velocity_planner::VelocityFactor; -namespace arc_lane_utils = ::behavior_velocity_planner::arc_lane_utils; -namespace planning_utils = ::behavior_velocity_planner::planning_utils; namespace { using tier4_autoware_utils::calcDistance2d; @@ -181,7 +176,8 @@ std::optional insertStopVelocityAtCollision( auto insert_point = path->points.at(insert_index); insert_point.point.pose = interpolated_pose; // Insert 0 velocity after stop point or replace velocity with 0 - behavior_velocity_planner::planning_utils::insertVelocity(*path, insert_point, 0.0, insert_index); + autoware::behavior_velocity_planner::planning_utils::insertVelocity( + *path, insert_point, 0.0, insert_index); return insert_index; } } // namespace diff --git a/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp b/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp index c83ff4e0607ef..9775e64145529 100644 --- a/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp +++ b/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp @@ -15,7 +15,7 @@ #ifndef SCENE_HPP_ #define SCENE_HPP_ -#include +#include #include #include #include @@ -32,10 +32,6 @@ namespace autoware::behavior_velocity_planner { -using ::behavior_velocity_planner::PathWithLaneId; -using ::behavior_velocity_planner::Pose; -using ::behavior_velocity_planner::SceneModuleInterface; -using ::behavior_velocity_planner::StopReason; class VirtualTrafficLightModule : public SceneModuleInterface { public: diff --git a/planning/autoware_behavior_velocity_walkway_module/package.xml b/planning/autoware_behavior_velocity_walkway_module/package.xml index 59fa84acefcbb..bbe87ffb8b2cd 100644 --- a/planning/autoware_behavior_velocity_walkway_module/package.xml +++ b/planning/autoware_behavior_velocity_walkway_module/package.xml @@ -17,9 +17,9 @@ ament_cmake_auto autoware_cmake + autoware_behavior_velocity_planner_common autoware_planning_msgs behavior_velocity_crosswalk_module - behavior_velocity_planner_common geometry_msgs lanelet2_extension libboost-dev diff --git a/planning/autoware_behavior_velocity_walkway_module/plugins.xml b/planning/autoware_behavior_velocity_walkway_module/plugins.xml index d7f9e948154c1..9a5803807ae8d 100644 --- a/planning/autoware_behavior_velocity_walkway_module/plugins.xml +++ b/planning/autoware_behavior_velocity_walkway_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/autoware_behavior_velocity_walkway_module/src/debug.cpp b/planning/autoware_behavior_velocity_walkway_module/src/debug.cpp index d26a47e512bc4..80badf59434da 100644 --- a/planning/autoware_behavior_velocity_walkway_module/src/debug.cpp +++ b/planning/autoware_behavior_velocity_walkway_module/src/debug.cpp @@ -14,7 +14,7 @@ #include "scene_walkway.hpp" -#include +#include #include #include #include @@ -34,7 +34,6 @@ using tier4_autoware_utils::createMarkerColor; using tier4_autoware_utils::createMarkerScale; using tier4_autoware_utils::createPoint; using visualization_msgs::msg::Marker; -namespace planning_utils = ::behavior_velocity_planner::planning_utils; namespace { diff --git a/planning/autoware_behavior_velocity_walkway_module/src/manager.cpp b/planning/autoware_behavior_velocity_walkway_module/src/manager.cpp index 1adea85788d5b..cf3efe3700a05 100644 --- a/planning/autoware_behavior_velocity_walkway_module/src/manager.cpp +++ b/planning/autoware_behavior_velocity_walkway_module/src/manager.cpp @@ -14,7 +14,7 @@ #include "manager.hpp" -#include +#include #include #include @@ -26,12 +26,8 @@ namespace autoware::behavior_velocity_planner { -using ::behavior_velocity_planner::SceneModuleManagerInterface; using lanelet::autoware::Crosswalk; using tier4_autoware_utils::getOrDeclareParameter; -namespace planning_utils = ::behavior_velocity_planner::planning_utils; -using ::behavior_velocity_planner::getCrosswalkIdSetOnPath; -using ::behavior_velocity_planner::getCrosswalksOnPath; WalkwayModuleManager::WalkwayModuleManager(rclcpp::Node & node) : SceneModuleManagerInterface(node, getModuleName()) @@ -109,4 +105,4 @@ WalkwayModuleManager::getModuleExpiredFunction(const PathWithLaneId & path) #include PLUGINLIB_EXPORT_CLASS( autoware::behavior_velocity_planner::WalkwayModulePlugin, - ::behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/autoware_behavior_velocity_walkway_module/src/manager.hpp b/planning/autoware_behavior_velocity_walkway_module/src/manager.hpp index d19bf9c1c1d5f..592181dd3ac75 100644 --- a/planning/autoware_behavior_velocity_walkway_module/src/manager.hpp +++ b/planning/autoware_behavior_velocity_walkway_module/src/manager.hpp @@ -17,9 +17,9 @@ #include "scene_walkway.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -33,9 +33,6 @@ namespace autoware::behavior_velocity_planner { -using ::behavior_velocity_planner::PluginWrapper; -using ::behavior_velocity_planner::SceneModuleInterface; -using ::behavior_velocity_planner::SceneModuleManagerInterface; using tier4_planning_msgs::msg::PathWithLaneId; class WalkwayModuleManager : public SceneModuleManagerInterface diff --git a/planning/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp b/planning/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp index 236654e598216..73ae5a52e0183 100644 --- a/planning/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp +++ b/planning/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp @@ -14,7 +14,7 @@ #include "scene_walkway.hpp" -#include +#include #include #include @@ -22,19 +22,11 @@ namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; -using ::behavior_velocity_planner::getLinestringIntersects; -using ::behavior_velocity_planner::getPolygonIntersects; -using ::behavior_velocity_planner::getStopLineFromMap; -using ::behavior_velocity_planner::PlanningBehavior; -using ::behavior_velocity_planner::SceneModuleInterface; -using ::behavior_velocity_planner::StopFactor; -using ::behavior_velocity_planner::VelocityFactor; using motion_utils::calcLongitudinalOffsetPose; using motion_utils::calcSignedArcLength; using motion_utils::findNearestSegmentIndex; using tier4_autoware_utils::createPoint; using tier4_autoware_utils::getPose; -namespace planning_utils = ::behavior_velocity_planner::planning_utils; WalkwayModule::WalkwayModule( const int64_t module_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, diff --git a/planning/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp b/planning/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp index 1928466400134..e6c8f61ba656e 100644 --- a/planning/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp +++ b/planning/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp @@ -18,7 +18,7 @@ #include "behavior_velocity_crosswalk_module/util.hpp" #include "scene_walkway.hpp" -#include +#include #include #include @@ -33,11 +33,6 @@ namespace autoware::behavior_velocity_planner { -using ::behavior_velocity_planner::DebugData; -using ::behavior_velocity_planner::PathWithLaneId; -using ::behavior_velocity_planner::SceneModuleInterface; -using ::behavior_velocity_planner::StopReason; - class WalkwayModule : public SceneModuleInterface { public: diff --git a/planning/behavior_velocity_blind_spot_module/package.xml b/planning/behavior_velocity_blind_spot_module/package.xml index ebf760405a256..67947398afb01 100644 --- a/planning/behavior_velocity_blind_spot_module/package.xml +++ b/planning/behavior_velocity_blind_spot_module/package.xml @@ -16,9 +16,9 @@ ament_cmake_auto autoware_cmake + autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs - behavior_velocity_planner_common geometry_msgs lanelet2_extension motion_utils diff --git a/planning/behavior_velocity_blind_spot_module/plugins.xml b/planning/behavior_velocity_blind_spot_module/plugins.xml index 7dda59ea2fdbe..fb5019de5df08 100644 --- a/planning/behavior_velocity_blind_spot_module/plugins.xml +++ b/planning/behavior_velocity_blind_spot_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/behavior_velocity_blind_spot_module/src/debug.cpp b/planning/behavior_velocity_blind_spot_module/src/debug.cpp index a30836ab9f6a9..c357df481bca8 100644 --- a/planning/behavior_velocity_blind_spot_module/src/debug.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/debug.cpp @@ -14,8 +14,8 @@ #include "scene.hpp" -#include -#include +#include +#include #include #include @@ -25,7 +25,7 @@ #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using tier4_autoware_utils::appendMarkerArray; using tier4_autoware_utils::createMarkerColor; @@ -107,4 +107,4 @@ visualization_msgs::msg::MarkerArray BlindSpotModule::createDebugMarkerArray() return debug_marker_array; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_blind_spot_module/src/decisions.cpp b/planning/behavior_velocity_blind_spot_module/src/decisions.cpp index 6e4135c50b253..6b963d86c9bbf 100644 --- a/planning/behavior_velocity_blind_spot_module/src/decisions.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/decisions.cpp @@ -16,7 +16,7 @@ #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { /* @@ -150,4 +150,4 @@ void BlindSpotModule::reactRTCApprovalByDecision( return; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_blind_spot_module/src/manager.cpp b/planning/behavior_velocity_blind_spot_module/src/manager.cpp index f1b0a56018d9b..7f2f7ebd89baa 100644 --- a/planning/behavior_velocity_blind_spot_module/src/manager.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/manager.cpp @@ -14,8 +14,8 @@ #include "manager.hpp" -#include -#include +#include +#include #include @@ -25,7 +25,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { BlindSpotModuleManager::BlindSpotModuleManager(rclcpp::Node & node) @@ -95,8 +95,9 @@ BlindSpotModuleManager::getModuleExpiredFunction( }; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #include PLUGINLIB_EXPORT_CLASS( - behavior_velocity_planner::BlindSpotModulePlugin, behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::BlindSpotModulePlugin, + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/behavior_velocity_blind_spot_module/src/manager.hpp b/planning/behavior_velocity_blind_spot_module/src/manager.hpp index 7d6f936cc9d5b..12dccd846affc 100644 --- a/planning/behavior_velocity_blind_spot_module/src/manager.hpp +++ b/planning/behavior_velocity_blind_spot_module/src/manager.hpp @@ -17,9 +17,9 @@ #include "scene.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -27,7 +27,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class BlindSpotModuleManager : public SceneModuleManagerInterfaceWithRTC { @@ -49,6 +49,6 @@ class BlindSpotModulePlugin : public PluginWrapper { }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // MANAGER_HPP_ diff --git a/planning/behavior_velocity_blind_spot_module/src/scene.cpp b/planning/behavior_velocity_blind_spot_module/src/scene.cpp index 14ebe70216d5a..eed767fb891f9 100644 --- a/planning/behavior_velocity_blind_spot_module/src/scene.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/scene.cpp @@ -14,9 +14,9 @@ #include "scene.hpp" -#include -#include -#include +#include +#include +#include #include #include #include @@ -40,7 +40,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -704,4 +704,4 @@ bool BlindSpotModule::isTargetObjectType( return false; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_blind_spot_module/src/scene.hpp b/planning/behavior_velocity_blind_spot_module/src/scene.hpp index b3bf90f5b91d1..cfb6bfdfeeded 100644 --- a/planning/behavior_velocity_blind_spot_module/src/scene.hpp +++ b/planning/behavior_velocity_blind_spot_module/src/scene.hpp @@ -15,9 +15,9 @@ #ifndef SCENE_HPP_ #define SCENE_HPP_ -#include -#include -#include +#include +#include +#include #include #include @@ -34,7 +34,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { /** * @brief wrapper class of interpolated path with lane id @@ -237,6 +237,6 @@ class BlindSpotModule : public SceneModuleInterface // Debug mutable DebugData debug_data_; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // SCENE_HPP_ diff --git a/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp b/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp index 690eca196d536..ca07636c2f60e 100644 --- a/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp +++ b/planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp @@ -33,12 +33,12 @@ #define EIGEN_MPL2_ONLY #include #include -#include +#include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using tier4_planning_msgs::msg::PathPointWithLaneId; @@ -108,6 +108,6 @@ std::vector getLinestringIntersects( std::optional getStopLineFromMap( const lanelet::Id lane_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, const std::string & attribute_name); -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // BEHAVIOR_VELOCITY_CROSSWALK_MODULE__UTIL_HPP_ diff --git a/planning/behavior_velocity_crosswalk_module/package.xml b/planning/behavior_velocity_crosswalk_module/package.xml index 2fd5e2bb514c3..eebf9c4d4a14f 100644 --- a/planning/behavior_velocity_crosswalk_module/package.xml +++ b/planning/behavior_velocity_crosswalk_module/package.xml @@ -21,9 +21,9 @@ autoware_cmake eigen3_cmake_module + autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs - behavior_velocity_planner_common eigen geometry_msgs grid_map_core diff --git a/planning/behavior_velocity_crosswalk_module/plugins.xml b/planning/behavior_velocity_crosswalk_module/plugins.xml index 3d1d720857c17..e38ab0d85a63a 100644 --- a/planning/behavior_velocity_crosswalk_module/plugins.xml +++ b/planning/behavior_velocity_crosswalk_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/behavior_velocity_crosswalk_module/src/debug.cpp b/planning/behavior_velocity_crosswalk_module/src/debug.cpp index 4bee98db2fa56..1418d46081fcd 100644 --- a/planning/behavior_velocity_crosswalk_module/src/debug.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/debug.cpp @@ -14,14 +14,14 @@ #include "scene_crosswalk.hpp" -#include +#include #include #include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using motion_utils::createSlowDownVirtualWallMarker; @@ -207,4 +207,4 @@ visualization_msgs::msg::MarkerArray CrosswalkModule::createDebugMarkerArray() return debug_marker_array; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index fe4282893674c..428ec2510c7f4 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -14,7 +14,7 @@ #include "manager.hpp" -#include +#include #include #include @@ -24,7 +24,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using lanelet::autoware::Crosswalk; @@ -229,8 +229,9 @@ CrosswalkModuleManager::getModuleExpiredFunction(const PathWithLaneId & path) return crosswalk_id_set.count(scene_module->getModuleId()) == 0; }; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #include PLUGINLIB_EXPORT_CLASS( - behavior_velocity_planner::CrosswalkModulePlugin, behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::CrosswalkModulePlugin, + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.hpp b/planning/behavior_velocity_crosswalk_module/src/manager.hpp index ba7e75193deab..520dab49b347f 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.hpp @@ -17,9 +17,9 @@ #include "scene_crosswalk.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -32,7 +32,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using tier4_planning_msgs::msg::PathWithLaneId; @@ -56,6 +56,6 @@ class CrosswalkModuleManager : public SceneModuleManagerInterfaceWithRTC class CrosswalkModulePlugin : public PluginWrapper { }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // MANAGER_HPP_ diff --git a/planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp index b6adb32f642eb..619e389f3fcf8 100644 --- a/planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp @@ -22,11 +22,11 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { bool is_occluded( const grid_map::GridMap & grid_map, const int min_nb_of_cells, const grid_map::Index idx, - const behavior_velocity_planner::CrosswalkModule::PlannerParam & params) + const autoware::behavior_velocity_planner::CrosswalkModule::PlannerParam & params) { grid_map::Index idx_offset; for (idx_offset.x() = 0; idx_offset.x() < min_nb_of_cells; ++idx_offset.x()) { @@ -140,7 +140,7 @@ bool is_crosswalk_occluded( const nav_msgs::msg::OccupancyGrid & occupancy_grid, const geometry_msgs::msg::Point & path_intersection, const double detection_range, const std::vector & dynamic_objects, - const behavior_velocity_planner::CrosswalkModule::PlannerParam & params) + const autoware::behavior_velocity_planner::CrosswalkModule::PlannerParam & params) { grid_map::GridMap grid_map; grid_map::GridMapRosConverter::fromOccupancyGrid(occupancy_grid, "layer", grid_map); @@ -170,4 +170,4 @@ double calculate_detection_range( const auto time_to_crosswalk = dist_ego_to_crosswalk / std::max(min_ego_velocity, ego_velocity); return time_to_crosswalk > 0.0 ? time_to_crosswalk / occluded_object_velocity : 20.0; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.hpp index 4aab9d3bfc888..c4f2c1a23c57e 100644 --- a/planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.hpp @@ -29,7 +29,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { /// @brief check if the gridmap is occluded at the given index /// @param [in] grid_map input grid map @@ -40,7 +40,7 @@ namespace behavior_velocity_planner /// @return true if the index is occluded bool is_occluded( const grid_map::GridMap & grid_map, const int min_nb_of_cells, const grid_map::Index idx, - const behavior_velocity_planner::CrosswalkModule::PlannerParam & params); + const autoware::behavior_velocity_planner::CrosswalkModule::PlannerParam & params); /// @brief interpolate a point beyond the end of the given segment /// @param [in] segment input segment @@ -62,7 +62,7 @@ bool is_crosswalk_occluded( const nav_msgs::msg::OccupancyGrid & occupancy_grid, const geometry_msgs::msg::Point & path_intersection, const double detection_range, const std::vector & dynamic_objects, - const behavior_velocity_planner::CrosswalkModule::PlannerParam & params); + const autoware::behavior_velocity_planner::CrosswalkModule::PlannerParam & params); /// @brief calculate the distance away from the crosswalk that should be checked for occlusions /// @param occluded_objects_velocity assumed velocity of the objects coming out of occlusions @@ -89,6 +89,6 @@ std::vector select_and_inflate_o void clear_occlusions_behind_objects( grid_map::GridMap & grid_map, const std::vector & objects); -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // OCCLUDED_CROSSWALK_HPP_ diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 191eea8feabed..91893c5224550 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -16,8 +16,8 @@ #include "occluded_crosswalk.hpp" -#include -#include +#include +#include #include #include #include @@ -38,7 +38,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; using motion_utils::calcArcLength; @@ -1281,4 +1281,4 @@ void CrosswalkModule::planStop( ego_path.points, planner_data_->current_odometry->pose, stop_factor->stop_pose, VelocityFactor::UNKNOWN); } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 107a904dd076b..13ecddafb6490 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -17,7 +17,7 @@ #include "behavior_velocity_crosswalk_module/util.hpp" -#include +#include #include #include #include @@ -46,7 +46,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; using autoware_perception_msgs::msg::ObjectClassification; @@ -459,6 +459,6 @@ class CrosswalkModule : public SceneModuleInterface std::optional current_initial_occlusion_time_; std::optional most_recent_occlusion_time_; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // SCENE_CROSSWALK_HPP_ diff --git a/planning/behavior_velocity_crosswalk_module/src/util.cpp b/planning/behavior_velocity_crosswalk_module/src/util.cpp index d276ae95e06b6..883b40b89730f 100644 --- a/planning/behavior_velocity_crosswalk_module/src/util.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/util.cpp @@ -14,7 +14,7 @@ #include "behavior_velocity_crosswalk_module/util.hpp" -#include +#include #include #include #include @@ -45,7 +45,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; using motion_utils::calcSignedArcLength; @@ -62,16 +62,19 @@ std::vector> getCrosswalksOnPath( // Add current lane id const auto nearest_lane_id = - behavior_velocity_planner::planning_utils::getNearestLaneId(path, lanelet_map, current_pose); + autoware::behavior_velocity_planner::planning_utils::getNearestLaneId( + path, lanelet_map, current_pose); std::vector unique_lane_ids; if (nearest_lane_id) { // Add subsequent lane_ids from nearest lane_id - unique_lane_ids = behavior_velocity_planner::planning_utils::getSubsequentLaneIdsSetOnPath( - path, *nearest_lane_id); + unique_lane_ids = + autoware::behavior_velocity_planner::planning_utils::getSubsequentLaneIdsSetOnPath( + path, *nearest_lane_id); } else { // Add all lane_ids in path - unique_lane_ids = behavior_velocity_planner::planning_utils::getSortedLaneIdsFromPath(path); + unique_lane_ids = + autoware::behavior_velocity_planner::planning_utils::getSortedLaneIdsFromPath(path); } for (const auto lane_id : unique_lane_ids) { @@ -229,4 +232,4 @@ std::optional getStopLineFromMap( return stop_line.front(); } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_detection_area_module/package.xml b/planning/behavior_velocity_detection_area_module/package.xml index 6bcca43edc0cb..b2d370380829a 100644 --- a/planning/behavior_velocity_detection_area_module/package.xml +++ b/planning/behavior_velocity_detection_area_module/package.xml @@ -17,8 +17,8 @@ autoware_cmake eigen3_cmake_module + autoware_behavior_velocity_planner_common autoware_planning_msgs - behavior_velocity_planner_common eigen geometry_msgs lanelet2_extension diff --git a/planning/behavior_velocity_detection_area_module/plugins.xml b/planning/behavior_velocity_detection_area_module/plugins.xml index 73497c8bfdf2a..9356c863ec26e 100644 --- a/planning/behavior_velocity_detection_area_module/plugins.xml +++ b/planning/behavior_velocity_detection_area_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/behavior_velocity_detection_area_module/src/debug.cpp b/planning/behavior_velocity_detection_area_module/src/debug.cpp index ee2af54e5ea2a..1ce982cd8df52 100644 --- a/planning/behavior_velocity_detection_area_module/src/debug.cpp +++ b/planning/behavior_velocity_detection_area_module/src/debug.cpp @@ -14,8 +14,8 @@ #include "scene.hpp" -#include -#include +#include +#include #include #include #include @@ -29,7 +29,7 @@ #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using std_msgs::msg::ColorRGBA; using tier4_autoware_utils::appendMarkerArray; @@ -191,4 +191,4 @@ motion_utils::VirtualWalls DetectionAreaModule::createVirtualWalls() return virtual_walls; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_detection_area_module/src/manager.cpp b/planning/behavior_velocity_detection_area_module/src/manager.cpp index feb5bf6bb50ef..336a1710ed593 100644 --- a/planning/behavior_velocity_detection_area_module/src/manager.cpp +++ b/planning/behavior_velocity_detection_area_module/src/manager.cpp @@ -14,7 +14,7 @@ #include "manager.hpp" -#include +#include #include #include @@ -28,7 +28,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using lanelet::autoware::DetectionArea; using tier4_autoware_utils::getOrDeclareParameter; @@ -84,8 +84,9 @@ DetectionAreaModuleManager::getModuleExpiredFunction( }; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #include PLUGINLIB_EXPORT_CLASS( - behavior_velocity_planner::DetectionAreaModulePlugin, behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::DetectionAreaModulePlugin, + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/behavior_velocity_detection_area_module/src/manager.hpp b/planning/behavior_velocity_detection_area_module/src/manager.hpp index 71cfa0a5eef96..64a76171814b9 100644 --- a/planning/behavior_velocity_detection_area_module/src/manager.hpp +++ b/planning/behavior_velocity_detection_area_module/src/manager.hpp @@ -17,9 +17,9 @@ #include "scene.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -27,7 +27,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class DetectionAreaModuleManager : public SceneModuleManagerInterfaceWithRTC { @@ -49,6 +49,6 @@ class DetectionAreaModulePlugin : public PluginWrapper -#include +#include +#include #include #ifdef ROS_DISTRO_GALACTIC #include @@ -30,7 +30,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; using motion_utils::calcLongitudinalOffsetPose; @@ -339,4 +339,4 @@ bool DetectionAreaModule::hasEnoughBrakingDistance( return arc_lane_utils::calcSignedDistance(self_pose, line_pose.position) > pass_judge_line_distance; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_detection_area_module/src/scene.hpp b/planning/behavior_velocity_detection_area_module/src/scene.hpp index f135c3b2660cb..f577cd92dea6e 100644 --- a/planning/behavior_velocity_detection_area_module/src/scene.hpp +++ b/planning/behavior_velocity_detection_area_module/src/scene.hpp @@ -23,15 +23,15 @@ #define EIGEN_MPL2_ONLY #include -#include -#include +#include +#include #include #include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using PathIndexWithPose = std::pair; // front index, pose using PathIndexWithPoint2d = std::pair; // front index, point2d @@ -101,6 +101,6 @@ class DetectionAreaModule : public SceneModuleInterface // Debug DebugData debug_data_; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // SCENE_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml b/planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml index 84d01d04a09a4..6b9db657d6d8e 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml @@ -12,9 +12,9 @@ ament_cmake_auto autoware_cmake + autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs - behavior_velocity_planner_common geometry_msgs libboost-dev motion_utils diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/plugins.xml b/planning/behavior_velocity_dynamic_obstacle_stop_module/plugins.xml index 2f5662c7998ac..ba2d2ba61ad50 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/plugins.xml +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp index 8497369917232..10843fd3aef2b 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp @@ -24,7 +24,7 @@ #include #include -namespace behavior_velocity_planner::dynamic_obstacle_stop +namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop { std::optional find_closest_collision_point( @@ -80,4 +80,4 @@ std::vector find_collisions( return collisions; } -} // namespace behavior_velocity_planner::dynamic_obstacle_stop +} // namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp index 27a48afa032b1..8431221a27d6b 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp @@ -20,7 +20,7 @@ #include #include -namespace behavior_velocity_planner::dynamic_obstacle_stop +namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop { /// @brief find the collision point closest to ego along an object footprint /// @param [in] ego_data ego data including its path and footprints used for finding a collision @@ -41,6 +41,6 @@ std::vector find_collisions( const std::vector & objects, const tier4_autoware_utils::MultiPolygon2d & obstacle_forward_footprints); -} // namespace behavior_velocity_planner::dynamic_obstacle_stop +} // namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop #endif // COLLISION_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp index 367a1c2be1d5a..5a457d651cd9e 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.cpp @@ -23,7 +23,7 @@ #include #include -namespace behavior_velocity_planner::dynamic_obstacle_stop::debug +namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop::debug { std::vector make_delete_markers( @@ -110,4 +110,4 @@ std::vector make_polygon_markers( } return markers; } -} // namespace behavior_velocity_planner::dynamic_obstacle_stop::debug +} // namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop::debug diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp index 7397f63ca079c..c567948927089 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/debug.hpp @@ -28,7 +28,7 @@ #include #include -namespace behavior_velocity_planner::dynamic_obstacle_stop::debug +namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop::debug { std::vector make_delete_markers( const size_t from, const size_t to, const std::string & ns); @@ -40,6 +40,6 @@ std::vector make_collision_markers( const rclcpp::Time & now); std::vector make_polygon_markers( const tier4_autoware_utils::MultiPolygon2d & footprints, const std::string & ns, const double z); -} // namespace behavior_velocity_planner::dynamic_obstacle_stop::debug +} // namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop::debug #endif // DEBUG_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp index a58e4e9b88c75..5f005348c4cea 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp @@ -26,7 +26,7 @@ #include #include -namespace behavior_velocity_planner::dynamic_obstacle_stop +namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop { tier4_autoware_utils::MultiPolygon2d make_forward_footprints( const std::vector & obstacles, @@ -81,4 +81,4 @@ void make_ego_footprint_rtree(EgoData & ego_data, const PlannerParam & params) } } -} // namespace behavior_velocity_planner::dynamic_obstacle_stop +} // namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp index 0050a4e2c9259..c75d7bb9cc49e 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp @@ -21,7 +21,7 @@ #include -namespace behavior_velocity_planner::dynamic_obstacle_stop +namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop { /// @brief create the footprint of the given obstacles and their projection over a fixed time /// horizon @@ -50,6 +50,6 @@ tier4_autoware_utils::Polygon2d project_to_pose( /// @param [inout] ego_data ego data with its path and the rtree to populate /// @param [in] params parameters void make_ego_footprint_rtree(EgoData & ego_data, const PlannerParam & params); -} // namespace behavior_velocity_planner::dynamic_obstacle_stop +} // namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop #endif // FOOTPRINT_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp index 63f1f3025f94a..ddb8c842fb92d 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp @@ -20,7 +20,7 @@ #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using tier4_autoware_utils::getOrDeclareParameter; @@ -68,9 +68,9 @@ DynamicObstacleStopModuleManager::getModuleExpiredFunction( return false; }; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #include PLUGINLIB_EXPORT_CLASS( - behavior_velocity_planner::DynamicObstacleStopModulePlugin, - behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::DynamicObstacleStopModulePlugin, + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.hpp index eb7bf4c6dbc98..d5c403e26792c 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.hpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.hpp @@ -17,9 +17,9 @@ #include "scene_dynamic_obstacle_stop.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -28,7 +28,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class DynamicObstacleStopModuleManager : public SceneModuleManagerInterface { @@ -53,6 +53,6 @@ class DynamicObstacleStopModulePlugin : public PluginWrapper #include -namespace behavior_velocity_planner::dynamic_obstacle_stop +namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop { /// @brief filter the given predicted objects @@ -91,4 +91,4 @@ std::vector filter_predicted_obj } return filtered_objects; } -} // namespace behavior_velocity_planner::dynamic_obstacle_stop +} // namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp index 5daa0cda44203..71da351d2f10b 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp @@ -21,7 +21,7 @@ #include -namespace behavior_velocity_planner::dynamic_obstacle_stop +namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop { /// @brief filter the given predicted objects @@ -34,6 +34,6 @@ std::vector filter_predicted_obj const autoware_perception_msgs::msg::PredictedObjects & objects, const EgoData & ego_data, const PlannerParam & params, const double hysteresis); -} // namespace behavior_velocity_planner::dynamic_obstacle_stop +} // namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop #endif // OBJECT_FILTERING_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp index 1df8a1ed6a4a3..0f6fdbfadbf86 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp @@ -18,7 +18,7 @@ #include -namespace behavior_velocity_planner::dynamic_obstacle_stop +namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop { void update_object_map( ObjectStopDecisionMap & object_map, const std::vector & collisions, @@ -66,4 +66,4 @@ std::optional find_earliest_collision( return earliest_collision; } -} // namespace behavior_velocity_planner::dynamic_obstacle_stop +} // namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.hpp index 5756c8589fb73..cc13614e80782 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.hpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.hpp @@ -24,7 +24,7 @@ #include #include -namespace behavior_velocity_planner::dynamic_obstacle_stop +namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop { /// @brief representation of a decision to stop for a dynamic object struct ObjectStopDecision @@ -71,6 +71,6 @@ void update_object_map( std::optional find_earliest_collision( const ObjectStopDecisionMap & object_map, const EgoData & ego_data); -} // namespace behavior_velocity_planner::dynamic_obstacle_stop +} // namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop #endif // OBJECT_STOP_DECISION_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp index 11ec540e3980f..9c5eced187aa8 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp @@ -21,8 +21,8 @@ #include "object_stop_decision.hpp" #include "types.hpp" -#include -#include +#include +#include #include #include #include @@ -33,7 +33,7 @@ #include #include -namespace behavior_velocity_planner::dynamic_obstacle_stop +namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop { using visualization_msgs::msg::Marker; @@ -163,4 +163,4 @@ motion_utils::VirtualWalls DynamicObstacleStopModule::createVirtualWalls() return virtual_walls; } -} // namespace behavior_velocity_planner::dynamic_obstacle_stop +} // namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp index 79911c40a195d..8018412ba2b4b 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.hpp @@ -18,7 +18,7 @@ #include "object_stop_decision.hpp" #include "types.hpp" -#include +#include #include #include @@ -30,7 +30,7 @@ #include #include -namespace behavior_velocity_planner::dynamic_obstacle_stop +namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop { class DynamicObstacleStopModule : public SceneModuleInterface { @@ -57,6 +57,6 @@ class DynamicObstacleStopModule : public SceneModuleInterface // Debug mutable DebugData debug_data_; }; -} // namespace behavior_velocity_planner::dynamic_obstacle_stop +} // namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop #endif // SCENE_DYNAMIC_OBSTACLE_STOP_HPP_ diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp index 532d770608dd3..32ef89413b2f8 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp @@ -29,7 +29,7 @@ #include #include -namespace behavior_velocity_planner::dynamic_obstacle_stop +namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop { using BoxIndexPair = std::pair; using Rtree = boost::geometry::index::rtree>; @@ -84,6 +84,6 @@ struct Collision geometry_msgs::msg::Point point; std::string object_uuid; }; -} // namespace behavior_velocity_planner::dynamic_obstacle_stop +} // namespace autoware::behavior_velocity_planner::dynamic_obstacle_stop #endif // TYPES_HPP_ diff --git a/planning/behavior_velocity_no_drivable_lane_module/package.xml b/planning/behavior_velocity_no_drivable_lane_module/package.xml index 79eea68142cc8..4c3d6dbf78153 100644 --- a/planning/behavior_velocity_no_drivable_lane_module/package.xml +++ b/planning/behavior_velocity_no_drivable_lane_module/package.xml @@ -19,8 +19,8 @@ autoware_cmake eigen3_cmake_module + autoware_behavior_velocity_planner_common autoware_planning_msgs - behavior_velocity_planner_common eigen geometry_msgs lanelet2_extension diff --git a/planning/behavior_velocity_no_drivable_lane_module/plugins.xml b/planning/behavior_velocity_no_drivable_lane_module/plugins.xml index 33b0d5d6e7469..e3e9efb254fba 100644 --- a/planning/behavior_velocity_no_drivable_lane_module/plugins.xml +++ b/planning/behavior_velocity_no_drivable_lane_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/behavior_velocity_no_drivable_lane_module/src/debug.cpp b/planning/behavior_velocity_no_drivable_lane_module/src/debug.cpp index 0c6bb747a854b..0908fe712dbf5 100644 --- a/planning/behavior_velocity_no_drivable_lane_module/src/debug.cpp +++ b/planning/behavior_velocity_no_drivable_lane_module/src/debug.cpp @@ -14,14 +14,14 @@ #include "scene.hpp" -#include +#include #include #include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using tier4_autoware_utils::appendMarkerArray; using tier4_autoware_utils::createDefaultMarker; @@ -102,4 +102,4 @@ visualization_msgs::msg::MarkerArray NoDrivableLaneModule::createDebugMarkerArra return debug_marker_array; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_no_drivable_lane_module/src/manager.cpp b/planning/behavior_velocity_no_drivable_lane_module/src/manager.cpp index 0b7a8a8c28dd5..8c3fc5ef0f3ce 100644 --- a/planning/behavior_velocity_no_drivable_lane_module/src/manager.cpp +++ b/planning/behavior_velocity_no_drivable_lane_module/src/manager.cpp @@ -14,12 +14,12 @@ #include "manager.hpp" -#include +#include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using tier4_autoware_utils::getOrDeclareParameter; @@ -66,8 +66,9 @@ NoDrivableLaneModuleManager::getModuleExpiredFunction( }; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #include PLUGINLIB_EXPORT_CLASS( - behavior_velocity_planner::NoDrivableLaneModulePlugin, behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::NoDrivableLaneModulePlugin, + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/behavior_velocity_no_drivable_lane_module/src/manager.hpp b/planning/behavior_velocity_no_drivable_lane_module/src/manager.hpp index 90455bd4b1c62..4afa498a5679b 100644 --- a/planning/behavior_velocity_no_drivable_lane_module/src/manager.hpp +++ b/planning/behavior_velocity_no_drivable_lane_module/src/manager.hpp @@ -17,9 +17,9 @@ #include "scene.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -27,7 +27,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class NoDrivableLaneModuleManager : public SceneModuleManagerInterface { @@ -49,6 +49,6 @@ class NoDrivableLaneModulePlugin : public PluginWrapper +#include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using tier4_autoware_utils::createPoint; @@ -283,4 +283,4 @@ void NoDrivableLaneModule::initialize_debug_data( } } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_no_drivable_lane_module/src/scene.hpp b/planning/behavior_velocity_no_drivable_lane_module/src/scene.hpp index fb90e023fedcd..6910e972a8685 100644 --- a/planning/behavior_velocity_no_drivable_lane_module/src/scene.hpp +++ b/planning/behavior_velocity_no_drivable_lane_module/src/scene.hpp @@ -17,14 +17,14 @@ #include "util.hpp" -#include +#include #include #include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using tier4_planning_msgs::msg::PathWithLaneId; @@ -85,6 +85,6 @@ class NoDrivableLaneModule : public SceneModuleInterface void initialize_debug_data( const lanelet::Lanelet & no_drivable_lane, const geometry_msgs::msg::Point & ego_pos); }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // SCENE_HPP_ diff --git a/planning/behavior_velocity_no_drivable_lane_module/src/util.cpp b/planning/behavior_velocity_no_drivable_lane_module/src/util.cpp index 4c5efad94dfc8..c9a6ce1ac1510 100644 --- a/planning/behavior_velocity_no_drivable_lane_module/src/util.cpp +++ b/planning/behavior_velocity_no_drivable_lane_module/src/util.cpp @@ -17,14 +17,14 @@ #include "motion_utils/trajectory/path_with_lane_id.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include +#include #include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -110,4 +110,4 @@ PathWithNoDrivableLanePolygonIntersection getPathIntersectionWithNoDrivableLaneP } return path_no_drivable_lane_polygon_intersection; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_no_drivable_lane_module/src/util.hpp b/planning/behavior_velocity_no_drivable_lane_module/src/util.hpp index 11953fd5dd177..289b04a2ce96d 100644 --- a/planning/behavior_velocity_no_drivable_lane_module/src/util.hpp +++ b/planning/behavior_velocity_no_drivable_lane_module/src/util.hpp @@ -28,7 +28,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -51,6 +51,6 @@ PathWithNoDrivableLanePolygonIntersection getPathIntersectionWithNoDrivableLaneP const PathWithLaneId & ego_path, const lanelet::BasicPolygon2d & polygon, const geometry_msgs::msg::Point & ego_pos, const size_t max_num); -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // UTIL_HPP_ diff --git a/planning/behavior_velocity_no_stopping_area_module/package.xml b/planning/behavior_velocity_no_stopping_area_module/package.xml index 0991b37120a6f..baa51d6681490 100644 --- a/planning/behavior_velocity_no_stopping_area_module/package.xml +++ b/planning/behavior_velocity_no_stopping_area_module/package.xml @@ -17,9 +17,9 @@ autoware_cmake eigen3_cmake_module + autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs - behavior_velocity_planner_common eigen geometry_msgs interpolation diff --git a/planning/behavior_velocity_no_stopping_area_module/plugins.xml b/planning/behavior_velocity_no_stopping_area_module/plugins.xml index a9b07297cfa30..23d2a800c3cf5 100644 --- a/planning/behavior_velocity_no_stopping_area_module/plugins.xml +++ b/planning/behavior_velocity_no_stopping_area_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/behavior_velocity_no_stopping_area_module/src/debug.cpp b/planning/behavior_velocity_no_stopping_area_module/src/debug.cpp index 9e51afca2d475..e90273d4ac5e4 100644 --- a/planning/behavior_velocity_no_stopping_area_module/src/debug.cpp +++ b/planning/behavior_velocity_no_stopping_area_module/src/debug.cpp @@ -14,8 +14,8 @@ #include "scene_no_stopping_area.hpp" -#include -#include +#include +#include #include #include #include @@ -28,7 +28,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace { @@ -175,4 +175,4 @@ motion_utils::VirtualWalls NoStoppingAreaModule::createVirtualWalls() } return virtual_walls; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp b/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp index faa265afe1559..6aeac1e9d8dd3 100644 --- a/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp +++ b/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp @@ -14,7 +14,7 @@ #include "manager.hpp" -#include +#include #include #include @@ -28,7 +28,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using lanelet::autoware::NoStoppingArea; using tier4_autoware_utils::getOrDeclareParameter; @@ -86,8 +86,9 @@ NoStoppingAreaModuleManager::getModuleExpiredFunction( }; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #include PLUGINLIB_EXPORT_CLASS( - behavior_velocity_planner::NoStoppingAreaModulePlugin, behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::NoStoppingAreaModulePlugin, + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/behavior_velocity_no_stopping_area_module/src/manager.hpp b/planning/behavior_velocity_no_stopping_area_module/src/manager.hpp index baf5901ccc124..696115d4bda6d 100644 --- a/planning/behavior_velocity_no_stopping_area_module/src/manager.hpp +++ b/planning/behavior_velocity_no_stopping_area_module/src/manager.hpp @@ -17,9 +17,9 @@ #include "scene_no_stopping_area.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -27,7 +27,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class NoStoppingAreaModuleManager : public SceneModuleManagerInterfaceWithRTC { @@ -49,6 +49,6 @@ class NoStoppingAreaModulePlugin : public PluginWrapper -#include -#include +#include +#include +#include #include #include #include @@ -36,7 +36,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -416,4 +416,4 @@ void NoStoppingAreaModule::insertStopPoint( // Insert stop point or replace with zero velocity planning_utils::insertVelocity(path, stop_point_with_lane_id, 0.0, insert_idx); } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp b/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp index 62ec0b88b328e..e7e66775f368e 100644 --- a/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp +++ b/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp @@ -18,9 +18,9 @@ #define EIGEN_MPL2_ONLY #include -#include -#include -#include +#include +#include +#include #include #include @@ -38,7 +38,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using PathIndexWithPose = std::pair; // front index, pose using PathIndexWithPoint2d = std::pair; // front index, point2d @@ -172,6 +172,6 @@ class NoStoppingAreaModule : public SceneModuleInterface // Debug DebugData debug_data_; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // SCENE_NO_STOPPING_AREA_HPP_ diff --git a/planning/behavior_velocity_occlusion_spot_module/package.xml b/planning/behavior_velocity_occlusion_spot_module/package.xml index 5817c2203cc5d..ceddd48b045a0 100644 --- a/planning/behavior_velocity_occlusion_spot_module/package.xml +++ b/planning/behavior_velocity_occlusion_spot_module/package.xml @@ -16,9 +16,9 @@ ament_cmake_auto autoware_cmake + autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs - behavior_velocity_planner_common geometry_msgs grid_map_ros grid_map_utils diff --git a/planning/behavior_velocity_occlusion_spot_module/plugins.xml b/planning/behavior_velocity_occlusion_spot_module/plugins.xml index a38900d1a893b..2d85752cf2b3d 100644 --- a/planning/behavior_velocity_occlusion_spot_module/plugins.xml +++ b/planning/behavior_velocity_occlusion_spot_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp b/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp index 1170afc490a75..40e5b8f91e6b9 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp @@ -15,8 +15,8 @@ #include "occlusion_spot_utils.hpp" #include "scene_occlusion_spot.hpp" -#include -#include +#include +#include #include #include @@ -24,7 +24,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace { @@ -227,4 +227,4 @@ motion_utils::VirtualWalls OcclusionSpotModule::createVirtualWalls() } return virtual_walls; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp b/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp index c8adb324b9055..427a6f27be3c4 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp @@ -20,7 +20,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace grid_utils { @@ -381,4 +381,4 @@ void denoiseOccupancyGridCV( grid_map::GridMapRosConverter::fromOccupancyGrid(occupancy_grid, "layer", grid_map); } } // namespace grid_utils -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.hpp b/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.hpp index 710f671df609f..5c8d77fc831df 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.hpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.hpp @@ -15,8 +15,8 @@ #ifndef GRID_UTILS_HPP_ #define GRID_UTILS_HPP_ -#include -#include +#include +#include #include #include #include @@ -49,7 +49,7 @@ #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; @@ -118,6 +118,6 @@ void denoiseOccupancyGridCV( grid_map::GridMap & grid_map, const GridParam & param, const bool is_show_debug_window, const int num_iter, const bool use_object_footprints, const bool use_object_ray_casts); } // namespace grid_utils -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // GRID_UTILS_HPP_ diff --git a/planning/behavior_velocity_occlusion_spot_module/src/manager.cpp b/planning/behavior_velocity_occlusion_spot_module/src/manager.cpp index 64adc112aab2f..b1757c4142212 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/manager.cpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/manager.cpp @@ -16,7 +16,7 @@ #include "scene_occlusion_spot.hpp" -#include +#include #include #include @@ -25,7 +25,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using occlusion_spot_utils::DETECTION_METHOD; using occlusion_spot_utils::PASS_JUDGE; @@ -136,8 +136,9 @@ OcclusionSpotModuleManager::getModuleExpiredFunction( return false; }; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #include PLUGINLIB_EXPORT_CLASS( - behavior_velocity_planner::OcclusionSpotModulePlugin, behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::OcclusionSpotModulePlugin, + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/behavior_velocity_occlusion_spot_module/src/manager.hpp b/planning/behavior_velocity_occlusion_spot_module/src/manager.hpp index 0955e4ae9aab5..123d0ef32afc1 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/manager.hpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/manager.hpp @@ -18,9 +18,9 @@ #include "occlusion_spot_utils.hpp" #include "scene_occlusion_spot.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -37,7 +37,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class OcclusionSpotModuleManager : public SceneModuleManagerInterface { @@ -63,6 +63,6 @@ class OcclusionSpotModulePlugin : public PluginWrapper -#include +#include +#include #include #include #include @@ -33,7 +33,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; namespace occlusion_spot_utils @@ -485,4 +485,4 @@ std::optional generateOneNotableCollisionFromOcclusionSpo } } // namespace occlusion_spot_utils -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp b/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp index 2b6d89680cd37..542c869919339 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp @@ -17,7 +17,7 @@ #include "grid_utils.hpp" -#include +#include #include #include #include @@ -46,7 +46,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObject; @@ -246,6 +246,6 @@ bool generatePossibleCollisionsFromGridMap( DebugData & debug_data); } // namespace occlusion_spot_utils -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // OCCLUSION_SPOT_UTILS_HPP_ diff --git a/planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.cpp b/planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.cpp index 96f497ca47afa..9fe06273ea617 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.cpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.cpp @@ -16,12 +16,12 @@ #include "occlusion_spot_utils.hpp" -#include +#include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace occlusion_spot_utils { @@ -98,4 +98,4 @@ SafeMotion calculateSafeMotion(const Velocity & v, const double ttv) return sm; } } // namespace occlusion_spot_utils -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.hpp b/planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.hpp index 8d7e9d2fdedd5..9def3b0938998 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.hpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.hpp @@ -22,7 +22,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace occlusion_spot_utils { @@ -38,6 +38,6 @@ void applySafeVelocityConsideringPossibleCollision( SafeMotion calculateSafeMotion(const Velocity & v, const double ttv); } // namespace occlusion_spot_utils -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // RISK_PREDICTIVE_BRAKING_HPP_ diff --git a/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp b/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp index 1f5ca1bab904e..e5c5eaec346ff 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp @@ -17,10 +17,10 @@ #include "occlusion_spot_utils.hpp" #include "risk_predictive_braking.hpp" -#include -#include -#include -#include +#include +#include +#include +#include #include #include @@ -41,7 +41,7 @@ namespace { -namespace utils = behavior_velocity_planner::occlusion_spot_utils; +namespace utils = autoware::behavior_velocity_planner::occlusion_spot_utils; using autoware_perception_msgs::msg::PredictedObject; std::vector extractStuckVehicle( const std::vector & vehicles, const double stop_velocity) @@ -56,7 +56,7 @@ std::vector extractStuckVehicle( } } // namespace -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace utils = occlusion_spot_utils; @@ -201,4 +201,4 @@ bool OcclusionSpotModule::modifyPathVelocity( return true; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp b/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp index b7da7c073cbd9..00126a2ebc39a 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp @@ -17,8 +17,8 @@ #include "occlusion_spot_utils.hpp" -#include -#include +#include +#include #include #include @@ -37,7 +37,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class OcclusionSpotModule : public SceneModuleInterface { @@ -70,6 +70,6 @@ class OcclusionSpotModule : public SceneModuleInterface // Debug mutable DebugData debug_data_; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // SCENE_OCCLUSION_SPOT_HPP_ diff --git a/planning/behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp b/planning/behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp index bc526959386e9..a21e0333082a9 100644 --- a/planning/behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp +++ b/planning/behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp @@ -15,7 +15,7 @@ #include "grid_utils.hpp" #include "utils.hpp" -#include +#include #include #include @@ -38,11 +38,11 @@ struct indexEq } }; -using behavior_velocity_planner::LineString2d; -using behavior_velocity_planner::Point2d; -using behavior_velocity_planner::Polygon2d; -using behavior_velocity_planner::grid_utils::occlusion_cost_value::OCCUPIED; -using behavior_velocity_planner::grid_utils::occlusion_cost_value::UNKNOWN; +using autoware::behavior_velocity_planner::LineString2d; +using autoware::behavior_velocity_planner::Point2d; +using autoware::behavior_velocity_planner::Polygon2d; +using autoware::behavior_velocity_planner::grid_utils::occlusion_cost_value::OCCUPIED; +using autoware::behavior_velocity_planner::grid_utils::occlusion_cost_value::UNKNOWN; namespace bg = boost::geometry; Polygon2d pointsToPoly(const Point2d p0, const Point2d p1, const double radius) diff --git a/planning/behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp b/planning/behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp index 05e73855f2642..60ef5d62a5b7b 100644 --- a/planning/behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp +++ b/planning/behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp @@ -16,8 +16,8 @@ #include "occlusion_spot_utils.hpp" #include "utils.hpp" -#include -#include +#include +#include #include "geometry_msgs/msg/point.hpp" #include "geometry_msgs/msg/vector3.hpp" @@ -32,8 +32,9 @@ using tier4_planning_msgs::msg::PathWithLaneId; TEST(calcSlowDownPointsForPossibleCollision, TooManyPossibleCollisions) { - using behavior_velocity_planner::occlusion_spot_utils::calcSlowDownPointsForPossibleCollision; - using behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; + using autoware::behavior_velocity_planner::occlusion_spot_utils:: + calcSlowDownPointsForPossibleCollision; + using autoware::behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; using std::chrono::duration; using std::chrono::duration_cast; using std::chrono::high_resolution_clock; @@ -65,8 +66,9 @@ TEST(calcSlowDownPointsForPossibleCollision, TooManyPossibleCollisions) TEST(calcSlowDownPointsForPossibleCollision, ConsiderSignedOffset) { - using behavior_velocity_planner::occlusion_spot_utils::calcSlowDownPointsForPossibleCollision; - using behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; + using autoware::behavior_velocity_planner::occlusion_spot_utils:: + calcSlowDownPointsForPossibleCollision; + using autoware::behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; using std::chrono::duration; using std::chrono::duration_cast; using std::chrono::high_resolution_clock; diff --git a/planning/behavior_velocity_occlusion_spot_module/test/src/test_risk_predictive_braking.cpp b/planning/behavior_velocity_occlusion_spot_module/test/src/test_risk_predictive_braking.cpp index 9b1d92b71a111..4a0071be10b2d 100644 --- a/planning/behavior_velocity_occlusion_spot_module/test/src/test_risk_predictive_braking.cpp +++ b/planning/behavior_velocity_occlusion_spot_module/test/src/test_risk_predictive_braking.cpp @@ -23,7 +23,7 @@ TEST(safeMotion, delay_jerk_acceleration) { - namespace utils = behavior_velocity_planner::occlusion_spot_utils; + namespace utils = autoware::behavior_velocity_planner::occlusion_spot_utils; using utils::calculateSafeMotion; /** * @brief check if calculation is correct in below parameter diff --git a/planning/behavior_velocity_occlusion_spot_module/test/src/utils.hpp b/planning/behavior_velocity_occlusion_spot_module/test/src/utils.hpp index f7bb3d4b1ad6f..4b8a7ae3b2f3f 100644 --- a/planning/behavior_velocity_occlusion_spot_module/test/src/utils.hpp +++ b/planning/behavior_velocity_occlusion_spot_module/test/src/utils.hpp @@ -49,17 +49,18 @@ inline grid_map::GridMap generateGrid(int w, int h, double res) grid_map::GridMap grid{}; grid_map::Length length(w * res, h * res); grid.setGeometry(length, res, grid_map::Position(length.x() / 2.0, length.y() / 2.0)); - grid.add("layer", behavior_velocity_planner::grid_utils::occlusion_cost_value::FREE_SPACE); + grid.add( + "layer", autoware::behavior_velocity_planner::grid_utils::occlusion_cost_value::FREE_SPACE); return grid; } -using behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; +using autoware::behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; inline void generatePossibleCollisions( std::vector & possible_collisions, double x0, double y0, double x, double y, int nb_cols) { - using behavior_velocity_planner::occlusion_spot_utils::ObstacleInfo; - using behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; + using autoware::behavior_velocity_planner::occlusion_spot_utils::ObstacleInfo; + using autoware::behavior_velocity_planner::occlusion_spot_utils::PossibleCollisionInfo; const double lon = 0.0; // assume col_x = intersection_x const double lat = -1.0; const double velocity = 1.0; diff --git a/planning/behavior_velocity_out_of_lane_module/package.xml b/planning/behavior_velocity_out_of_lane_module/package.xml index d3742ea7d305f..6ea60dd1398f5 100644 --- a/planning/behavior_velocity_out_of_lane_module/package.xml +++ b/planning/behavior_velocity_out_of_lane_module/package.xml @@ -14,9 +14,9 @@ ament_cmake_auto autoware_cmake + autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs - behavior_velocity_planner_common geometry_msgs lanelet2_extension libboost-dev diff --git a/planning/behavior_velocity_out_of_lane_module/plugins.xml b/planning/behavior_velocity_out_of_lane_module/plugins.xml index 8c18fdce79480..f85eb50367ccc 100644 --- a/planning/behavior_velocity_out_of_lane_module/plugins.xml +++ b/planning/behavior_velocity_out_of_lane_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/behavior_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp b/planning/behavior_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp index 0c9e6448bb374..5e3877753d203 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp @@ -26,7 +26,7 @@ #include #include -namespace behavior_velocity_planner::out_of_lane +namespace autoware::behavior_velocity_planner::out_of_lane { /// @brief estimate whether ego can decelerate without breaking the deceleration limit @@ -102,5 +102,5 @@ std::optional calculate_slowdown_point( } return std::nullopt; } -} // namespace behavior_velocity_planner::out_of_lane +} // namespace autoware::behavior_velocity_planner::out_of_lane #endif // CALCULATE_SLOWDOWN_POINTS_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/debug.cpp b/planning/behavior_velocity_out_of_lane_module/src/debug.cpp index 862ca351a118a..08e66f99e2a0c 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/debug.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/debug.cpp @@ -18,7 +18,7 @@ #include -namespace behavior_velocity_planner::out_of_lane::debug +namespace autoware::behavior_velocity_planner::out_of_lane::debug { namespace { @@ -184,4 +184,4 @@ void add_range_markers( debug_marker_array.markers.push_back(debug_marker); } -} // namespace behavior_velocity_planner::out_of_lane::debug +} // namespace autoware::behavior_velocity_planner::out_of_lane::debug diff --git a/planning/behavior_velocity_out_of_lane_module/src/debug.hpp b/planning/behavior_velocity_out_of_lane_module/src/debug.hpp index 0802ae78d7a26..05eed6b35c13c 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/debug.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/debug.hpp @@ -23,7 +23,7 @@ #include -namespace behavior_velocity_planner::out_of_lane::debug +namespace autoware::behavior_velocity_planner::out_of_lane::debug { /// @brief add footprint markers to the given marker array /// @param [inout] debug_marker_array marker array @@ -64,6 +64,6 @@ void add_range_markers( visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges, const tier4_planning_msgs::msg::PathWithLaneId & path, const size_t first_path_idx, const double z, const size_t prev_nb); -} // namespace behavior_velocity_planner::out_of_lane::debug +} // namespace autoware::behavior_velocity_planner::out_of_lane::debug #endif // DEBUG_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp b/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp index 126c75c2f80b9..62416c8d38ed6 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp @@ -29,7 +29,7 @@ #include #include #include -namespace behavior_velocity_planner::out_of_lane +namespace autoware::behavior_velocity_planner::out_of_lane { double distance_along_path(const EgoData & ego_data, const size_t target_idx) { @@ -380,4 +380,4 @@ std::vector calculate_decisions( return decisions; } -} // namespace behavior_velocity_planner::out_of_lane +} // namespace autoware::behavior_velocity_planner::out_of_lane diff --git a/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp b/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp index 4f2b0a6dad89b..27c5b00c96b3f 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp @@ -29,7 +29,7 @@ #include #include -namespace behavior_velocity_planner::out_of_lane +namespace autoware::behavior_velocity_planner::out_of_lane { /// @brief calculate the distance along the ego path between ego and some target path index /// @param [in] ego_data data related to the ego vehicle @@ -110,6 +110,6 @@ std::optional calculate_decision( /// @return return the calculated decisions to slowdown or stop std::vector calculate_decisions( const DecisionInputs & inputs, const PlannerParam & params, const rclcpp::Logger & logger); -} // namespace behavior_velocity_planner::out_of_lane +} // namespace autoware::behavior_velocity_planner::out_of_lane #endif // DECISIONS_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.cpp b/planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.cpp index 80cd106bf52ab..bb352f625580f 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.cpp @@ -24,7 +24,7 @@ #include -namespace behavior_velocity_planner::out_of_lane +namespace autoware::behavior_velocity_planner::out_of_lane { void cut_predicted_path_beyond_line( autoware_perception_msgs::msg::PredictedPath & predicted_path, @@ -143,4 +143,4 @@ autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( return filtered_objects; } -} // namespace behavior_velocity_planner::out_of_lane +} // namespace autoware::behavior_velocity_planner::out_of_lane diff --git a/planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.hpp b/planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.hpp index be3e8809d2e3d..a12b37e4c7d6d 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.hpp @@ -17,11 +17,11 @@ #include "types.hpp" -#include +#include #include -namespace behavior_velocity_planner::out_of_lane +namespace autoware::behavior_velocity_planner::out_of_lane { /// @brief cut a predicted path beyond the given stop line /// @param [inout] predicted_path predicted path to cut @@ -52,6 +52,6 @@ void cut_predicted_path_beyond_red_lights( /// @return filtered predicted objects autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( const PlannerData & planner_data, const EgoData & ego_data, const PlannerParam & params); -} // namespace behavior_velocity_planner::out_of_lane +} // namespace autoware::behavior_velocity_planner::out_of_lane #endif // FILTER_PREDICTED_OBJECTS_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/footprint.cpp b/planning/behavior_velocity_out_of_lane_module/src/footprint.cpp index d136f4a8598f3..48992e46ec74f 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/footprint.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/footprint.cpp @@ -24,7 +24,7 @@ #include #include -namespace behavior_velocity_planner::out_of_lane +namespace autoware::behavior_velocity_planner::out_of_lane { tier4_autoware_utils::Polygon2d make_base_footprint( const PlannerParam & p, const bool ignore_offset) @@ -87,4 +87,4 @@ lanelet::BasicPolygon2d calculate_current_ego_footprint( footprint.emplace_back(p.x() + ego_data.pose.position.x, p.y() + ego_data.pose.position.y); return footprint; } -} // namespace behavior_velocity_planner::out_of_lane +} // namespace autoware::behavior_velocity_planner::out_of_lane diff --git a/planning/behavior_velocity_out_of_lane_module/src/footprint.hpp b/planning/behavior_velocity_out_of_lane_module/src/footprint.hpp index a573b6ff3981c..1a0d38600fe73 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/footprint.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/footprint.hpp @@ -21,7 +21,7 @@ #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace out_of_lane { @@ -54,6 +54,6 @@ std::vector calculate_path_footprints( lanelet::BasicPolygon2d calculate_current_ego_footprint( const EgoData & ego_data, const PlannerParam & params, const bool ignore_offset = false); } // namespace out_of_lane -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // FOOTPRINT_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp index 67d8a79a63f03..42df39853f4f5 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp @@ -14,7 +14,7 @@ #include "lanelets_selection.hpp" -#include +#include #include #include @@ -22,7 +22,7 @@ #include #include -namespace behavior_velocity_planner::out_of_lane +namespace autoware::behavior_velocity_planner::out_of_lane { lanelet::ConstLanelets consecutive_lanelets( @@ -127,4 +127,4 @@ lanelet::ConstLanelets calculate_other_lanelets( } return other_lanelets; } -} // namespace behavior_velocity_planner::out_of_lane +} // namespace autoware::behavior_velocity_planner::out_of_lane diff --git a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp index 87757a0cb2230..8985a49a12853 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp @@ -21,7 +21,7 @@ #include -namespace behavior_velocity_planner::out_of_lane +namespace autoware::behavior_velocity_planner::out_of_lane { /// @brief checks if a lanelet is already contained in a vector of lanelets /// @param [in] lanelets vector to check @@ -68,6 +68,6 @@ lanelet::ConstLanelets calculate_other_lanelets( const EgoData & ego_data, const lanelet::ConstLanelets & path_lanelets, const lanelet::ConstLanelets & ignored_lanelets, const route_handler::RouteHandler & route_handler, const PlannerParam & params); -} // namespace behavior_velocity_planner::out_of_lane +} // namespace autoware::behavior_velocity_planner::out_of_lane #endif // LANELETS_SELECTION_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/manager.cpp b/planning/behavior_velocity_out_of_lane_module/src/manager.cpp index 840054d92252f..61ec1a832bf8e 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/manager.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/manager.cpp @@ -16,7 +16,7 @@ #include "scene_out_of_lane.hpp" -#include +#include #include #include @@ -25,7 +25,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using tier4_autoware_utils::getOrDeclareParameter; @@ -100,8 +100,9 @@ OutOfLaneModuleManager::getModuleExpiredFunction( return false; }; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #include PLUGINLIB_EXPORT_CLASS( - behavior_velocity_planner::OutOfLaneModulePlugin, behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::OutOfLaneModulePlugin, + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/behavior_velocity_out_of_lane_module/src/manager.hpp b/planning/behavior_velocity_out_of_lane_module/src/manager.hpp index 9da1751576a7f..5ab7126d88d4d 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/manager.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/manager.hpp @@ -17,9 +17,9 @@ #include "scene_out_of_lane.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -36,7 +36,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class OutOfLaneModuleManager : public SceneModuleManagerInterface { @@ -61,6 +61,6 @@ class OutOfLaneModulePlugin : public PluginWrapper { }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // MANAGER_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.cpp b/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.cpp index 6dfb41ccfbfcb..a081df0b52028 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.cpp @@ -24,7 +24,7 @@ #include -namespace behavior_velocity_planner::out_of_lane +namespace autoware::behavior_velocity_planner::out_of_lane { Overlap calculate_overlap( @@ -123,4 +123,4 @@ OverlapRanges calculate_overlapping_ranges( return ranges; } -} // namespace behavior_velocity_planner::out_of_lane +} // namespace autoware::behavior_velocity_planner::out_of_lane diff --git a/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp b/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp index 2b0830acc28cc..afb71c11b3ae4 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp @@ -23,7 +23,7 @@ #include -namespace behavior_velocity_planner::out_of_lane +namespace autoware::behavior_velocity_planner::out_of_lane { /// @brief calculate the overlap between the given footprint and lanelet @@ -55,6 +55,6 @@ OverlapRanges calculate_overlapping_ranges( const std::vector & path_footprints, const lanelet::ConstLanelets & path_lanelets, const lanelet::ConstLanelets & lanelets, const PlannerParam & params); -} // namespace behavior_velocity_planner::out_of_lane +} // namespace autoware::behavior_velocity_planner::out_of_lane #endif // OVERLAPPING_RANGE_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp index 067a5e3dc7698..3f34e8441e8be 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp @@ -23,8 +23,8 @@ #include "overlapping_range.hpp" #include "types.hpp" -#include -#include +#include +#include #include #include #include @@ -41,7 +41,7 @@ #include #include -namespace behavior_velocity_planner::out_of_lane +namespace autoware::behavior_velocity_planner::out_of_lane { using visualization_msgs::msg::Marker; @@ -241,4 +241,4 @@ motion_utils::VirtualWalls OutOfLaneModule::createVirtualWalls() return virtual_walls; } -} // namespace behavior_velocity_planner::out_of_lane +} // namespace autoware::behavior_velocity_planner::out_of_lane diff --git a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp index 1d51c45c6afd1..38101d6a9ba1d 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp @@ -17,7 +17,7 @@ #include "types.hpp" -#include +#include #include #include @@ -31,7 +31,7 @@ #include #include -namespace behavior_velocity_planner::out_of_lane +namespace autoware::behavior_velocity_planner::out_of_lane { class OutOfLaneModule : public SceneModuleInterface { @@ -60,6 +60,6 @@ class OutOfLaneModule : public SceneModuleInterface // Debug mutable DebugData debug_data_; }; -} // namespace behavior_velocity_planner::out_of_lane +} // namespace autoware::behavior_velocity_planner::out_of_lane #endif // SCENE_OUT_OF_LANE_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/types.hpp b/planning/behavior_velocity_out_of_lane_module/src/types.hpp index cb2945f8b32b8..f1c48a6e96d17 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/types.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/types.hpp @@ -31,7 +31,7 @@ #include #include -namespace behavior_velocity_planner::out_of_lane +namespace autoware::behavior_velocity_planner::out_of_lane { /// @brief parameters for the "out of lane" module struct PlannerParam @@ -230,6 +230,6 @@ struct DebugData } }; -} // namespace behavior_velocity_planner::out_of_lane +} // namespace autoware::behavior_velocity_planner::out_of_lane #endif // TYPES_HPP_ diff --git a/planning/behavior_velocity_speed_bump_module/package.xml b/planning/behavior_velocity_speed_bump_module/package.xml index 9b1de66c95c92..62e215951757d 100644 --- a/planning/behavior_velocity_speed_bump_module/package.xml +++ b/planning/behavior_velocity_speed_bump_module/package.xml @@ -15,8 +15,8 @@ autoware_cmake eigen3_cmake_module + autoware_behavior_velocity_planner_common autoware_planning_msgs - behavior_velocity_planner_common eigen geometry_msgs lanelet2_extension diff --git a/planning/behavior_velocity_speed_bump_module/plugins.xml b/planning/behavior_velocity_speed_bump_module/plugins.xml index 506d25669f8cf..48287a7f94b4b 100644 --- a/planning/behavior_velocity_speed_bump_module/plugins.xml +++ b/planning/behavior_velocity_speed_bump_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/behavior_velocity_speed_bump_module/src/debug.cpp b/planning/behavior_velocity_speed_bump_module/src/debug.cpp index 7409c24e7e8bf..acbe3e05debaa 100644 --- a/planning/behavior_velocity_speed_bump_module/src/debug.cpp +++ b/planning/behavior_velocity_speed_bump_module/src/debug.cpp @@ -14,7 +14,7 @@ #include "scene.hpp" -#include +#include #include #include #include @@ -23,7 +23,7 @@ #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using motion_utils::createSlowDownVirtualWallMarker; using tier4_autoware_utils::appendMarkerArray; @@ -120,4 +120,4 @@ visualization_msgs::msg::MarkerArray SpeedBumpModule::createDebugMarkerArray() return debug_marker_array; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_speed_bump_module/src/manager.cpp b/planning/behavior_velocity_speed_bump_module/src/manager.cpp index fcd000699b7ff..42f10586d8fec 100644 --- a/planning/behavior_velocity_speed_bump_module/src/manager.cpp +++ b/planning/behavior_velocity_speed_bump_module/src/manager.cpp @@ -14,7 +14,7 @@ #include "manager.hpp" -#include +#include #include #include #include @@ -28,7 +28,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using lanelet::autoware::SpeedBump; using tier4_autoware_utils::getOrDeclareParameter; @@ -80,8 +80,9 @@ SpeedBumpModuleManager::getModuleExpiredFunction( }; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #include PLUGINLIB_EXPORT_CLASS( - behavior_velocity_planner::SpeedBumpModulePlugin, behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::SpeedBumpModulePlugin, + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/behavior_velocity_speed_bump_module/src/manager.hpp b/planning/behavior_velocity_speed_bump_module/src/manager.hpp index 40fcfdd081c2e..41b9a593dde95 100644 --- a/planning/behavior_velocity_speed_bump_module/src/manager.hpp +++ b/planning/behavior_velocity_speed_bump_module/src/manager.hpp @@ -17,9 +17,9 @@ #include "scene.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -27,7 +27,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class SpeedBumpModuleManager : public SceneModuleManagerInterface { @@ -49,6 +49,6 @@ class SpeedBumpModulePlugin : public PluginWrapper { }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // MANAGER_HPP_ diff --git a/planning/behavior_velocity_speed_bump_module/src/scene.cpp b/planning/behavior_velocity_speed_bump_module/src/scene.cpp index dc944cc0c292b..0ca4e0731b155 100644 --- a/planning/behavior_velocity_speed_bump_module/src/scene.cpp +++ b/planning/behavior_velocity_speed_bump_module/src/scene.cpp @@ -20,7 +20,7 @@ #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using motion_utils::calcSignedArcLength; using tier4_autoware_utils::createPoint; @@ -169,4 +169,4 @@ bool SpeedBumpModule::applySlowDownSpeed( output.points, slow_start_point_idx, slow_end_point_idx, speed_bump_speed); } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_speed_bump_module/src/scene.hpp b/planning/behavior_velocity_speed_bump_module/src/scene.hpp index f227366127046..ffbcf5fdf9325 100644 --- a/planning/behavior_velocity_speed_bump_module/src/scene.hpp +++ b/planning/behavior_velocity_speed_bump_module/src/scene.hpp @@ -17,14 +17,14 @@ #include "util.hpp" -#include +#include #include #include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using tier4_planning_msgs::msg::PathWithLaneId; @@ -81,6 +81,6 @@ class SpeedBumpModule : public SceneModuleInterface float speed_bump_slow_down_speed_; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // SCENE_HPP_ diff --git a/planning/behavior_velocity_speed_bump_module/src/util.cpp b/planning/behavior_velocity_speed_bump_module/src/util.cpp index d1533d7028dcf..ca4e7e379d1ea 100644 --- a/planning/behavior_velocity_speed_bump_module/src/util.cpp +++ b/planning/behavior_velocity_speed_bump_module/src/util.cpp @@ -17,7 +17,7 @@ #include "motion_utils/trajectory/path_with_lane_id.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include +#include #include #include @@ -32,7 +32,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -172,4 +172,4 @@ float calcSlowDownSpeed(const Point32 & p1, const Point32 & p2, const float spee return std::clamp(speed, p2.y, p1.y); } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_speed_bump_module/src/util.hpp b/planning/behavior_velocity_speed_bump_module/src/util.hpp index 2cd408735fd61..72bad3db86f73 100644 --- a/planning/behavior_velocity_speed_bump_module/src/util.hpp +++ b/planning/behavior_velocity_speed_bump_module/src/util.hpp @@ -35,7 +35,7 @@ #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -70,6 +70,6 @@ std::optional insertPointWithOffset( // returns y (speed) for y=mx+b float calcSlowDownSpeed(const Point32 & p1, const Point32 & p2, const float speed_bump_height); -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // UTIL_HPP_ diff --git a/planning/behavior_velocity_stop_line_module/package.xml b/planning/behavior_velocity_stop_line_module/package.xml index c71ecb83098fb..3132f60d1f342 100644 --- a/planning/behavior_velocity_stop_line_module/package.xml +++ b/planning/behavior_velocity_stop_line_module/package.xml @@ -18,8 +18,8 @@ autoware_cmake eigen3_cmake_module + autoware_behavior_velocity_planner_common autoware_planning_msgs - behavior_velocity_planner_common eigen geometry_msgs lanelet2_extension diff --git a/planning/behavior_velocity_stop_line_module/plugins.xml b/planning/behavior_velocity_stop_line_module/plugins.xml index 51fb225fbebad..4b8ce9852fcec 100644 --- a/planning/behavior_velocity_stop_line_module/plugins.xml +++ b/planning/behavior_velocity_stop_line_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/behavior_velocity_stop_line_module/src/debug.cpp b/planning/behavior_velocity_stop_line_module/src/debug.cpp index f63bdca5068a2..bfcd5a5828556 100644 --- a/planning/behavior_velocity_stop_line_module/src/debug.cpp +++ b/planning/behavior_velocity_stop_line_module/src/debug.cpp @@ -14,7 +14,7 @@ #include "scene.hpp" -#include +#include #include #include #include @@ -24,7 +24,7 @@ #include #endif -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using tier4_autoware_utils::appendMarkerArray; using tier4_autoware_utils::createMarkerColor; @@ -111,4 +111,4 @@ motion_utils::VirtualWalls StopLineModule::createVirtualWalls() } return virtual_walls; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_stop_line_module/src/manager.cpp b/planning/behavior_velocity_stop_line_module/src/manager.cpp index b37b3b119178c..80f48fa65efaf 100644 --- a/planning/behavior_velocity_stop_line_module/src/manager.cpp +++ b/planning/behavior_velocity_stop_line_module/src/manager.cpp @@ -21,7 +21,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using lanelet::TrafficSign; using tier4_autoware_utils::getOrDeclareParameter; @@ -102,8 +102,9 @@ StopLineModuleManager::getModuleExpiredFunction( }; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #include PLUGINLIB_EXPORT_CLASS( - behavior_velocity_planner::StopLineModulePlugin, behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::StopLineModulePlugin, + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/behavior_velocity_stop_line_module/src/manager.hpp b/planning/behavior_velocity_stop_line_module/src/manager.hpp index af9dbaa083c33..eca5132a75c5f 100644 --- a/planning/behavior_velocity_stop_line_module/src/manager.hpp +++ b/planning/behavior_velocity_stop_line_module/src/manager.hpp @@ -17,9 +17,9 @@ #include "scene.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -30,7 +30,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using StopLineWithLaneId = std::pair; @@ -62,6 +62,6 @@ class StopLineModulePlugin : public PluginWrapper { }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // MANAGER_HPP_ diff --git a/planning/behavior_velocity_stop_line_module/src/scene.cpp b/planning/behavior_velocity_stop_line_module/src/scene.cpp index 976acd98fe42b..1bf777338e43c 100644 --- a/planning/behavior_velocity_stop_line_module/src/scene.cpp +++ b/planning/behavior_velocity_stop_line_module/src/scene.cpp @@ -14,14 +14,14 @@ #include "scene.hpp" -#include -#include +#include +#include #include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -177,4 +177,4 @@ geometry_msgs::msg::Point StopLineModule::getCenterOfStopLine( center_point.z = (stop_line[0].z() + stop_line[1].z()) / 2.0; return center_point; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_stop_line_module/src/scene.hpp b/planning/behavior_velocity_stop_line_module/src/scene.hpp index 70c67df623c85..0ae0a885f036f 100644 --- a/planning/behavior_velocity_stop_line_module/src/scene.hpp +++ b/planning/behavior_velocity_stop_line_module/src/scene.hpp @@ -24,16 +24,16 @@ #define EIGEN_MPL2_ONLY #include #include -#include -#include -#include +#include +#include +#include #include #include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class StopLineModule : public SceneModuleInterface { @@ -106,6 +106,6 @@ class StopLineModule : public SceneModuleInterface // Debug DebugData debug_data_; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // SCENE_HPP_ diff --git a/planning/behavior_velocity_traffic_light_module/package.xml b/planning/behavior_velocity_traffic_light_module/package.xml index ff7b5a269db32..067dcaca6a638 100644 --- a/planning/behavior_velocity_traffic_light_module/package.xml +++ b/planning/behavior_velocity_traffic_light_module/package.xml @@ -19,9 +19,9 @@ eigen3_cmake_module autoware_adapi_v1_msgs + autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs - behavior_velocity_planner_common eigen geometry_msgs lanelet2_extension diff --git a/planning/behavior_velocity_traffic_light_module/plugins.xml b/planning/behavior_velocity_traffic_light_module/plugins.xml index b65cc66c5c232..9b5e84fff982d 100644 --- a/planning/behavior_velocity_traffic_light_module/plugins.xml +++ b/planning/behavior_velocity_traffic_light_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/behavior_velocity_traffic_light_module/src/debug.cpp b/planning/behavior_velocity_traffic_light_module/src/debug.cpp index b3dedaa29d6ad..7ceded9c91934 100644 --- a/planning/behavior_velocity_traffic_light_module/src/debug.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/debug.cpp @@ -14,7 +14,7 @@ #include "scene.hpp" -#include +#include #include #include #include @@ -24,7 +24,7 @@ #include #endif -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { visualization_msgs::msg::MarkerArray TrafficLightModule::createDebugMarkerArray() { @@ -54,4 +54,4 @@ motion_utils::VirtualWalls TrafficLightModule::createVirtualWalls() return virtual_walls; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_traffic_light_module/src/manager.cpp index 01c3acf84cd63..ef5f8b2b36016 100644 --- a/planning/behavior_velocity_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/manager.cpp @@ -14,7 +14,7 @@ #include "manager.hpp" -#include +#include #include #include @@ -24,7 +24,7 @@ #include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using lanelet::TrafficLight; using tier4_autoware_utils::getOrDeclareParameter; @@ -188,8 +188,9 @@ bool TrafficLightModuleManager::hasSameTrafficLight( return false; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #include PLUGINLIB_EXPORT_CLASS( - behavior_velocity_planner::TrafficLightModulePlugin, behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::TrafficLightModulePlugin, + autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/behavior_velocity_traffic_light_module/src/manager.hpp b/planning/behavior_velocity_traffic_light_module/src/manager.hpp index 97340f8592a7d..c40056a0ba10c 100644 --- a/planning/behavior_velocity_traffic_light_module/src/manager.hpp +++ b/planning/behavior_velocity_traffic_light_module/src/manager.hpp @@ -17,9 +17,9 @@ #include "scene.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -28,7 +28,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class TrafficLightModuleManager : public SceneModuleManagerInterfaceWithRTC { @@ -65,6 +65,6 @@ class TrafficLightModulePlugin : public PluginWrapper { }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // MANAGER_HPP_ diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_traffic_light_module/src/scene.cpp index c886578dc65e4..3ec597f1de249 100644 --- a/planning/behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/scene.cpp @@ -14,7 +14,7 @@ #include "scene.hpp" -#include +#include #include #include @@ -34,7 +34,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -432,4 +432,4 @@ tier4_planning_msgs::msg::PathWithLaneId TrafficLightModule::insertStopPose( return modified_path; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_traffic_light_module/src/scene.hpp index 8385a1210d421..220145a2c7163 100644 --- a/planning/behavior_velocity_traffic_light_module/src/scene.hpp +++ b/planning/behavior_velocity_traffic_light_module/src/scene.hpp @@ -23,15 +23,15 @@ #define EIGEN_MPL2_ONLY #include #include -#include -#include +#include +#include #include #include #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { class TrafficLightModule : public SceneModuleInterface { @@ -129,6 +129,6 @@ class TrafficLightModule : public SceneModuleInterface // Traffic Light State TrafficSignal looking_tl_state_; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // SCENE_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml index 2f4e7241d60ee..a115d28ee6d86 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml @@ -15,10 +15,10 @@ autoware_cmake eigen3_cmake_module + autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs autoware_velocity_smoother - behavior_velocity_planner_common eigen geometry_msgs lanelet2_extension From 7d6c2fdba3e4bee7aaa1b0dcb665e22ab1a83c29 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Fri, 7 Jun 2024 16:22:24 +0900 Subject: [PATCH 15/65] refactor(planning_validator)!: prefix package and namespace with autoware (#7320) * add autoware_ prefix to planning_validator Signed-off-by: kyoichi-sugahara * add prefix to package name in .pages Signed-off-by: kyoichi-sugahara * fix link of the image --------- Signed-off-by: kyoichi-sugahara --- .../launch/planning.launch.xml | 2 +- launch/tier4_planning_launch/package.xml | 2 +- planning/.pages | 2 +- .../autoware_planning_test_manager/README.md | 26 ++++++------ planning/planning_validator/CMakeLists.txt | 30 ++++++------- planning/planning_validator/README.md | 8 ++-- .../planning_validator_plotjugler_config.xml | 42 +++++++++---------- .../image/planning_validator.drawio.svg | 4 +- .../debug_marker.hpp | 6 +-- .../planning_validator.hpp | 16 +++---- .../utils.hpp | 10 ++--- .../invalid_trajectory_publisher.launch.xml | 2 +- .../launch/planning_validator.launch.xml | 4 +- planning/planning_validator/package.xml | 4 +- .../planning_validator/src/debug_marker.cpp | 4 +- .../invalid_trajectory_publisher.cpp | 6 +-- .../invalid_trajectory_publisher.hpp | 4 +- .../src/planning_validator.cpp | 10 ++--- planning/planning_validator/src/utils.cpp | 6 +-- .../src/test_planning_validator_functions.cpp | 6 +-- ...test_planning_validator_node_interface.cpp | 6 +-- .../src/test_planning_validator_pubsub.cpp | 7 ++-- 22 files changed, 104 insertions(+), 103 deletions(-) rename planning/planning_validator/include/{planning_validator => autoware_planning_validator}/debug_marker.hpp (91%) rename planning/planning_validator/include/{planning_validator => autoware_planning_validator}/planning_validator.hpp (91%) rename planning/planning_validator/include/{planning_validator => autoware_planning_validator}/utils.hpp (90%) diff --git a/launch/tier4_planning_launch/launch/planning.launch.xml b/launch/tier4_planning_launch/launch/planning.launch.xml index 97bf6414189ab..1d01732454daf 100644 --- a/launch/tier4_planning_launch/launch/planning.launch.xml +++ b/launch/tier4_planning_launch/launch/planning.launch.xml @@ -32,7 +32,7 @@ - + diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 7b03097e55e10..0a585bce673b6 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -61,6 +61,7 @@ autoware_external_velocity_limit_selector autoware_path_optimizer autoware_planning_topic_converter + autoware_planning_validator autoware_remaining_distance_time_calculator autoware_surround_obstacle_checker autoware_velocity_smoother @@ -73,7 +74,6 @@ obstacle_cruise_planner obstacle_stop_planner planning_evaluator - planning_validator scenario_selector ament_lint_auto diff --git a/planning/.pages b/planning/.pages index 7b932118b5010..6e3c6d5d49104 100644 --- a/planning/.pages +++ b/planning/.pages @@ -87,4 +87,4 @@ nav: - 'Planning Test Utils': planning/planning_test_utils - 'Planning Test Manager': planning/autoware_planning_test_manager - 'Planning Topic Converter': planning/autoware_planning_topic_converter - - 'Planning Validator': planning/planning_validator + - 'Planning Validator': planning/autoware_planning_validator diff --git a/planning/autoware_planning_test_manager/README.md b/planning/autoware_planning_test_manager/README.md index fe5484ca498ee..97eb2fd8d94fd 100644 --- a/planning/autoware_planning_test_manager/README.md +++ b/planning/autoware_planning_test_manager/README.md @@ -41,7 +41,7 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) node_options.arguments( {"--ros-args", "--params-file", planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", - planning_validator_dir + "/config/planning_validator.param.yaml"}); + autoware_planning_validator_dir + "/config/planning_validator.param.yaml"}); // instantiate the TargetNode with node_options auto test_target_node = std::make_shared(node_options); @@ -70,18 +70,18 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) ## Implemented tests -| Node | Test name | exceptional input | output | Exceptional input pattern | -| ------------------------- | ----------------------------------------------------------------------------------------- | ----------------- | -------------- | ------------------------------------------------------------------------------------- | -| planning_validator | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | -| velocity_smoother | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | -| obstacle_cruise_planner | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | -| obstacle_stop_planner | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | -| obstacle_velocity_limiter | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | -| path_optimizer | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | -| scenario_selector | NodeTestWithExceptionTrajectoryLaneDrivingMode NodeTestWithExceptionTrajectoryParkingMode | trajectory | scenario | Empty, single point, path with duplicate points for scenarios:LANEDRIVING and PARKING | -| freespace_planner | NodeTestWithExceptionRoute | route | trajectory | Empty route | -| behavior_path_planner | NodeTestWithExceptionRoute NodeTestWithOffTrackEgoPose | route | route odometry | Empty route Off-lane ego-position | -| behavior_velocity_planner | NodeTestWithExceptionPathWithLaneID | path_with_lane_id | path | Empty path | +| Node | Test name | exceptional input | output | Exceptional input pattern | +| --------------------------- | ----------------------------------------------------------------------------------------- | ----------------- | -------------- | ------------------------------------------------------------------------------------- | +| autoware_planning_validator | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | +| velocity_smoother | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | +| obstacle_cruise_planner | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | +| obstacle_stop_planner | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | +| obstacle_velocity_limiter | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | +| path_optimizer | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | +| scenario_selector | NodeTestWithExceptionTrajectoryLaneDrivingMode NodeTestWithExceptionTrajectoryParkingMode | trajectory | scenario | Empty, single point, path with duplicate points for scenarios:LANEDRIVING and PARKING | +| freespace_planner | NodeTestWithExceptionRoute | route | trajectory | Empty route | +| behavior_path_planner | NodeTestWithExceptionRoute NodeTestWithOffTrackEgoPose | route | route odometry | Empty route Off-lane ego-position | +| behavior_velocity_planner | NodeTestWithExceptionPathWithLaneID | path_with_lane_id | path | Empty path | ## Important Notes diff --git a/planning/planning_validator/CMakeLists.txt b/planning/planning_validator/CMakeLists.txt index 455dded2d7e32..da780cfdebdcf 100644 --- a/planning/planning_validator/CMakeLists.txt +++ b/planning/planning_validator/CMakeLists.txt @@ -1,22 +1,22 @@ cmake_minimum_required(VERSION 3.22) -project(planning_validator) +project(autoware_planning_validator) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_library(planning_validator_helpers SHARED +ament_auto_add_library(autoware_planning_validator_helpers SHARED src/utils.cpp src/debug_marker.cpp ) # planning validator -ament_auto_add_library(planning_validator_component SHARED - include/planning_validator/planning_validator.hpp +ament_auto_add_library(autoware_planning_validator_component SHARED + include/autoware_planning_validator/planning_validator.hpp src/planning_validator.cpp ) -target_link_libraries(planning_validator_component planning_validator_helpers) -rclcpp_components_register_node(planning_validator_component - PLUGIN "planning_validator::PlanningValidator" +target_link_libraries(autoware_planning_validator_component autoware_planning_validator_helpers) +rclcpp_components_register_node(autoware_planning_validator_component + PLUGIN "autoware::planning_validator::PlanningValidator" EXECUTABLE planning_validator_node ) @@ -25,7 +25,7 @@ ament_auto_add_library(invalid_trajectory_publisher_node SHARED src/invalid_trajectory_publisher/invalid_trajectory_publisher.cpp ) rclcpp_components_register_node(invalid_trajectory_publisher_node - PLUGIN "planning_validator::InvalidTrajectoryPublisherNode" + PLUGIN "autoware::planning_validator::InvalidTrajectoryPublisherNode" EXECUTABLE invalid_trajectory_publisher ) @@ -37,29 +37,29 @@ rosidl_generate_interfaces( # to use a message defined in the same package if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0) - rosidl_target_interfaces(planning_validator_component + rosidl_target_interfaces(autoware_planning_validator_component ${PROJECT_NAME} "rosidl_typesupport_cpp") else() rosidl_get_typesupport_target( cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp") - target_link_libraries(planning_validator_component "${cpp_typesupport_target}") + target_link_libraries(autoware_planning_validator_component "${cpp_typesupport_target}") endif() if(BUILD_TESTING) - ament_add_ros_isolated_gtest(test_planning_validator + ament_add_ros_isolated_gtest(test_autoware_planning_validator test/src/test_main.cpp test/src/test_planning_validator_functions.cpp test/src/test_planning_validator_helper.cpp test/src/test_planning_validator_pubsub.cpp - test/src/test_${PROJECT_NAME}_node_interface.cpp + test/src/test_planning_validator_node_interface.cpp ) - ament_target_dependencies(test_planning_validator + ament_target_dependencies(test_autoware_planning_validator rclcpp autoware_planning_msgs ) - target_link_libraries(test_planning_validator - planning_validator_component + target_link_libraries(test_autoware_planning_validator + autoware_planning_validator_component ) endif() diff --git a/planning/planning_validator/README.md b/planning/planning_validator/README.md index 9d70e7f78a5bb..92c9b86c8b31c 100644 --- a/planning/planning_validator/README.md +++ b/planning/planning_validator/README.md @@ -1,8 +1,8 @@ # Planning Validator -The `planning_validator` is a module that checks the validity of a trajectory before it is published. The status of the validation can be viewed in the `/diagnostics` and `/validation_status` topics. When an invalid trajectory is detected, the `planning_validator` will process the trajectory following the selected option: "0. publish the trajectory as it is", "1. stop publishing the trajectory", "2. publish the last validated trajectory". +The `autoware_planning_validator` is a module that checks the validity of a trajectory before it is published. The status of the validation can be viewed in the `/diagnostics` and `/validation_status` topics. When an invalid trajectory is detected, the `autoware_planning_validator` will process the trajectory following the selected option: "0. publish the trajectory as it is", "1. stop publishing the trajectory", "2. publish the last validated trajectory". -![planning_validator](./image/planning_validator.drawio.svg) +![autoware_planning_validator](./image/planning_validator.drawio.svg) ## Supported features @@ -29,7 +29,7 @@ The following features are to be implemented. ### Inputs -The `planning_validator` takes in the following inputs: +The `autoware_planning_validator` takes in the following inputs: | Name | Type | Description | | -------------------- | --------------------------------- | ---------------------------------------------- | @@ -48,7 +48,7 @@ It outputs the following: ## Parameters -The following parameters can be set for the `planning_validator`: +The following parameters can be set for the `autoware_planning_validator`: ### System parameters diff --git a/planning/planning_validator/config/planning_validator_plotjugler_config.xml b/planning/planning_validator/config/planning_validator_plotjugler_config.xml index d6afc0b017d32..04d5d4d8a0e38 100644 --- a/planning/planning_validator/config/planning_validator_plotjugler_config.xml +++ b/planning/planning_validator/config/planning_validator_plotjugler_config.xml @@ -9,21 +9,21 @@ - + - + - + @@ -32,21 +32,21 @@ - + - + - + @@ -55,21 +55,21 @@ - + - + - + @@ -78,7 +78,7 @@ - + @@ -86,23 +86,23 @@ - - - - - + + + + + - - - - - - + + + + + + diff --git a/planning/planning_validator/image/planning_validator.drawio.svg b/planning/planning_validator/image/planning_validator.drawio.svg index 070c1a6d68b81..0a2267cba159e 100644 --- a/planning/planning_validator/image/planning_validator.drawio.svg +++ b/planning/planning_validator/image/planning_validator.drawio.svg @@ -38,12 +38,12 @@ >
- planning_validator + autoware_planning_validator
- planning_validator + autoware_planning_validator diff --git a/planning/planning_validator/include/planning_validator/debug_marker.hpp b/planning/planning_validator/include/autoware_planning_validator/debug_marker.hpp similarity index 91% rename from planning/planning_validator/include/planning_validator/debug_marker.hpp rename to planning/planning_validator/include/autoware_planning_validator/debug_marker.hpp index 4671a0b0d7297..955ba5bbf64ab 100644 --- a/planning/planning_validator/include/planning_validator/debug_marker.hpp +++ b/planning/planning_validator/include/autoware_planning_validator/debug_marker.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PLANNING_VALIDATOR__DEBUG_MARKER_HPP_ -#define PLANNING_VALIDATOR__DEBUG_MARKER_HPP_ +#ifndef AUTOWARE_PLANNING_VALIDATOR__DEBUG_MARKER_HPP_ +#define AUTOWARE_PLANNING_VALIDATOR__DEBUG_MARKER_HPP_ #include @@ -57,4 +57,4 @@ class PlanningValidatorDebugMarkerPublisher } }; -#endif // PLANNING_VALIDATOR__DEBUG_MARKER_HPP_ +#endif // AUTOWARE_PLANNING_VALIDATOR__DEBUG_MARKER_HPP_ diff --git a/planning/planning_validator/include/planning_validator/planning_validator.hpp b/planning/planning_validator/include/autoware_planning_validator/planning_validator.hpp similarity index 91% rename from planning/planning_validator/include/planning_validator/planning_validator.hpp rename to planning/planning_validator/include/autoware_planning_validator/planning_validator.hpp index fed6e161c4d90..113c70fecb62c 100644 --- a/planning/planning_validator/include/planning_validator/planning_validator.hpp +++ b/planning/planning_validator/include/autoware_planning_validator/planning_validator.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PLANNING_VALIDATOR__PLANNING_VALIDATOR_HPP_ -#define PLANNING_VALIDATOR__PLANNING_VALIDATOR_HPP_ +#ifndef AUTOWARE_PLANNING_VALIDATOR__PLANNING_VALIDATOR_HPP_ +#define AUTOWARE_PLANNING_VALIDATOR__PLANNING_VALIDATOR_HPP_ -#include "planning_validator/debug_marker.hpp" -#include "planning_validator/msg/planning_validator_status.hpp" +#include "autoware_planning_validator/debug_marker.hpp" +#include "autoware_planning_validator/msg/planning_validator_status.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" #include "vehicle_info_util/vehicle_info_util.hpp" @@ -33,14 +33,14 @@ #include #include -namespace planning_validator +namespace autoware::planning_validator { using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; +using autoware_planning_validator::msg::PlanningValidatorStatus; using diagnostic_updater::DiagnosticStatusWrapper; using diagnostic_updater::Updater; using nav_msgs::msg::Odometry; -using planning_validator::msg::PlanningValidatorStatus; using tier4_autoware_utils::StopWatch; using tier4_debug_msgs::msg::Float64Stamped; @@ -141,6 +141,6 @@ class PlanningValidator : public rclcpp::Node StopWatch stop_watch_; }; -} // namespace planning_validator +} // namespace autoware::planning_validator -#endif // PLANNING_VALIDATOR__PLANNING_VALIDATOR_HPP_ +#endif // AUTOWARE_PLANNING_VALIDATOR__PLANNING_VALIDATOR_HPP_ diff --git a/planning/planning_validator/include/planning_validator/utils.hpp b/planning/planning_validator/include/autoware_planning_validator/utils.hpp similarity index 90% rename from planning/planning_validator/include/planning_validator/utils.hpp rename to planning/planning_validator/include/autoware_planning_validator/utils.hpp index 11eaf4f37f400..1c943f5a60e08 100644 --- a/planning/planning_validator/include/planning_validator/utils.hpp +++ b/planning/planning_validator/include/autoware_planning_validator/utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PLANNING_VALIDATOR__UTILS_HPP_ -#define PLANNING_VALIDATOR__UTILS_HPP_ +#ifndef AUTOWARE_PLANNING_VALIDATOR__UTILS_HPP_ +#define AUTOWARE_PLANNING_VALIDATOR__UTILS_HPP_ #include @@ -23,7 +23,7 @@ #include #include -namespace planning_validator +namespace autoware::planning_validator { using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; @@ -65,6 +65,6 @@ bool checkFinite(const TrajectoryPoint & point); void shiftPose(geometry_msgs::msg::Pose & pose, double longitudinal); -} // namespace planning_validator +} // namespace autoware::planning_validator -#endif // PLANNING_VALIDATOR__UTILS_HPP_ +#endif // AUTOWARE_PLANNING_VALIDATOR__UTILS_HPP_ diff --git a/planning/planning_validator/launch/invalid_trajectory_publisher.launch.xml b/planning/planning_validator/launch/invalid_trajectory_publisher.launch.xml index 3f73e0f462cc2..a1cdc7c7ecc55 100644 --- a/planning/planning_validator/launch/invalid_trajectory_publisher.launch.xml +++ b/planning/planning_validator/launch/invalid_trajectory_publisher.launch.xml @@ -2,7 +2,7 @@ - + diff --git a/planning/planning_validator/launch/planning_validator.launch.xml b/planning/planning_validator/launch/planning_validator.launch.xml index 81573adb4dc24..fa1475a0787e4 100644 --- a/planning/planning_validator/launch/planning_validator.launch.xml +++ b/planning/planning_validator/launch/planning_validator.launch.xml @@ -1,9 +1,9 @@ - + - + diff --git a/planning/planning_validator/package.xml b/planning/planning_validator/package.xml index 5a413f27dc7a3..7fe57e68928d9 100644 --- a/planning/planning_validator/package.xml +++ b/planning/planning_validator/package.xml @@ -1,9 +1,9 @@ - planning_validator + autoware_planning_validator 0.1.0 - ros node for planning_validator + ros node for autoware_planning_validator Takamasa Horibe Kosuke Takeuchi Apache License 2.0 diff --git a/planning/planning_validator/src/debug_marker.cpp b/planning/planning_validator/src/debug_marker.cpp index 82117d199c36e..413611a72b5ab 100644 --- a/planning/planning_validator/src/debug_marker.cpp +++ b/planning/planning_validator/src/debug_marker.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "planning_validator/debug_marker.hpp" +#include "autoware_planning_validator/debug_marker.hpp" #include #include @@ -90,7 +90,7 @@ void PlanningValidatorDebugMarkerPublisher::pushVirtualWall(const geometry_msgs: { const auto now = node_->get_clock()->now(); const auto stop_wall_marker = - motion_utils::createStopVirtualWallMarker(pose, "planning_validator", now, 0); + motion_utils::createStopVirtualWallMarker(pose, "autoware_planning_validator", now, 0); tier4_autoware_utils::appendMarkerArray(stop_wall_marker, &marker_array_virtual_wall_, now); } diff --git a/planning/planning_validator/src/invalid_trajectory_publisher/invalid_trajectory_publisher.cpp b/planning/planning_validator/src/invalid_trajectory_publisher/invalid_trajectory_publisher.cpp index 6cca99cd9f14c..645d6c92e3698 100644 --- a/planning/planning_validator/src/invalid_trajectory_publisher/invalid_trajectory_publisher.cpp +++ b/planning/planning_validator/src/invalid_trajectory_publisher/invalid_trajectory_publisher.cpp @@ -18,7 +18,7 @@ #include #include -namespace planning_validator +namespace autoware::planning_validator { InvalidTrajectoryPublisherNode::InvalidTrajectoryPublisherNode( const rclcpp::NodeOptions & node_options) @@ -72,7 +72,7 @@ void InvalidTrajectoryPublisherNode::onCurrentTrajectory(const Trajectory::Const traj_sub_.reset(); } -} // namespace planning_validator +} // namespace autoware::planning_validator #include -RCLCPP_COMPONENTS_REGISTER_NODE(planning_validator::InvalidTrajectoryPublisherNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::planning_validator::InvalidTrajectoryPublisherNode) diff --git a/planning/planning_validator/src/invalid_trajectory_publisher/invalid_trajectory_publisher.hpp b/planning/planning_validator/src/invalid_trajectory_publisher/invalid_trajectory_publisher.hpp index 1d1e47ad10407..0025d759217bf 100644 --- a/planning/planning_validator/src/invalid_trajectory_publisher/invalid_trajectory_publisher.hpp +++ b/planning/planning_validator/src/invalid_trajectory_publisher/invalid_trajectory_publisher.hpp @@ -21,7 +21,7 @@ #include -namespace planning_validator +namespace autoware::planning_validator { using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; @@ -41,6 +41,6 @@ class InvalidTrajectoryPublisherNode : public rclcpp::Node Trajectory::ConstSharedPtr current_trajectory_ = nullptr; }; -} // namespace planning_validator +} // namespace autoware::planning_validator #endif // INVALID_TRAJECTORY_PUBLISHER__INVALID_TRAJECTORY_PUBLISHER_HPP_ diff --git a/planning/planning_validator/src/planning_validator.cpp b/planning/planning_validator/src/planning_validator.cpp index d14b1d9ff37d2..aac50e24c5d5c 100644 --- a/planning/planning_validator/src/planning_validator.cpp +++ b/planning/planning_validator/src/planning_validator.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "planning_validator/planning_validator.hpp" +#include "autoware_planning_validator/planning_validator.hpp" -#include "planning_validator/utils.hpp" +#include "autoware_planning_validator/utils.hpp" #include #include @@ -23,7 +23,7 @@ #include #include -namespace planning_validator +namespace autoware::planning_validator { using diagnostic_msgs::msg::DiagnosticStatus; @@ -584,7 +584,7 @@ void PlanningValidator::displayStatus() warn(s.is_valid_forward_trajectory_length, "planning trajectory forward length is not enough!!"); } -} // namespace planning_validator +} // namespace autoware::planning_validator #include -RCLCPP_COMPONENTS_REGISTER_NODE(planning_validator::PlanningValidator) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::planning_validator::PlanningValidator) diff --git a/planning/planning_validator/src/utils.cpp b/planning/planning_validator/src/utils.cpp index aada0bea2da9b..4710d3ae84ea3 100644 --- a/planning/planning_validator/src/utils.cpp +++ b/planning/planning_validator/src/utils.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "planning_validator/utils.hpp" +#include "autoware_planning_validator/utils.hpp" #include #include @@ -22,7 +22,7 @@ #include #include -namespace planning_validator +namespace autoware::planning_validator { using tier4_autoware_utils::calcCurvature; using tier4_autoware_utils::calcDistance2d; @@ -324,4 +324,4 @@ void shiftPose(geometry_msgs::msg::Pose & pose, double longitudinal) pose.position.y += std::sin(yaw) * longitudinal; } -} // namespace planning_validator +} // namespace autoware::planning_validator diff --git a/planning/planning_validator/test/src/test_planning_validator_functions.cpp b/planning/planning_validator/test/src/test_planning_validator_functions.cpp index e406b6c5d7da2..41ae41a80bdc5 100644 --- a/planning/planning_validator/test/src/test_planning_validator_functions.cpp +++ b/planning/planning_validator/test/src/test_planning_validator_functions.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "planning_validator/debug_marker.hpp" -#include "planning_validator/planning_validator.hpp" +#include "autoware_planning_validator/debug_marker.hpp" +#include "autoware_planning_validator/planning_validator.hpp" #include "test_parameter.hpp" #include "test_planning_validator_helper.hpp" @@ -21,8 +21,8 @@ #include +using autoware::planning_validator::PlanningValidator; using autoware_planning_msgs::msg::Trajectory; -using planning_validator::PlanningValidator; TEST(PlanningValidatorTestSuite, checkValidFiniteValueFunction) { diff --git a/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp b/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp index 2b2a32bf54618..78f57e0fe104d 100644 --- a/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp +++ b/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "planning_validator/planning_validator.hpp" +#include "autoware_planning_validator/planning_validator.hpp" #include #include @@ -22,8 +22,8 @@ #include +using autoware::planning_validator::PlanningValidator; using planning_test_utils::PlanningInterfaceTestManager; -using planning_validator::PlanningValidator; std::shared_ptr generateTestManager() { @@ -46,7 +46,7 @@ std::shared_ptr generateNode() const auto planning_test_utils_dir = ament_index_cpp::get_package_share_directory("planning_test_utils"); const auto planning_validator_dir = - ament_index_cpp::get_package_share_directory("planning_validator"); + ament_index_cpp::get_package_share_directory("autoware_planning_validator"); node_options.arguments( {"--ros-args", "--params-file", planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", diff --git a/planning/planning_validator/test/src/test_planning_validator_pubsub.cpp b/planning/planning_validator/test/src/test_planning_validator_pubsub.cpp index 2329a3b9bb6c8..8cf56525edbc5 100644 --- a/planning/planning_validator/test/src/test_planning_validator_pubsub.cpp +++ b/planning/planning_validator/test/src/test_planning_validator_pubsub.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "planning_validator/planning_validator.hpp" +#include "autoware_planning_validator/planning_validator.hpp" #include "test_parameter.hpp" #include "test_planning_validator_helper.hpp" @@ -29,11 +29,11 @@ * This test checks the diagnostics message published from the planning_validator node */ +using autoware::planning_validator::PlanningValidator; using autoware_planning_msgs::msg::Trajectory; using diagnostic_msgs::msg::DiagnosticArray; using diagnostic_msgs::msg::DiagnosticStatus; using nav_msgs::msg::Odometry; -using planning_validator::PlanningValidator; constexpr double epsilon = 0.001; constexpr double scale_margin = 1.1; @@ -101,7 +101,8 @@ bool hasError(const std::vector & diags, const throw std::runtime_error(name + " is not contained in the diagnostic message."); } -std::pair, std::shared_ptr> +std::pair< + std::shared_ptr, std::shared_ptr> prepareTest(const Trajectory & trajectory, const Odometry & ego_odom) { auto validator = std::make_shared(getNodeOptionsWithDefaultParams()); From 2b7c0db3d62418f84e05a72f72d48fbd3af9b5b7 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 <129915538+TaikiYamada4@users.noreply.github.com> Date: Fri, 7 Jun 2024 16:45:16 +0900 Subject: [PATCH 16/65] feat(pose_instability_detector): change validation algorithm (#7042) * Create define_static_threshold() Signed-off-by: TaikiYamada4 * Revised dead reckoning methodology Signed-off-by: TaikiYamada4 * style(pre-commit): autofix * Change threshold calculation to use the online time difference Signed-off-by: TaikiYamada4 * Simplify threshold calculation. Rewrite json schema. Refactor some variables. Signed-off-by: TaikiYamada4 * style(pre-commit): autofix * Rewrite lateral_threshold and vertical threshold Signed-off-by: TaikiYamada4 * Consider dead reckoning noise, update README.md. Signed-off-by: TaikiYamada4 * Added sentences to README.md Signed-off-by: TaikiYamada4 * Filled README.md Revert lateral threshold calculation. Signed-off-by: TaikiYamada4 * style(pre-commit): autofix * Add #include Signed-off-by: TaikiYamada4 * style(pre-commit): autofix * Fixed pose_instability_detector.schema.json Signed-off-by: TaikiYamada4 * Revised calculation of the process noise of dead reckoning. Signed-off-by: TaikiYamada4 * style(pre-commit): autofix * Fixed typo and lack of information Signed-off-by: TaikiYamada4 * Revised redundant time substitutions Signed-off-by: TaikiYamada4 * Revised dead reckoning algorithm for orientation. Signed-off-by: TaikiYamada4 * style(pre-commit): autofix * Added information about lateral thresholld calculation in README.md Signed-off-by: TaikiYamada4 * Removed all dead reckoning related process noise stuff Signed-off-by: TaikiYamada4 * Removed parameters and desciprtion of dead reckoning process noise stuff Signed-off-by: TaikiYamada4 * style(pre-commit): autofix * Fixed integration logic for angular twist Signed-off-by: TaikiYamada4 * Let the hpp file be exportable, and follow the guidelines when exporting hpp files Signed-off-by: TaikiYamada4 * style(pre-commit): autofix * Fix typo Signed-off-by: TaikiYamada4 * Delete include from package.xml Signed-off-by: TaikiYamada4 * Make test codes work. Create a threshold structure so that other packages can use the methods in pose_instability_detector Signed-off-by: TaikiYamada4 * style(pre-commit): autofix --------- Signed-off-by: TaikiYamada4 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../pose_instability_detector/README.md | 141 ++++++- .../pose_instability_detector.param.yaml | 20 +- .../pose_instability_detector.hpp | 49 ++- .../media/how_to_snip_twist.png | Bin 0 -> 179156 bytes .../media/lateral_threshold_calculation.png | Bin 0 -> 67649 bytes .../pose_instability_detector_overview.png | Bin 0 -> 136030 bytes .../pose_instabilty_detector_procedure.svg | 316 ++++++++++++++++ .../media/rqt_runtime_monitor.png | Bin 438840 -> 86975 bytes .../pose_instability_detector.schema.json | 77 ++-- .../src/pose_instability_detector.cpp | 347 +++++++++++++++--- .../pose_instability_detector/test/test.cpp | 30 +- 11 files changed, 858 insertions(+), 122 deletions(-) rename localization/pose_instability_detector/{src => include/autoware/pose_instability_detector}/pose_instability_detector.hpp (57%) create mode 100644 localization/pose_instability_detector/media/how_to_snip_twist.png create mode 100644 localization/pose_instability_detector/media/lateral_threshold_calculation.png create mode 100644 localization/pose_instability_detector/media/pose_instability_detector_overview.png create mode 100644 localization/pose_instability_detector/media/pose_instabilty_detector_procedure.svg diff --git a/localization/pose_instability_detector/README.md b/localization/pose_instability_detector/README.md index 89cf6ca3be684..4ced0fa8eb97b 100644 --- a/localization/pose_instability_detector/README.md +++ b/localization/pose_instability_detector/README.md @@ -1,20 +1,111 @@ # pose_instability_detector -The `pose_instability_detector` package includes a node designed to monitor the stability of `/localization/kinematic_state`, which is an output topic of the Extended Kalman Filter (EKF). +The `pose_instability_detector` is a node designed to monitor the stability of `/localization/kinematic_state`, which is an output topic of the Extended Kalman Filter (EKF). This node triggers periodic timer callbacks to compare two poses: -- The pose obtained by integrating the twist values from the last received message on `/localization/kinematic_state` over a duration specified by `interval_sec`. +- The pose calculated by dead reckoning starting from the pose of `/localization/kinematic_state` obtained `timer_period` seconds ago. - The latest pose from `/localization/kinematic_state`. The results of this comparison are then output to the `/diagnostics` topic. +![overview](./media/pose_instability_detector_overview.png) + +![rqt_runtime_monitor](./media/rqt_runtime_monitor.png) + If this node outputs WARN messages to `/diagnostics`, it means that the EKF output is significantly different from the integrated twist values. +In other words, WARN outputs indicate that the vehicle has moved to a place outside the expected range based on the twist values. This discrepancy suggests that there may be an issue with either the estimated pose or the input twist. -The following diagram provides an overview of what the timeline of this process looks like: +The following diagram provides an overview of how the procedure looks like: + +![procedure](./media/pose_instabilty_detector_procedure.svg) + +## Dead reckoning algorithm + +Dead reckoning is a method of estimating the position of a vehicle based on its previous position and velocity. +The procedure for dead reckoning is as follows: + +1. Capture the necessary twist values from the `/input/twist` topic. +2. Integrate the twist values to calculate the pose transition. +3. Apply the pose transition to the previous pose to obtain the current pose. + +### Collecting twist values + +The `pose_instability_detector` node collects the twist values from the `~/input/twist` topic to perform dead reckoning. +Ideally, `pose_instability_detector` needs the twist values between the previous pose and the current pose. +Therefore, `pose_instability_detector` snips the twist buffer and apply interpolations and extrapolations to obtain the twist values at the desired time. + +![how_to_snip_necessary_twist](./media/how_to_snip_twist.png) + +### Linear transition and angular transition + +After the twist values are collected, the node calculates the linear transition and angular transition based on the twist values and add them to the previous pose. + +## Threshold definition + +The `pose_instability_detector` node compares the pose calculated by dead reckoning with the latest pose from the EKF output. +These two pose are ideally the same, but in reality, they are not due to the error in the twist values the pose observation. +If these two poses are significantly different so that the absolute value exceeds the threshold, the node outputs a WARN message to the `/diagnostics` topic. +There are six thresholds (x, y, z, roll, pitch, and yaw) to determine whether the poses are significantly different, and these thresholds are determined by the following subsections. + +### `diff_position_x` + +This threshold examines the difference in the longitudinal axis between the two poses, and check whether the vehicle goes beyond the expected error. +This threshold is a sum of "maximum longitudinal error due to velocity scale factor error" and "pose estimation error tolerance". + +$$ +\tau_x = v_{\rm max}\frac{\beta_v}{100} \Delta t + \epsilon_x\\ +$$ -![timeline](./media/timeline.drawio.svg) +| Symbol | Description | Unit | +| ------------- | -------------------------------------------------------------------------------- | ----- | +| $\tau_x$ | Threshold for the difference in the longitudinal axis | $m$ | +| $v_{\rm max}$ | Maximum velocity | $m/s$ | +| $\beta_v$ | Scale factor tolerance for the maximum velocity | $\%$ | +| $\Delta t$ | Time interval | $s$ | +| $\epsilon_x$ | Pose estimator (e. g. ndt_scan_matcher) error tolerance in the longitudinal axis | $m$ | + +### `diff_position_y` and `diff_position_z` + +These thresholds examine the difference in the lateral and vertical axes between the two poses, and check whether the vehicle goes beyond the expected error. +The `pose_instability_detector` calculates the possible range where the vehicle goes, and get the maximum difference between the nominal dead reckoning pose and the maximum limit pose. + +![lateral_threshold_calculation](./media/lateral_threshold_calculation.png) + +Addition to this, the `pose_instability_detector` node considers the pose estimation error tolerance to determine the threshold. + +$$ +\tau_y = l + \epsilon_y +$$ + +| Symbol | Description | Unit | +| ------------ | ----------------------------------------------------------------------------------------------- | ---- | +| $\tau_y$ | Threshold for the difference in the lateral axis | $m$ | +| $l$ | Maximum lateral distance described in the image above (See the appendix how this is calculated) | $m$ | +| $\epsilon_y$ | Pose estimator (e. g. ndt_scan_matcher) error tolerance in the lateral axis | $m$ | + +Note that `pose_instability_detector` sets the threshold for the vertical axis as the same as the lateral axis. Only the pose estimator error tolerance is different. + +### `diff_angle_x`, `diff_angle_y`, and `diff_angle_z` + +These thresholds examine the difference in the roll, pitch, and yaw angles between the two poses. +This threshold is a sum of "maximum angular error due to velocity scale factor error and bias error" and "pose estimation error tolerance". + +$$ +\tau_\phi = \tau_\theta = \tau_\psi = \left(\omega_{\rm max}\frac{\beta_\omega}{100} + b \right) \Delta t + \epsilon_\psi +$$ + +| Symbol | Description | Unit | +| ------------------ | ------------------------------------------------------------------------ | ------------- | +| $\tau_\phi$ | Threshold for the difference in the roll angle | ${\rm rad}$ | +| $\tau_\theta$ | Threshold for the difference in the pitch angle | ${\rm rad}$ | +| $\tau_\psi$ | Threshold for the difference in the yaw angle | ${\rm rad}$ | +| $\omega_{\rm max}$ | Maximum angular velocity | ${\rm rad}/s$ | +| $\beta_\omega$ | Scale factor tolerance for the maximum angular velocity | $\%$ | +| $b$ | Bias tolerance of the angular velocity | ${\rm rad}/s$ | +| $\Delta t$ | Time interval | $s$ | +| $\epsilon_\psi$ | Pose estimator (e. g. ndt_scan_matcher) error tolerance in the yaw angle | ${\rm rad}$ | ## Parameters @@ -34,4 +125,44 @@ The following diagram provides an overview of what the timeline of this process | `~/debug/diff_pose` | geometry_msgs::msg::PoseStamped | diff_pose | | `/diagnostics` | diagnostic_msgs::msg::DiagnosticArray | Diagnostics | -![rqt_runtime_monitor](./media/rqt_runtime_monitor.png) +## Appendix + +On calculating the maximum lateral distance $l$, the `pose_instability_detector` node will estimate the following poses. + +| Pose | heading velocity $v$ | angular velocity $\omega$ | +| ------------------------------- | ------------------------------------------------ | -------------------------------------------------------------- | +| Nominal dead reckoning pose | $v_{\rm max}$ | $\omega_{\rm max}$ | +| Dead reckoning pose of corner A | $\left(1+\frac{\beta_v}{100}\right) v_{\rm max}$ | $\left(1+\frac{\beta_\omega}{100}\right) \omega_{\rm max} + b$ | +| Dead reckoning pose of corner B | $\left(1-\frac{\beta_v}{100}\right) v_{\rm max}$ | $\left(1+\frac{\beta_\omega}{100}\right) \omega_{\rm max} + b$ | +| Dead reckoning pose of corner C | $\left(1-\frac{\beta_v}{100}\right) v_{\rm max}$ | $\left(1-\frac{\beta_\omega}{100}\right) \omega_{\rm max} - b$ | +| Dead reckoning pose of corner D | $\left(1+\frac{\beta_v}{100}\right) v_{\rm max}$ | $\left(1-\frac{\beta_\omega}{100}\right) \omega_{\rm max} - b$ | + +Given a heading velocity $v$ and $\omega$, the 2D theoretical variation seen from the previous pose is calculated as follows: + +$$ +\begin{align*} +\left[ + \begin{matrix} + \Delta x\\ + \Delta y + \end{matrix} +\right] +&= +\left[ + \begin{matrix} + \int_{0}^{\Delta t} v \cos(\omega t) dt\\ + \int_{0}^{\Delta t} v \sin(\omega t) dt + \end{matrix} +\right] +\\ +&= +\left[ + \begin{matrix} + \frac{v}{\omega} \sin(\omega \Delta t)\\ + \frac{v}{\omega} \left(1 - \cos(\omega \Delta t)\right) + \end{matrix} +\right] +\end{align*} +$$ + +We calculate this variation for each corner and get the maximum value of the lateral distance $l$ by comparing the distance between the nominal dead reckoning pose and the corner poses. diff --git a/localization/pose_instability_detector/config/pose_instability_detector.param.yaml b/localization/pose_instability_detector/config/pose_instability_detector.param.yaml index d94de020a4a12..d9b11b78885c9 100644 --- a/localization/pose_instability_detector/config/pose_instability_detector.param.yaml +++ b/localization/pose_instability_detector/config/pose_instability_detector.param.yaml @@ -1,9 +1,15 @@ /**: ros__parameters: - interval_sec: 0.5 # [sec] - threshold_diff_position_x: 1.0 # [m] - threshold_diff_position_y: 1.0 # [m] - threshold_diff_position_z: 1.0 # [m] - threshold_diff_angle_x: 1.0 # [rad] - threshold_diff_angle_y: 1.0 # [rad] - threshold_diff_angle_z: 1.0 # [rad] + timer_period: 0.5 # [sec] + + heading_velocity_maximum: 16.667 # [m/s] + heading_velocity_scale_factor_tolerance: 3.0 # [%] + + angular_velocity_maximum: 0.523 # [rad/s] + angular_velocity_scale_factor_tolerance: 0.2 # [%] + angular_velocity_bias_tolerance: 0.00698 # [rad/s] + + pose_estimator_longitudinal_tolerance: 0.11 # [m] + pose_estimator_lateral_tolerance: 0.11 # [m] + pose_estimator_vertical_tolerance: 0.11 # [m] + pose_estimator_angular_tolerance: 0.0175 # [rad] diff --git a/localization/pose_instability_detector/src/pose_instability_detector.hpp b/localization/pose_instability_detector/include/autoware/pose_instability_detector/pose_instability_detector.hpp similarity index 57% rename from localization/pose_instability_detector/src/pose_instability_detector.hpp rename to localization/pose_instability_detector/include/autoware/pose_instability_detector/pose_instability_detector.hpp index 761a10b7a6bf7..0a55a5005dde1 100644 --- a/localization/pose_instability_detector/src/pose_instability_detector.hpp +++ b/localization/pose_instability_detector/include/autoware/pose_instability_detector/pose_instability_detector.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef POSE_INSTABILITY_DETECTOR_HPP_ -#define POSE_INSTABILITY_DETECTOR_HPP_ +#ifndef AUTOWARE__POSE_INSTABILITY_DETECTOR__POSE_INSTABILITY_DETECTOR_HPP_ +#define AUTOWARE__POSE_INSTABILITY_DETECTOR__POSE_INSTABILITY_DETECTOR_HPP_ #include @@ -22,6 +22,8 @@ #include #include +#include +#include #include class PoseInstabilityDetector : public rclcpp::Node @@ -37,13 +39,31 @@ class PoseInstabilityDetector : public rclcpp::Node using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; public: + struct ThresholdValues + { + double position_x; + double position_y; + double position_z; + double angle_x; + double angle_y; + double angle_z; + }; + explicit PoseInstabilityDetector(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); + ThresholdValues calculate_threshold(double interval_sec); + void dead_reckon( + PoseStamped::SharedPtr & initial_pose, const rclcpp::Time & end_time, + const std::deque & twist_deque, Pose::SharedPtr & estimated_pose); private: void callback_odometry(Odometry::ConstSharedPtr odometry_msg_ptr); void callback_twist(TwistWithCovarianceStamped::ConstSharedPtr twist_msg_ptr); void callback_timer(); + std::deque clip_out_necessary_twist( + const std::deque & twist_buffer, const rclcpp::Time & start_time, + const rclcpp::Time & end_time); + // subscribers and timer rclcpp::Subscription::SharedPtr odometry_sub_; rclcpp::Subscription::SharedPtr twist_sub_; @@ -54,17 +74,26 @@ class PoseInstabilityDetector : public rclcpp::Node rclcpp::Publisher::SharedPtr diagnostics_pub_; // parameters - const double threshold_diff_position_x_; - const double threshold_diff_position_y_; - const double threshold_diff_position_z_; - const double threshold_diff_angle_x_; - const double threshold_diff_angle_y_; - const double threshold_diff_angle_z_; + const double timer_period_; // [sec] + + ThresholdValues threshold_values_; + + const double heading_velocity_maximum_; // [m/s] + const double heading_velocity_scale_factor_tolerance_; // [%] + + const double angular_velocity_maximum_; // [rad/s] + const double angular_velocity_scale_factor_tolerance_; // [%] + const double angular_velocity_bias_tolerance_; // [rad/s] + + const double pose_estimator_longitudinal_tolerance_; // [m] + const double pose_estimator_lateral_tolerance_; // [m] + const double pose_estimator_vertical_tolerance_; // [m] + const double pose_estimator_angular_tolerance_; // [rad] // variables std::optional latest_odometry_ = std::nullopt; std::optional prev_odometry_ = std::nullopt; - std::vector twist_buffer_; + std::deque twist_buffer_; }; -#endif // POSE_INSTABILITY_DETECTOR_HPP_ +#endif // AUTOWARE__POSE_INSTABILITY_DETECTOR__POSE_INSTABILITY_DETECTOR_HPP_ diff --git a/localization/pose_instability_detector/media/how_to_snip_twist.png b/localization/pose_instability_detector/media/how_to_snip_twist.png new file mode 100644 index 0000000000000000000000000000000000000000..6dc66a480e7698f917953c357cd357d2589ac6a9 GIT binary patch literal 179156 zcmd3OcRZH=|F1p`m39)!sEm+g78xxvv-hg(m9jS#4H-pt$ll2;S*4I|9sW6_zZK9-RbJoh>l8uSw6?!ET3j;hzLc(>7i)Wx9_ZaWsqdQzYgCPm@oW};k zZt(C8+_}ZYIg}Jova>RRgoK_%;@oK^heu-{9c^UhS5~J~r8zh3^bEa`nw4tE%k(@s zWu~!bI{R{`;|0 z+s>RI|N9|&(gXX6!Tc{@_iyglw*J5TjQ_qpz47)xe?Qbu?|F93-w#>sD2w^~5fc85 zy>fp)4c&$InFkLY8keX3`_0_OeF~mt zVc$3L>C^oybbtMl#9Z_Qxxv{LBu_~kP-@m^@ zyTGd4ShJ4OwAgj!hohILr(i?pUr#0BC+(H{w22t?ybL3^E!M+_#e>*XYb#PoPI>$KwqVYE z@(T+KH}7H9uk`-;=N>}ZB`)e1*MNA11j!Whj%>Rp8-HCm>@?o$KbS8=bLL3i=J44p zi>`c=g~?vocwv$PRm^gtOoU->l1xNms&ZOq*1?~Dc2QO;_=x<)i;o#ntcPkxdP+-O z$$rhosl=!0f|KhOzJE{XVm7%r)1IZ*p}g&{H$hK&X#Zw?ZV?d?J*vbRHPUl&v9acx zgZ`e)i@sM6->-3TagiQx4u1G-KLH<_k!Gi~h1HJ4NQZI(o=K1Z$LNU`h z34DJ&^;GRS;;CWk6vD&rV~?=^J)mzlmc^Xn>nw3C%(BQ*GuKh*cABe?c3F%nA~)~{z_U|^6k`+Ft-dg|xCK0Q;-x((q`@veb>e=p=yrdX;S zZ`#`0+H2niOgHLs-_{^Kmr?omOVYCwFZpY#>yPZ?;Nej^efqRI-`|^xeh8aN|0ZTF ztdlB?x4D(`?-D4!saKAEALc`7j#6T6LZu&#^VolT3cs$f^InpE9yd2PZ$H1<>1&vf z{-L2HF<)wf@9iX39DDcfl?gre$~Xke%&+Cw@H#sWMcVtg_Z(49eHfYc>ordq?%cLM zJJjD_Hs4R?1o=}X6$$$AVN82d z)P}ELzs?=~edp>gUtP{p8`EBQKk(5>``Sb|k>#1dAIr;(5_zUAjb@p}hE0y1&q+um zeCaq`R|<;Lh&!4*vNR-;@crAk_V2OwNH2RIbBZE|w@5u*jg$Yx3GskOj~;Dw{fC6B zrec-j=W8k0jyx=8`}KxM?gwF3NJs?xru)B_jw>V_Nmc*$VA-2^;^h114xIj1J}!=O zkgu+;ULra>zV4s>*_IqC7#V)_*xjR;(#Sek=2lMp%E8cO^7JLw)#5mYs>@l{oWx`J z%2tY+Dg5={fB*fYjy?GAPe1?jf7$}4JBW*26p4w6(a1G^&_FBb@bp~>hvmQf-gRmG z*^6s^w-{2?a|}o7V{S&W{aR$F42fH(-+K=gs5@BdTNXNWE)-r8K>moLd0d8Sn3H`bGNX8r0D z7cG_3RFq@Rcri#kdGf^W$?pjdLt`NE(0X59F1nlfLasg4&&z*e;naV-!#U*FYk3@b znLYjcW&eEppI-j|GUoU`rv3BP)yOt)ZhUo<)b`t;jQSCZJsdh(%Bf27uWxNtE^@f$ z970NRDzUu0eE8+{wbS$Ss^`vmZr*z|oy*`|vSCels^+sN#npex+b?|ew*0c5p6zfW zW8C=HuTRc+ZSFu*;IB%{EMcXiqlfSSBuJ5(5;1DU~tTH>=COh@~*|TRGwo>co+K;uzRQT>Q zGTAD-8{LK1wE1nfL1^xkkDUv&`6f*j3vR+J9kXKwAwte`UyA3un`$DC2hx}|CqJIfAHRytcq5MQ`@c6hq z*Jat6rFYvzx4X!3U}Plq`STN)w*>yt!ye3|-Nnw-$1ZxzP4q+$==sx}RFMif8dQE+ zK9ET!+vSH*6>e&F!hKb9=gyr@UkirDv}+X)oQy6W;(43xh3si)=?*ry^HZ z^RIkNy>n-ybI6oZRjm<6;fF$dS#%Y#Lg_FrjS`oFa9%URvA!_U-}^$J_ZK=J`-(+U zVb@#c#p}9gv*(Cfeftnb%0K)5xrSKL0d&&b>R@)WN>h^duEqqZJ-c@wk`N1}t5RR3 zVwSi`x}9(RS;mz|f0n7f(C@1r6%gobf1*{8%|hv&bRNT|oT($^9J1yU%PWQX{Hzu3 z3jtB?D~>0X|McCrGSlt9s+=A^QCg7{ssQ z*e<%fIBPpQ(xSg4`{=|0BO{|YKrhEgeru-Jea_C#W*EbOc#X6ed{&RmngUNi0IS5J?&W;9`j_fS$MFU?P+i9a~Vs+j15 z!Az`;JehX(_BN}lSD!k*?{Qz%9&O8P>wSHjcAf~1k`r+e8 z-?``4`gjcAQ${?YqosX9=eBS|)k+cB_*mUMMRihH5~N`-b7_ytFe(_l?RQl0RUbb!+HtCzHk9OT!N zQ9NYGLnU(%d1lfiw(s~AY1>DYuA~NSIU(V?Qrk~&3#glbY z`_PwaLOIWZO32I=;Bw?xVvirw6D2R4&mw%ocG`4_KqeO5lJup~&kqirpQ$}L!9cc_ zbi)SLW5?vWySq~rll%^LvJ4)=HpYDpXh1BE#V#hBNHtw^!jwRUZvk~oWHOnriahe+o z`|5ysXx^*q5@T8NT@3syQSWYP$eRg=Z-X_nn5|T_SoOuQ#>OnY^NJ^$D=V36u71HF z`Cd$Bh!kaxROMrPS4C2V^h{N?P|k0;B8IXO8;x{C`hLy4}V{t@8LzWZxXstg^JOVV>Apk>`|d zrg4NqCY(nCBbSr13cfot7-4CO5}DFnIcE3i<(k>yrt|Xh@+Ncl?%b(QmXB*Jj&3a~ zF2;*qEr0VSzU%nGgJ%>Ir5iBsdBzO~_Z*gcX@kP1jhiJ{Gs=MPGX4n(3=Cu-Iw4ilgou1)m9jv z|MY4tdi*KqGkmVM(4A7Tt~Cm*5`fSzHSx2ssHBHp&vHCH=PE8R29bPsHjp<>8ZxwuS?Dup?RoXr=vi; zpGW-G<|F%d?~dcQ9{lp9A#SnvHl1`EhkUH(l(UbYp9=JvYw18~iR#fgu~+`Iuz+`Z z6F<9N{{^CBTwhCSgE4F}e}DqUGe>vgDt(QCw}tKeS8Za@8+Bi$VN0{38ep<{4E@t} zOG_F=Pyo^Gr1+|}V9xTYDBGHVR-vtS~gFq=}NH3pL@q+>382Doop- zUP?LIC+Iw9u6Qihb!iT3EqZ1s+I<8yak0-|1drLFe^&FP^);s`DsD+xTv!M_qYf}v z@4oVl4%=7q_>~WG&>rT#eoWggyzp}4h@^W>_H7w)Vb_r#PyW4AeVN6QTO?g>BRHK=r`rXj+fkk__aE zf)5`)NH16VPz9Rv)t|#XW5}PdNDqJh9E-v^Tpx4xh1>FrquMXxWg_^(4C%L$ku`~| zOl?=(aV(BlmM%J@k8K9t1N>6f?Y$O+8PBivBv-vgEsBo^{DVm1wQ4smyRye({o+H^XJCspVZ*9JIAhFy;@(* zQJRj@Q~mn&>k~s*7#e7{-hHlf9Y%>^qZ-eyWMFTYU~Q%96u%(Ko2shn?3aeK7|^Cl zI(PFK*O@O5Zf&881v+gC#Q?FXq#x@f1`^0~V0f4X5(jp_EW|Svw9;8rT+-KjfbcffHHA_CQ9h9TWy{ zzYUsH1u&X6#^1#)#qMI1OhzdX`@$&?P$j%HmLsh@Iy2mqXpkQn8JTBLP2uS1n1Z&+ ziV8ve!CoDQ(*W>|mZi&yfQ*#O=Y6RYAU8_uif}Vsctl{qedBA^ZXiZ#q%$u~GUO;b zGcz-RAHNONwPA@^=#&VsvPuH{aF*S`>=BJgB~vE@d#$>oL*38M&&uAu4O416`RO#T zN#mOn?zmwLiE67`ySWNTkVR*%1jb5k{_98OXIHd&jq6WgA2ngdm5QBg<0e3%WTX-` zHDB1I5F{#hACK{4>}r$#w-0~-Zf&MGk{rM&m5P0U84E+zG(U0^pzKM^+1rK_qXvAM4=5JejrU`PUoQ7fx$^M^_3U|G=z^2xcZsS4o z>*4cC+%>OW7y5m1G&91GRA%J$b`hTSc?#jaGh-b&6>|WH0fxS4SPE@Vw0-9q;?D2c zw=cqU)o0<;&Fw_TN_03P8zmUdZRCe?Z#32g1eIvC9aJ{oq@oR*ww8z6LIDV-m1v0{ zMxQ=?s&w{M#{pC@pd7J6Z05z0w9JRhvhUorCt5QiSY8GPqhx=i^{_@-bEkMBqnzqEEcT3swY5bXyC?0~R^1Oyw8fAw)} z269H&KW_t>WiRkjh8usWk4dB=Q`DoeVh1mSY#Q{HpHcGRF;`L$@=UV5N8_Eln;xU| zCU&?hejXk+36Gq97sOVzXbv9-ZRL1poS3g9_wOrB>NO73ZOns*6grYkVAJTj((LnSdhZ)NNH&RXk+cfPgF>Dv8omK}XaZjq4uqD-xShOG_(N zkLgx#s!E3G5fh6Hj79~vW#MeYdAebIPw`VtQ(=dGBnmNC0hHfjQEPa(BPR)^BJ@fr zD$~A8ye#7hPZX^QMDpIf*l9NVyVmHZE|ePlS;7`nzx0stCrT*+1UdN1?>OBr-&5k+ zG=}0z1I}3cbIuZbZZg=8G*>kXJ4`;78S2nuqf`^ZfuS5E=`;V#HSGtQ>Bv^GziikOP>fW~h#C>z=(W^vT z8i2dj`y%R={eAX;63fOVH}y2Rm>UEk9Z~yJ2im2kQw)e7=xxH!ux7A` ztWtrMfnI(&N`U&2;4SML39--gnQ=qepmpF2;M2sqycXYm$I18YGs^|CH2+r6lBOza zZ*E5CI`cqy@k^Y~o`qGRyUq{xq#Je1+?(Y#$WjZSc~)W%o!-jMuGU6|=p{8u;o4Eo zU-_|QM$xMSR>FIqqw-Z;8>RBs%r|El&YY-3S7DSO2$qAxb53VVi1aMS!aEoTqKOfO zR3bC}zNl;W>m`Yv(SL`NjGM4ANZwARhp^RMHlY>#lLatd#Te=>fnX-OUAS<8iuxJ0 zbmANsp3L|`QSY~1U7D7~v%w~VVrDBVE8*ygFYLxsU)YYmtFD#;lTOjGZcSHT{PC?$ zv6vJfyxw1AB^fwz1bDv<(t`B$_R63K&X%qs*hBG?lapJt*@l;0_Di_8bsRWyAsl8at8GT({F3^xS8XYkxHwo=r>i-n7R{LY-aw&kI7Gv5_2x?s zK%}0@B4mkF0=zz{?w+96)E_7mVvGLQwxxx;O1yu59n;g*&4Mlq$I7h(Yq>%j41#eh z53gwB?GlaC=EuS{nMWt&x9;PUo)tK5+5HfN9soGz@#DwjOZ`=W=Lv8Fsxvd&rke&F z!>ac5qPOdzLx)hTSP60Gq}|xtdZX&in>KAqv@^9$tXQ0%d!BA|$5kOfn9fAPq(aI} z-H{{R=y=Um$ay*D>CBE3>91o5+H}Sne*_c}eJvfUI3PY&^j_-en;R-tFai6zTBY7S zGi@2kGW_O3(S3T@HM&u6`D4wO=;MFpRex`A5Fwo2?=!I3AUV3y%3T(8SiY>8WB9%Q zutaAmRKb+F4D2p3f7%Qn4?+e42c4dpdVuu~8T9gqGZ0qs%Hk+)LO1nQJOP|^OWmNs zM90R)+5iIT6+xYfC<957cY<@2XW3J-g`F%qAlHyrW&|d}PmNaj@u}-uw5u2A6`|8X zcrg0%gPDC;I=eNeIgz=zL?XIH*X_F~hB&wQxz>C1icpDc3?)E%WF%X*463Sfy!cKc z{BYpFX^1Mol^<#|}G2u!9s9#YAI>v;xj^ z>9E6@Ko;U;ZESME$&8yEOsd3BeZyT<v@ZRH6=Siq3=%64mC zC^>cgAE#cgy*_j3ZWhAxV7Vr=vQ8Z7A$w$H&z!kY`-opJyo&dDR*C)IqgwSCV>}7f zolpu)!lsy0pt@B6Wco7$E{b_)X1Q~t3(UCHf~X19BGKVokBxRZE9`_I)t8~g4dr# zJsCki9rja&go6f9XWS*wWvXFbECQ?!Bb~2P;;ebTxKk~zY9VY7+6%oZ1@Hqp@A#JW zQgr9RPJPFrP`pFXC-EC((ffnfKwr@Kx{YBLbQPH|Lp5lAVQZ$Gq9BT*AwzK{cxAJs zQOMZ-E((e0I6Tzhas{A4snpGt=w%Ql6&xHE^jZQMoEu`!lIkrH>Vw^Q_%=FW^Rb*L zb)^78)`x&WJ&v*yQ5NIRZDwp&d^5Z6yD^L~6N(;GxptQ;jYEfq$I^c;HT=^~M$}iU zEXX`Ekpe9X1yB=;rT+0S&v9FJ`VMg2F@)D4q$eLc&}U^(L&fOhJuZrl(?5E26A~{( zrY0vR+hmGBSjNVu9xriS3ipHbr+)3)wSaii?X+JYDC@q^(?O7?`KaoXM_Jl&Vp|oD z)ht>kFriFZ;dQkAFx?aI6=0p~D-t1%q47ZDjS zdZ_@UfDRr!7*N9ys*MF;aj`TtgY%kh?MklHp(lPH3*PeJh<}gRleAppW;~?y2 z<=%UK-8YtJSOrkes9xJzlDRpE5!9;}CLw{e7w-QxCHlL5O$bC(2*uqCjsa4`|GW&O z*t<80XvlCuS!hckI(55zlW8iv3T9Zf2%HgNIJRZu#(Ix6Ya1U0O^s%jwxUS++D&~f zp9O;oUz~yPmiuTLrGr4)N|iqT{%zR9GE3_5|{A#bXw%N>=hQv9@(*2{O;KJ}8j9+@JNmQ4* zy>(yk=h@d~WrY4mEkdP!MUWS4Q31P-V4D6F{&XDo$^$O1!bWCV@=2kB8iWXk&s>=o z88675(vpbNj5wXk0#ke^wKRson$OVt!Y&s92E7jaCcu-nh>?SW@XiQ za-v8tccP~>6YDRLY6n~(PeRUb64rE=HOVTe10ra~3ThInL=4EFI+&^}rN-E#cokz% zQJ9XFk*F@p&05%f8a8tA>dI2$r(x!3mjJ`(g3v@Uxo%=cR}0!g-}2VeySyU%SQ$-1_ka_ zAuA07ND?L)xIWN&$||(lkq-qqCQQuuJ+DP)GtVFlKA&+&Z(H}DkORGGM!TN{q=u;{ zPPii&F~W8+hU6}`3N_03?fnCMA6jw=K@!-ID3Oq~xKRw)VElui5~dMi6$!XG%H@5$ zrZZ|W0(h||R|r0;u!49mzu7q6Q>uIE(k0wkBlZ)oQSE+IpZB>RX3=>vVe}-Pm_w-o zi0AGb%Bd5swux*_lny&c*s8@4@d*}*8mcHReg|8ez!1K4B09j(%4%wA*_;X*rd{Rb zj2!`!(Qb<=1eQg^Az)EfR@Mub@7b7wB$W(}FhfTe5l`X81YNEnMz6-<1ul-n(`lsK z8dP;%gL<7WW)Nb^T$WxX5A;xWogy``P35asC-r8>t@2-uDgRgQ8QwJ8lUf}kBu>-<3&Phhu=Sk8G@d(RL`aJhB*+Mw2)JxLVX zEIvHXA~>7=Hz0Ao(nGv}9$%9x$*ZL~L&PYi(IysG?%t+5Zhw{?; zL^}<$PJJm429xVd!+Dd|`^>VmM4be3viGhOfkp&~e(t>A{s%LvPaD7zbaZq~{4{e6 zWr*NW)f^HT^6tQ3 z?Ex$py-nvPo^Ng=hNh#8(%FOp&bZ8bXb?s%AYv*{U7A`}tjZIuFmuDQu|a5oXv5e^ zI%1&{C_jJ;SG||NL5YR(Z4BI5QS#6F&GGHe06N1t^=_fQ5L&ZDBTA;iRthG7{l~#a z)Guqqeh80?izAFoaCE7~QCbeI=k+JLp-bwoG1eq>(uHl}jlt}iK6PN{28zc{7Lp&9 zJ0-HR5U1n5YzwzvtWme85>J1*?)cVF&HAEPC+O0aB}I$@jqs!U&gqc=*BPXn1F4Fe>;snjjWfFM|js zs_*^@WAd;&Y;GnJt_yBdhMUn)1$tqw!_;M0_-Bb!{7sDzmB&96C<3y$j*S|Lp}h`_ zk7uCr3)i?YN(DEg6A_Rqd@gCWXd8`y65g?t{n)v?b*4kLkxgUAp+u7#J$e`~vihSb z(JZ0==5}E@bWBCTISBmvP9J;-1%k)~5N;f*iR?2%59D>4F-Fp%VsJv!NdO5^Q*rJ* zXZSukjt&l?bIR#z^5{5{vjP$~G2Y*t}f(p+~yPJ!h?SbW`vA_s{;33$A(EJB$)1H#z#rcWo81+q9 zg=vHzW>ovA0dq}wIA(262w{xSrl9U6LoiDL_nDrYe9CeTD@48~T11z4VJv>z{oqM<|v*C23iFv)}`gDxU!q7$qu5~t%d%=mp_fzT9yh6&;X%Pj-j zFIh5(b)+%j9wbTz@F-$#Y_2#RP(y1Vx&dL>pqtyye33_t`U{#6D{3?P-%O(v2UVS^ z#(|M@cMp^xbfJN=sDOO(^iUlEyWryUHO;?*t5LeLn1*c^2Ptp_rNrCcU$rCKKym9j z!w^tzQ%D$uAx(r3h#VM}-3#aWCrI`xW$Q}-L`q=-m7pgom$-aCk_kxbRu3c_M<~yT z5-2GtJ(LVSg0P8Xg3|@)PkG20#6@aMH5vN#x?p@F7*zw#t%!L%kiZ{)Aumxz4tzPJjCrIMbHxPM{oQH}CIb z)c(g2J=iXSb8FcANLpi}jJt*X=$ssz%DMJu^q*LIv8kXcP>s`^w9}U&*;!CW1Uevf zL1{c(9lX6R8D-z($HJ7@5_pL^_262P{%v$Fa%w&9t8HUV85$BLC3Z(Q%6g$CupnI# z&|F|`gsezU$@IK^L)G!l<3&q3Q5463*qlVqb+5J7@;7mJHR;yc3^9g>VOTKAs= z85jQ?^wlF$YN2pS?h=YaT1EAS&DVJ{L1ASeJ22l)ZTc-X1Bq2E>h&cYEzj$euv zQDx%mWzNgXS;md=5}P+~4v2_|K)z|IU9UAov65#6i?eBL^|ud?W?xZqyxXBK>tBhC zH-aD(47gcrs`)QJM)O zNpThQWR!?BLZ0aF?|+z(_w(Hm|Iiy23k}B<|A6+B(O+iqL3NHS$ui-xwqihsd+${q;I; zkNn5WfiqKFP2ypWce@?6rwvC~_^Jb${UNYIOEH}YzQl2w1K-}p!%-H>IS^q~FgLaX#2d&%GJw!lARC-i z^-StO=hy>5Xo8C*!UBRE6@&GrZrPugz$BjgosRZM0-Vn1CjzGUZdz%Y?H?T-jjR%5 zR=kS_g07}cvXwZA;02_e;aJoTu&42qdJ#|OojtaW54H+c}9}D9=rnU9=ZQ`3C?XN7W6?W;@ zVes;Rcr?yr{i=X}Pw)^=rrrKi|L$kqPAgas>o^mVT$1R!wZujqK7wb zu!LcUK8lPS7#m9`ILQ*cqbpBkZ9P)_Y{=+^-ZmX?-a5APtHfzhgB5ju~ zfJl~aAGBefx!Yb|CaAqcQf#C(gAIWVqWNmSuxY@s`8Zi1zHx}ikFMRYMGh=U3Ht@! zlrlgHk-{VLQzfmutB44i_>K1U#SuVW0m52i#%uHiv=`WC4+*dXo{*wdU`0gP3GoIM z^a~&=pKBtJ9i{CP&1bdk?m!#9v_cx7hpI@yC}&+3g=8vD?0wE^6EQ6WFbM{U7L$g- z`7I8%LP%|L=?>gXM#lZI3&$%MM+pN`G5Sr96lgY|Wp_F(yJVPcsGW-N4+tHPNK=8L zQLShJy)@zqEx9I&1Pa~5sw9WvJ)7yiELFO?QrM7*K@$^#!(2OQ%fNE*U>T(zns%Zd zF2vEcdB1u4(^u`KV1iqzxX$5q9-t}Wy(d6HB$S23iK|3P zt0s*5JmHPO>IcAaB&1?$0h?sM{rmwjbrC^zjw&at`tPiKuX8872?A1^HYdjrc@dN@ zER+kgMF6KM*w7Wr8Ax4Dxjrk0_2Xj=^(6&?IO&$?h9P>kZc-Q}$0~s4BC=M&ZxbiJ zAO_Nyz6_5g92s(?NtM773tqe+%%hN`q$ENk#Q1gCYzObM)N1PL>Y^+p0Hs2LH_?iL z?1@-s#YFRBT?nGj)OwH_Mq%fx8@3D2@l}NQS_Jz88QbN&2&HCn=N!1=!i%Lq0d|`O zYm4CM0H*Wjd5A5P<&~9e(2QQadevF%{0z`Nfe;Z8fPD6y8i9dkkO?0in9z5 zWsXS+-)5g1>xi50c9td3(RiutXfS|(0-{gDIDXMc1WgHH>tr{G8p5sh`fJM2rf_CL z7glH^fddh*Cvv}M^N_f&Zl9Z+6wjH!3xnL#4MXIr@*{$-NF)&4fk@157x^KFkqtlq zqbBd%xpQAI;H{XB02&x7a!3FG9I*hp6M{%>ZLNtPAbk=Vof#xWBBwFj4nYOO%9x>5 zpa5^J+Qzt%0+tA&S`46pb<$zTh|&hgrt$RR_3mZ&v5)pjtYjWX-;Y5CndMdQ=%925_nUg^Em z9jTrFsw~z`Waw&bcbKzLRAe!?)ce=g%opCEJZ{(4E_bgCg_MYa>cf)cT7rJGW9QE6 z*cy6eo}1K=RTArwGC@#xE97E72$0_SM*8}n5T<$V_>BoH=nh6b1|^oHoB1Ccj|dT$ zkl5)9Fd$}Q!vhE016NL);SZS+R6T#;!Zz@b+o)W3chz!nb3b_a&=bZsDYncjyf_g1 zR##Wo1_vP_p)FKg>#%}INpP<46HMVR?OAb+)<%Yg-oiJrA7iu%8kda7Wkj|&2Ze^- zA&8`S|HGNje$%S)R3tw;t4Hq3`t6Vz<@q1y%RX*C|P&hN_U<8pDX}U6V0j0WQ57ll@vcz zAONB{1$OG4nnE#%_oaqpIcDXlMHgS#2~=y(ez{M}^VeCc2rHXhNEQz@yO4?|-5oj& z3Br?q-`>5$I$YT`DGPy*U_N`e_lPn!$VHGZNG=FuWuu# ziHXVN^faqY6c*>JmX^HwYdB8v5)|DtzobMsJtJdkan`KC$hNm^z0GLrR=n;xbghAk zom5nJvGEQ7aGSh;xg?oHtQ1hmW5)ILK^1RzQ&Mh($rqoHkRr$=EKG}mKY!{J37R*X zImhsjqKOu>%<9)uC}zLEv{a&q)hN6sQ>VBLb;#>Y3fAmpU=#3L*3X|mdwR!UtL|ic zKrCrAgAt?Ltr8vfDQMcd_3L}l#6m$=4|nik9Rd5(WM^k@7SeHX5rlBWD7nR=C3O#yn0K*H z&xwlmq6tz0smm3}Wm~0k!Rai^9-tlR;8%XvGIgtZw zvdt|W23EQ1?*h#v))jSU=Nvm8P#aRmkrccV^h%(UPng~l&T~f~-7dbxD21A@&b z^iE>e9bsojDfWfr+Xqpoy~vRpnt*8KD&}h7sEjuCH!Ygs;o&ovlk@U;AtK!@w4XS5 z;J_Mm%SsfNi~9NuGa`=D3`9q?egu^M7(&aLC13&88r!ObkFY=(tl6akn4(Bgfp-rY z00DZA1J3Od`j!wlPt;a$mV3L-Vi(*&(xn%qKwMh-4bb2{AU*FVqwcHAw-FDniqs82 ze96lw6SWJm#Dfe$2+PFPpXD^Axs+8;jb?*Qd*Di#lPAe&q`_T${17d6lkfMej`@?~*&J198Uk?x{rV%h*#iv#m|3ns-zSFEi`6ot<~!YYfx0}>Jv z*D-O2IdNFv`U!_gdI-}Zs9}Am(;K&Jd4sAa+7p4Jgj`aUA^qP{c%B3%y4%yEj{N$H zoe$kFN$fhhVu*B7$==CHNw={-^&n`$%MeB`Y&)_x%^8||0jOS~*@_0`*-dn7kM-Y# zL3#*slyPA}K`)RBCCn0_+x5G5?+y(OeT+g&$!kiE!(DeUY-G!5e%GM0B@8((OdddT zZwk2OprGJ>V%1`qKQ(JRI)f*wO`KL{VPO%+9`^O!3LXPXlJ7D4B!nd*s^bq>-wS6O zYH9E>6cZgAR|a@RJ2G`kDLQc-;uKLsk}RE?hDO=@_ggSc6(~ec5fLj;<{5aPrBDJ$ z>oq4KEBkZ7JEXm^G|e*}AbvB1$}DJlp~6Z`Eg-q~7` z1;EH_h=WK+2~q)H!F^-Fp_ME|qTWLl=1F`yka&GwYR@XpUY+S`Y}^Gayc{P&ar~Dg@$?qSOF6A8l=WuVC%rHyOw2WY@@j33<>Ll3)xt;4w~4V3DoIaEMF`VsyghTLv<(tloiLRw7IJ zX?S=Ot_Oc+GYHLVw4j)@rPWmycf>jM_4Qv?Rc*ommt!Y3*G-reLe z|1A$q2uU1<7dFEOeIB?`NNN;0WF2n!(9*I8<>@sf;kyXZmA!ehuC=xGs=a;X-QCQ` zEV~6`EU#R7B5joFf@sAAn(ThH6K`%v%C zbYa$UM}ZLznQ3YFARS1|{P=+sho{I}xi{tI>k-RKhLHC(1NzYB(zrDju~Dp|jc_aN z(7cl0^<$mt2eU$!c#zDMUR*4M55Kr%Xvj2Qgu^qhK=TgdMvJ(E*xMcUQI5iTCCkLQ z3lG8+x#Z5q#wHEBG*_mjhs--JH#3mQ?Z1}b)yjT30&RzSd99~7qDKFN{0O`B4Cg%@ z71Mb2?&C)qwEuF1ye1c>^m4(!)rQh_iUovMe^@uCscy%>kSj9;vy%kU0;{C-5$Ssr z?2^Twu`Zy8_Yba} zxpc|u@XnnL%#cM!1C4gEE9{QezDPtf^E*okcfG<+Iwap`?c4d=y|B)R4t3Rm(3 zY*9!_AydD`Gn6kdAgKtJlvRIJZAAS6K;u2urzZE{BsL0HR8&08%_Z*yEaGyljTYf3 z!r=oZA_kIBiO_gCGCxY*-(WYFIS#NR+&duk1IOmh6rxKVL)jQ!fcUZ_53oD+X(=Rc z$q9KYb?sAg#JMaoEWJIQ_*584|4onIupY`sBJ?2xgDiNbS6jf;-upV)E=ZuTM(SGe zPi?;r>T683P=*8G%FTALMcaGczn50}F7H(Pa8OV+Bz689KHtI%P_48ARo!4wyw)o{ z{RqHgZoM7?Y2K`2W`|y>5qlWt*EVHh^WKA#lFCyHKT)Y5pMFY*7KJdVJ31F6HMKd@ zeRU-^zkey_EcYlHS zKrS-YuHg8_q6^`RAFtoxdEMQuvta*^fqVSvKeJ}AH}LFT)bB5G#|d~g{f%h60Anw) z8AN_eu0=1GVyrq7_Tht;pu;2y#Kcg@xyh`dGXc-NG)}mUYY1t-Y;3c3aM5#bF1q+M;eRGV-XE1i;!&O}~puV|Aqos=%nS$?SPyD|N{o6~jv^usY84j0w2MIf>!MI?<}{$aj&+Pv^ei zBI)@Jzc!lLpH2#J; zqP^q2s^u7NC6F_s2aoX(0QGHY17R6S85vPLQiA+J1=FuMwOjL8<7I~kOq4y>)V;ARD>}BHQ+=)Jo0ri}8eg$0<+NU`_1vFjsS8eu6GO2fK>%|W$OG#18!ufV73~1-XIxNkxXXoS?q<)|{{BAx-;M?gJ?iw25 zlNwHbsY@>R{fbYtjYH9!oSiKPwDETF2~g;4lh|kdQ(*YH6u;J<);&Ev zFCth@$!8w=!P^+p6(IOOfY@I6xC!I_51@h`X=!Z#{PRyg(=C-0h4rY6uYqKC;=?p@ zw4QP`?&%k1@?z&c>dzYV2IS}POyD!XE<({8_{OTZYtt()mJ6|uQ5`oNV&NZoPx|R~ z>QU7X=jvh?b_^Bp43BtE@2UZXyn*h#aU4tZ?wr(77F{eww0@nN^1&A2k4Q<*DKjSo zu_dkau%<21Fn@O=SB_Acj|y~KAs;9_&dt3WBGPNXo;^&rK#OK5aB1F)>wZN+xnts}pKJgHpEQ@!ISkCGT!z3)CU-k!IC{I&!De zn^n=t!2v$`dJ+!^8-kA0>*nU>00Ts!ch_5@8*50kwonW^KE-GC5PE}#w^*=^vcB!2 zR4wW7Jd1XU2G#J&$jSjy5-^vwh&NDJSlifm-n&NzPYU7%X)`MH%vcHJ`_3U2zwE1# ze}?GJon!~K-|$`C$;kIjA2J4k30_qT$wiF{{6?pS9vO0TU8t~#<+t)0ZxMGhny3q^TlXEM^O5T z69#(nnpP#^`?&P)BwGzY1Xx2tkR2G%UgMn_3ObrcjvP5>VH;JLZ~)7ML#IeC#S$_y zK0nGUzqq(~@&(ds00O%@M+6V8`GmYcY<_HkN+^^vFa%X&7+3_HCX@w8;ha|e;y6gE z!IYvKsc#}vKWF=&8Wa0jkAONmce?JHl=3n=wQ%efb9vwT0eymcK!Ot4ZVV|=z^svy$WU7P273hlRp zo05{?B0=I)juK-pNd)?R2l8a~b^bQ!D}6&-{h)dk7e7B0 z@Dr;q#3EW$4k^}j|1;{5LqI#MBF+gz1vo(dp(Hps7@lNAJ>QsA~|K&(1uW{ri<@ z$w=VrlIMYFZ-pb1&=((=FSR)TkA*Jte+G?JnCbQ|j9J5Zb^!ruV7>FurFsVknF1fm zQ(_fhd*01wWMr(GQ8XyHG^~HJ%9BBqAw-B2M<}&|DpE$ys<9Rz98fk2O)e;KKf#H- zmJpQ$G)BOytOUCzR-cH@1ce+Hab4s=a^{ke(QV*CJ+vcMU$!T(U>~D7o*_Pbht>C_ zRsY86>1j#U^vi*dwv$XkfluMN(BX2}dwcJS{CNx;WQo^c>_KyIBX`$)!*+VBR39|h z+k2p>#BEt1ATaP6koK8*_bp11IbigAb|L>JMaOacbyKFIf`aF|O9l#xir3%@$7tgy1B7y^gsk=6i_X{k?f25J z&i^AL9G&aWI(R! zO&38Pgc4zvPA;O~so`K~BPWJrcli>Oa$;``pO86>=$t@cGcj zxcoD!f(CVGUEOw^$=Y0b?)-T@fP89y(dm^n@4gDf`(b0dFAg)KtQ;Qu28HNu@F}{J zcIl0MkQdL2$3l+vLOSB5BXC%7q3FrLu&@+R z9G(m3&y%8`?dgQ%t%gGwWt^~DW4%?uQ=uCN4;x*+e6Yw3N8VzjiX@riiG$deY%2&q ziB4E6Q6VL9LRR^5TRx0tZ{b3G#)pHmbG0uo1H(F~Fd1cfn1ntcND>e9YC;l|?4!iz zy}f_`-g6GCEel6N3YMYjPt_dn`2+yJCqK`mX#;VJ-sz}J7*eIiwY3q)WfQ3_u8)nG zONaBMNOQ1kFDeZ&A|#r?fB=YScbl7=&n$_!uk6Q2C^@QI*@}0IkerL2y`7p~`wjDp zPoWYO7kp?3ofE#7nz1VIfv(GxS7RSFCFMmd^fO&hP#ngwqf<+kIFIr2?$KdJS(Hf! zL%NQ1Qhf=mOyYwiCQlk;1H>|nA=mY?x;ky)^xlIfPwvCT)*~0W`C~L(0i^N0KS$!k zhqMSl`SZd;vhlZX#eI;PxK#cD#X}FA=}aMx#t?L*bK>;k{0-!x&t6(Zcw8D$`oTik zZlRc}p+LS&#cK$Yd`8&2O!oBW<2zH1f(s%&^ybYui`)N;w)c+5`t8GquXbsdQHrL> zR#rk%WR#UXQ;}VSB&(r9Qf3h$dnT)lREj7gGo(UxqRa@tNhvb*w_rH8*e> zN+5h;3(Ceec|p`tpv&+Q?2ZqJLs9HFu&3KUgrcRM^xBY-TQ6rtS67$xCBQU2^~p?1 z4@57clW;2!&q`D$hsMTa(Xn#J-+%l06=iIWu+-ak)^X^mJ@)`7|GiohU=A09rCkO*E@8c0U7@ZmpgawUdH;8 z7=|2G4HaNL8v8Pi+x0q?opQOQv5KwRN>h_@@v6-?!4W=*C=ewv#?e-A5_|UV-MWOGt_chq4lT2v0$}OZ1l;U-ihayk29XD2W+Jz2g8X zV;uFv>q#U*eFZU?OwInGerb-P30z%2IM1|11ch|a24TwOPOs@01c{x~Po`>bXy0T>>T|a?{&vWd;`SXXczo2%c zu=i+oPfyPYc!HkRd=XYjm!*`OzP=jT0u8_d0bNMz*-6rC05LX38vH32B_QpLlZz;k zsK9QqvNP5R>qc@YgMBc6!2)ua5U$GF7(qHQMgQ44q6qkV0v~%A7rK^}mDeg+EtU>o z;&A&lgI)5P3l@1`hoM|OkAf$DgE-(RzzvVjRI%P-7NP?(G@pVhrZMQ;3RQbgm8`&b z6|Ua(L2|VU_T1_BFSf3#hki%|-wm{&!2t3me0JlA8&4sgCrQ1(lgwDus^^t#@DpaVq6itt9BI^aXCK>^$)6Ab|?|%&=t(3O1;>JT*Ou2dc zHt)zpsGFpDzu4T)z<*SKX8a90!65JfG@9^WL>sx&_s@lTZNFZBaT#6-@|0?iWZCH* zs7PZ$)OPLWfnkLV_#Uq)Qnm)zR}G$>u^td3*^p^Xp|K~C2>mc9Kng3yFqRD55u%#j zV3OU;*~H9DmyY;~^40Z9&yyFbK0pm82*)}%I1 zKh|FxznZkoss`0RNkU#E%_c7+mMSXwmkR)^cLO>3NuUSO1EF%Oz}4AC>?#3Ju2e6f8i*>j)|9A;0cs8iAvJrRUpZ_k z4~O>#YhR!A_z!vwPa>mw<9+--`dtXnPsc^U4V?s|>0{;@znV#oSzXXywY4KLMt<<95x^Z1s2=*S|-xVgcK*OHIRn zB?ZQvG#7Fja4`eykEq)pQNaJ6z;}o>0&EGV=!wb*3cciHA>xgK4h)^&8K4xX+!-U? z7Cqm!V%_@ncLM?z09oGv?!hGN|5_Ux8+`r}lt6BQIK2a|0O&nH{q37KZ>~mq0AsWT z@=6pBKuf1kK9c@biba!A^kljrmJzau90?@6NbE^&hiBMxMN5h0y0yIK(gllGc+^E2LlrAnV z?s0DJ5j(p*&;m)iJ8X7HC$t;LD9Zk&=&NoU9Q4D1-^s=ng~0LLxpPu*j9<~eA~;Vs z0<27*<}DWWS{jI4m!tSn0?=#?1A`|hIVkDq{E$!u47FL@X$^Ulj^8)T%uJm{Qo3W` zKAi-YRuCy&Kv>_ve?sbRM50Uvg3*!w#?=rgp*|(>LwoxBAEC^SRBIEs==Di%*0^8n zQ3C%>V1tsV6MVTg*MLQJcbY- zczIXh(UZD(jY67#2OaoT0bWsCyg=pHAu757KO_49{aG5!OpJ`XEJQ$0-TCU#Y83=- z2zz#B9l5n3>W$gow25T{#Y9;xv`No3F z*=Ms*sNYdF2I-T#pc2p%3P|*0?l?=((eOo)z<3kaJU4N8r4vXQvZnw1xf2@7nd=S^ z1zzbYj_&dn(Jcv5PEMlFr+(~@0^8CZC(AO>%zr=6LfyI=G zsi_?RKu||Mf}1k7wq8lR?;C>oBc|F8?Y0eHz%O{3muIoVo^u{-4E8q#l!%p-r|z?o zXe$L#bQh@&U;|!-;|HySF#kz(1PigYq!C*gIeNY3M2ra{^kS5ERnW4CFia8Xc zmV-_|AY0^KC_@0s2|JBl3d%1eoB;G17D|?Ahc6sYK%y%@(sj=Ag|Greq z+MoQQZ2(gu>?i6x!U4mq(FgewKa}~tqNVfb!aqx)g|LW_!AOr5Ye!etbx=bdfo9FN zVPlX(PEL-e4Prb($x+zH{2%ue?O$3>_SZvxfF-I=ZUKT}e6(#lr#@mE+n?<+V0o`a zSbd1b*uq05JUev3EJE~k10XCGfLmnQEy-0tYl!KGXtEzN%ri;ya+$Db zZf`k|Hoz};48=1!B_(_t_q-Y6!`3(cA-yrb_=WHO?`z9i8YJ}ZL!o`;dU%ew^MC!x z$XaTN@&EpHKuXu<&hr2D2mjwcV0Zigg=!^wiXErMtUo<>-Gs#98muxY)Z+kOg>j?a{b}i)vm@~lMDHLS3 zpGe(l7Kj!C*~NgS_e|N_+k?M1EYEhM>)W@l*uZ8G8pt{HyT`=Tv>h{ho)?5zKtSVYLGTzd!ZVM`rq^FY3$!p0EhEP z_KJ>Z8T0Evt^U4ZG^qTu><+qX+myqCe&hbK&k zeXH;V+@r@1{hCPDi}8jnZ7w4y3;Tf?m^7xNbr!eT~AF-4UXPn{R|vkGzj^i zfzV<^piQ~!E1mY#?U_P{JI{k}yq4AzsfO$b)Q4epz$?v*Od-mjx)+Tz)?beta;{UUO z)FVKUnOg3D*h}!3-H(l%Hk|?#N1*B)+aGIHFQbXd7_=kGgw@u6EKIcWYFg#?rkwT0 zjT>L}10S*!ST|WGS6PVGP_K0;e(Y@e`0+(aiEN88bt$PIzSi6`EoTAseWF(@8yZFo zH3M(*xmz7Ci%*8=jKI2oJ_BDwKl$q>|6LvGSN|NXyK2ab`B7MLL*t33E8>7?SICHR z*6c$JaP1V)R{9v>?@!>F1xPXu;b$kTt$o2ci3VOwYFEfj>m?geKNNsW@6)GG3BB&| zlPA(3@P7c`li(p>7OIN6k-#?P?B{~Dn3eS0z@CTj0kcnWd6Pu0`%{kfCdyW%JE-6E zd?`ABI@5fF(1hKGig^i^=k9|CDPx4RoB?txpd@B;R1p{9sjdVUVI9G4kRM!y7mh8x z8=<`Dp)r`e5OSaci3{oNQUo)Et_~eQ&XJWXR?y!*4-@ghmXIRH9}ut@=s%&9i|*SO zg~rRr85x%!J=%d*?A72uBXqPBAG`8f0J0Ot?{VC(bs%3|3QF!dTib)UloKH4Ay#?O z(y|FFx~IDe7z{#1!jx!pLqTC4!Drx5y*ZODbV23-I?(px$0`8w5QANb990$vpPH)R zNYRyccXdT0ppWiHE4yH9ccE>^V$?^j3BZ2IAhf_?yk?CLj}{=jwlQDi(OKz;&tE+U zf=+pX5S*l}ADfz@@HBer64xWhzfQ>5%(dVh4ndLfB|?5A7T1tNfXk|i{u*Gy%!Elv zSW&0XoZ)gg3)@L=;D?&je2QU#(`5u!k!Wm7&`M_o;rhc<+f#(YPPiWk@&XM-%*la- zhZDd@i;9W8LN0)!zBFoTe*13g)7$Z);QjnC|FcWwfD4t=#DG3%%dHavh(O8 z0qD61(OmQZBGh7#Y|del0bKoJWcIH?Hwk1#Rc59bnjN0tF_nGi677Osz*Q`96tpsc zn6u$Fg~r?z-oYjbz%;_2=w(SDkR+T$plBK3Ape1G!UnX6E0li9J-dZ0Gm?kk{;R_`d$p+pE)a4}~NGUrc~*EK}C-V(ME4VoQRmP5><<`--^1 z7a)IKMrr5fBmstzWE6v{^%YqaxL_|(sqdT!x;XxW1sr5A0;uiSaVU!q&^UN6vItO- zz+VO+*A6x!A#k3){Ro9vbQd9iSPK$9#e*b&Xpivl@llNGRsxEMKvhOQ9SQ}WUm(EH#u zBJoC?rPRj=(M(Y1hTrHaNo)FO>jCYDP4}>fkVX@POU`?7x;Q}z#Wnlk=_<}wrRncAi{A&n&H8at% zIyNJ@9eZg5WKpqu)%)C$P(tl^J*+ya2I22#03N)AiA4VoeNM%Led~d&Uq_4A(OF#U zS0w$?mtNmo`^q&fKA!#44PsAlY!7#TsI6TPIdMNQICwE1U%K?e3;kE~Msn6H0&!xiqvof>`;-0<6s1+4^dNcq06{~7x*4~d1J=ZY`?f1nK@sG6 zJh?S!8h|T11hX7#>*?j=Qw%B?Ja5#md&p-_qEQW{{Wp+!*wK6j1|NqAV6_)#Uh~I~ zOULhXj$0WkbcmTx?)UxID#>l+}U&UH`23z{qXa}e)UzJ_JOD)6VJ)LONKM44Xpy`Rg}{d&vWX@~M!IJn8Pu~)APeV=U^pmp zo&!8Ucw#`a7}(mTAzV!QJ3n>&o}Basl(u38KX5!8l*P&qC1pSk2QlDU`twNzx$6~G zRW~r`;8lmhudy-4B)ZVBut$h{r2Vy!c-f+I))uOusbGb=dXMugOjL9S=o_lL1hT-5 z6SePI11R|>cKmh@j-}|(yaJ?76eS;?$|DXp(4~EAk@-RxNUK zjXH~NAxJCU#PQmWE-i3<(I@l@uABfg2pyu)gB;zlMbc#h(P?AO--EQDRGl~k>VTO+ zv*{&#FPg&rfXsCuX+-c*RLzce0#lZWjYAO)sCz(I_H;aacp-vFu3A29ceo3NW&*_n zPUpx%1jOeuX5=~=WcD4Gam^Lq2$^DqsaVUzw1k2ZqAUrUPMumnAxyDz=`k@esGKPV zZh)ea6v3zvVsC*0C}E8)T)g-sBBki=<1kO}pN#(k&uJ6NK-Hi~f-Pi=M??}sR4Spt zwHWmjj**J;@>fVQ*Md~llYyEz31ZNyfdrqlBa&VSPEI;_pI1mE@ps!4&V7RSCDQI{ z?|%W8I~KU14_s&92rS59P*FLEXG_cg^!i9$KyVCOD_G~G8~h8ZHo@{qhG=;l(s>9e z%mGow|Jm>iDYV9o!zM}x9S(2Ww28DZ0N;$BMwPu3YfQQzw$0yko9>CT6<65%OUht~T?EV^s1{n=2Q_NJlbA<=k`&by zPQhqhfs=cMz5!B(nndArHE^yQNP`k)@r8_+1B!DWG3WEWS_ArKWZ**t(0GQ%Koz;T zX(+Xm%o~sl=PjZkNfsT&o3_r*Mab{Jf%1h%z^S3feH4>J6QbkMWk9fUK!?h8=^#jw zP7v8!8!p3PE@L1*YbhLN>^nUswy`U0u}H-;h-FPsIry==r-wA36ocRmfS>YNt79Pr zjfB_?D)t8i&1)9oVoL$Kv~_p0TS2)l;piJZ2WS&$JY7v8y+Q;APf&Y|XAGi58%knG z5{=RF{I;y@poIk|C|cKm11PxRRX)&t3LGTxjW6R~hZHol=O#3S54xnepjn$;Ca1#YX~YX~Xp+!TgHi z=MhLypDO?os2bby3W4JxW#!dGR)=FPJq6ABK4f1ZregRp092k^`!NNgeu4WM5FFdW zJw{mrf+lgXzu)EYs#-kOQ>YMZ*lW51q5ixA<;{bTo>Ne4RNU`ABaX6>XHHnyCZr6W zcAc+hS7^j5u@HO=$;MSs9r(Wx-Z#p7r1UdzJ~_1Qd%PAccDr}h$Hv4Y6cqeMq(ZtSqBv9G zn9z2y5~cs35=Fgiiy)N`>nWt2GhhQ}8L$Y1bW9p+Mn^{({F#JUE}`NAr2n>b01Gtv zuMy!`YJRInyfp-2G745OGV!dTUrWFE8~hf`(Xwic#g-=q`!adh&<_JLXD=n z^4+^)5YwX7-q#?}Jlu`#n|<_T!cG`X;L$2*Na)wt9P1h``18L4F-|Jv*kqgcPhpjb&a)najlrf`2VJeYx@808q z4;sJ=B9k6^p8`@kfm0{FfA?;A`;~OZ>prq8J>XD~4Fn|l(5o5S-V+7JPcvw8MA{Tl z9h_pPLr?NB&XD5y;_Edys6Cg9Fq8*HcYyd|UN=e>~%aPU# z>etYZy%;VyipQbOyzA(_t$+5<aB~-C4`%rx zIx#Ezb;ZPOIp{)P;kl*r5n^z%zsk?ci$&=NbUv<_ZYl%LYiF zA(q?>JV+nTvz$q%Igah|Lg`yIE-5Mt8=C8ApnAy2rHzsliM9WxT4B}f(FXULZ zu=$l-r6q+#oi(RO3Cd|2J>S`<{C65;sMJ?|0d`|Qh+U^)V+6YlXnGzR6kg?^G}Zx_ zj-eS*Ai>$9fG1n@SbV6j50ZZ!WNKkS2XnY^;li!l+($c4pD5$Z0^`-GvlnFk9_P2U zNN==tbe0WZAlV1E-YVtrOHy{b#}T=av6bREF9_rX)eU`=ERgOWH^$g6&wa0H%9t;=F`DV!R$T%;tYI)!MTZVIr1dgrO+?a-O1 z)9el?`=~zAtqjbGT!k(#g5aAQT1cta&lzTQ`_K zk&mNK0>_kj=LLnyo0EJxPY!pUIjD*h&xbRdQR|@eB>1ZLWF8NSg7ZIoaC#hjLgQUC4Z_>1x0 zqZ8d|YU*BbX4W5+8bD~Gc$37z3|IZ&VtN=n7emf=M zKBM3Eq#eUtU&9ceP8xPZX%(S|jAS||43f7XufSiP`@#tEi&qfPwu9$N2mzXEr_hq1 z{)6k{Y+OvtR~Sm^=;Ut&so;H-2OXb&=>C0RAPRMZg4MlKi5%b)u4QKSCIn7rXyl?f zS1s@bU*gkcl}Q{G{V`sHg8u>XIq=gsz^Jt$RAHLh0P`PBIwtCv`NH21135ccs*Y*O zS2$cH2yE0C>XMGcO6{pp?XujO?&G<8Vor;fryWu~i4oH`Am+XNA_{2|alfUh{Y;pYWUZ-K21XR5`2da*I@K4K&vx(M0r(*(-&WF?#HTDv? z(=ryW!gNu1cZMI0BMv+^*%D<{20B(UUIwkNRjjMO*)=5XTx0_UAk!9fQGCD$tvi-< zJX`HFE&(dASKz<6zH0&HBIq8xDA2u^AQ#nn9|?aJ)iV=Ru*BQ{L~^CX)+*AI3$C_j zka{wLNkTeB;f64|Nd1g-8}_=$s4}MgwS2gERr$Y#4c9Ex8MrNqE)L74{;ZikcJ!z> z%W-+dW5;;xjLJB@(Q~-Y5E(Bkgsk7JP79PPSyeE*xn5^Rf{hLKX`4$I+e@UB2@_2K zPQN1&d0jb*gVK(aXHN?x*{>0%2FW%u&L>-d6#-rd><0lLVRA{O2oKwb)BQ855(C5Z zqcinr1Z^!soFa>Wo-+Cn5Zc9P&Q~(emcXxMAjtk83~ZE8#1IO5UcI^id<3AoJm-JZ z#0>QR$DvdA|69`8!h>#B)hR?D7QTKrZ?4HkpNS9dkxR~A&2wZFbzCMxMZvTUO5 zO@_NL94l6=xHbmRMx8Ybl_HQ0=mto89bCwxpF!6U&L(`)dh)~=0h&x1nFYW!T4>kl zU0&)sJt>5fsvz+pSqj8Hu-hfaiBUiuM!MzY%Y&zEUFCKjAcHo5@Fby$Mwk)4Et)O2 z^FBZq5R^T~5VeprY}-N92UxJJU)G88NREPl z$(b`92(6{_p-3G)?LY8-_SE3#;^>s&S-&Fjt(;p`Y7QQMAzYD1my&hFb-Cn>e;rG>>#!+>g~+8Eg})_cZ7Rk3&}Gvqd`Fbj8eA>1tHB?ps!L;Kx1V zZ-NU}j8m#g9c+aL?@vANu2?8~qj7qMo}m}ih_Rlh{%fzNmbZMl40`hy>q#4^`Tr;w zt`xf(dC1Y!C9IXAcj?WYc58F~_Dq;m*G!m`v>g&)r zvP5ORGQGU>)VxR`qP#Y2r=xS96?)3fnGUBA}lr2tQ=fPR+>j#q86QC@aIO>)>!>Vv>D&NUY?nA)tIE<N1 zauTAh8aT#^%`So{o>I!1yuI7SO!Zt5fai(b5tq^$S{`CLPj2D`K;=XS zEPDWOMxQ2l!cErAJ!J%HoBrwNUI)Y3I@XIdV`>%g1yA9r=UZ0fC}PE_$o3jjb3Z3t zxiY`o0h=uzS$bEkD+Ul302^ws_L?1HizBkU_F-8O&+1 zsm0kg>Yuj3+%xMf@_CQ~k?4Dt6tIOaxjqRXlx{Aj%N5xaO*=vw?3sZPv~WAd0Djsy zoSHET`zG8hq1 zIhoiC-QX|QEkv;`#K7_XuqE8+u|KVO;uyq42FsCAc94SPIB>v-%x3~BJ1ES6W0VHL zv4g&)PhkyO=U)ManAaJs7kKYp0uVrLIGK7ltR%$S72vXvH`YtYL2^Eco%I8vX}q{j zEi`Io@^W(4z}VP#hhON!z~CAnayZ2?NSe)v(Q5bR0vyZRJ%(wHQ4kuC+^ajjX|?!} z2SESuQ6#ALxYJ$??5%@tbu#9$Xso(%h-_c`!NT#r>zi!Q7+LzD#SgorL}e5c0}=sJ zijtO_V-e!dnjM4Qz1M06a>NRv8}p^q$x9safLe(}BfySm=-w6&pUqpG`^nBnPXge% z1SS#M6n!x9^<%pjXE*IhYjX5gQJIR0V{Ma#%W%d*0OtwG4>fU~hbJ{h3R zF?2>b{9uB#E&3{Z9-OaC9R3Kv*P(&092qT-D7Jj+hjgTvzj4(oIrJHH$ ztG9IUG>(iW8a?q7t$ty6iaLP8D5P`Bm-v4mz9&pvHvpNZIamVqaesv3VFr4jYH!EO zV5F+rroTO#mr4KJWrz^3B!e~fHIL|FWJrx=dSP6PP5v>IT6}lzcr1eF1D%ZcN>{)& zBeOGKW|JMK0r`(qA6mVy9}tEaq8&1T)wlFMCPqTR`s;%|5FAk>O#oU34nZxBNXzL~ ztgu(=e*f;>dEUa$5CemKsVpAM%X`P0e-xF<^Vg4ZadM8d`|y#G1?rGU04z)<{b=ba zP2;-_*!>B_6%e=n*?F)ZCb}L)Lv>BfIDnMqsBUE2wB%nnTL@|R?3o8Sm|~7}q5%mW z8Sy8-C)nvBUFgqN1%r;>UxNvb`;p)3YsD5fxtTkSZO~hk%_|cqgk~| z$Kivsp*AL;HvD};WB5GoB?51RR|=)SNM-CQ|&)_p3Bw_xa% zu3sZWWX)Q9&#Jd1Ry%;4S;* z*MZ?!K!%JcDLQ^$a^mX(Vsc3>nhgC6LWF{{Rk~2YH%r*ukP6dUM9^87 z&gzO93z~(s(1XtV?AtoRm_Sabg{LGg*@YZd2(2207$Q$L90nO|g4aq+NRR_wc^t}` zK+R*oaPGaboOh`00-`%9_k}nMCCvyb!d~WE8ZR(c)@TII0VNENY5ibu|rvi49_oLqLl{%L^fu{N({f>I|+}E>3s1Z zzl1w9=+s|{kJ$4cXJ4yXqfR7ezK8PrFp;Wf`k%pW3k(cAZFhvyOpPGGM7q!bymXIi z`KAI9i@?AL8+}%RXmxY*MGk|M7xq;W;|~yot3r#u?&(NQZram!Ix@%G-+mywu_50| zj513GE)id0+u$cLwjq7xJi+9cm^9rSZWVv~(Rz&k*d?;Ch!6~#1{~#Ud__Jd;0T4b ztf8F)=4&RML^eF~J}P9&{@QtSlbi4@4`rG%yoaf}pqA2BMZk(6c5?S zZvo2hZRSZWc;MWZNCvt!SyL!qyZGFH`!w;;t|W3ZAxzUJsDHk3Q(-l8F>eB7+x&2Ti8qH>^bHe_}gQolLZtnx`b(u#$z!srvG>= zeEI+P#jgE-wT3Z|n#gmFv~AYf*V-MREN1cg=9=M9ay!*0U1kgW-yF_&+$B7h>qeHX zB{OHt+HP;QHJIrPah#ku712(9c}Pjdv+1v3vY7%m*J`}ME0Z%}t>mX3!D(ld&0EDX z^YMSkt6F^n7v8A)O5seN{a24IS~wd5VU^A$gq(*8*5 zIGKYewFwBg2qe6lbzrcuEekYMwn|JyCjaS1Vi%7a5B^lTIDT?OgM&T4)PApv-mlJCORQkkamm&Wt@E)FlfPHuci z$ts0@{SFgT=InX}(X7->5Yhg3|E?jENzE>g4Fq&mU8vu2L_y@!3Bv>Ay>)qg-Z)&W zU=9wRJMg*-sLzC_I&im|ZHDbWeii32o%2)Fo3?AUy+Oa`gg!5i1J7P89(hG}QV(|bZ7tZe9 z*Hqv}ew4LJBP6)$ec+xwM=j@~XsPwosgl)K#D{MM26ZOQ{#?CV^yA-O7im3xbWQ5( z5$e1fT!{%)_P$#BTc^CAL|4+1mHsyQ6?4DLI&WUh#LqP6H*|@Qt7+fEM+&YY>*~R{ zeVi&L&&Ya@npI+Zq3449G_w}+4JGq;Jmch@a$=#cU zb2FOvsdxMe=J9Xkm65ssaZP9|PzHO9*pXL*KXkwx%g|42$?sAq%vb&!Zs_;n&AWLn zVT<#$gL%KE*7QV&+W3#IQ8I2Jax|}FRqy2`F*Rz5(XZ~YhWej$)G|{-I((cJm6)ZZYVtd-vvvolePZ|=C}s2k`$f2^YWtR_p7Tnk=;6som8aNLj=I7iZ@@nHXe zxo6q(KhKhpdMMnw?w^TC;nte=bC-Mha&CF8lf)$K-!Ycii2QS>pJ|tVh2F(RcDN3}vq&QtAJH_Ln+|fX#2mHJ@uE}MZ z-lr}j<&%AYz`?9_itpwIl=3W~t;mUN1-;z7zS1orc^5=dsRr}T&P5C5I!g2VG?HUp zNz)b;AMo|QBLiNhBJ;9j(6&;GylkgDfu~UQDucgyucoqfw0B2m7qi3cOpVAFxq*GY z#4>nndHeRx;uYuW(+k?4f5Jd$>T9<4!}rDbsyR<5Qy}QC^BET{ z3A-5k;+3?=MiEM6UflXb=1EIMAKagyCu}Y!8u##8NM-~f7E)1(M5ttmsyul^S7#&Y zF*yohJ_e>uAqy77o_Q#gOC9-~P{wjWZr;3-PH(zX&bVT;`-VA8|%nIaFJy(Su z^n$?J=+Ep}Pn;8fS)N19LuRbcOP%d!*>%x4TDN9IdDi zeiz5?yK%?P*RNfxX7}VG)p$s`Ch_u|%~cE&39CoqW0nAXfRm4}>bo#m*gv~a-$rF^ zyewlG8O43?#Aor{T<qcQR|FD}nLr_VQigHE2*A6?FOuW>oK8$288TSu;J0s2SK zvp-~HK@(55vzJ%eyKUQQK0WIirCO+!st(R(rg4FHjdi((E~6P|{}*I)6Sqr3A4Di z_ie{|&1Cab+HFx1=24IF7DWYrn&JF$P?h}1%&R#&U}oZoR-viyl*Qlt_`M9dk{351 z589A^pm%?D-8C@>gn^W8l(SDt6 zR~|8#=dmEvtvAv9^`)A9)_>fe3oS>v7Z3D~0F0TdR<9Px2y1w05tL)&P+uFb*qR^K zu!_9zgnqtb&6Zh?*f{3VP@$5AA8sx^KP6qf0;2^XaB+7ha?!?bw1kIJtwL;#Suvn6 zK@^5ETg-&$=wg7t+sn#I>>nr$cgcr~{qxs7X1$@7`a=KM|1PTAs$S^${SG6qeSPtD`G3O1>QCH^ zjh*k0?%q-S*MWKn`w`C~wO&rapLmufixq~u=XQx;uE42J{Y-}Z@qc|Y)pj!TNEqlA zeb!)SlkbkOq#2$Q*T0?sS50fW*;36oincefTGkt>)<$+lhy~LmXr_lrrom|B!5_z=+JcjrYTj7sYW|x?Z)bjM)?8NVA?!oF;{~nmMS+N5n0N)# znaFPsF){kAT^AJNO&3S(D|wmrm^s2az7PkFuL}xYCMyE+SH;E0z9)1}v@h@V75Q&7 zH?y5nA+L+seAx7nl45}A`*VwA+rE&QfZ&+Q`9sekc{yJ}^|#x!cduSU+aG}Iv4}V zPqg*hRPtM&Ze}`j^3c#nM4P8)2QIb%I*=2kPbfysE$HsuZ8wUy$v1Q#5fPUjfKvxN--`9}~s@9}MUMPUnG^D0EPueG5xd^=QuoqtJ=<)foi6ptPD`?{B`MmHN6vpXzarh zsB@=Zpx(M<&1Y(ipzD8Ses4ypK8Y)`%*k$Wd)da{;NyEcc=3umYHH%EuQ!yKf>(2^ zL*|HLVqyvWqzB_R4!KbNmxvoX>AdGlDFy@w$DwtE17;kPOwl>Sy6BK)z}>r1AUUnv zz%PYZLP1W>tnMfEqZ5`aMr%bM*KYu4VMlVj4c>79+p z{P>`4FuB#+k4AjY)7R!m)i*cfLkUVa>=@n>^DN8FzArnM{kUb|iEb(;vulD*Oa1_- zDS!$Ee2rq+ALF^)VDzzZ%}SAbIPUj2C0dtS#>EJJIjnr6m|@*9MazgO1THHXX=z7t zJnlEhc5-^WUj7`rt>|V2G*AFutZ^!&dTX=!)T1blFeY5oSbx=uKzKKV zG5nsz+m3~E`ZAk*-ZSW!FOX>ef)X6Mgz}|ta%UYQ15U-7fZ)@ap@ z47>e1YK=n9T@a1Aws5yl{ddI8QY-&6no>WL*(3<*+akkP5-1*_ax(`*nHkfr&G?I? z`IwcKgxQ^`C1I56KD_176E->dyZ-*~e_&Z2e2WXawJbVlgU6B=Mltd6me2{do9OpC zr=gvyIX{}Zx6Tx?l=T& zwQcH%Ec0>kj`mN*k?hI8UMB85mD)67-;o?;S-ETHhHZ5d6W0e|{X-wTX{Wov$f%J1 zoby~zrjkZ3?(9@M8J)ap+1;*6A^31J%~dx9Pv87$bXG=IA-&+_HSqxdzE#&7 zc5;?~tTGJ{w%&8Qam})2vM(60={!Gb@7`6SQ8aYrVj;z>1)B~cFZGcp%y9E$$XK~e zE}3@8y5tZShz4aRGv1nJqRHeKGe*5PO30~!Wnv|)cXf=mt5}YbWMpMODdJ#aq2neu z^RjjShLUh*Qke>JX4?GrB`bEb#r96#^w}#Nr2B< zv2Y9h%J+hm9YbT{>n1*B5)K1@-6TWX zzAmhB|DO5LXb;f{pyvD(GgoRY>fB!|Irw?bN>(J<$zM2o?K<;u$*?^ebc5cUJi0Db z%;x?2jT@i$!z(%s+}32J;Y6;Yo-!r>2izp6U9@~Is15ZkZe#B5OuV;Y$J32W-9ESVPoDCf`svv8 zX3_Fny^r7}?P;kGL1(Bza+U;+nV~iKrn_mio-Gcip;;Y(S_|gN7c`$m;gOqfb(V=^ ze%8gzpV=oa2Zmbw$^9kv8KV*?X2Z0d;{A^i_4oTSyM!_;;Qsu=md)ym4~1E7EPl-2 zF#~5*pDfW5Z+G$cu`rirX1MZOZ`vo%h>K`B4@wxGpJ&GUnU{SF>QuLG-7?k7kpLyP z;fpM1d~EE+f-mR_0By+VcLEp1t+8{JdaJvXwCmXs>)I3oOIitJu~ zmH?7fCf(a3BWC;R>8GfxcLU~o2*YK?DLQcq)@d(qxV4%-MRWI_n&AO!;W!h7xa>B0 zW%st~dc}6m6J$C&Kg9oZW>Y8+o>{%csD;;W@ZS(^qz1Lx6lm=|eUqNm=7GtnY-gqw zLAM5KYkjASi(}_4xV8IHffj5~bsyD3PgL}$D{gW5nzVj>?D;C%>G|yT^h7qZVqw@e z?)MWaI|Q*Y)zn-_%sQkmu@>T25w6ngvS z9h5`J0e1X+bY)>T>u{sHukWZ$!FgTgEr__jvXhXL8rUL1sKz@B*<-x!6ZPpsCRbp_ zV&mg46%XT{^6Pr&ex_ddLH!iFR)W_!pXlM1^4M`4=*N1$c_k2~# z0i?`}SC3igNpdfuyf}M{g=^8GXBOAh=M6C^$6r@a^M4q=f{B44R-QF2_(X1tjxMX2 zIcM>`8R6fJ7D3ln7~eCHfKj_EO*U2SN3dd(WxZ?iVB&{lkkhfXl}-6v18a(SuA+J&jgLpbxg|xT# zeL-j@x}elFKz!-_#pQ(N!_dZAWi=|Am}M77;n@<>>3+zw*oz9Z&9jKt6-w;AKa(&-F(7-_dR zCk3RV{nd3jF)2QAfMRB{N8Dv*aIj6~?BuZEn&mGRE?c(J-RR`di5(Bja}|fXFEPR@ zjw>S4{c)j+6{Cx`S+Tgm$@dRK0z>{BC_uz&LC?TO5D@5} zCMEC#JGBlhx^bwu;9gy~`Bp}$y_vecd}rUh-Vmh{RxvDPW*r?JgP6(b>XJ)E?#_9E z{xwfoDOnb1@TuNESnvp~RAd1C-u!UkZD5Om8G%e83FPE6j{8N+Q1CR#*41cxxrs&N zP{hjC)wBeqy6fou?Ig7SQT z;d%Sa{WH#lS$gpzXLf>IQ2~(ab0x0~1qNt5UL-s%jMI z(&iwIG{5&TD}weylJ0^CaEH{ebHyCLa{$jw)_OF)z@mnR<%ZV&kH-;k88SAPkw@!N zU){IT)R5w~fI$)gz5kd|Vww3$`caN}o-4^@u z#l&o=J&ZcjqazYu&i1JXx6fCpfJCVSdVqnH?8S7kB*+qc_%5t+BRYD!D|jmPX+__k zydzKwPFC^7@ZvVKZnQFIZ&BGq5|+pcKntuc)dX4qI*$Be!n0bXN|JI;H1s`Uyam`7q+;~{OQ^f#k$FIq4ts$LoN^N)FV=|Pa*`(Lo8Tf z^9Z@Ua+W?}^EL5AF2amm?d*Qu=M(J~^Qz*SS0}7Iun!+{>|?I7bKh=~A%T@hEG&=G zjsx7O9J~!bQ@De^e;HhHJ+IYJGp+{Qvi`9F&gN&wO^)2IduounXODObFJhuoIC-Xf zogQZ-nX@I=qqvc^3%m_h>u#L+CG5rXcmi^dA3F1%pYPnpO_tmygNfz6D&?MAk)Hcd}M_aWIcE0y|%WpbLiTX{ISqO zD^6+DrRDC9*g*P++3jn6WRSL2<&HaYa>AL)fx(yE4_1ULxt#55afS6Qj}JO`tkjaQ zc_4T$5*dSs(N96{-rm!d&{|WlcPU*J^k?GHh2v6OK|vc|)|`F*;pca&AQnmeDchRb z!UNFE9O9yaPq*BEZIoRU`3$Z9D9h4LM5=>y1lC_IbA&X}la>MRU$sGtt*)he1eb;dXb1T3biZ%EnbCCN z;q~jpTO=h6ynTjEj-;xA%LGp3BOsi+VGrNDc|*5ql_pZRO0j-!LWPpdAH=u^A|4G+ z8~A4RgKp#d30+4rzsTQzUFWxNJ(wh^4gyg5yLa^{(PP#QCq~K-{23~n0a11o-2j9q zsb*`N0a>3UXhY&R`at(O`)djV!|$wO6;A+r8uZ;B$k@_h<}jG^Q+}s*9 z!TK?S7L1tFP$b>*6u#jcje_H;8*p-I6%ECoRIvW zewzs09LZ+~sFei|VeXwf4?}4O^{0o-e7=f- zjg2#>#bNt_qGh4U2QNNT0O>h2EP3qULAsvL1}uIo!!FEANNoEjl;rWv10^QE7FSrJ zA;L75BDnGFs|Y|&j6QG96bc3ww+%TxF?W$jZ=?wBP(IWe6(uWL_fVT#R!WdPe#Tlt zLWjve2KwTuARdBPobB!HZPEGzT+3R*%mbCUDOu$!I7@;M7s&0$bU5m5J$|f0IJlB1 z9#~9`es4MsX^hOYXI;#oOe>MLf{C^ptvMSpIf{^Q{Vp}3iHA^V3GElQRLEvMBV!!+ zj)vgkUAXSgiXH-#$NgAa({o)BbL8t{AZI3eoEp|Ei?^j<9NkFe{y{RZJt@ItG#Wgo zKIA)f(DGs4Y?YLdP)#VJ5XVuq3U9CpO~Zln}nG^-3R*dZk2?K)_|c{{SuB~WI?|8e3O;1D;g_=c-I^5 z#$Ln6K2Li-X#o&3va<99Ele{=&26#Dv0!Il+qJ9Dn=36L_e`eA>C*&qEw8Lh`#I*} zK{2o^V`GNY5MlZMw6&bvH(mR1CWdsMB+n?#Ol^}VaUk#0uk+6of^AI3zB{m<0RbXkSWB_Uu5zP~&7KdLxct*tZduAbhd&vpRUy^jwylnI5gap%t!^f z`W)sMd3$-OLgb~eB`!Ahw~44=t55G$+dnTC{<#s)^;nyGX0K2dr*ixa)6*Nyj7;=? zGjYEQ`X5;H2QlR~{74H#qpL``Ncf?IM8Uk*^p@U<3O(#O=U-*)*>K^^XGw#Cq5HIh zf$M0!Z^Q{Fm;(~@LPjWE=!8xg0B>}30bI{RgGU|uwq#o`96~|e9Ar20ko#I4F^R$% zPj(apLM}8VgK;|E_Z%$T5fJMv@k7Ib3sCwaC#Vyev?0YzqhK+NzdFoQS#5wq0!#jBhXv0 ztecK>8=$fPUugLU#3o(s|2HAfi*WO}7i?P4=I-z9zm8$xQ=)(2r7++li3V=Z#dvhu zn@R)(W`17=GJKAX&VSd@bM?uZ&#puRhmTOIO);UGJx;-gfwYDDt%dWRUo@+TJmSrU>t4Q z*uW;HExXZofes%?oaH%RjnW{i2tn3K3{TzUFuRiIP(X~R_R$G54V3#nknSa9coz$* z5abhCwTmn(Qu}bYsa;aL408@6gtg7?C)5A@#!^vh`FSSx=~HbeT@)TEg?7({Y5I(@fSFV^*q8UWQ3pZm(@n+PppI^ zQtI20LDrHi@|4OR5ZBSs5<#+Kv@FPwei*pipyS1TlGw~-tg30{gG4mNr#pXqc0L}b z@~U%g{;zVbLa`rZoaith>(Rg#Rkg2sGoanw92|0Z4-H4h96hr{EG+0Nmi}eF5yZrk zkL0<@1ZFAP9J%00QN)9ejz`P7o*=Tcq*(#f^du4ODbo6rUhqr7H#gjEvX}5INi?u% z@#6nO)_cce+4phdcJ_$uJ>-0vplSc#O8_#xbSd< z(!IdK36^`y)iy0D4Ft zi`Rg6k$bcJG7rz+D>S<`g@iOnW0&*Nb0Ct#ZC`>P0hU=nRc0|%83=|QNU%D2k2xpO z{eHjr+T93#uD{leVe|w{lRK*tAyr_R3Y}hqDHX_3!M;%&!M`KwGf3eCk_E+kJ|dEm z#*qCgfjLUY;ON4QAg)K(5wbcsJIK^HA(dEEbhQ3x&7VrcoBM?)K@vZa-voy6u!pTcQ2=F|J%;95s{jcF zko=KVYUJIKN=c%l3aVoxBd?deE>Lvt=EBpWv?I53{{xR>E!vTdGRL?aP9lkv_CNj3LN8S`rx%<4;z)C zXQL3?mc34Q0dD?^2gpUInWL-F)YWf)m89DZ63Kfv-3Chs0L0sZTF=nghk1|Nk+5$5 zhXt6QUwV^j_HHkr)ViA(DJaFpJ#SU)7-u540pu2|D$d|8Q~?{W#tAt_i|-2GzuOik z8ozlZSQhj^Zm%98r<|NqBVSZ1BO`;aaOlsTunEjJfK-Ig-}FF_V7X~s9Xu{0M)iI` zU@?UqdwguHHq_>je-V;#ax;?%(Ru7mc(z2cf0(BtkdL^y{{S?VxQ{vg8tuBCT$VWd zdH*erB1ge3`*+>96nVZ%-HLh?zrUj6Cm-fQ2fv)CFG^T%L+}C1(8Hh1tzJp{YGcPzd41Y*&}2A6PgEjQ)!(pc7;Z$Zw=%0Y*|K(DYANT|&11 zJm-=G9jG&4kr*_<%_;ezNFuFgEvWYhp`d{!!&QGPYsK3{v%uQ)@&^c>2#AZ-SmfW; zc#1&&fob%&3mZz>Mi@zcvcS$Lx~f?YQkD>(RWjPNdvU3d!0a4Wp$;{2p@(^h4~+im zh9C|=Tz%)$Qs15pbeW^`m2p2`y{J0bjdk`HMUgM$a#)yOjS|)v0HQ$t4gYQ7DWf-6EXi;m5?*JPQ*c)p zzH?>!c=ox?mB(}GKe@I~rEW5MXnozn5q{kJV%^U?xqDnKoY~hifv8jM5Fm8*d_bTJK)i$} z>*D@IfB-_40pj!wka9&Kc_C_Lce*(yh5o9Zk*ga}ZESQXe!6p~mHcL82_tJxe)f+W z6MAJKvKM){!wnL!;`*c_upVFE+N;hyqj0U8vUN~g2jRJEu4sFMc`?5m`sf|`lYn;V!r>x!6myFD|TNVn3WrgMym6dk*7Zd5V`TwS@~>9anyP<40j2aaXl<;9f;9@t2!=6XA=n z>1>5ZTXb!k4h_6Lrn+U%gkYLwRkI7E(#L^=zg%I?-IW}?!}b~$fPqesv1YyT-nLqb zBM#@BPq<#8MW3JUe!tcF`ucQXOf1UYR;0W>hV!|GTHx;&Q$xZy^Jy+0X}Km_Tv_PZ zK-PD6w{7@)k9 zo$)I7MQCj@B;l($Xh+4i+bRjN*83d0|CMUQ3*6pFM zn_(O&J-iNtDQ``L$0x0@O2K&2f(Xo$t5~xMHtMuL;#kYYjf=IV_m^faOCv@@nFrIv zT~UocxB7f6lg0xlhQ|2ru^c+Mh6Ux6JDJjTgrOjzqh2K2HQ|nVD!24{W3JR zw>xBHy}D**{B;2+G-^Ve5;mELUR#lmGI?gdCsmawFm$^=77n!)cbKQh?8zwX?(O+M zXi5T|Pf(7qVY*SE=fBE$1W_682yn_dj>mLCV+$9wb3Ke}Kouq#ZQfUemIxSxkK~?l zUIzhg)kSwHHc2UrnR6c(M0F1dIkJbnH(f`aYO?e5d-5`|(Vhc`vb)}vI0oYtgCs<) zI1n{Wsz2@7ScJcn1Zp4+#dJLMe_X|-7&F7DFK0e~9t%*O8ZThh78Ggiz)VH>6{rhH zK@EW7;pqTIqo7^5Ps?>JEfpP|lp;iB%@s0keX)asgCZ!XG2cj#fIeo^cZK&(dFS%> z2VXd;QAm;Eb+6)%zM&sbL4$!t`tNL@qP@JmXJA*(aAND?LgI5h_;52Bz0k|{P^<;d zoKHzf=Xx&sUC%*uwD|-9R=ZPwltRCs@aE6^HWw6+srZ#zI?Lqv3oliZbM@c4713G_yw5vAoRukcNYeNtueDkDBgH9J9Sg{xMchyhHgx>xH zF<=<)=ebGm3X6&45^PrbciJddB;OS;|M?ScR?-clBpPxCxu7zb_ONqteVXVS_0Ryd z8)o%*qlsVvP^s%*m`z-{IzB$0`1UPl?{VJ?;qC>GTT_4Y00m-u6a!>-rwz839oa4| zM2?d(l_o~`CT_|He^^-KjppZD=X%S%uM56-2>N`n4$j2t*W`Qb zeZACaWNPr*F*bUTYEstyNtuzfwCVEEAPHi)x`$c?Si?m$M!~zcEuPpVQpo*xiC?~a z>6)rYp$#J*5O++iO76X@prb?fSyvMMBRehzr1HCoO-!xtvz5p`-Y}3aVGW`WzzyFd zALt>QK|A^L>KUlL!#=&Xm>dfog!doq-PF|Vs1q$!BAPsD|Hz1VZ90heCaTPC9=Jo*5-GvT^jE}E+Zul_^gZGR zhCM2Cr7cq*`GFx0zn0oxM(ibbFuPxhmQH%pnJg`#7jU_4-(zOxz z%hueJ0pU=_<&#xHyP8pWgK*g9PJs|3Vv!BcfJK?1%4#@G>~?gTLUt=CiEhG>isU`$ zV>6lXr>b_3!LX`<&)oZ`jW&uxyFd?o7QBz|NV!g-RT>p{AF4zvmf%{Xz5o@WY0x0w z`=wda)Wk3}G?f4TeKfowg(OPt;w8UH> zAhIE+g8U=gv-aWQ;3%a_85yyYb>wj^=hC2^_;G>>&CzEZ8#DuDRwZAaB@yrVc*_F*T17Fl8Q1OkFknVk*TR|(Q4qPV#qHI=kkgbvs$`T1Rg z`aB3f4nI5;#$Lzt_}HN^EX$Ngyr>f?lol38x<#yQ5u5`;jOpF=y;t&f9)L0{d$O15 zMVCK&94Dymo;1FbYvzH0Qc$Q{R2iM}-6)3@!@~@R(2nU)030FG^3l;aB4T2yyLV+n z_>3xh_~?H@z^Jd6Nd6kZ*8K&fBj%kmNl3aA2_Ip|d3XqexcREvnp|9RvMPK&WX&yP zK3iwPPcP|B2!$Hrk%-8LB08!DW_}!CBhwU}%=ONbiB1D#h2^rfYol_lo7fys%^?LX zKA}_RYb<`$#2j!%@`r!ngBprhW#H1AHB%+Xwt-2*`i69LUHYHRD@si8z^M|v1#OsI znAzXK$Xon=pGt@h*%1|AxW_PWiKUM6eXf}#dU+EkzL~;8vh$LV!~N4D6TIVbpJT5F zWwk5b5S}buoK;TddKJf&tapfA;ICQ?E`@q6clMnh-V{=ueuGCymU0(_J@VhZQ-F!% zN)Wbus98x2{G*a9@8%{1O>9b9+OjAwH!g;~y}iZNG|MY5EJSEe-${dxB~CPb3A%Sft)n2?)2Ehvaj~2bn=U-=jRfn5gFwQB zu5joh^pbpazrpFaz@qmwEsfxDFU7{}MV-*=46{u^0e4&SQ)urkm`XZ_lU-d|U*9)O zeMowiAES_sSeqFKO|+N6I*&NyQ@k1|)%pSn@2(f_Z4?D~*l>bSK>{ME39?4*Ffk?T z5|ywFNA}Z}aZcutamVo>gtW zYFz7Tsr{j@ySqELww4-%YS<8=o5^6+dGjOMis&!*|Uu*)G z*POB0KQ=Ze4sON7Nbu1ul-4VylUT{Z(@RAbwv+22>w~C(kUDzek(-&(r#p6?d3kIQ zd+=yzRyfrmMW8|FrzsY9h=(>(f64dAPVU;)8YHI|I1;W$i+f5&QY5qh}QNU}D0oC26Uc&BQ9wvlkR%AC21jg|rxi>?bS1 zRXzYPtjs;C>s3aHz?)(N!%|3z-LP|lCCCEhnm>Rl6m^^pdH;qR*g)#+?ClYIkB`^5 zWRC82sD8w>>efnBi2!HmHbka_nlJ|3w`Y)9-!Yg2i)T%CsDar)EesjlU;>2rKES@D z3&yQwz+11Zu1>0Rxpj*?`0$gt6)XbC{iSM3Ov6q2so)LAhOrxNy{Xx-c^wNT7H|ef zTjJE;w8N^mK~P^gC2|@uS&TQ@9~ay4)78B@c~?`3;_`=O%0Fd6{t`#Q=K<_XyTM+h zL|0Yi(H;GR48yb8c742aS}Mqgqj69d>f=6aWPF0gAuMZn_R_3!6mQP9#d%kBn;uR zD|cFxb*{lBE_3X{FN;_VElE2iBg00rCFCB?%g@Q|!LLIw?F(V_MJVNIfmc_(`c|{8 zxXVCSl6&EIxyK^z#0NPhV1AZZ8}U*mdm$rA^KQZ?VAD}!lllqCh?z~WfUyd}=&HsG9zkqo9A#DS({#|Q>K0PL zQMs8eE+ig*26`i@qdx#1&osQ&026$f_bq4s$Or=pRVr7Iya_nH1`bs}A_+7|kTNrK zZ+nma@#DvAejz}gIZp3T+(_veoy6DF)U?cxWF_lBoZl$C>gz*e7-@~Ze#Br5kqX>} zODT~$p49xy$S|3S$>+g|q2uz8j-$`QuD!JcVk3_J((u1y8XmY^YiO{nGVC|Kg=wsa zna=iM0vu@uMxLl!e0iBY-*Rrc!mO@Dfr1IJ;0p~#mQ+_zoM9u>=pa|-Di{~xd)7l2 zXCs2a`MA>Qr|9>No=`gGq@KOoK0ac9>p*@!K0YgF+rKqeJuJOKfc|Ns;8y7m&MEf~B>CM>Xpqz<`%wDk&}|`ts!qdA+q8@4ul-&R6oAwJmrD-*3rb&BGLiH9oiM zlJxQZ@pr!O%bWNF1IHieT-8=X$=FW`sB(Ok^+yce6FM-I@9uX@d<&nzywD%8!AxIV z9E|Oaq_a3Jv7Nec;>I1_5p|XvJoUn%cE_tRL4o(><9zdY<&$fE3_{Oh%YyZ$OlHH^AiyLrqPK$P)AxlVj4z|M&Msj+o3$qVnR^MI ziHV7f%ZNbuu{dZO(XNDF8&e{Vc?F&q_rIpMK|MELJu#~0ho;T_l+kh?Hm6e{+OtUS z?PQXzjp&P_zcboN4mrW>lRcLLVL!`7Pl+Pq8ZGbcKEPI#czNM0)(5k1i8dZ=b~6PO z(ecqsTyZ7nS;v6pU)#Wd%OO*{q4SgPmt>ivo`r>2&=Q@6?Z9OS2AjD|r?{XCu;I(A zyJPWprj_$CTX9WHSK!Xf84e2>Ssca?T-LI|LCc`MJ7o!rm3HXTd%o!v_p;Z!s0Q|r zCp(tj2+NDO?d`PspNQ8x*jq>k(|>*S$~6^v+y^R+m}Nt3Uwqk#MNz}Rj}QkF3Z^m; z1%LPo##vOiZ{LRJ6&fAFrMfs&s|c;zTs=iN+Tw0okxKnX^|G`A3hqm-3*02omGm&3 zR#E3wbbxpxN;uZK=?Hw5=u_H=;s-)Eg1$f9-<}MQg@Bkg!^(ps&07-iX z2l!O8J{c5@1Luy=94ZODX{4u~SUvx5Zj!>?KdzuEebbV~f5I2@Y7^sEowd(I6hA8M zN|$yQPq#A%WM}xd@)tbY2Y$s*L|hm+9x^DcsVq%HLBK#oPtqIS!hGyat)gw=%j}cMan1ids2Q|>}UHS=VJXfQ6MYD3Qi=_ z!^tNh60e|5X@udOSqtTLwoKLF5?IFV38{FKh^BqXFD_;<(MM5OM=Pp&UxK+v7Ysbc zhq0|+H`X}61vSL_B5OEPU}({AeQFyf3n0dbW%ga|pD~}xN|J>O{WGbXzc*^&< z{l9X87RD=tEp^qE6ty$)8$*gp6n5c1`8;{|p7IPFFUTfXPq;MjS&S>04!&)J{I?je zsl3y;sj`#!a6hb~hN?Omrz|bM3*)|zPwfq)JV819!05>HjFwcCS0XpJv}DoXBnN0) z1n86bdq!;Ec6R1pYdH^g9IYk_XBMPT7a?2n{MHbIA$RA_!CD}6j*l)bjTY(=#v~z9 zw2ZUG$H&K;-*4TVhR5eo60Bp18)2-;xC|;;^IjV6;(TU}BW(2Gl6P%!_s9*i4CMOT zf$z!M%#&Hth<&U=;O}o;X1D=Jw`7SNsYmUhpm6B?32f6BQ?6aM1GgCGPvBc1Z*D$0 zRSs>GkjaLhBNlakT#<&bT2q|Y&RYL-S^lsmt21f%%^9BGVVd`^5nYACJ zA!$)b6eO|0e^%6SfeK6RkEY61I>_6KpO%(dh5NAb_*rvo=WLy#s>+0l7`QSj?srrN zBWafHeKqCg&=3sGRK}(|VkO=0ehxxz?x9zHWlKKpX;f6iC!yY@NGN8+zrIp7aldl0 zygVyi;?jn@syJ*{czZu$IM?HiG@F`C{H@XVTTzD#@Z8zd-e8VbGb*Npe_(({iiHlx zj`J}dWde3MbJp9p_r3?+<{p~D1-l6=3Q9_q?`jsT_^c7=DDFqiK{{mGrbLlj*Az%Q zE#5u&YL#E~B-l+>WgIjxeRl>_#}$&{mccLx=ACUdEvHVXrp8z&JG(Z>L~~xe0q|7m zt1NyQgs91d>;Y@Ep24y5J=yFobNqS5#N&%-zpV)379k-isbgRe0|=FASd$W154F|6 zj1uBqeKGv0eNa)21N0URepLH%a8py0FG%J=o4O~|5aF%bpEwV$)85A3btXu4w9&L4 zL;_$r*c6l+6*G@ZW-T)MKeXjmc>MwBHJu>Pym7P(YsMMCMAI!urrd;1 z4iqeXA-0SSyMTo-w?=Xa(=~T2(AwTx+@k?|CWsr|W)1no zJ^&+_0<;=q_sLL6a1?AAI%d;h=6wLL!A<0<3YyR}F_GjAE)D1iKZ2+}4Im%Y+qa*N z9zn>L+8ePxfKcaS0!z}^gzXi!pJQVWpc$@Be9Q!J(J4`j8v_x4n-qMyM3r=1kMq-6 zb5;MfYZeD0QL0SXSA-*s7|C?>Tz{^X4*$3i6xnF<^=HL2{QwI(+RV$eY;iw#SHJee zSQ3o;=1h)>iKU{VEG%r8AB%W9HD6M!l|!r9u98QGA5&e4Ch3jV)rBeUhk zww&*ppU>}|!nkAwJk+6tq}``Rc4)wS85{N^5K?{&CK$6Ie7(7tbqJUvYsl4x^`4gj zloSS$V8rn%_>fFN*hb8VR1G=^_-k9)Yyqy~WL~WFKPZ|CluPHKW;9ZVC?x)b#W6G8C`%gkf?10cg7+}gg;z(@}ti+ zm|%d0Y#8tLy-I}PbiN)p^by1$k4axOyS3lEkJvjU2E1|!S~f;bO#i^ZbaiueH6`*p zFqU`-1qduxfg`AX)9wE^Wgh0DtBPbMd z76{KE3wTB%{)-U$RZho+;qiX*^l4O%CqC=Hp(yX?ds(@d{mWfxd1B7=r$z=2Jc5mG zy|B{pA>&|;zn#+0r^mlgX(z|)gS8v;30u{ej^4>ho1H`cTEC`9SjaDOG9AY|WeO|I z5`vmvEs*k%6$WZyD!F(*G)ffLcl`av6|v>%H_h%`_SVOxjF4ZMVCJI6kM&An2Uyt$ zSmDJ&<22zUa+Nt+NtK{9QN;QKp%l0YKEGn4F8Gn~IW(;8OP(`;1*WeUeIqt`_|-=c z{9cn?^J~`L4X{f~GwhFfB&(`XqiMl@3)y>&S%YWlEXZwlRsAqa04#6csski81$lXS zIfuQW9OZ-$47tI8xxC)JNlBcToZJoOC?Cc{iqMuoj<QaS7+O_sp|)%y*`<`AWQAj03zl7k&3F1wp}J zjcE%b^#tj9-2z%OF-MN!?{Z{eNwB;*t84=gGFniaW~RZ%9z30p0(i9Ygt$|1JW%F?#NMP2v~IjjE?=n7UD1pE2Rf@n(Q%( zgM)*c6`7}mh{W|=5U8ZbBchhX(Zq(0zCy#GK|E4-J04EjSn%;`Efk+N89ZYkYN2gp z6c5?$M_w8}1wOWO{Sv1X7*3X-HKE*<&s}tpvQ2$LA&Zk7i0Qsx3Ud_bMbBZR_l!?* zbj+8nG|;c-BRgxn_`nF?lklE-g^&QrqtVf9HI2wCJOp?zUTABC5-dOoZw(^XQw4cw zsRX5?VX0;p&!4d)Z>{Fv=PI}?{dVFMPdF9F#1w%WF&+wCoOeilU0n(|^!-g4} zO$F%j0fqh$f;3!lWIP1pqyY;bZI^8M%a*OSu8?VG0Nn_>^^%A~XR^?C2TWq7%Rlie z!Wy{Sa1&s!lu&seO_ej_9)NUaspHS`tRenxz!5~j@@NXQLpF}i2Vt-Zg12B~$*_x< z#nb}(3i-@6ySkX&p(E0s5UHG(!+(l;)&h;W$h?IS>PAH`FVW_cts5hb)k6C(K#_UM z+Dwboq(BceXfZ+#I+!*9!a2BnHH989sW6uWTjD9m9BuGf`zI#Wyc(c+GYMF&G6X<> zUmpPi=J4o~jsblX0#KmGLuMOZl7Je3I0GYLEI^IQWbj->%%fq?+XYE06pkPkEI=YW z9_&Abp^zJl+h$=j#|a*XjP2@|M=1DRYRpM>`awF{1IEi@XcmCeMlB3Eu*M5@by=HV zxK-HYpl4izkr~4O{)YO+l1x+g>uT!oP@wo57>1AhcSu~`Xo$r7R?)&5sk2aTnm-Co zp)Dlgu>Iq$?WV~{HF!YQpcjZ|e<0oh2x}zQL}lerv*OMWJby_$nXF^N%V@o8Zzr#l zpd8qCS0sL%X3iU*;b9t2^N4O?&}in^&i?)^Obo;W_IQy6adWc_93xBE$0NR?Py#Wn zUF?{FbJ~fJV`{uWV_)`tv)ZE~)>t`ZslZ3e;AFzVGSMrh6;7P1KolY`p0 zyd2{;6r19K2ZCQ;NfR`TC(X@))xup1kjJ0(rb?vXPbGj+Bp~k>S5}muM}#LCQL_c> zJK?DXNmx13($TTtV!#CWA&fTxYVaBIV>{Mh%rZE+L)v4;ZJ+W0YbJcoo399A_PnyP zk{_}brw0rpQuan1K-Q8%b|>H1u6T-zKnJ>fU4G$(-~W-i<&L8mhq`*r$k@`!9)tC+ z5~*@?u)JIg^Z!=GE+LZeNvwF*{-&li3d-< zs!UHd zR4bP^wraI+wq`ce)`|l@GU=zZ@GrpVA=92|el}L%N=<_-bSvnClYZYuET=(T{kC== znIohffP#`i*2sC7?gD0uLPIRVqN0}o%}n4!LxDpW1Ge%yhJzYz6bj>vJ&06aV4%PWv>=PUMtD%Fn(@#+bSztF!!@#XU!3;-PNCJJ`P=T zcKd08#?8}VggDg?jEK-~y7aXxOk(C>MqiLkR5?!)rHlv*+5VOf4~|*zp$*u65&=Kw z`Bf)ch}|=TWk62ou7~?3%L4%~-s#_G>*@VsiWd3>$HXVYS8?Zbf1A^W_2mKm{l4~J zBR$U96oRMFgRU=^0c#S<*SLkxrA2g#REMpTAIyYz}ujGSHfIZ*H!~6@{u~naIXa_QNBQL27*Y~ zr+HeF{X~~QOeDM8Fm&5jSpkd7c^R?|oB+m$63BG$wn;4kGb|iOW|!IN3JwOUdRu6wXe%A#2r@X>gt`2 zF(vZ1Saa0o!~-a$FA%#vkc!d>xzAPP<+V7`Kvn&gv$km1HI;&%l0aLZv)Om!O;nx0 z!r+pEj|^)LwZ1m9)_n#G!N|f#akC&z$k3>@fea4EU;{v=X<}dH8`e-MGWN9AxXI|m z*!v)XH%G_>Sv`M3T1=p@aICik>^oC8d1BQ8SL)fQSm}y&wH0p6BZ27?KhpAMrD*NT~zUAb!dSB*X&5_5C z3V1cM9_Lo;y zIuQs^R+F>Ivrf3QyRe9&B=h#|xW^`Ou(pGy zAC}rQ_-|sTSN?=o6%rtuqdcuBNc8b@bFQfznaoOBX`5k^M(+x*JxY#6;d)9;Eyz-> zJCu%gwUF!{2~sJ;-(Xkut2@Yf+eklB&atx~z<0@9uFM#9h(IU7z#SdtL9^9o<35vJ zP?f|0N5m517t)=Z@Ke>-*8}7w795pxCO?S|fGx-v0Oqo}Gi?B5tOg;nEBC*) z2LC3U`SvaA^G5{*6&zA3Y(+IVV$`(Pi@UJp31jtd$GIH9g=w`FY4!R+bb6=ShCo|~ z#rqN<09fN`?RWc4`Tc`z6>_k#t@g1edenlCrb$9#%}@UrQ`9yH{? zxq-LtW)E93Gc2yDZ7z1D1NUJHe3tM&)zJ`h#1sCD5o*}Eeg<}SxLjQ?zsyJ`spKBi zeeaLc=Lx2uN}w7Oe-?v!3)fAV?!J#$(fD}jRT1XtW#=5X%a^D5KS@T&({nIgZ|k4_ z_%ZY)t=nB@*fc%R5~ColGVJW@@W+I)Hh^D|Xl9(D)ky3lg3+CPVeNqXsc(i+-Yfwp z{&ScjAWi*9y%!Hc_DUAo)CGjBCE(rFVDX_4g*+{B{~G!Nxfn$;X9})Wtf9Tt8Eo;# zz5By?_bLvA9$NA7QwlT|n|)c!Q4;E$cWpH?=!Wptl&&RiWHe=KCvRf^ZbZ}bX86uxUW#UmStbXzV4twZ$j@tN|r)*{3&T)D1YVKcW}x3SvsN}PbZ zz5N^$kF0qkr>V(j{%i^nWV;GTdN*hrr%v}LyMd??|Ni}Zp?#ggA!LX6Ou#$|HoGzT zP}k;+w7J4Sm@G;!t34aOI0J9~Aa1oIS@-?{EiS{SR))#>`5A^^bYkUcr~xea*dhbs z0shErfB1t6yT%I)n|qw_z_c4^XGLTm9xAq^4gJa1dX4F{bRz27fs2`=q=cUG3}?*! zQ$OONfgOBo>?RF=Pv<+`a}Ck{%a#XvJdb;i_b@{Sw~}b^%b+&RDJmj_h6*Tg(Op*Z zP>uNe`=g;jDGA*oKH@nIs!a0P+L3iuIdKlKH-($yQ2U8FN6_lON1b%Kf6PS4fTofz zU6a$I181FTD7?*r8b5v_L{>3JiTuH*>CmcX#?ytbQ4JJ1Q?3%zFa(6%5j-_&J)a}p z|L8Hx$asoA|1yK}3!$JO^wOazDXd{89AC7&g3iFuoH1xY+E+MuSS?FNRyVK|-JU%@ z-pW(5arqepV$S?&s&1OI*SK%AQ4ay%3Z;l^ssd!D3f8-8bnwl);%B>0M}foqIRuM? z+P(};S$Re^KRg=~(t_^GRIwdrPBLZb?w=KlKU*@}wBu>MPMD3*(hb1IudoYaK|Hqu z14e+8{O z2=Ic;k*6Jda~;!r_2N1@(&_wPfBCWBNUcz;sW~CeWCTZ>m0+ypklMSrSa!=AZC0Q6 z%`zh|Uv@g@K#E#lAslPl^*H$5Q zy~98S#KAl*bmExx?h39U%gWkvU3`!-bHK%fd-zUkobn}O15~wq@ zG&rtTSw_^707O$c57T>%Lbe8i+2I03Vz=YfTtKOyS!}r%%M}hOobE2ihKGl1KU0Cv zg1qL)qZQdSLPBI=1=C@Q1CL@X7>LeF!nkG19i-y4`@}YWr&GxHxjcD_EkiAF@`WV< zTRd1wu=^5L)@vpDFuKauykv*%NCY$QBimAHcCYIfz+I%mLR}=!{`^@<;T|W2`uxc8 zi!WOWso8|l#A5w;diKRoQ{18He6|EvWO~>*?05~czM;z|B5Ydw8nR2Ttf|37gSi>Q zZ~O3Wt1=7d2VoZoOR4hxAGRVWets1|ZgoH)`TL?sq2M=gBpd>HLswrKgH$LgqwPbh ztFMZ{*aKE+z>A_jS$}uCuoMJJO1~>*?~Zx&SpuU6Efi=MS?MlkWCK`$<@WRYR?Wvp zw52!nQQcx(;ykI$zv^Jk%B@Vi#+6qkms(AT_LSg(y-4dT>1>i}(iDRgN_7gUh;gOc z-0O5bOJ~Kpaih`8I0W*f=EC2 zfd;_&d_GBxCITS+u<-#LnvRhXZRzYqGVF-I2-<<#QN#rWnK>$G|9y-GIzfRGU7qyA zIKuaPE_`3BwU0>{&{$ikEfxr=Vj0mff$xrh#l(Y-D!Y%~zI`jGrwFkoPoL zm%z&}TlFDyiPNi%K;qbiEAk`PzMCC)#`H>K*u&T!fsT%U@h^56brml>6ngWl^71RT z-D0$fa1-;3iaKF_tkdIN^}joK&uyBYS>NW~J%7^>pdyhPAmNb~7zDSuEk>)E7nnca zb4zbD;l2c=MYOP&#JPl@U6qyEoBCftgiU(Q!6Zr)q)8R`k)s-st;8}@K8oN1k&;`| z9qTk4P4D(~SvfnqyPwGbu#=|r`jJHRtJqkT+uCSz3nY9Oydz>GCB{Ip_D4PG9aFmfVSr?MYOap1AD!gMag;WIO{bg+L_&RymJ8)L{Q=9r+E+ znbP#k|6*F~bibgRM26W9A0MBX+KZ6F`>FZpjkKBXu}8?P-Y!W!*RrrHFf?IS%w~I< zn!tDKHn-og(+Fw0e{4@gZgJwcLL94-iHGnEG1IeZH{~etkJ68N>gqad35{srgj%f{ z$rVt@`qcR*oAUlFwZw!W8!PJ*z|(8%>0uEJ_WtiKS`o%X_d>dEd|&g^k>!0Pl=LD= zO#3EO@hco?W!uAVHMjN(@<}JJ5&FB48ozz1v4xR?Ij#|hvc+kL8vapXjM9mWO%;Aw z)hK1_bx>5=AM|0<5W$je8S7KJ4r(fb@@OoJ&dXXXdDwi??2zs416%$B*iTt7Ius#| z67tds6{4rb0Xl-bqGH645@6s*)zZQ>nc99foBs~q^2f7}>VCO*0Pe)p_}zZ~f|8ii zOwXMhW=JtPJrp$oHI+nQR2XcqrhS?BN%i>G40*nYSd=~?6Q4`j#*!B+z|?^A?4?e%L7>sKXE!y2+38yPKoNX z$_-(2&WFOCERrwQpQwXMy7{6`YbjiTyEh&_Uo0EfyV6gVDkhry56WM za=VtH1wx}cH+(&=NlHpC0?LRi>SY(}nV773Ae&Yp(RA;w|I)bV_I8JCdsQvEO&2F%sFGp&O z#j#6WWV4o@_+RIPYQHQY$>Fk`E^VH1{jI}zhA`azB*g66N5(5nxHiKS*?B`2~#XuD-NrHO#uz$%D zP%V-A?c+t^%+NNq-@VdiD{}PxGY0AMu&v0Wuh;*(jdKb4bUZDviUpu0*O(1f6u{tt zW%4giKO7#`m)h(kk6?l|sQk5LeI6}kBEPk7j*Rxk60cy3XK3)S^sz9%%-FbAT+Z{{ zVj{pn2~(?6V9(e)a5ycz6tUY8kjQYYtj^h=lHUp5y+qH)7dl9jg>UolCq3#fCiD6arpwet;6)|b5P8&+}U)Q0TRvkA3r*v&S-2jaaX%ltgo0i z*k&OpM~VdooG_s1l?h>%eD%Ld$dBA>T02T147RA4ZqtmIR9N5*@64b_JnQZe=u;Uu0dhsU2a>Y^oN;B@5JkIe7Q({^-}KSze8*%0?d- z6@^KQtGCaEx^l}AmItw@xo8sO`~u6fU{*nD!V!`Fi~7;w0xyk==CC(#95>db+sXqyQ=;`MdJ$Q*XRztOvlxB?( zhGon%qUh463h2zZ7_hG63TOcW0F(k0I0v+$u#^QJ5Kt=b`j7$QrC;?IQQ?2jf(VO} z4am?VOi-ATMm9VMeJDy5$Uvg}Oq{7DB8*CS;l)20XS_DZ*@m7aO99AJUr4YbfOi5qT4=F5>!JR+?ig zn4Q6FpAUxzwJC-qp^sr2-@)}nicCk2h>36V8^+2AS+#Bt2?PhQ^-Za|3F`sRju5nP zwcLT$yH|SgWAVdV*AN^f@}h9Xo91t2LMHjJKqO54B)V4p56%Qg5~p7j55D1Crocy0 z-~+FdSxATsI!Pd<$V+oU`jGcGydulgZyRnDZ;nrZe%ZxeXhUW0DKv;fR+gwIsOZiN ziA(*nbw&D+zoVfhPZ9Cpq_}?ljOoejOk8Zc6#`8#l#~KL#^MHMt$ie+w7~ z%%oq{+^PmHLEB}xnWx_`yL}G~Xjtz~8IgZbf*Bi&;o_^+?|i|`|FYwoha^BU=5T2M zzvVll7b5fvpI+JfnFBF15G8PgPT#tX4>GSX>p>5T) zq^$A`}|y8EG$$E^sg7Um$`Q5=<7XUBnZTzyHy7I`5E3|r2&BdWxr9^ z3yK#Y5#@r#rTZ#8O!Ft%?2kVGYp~vylwjkBqivVsN!nM@{wgU+wG*L*gf_RZpvbT! z_5itNaMjTM4rD1tPw08hQ(MsbWGVZk%a>UGvkDoyd+5DvOZS?+6Wda}t$j>aFLIAR5 z&Bv^1vycON>1!uVPICC1)&NBU*XhUs+b1WD7CY{IuS-iw0Yhxq(xgR|uO??@E@Z?Eb ze?F^_&QUKbZ=|Y@0x9&=oq~&{Ni@L>eHNs$XhQ7o2GQTVIb#~ViL_Xf^o9B?K>zF> z=eJzY8j+BkR=-Iie;XMG!y$MmZjE#Ctp-iNET8df1`&*i0|?Vye~Bn@*7N9_9L|v< zFJ22hXP>ah)-A~Tu^eHPU;^+)*kq2dPJ1CNb=V^{&|XX|wfRH|4Bp;8>{+1~8WEO` zi7J>ttOH4&%w*}m(e9--du8QwYS5O61JL-l*$8+ttaz9c5Vm;61PQaXBO@7_5XH;X z3yZs9c+vjWSK_Aou?gn9+6b7Dte2~5SzK~o@CixSS#6YKpHBbNV>`jvj|07Qb>E6dsCybGxZ~c(i+C_z# zCf2YZeoHs(Tf=e6OU_)GJo2w=&f>5ybFh^|bOk0VE+F4_eNksbD?K!~*lEW#PK+?6 z{~4bZ3f5mMJ2d$Bgthh9gCjSHG+@R8WC6JlRn;CSe5M!DrRm<=4YE5G1|Hg=BqSqD zQn>CLP$9XrxNJbUmVY7f_smQy5|W(%&n3xqgt(P*upi(Sc}6^BUj^IErRZ=mLqE8+TOtT7kjTxT_#xgDZvOt{g|#Ls zare%kCIxg}^P%KprX|%6dQ=z5XVGcyXt|hNr8{z}Zfi{g+F-#M!y~IOW;EEUE>Gdf zN!9eSx}4q0c(nX!D;0k{dGM7x0X0+JpDUS@J(VhVmd=XZuzj zvGh&#luQyOi*8}a<9Gl63?i5+JM|AGxWU|0dsr+O?vl>S&;J3;*guSG*^@rA%>l_> z28g2_-oXi781T3PzY1`oe5?&*|Dw+Iwy)Xpz!h}+^ZhcEYO}D3UtC)w_Ccylk(WX$ z4Z}m|JO&t(CvWcy?mVi~qBg5gJg>y0xn(NPBk;aj|C{&w-pA7`OXwzTg;A_ee)4(~ zBt9vNc>2_eYJl03-v$PA7-$PKU5{#RH=mTxO}=RpB(+^XKJnP6^qP&E(k1}VWwsuM z!!RKqs5mIf>%>dxHsHKBYoh&wHo;44s~b@WZd4@BEJ|eRe;a~GQEG|w|Fw0qN617T zN<((*g?=h_KJY$g1ZaOp(@Yc!Avop1qe7QHO`Z3ULfI! zc~g46F4+DpfoyOs)1=w>`e7GyY{~m)l^NSJ2?IVG%xH2c=?{?5oA;WTp99;ipg^0Q z6Q@E0pDF^~u!i50ZSKvL7oDM?os~6o6eJFnUd}XqRFpOnaZ`MpeX|!=lpcZl3zc~! zkF+$_kYDOXCwb`ihcW6L-j*;D%mPAU7-y2VvL+7{&q+624&ldUtify>0`f@@B#=Ft$#f z?TG;h(;rI_9neQKE={|X2#iw-WQh=jyB>!Wq4%pk%LKsU{IYc>B|dVz1Y=&Az5=DJik! z3}G0UU8{5yj4Y<0jY%)tN_mi55Z9OxO`HL0FNQVFrZBGm`=uXoyp@bGD%M93f3pl{|gWKQ&Kx)_2oC50a@PYHc%a(qPMr1N;6x>Oy>Ix>d{|h=C3j#4p?a_0hm|!rM2mb0-?d*tiO)k))foe#z zPmL2H?=9#lck?F6E5F|~W3U!9taf~Hvm04Ty8)KVxcWiM_};2(C7x~NO@&X_%6M## z?oPGgU$|0XQakf!!*k>Th!OUVO5o!MO2mA+r`Yo4H)HE96lp4)hwpkdQ~9hc_sk_! zC?i+|+hBjPDRgDycY!{S_ZTe8NaObS;36!pL>A|;va|gr7juc;>Y|!o)idKSIlcxX>(&2b{)?VpMCfpR zF2)u&=J&!vF2JA1Ryoyc^m598djRR`Fo+(g2<`3dZE{tA(S~8nxDnIt5cq&$I;-o< z&J+Pv46t)lKmQGWI(o6aJ_q20F(lO84KBd`W3G!Jvk(WOI(_R#h%FzWGCya^POe)+ zj2Xb~>iX869Ul6Os4r)}xqDnc#y#*v4T{-El8M*uf5CU`>6#A*{64H-YK8zZ)|Rzs zVJpIc{jlFH1EbTCQnmM(8(N2@PVM}3ViC^ABbGmGpA0AZu*;J!zkkmtywmBN4Qt-> z9A(!clekE+$tR6B!+RrZA9Gm_El;OQOQO7B@Q_k#iFr|j^UiVIz0aWvB_!&a5UA@b zMW&t^N1u6){iApm5W1L(xLto?q(VUe)3EE;X+0%&hnpa_vB>q$#7uQ23= zc`G!*kHUXV00LA#cOXmq_Y>$A;gzGEK;VO(y$6WNL>fZuP>3@R4!!aQI=gx9Uf|%7<&LS@?cxYUfvXa_vP_l+`hN z0(O2rX*c61o2v;7N~+VgE~_+a%wd7XxwJwD?T|zAF&)E04$S<08>E?q@S@$LI!Uu)N?cR+h`C@%@bJ9^G zGpdU<&u^MLJD#<6+1We&{p$B_pww2@_2yKu$m-txqs-cxPr+?I9Q*!CJG6TtXv%?(pHh@G zqz$cj2)||`c6|I15c@gG(9tNk4bv#3T>tA#s;qQ`_d&ui3SP4xdTGQw?7ysl)u@p# z5c?}Q2$GoR;AR^$b_hRRn2JSE-(oK(sW;2c)zQjSCv`dM7x~`y{#uv3oKb(U>q=Ke z`rLCdF~srW)#LPxfs>0fo0(4pPsKd*EH3?zCC^ENuCkJz?rYPNE7@i}QB6XA(0X#0 zsFb3xj3QUdW)>A4 zG%eD&lCAuRT>v-#8^NUfPd1M**(c0Zk4k~p5;X$X{Tt%6BtRo_lU2Eu*b8Xcrbm8# zJ=LS<*V~nnLIDX!9Jq%6du#I9G5F!bgM;+UOv${4J5|-y9$!|fDl1W3POy5W?vp&@ z^52a%F$I&_FE{5cb)P=H4fJ6V`=@Yfyh#{};?+4;pL`y@BdKRD;vYgcEAef;=C_Dr zbFiXdA9L;(+V{hHG2A?S`K3?hD-g`K^5I@jtcm2FWMTi0B_!>oMRdp*MSLG-R&l^NUlRo6w*^#0^Ogh}v zE2lkf-^@i}Vh%OkODjR0=0OvidXsX4n;sn$bB_`Kl?db)B@gsSm)TbI4KVWfVg+NH zaJ#ZPY-qPaxLrYyxd9^W{*@}=ZGbf}If#q5{Z&9FY05iWzg`wH<)8pbQ!NLhi82DhwBf1+9&$j_y{ zgS`fbvgFxSDph`ERT^57*ZXf2o%v?nqDUW$>vNeSn|iLW-N13I%H6yCD-|Xa$!3jl z>#9y~ss+4gL}|ILgZ$xMABZaBHBU~at{aCgA2g*Qhx*ZU?KlT--$uCOZa(mI-kojf zm1RKfpNp%kypPJmADMaTFfwX&nWKXr0B(5a_c_uLS*twY8|N1kV4*poD5POGPXj#E zbU|pMw)*-y)Jx)+Rbw&0X!7m1LKTY8jydU^OVGUxu~LqM z!)hl;ozcK=ZgvkC-!tKpV3?#?;@xBnAGZ8#cx>#|Mw0p40<4FXSHK~2A1~}ZqTREC zqR(RY^}6v+t5(d|Q8_Ysth?}CPFQ_~=HZ{9lRfP!yF#s8Qkl(7+)Q!2nQ*!&?tF)u z-~6W+XFD_!QLV80#e**bILxcqZ?d+S2L1l_3e4H%^Km~A|DpA~=kBfnSX@m~1lygH z>pb$aCB&JD8lS3Vs{F(RCTf^`zNbspaHSHYZ%$Z{5fZ89a2GE;sja$7LqxO#N6d#A zsSRi?$${ThdpMqbCMd|roE{05?4y2}rnT$_k>>obEN`!PG-yBjTs6rz&QzeyF)#*X zDZ?DqtBFjSZT;LpDFKe_^7Q5#tNTkDqW>-$R@E`M;n*1H_H>qw25M@=w7xsiD4P41 zuT;&6YtUoe{q0&;S62(9wJ<{|a6&-2d+2cJwyXf9_&ErqNeobY9HO$St6uw>vw6{h zD>>U|lh=1i&IwX2h`#cnv*JvJEyslF&s=c)@H-)KF4OzHMw$M}Dmw4r9KWmYUH*r@ z@Y&U0I|2I$sIqx}eY77pM}y-0&Snq1W~Kb8+lKY%DOEg*b{BRds(!j$qlltVh|<|1>0{`f?m0|R`su5gQi?jiY87AR3RrW!o^SIR*ExVX4T*gykI&c^engwNrZ_dsus zIQ3a&FtvT%r7Jr{8?-l;JR4)E~@ z-%(OaxA_!#gGGumUsID;cW5$ZqtsyG0SUs2E5KXCSLh}TdBUaw&Ng?-42#$($8VDd z17h(JhTq%?^o)6F^_xPb8>880J+)g=*w(z1mN=iZ1gYP@DK45+D}uoGIVU!J4Ly)h z3$ksx)L~~`5hg8Yd+>i{Gs5XN;6_rj3)ms(fSOg-Xq%YC&yr>p0l8XfY~r;2dNc3r z0&Tp)p%A>3`!-L|o6oJB8Ow``wq2D2C_hJEZp!Y`EI9w(b&sl%SQ?2pKb4q4{up>W zcU_MSx)I*`M#BL%?|U)1G^<9kDfnl9akE7*FDoo|XhlQgntTS}AcFqn`B6W^aXgLe z&bJ$(m_e4Q968-g?b$9OS>_bh{3$OnQc^0f_l?)`#dVTu-rDQS;SqIx`|#f2V^}-p za)T3iK25*v?U8Vr(QoW^zUF6S#6a@84di8?@ic)liKU!&P1(WJ1xggVcP2~}3fU!y*XOS>>|$^p%#U z+`&FHeLEnMO-<&G^=pe>iYqJM6g}8+uam#FSdfPUIDXY5Bq{Vz!e`d;iQ@MeDO(&|;fzEglk4~ysh^!6@1oP?2->~O+a$b3oCVVrNGW9TF@VXLM)BF@UH}Yvqims{ z-(U2=6coItd(E_lwIO|d%l*dmerF*gvU$}+;F z_da~mb-Qukg-jg)twqJ-c-V{s3b@&lu^(n~CS_7GHSQPCF`t~^iti_EbP6iTd_W@c zpYQDr)Op+%9VwBneNDf6*4G>2cmkhujI3p5CYRLr`*)j}rkib`_N*dd%p=q?oUCDx zQs{k0jGC8xBN)h3V>M*o*Ozqwfv7(2OEx1mJXJsme!JBR>*dEJz2^7_t-~v`txPhy z$CwEQh%**|^1@9yu_+eHvTV{D=^Rw<5Bbm=t)hgCjOgmBWil`#yXz7Nf+j2zv!OI!rJyV_vMW)#GO@nHBpLIRUa($-t z6>WibZ|@x*ceuG+xDRHv@4a`r6Y-3#ozXDvYqo?;3-+N?e zNIK~auv!@Y?d`QB1j;TZ&ObhuMvQ_3i}k>Bb6jw759LumUyqF+{;bKka{_wQ#TU$A z72=5IR=aTVsMLlqEyCitQI^t_gY$abv>8TVjyum$P0NAhM>o+{8}hqV`sc4W8ZUT> zX$WRj6lUlPGvO|FrTdBVPUJzF`wCJ2NBO(A{J%9niy3<`LqmaurmAB={SYYBY4Le1 zH-e?F7#JYLIVX#$B&gD>F!K3`=GayR67gA8gQdMP(n&$Xv=x4?{1Vk}ca){;KEP?l zyp@OC?aPV3=ge1G?eP3*V!(33GF*1b;V#(tY8V;Oth^5^%PlEUIs9W? zbp!iW;*%@jEArx#;gcs%l(0E(Q$%kNw?d0T5zW$!68^!jo@B(FMo!qQZ0uszW}uG(L|pG?mt1tVq017_HrOm^o*e$D-8O>FQYh=Zd6r7graqJ;`wwIsCgzWaxD1$+$+J ze!sauc@7fNJZ=msLmw9OL+$kgN-`>g}d)( zD4jY1Jsi46H$&bPyp@%X7B9Z@=8~|}-x_|WMf00jQPBtvc4^oOZ?I&} z@WSUDpGd=fCeiicr2owm>S4Y zQC%|KQQZsDfQD==!N7XM!-txaQHdDlzl)a5(_m_{V5n*dMkD*rB*3vS%xHMY=cQ&f#uS_}y5KMlg z50&l4*g4Htd4Blw8flh)A7hNq(PrAyyLzaNTK=#tE_aoY68Za=Izp85;hV2Lh};3= zAWdDhAN>KHBEdEs;6$(;Ws5N7U17qC*V z?M9TJyc84!owab5TBhV}N3#2XM-yVp%5*$RVm1SOwGz`A4Q2`2l@^SeAI16Ooozln zO4B;V0apQbIPN7jTwE@j|D9dP$OI?>AjCQp!@bjAc+&Ro0?E4y-gafRZ^06Pk&^Jx z#}|}|Q8l1`7+94cYv#NnItee7%ixw8f9E6BSX}#C^T+wjk!bIyxDTHQb$gt-ySGkx zVxApEpY?LI3t#d}RW9_KiV3Sl|IKkH&HAt!Uoj&c+Kz?w+pvy*NtRWh@xw^;>yc>F z?W25KcTbIvVgjPpF@L!871s*+9@g~x_kPccE-5v*s&fsYxi5o-)%uu0gM}tR+Xxya zXaz$y_I_N=UuIghRYfM7IW!Q}9vQzbRh{${rX*Iq2CW?`xFX^)8kppQ4Xy+@$zSXK zdIdloR72B-I@ybdsJh=rBq=yN5 z$R>2@KpRh~@5p}uqk!3C1&;I1qDX%nS>fZ)�gI(gdH3*KR4q&1Q=H9<7CbK9P%D zrm&PK=mqPXgfAuBr)(zbu5LDX1Jb9?a0lyq7)y#J&PrvqCS{R?e*$;$yF z5DDjz6L(w=D8O0m(_hwyM1p7TLjY4y{ovqL@`6PGZTf9f{QPSm#H+!ZW64RF97h&? zfGEXCmi^Za!Z6EJUgo+3B2Tr%e|QaBA~ZOnX6>QqbW&iqT5|BulEhW}of?hXnXEUc zqOpC?!M5i?<82u0WDar2#Ln@89qR8j{fCq}e%C0vBq`UNK69tth%F0z-+>rA-P~+d z_s95_i3e@=%*vA&@-_d*1#nyFIPU4gJnnk>SInV%Jkp?<$nzt7KRiJd^n?j3#-P&Z;H1#%sRo3wyV8Y{_S-LyO6)@K09D##bUPfl zQ*HtR^pkLXc8Q44dbC|c_w;FNG|#QlRu4a zwg$y*d)?O;Yx->x=$0SA`T{*?AzT@bQ})}}=2UBL0?-Gfc(>ER_57J?Jx+|w3VRGq zP4wiHP6wX~4ZXJ|Z=EP%WD>agE6C)6Z0DIzcJEgV3ImMM{kwD&zISj_I1UepnPFdr zsFx`CJ;ju)+gisPdkk+$GJ^=!VYG@oe{*l;Y`epApAB{AA}IvvxzdLkGu|G zBJ3Z`nM9_0Y{~y#jg~WC|C!U%H`kGGGr)3#IGW;iJ81G5)6-MffQAB&3sEC`UgDtm zL}>&KHI1KgDv|+s%KLQuV?_IVu<&%U{2IXZ^`Q&queS&{m2WS8@BWV_67uD@({GUK zdAhl|5!P)1uPWU40y3>M4EweNE`5&wUZCfoL{Dsjzuod=BRUx5v$iMkN*=MuXLDvg zqS!MnWJV{r-qlR-q(qoHFZ#Drw_lATPFXDmICtRuaG>()6l7@JxlUIig=hY4v^GVQ zd7E5Mdwi)KG1bpS4`cy7Wnx`>wyhKraR zIQmqhT4qPOMp}~d?l^|gar`Sx+x0g!Yx;2uNvI>%55XkW>B6EL3bXKK2`i(L0!K=% z&BtB?$4HAS$)cd&{?=r|j0JcoaB$(x2mq*WhC+yjT^pu=njr{WHm4sVD@f|CLBNtk zv#43sljRpZw5|UMVPJ*I=~WWk4+T;iJ%q5D(C>kPFF?$g&3jqfgtgP)#Ib`SyVXxY z^4dJ8Of_`CAmAuq0hDnofqk)bQnWx?(*7usXQP-D3N%Nw`M}OGoZB(-7Dwn`K{by| zRY>NKk$3*J9%R(8sP2o6jQC{}qe_#+9GqGt8QZf&=I$^)SktSNI`fzK_~PhHO48ew zQtI>xn#qOInp?T3>(VD-_y;YJ@9g3^9?vE1LUq$~zO%~$F9W!}U0L}dSNP^i(7btE z+&lE=tm<**OS~xj=~K;-_rsJdB6o+f+SnUR7t|6|A=QgS*ihhv&7^a8-YDXYfk1+Y zYvZT`rka4*GAWdYi{8CE#sb|xVKmlpCl6YSiAsx;Fj~g#9yv`q;&4pbcpT6mBTBb- zy=I++>t(Y6FzV_fUIbFq)gruuff6O4YGelErPrUZvUXUM%n9w zca7NJ?6aK96FT4np;UR`d%WfE3l@wI>s(mc=XPFC{Qa5Q%-j%W${T^Q0MCHc@Air( z;G|cB#nzhJs-z6F09rt}H6Gqi<%Tl{nsc_>x2+x~^DFsDe6YXqdS6`Dsz5lAoM0C} z?C?S_Zb$rU;H1OA92jQ?j0~3hU+cGdMnx6(9dql{pLB*FCn2SMTW$QYQCtU!1QyyC zk@3*X{P{qq3$b}RHP1h?i_fSKQ2sK-9+U`JDIM8tZgoe5k;ZFon6=PJx6r{I?Nof4 zhc`VVTEj<7RD!mXX)*tOyz~>sykt^aJK65(rZ3sTi2PgX6po`25&W5LXp?SN`-gNY z-^%+Aub52^&bx_%Q)WF+aC{iEqGo&sof^DlPqdVXP`BUJ>_@&)J(f|94F7cz`~^^mRuEcc`U;qG)$Yw|DdnZs0g}{aY3kcvh z+(c58I$zUt#zIpF;=D|?$Ab@Qe8g$N#S(slRUTM=0sU4^yg8C>h(?O|eE(f*zy&L* zXz?p6f64xF(c^k+SNn!Y9UbI#!XaDq7kHqHs>yx(QjrXxdDX0_l0HA~F;LdBWOe?$N_^n; z`FYB>zi%kOSvR#8E4q`>N8Fd+EjH<~Qw)D35VnTK?$WgXj|;gfpS6KOW;I-*U%Qy3 zjO}*;WMU9rc7Om@$R6ZjMv_u@KjS5V2NVva2$uGPE9lU(=^73j;G}V*u2chj0o1p)Chq*p{Kok~t15-yAeW9DA z+21UeQt&#bkip^vRD`v)?ACXk{BH2a_8D-Qdn=O7sWnMf{uRp#9O7s`#0u=PmZHk| zdmQf*Qs_MvpL4;V;L)a$=S2Y6ubs${2Ht@{ds#gaS;R_>+q%B{+G0jBbR06Fh!L7v zQ@(ecw(2B~EKa<0%oYBfv*wVs)x&Ld4|R0Z8G;nMYkvoT<1g1XliK%L(>+@VsGjDCyHZBvD6X%`1&=P)agKcLQ2ZD zA&-~bMp3)6pQ15&z5iJ1Pf$rb6DZNMQ;{h~2G%}vhrDOd7U1DMC;oT|&kRQpi`6A^ zV6=saWOV%t1?H3k~Z)wcT|L z62sB$m$hSOhBk>Q+%*>1!<^d8F=uuI3nD$(-DyY4@IO8)~9@WU31HWld zD!loOo~-l!xeXX~qW8XxbjU4lnLeu9`++%Je!Z=~xNOba_k&Ym2m0qf^G+G6G42oY zDzyd?<*vk{S)=||1%KQhNKi~+Q6XP33OHt$ED4BtyxFihDXAA7>vbssrgJ(j>bQCs zlkRAz>>-Fm;(;w|lWQ3D?VQsXc_tXz0XC2uZ%L?>3`}hJS9>9Y_9N9~B|_|w4J&PL zj#raE-nw)E+J^cSncxf&nP5-I32Y?wS+H?=+4KYK0C#6YNai73CE?RK97Z_cZuNT) z{5a5Q{q{BG1WAbsKxzw=99S|WaF2ncxZ0^L%TyVG*Z0u8mT#Dzy3LNXP#iTZE}|XH zkbvZK(mj=ueP-fbH^zffvV{?g&P{Av+vHMhquUq-E~xR+R71_#@W23rk5Pu|hI(ZE z-J#K42l?i|^jge?v&i5iQftPd86Wjwm$_h!P<;G(Ln3IcwF;YPXwHs0)_3VA&r}6~ znlaMgW8>F!JSj;A`6z{F!YGfABqOy!Xo;X30s5y%G$MjQIwS2+CVsUXwe4-TiVESL|<#^6Kdi2P$ zd}5qKEsXus*4+>jacQJX;cGOrS3x}+pX?S4V_nu>QdmBn;;Rxs7UlpE^+nhXmtj3a9bh<#GjVZ-$D4=3JB>)8%k+#r(x% zNVVG;IKbq~NWqb1x<-t-K7vUiaV1kY*Y_{Y#9*P1cF6pCNCi)v%@sWI>nMgsn339l zQ=YjTDJgW_o;ym?1PlF*-n*QjM4RWK4BhS^K?r-3i9C}SwCKLo0FZgD$dMta9-h68 zw4cO1Uwhz(nV&rFCQ1XViYtc(38Fgaq2chbv9;CuSciu3uPc^b!XIluhl(<<*?sY(FL+7eH_-Ct>{K;pxJqLCVAIiTtgRY z(v^hwKGUk?Gj#+9mkz~zvhs3;78>KX^g;)g%VV6KzuP2}d~WS^W|`u-NuRQG;{o3i z$TU@qEJ4W%$_*m{$86U$93|(3+ez+Nv(a!Rs;%~#4~?)v;{Hd@u#BaP*VKL|)A@!R z5vxI=tS-F&8Ewhq&L#E+j-P2AG-GN0okwQjDd zlJH?CSuAN=ohyQyE%1GT)u@$jX({Ew{;wT9y<4v<&DI{)X&wG)BNrI}?M1~^m=mEZ zwigCtSgNQ0yUv<#EoaE#43sHS5#w~^GDWJrQ+{=iYT&*$Fiq0asq}k6kY@(0&8b+f zBq*sRV$71%rFy;pj1}O*L4D)zKm^+mG@-(bDj|?}nGa@u4mCGD8jL*dR~0Y3gE$Xn zMbt3{2vcK#Vv>fI*3YTLWVYI_?y=!whaO3H4Q&FUI3X&AunhSmz|m%P<_r(aOQZ7}xLgNhOq>sG|S%7y&2B>L}YdY!sxO zqrKxL4lbjSu5z-dNx_efho!^E*HE$*n9wtT=itwnU#mzET+JT<_6j2f3!%79>#DYe z-PioV#8!k6T8%U!7?aO9P5BS#0wi5;?Tp*a3%S1i^VBmoxx9>GB0hZDVm%yaq>-Y_ zqdw1)9uaZXGvPiirHkJBEkR zRD=ArTf-E9Gtm}uA+B|XQHP}?>tND9|KL9bgk~t{QUMH$qnzvd&_+{HFSWW>+d0bFv5!^wE3RuY6} z7f2+dey|8r$A#h`AxZ(rXN5L2V10$U!?Ni@*+`b(@MxHK$N)|%9H;%AeA3neRH#;W z^sKO!5ICyv&3DWg9?-ZMF<2*e`O`(OgzBhS-aw^Of`0F zq%(oGj@@tQFP3)Ahn`7gpXJk?5`;o20^PNg=9mNz8HnGky16=F|EKi`bH9sZ^ey7gbK*g9>cyOU&Y(i2y zrO5d_g6%2X@H!VpXozu8)Vc&kOX6_Z-N8F>xGCom5B{e~WdDrB)=Y;-0rccko;$Qy zS3Nr4!(5?vNsF3v>Dnjq(x(%Fc4g?0E*JA+yA&j`6_^hjDAI)aPW=>=CK!3V2)+fIxfz9=}xA$849Y_mK(AK>c zZhHm5dSDlFu7NRTS#A)E@;uvKPw8E7k?i=aijdU3bx}`9K@E z1UH0hA>*jgoBuvV5KdK>Zo6JLM6(~iQfuhf-6+><8gWVKSvRwMOWXeN=qqQPu#2T} zPIoXvtE+h6RJfnbk-X4h)p1xt$r9DkZYgdeHIz^$s*dbWRs>y;bophxUeNjzj2-xF zr$l3nE3cp^i0ff{fBIqg+Ykn?Jh-$JHR%Oai->J@#7~Gv#ke~)=o+vf-@2`CEP(`O z1t6qUJS1pP4gqVDg@vZl5CNn~w z&HgMtD;)CAbRbzUq2)Pm`&}({^q%)ZxhuYOc=-3BY_cM1)-~1tTKIPnP|D)IhiTf4 zwAc8GV03mOHcfypS@OU{?l4_YL+<$dx=95F3JrJ!+7$WMPLzNe%FGV3FREnWe-~L{ zhIWNf4zyr<*1HFhS6hqAF$xM4!ONHJHf3zrmh-OCn7t63Cm`-l`)&;gRfO$mqxT)~ z!Z+l8fLzb`ZmlNIgnDOr$*Dqf{opK4d~&`qR)s?pe){*qY()JUVffE`$<(HxO;$Oj zyqZ5SDzPjFqcg0U2_lQe$CldT6Cd&5Y!&wUu)P5G5i8X$R`y-p??Q0nz2^tnXLG|L zb}4Z7F*?kBUBTY*d+oj!Yh333LL>XYNUBuaR8GWvn_ZRkR6p855N6bfuHap!$0sg} zXfU_JO;^DMH%rTh+Eo@fgR!w+o-JMLG?M9CHmE1}Zyo_tFZ579NjF+?Tz6wy`J03q z1?wrs$Yf`SW_>qO31^vq0~r>^q~ebs$-z)m26fQ5vnU3Cw}v_#0?Au2og0xxGSovyAy}+bz7O@_vwtv2aXf6He+Yv!awXyB?{_g zU)5wsh>n!W0bx_)(??`uEKEc7AG>$qs%OV&NTb8UB0RBaR7@{?p*UF7t3p}xmH~Gr zpphgx`3$RHd;VK&BL#Je6-7oD2PQJ$z;xk7-$!N zt|Q37k8%-Q(~`M?FgWQ@lh^a)F@VEPIf8Mh@q>+kOwt?wJ~?GzX)d{d{;Sii;oqYp zcUzsX zc1Fvs^e5&W)y?O!i99~9X+b}lCfJynxvX>akFAYXQVzkcFDYBmUK=;V)i2? zckVi4UPLI06ym}n&tpQXdvD(!=&m;D85Y$|+-)MRvj)xL%MX;wMBAK%O^;S{omV^pPZz8%oNuIZ%GJ@d9y!&J_IEd{I+YLmy<+(2m zD6zp0RAsmlC@cbhyqj9f{jpSXxVv(Wi2nz15fSByb>GJi<6u}hUT6!M_x*D)azqkF zL4mQ|h}pOkjNRFJhj(FqEX_78Qd6XEmpv`QoI}6@TU5vaX>+=7nackLl2v~jHc-r+ zpQA2u$S1e{1E@t0w-pMj?u;!FswIJ;lj*p?>%#lY?Rj{NUQmd+G4fV2F}VyWrw$|7 zwqoRWZ!|;)%X+ihL5YN<79o`7Gyu;$(9~#Rquc@eSeTW;WCm`^tgruF>NFogVhUU5 z5Rrg_4;l!M0^3X@9QhC$KZyoc-MT8sl&+Vz5P!=iIzR4ieRan#r(uZ#f$w*0h9LWH zDVs&-V24TTg_b5r0B-EfeOaEgAN(agxUxD8>FySnFWH2>^@t>6%gl+7Tgg!X_60mB zea?4m$0(y(c*a%M!Qrqtz}3WjDRHr17^#scl07I@&A8Q`>7szfHWmI0FF85FK>Sb| z$!Auv?`vejLxp!0k;wlang#ey4|f4w)!4VV|1i$vm#7}h4A6RqR|+qb|NoR9-={{M z5~Cyc)zeG=*{++No3m}reL$DwU4*#HuAX?y&dveH`~obmHTKq(b#E@Qn-80*g`LpA z5&qcIFy$t3mgF7k8JP(Fz!7WZqKZvut=!7=F$1E)^q}lYoTz8sn}E(ZQ~cG27MRH) z@IQ?q1MeUVxhwiA`NNQrTK#Zp!vK7e4iDu&l>}^FfZz&r?tO$@XX5aX|66v-`aRtD z%6Nd7E-RUnnhFF{s#xpMgGjAJg*H4oNJpy?&9mZvrD0+swc$d|ne$35i;Tz<>{{tb zf1klf0X<&g){lVq-XgMevVIMQZV0FCrq;Eg`HSy&F(EM;ybL0XR3jUm!QHDfIAGTt z=;f`2@3MnWTZ7&VA=tRX0y^;lc}da(;%cmE5L%JFV$9CZl#8Z!Q>Q$uIkk!9E& z8sY&}x1smVrNB@x`XO=s;m7-y-RPzZ^0NoEdidfVU?~nY z@9Zsz|LrbDk)OAyPa#ZPYTh0A;`xtq*z^~}WC;iev|Zl#rh*E&WJ{@tD7UPP8+}OQ zJ?@o2h^XV>l)DEPY3f#6EZS$dU;5P5{CXIVFx+ZxQm)lnTCwc3Tyh52n4CSbx7E&b zru)^1j6`vuXn?p4Y|q3dYa*T7w<9NxGDUVk#UbqJ(0&NI$5)(yw*#RzLC_4t<*gc) zK>G3a;41lp(t>um*d%7#qGC+o+8Yre{JP9n@xrr(8Q$hh`uk`>R)>Ji zYF&tbY|KlJw&*VgzT*3Pu$}EEUZU7cwbKcA_58O|a)lqrBzvFlt>pXlQXIeJmh+0( zI;|k(X1lkNE(j&#C2IL7)wcG$u$lNoaIw(6(2ze=EZ5zygBy0Z>;!t$q6gPC!@vpR znMuRnNmo=yZ1Wl9KmcbzmWmu;rG`fZL$;dw`gk=H-%U}LfAIYwn~f|Mt!PqEhdu5k z-54?L6^BO6$-`~nFn@d1YF8dw0a1etpHj{Eh!DPb8gH%F(J?ZTo zsIVev1QiGrHr#HTK_8n_w`0c^8k(DT^WZ@MY>Hs33zkNa=4pHm=?8}?&Nfq1A}g?q zzAllWYu1R3rI1>Qr{MEu_-wTtP|)wyL#QKFSdV4!#AX-Vs34l6G7U@aKRXJcr{h=R zyD_03&YHyh_}?-1g#KyQ*Q-{HN4TPO`9rqOV1sLx3a46H4W`}yaRD|2L@}~NFu^4Y zBGdN+9L~L3t*;s(6=R~x3lnNeezA8A7o^urCkJdQ?jE!W>&YPJ&V5lg6Unow_do+h zvA_U60e~9zkXa2P^9~ODKo7*f94|rngbE&@*Adz@2MEWeG`gz0<+@q?-NjU z!EJ^zR{kN^%jBG||5-AS--fF-tTyiSRVTC#NSziHmSs{FCWJJA*1t!X-Ejwg+?)ip zE3~gGwXPr)A*-!j=5@3Gv6Y>z)*b44_ZN*$zu)wjk*nZ!*HJO9-G-wHxUH=L!wUd6 z7N%#Mab5q>r*7{IZ;gXUFY)nhWe~KRd_Y4xG0oc5IafC2TvN! zcq!!v_XYo}6D<6U_CsYQXm{P~iF))QH2@%7G&Ga}K5AIW`~du1bJX4~ zxbd&4Cw=BwDx3Y#&E#NY;@RYQm-5tjRM+rZbou=Kq|bE;RpnWjVgCB~1UQ$4z=T2~ z{j5}kQAY$+8dN$4qz|Do0O>g?n7Sh7znJoVS*u=!YdDpvC>Q$L67!S|5c;SD~sX&mWIbgak7%f$&q(gP?yz+$e@gP)$?zedDn9CG!MMpcjB3BtdMk~Zn&h|p@gA_;riP|CPZ6Z-4*FNz* zLe$8$7g#u;=fMUINy^602=YBb_f^C60cUZAN8{D1hOg?}ihfg%vv3jsWg-aWPS7Id zeNaH~?rNHZftxYSTIRtR2S=V%0$FL7pKZxA6(*mPiSI$edjAkOx0gutcYsyDx@}B?ZtgcY~Wd^U-n+ z-X0q-aq}}H22CnGVC6Y=omo{(yqZF>lc?@@g~|F5V2427;dKB{oPo1755bDTzg9md zGASe(QCSJs83}0nSvLGyRq?Uhg z|A48@oXqTO+n4GJr(9vyEW+Cgy0t44{PJ%8w|MAkr`pT@HGRomp!&+%Zb1?DLz||v zSq-@npLN>pDID7u{1WrO-|G5o_vz2bDwV1_QW0G8|4bQ;euIlOTU@ER#4L5 zRkG3|#cz_oVtR-6Dw*GRtB&+)>3mK_sZ)q7^bn9;4QB3l@%;rNtlX1!VZc(J@{KU{h-eqkH*V{oizo7!=XA8iDI zB88q@Yx`jPf;}t`&otydA8hV+HMoQO1!#dhOwkP@jr%${1F#Gy_crYXwzPYUAOBqBRru!{q-l#AK6m+>>DYho zCZaLft}S@+Bf0=pX9<$UzPdJ92H8>d5P6>*t=-In1XfoRdyT;x678kQhj}DF-m%3i zG;$U3YxF}AR=#s?1x)ii!c@LFn7r2GgCtAyY5u2A*MLgm1pwR5)VBY1RJO>3V@oV5 zGE82V?4aP+ss=25yD=S_sjXcvOHV<;S1Qh>&*vA;_kzHQcshWNjR$A&#$E=ChX9r7 z-)FO)EtnqL*v-eC*(=G}XR3p3sWjUhBw-k>o&l6G+W)FGGO@@1kKzfzb&6Ye=d3Cq z_V`a~d68n))n(+3E>pC!rs@@c*fc0JSj}WZZf8>QA+ms?moX|IbiQ|c2&OGP7lpEr zT*QB?y$ZbEN{kvPNF?@2QGp|ni^cwa6NaegGnaqqz)w(r((h;r6~-F}fj2~O=EZ1s zB4wUDDJoeKa-7ag%3pelU!VNtZ-dra-Igf5l+>8+n;ITJyyNMkQz_#|;^IZ^LIw%o$%yPPgmf)+~f15slL$GhbCX4}(Ez)ZXdq`TM&_u6U0 z*@aN18({XqSCY-2lGJJm9Bpb&%^xs1c>7j}?^JaGmC7w-lht9a*<} z9t+qzAaq}29zP({vl`K$dLqMMy7>rYCOGXS8xt3wtj2n4iIOnzr-^zJGqD#C6bXuY z-jww88w6-uoQc^EHWkVDYFaTZHY_e-wmgFzMd!>MIDCO7!ve8Vi?<7h-VW;{L!@IU z6I`X=GDnWZ$y-eJGUhdR#bHt0UOUnATVNQSexzMenvKsRO7e_L;!DQ1Eu!?Z9n6^rzeD9=wHurRt<`5n|5$6f+% zB&bM1)*Rp9d-TArpavr>3&=N06ZhtafRC%c4k7{xNx~0bf(!?Yl*mxQ^6hiHAl{6~ z67w{NiliC4CJEDVV=$;_gji@wF%K@VyAOdG^&A9)DX6KbZCqdoNPP{s5MF|4)1X8gz}>67v_1{#XBcFO~%s_Pi0N$BzhMg@kelmzoV9z%3j) z8Erb#Q^~Bo-W}i9MId;U6#sFqa|=GsVbQhtIJz%Y0sHx;_#ywDI*$Oat5o=k11Udx z{{ESqT3@WMK2})rz2_vH?0%CaFRcOvKK)|=^T&YU^PBr0@jinydvDE0oiS!Ks9-Z5 zqCxfbUk;5l2V8mmLwCIblajuSjI4KhUuEHm{(kFl-6b+!II)?_%8KdGN>LeBK57@7 zi625ML<8AbYFctk-7nN7;nFs>QUN&bt)ldOw-F=HT(Eiu&g6CD2n9MnfyiqGO3W&xZj&kQk#}bvs7rQ^)MX7rZxvrkB0gv`+jNQXmZL?72c*P{YK((_MG|N3vhG|6tHtP_<7hYGC(0#dBmkU-M^ zu*btcu%d^VV;f#D;}Klv4t+CwHTS!9w23qluYa0Y{G6B9)%w!Z#+h&Dhu8p)Y{NsY z*0-wW@2xm`dx4Ua;fQw&Weo`jCHfOvJFDB**|_C}rRZ?4%s#c10iq_*X1nV|UoB?; z_Gs`)dV);W;J9WgbTk>TUOIT`(Ks7Szza#WkgP-S;+CqC2ZVGd_b4ePU(Q3Gjc)Ph zXBFv>9`i?T>OSC<5}vt6N+bRC>t_YRf_meZ4~^Ks$1Kq14Uh60^aqSohP;%YU*0xw z0%iJK)6ulDhscdwIIZo5OQb87mZ`FjpV-?cU)#BI8Ya$U6mLUM7|xLle)*tj zrv`Zxpnnj_#Qc&=KN!+4q)X#Aa_&$Q=jZ04!-9@*{v?nDbUd4DzLomGgQg}{ILD`g z89KcEAcZ!Z1CXIs*s&FSTFJrTZl(lj_Uo#umE9-50#i*WaBf-uh}o1>R_^pTI2{FZ zgg<{e*}VUog|ej-kx(amG6Vrl^O2b7|H#{T<0Kwd#ffIQf&gh;O8n2kB5lZK(*cVckR?1VEH8)BDh5De ze06oTWvT*G1Wc-jY~>)Wa>E_C_K*l24$+Omdbet)9JmZ?H8gp3iiaxUy_KFm$hGMvgoSh+~|T*$rNCCE z&_17;r*f7pOrS@E?16AiLs^mX@quk(T#TomGeuADyjxd*Z$lfsG4TIJ8}%=qF)dm# zDB-P-lq&!XT-p1D5+WnI>fP6qjIfDv!Iv3QYgdnsQJYLIngXVGJyY?(V|QNYlKVtE zU`k0Gn+vqEc>TZE^NzWD+S)HR+^LCi z08>Z7P)3=OV?d??G9)_{3rR$adZR64)Vs>cpa$PbZ`Pf~7x$#4&DZ)@k@p5|ui@|} zZ7x5T))6PSiHC4KN{sQhshi67=Mu=*MBkP~!GMY4c$0f+P?VxH(<>==21f`5h+nVsWU zhQu1;EkT-X0&kjUqE{(o?=PZPgQtpEn7LD&gz0qI^oFg zzCEe(W*tEkHrFo)VD=`A9*oQIp+dPGCXpsBkXvvsnr6{K*6?z%2(6%(Bz#u=((&%ah^xmn@P{52zW zEhA*{UqQ7mNJPK=4DGK?Fs>P>2#~7mitjGm>kH@L3<{r&k+&*!j$mVVXu2j046e_3 z&X;v7D5r2nssv{C^|03?tU^Jf8NZ6`8%NfL80#pvh0>j0e|%M}m(iHo>2Q6dtH)0t zj6+XS1bp@70p1AjjK0p=K$wR<^=!Qq__aSrL0EGtAq0XXfAqeGr3wO+7k!br@MiML z%7|Oerna5>B#ulwqplT}m31|2H}{&db;bD;%SFq7% zP^EvZ)ft)maQ5B6L%FfQe_c;Yf5hR{@n*GO)n}i-y4EZnz4b$?Dm~{O*S;AIB*+OR z$_Ys$EVG`!nxX5y@#=4;S=f!)zrNyLzkQdva^?sz@2t2_JH8nI{NTX@CPBe#3=9mY zfW3a|@$vBw-h0-Ng_%K42>EStdV0fw%l9G#pHAV|Heg;{z!}?G=Q>Of#u179hI3m) z2TQ;VWOd8&0=B}2s^7#hYbFI(HGN5+ss zi0_xazHXtbr}yDGEg;+)mzX&0KC=u2yTN4dt8EihNQS$2J@2)t5emuC#}~0zQBO+BKiIRBFgP^z zL~wiAdhBn-ZAaNT4Ve;d!2>l0fgG_b5fZIq8GiNqB%uGMIYHq$n57jvEgK8Wx+Eh zagaVTF>%~vPegD*^8B??0XZ-;hG;R}6seGq5QOhpsFtB2>N{%qoqg8y_m>giF;m;8-OAia|&*gJlQmrF3^#MaKDtpEF0^XBo1I>+AcH21S-!WVt6-A}s}e#UmQ zI1q_?K=`X@MRfjV=fs@pz>Hhy4q+vIXstkg%53>1BHE(fkIf*{+FDCEnN$W>^F>B) zv$&ND{~kl_ZPLiJ6KaXC4kwd_^eml8cle9XeGeVQf`jc>wr`e&vvBr$WNX3y9+zQR zW=;bWGI=!g^uka<)exQlrxgC3nk!dvuSCSeAl=*q^78Y)*FWVyhmZ#uX0o}wKUbH~ zVejZYm&O_QFwTK+X=!FMeanf^G-V&L8a<}!9~~hlF^VT5+WwMzW9ffP0#B%whTq+* zK?Z%E*qobsE*`3$-0__TH|PHC1=J#x`SQhbWKdxC={`i}HZ;)?qob1^pJ9q;->|mE zcqXM5p?Y5xD?1?jtdBxL=Dz4v$KCRt61p`C*X&>h;ZGw@iHTv zo&Qcy0;xwYv4`+SXfnW{$HvYsM1$=!D%}!}376^rN7Pq+tWni@d$}Tlf33I4?`C%Li581#hv}#*@4KcTpRWmM02}}H zI`17XE~H(+z23d^&DH?#qlf~whvdbY^4IqBUBKlxl=X{o&hY+{j5-iSj&pLtxV4SC zw$@c_E8uj*=uhwtEV2zfV=Os|Zuns8;XguFqh?c?o}ok0y1@y{Wso*4TCMLX`Wp1&|>ifE+f?m>m>holGKxQ5ka3I&*` z{R|3^euZ(tacWo?5hCgjf85yA_EIcB#s~bsz?C|q)m5DSY&*=Wp|i7drs@c^9?zQ_ z{ji5x!Swzb1mo;yBZGs8nb{*fGjOPK{S_`B^2~^fd>%C3V4RcE%F2p>XLWTo_|qrK zu2>P}p$9*%I8@Tghtaoe&wqcUshKXKY-(p02CQ{caD@8=0vGMaYE|~LXr5<><{(VH z%4N|yzy1Exr`JIYp00f|jUWsFp4UXXQ`0|xhLCY;W`rUV{s<;EUTWPxG?Yfo0BNJ- z(el+{rgo^&*M3&2+1fx(gv=^2cu8V5z96_~gOxq>=&PkgPz;N-HOois5m?Qagcf2UJTJ33lUkx_s;-aP|4me5e*zenF1dx>Utu*)8G zb)%QawvT;Z_rw&xhu<94^mv@w8I zV(6ye%J&zZs{OAv5(qg|lSYb)_?}0)zhPa;!ze^d-{+8fEx-C1+QWATQW}j^V5SD zQzOQO#l^C4oIZrX0qSa}RdU#9+So2YJ1A|1il=X61Y0t=R|hPf{|FiWG=2Pd$TvCN z%F^=o-Md&2Vzs%ap;ZIoRx>a+hv0Z;AdWflh2xuSq#Sc27%K+C=73vsM9x921)fWS z8`YbVh>dQioihdJcxp5rg7>`;FN;*zqC?ye5m^QC-C2G3T=ks-{2 zp-r=C;n>0a>}+xt0W}?+?Vm_Ne|yAncV@=;OIjLLZI*FCb89QJh{(utq{S0^u;TWX z`xfVYBO^ETw_Q|>o%>qnU?^vzG+gm8&zmK=o(>7_UI{X%$sR8Op1^x^qQvtf+JNtQZ_?m~$_NJF6US<*vn&C&65 z#mgPmDbTPR93FO<%Gc&<1%HAtPOZF|G4sSBnvDAoA8O(Up*27(RKg1)CnvXxFHQh~ zq@M4sL&!Y5$FZ{}s*V9DJH7#RO`GwOH%`*KFcpMsdPmK5!SvYbS8C7JfH5}eFAMPwa@5k+7E?YRqq-0{ zFjFr!%kY6y$4BEBy@`?9GjJ^XzMsk_|q<5s_3BS!`6&b~tXBp<= zUk0$@hUvV&(ELNYe*HRrkNt8{tF@*V7`luWJ`QSp3Pyp5=W#@tas?IiIp85MfDAII zcMBhvK`zPnd`?b-(vcH9vzc5ad~lZ>Sa*wbr!c%F#&yj0(DJ(lLt}p7zC%4Jf>Je8-F6HhvI`S%7;a53u1YB{7l8@YL0{v3ht zijZ1Kp8b8CYs{9|EC1vP3%n$35fPEmiHTGI3gDJtGdHYT2i0Dp$39iUtBsqf$3H=8 zy6$-6R{Q}b28Qum^P8>RT?`bMvqmh$AyKgEeA8lD1M0%sKnMU!z0i$f0J%VzJF4e> zvY#J1;zcbbB{e!WmJE83@XJc)6F{m_FP^IBfv8tNMh4r^`rEg73M`k0Y<;A?x3=s{ zoj!7JK7RbTacO7h9m3%Q{L9p_9@fqB@^arxBgoFO?U&&q>CUmeOGFibMJb^y-1_qeP7- zH1UmI`LkJ=kG1Ly0qG~1WEJblv;0Dv5w$aMOIY4f=^(<|Wl`7)K7)@TU5+b%P(cHW z8;KPcCkyYG$|}H`Mu4rDm^Zt-jzHojSUH27HZ#lgzKyK2Ff#q_ ze*X1DUxu5p>XnFE|BC{t5S2hVHPuhei|bMk^Nq00dN4kE^?Gh&s_i-UCiq~=^~RwN z=M5QXo3~$1f4l6Dn{JngB#lr9I<{S9)(((e_c|r}u(!&6iz)!EXmy0C+LLZSA%PeJ zqoHSP?5~?mHYaXCnOIPT?!~J767!(etYhYtD76MprE?#O*k;uC(5lc zW!Kl&!#{igYcui&o$trrr=|=~{?3OXndlS#7^@n<*r(lhE+JE!@jFTn9}Z`AxXv}> zo`AQm@u@cQa-*Za3X@Y)TSYPJ0q7d9IRi*2F4WU*vUlOyh+#eSsd9xqLBtg-geYy| z^MZQ%-3*- zeQyG3QE$X5TX*R4Q+_H!Ix+vvy5omreS-vapY>c_MGZanG=|n86C?pZB5NWcA;Ie4 zU}}460~nBJ-Uj7XNf8ye=6wI5 zER}n3lQr^wI3UBwUARw12L^m0f6aBCfYr>qQF~yBqGWLb%|*>>DIOj|z?iA}<|&m< zy`lnSm>{nR$W;64`;`Qz!t+#2@_0=k7tIo;+C*Kq7-39Alx;`I4DuatF^XE*M^2Lm zhpp#jU=(Q#4JfSg$185$dxphF**Q6Kc6RwIW#Bz_`SRtN`FTIsS1=HoR8|%>G|#li zXZkG}-Nf8HC@F~%8o9XO!v>YG;1T{CVr%H?+_AFa08jh(2?@`(HFv;(NI_XSsBL)q zW7v&X2WXwq=%-UVx0y}QQeZ^#1?e~pedU}p$!U_4UY;z)A2CnQz?6-wI}AKL=;TGE zqY$7T9L1^Gy}UJ~HGXjCF4{yn`p#mE;ERieEz?Fkbp3MUSp#Zn=QcI9v6dlW<=s+z z#qh}*+_CQ18T^SywKv`ldu8$A*#;tRI*q>v3TVpvOiW$^=iHi z>lG3e&#~KZT8`VBh@q?z1z%JC%HhY~)6)Yg{&W!Fa-6+Dksj7{$?!zImlTgd)feGK zC_cej#Msy8?R99~fwk66fCCD_Z>2Qpp|i6vlvG(7LnJ6*YY_-QKxXMRspoSTU`m`v zHaf8Mv+{)%84K!;`XyMnEn~&zL#+_jK~$@kIxbd)O`ZD%lx?NQkXfaRuuc5<;YTEO zqLOWz418(e5hWKNWvRkQCeoj=nXWUi?SWzs>C_s&Tp+7mHLS3|&56=JzrBU@nFY+c z`YPYm)=I!ic-_{fP_s9zCp@i5j{>iFkp3%_%b+dRkCy-jzkmn4zn?~ogW(o!X>AQ- zDv{%#Zt8Y0NVuu5?`J$p-2&gvZGrsFeq(2+;?n8V)RgPtLNwUiB+i1ukJSNm`duoP5?w5?)A3t8f3m8wTedQBGk0w~ff?|x8f=|&FzJ4gUXjmMctu`@k?=fc8b%ixKXVPei zdDX*wjLJ3d-i=ZT~PdnY#&f&2qz?c#?-0bKH7dqBOQ1 z>+8#wc0uv6G_)tDjUzTUBO_bRWTfeNdL8_#zxe8_wKc|w?7I+aFK*eU7KU`vg+=>DRgI2pK~7gbC}~MmB?`9R?^THK&{U`c%XZe!f6V^Fn#7 zZQs0kGn)Hopgbw5Va7U4j`@*w+Q!Tb3i$fD8M5i+%FD~IPTsA1$FM6$m`L(lO;0b| z`4&5SyYY>Z`oop{Isk0BAd&^Um3#9^&EV$)S| zadGuXIn)f_6e!i>CLo<|Wd>-OIsEmHSQ-8b&oinU`v=PT&4l>*9`DdCTE%JU)s(gjJ(Ui!#n<;$NjRE876(e|5;e78lP1(Wv(8^%vODq-~D3uQLg=3+?rU{b>nS zqV$n`b`?%))55>i?h3}oohQy|gJAUgtBAX|y-~V6)5g4eTQH@&D6+l~2}J^wS-r5^ zkO7d=LU@GM0Sck_6cif31Lu*7N)mN7z$XBHkq{FnmAX4P6zPJ+-a7`V9*(XTJBtr; z%XZ<7nc-IaUiru#-Kmq$dj$_fJAsoGm~s z-l)Cv?_HWN{7&Bl@ocaa5l4sEqGNpss5Y1)W`rL8{cHStAT8&B3a<9$3rn1&$LBq< z;hFXIP{4Y!12~SQ-~gB_3Tf)=+uWed8dLRzZp~f4H?6N*OiQia zpp;~ZPzyY6C4m1OdhugqBzi|UFlC`Lx(WVss0i9q*;@I-cx4PX9WWpaiOIgc8c=Fj zOrTTee)w9Fwaoup@+p+_Odw?qq8F3^2|;irrlSjmRWrAzdH-IA#c%iI~qT0JoKloQuP__P2OD~YbqK>m)48X?<&evPO3K;0eYaLp|qFj_Yk6%-ezMMXumu(44OjlcN< z3o;|DiOc9p_-@_OdaxAky%_#AH(!Q=K^w6BegnUGb=UB0q>KMQh_-f2mV1$4P|9{H@B)R1942*AbJsznKlwu zMk^)WxB}uaQQyj_#7~4HGeK0M?P8Q}%fzIf3v)zXD4s{SqMmWS$^YPk_qUEjYo-?x zrHC4R(4%4r6l=c8jMg4;9FskBAz|_#rDtH6@xk8sIaR#$Pz7l`Fu4^x;JjQ+3{4}K z>W!`f9{aGi%4Ep!Qq=5AZRwY7Sm_50_ zyDO)pM9`^2O@8GHhL3cTuqJ5o0LfN9JMBO^GAha{^jg8q?W~~1gZk`jeBcS{cK#M) zg%Q*FntA}fQMHy&FENtO68FlT0}cRBm#QyGRHZwq11_n|pd5 ze);-!9vC%OQ_wQl0kuTR_nuX#%`HRsh;YK>hTXacg2r1XqDVlkX=jI~?}(e58xEgF zP!!!BR8yV>c`y7k2+4Cms*zPz4vR6n2VIn_S9IAJs~p)2oH*Y{G`WLmBp#;y&SHFF zuAWaMXQ-#u4a!E9G)#OYy|DjE7Iy##8TCqD@BJbC{d*=+%C3=$s&#eQ`>~stE43}= z-eo*?+WW6VSI@7G51>6U*R$n-_w(ARrL{<}XSgYu+=9gJLD|4Nk0hH}%XwJt#rMBT z!d52^Zn1iNq?=Sci#Ub3xRmmB?=PHoe-={AmWealQd6_F&DB(R0coRH!784gs821xa`0QNwt@&Qysr!-CrVY4pEi1M%22Hjh{C>rI;*CZ3|20URb7l2yP ze34Q3*UazVnZoH*C>kIR&@_~-rBM!P8VN0Jjz+u+PxLB52Pz!a9v&V@??f#F3%@w>$}E~oBB!gIIDx5; zl)(s?NJe&P`OX1Us}*j09Khzm0kqpcFpybHj2iYNq!;u0!?A#3-KHXrzg3G(aX;=7 zPd35p6&t?9ID#)}eCxWq2K>KgpMQ;4JYTtWc&KDl(xsGSw6Ne7(r9zi!9%&i*pw{0 zuiMy%j*UXN^!%bvg~KEl{Hukcv9}vDzc^y(&pWV(aQRNyc2nJ*k0Pi$*5rHIWtqFJ zTPvFiZ8u8nnbdBVqy<#Q$KZbXqV075;su73)a!u^tsHZ|H)qEiIc8eOI&EzVvIoax z{tghA?cn1T{iGc&i_)xeUjIC-4KB!{M%?R(}6}1GRUy2EK&XnK*QpX4Z0! zSvfZ%%`#0tW}l z1DryR6`4R3ACzS;&-1T||Mk^VWIgLj&5cLxSMmv^<(~`3+epxMkWYNK#sg^lVJFdD zr`whK&k7W?%&y60s=uwN5s&ZWxPlia`dr4Ai;K%fdg!6k_MboB6nSgEXkcnY$T8oB zc3<7eAH^J_dU^=;f1yZG(a~wQlJeU=-5jh?C{0b3<<$GO_wq+#pF)tlUh5n%7Eii6I+paDqmSQKMS+uZ5YJ%M%G!=YGBFIgVDTE<$7*a>K(wS8Okt3`7~wKA zfD=0O&b;gDB#XPv*>3E=$O(hUt(oNfMe9i^^19Gpt}`!+02F?@?JACJzH8So;c#sJ z3RBRCARs}mol3ZEwCaR$F~N(J84J3 zq#B(4d@oG5SKR`4{;QhXSo8|f@I*w0J0~Ken=IGIZ(H*9LU7%AOI9#lpZLRVP9vK! zFUvP>>IRAF&e2jun(9n;evU91{QYLP(S+cFJ$nnysO_iTOls_rw%QIAwB(9KE%q6O zr!1_jR^56=)-Mf)#GOjVgoEC{Cq`l!R6I`%o)-dtc5G~HwBq?yL(jvf(0TkDXX)Zn zely+b{o;WkbGQZf{I6e6{_O8*xRwfm@|3-!qdLtG0$;RopI!t*JQr#Lc3r9NZQ<_6 z8yg$%0Huyt%n8fR&dySZUwl096^>5m>8X__Lg7Tu$Mgs?y5ihh15L@puHF1k7{5n- zV%U?c?*_2-`Sa&l0|T%N)va&aWqhgPgRm_6YM-koK?2{q^7Azgj{8G_2_3&L%W$y@ zMBuuj5vS0}-=KK$9E0M$v3;qbsL8C}!A$hcKC1;u;=R2F38FCB(EV35+z*#)NeM6u zYS+VDCHnD2(pEZ!1X0X;(abjP-~KNxynSV3<9(h1e$c_Rc`adnD*8j~5t$-Si7!M_ zHsLSFke71mwna@XnmZEx9%XEY~3|A1 z3Q~Pi{24c3^Y_|Ee>W4K=NV?x`kO2 zTKR?=_zbVy+_E&%Lf^hc3;V7nkqF%f5PlsTZ(XwfGD>>+GS@&)eDBg#*fG!?kU|QtFxsK==W-RmCCCQ1-(7xWGg^RZXlQ7bn8;0~Kw;Lsxg_m7C>zgRXQne}9{lOu zw`4cKAWfkpMCQk#8wSU)hDkq6<;Hu36b_A#zlA>6ETHZv-oPTz&@MUWy$(Iag6`O% zXAXF;_t6kFII$-QATe_3M_OHa>))b>%XfsyO~?R*Q{xRc!2 z8#7T}5O739sbhI9GIirFgLv&}uEe!}TQ5iEsO@S2C#T=34|?42i_s#?lQ>!h@Qz4~ z84uqU6Pp1>bX;}-n)kQvOQxakt&PA$7TgDy7O{f7QMTkm`8&mNnHD2Hc{hRgiC~QYWFyYn;7U%F>)^83MFn&U1Rk)OcXoERcW{ug ztA9uv1(wKK|U%+i3bsfB@! zoeCO2NO_pkF}=IHn^aPwZX3_8mi}pv&%(jkxfKQoZ@`eTql*ieSEE4J0g+FI&fldx zJ>YwmPr2cP85RBTdS#1g;k{KbMlVfNZuk?)VO#k*8!E-NzT2}Z(Zr5$i^rz@1+;${!Gk2_tb2~y&O`do+gvHpjp!B$;k$f z15~MV@q&)Hk-S2fp^+9QXTB2oSK=&`VJm6)^wFb+cXSOB2cIObe}j0|{N-Lm-|#hT zYNh%upNnkw{jBt#xnN{f7~H}9x(9|Ue)Z1WN0&*NUT)uMYifEhUT^UD>KZr&pC(Am zI62xI8qF>SPAN^b zWlk}(cI3fI?JlWg%XZ}mdjw<_Kw15pCn#pE%05C8g(j_}6rw4ro>@?!!u@k;X2u&x zCB>3h&a2-|EnU2ivcSVn7vQPz;^Im%8R~-Q?ub|`(@E*Qv}DU@}Ys^>m8l5AUhGK zmE*lL*FwBDYN84=^ z^D+5dU5&UGlt;}L;h1t;nq$@Xercd9S{plAq!_L1%wyIn98~?P+?GDdc4Cw}Hjco; z@qRgnG9AUv9+3qhYj=`4yhbP~)XS9<#50}iqobpHwx*2dwp|gr0K!%uG4i5g@che! za7^ND!(TW!l(dRFic|I>swY5KuYeT+< z!pfGVvnK#2tu@W(-bzs2*5EvXC6qlW0{OV8s3?K!R5}EgCfMjO!NCiz8B(pl@nM3U z9CZwpm~EBmg0zr`NNkBA6mG-X#>R}Rd(fy^@+d2=bZvQ?v;Fx_AR%7RXCL6FnRR^v zAx5potHZgYbso18JdZ4)&H%tm_m!Lf`*60aP0Lj1OylABB&L6(L!RYT$3j*l#5g{P z(e=4yqY34D0wsVzTwi7$)Vwtm&74dOBv5B0u-?L5GgO!tCixfOaZD_eP#>Yp2njZL zo_mVc{bkl)?DARt$Zj9cj|r#zH_LV13ND=#>KBHEXufo}pl2bO^iokXKhUwC`Qa*C zv*~MVt3Cs59LpC1efeUzOi#8>54@%iy|gIQ?g>gwyX_!oBNkn>RnqU@QJ(`W2Y!qh zwVNm|uY!<|os;#g%L=;I#KYElCmnPROjY+Tj8mV6q7%VR7r!ahh|JKfByD008!AT9nh6xW|qmm zZwfu#3qHz}woXx6jZAU_5Vv%AH=)jktPki6xZtc~b+8AazOHWSr&k%J z?h&Dwfu1vX_i-asN`OKz%c7S?mZR|U@^;1DB!!Fwqv6Zs!TLl{s(e^hB+7Mv;$V}P zPFWPX;nnNRa<^C;N2jqmyqA+@8`h&m{B(6iF=XSt*SzlW9c=I5*ycC$nGY34~K9x)qjl*6LX|D8^u-D9^z9 z&knFtN@efZ0j|b?3f++gJ3~aQL3um8rh@V)vrWI+Xx8D zeua!?=9w8KT%IBKEk)IriO|uJewJq|-kj{It#4q!2LN^{-b>R$N}#+|9B)+Lw95xJ z71R(I4gUS^?(W3ERx9P2QhWzZi|y_0w$4tqP?$3#Bog03fjl;wOgkQuo~1)7Ku?40 z>JG60Mz^rAkOqDew5hf`IP>ktdq60EyVvVXEf>#NON-){L#6I(E`I*Y*hKW|dIu2b zwQF1p?=_CVb+f*`gAONfFa&UCpQJ)sgNUNhQ^D(M0Drk_D3M40)B{n!dIbd ztgLgZ`SqHUz~Dp}pF9StypCV;IdY+E@9J8id+QLoqObu|QjLPh0qFnx*R{Ck6sdgf z-NRi0-?G6$4ESy6t1FqO>3Tq0iG+b63=+ZYP?t}m24-wGgldrHa4w(6tV(wScS9{+ zh7xP>Vd8b`TC?zEAC4g1HaHEo0O_1LJ(&Iu_|5x>2-!vznYNjXJhSQYt86%iUY;10 zmC{Nf+bv_7#I}~GX1!RB`X#9??YM0{Sc^Q*(FX>I{i(%+y%-6|M#EbE5-nz9%SILz zh1kXY!>VMISV-S|!b?F#9Zqt>278#_=B2B>b!DARjO_`UL0QOYQG0tCiN%7&!u|bD$@3ap+9+5ly;s@Vgjd6t z@d`k?_;#|2{nRidX&FcL+FW-H4CvO@$3`yyAaIY0jz-+G&3h9xXu@8<_O7p&f|uU3 zwDWx9=S>(!TK@fewuBDm7p`C5+X!%%G|H};frO+)<|%?3uD6eYJ=UXA z1#EA~oKgUsH>X*Hgv)|18n`J*5%U4rpgzy{`z1ed6^Eb$2_{=Kwj`vkly|wJBkFJMwI%rwR~{B$)%wvo!L#(JXg_i(io7R12S`AKIY+3%H*h zE-5G~Ho+WG7&KUCPY!piuI1q}HP2P}vkLH|pcoq7(337Hjl>NsI=uCej3EBiD@N{1 z#CU~Nu`2KExxS&Ea&AtTyJP=@cZvB?V3+T%jiFa2te_8nv47#`+DWd!@Ur=YCc2ZU z*7?#TCMNO7unbf9Cocy75P%qzJez++98&s^w<2{Hb%p-lkBPl?0~u*Kx-IJzRh2wz z)KBz@@S|&TuEFob9hi1%a#lb-a;h7NZEa-*h?JE5_`}<`eX=gOd+Bqyw|@VQ&_}W+ z;Dtdc`vY&|+V$%%KGRTqZj>t24gp%q`FsgXM?Ooctkki!fjK+f&dRDPnJ=kvYY1&m znDDoGrT#mZ7|2aB1Kb#TUnNmc!O5$tei+wwaS`FaDSnTJhNjT#+;g}yHhA%chUqtR z+|RiSJCMd38s=4X&uH+T{XQJj{e}4{03`5lC(3AM;LT8ZN4~(B&@62S6vsI&W)6yIvXxar6T)ILi z6b?xuFvRyaCWGM!c)YhVgfM!yz>GtFH4GObrMgWMOek5^N_UYE+uE6rKl^lr0P|C} z?~fm|Smavu3rofM@9+PsrkPk(E2>kMR`Z$kO4`QN9)$-5Bp*a5GZs5e%L36QiX55q z(AU7cX@K(Jb$d~f_j_Viw%gq*$lpevo2!V-?CLPht0)KzA$XSg?bnluRf8T?`y1s= zA7ZU*e?Bu?+`7p{Pfst_6eV@Cg^rMtH77u4s0ASJ(pDfa?Uk7f2SC>mSQNTD%hRe; zjg5_8q7H1jV+7=_*MPGu4GhTay#cLaRaGknQY~muI+b_T^P5P!nOQv2S1?MR;R#GtBZw`fr2YmKIE) zFX_&MBE2B>{q>cVZ(ti61XG?=`aPQ3@NP#XVamXMzV#9~q#||}+Qnv<|RLEHm0mXQIywog?o9T(1l{LCxp639kkcM^JNAKkrfv)v^XVzsMZ3}mUcxVcE z`e>w9=Tt-u3*0`)hXAuX=h|bN32G>cO9ssM=(cU`( z8Cheu_kbQdJVrjD&#Lq(Nkd2#c(d!}(|4Vn%Nmok;Or~28A};5{n_4*@V-YX--U&R z^=v}Bfg7O^!KlGX_ZvZB;W^N*Xn}i_ZYToviAqxqvR~P^?{?Ba9ALD{DSPU@7KB20 zq!y*##^)VHC_Cb(z@F*{ZSnvaR0t2iQKR|^y;c7n;hFn^S%GLuPy6AZ{$1+@+;cd& zg(@zo;b5S}4{;uVX%C#~)Hy##A(VoREkZ-rJ>WL1(cW|ex*87;kJV#{+<$?D-ZwUe z3j{9U0ma${5dxT%&;n!skD!mga|V0d=4ZvDY*jG(`VLA(*~M?IydWhQs_cdyklvCc zaJHWR-7=}!9Z<}&%7ZJ5(}%6g7U97eO)_C_=N=xe2#sKXcA)14Mh8sP)YM&Nw#v%N zEG#UHe0(GT0|FVvY(kjn3C8?Dm7Frpk52ryb`#%NOw2%${>e*Si9{#I(?AABr{4VP z=-?1=Bw#fgEYOdQ=79>yF+Y6?Pv3>LFvGODCjGzmIU%M__ z$npp|K-KmM*Vqe+Ae)##fz}v>*wRN`U!^_HH!-MafyWr^$`ph zJkTJ!TU}L!Ozr}(^gCx)45$FmqoMj~E-j4$z6e9DbucO64s7_Wi7?3{HefbctTYv6 z!1F?Anke2dp@g7=2qzI2*9YdCpjQlX z`?x9a5)J`@9MqC)>+AiH%|g#4_i>SF3!Xaw0(Y}Rbz=cMdTpC(Zy^O|G*EEa*w|nQ z78O|cgB?jkgOD?a!?X&Jt6`?7(PrYBKQUQZq@bTKfhP{1n; zV!}w7_3^_u9$Kpz4$f~q0AIzZo_gRpDqi_i?s~1JCihiQ%)iyEmu~M8R}~e!;rDiRwlD(OkHp0KM*2~2QBa8fJ@(uDZMn`40RBhRN8xQ{=qZVw zN10jU@B}U+R6@?)*AN$9e@y6MIjuMu=<0g%)?#haI)>3qkLHFsVYv()irTXu!<}kH zAER0^Br9p7a=4&d-riJXLv>*GLWXHaJJ1&>fJoV8sBe#NHX(eKM5%u~Zm+^xB9J<5MEv3PcxZrX9j0< zCqgyIlCe~RdGS7~quQ*9 z2+{=CIb4MLju#-adImfRzZNtKE^Tk1x6S~i^l7P-buj=-g|=7ga@}F31HsRM2Ronn zHQ^h~ENg)Qy9kU<4tV<|LuBOR<3r4|&fx4v5`#u4v*e&!dA(O?F_~w>$3SH{WuP3} zYRXg=ZMjl;|8>FFoDT+%4BsBD@GG>`wrU}R2@s#8p&QqJw6{D~&+uW_u}yG%^^(6h z7r}?2?EYeNA~&hS=0)G+)As7>{#OflRl#o=tDmFyZ8P0s`t`0tbYhe3)j|i^(3?)c zZLF1pV38=K)nxg?j3gtAKf9e}9vZ2wZP&hxOa(X~veMmb&JN^YhXi;3PeXjupOc-a zn_TJQ8vOi$!!R;R*gAc-FM_E1u;wxVlLQi1tJ1(FE9f^Al#k@yMkcmzTUXMOlKR0P znZo=OYp#^lAR7W7BmIW#h4r zw*+zGj3|HZ1bg2JX2dd1jK#065g&zyQC>})#_D06KL*>+Nv1>rY>zi@H0|i@@B*|6 zo;wM#?CrtGsO-%8rP0v8s{^?G?AHPgL;S^x5!mW(b4$#bqJTvFz4NrRn5luZ9DRtHoT%rC zsORaP7PybB;4=7M@|tQl@$aOa*%{aMzrD}B?jsK_nixF(NNcX51|sc z;dSO7;gdHt^KL;L#>U9Q36pU=uy@87-vfYAr=|AK^nXONiAP28kC)?GRPQdVI~GzpD+NF-m?Hm2H%TC zB@m+M`;uscf`l$?26t~iY@#_}@VW5@UctdoxPSi}tU)+X?FQ;>e1woAXO2DOG?11R zgld50=MC#BRg2kv0VZf+)gp@uU>oP%MiG-)KO#wKNEA^JX?ZA*i~oeQ6);{#rS@80 zDRJW5>4{B?A~)W*Nh#_J5*bzO*5^U32UC)CBC0EoTF)+WMoUeb9!=6W^s z(|(cj*Hx9DIGJ~=asDBl(5A?qj0y^p<%`R&D=!cFhkBs|;a&F+Vad#F*qB70xa&}4 z8CgVd2<6|~m5F=75ETh3IoM$(6Lf+Z83^@+@QA>$kA9V-C9zqvj4m~p+%=SuP<)RA zKC(%NVQY&eZ$x76u3~TZ(=3nAs@F>DBROsBpZrDn@>L-67PfD<2>@u+?foYGxiFXw zMGXv(NXyG(!_hqpnUIl@5uCv$%~y&q2e)Kx-T{CMMus69!G^{#oJPz*4@wLf_fl8sE;HQU#8YskbFOU z9-i2Hxcy%u-DX_8FuX<16mff?59OX3DFB|te-C}k1385J39iS)xNsODp{3b7B;=Nc z_=CvAUiYU@KH2JG0ogGhBZaV|BObkS^v<-&_SOxffGifyc%aEeq{{-=)?C2m673^-`{cgu@AB zOu|OwY~)ygBw?pT(0+Z;c-=-Huip0lyK{YjOO<*|$>h(HY zg_?xW!O{|n+2MpxPfjiV+nQo&h>pVhaA5sY!@>)KlodXUDbR4CT`-(*naTf?k*B0u zlrMyf4ekY0X=cOrjcuA_CYFLI$~vAgb~AEE0H zVGP#eC;q2+HMO-Dy>mVTecI|M4%(yVC1q$Y7VU`wIqtDE_+mBypzm=|sQ<Q%qk)CcmLiI0cvKZ(%AaPD-#t(GHf+J z_B}BaA3QxvFO0-D^p{~R`TW^x{a@Ox-TRs#sH&<8Ik9nZabE`q`{8R`hY5WOn`4s# zf}pZ8e!IEg;0K8x1_sikorQ0>@B{~p1R5T$VZk?)r#DIp`oyc()-lO>o=_2YcRwwE zBxa)U-}7k-tf{7{jf|YRd9$%`nqlA25GBlf-I9bqLsczCx~0r^EvmP-eAyBC@d>{Z`Jeyq8JlrS`y&n0njg0@yiwFuOblN?@9B|1cu6o;b@$ z4^o*8N|=5lxXQ$)*FQ2M->4z;`nMc2xO~iaYG?@3)DUK{+9f|rB1-^_KGPlFA!7`(4?er+}+t&?%(|wLXiGDSSZ^Ti7>MF^=Z`{ znMI;;-x$_dRC-`y^0mv~XP_pdbzds@@>Nfmh5Cx)^$@@cf4u`B?UK~_NwLO09U0jj z&_c0kc#Rtbv#U^d=ROCjD`yuLQqcmk4pHWKnJeT@xAM z54yu*ik9rCeQ`ZUWTMdPbkzvVc895_i_OEx%+L|`Uj;&kbTu%DCo_}9p%R9@?#~+A z$?LK?42ayNKzgxee;L$t-{tVD4LLfkBO;W<-5vaOFRoSbyEMSG1u}8lc64PqijC2} zq~{Llf6qT9Oor9(OC9}(*1I_F9!y(1=)IoJ?m74FvJnxnijz=a!`$LV-F2l;DCXwo zDA0B|pV>gVB78v=qKll|q3qw|;c1nY@)-qwcvD!|#cK+GkAUOy@AYqYEBc+Z9bUwI zX7Zj@)BEr1Daj_L=)QsMyT{%F&dQ7LqN%Dn8X&u~6XP;fo^AK}GQm&|8t)Z;yI*5A z^5)Vd(9y0L`-_3H7=hxpBxMXoDw3j)SN&qMd$0RS?0;V*QJ>IKjr0pt9FPP1{9oiI zpPy}Xcf5KTb$#8hd>V+74qMK5;Yn+M4#HN`Rn@BBhBhFl=%*eL0)8=&_u&_%_d0nl z4ihxP30O?cZxOmcc*oF?#**u?v1f-o4pl-$iLTe#OO!?2K#rF$`B3}Y6y_&XvE;&N zD<$5CH)6<*B}M)D-}2^Xzw*AUB&oW9cy7gt&FxjL#8qIM@x0TEK&W>9_QbSG*Vt@{ z|80EYon-rr$hHNC_<5kJ`H7Rtv=xxj5@28!>XlVd=h}JLlo@Ayh^E+D&2KPpp_)$T zU_5$!y}*_x+Y&wLVi*azCUM)dpVBVR`P?`;nKn1d_8oBwal&y%OFPGlksx%j%3xPr z3XskH0u6?x3OQz~Ul0icuNioVI$8t~r;M1#3Q=bLnn$O-)wI4^pH7sOR^RXrXlo_u5~{N|V=aI4 zzYk4Cg1{eohVK$STn42a9eDYlH11**IHZ-D|3|z-K3X6gyo4z*I72JtNeeha-PBW< zP!@VE!0b<;M^E2Hg)T7;gbLbLOv?Ph-)jW4;%yR?S%S`7?_)dp8S$=nHJLP__Wyd4 zo=E+_Z<-SHFQP8<@C2^4UP6lI;`TNa)5p0I`2TyNuy(GD>b*kKhiMjs90t{*h^2u6 zpbY|jmQ>fExkMfeanjsT$IHtrxHpKHU*=0X+V9`e4?@QaicHx+k~EV{RtOUl^?Ml1 znWPHQ#gjABTuh~;c$m8#HL(7hV?UF6BGp*cAH)VC(lFR?2bX29)0s$|0C?)>rba_tK|+ zL>}cyO749d%yhhjiCh(<%RuXE)qv{F{dF~)^Ru_>Bg$`0)vh@zX=Z;++&sMgf$@m# z-|drvm+jBdK&3a@s`)jESu_bbdGH+y1IO^Orzp!xMa2>m1)L4W8EKk!XLIrIF=c58 zC>cHetk7TDD61bT6nZ-{G!QLc&Dr;*!3<^76F|bYdPp8~;*O#9z6(+RcND zbKfletKWb3?299$AS~79ssc32aL-Vi_NVYTKsnJf!A)%@IiFG>VX<+|A{-hgoI#e(j#ENls%iwqMInU zvfCcX%FY$8W+Z@397C#@Y`bF6UR;&&q(yq~ZsditDP^L%;a=jw*Egv>f*UV;F%_JPQb( zF$VWzL#YJrBBI5S@B7^B@lnv8pHw&=E(`?P-o}ts9wELQDXuqUZsvxT`oX;Vpi3#U zLYw2TjK;zwc_}+7iH~@E5GB$ww=Q+l!gdw4zlzepqjb0D7T%%e!Non>)-_MVuVzU( z$n|SxSEZ$~XT5SM&PMz9IK7jcM(r&?HV8OK$-8S#+I;oSNqOL`i6x{F=0;{P6%=A9S=2vxgzRrhtvl-^p-YN5=5 z2G{L#J*R*vyZUds@3YW#Q{PaByC=0g|B-%=w{G;|or}-B#jSMV0&6sHMP~rzmELCs&oO@f8KO2a(yYu@`{yEFjCna9b&seT!pVROz&l_Y?_bcsy zzHC$!kL}Ifi{~vZTDiKSuBV%o^&s|_sJ*m9Wfu?be~-eQ7#!9gu8mtup!ScBsx5)@ zNEB~0Prd$!Ar3O~`@!V*+S}8IGBefE=1kdd>9Mm9d}rvq&giz&J@Db0s$&T|*~QnM zX)!R$hiDQ1v*e!B)2APPSUTVP?+$$#ox6tB&_r>9ncP?dER>RJ>-@+m_a8f7Tjp>B z4PQKnxP9}cs&kp3SKZR;-|c<&XLEAwyviLNf5aw`S7JY;j1H>nJUr)q@ZbGz+>XW#BBT~n@WZ;qUrm5=qa{-7KBtzObJY%R zpm2e%#O-dKVsWpc=Kd+`pcpwWmg|r`Jv|ytI^5fgI}uJp@J4h&q0kF)u|S0i>4S@huq=vR}UvC-u@q zI}XttRJd{#)YaL=hU;RUeER7JFJno_2H$mecXOhs*dm=1=|quMM(k@>j<<^PFIpoG zHu(6&sTssymy=_BR5bdEOsw|l0g-Z!)xA$fc3_9L^^gA~tET$zmbI1n&z2QtK06?@ z`eGbT;?osQZ=em*elOBDh9;`>bbt=9&hK6wT^@*L*bsJw; zyKB9`BWYWIJOSB;VykbF2G(P8(~U{-XYA`o&D~ize9bMQQne75Of#R+q&@i|Eu@C} zd2qGFF+1F)hTiRPNvz|ytg)|pYkTABHsVd?y!`gf9KaiCm+zz=)to^wdiD;}wSDbM zmKC3%sHPAZ&#tDRslky=((&spGnuvALVvPXLAPqgGju}iXk{>6yXB2L`hVT+?@gb8 z?z;D3$#0H-?_AqC$7$BS1RPbyZLcNyZ5)$cb&r|XH~OpZB%WsfU*oN+4Zhy729rA2 zQ4o(vllXSz=u{--Kow8Q##~YzpT+29X~AHB(zw2FfR~oZdxgM?T|1om_e>hBEyv*S zU-y1^3}NOj>(dIEHYuwim(wC+OkLjfZUn%9j-8(miB5VpBm3i4Mt|RmZlC!lv%#nF+@?y#Vh=uNWOS*gT+^J)%lndCrxY9; zr5(woHy!h`de;t*4`0?!kFYM4)~|!>dfXycQBxy%fe3bnqngt>&oeRJaSj&q;*(nU z^4iMu`A3)7U$Af4!Y5Unk<~o;b?%!4iy&$A$ExuC=W*`V@8geN&?=z}_Kq~s*MB(N za*C6tvclNmI47@4Y2}QgN>Yf0ib{+|W{ZFeH4fXcBTpai+wPo?fb!7$Iq+Hlx~NkGCn>nG*2C3Cf}Nd24I( z*Y@A*`X?_NtAe_0cx;GZ13Q;u4f-dVN6)M%Fjrpv{>@KLsxt1*bqlHO5BqymFjES*wUrAa2vaRj4&-V`xLNXofH)g)gonWX-)e4!|M9$Z0TSm8hlw)SY z`GG1waq)GUxi7yc2>-AyUAul;L$b*%sUVq(WcB#=9K~t!xHrNWJMAlfE+_kpS-)BJ zcsj3&O2|z;*=GaxZ~X;x$JC|U#MEwu-`*r)n%DKIuD^FfQ~oJIQk`B#)@A!CS?RPU z;TEItA^R<>&+6L$H^mQwN%m1uJ*kzHtC*qvXt=D5DKmFkj9jcpSo_9BP3NJ_R?#t= zggQc}EUTuKQf4CeudjL8VYlhHi}Ow1#xu(`y9UcEDb(5R>_QATdVQ*>n!U3YijnPL zAbi8x#{+vRo}ERup})d>ufUP)D;3*AxY)i>`|e`4m;3jv^%i4EC0}O2=gwa;`SSX^At}@*4Ab4fLpHw7pJ@z&K{et4>Ep6fUd?QY$Fro&6VPa&w=n1m9^&z3pS=d!?2=E(aI^^67nEtx9{)36cvsB+j z^gGB?IPWpatlpYhb2ai>KKb#b^mGOyTn%(P&O>4iZhlqIf zzsSgTUyn;vsDDiFR@|s*{XBkV^ce!ePh%7o+8d){9A?yc4xW4M%M&0gDdlT!{!Ud~ zMyKMW5cj!nS!=%^yzW;};d(&ycDQG6*0d54*C?yT|Jt2yseHHBiOEn?yCrRVA&zw} zt9+c898Uh~Rpi^-9v)E^YXN}p;D2swXNGfrxY>9*XSUn+Ggc7@ffi?mdZQ)d+j5mn z?j5>BMf=pJPd`onpAC0JJbZUNP#2-woy5M*glFvuW6u6woQw6#OK!!yB~NBoZj~{W zyuBUYnx~S%#AM#o==L&)?1uIpI$d+s8l6)@je}|@Z`ZUoCT=zaLnHA~-}2w*%k;4c zc5yCS|JkI$&kr1P)D5HU?8=IYf5mSV-n981t-8>mLwQ!|iaOC>Q!TfzE%9F-yH~@5 z{mHl01jo=Q5%gIsotdEi2H$Bl&SkaWO8uj)zxFQ-$ zXq~EvYm$-a?fDf)2%;M5QIh$+_wVU_$3J{{xcc|O{~FGHaUFny4Pp8RKm0@Fd3+~Q zzh<0&6sfH7?7Eh;Q_+WXN23h!?Ly7v*Od~Qx^~%LmNjP)oqp)^;wxLRMoM$ha?@^J zIljsA#*U^C!4R3qnjEd`k#n|HpS!PX&2k8mnol1B>MOR}lqN*L?iG^jzdc8yW9YWt z`#<-&dP~9=v!%CMZ!G;!Vhi`m%xpMoGIV?Ux?HfvvELC1Om7W(Q4+Z4$WY0$^vbwR ztI1@M#=NRMfUg zj65P@5g+fa=`v*-QwjZ+*$l4?lOCG2Xh-|2F1SzAf1FFC%j5>JcT60TS&a9+wNG7Vee6J=tNoQf+5BBp z>&!O?V^za%(;V9F78^KA^uDCO&DzZ2ky~xsY4Q2aNAe$$+J4TT>qJJj&5V3s@*p`~ zImZhTG5SuWVb{)g{tq4$50I=PEBnxL8N`UfOE7P3D?> z_xEBP$GdbZE=p95id|ZKe?{`Dr_jnp7SlW~@gk{95=~Ndd4pn)Ro2(U`N>g3Fp%X)U4L;Pzg{w?P`9($??3heVt$n}!o(}oy zm0cgZ61S^Z)l$3_epHG6IsGD7go&kCM}CP$a|0*y72*-ZLS1gyI!0Pj z_(VQXK0Vz}SL0U9;mED}CyE|4-wR=8qh zWMqC)t#oZ~-=Y1rS%ii6+H@G(CTe#G6>T~$R3E`MN;{JlNU45}M<8aDrf{>?`G4tb z!XJ8rd+b6NLPj=qb^;wDsNB3sfto=8j0{CxF0 zRDb>#8QC9OBOPKHixRK2B>z$4_BcGhUGtjl<5MS8HtDqQDvrO!Gk(r5Iao(vzpBcC zrK#7=)?@nvLMK|Jgmz30)N%a?I`{sz2J8C8CA@n21J?)aN;8kzX_Bw#TUvTtvF~qX zr3l$m$rMLWRorAg?sJO8-0Pvu(!rPG;frNQ7h2p+R41M1R^%bQ5^^<`Wa3!a`BqL! zs#$!^2n^Q#{)$`OS&JswZsc3_q!5yb&(%DkTq>fu7RNF)`NVR(e(U;HaShLS(U2Id z$(^WZ88N!f#_hTrsdpqLK4q9wNnBpIlFrI@PE+12mD4!D+mB}M^ZcZU`r3{qqx~IT zY$yu$k8RDi=o@c26=vt_v`FbPOL|ziXmWn6W1pugu~iT0UWs~kDp}6*JlPmqUyGFU zz^$kQafd!TPv6Yv$bCokCGT!kkzR4ViT$L<;M4kRh(PZ?re~v~+#s~_#Krqnnuy$5 z?m_l_|8H*)U^sWP;m*(4x*SC+3e)&ZCi}mUx5*K756ve zXU`7w4P=hduHB*@J#i3nUIGrD51e7VS(a7gySPaX|44=hN~pIJ|Cgn()hvm*?7^;w zDjD&TO%GCA7y~6!V}b*#quID8-jq8iIKOv4t}d8YyD=-HvyZRBzcop+sU@`{g1#*; zGhjtOFu6JJ?QOw7SWcI7f>#jxBuGWA5PG?;!UvM9jw(4;E=TO5q zGmZ7!RlVD0G&$+GEpoac?p$vj$>8Ck-2ovc)=X=6qrU04DY(cReMz<=bmgc`RfvvX zchPhIME0^X6ED?1@#xMSsiL0jIh<9_QB-owMXcmUP4Cq2&3z}x;=66b_r7E1+%Sf>f+Gst__g2Xb(Gigk!r5rY4V-B#8$;s z;&Vqh>T>S$?ebEzp4e-wk}8$4eq*4Vh=YCaN&~STac$+&!K_qNV!XW3K5GwC-S?jh zdGMc*eVjX?G+pXr{@KwYH(4Fmp-OH~#wku8$s8uFxmBTj4)L`_WOPKM+mV=On1BvaBoc&sYy`gaW;)h^p1KZC(Ccc{WvA)W}L2u zry_!#-b# z7VCmIWexv?_lpvYVwf*!1WLCxmvij`cZ9uLekO@O7i+)e;4f1~)>>gvC6-di5MpTh zd2q$iD#P1{DunC86JMwnf4M@p`aApoQ!xi%yn&w-A8*0N&Cx#Ux%&664;Dh7B~u#O zh{+Mk2#w9z@~UZvkNTO&W;G@zQ&d^4y|LC?zhVvN$-s_}&b3kWi+gqa)_n6N>!NAi zfa6CiM}I_Q)uOUGKZ?IU@0`rFn&>Y5&!_sq?|1a$F9!ely=p&xWO?xS&J)hHn^8e> zT&1k!yTY|==ex}QfzZs6vGrtcQXppRuTI#hgO}X@XW?A?TgI%DRMJEtQ3+_WXC#QE z@RQI~r3A(2cyEzYQm>cYMM3E}Z)vYZ@De?z8561=us?2f0$;pU+|8>ilgM|I^Twu3MY zemi<`qOkDmoNuT=#PWJK|I2?9zf5+#j_p{l{_^rpv06Z;iKes{+d8ta$+Why06_=q zo|%cUxbQ$dDXGTc)%Ngr{^)*A3*`UD2jop@Va*Vo_A z3RR2M-BT_4`)w1KWCj;)X<6B+TzBg8s>+1p*zovQm`+@2Y(EcA=6jp~tq)?Zqf zwqF>E$*&|iFOKDOKV*BCGaj#)kbdLS&J+ua{_+}(Q{2vJhhT05;$(48`|05*Ab5ES zfc=U9^q@(jCk5~jl6e{X*`&M4eUJIaWq`x(`KqED90ldv=a>IJ*rH~d9|f&DhhPVQ z{e7N2yC!#jP`nuo*S|il$61aZRR9-(j0MK-i0uZ*!JaK{3tk~1$(UCIj$j1yujIqD zcrzaKV*fr4OH52Wf!I^4*!@H*E!o?fxg^yz9gi(rx5B@bVF(?Dl z=|PB66)8@(K?~!U_82goA}DsDNq9Urh~pYoG6%!7=@^K~M%Se5?ERNX0@xLI+EQ&y zduG?m%hd}C6*TZ(U}d$8j5z1%y@Mv^)Zz?zo2moFJ|!z-V_`$ZhI&0yJG;QfVK47U zAu+K(Qn(yD-zW`SY@dBMs2bBTd$p;1&!qcOQqigYJ(*VQAzxVpdgN`3D^iFbEUG1( z64b(yriZ#2lhzZsK`KhhkC^F+iiWWP6(TD$^96#jy35WwR~@_+rJxg*P!~SJMSicA zmvV47__wA(4nCBW*?usrS&CwxP@qNQb@~3{>*AtGj@Y3} zfwTtReWvY+ilI)2KTYl{n^@`E{{D4i!anEbxqXEm$r%G*t}QKxt{By+%5&sgls}fu z*qK4SJnNFlci~$Bjc60!Qo*KN>MDQTQB(Gi6IEGBhF{&KyY_^>J7wZb{Gho*HF#(b zEPj|%^O&_Da1wu1Jm>@cUC1OfNm;-+a)Wf~-FDm3Q!mIBjyEfg$M6meIAMrEom{sUlFj8I1JUS~GkDQsSNoHWNw%IlFdB(SInW4d}5T zzir6E&E1*t`NHFLJ9e9M=VT23v^wUVY_;ID-5MJ!ju$&?lYmwV9_q()+Wmiie79#$ zE*qQni7PCfW_{DVw5?4nzdGmDW;nB((zO@C7A)D8>;yC&>(Qf}S5hi;yef3$;XG`& zuD?}pDPiZ*C6mw)uV#`Rl`npd*`mjTCqR82-_ySjiR!Hazy9SY?Y7P(>CpUPd0zU= zQhH;G<}opVa?bUb_Wj|y=VzIJ54}cVuU@cht|mGQ=gjjvmU{Miw24#fJ}!J_?(KF? zK+~+C^WKmRnv5FM5tzgP8K*scGc247f}1UK`865fJV*e#*tHQNOmZ0O#z7?IW`?iG zv{)uxd+(O<|9{WYf8A5!>;19Yk~W^#lK@%};TN{v$!nK`T9`H%*D`+6nG_6tx?fQ- z!-1D=eHS_JK zPu7bqgEWRh;=X@nI5sxD@a#B=eC2}ar#cdoKgF?s6KmcKy6iur9yU?po^k7WUC3;( z?&q0|gG&XI?rjB1ksUT6W^GLmr-&1@sQS#g!>-s^ldX2bLD#7m*Zb>OE{Q>=sTzJO zkanAofI8*YEn7HmeB2?@W6T{02_(Wux4&~GqsMR!Vf+VzEGXW}kO})yt>s`}COj>w z8oVEI5P^qP&3T&V>Ob%XWN*j<3%MIBpkZh5!KeycImwvQ_H!$t0lQo(?f%msRhi*q zIHlt*hGgcd&}u01PwYgH#bd@elR+6Tw$+$4Olvp4l6kIERY^&v3p=WJY)`9uL2UB= zvREe^hj(ab3dV{u`5JZ7^s(c|WT*mq%(LN7A|WOhiy>SvWDdjNczStp-Ru;OijEFY zk059d@qZ9}Y#>p^Og*vdDuot}P~tz+J7V0L{%K?mO{uN(wCudj-?Iwl`|0QfY-NaR zwdd!;XKmchu-A9iFtd%g4g}4>*Ds!$nmSzb;$CfSEwO?SXJWr$$d#9g+e^TGV4M|E zhg^zAJ|_mTpC&hWw~Z;u%09yn6;Op26Tft+9*9D#MipHa*7)gmTe!JuOvqYxzWD=W z&2b>GCGJwxeRueW4Vi2baRVX_bSvAnI*|>Xp^^IWr8>vv6=oq4TaS}AKk(0RH0$Vq(&=j6HLXz7W65 zuJS7KtL?|92M7s6+9!nk8-fETu*sS)E*dk5t>3tPKB%A@;*8@b}yd!2XX!2by>?;++i7TTrmmgWd&4-`yIsM91g$7AO|jnw3L-0X_wm20_dzhPJ!Ri6l%P{GHspO7#+SI@m%? zVzfdx!^RQzNG7BB9yW3WajcnHYIrIl{x0^z7x6EQaCyc!=tUMhsf-10)3LlSw}1vV z(EE;Q`l&`W(;*OGH4&K-I9-cA+~GMahw&DO{|sWzT%Vh<TIie)FPgITSe^`sKpcdF|AbtVIvnQ8mn~orQ`WyLyfSp_n#REwUXryST3z5d74G#zckNIXa{EJQad^z&Mi> z4X%L9xN%`jA{l_Ml=xd{>=}@9tW+~ig27DSjg0Ijvut2RG?IkO1%VOh_}EVyB&p{r z;qG!d@~3KD8}+3jWK$r0+7hB{Ztue(;Wlq|oo{cGdkE&Y z?Rz%@DDo46IPpEwMBcp=NtaX4LHqHagahfXAxO~(%EPIdHq%VnZGt3l2*tu(mGzlt z=r7H*%N2Aj(QbAN83$|aLg>o;zOm2QbzkiI7mS%j+1hm@i07Y6EaaNj6W-t zC@CwCfO0_2*|{JbsA6z*t)>>RCge~b;S5DBa$+F5SVUDe>%4h^`K3JnNYvJW!H(^>Al4~JIj zu*=G<%ld`f-NCzpf1zKnqIws=EyI<2hgus}=ecf(zEx0#&Q_Nb)qqt;ao`y_kW|xWPMo{j9dBL~U9W*U5tm-| zen3D5iIv4`SJ2RCKOGH9vRvyi19|e8dm`-Ak1BZwg1FUFm`pO&aCn12Ly=cmQdFd0 z9d;HDO+i~b3ZeD@Pq_*X7zV|M!Q%qoJmN%x)LyoZ$Rh}H&End`cX9y#UcGXPsnY=2?{ z-?Pl^g29>_GYCKy2`%C2v9_jx3`mCQp*-$!pfLJcu`pq%@b*1Qu!XHZu74TB#=;^C zdh(vHVP|h!B2_WKY%`>OOavw@`7%sMeED!pLT$bO8H;IaF}yMYV zj_pe5i>*L?6+5JFx|Lw=K;djtdXZyY^*j`wX}ieAP^9FlL=6G53qt&?bxP=fGmm*v-EkcDVLzHV4+B%l|tu&#;cVp1$ z&k+O-df%NvCT0%~x_pho<%N-H7^bF)&roVuwB#YB>&qu}$;8yP7%}U>uz(^^ALM%M z8a;@Iz737qz5SCW{d5c$&N4V=UN!MPDvH?my>nB*Np118x8smUA!d?<3U_}grZd$; z^rJBeg!U9j`*;`%p}I=MQF;9&5Gx^2wFzwBdT@Ok+Pc+u6_u2RGnzE&;;B+b>b7@O ze-d{X@mh5V!Z8_k`H}>CiH5@%SLl9({CetjPvtBQ3hp(?P$l=^#|iLf8*2S*k_m9j z;4UE|Og{8PAOa<^MRGUsTGv0;6Yg-xjn3qYoiXT&7H~fzN&|RgMH!h+i{xT3*GzHv;;3TN;v~oCLpjW{q#xS%H;a>2+#(G7qffbZs6Qz-EKFKF=Q{w zWhrV*yT!QFAY&na9|9$PvvzP2jiqS=Re9SA;oIxol!k=rwjTFjiA_ zq08w-NpImLJ36BZ$K%3vQZG*>XfBD1+@mnI8pZE96?T30J?DaMg$Bu(scPWMznd72 zPfc3CC+8V-=vdT9=qbnVaH0;MVu3Iv$@-v){X~E@E%#0ewtodVz8%STgq^l9`Ty&)zKZ>&7qHj3i}3 zdzcMwjPRDx3yjj6{&6|`zAp2DiARG$13d2MXg;a!_pISjDoBg&Ieorr+wQ%s3YrL?}sn=qe`OLgn!nOLk`4NV;DVn$V%_L~+rC1>2%7M|`mU2kU zX>q0jfoi`+!O-iDq#@+B$@w#?B3h?Tp8OtCh#W z7FZ;lriGw0=DiowED&XnS#U5jmoRT=@oY26W$$)*e%4c37pFg)H^zXIpOLnln zHKm}o6lq7{^7Ju`km>&HgrRWq_d7p5Nh_-iXFgg#yokkMwJs9z5|N!^wbUKI7HMdKV`$*i1d6eWXfOyH ziq&fSsrTKI35)x`k{jFLQOR)7;4L0wQ<1kbU&@NysNOCi^Su zKuPr?&?G00#K&^zD*4U2FDJwWYq`Ldf~8WyT3CFK2DO z=8nE9bL6`Mex#10`IN$3#^mKo+v*J+Im%F{mz-UJ6;kGd%0+jfalvzHWYwzxaovT|8(T@B|Q*OkvccDR9 z)6S}AFPDM0{nTLBt{D@3!+8Yu?(W;(|J(07w|Iq;l9Gsa#%gP*gSY=eA`s5-Tv(dr zhKv>?9lz>6A8+rupi?=2W}Nv^GHv3`C5_iTKPj_3Jk>;BcOM&LBUg(4Uy1qe!ZDn- z#a0Sq!&TY+dpx1mjU8E7S_K))oQ@8Iu@FU9)^0 zS58l%$Sf2(Ae{S(TNj3RxGgiKY93j>G~vd$phJ;#C0hSngJSysS0&IcLNp5tQme;Ea%0_s)TC-U<0OB)m3 zz11u!ZJZm?X}R)d1ZG=kU>&Kr{XSCThQ>zwV7lX1g@uE80u4rV+5N{xrD=w)72kBR zh6C)hFnQzp#~&#yV$_eA21AEtdQ&EET98Bn-9+ee9zWj8TRY;2S{zP*V?PZwwLNJO zv{xSV{M?-ZOAj7CtcB+t$}CGL>#HT$Phq*$VG>fn2S2Sz1Y6VSl+`FwRv2^)^5acz z%U!v5#+$L>&-p+{;?3gYI)h4TGKyvCd>jzqd8VPMEF&x1Wx;_oUa|?ilQC7<2rSZv z0+!c_z1`3e*}3lDTo6_ulc#$ERhQg4=unmjOzDs%H-9qfmqg(j=>(G)VJtba zI@b~QXN=nOLhp+oxbn3pJ#f{Mt{;8#dznwUPv#`$H5iba9#FpwHjb+7*BeW}-}P&y zr7&(aJIT%6Xj;O5=$4%es_RpHl^;L;WiWPi!=jLffxRi@5~;w;{LKm}9)8cc5jyMI zsh9IAgBiMwB^^vB+uPsKYZx!IJZq)SBDeA9QV4K64Ick^Sa$v=3GtOHrd9s(cr{HmMF0#%|{abC;N`H2+8Yfoo;=oW1#v_a*3<|Cl=tj zzy5>8bF8tkEc+j=d$qiLGw*$$M(4U&^S?E#O5T@zo|tv4nsuz~3bHW%{soes{j}51 z6KL(1G{D!-8CR)hsXvd3f!FNg3}5eKiO5({6ir^Yem#3T5T`w=+2&Coev1GF*dSyF zl%8zmVetH!*oV=oAZ%P-Xeu0jz|&qGn4r|czZW|w@L|*^Pvmb@8kKFnM zG4dQ!V`Kfkhc7EBp7#=gP?r_NgI*Lwd^1KQetPEoH3(c=-}gyR@y)UZv7_ zoX5(dI>dGCSe22FwBf!BCtXs!?`Auo!kTf;;+=WFb2OEmi^3F1UIpxAiiOTjFOZVY z>=8nz!Czq=dycnbO>Z?SCEx}iRktItubFXmCG*l!RRf3gH295&5#2SQslbJ4(+ni` z^}Wk@dqfoqEZ4Usdqf&Up)>dUqf`y1ibsAK%V+}`@0FZCs`k1(!VE1A#(S+#vwM@% z)6=(9=$p9M*vxLJfN#~WRX+VJ{%C2yQ`;|{XTecN*9u+rqfKTBtQNDvD!w`?AI(_p zQ;6oo)N=`2H)DT?WG^qTGQkcMe^_@)MX{Ii$l-d5C;wv=3;Id_zMuQx}hF7UZ2fH)?GFtTC^!LZ)-l<5w5<1)z~Mukb;~w7L0m znphw(2j<{_=9RKzdn5ijyXk5+I<(KHd}f!Pd3n76xI*c8M5zVhQre83o*wd9ry8d2 zM@pN0k`+Zv8sdFqJEnW9A*wNqgCp8zlo6T7gnb_#7PemywCVP!5KJLGjYUc8a1TPF zbf-mY{(tVryY~J7@R7xe;v8~0&fO%{_sxK7Tf)ijvzQj&?yQ zWkqk}>Ws3xb`j)uA{$DtCtyA`^G z<~MI1!M=}2+!{FL(??5X4HnDy1Ax&$pI1~!NXV@K%%lFJlSsDxMlJ(0p)>J^;b+sA z?kOoLV$)qX*epy;QRNoKq?`uTYl>UIR0SQbPq8?*P6UET>}duk?-UNRxReyP7zN59 z2~-D{LqT;V59;IwqC|sCNA-!|j6bNuFZbKIQP3OI`uY0mci!Cn<=7Uclxu?hJA=@NoI*#z&n_92`?SrXZ{NPfD&(N> z_grCA0Bp`;cMEF4c^P|2LRop1sV~Y<;x>&W=NZSjmtuc5*It3JIJ$dW!-lQtaZrgM zH@1+_GDUF$mP4D**OEOhU2mray1~5@6Po?mGC~v-;3Uv{Dy!-2?EKvM4`EMKcGIEF zWay^EdZFZD%qyz=(AkNO6a*B5=&iXG5ZIf=M|+c0Gvpxe>ajqiWQgSGrd9ZP>x+uc zgQv3=5#_cAd42PXXKPC1YBQJyA8C0QK8}AB`U}E|1yMpvLC0*mdgQ_LzPLdha#Rp# z5p+F&e8#ZxXxpC~Zlitme98$qxweM$64>I8iyg7Fu#iXBla;c=3Y?zYLyO>O_t=># zj*jdLX`%VZOC?7G_R>;PDnu`tZUFCSkw)9AIRHn%v#nd-ROsUJ;&owRp%_&Wf@r6y znhV-|N+^#CEsmb@T0VPwqhfApvLXp(piA-FO;JebzVSXW@n}A5U};4~#(CQ!h@){2 zrA?`utKYo&Qudt|O0r_tooa@|?h9yk#CP0W2$TiAPYpp z;ADlxVD$knp)+R+ub1%i^1@V22fP?w-6>%Y?JXKu1(%<=45qj&CA@q8evCLhtDiUL zz^1Dm&p?Z8=#TXqn~z6y`(&685jA%hycUlAyVLdSif`zD1==bftYt_JGxZ(=&;(_q zWUiq?)bD#CHScqJacT(Uo3wkTgU`5V0Ide(q4k4B#2mvQ)#s3JsKy0e^fI40bHe0m8l>IG~@_}QA|8y<#HJu;C|;sL?jmoif}!|iA>{x{{FELyUH(rFxYr?JYS*FAiIAj z4+1ui)*^Nm7xkLnnutPSGZ^sJ$nNOu!mW8L%Zt=2>n^CO1_-TuxA0o_j1Qtt@?`Z{ z`nilhRtyIYEn9hEVb`J_l*;NscPpN--#-8P5DG;{+e_-|ysmHb!3=xINtJ`AQ4CGf zsi;Mz)Elr3>q7VhRsn%4(A_!Qwr<@zPFVPaqQTzYNTNm;d9oJK{Mpb;_!*BLMcS(4d>#f}vXBROLwC0{~NHGjHM?eK$O zl!jj#G$k9ql9rKq+9DoBoFBuK{Al>ev=U&vnt+;#M9SP^B!J>PkApySJ91tvxf3Uk z9g`+#wlrLptj=G!z=pCNfeQQhu^Jq`;h-ax4CYfrrPu54`jhb@HIoM<$NhDJ21a#`_QPPbk9?n132?n+z zL{JSqe$geA?v8$Se8eE_dGO#tq8o%VG68~w7#3^K^RW2iNkzXn7VuVBKa`b85UYG= z^RA=q1NOHDiOEXnY6KP$!$Cj{dBc@_pnbdI(?%+?e|U6w#yhoYIL^ zNz=hX2g527`4a*NuSi*Nf(7$g#n)?5smm3B&xq>GzpO-vjgjT2gd)j{WjF}}=4;UM zDoQoOfC+rXM1u?wY-^!Qq3pUbE36EUid?}dVMIkks!zzN0_Fz*GVw`Vc7Pp{QPQSVq&N|aRmmALDw7Mp|5Ru zghY!(Ekc=T^z3L`k#g39%1^E`?Uvv(qOc-!embX*I%8&1UW1equUS}-|9%x{gSYKn zgII)$fgw5HVOBM-YMQD4{rmS7O4|}+;rdY)4KJq>$H9pN8Erzz?OLm`Rz-BJ>pYnx zK-R0BJ_cVyG@Q;)&dtvcf!h9M%g)h5qV6(4N~2U~{ED4}Be}U06SrY!*9*=xYauMs zi7R0V+B-Ztdd1++H^W!aR4}))YCwHj@6{M?h7aZcI17kh65Y)cabHyZk*sLg4>1un z_67J{$=9I>8-QSCnZ69Sh_dfJ0$w9m^6oV)k4YjrtBR2Nibh$xG~EbY) zQiIs5d`8F+1$unii|ag!_s`U?69sfdPE=GhRf}k^2L&0WO>A$bC?lrY6l4YYEvxhM z?e*urbZyzZIo0O$4}0foe*fV^);egyWiWM=JlU553(UsKT54dn4H!DC+!2fGu`w|* z*d(G2GW=UWunQ}rl>E;{1U(qcAQ4F=SYeHKkXGC=R|oKi5>Cd^_80(Z?fZO`%Q=j% z)FT(S0>nZj7p^WI<;d*o`Oi-C@eQYzFx25#ms%R9Oe~_^pofEKZq1SJ76b+15YRSa zR4=D~_+kIt;-Voi2#jt@2bPzYRbO8HcO%7KJ=q3n=#rvFqC`Zrfqxl%a#Hvk*6tYB ze61&AACMXiMlSji#eUq$kxU~=+UP$Lm~otD_2i}X>()&H_Zo+uMbu*}3yZWtKiQ+% z{jv73ziNLC7mbV(uWM=b`FlnzjE@iNUpr3#37XyDk$@s@KwywoR_EJmPgMiUZV1T@ zf;JAvLg(u;!V=Yd`wXm`QaEEBHg6z@#r85{SE4@GfaDOK_b@$LlgMV+t@9v1gKAy) z0TH)Y6H<;3wJxMEAcH!EtdKwk=2#ASwh-AJQ4;}B#pV-2rh%%^V^-q`fa%zI)JcBc z#|%JRhQ3!O0rMab&L3_h;V>jX9){?v;K<5E_dvyQ5SW_=bO+MWx`h3fz`iSbY-4UN z2Ty`!jfKXi_vK*98QENGW67Y?vVdPHK#rSe;(+584P*q`U^CY+fNdc-%OELjXKQ=W z^W>>hlKt^2Y0;8e=xH^eLotP{k5x#heRQ{lL@Z51hM_WsBZ^}oTy!2;HFeQ74&M5= zZ^N4-$DB#Cq_V%6-|}Qcz6O8!x)zl8XE1vU_5Z2wK!WtaIC`k`owV)R?>RoOaTV6HwDSckB>?s zPO(HKOZ@&||IR&o;^21_Y(wCN?z*{&doIjQn7&%F->G-wMkM5wSsn9`H5*_vpfd|buj?UfP(dfmSEr5SQ07#Tt>~+?FZtqpfOUxawwppO@^qG8AST?i;D^9 z;ZrM~I64YZvU;Q|I3sF%7lohH?$lq0$d^BpH^HGYCb{L5ZucS3qST0hq0C zU%$!<3%`-f{9uQxpvMYKbu6M^^?Z9pC=ub?WYCgp04iq7F`H04ApBymkdrF(+n*s0 zgXbgSMV9^h!#?|5GSwl?vG zjk0v#R@rjKCh24upwC>8UF5&8flPQB{O<7tt|faQB%xXWg(xMlh4c>yXT`7UQS}4i z;PuZ=L!@^yh~FA^o(6hMj3~J)Jx}2KGBe|wnQ4>3PaRKTA!dy2>tpQ*H;z?SZv7g6 z5(|#{RLj(Eg#Uzt1DM>ft|#o<(_hvAdq$Wkt03U&`Cb38y+`kgl7Ycw;y4*u-%9|O zc=`Dg;K~hZBOee4tzSIfvz%jOd}PGXW5*u~>;6+(+au(d1(YO*-<&OPZ{KQRjg0bd zYU*gX0)1>5aY@Mxo6|a}-U4Kwo6*mRA=0E)fVv30T&X}60GXE-0(f+p#5+Z0XS{Fz zu;j$QWK2-y=q0V(Mem^&Z+$H;<)QM?v)g2;#O zlPA)5d)CYF{wl~2mkRUzbJHfa!-qv-&0pCZ@r;xT=3~Jhkyy^4a3gb;p3n05kXnIb zHs&bUTUU_n5+D}Ig~jO+<*sHjh2Pag;&Lz7qYhK_;RDgOwoW)WjC;e2B(9HaFiiqx zb!50U>JhM;`t>xscD=wpAE}R%FBj5A6;`u4vcvKpx0@CnL;`WFiqG*6sbpIej7TXV-Foguz5GWQDfY_S$ z0&GkSNwIww-0((d)&0qw=bHZdjFBoU`%_a>Q)LbD0K|t?4GAo?pvXT(0J02lwihE_ zDw2Zp@OK1uh|g;H#>Kf&v`r%oA4Fp};*CCck^;Kg2DV%g-JEowRfvKVA2dQ95X{NQ zDk8DmY)6j7dPZ!xx^=aPt01ejk;0o%J5%r4z{R!iCL^06*m?0P+uN^^k(m%KhyY=U zKHeLL$0NW^=p`YM0U|Vnu&`ZS;egl2;uV@(ACB4{BjKsKIIrJ2SY!PdFi+wmtbGX88P`Dnd-v`U-IuG}ck0%rD*go-s$H5gp!>~7%w{m8bXN8p= z?ycRR>z3a|p!jDDg7&c}kec(kXk-}Hzx)-ujsEwR5re^{u=~++^*;5}o%m@Ln*V)~ zzcxC#_5j2`U8n!Ys1ZMs@mT$lt3e-z`;>8pjJ^#3C&#&$nT6$(o*Iq~eHCrd9`qEu zbn7!sH68BVrn`)UZQE=ukRplP6Ug8_+L?&7vGudC;xo|oTZSHkoXQP%rm9;Rp?(M) zUd#gq5xk{Bxq+V7{2w?97HbF0RFOAbN6O{1`v(gT*&FJhu~piRatG8k==m)~Jt?7U zih!T+0c5Upk~n$<%M6ex7tjTjhZi5CUnACl+1mN**%U~Yt-Gh>fyi!7SrDYnz|dH*O!yV6mv87Wt~N@U7YXsGONg^2WiVyCYlwNpeCyjNaM zp@XE3G~%Vr&-2K-=eKe5*ehtS0No{Q`N)x#!OeeFI^jI))LTtMBHh<&+$x`4W>>hu*@ znn;BG5}v*s>hS=4DWiT##3SkGGZR%c9D4$E2|Q;EavEjTQEXQ^2r6(fk*E5Pdz=lP2T5R=XiCXo)(wIXHz zHZ#+Rlrsa9lfw^&R z?wvb>fTqC0D_iGqFDgPKteU>+tgIz7c=6Kfn;c}ZqIkf zL@8W$*cpzz5o+p8V#t4*5GaU~2rv$cZW+#VU7Ls*6BJ*tCFK#eQSICrfu^@15VCz| z_H4a8lI@u|$v}KJR*L{ME-j3t zGL8nE9TeZiP;5;ZFIY6etM}2bEd9<==s5ohy|@Y!lrn?6CJDd?PP`9ahiTzbH1;`y zJYyo2W{iU#C*oBvL>Mp7&+r-IZ&IrIS%QDFdv%Yy`UGJG389A!Y_Au~DDMJUppR~% zJz!g?NJnF4@>9eIPvXS^XLyQHi_#jZZ5W9dLNRo8ER}$0!e+%ZRK~;-SXyMGnB_P* zMJya)$6yO3J>!k29I#1=nFqx7wA0Ltj7RVuQ8<;smrY}zc=sG-_d+m^@`_g32w?&PRLYQgK_i{Xk!z{@3oJ z)u1hT)`}4S13Ee#m}G*L!=6yY)vGy(TA7MtGEW3VQVl_i4%936@EM1hL_*CRdwSRd z?O~$qctWeVnMJ&;ueVnZaDM`Z>HYk<{%So2VH+`eHw|QRJR+wB3^QDt{-?9lHo0_x z0cH9QA_YJc;a_gGq?>Qt#=W#O;nGBaT_vBNEQ(;v#rKmz+JqG~unjpoY+`Oa7SF$4j!jxUD>OKY>1>mVwG(Q4p z;)M_idsL-Z=5nzYhWh*y#Vr*s8Zi-+4b6A$4L844Y4P zixHyt;*p9S`p{)&FWp?J5}&#SeQg$%;vVJY;t3l3ZskI^-eL z(+vS(4K9i`n@^h#3f{$w&1|n;NvLs32WgGkEed~oOTBp(*i(zap&>Cx4~VY2ab(N* z<1au)Nx`E6z_Yh(2{!w)nbW7MYHHpLSNL$}v1ah-y2(3te#xB4-On2hDbcy{kM{&< z!D(au3<$z7aEe-_&fd>)bHP+zq`%hjgM80iiG{WXZGyvvuz;j99%rUZa& zqv&=W6_q;x=V56a9Y6Y!{s!Ito&wm<%8);}0i{~WpyQ4isyN%fU>WcR?9Ih>#JWLx zcch7yVDrRy>MQN#fRF%9BsA^*5N8s2N)dH&V(P93AeD@o{tj zgoMiP5Mv@Cpi!NnyZ(ll7?(k7wAI(Ze)z4{(yeDHyw8|DTiTtme}5HPQX}AsAN5Fe zQ7Kca$*?AB&w>L2OV=O!ip^Uw;h-n8x?m z_}HwA`!;U-?WU8>*Q3IPILO`vL+lVFi#iPG?rB}#LwQ{u_c+vFwyt@J@mEvy8A z9fi4QU`~tP$fuf=F2gA_A#9_dvxPh==;!?F_-MEe@EjHdctO_ZxM9aCafmvDDBgh$ zSBV@&kO3D6QvFbgw!RdA<<+?x@%TNQg|`H5I=+3OirrfYo%$V|){Ez=lR5~c2a>M> zvv&Mil2N{Mj(ivxgrbTHwesW{z88I+lbLVPGd-F+@oDSM`ocm6CLaf*Fgo60=j2rL z?$txWDvu)@)y}Yw^e!1cclLAtp3pxzz&TAn4z$`jZX7=th4g}hqZv&&NtCT2lUZD1 zh&1IiHkI<062wA`hKs=an&AY3o`Slj2;#(t<9l4&b=m+2sIrf!WD-dafRsgml2vTM z9txp_i*SSt={nI}4^y5zd9ozI_OO=w5}5aa2$a9#dsSWiyWMVWzU!Y`sw^pl1c0K?Aarxo2CL9%)fPwNpN>zHWuRv zs5?X@YXL3ihrO=F3Krd54FHKQ^y0a5mM&dN88i;~(shp!+8|rcux-5(JO&29PvFu5 z;$%VvRx6h#3gF|34VU6e9+7fHyP}|n#2JO^Uyv~auUaB_X#o@)vOvYlo?~Qu4PsZ! z;+?x;E3;Uvu(zefkj^8Db#TPQZ6%z8_e$vcAQ9yzL-5*_z-DIkpx41)AfC4k7#Q~6 zVzK6IT$&p;II9)=#;A!wKr#vD+|FH4xJ%t?Ic@ZGKqxEeGu39uCHjpmGxnkQE6jOubarPbhAZ+RMY^3}OJ zXF8)d*}eA~${>H2nz}AObWwAEyxgfKJTELf3g#X@&8US;G^^(^eKCy_bj-)O1(k6I z%|eoIaAj8;itA@ZfTmnrN61c)f{T*;S#*A(r)=xaPw13Q7I?e<6cp=MIo-TQPhaGY zc8NSRk&%%B?&d9f@4|%(suvZ^`v(UrkVo;N!iV~!sHP^h(xood+S+S=fR7KWO95Cj zb-^m}8$Rvs>FVNS_T}iH6a-@%2@F-gD+>@Dw;#Y#xg=2vtn-=pb63P&KjYGQ$tpml zlh;3gBQ%4XHv4=Is-!O5veL6?pkrMP4xtzVt=Hl@^qH-dp03Fb1YQg#gRc&mbd(Ce z_mD2*Zf=3VBEdHhyKSRqIq2hv3_bP|`J@QMqo(^H1EKtfct{9`1XmaEF5u_4sEmD* zh_xnB6{}bOT-@sTM{FNx0rh>(Ac;4=W^j^m3MhcTK)c2zqMuQH2zuB+BckM4Qdn4q z#NfD8xbQh&-+bI&Wf%P!8h@3PmdYr7mrcpa)V;cMYzio=pTqzBR);CLI41$uCY~KT zcBmt9J5)di*t<=b6@1JY=gg5>CL^C!Aa(D=ACCd9Qscebh}hN8P{YVVg_JAua&qmHu+Tv?(iH_3k!16mq~#K*i3oRG!BXAf9o-wd8OJWe6!i zF+m0a?rbA`MCHa@6vcNvB85l5Z2gflHmsA4W;VsAZaTI|t59EPZAm#%RRDS>Q}DE( z+J|LCnv>$OKj&g!FkYG9D^9$hT3I`1OJ96m)d}SaWG<+MdF3>;FwK_%w3b*?h0%^x zp_aTZDKjL*a-B!4ZWuk7xn?$YtqwMt;?szQ`~Q4aSSYEqKKr__SL*v(aqYFIkhLk+ zM-_caUrB|5nZvO{sZ;44&6b>^4PQ*-WI~rDdI4s9u>TGLQjrgei$eq*j~D=DfG;-X}X7T4;%DUQ(H>*9uQa5mD=g7*`m;nftdFgjbV-DPC9lEwn81$FpC(ijHp z4ki-!retKsBk^IjVWsDSCfMq2*`(eA``HbOh-yO=arRx6YoXZ%C6?V#AhsX5LVP{S zDI>3w=|D9Aw7d}Y$>Z{~FG5DT5zsBq8fbIg$rHH+UmkDgSezo7J()$UQs${9LsAxi zrWKu;^^7`szrEU&-Zg z&ieZ9#?d3TSmS-4^zOdWqO)Ju;lxf-0n12YkTU5d*J=znytNq88y``WHh#H{amX>) z=!vQW@>xxzK!D;=&sOP0Z7~tMD`q2JD?S`j=nAYP{$yY|=X;+T1YB}QGDE7BzdDNf zr+l2#5r9Ng{$iCgkA}1rhrhEezq|JI9PPn&mMXKyMU6L5#5_mF&0hq<59o#BsX;AM zoejR12@GSlvWqn|k)Hh8Dk_K7|B;6Nol6rgkYNch2%UorV0Pc@JmsQhoJ9*J5_U1w zn@r@OM?&UwDTgy`;q3|?__)NwqLbk~n$0g5iIwuts|f6;pF4j{5>y<|0RC=4vxWLs zvO`1}bK{wB?=p477|8sifAzRds4$owVVmP7*4EaL0&BU9zAuBj(p_Y{{-TY#?7XKP z3ks@7&{Q=RhHf!+^fTr6YDBTbaAZ;&`eKw8P}Y(rSxYRo>rRKup+w{Ta=VX`bDWtS zQ_3%KePC44*=v58tC25}S(*c66-P(x935HU>K*DWQ;!4p+HCvgFS4jeP7~+^dbUo$ zbwTX>jB^ubcdkr>kTjTW42~bzBBW!X=tQRQ>ZzhFyU8BiR;;Uu!Xlluv7F}C;lte~ zGxC+;+k&$u020z~39DwJ=?nTL3DJPq?4l*ki1bxePMQs zha8wz@lNd>1nhw4NCrmq@Mbr2r(h%$N|cv#Q|KBWpXCVg*pP83Px*?SSBWSm*t{~y z#9~&=bw9D{oUe|*SkPK83%u=r;r%C97?1i!E>C-2n8v_eDn*9?A=Lyi$|)Y(q?6x^ z;qR3S*!B6J0-<}!E65e!ut6;@Yv4+757I828^=+iC{AZnMpzd%;E&6xp?@l0sEy2+ zfT2k^6t*S^uo|BL&obYw*97;B|3SEAtZg z-*$KA&p&T8L!Hz3+6B%x^C1aO6*RTvbw-Av4gh~AwsqrzQs9dEZUsKZ2$+h>(Fbp? z+fLRQm#15>DI$jo$eS~3lB$Ldz>WcO{@_MbrsR`T`ADTu_V4?fHGUP-T^lcTv9AWe zjE~5696^No<$Htz(a0kSYFUy|h6D6LsQpYuQ6RI3V#$}42wMV(xOxO^qX z>N8On3cwn60_>5HmQ-isOmMHOmel|UGMiuaIo0z~GiJ;nj$o(3tD@lD^P8)fuVwZmb;P5-Vz)^0?p?byv-+Saj6~Pxe%wXs zr}Sg1M*q!<&rC~;Ag#(U*0Pw=Q8za?HH`Pmm-GrZO=zUNqwFjZyk;6we!ZK4y8)P3 zELJ0b_`&%@^M=CAmCJ(UovWXxRG(t)&Yc*~+&yv_unQ{iBc==YrzEO_k$1225mnWb z{X125cV93J4K(>Hur#7^)QSQo8uy72LoOu~wY!G+OD>LV0{ z3Rsdhg0CQf-wPHtFOFHhI^?!8n-35*yr10}?GQ_f=`(cU$marQ3WE)u3FEaH?)+@! zd+k7cv7Z!2YOm&mWeFfgl!Vw|KeNEn1?#=n;wUw@?iQJ&u~A1}O-K*?FM;Ll1@2`x zcND&y+ICjUCL4E{dr_0Svz1cNhza`DH^Ttm8|c95PVKqnI6R0{(7AZrN6c_JP_S2a zSO?HdFuSr)Q74)W6@^UKTC`}<-CjG;Mg$_ubUiIBj91!{lF`(`VrKPS_9f0f1Cv_WZDSQz}o8~~>P6t9lPq^sW-i*>@Ut_l~E*y|1d4EPg~ zHQRp95|jW{uLp(ZKz9T6;*xQ+<-B-*ayK%WkVoG?gQ8oHbmvL9wmQ9!!okchVa`GS zRwdH@!;a9-nhZfC$j2U5dJS$Ld04~q1KA8aA+nd0QSx5QFWUF>0Ai1Qf zzFvpA*@MSGh4U#a^zG0}yJGk1iVuz#DaMX0RV*hx%J*t5vFuKxFTkPg*`l4zK=O@- zKc#Ta_yUKmkI?&|5F?s`jArWR?qn$uag-#CUiT^C{nVSuwOLBBZjMEgZv?my*cpT( z8b}d_`FXhlho3rKJd3<&<{DeP9H<-a{Fsfh{ zW--`6k*Z28!Sta+WPMU9o<+D0^?C>-0_q}rC@Kud(Scfejs*^g=URG*#bR>&H7>uf z20Yh``$x#ONmcqexJ$Btf{WR@%wx9L<9foC%pVY58RcXb3(E_0EE^J^ff=BE44oXG z;1Cq%oxqjFM*68yitxoc+I|4|q#e4{Eo&2YlOY^5w-JPj%VWqX0wxlTDjW!h+5;6_ zGDvjNgVZDfIVBm}!e5v4Xf*c;0BHq|={UK*EHxO2UFs*ZA+#nHxmYp#)2UP{9H@dw z`Z=!Y5W;U4XqSxBLmX1P(eg%uD9PEVg$xj|((_|YxErMr@_>1=(KVo0vjImulB5d2 zI#Td{NK}5JGpIXLLhKyal!xtkj5`2w zWfc%y{~9ORG!de&wH6i=jOW|GF16hpz*h^Td0rxNLIVQIhsr!efO zF}l3b{}Tr|Pno^@siW^jvDgu6X2ON9@DyDDPddDfCPs#nGE^LCC;LttG~vjl7L9EI z31O)&7N2nvaL#*ZU^@Z9lX)+oe>DsjJa}*n#=6(z;;b)ve9W6EVG4+jPJMy3s5Hn1 zPBpn8j~rUKh(DSnFArAZpeLSzh+AyQy%|1_hEdN@|GubAGt&L;AAh5$KfALwy5SfsrW38Ei-~-w!;M=ms%CEIedW z&sd$=0DMU}yR-gQJ56W~6)eAN-uD9{T4D>b1`b|tF;l|9-d>7|=;E7_J7G+yild?cbidh$Ii!NK@Q80f#2SfPHgZvYxnC>jT(P5Wn^{oxL0mWy7C?E)m%xDUR*- zy%i@;Lio6xQBGx107X=d>3Wkldgq^Won~ybcP;i2ARC9Kc_S7x-%TX#LzcsBrz> zJ(J5VMC=g2wz}_02q(|!6sq$fEDirgM|g!jl+aQC!F;P4kHs3uR!RR)c0k9$Zw&uD zIWK~zbyq8ZRh~OD{GmUGGt3H?!D1QOV8m17zQYtAYLT6kq9d(B4{*n!8;^zkV~*mS zDg%c_8)ohL^@pg6hO(HHBRH!&b3XM}fFBbAs_Gw5L%u;ERyuI9lbVKFYxL09hbqAf z3Vs6OCgsYDOVAZ^pX5j>IlK)NA~`G4}bl(Z)O+G8OsA=ww~ z2)Yq;SO}#=FycTW$ucl9YSKA9(i?-l6NO}kB_|QtrJ#YpK&Bw1YJtZOB<(%rzWljnq;M&4;y@%gY`wep8Rw(ztPLZXSDzNVPAe{H+ zEJgS{;@3kBbHFSi28w<6aT5ggATVkm!7%RV1`2%n(|h1+TgTqt2$nzg#B)Z0s`sqr z3cB>Z$Zf+>yLF;WqbrG!R|OK82BTwviBtp(kBgsc^E0W8{>1u~^TiiHYXkZH5kQJs zIt*+c)tw|&LU@io`|P#mr>}Va{L>81y&Jc5ofnk3?x>T1iE z1LSgB;OOz~uN(G$)h?emdxHR8hH$phHCj|U#=rnV(xm^aSrb^jT6p8eVeQa64|4vV zd?TLwGpEEFQ~%BVM|beo-h1^`s7y2tAHH)$>lCPx1k#&gDP}*UCt8^z(OGcS&OT}X z)q~$izCrD%64>*)rSeV!^$ii-UmMxmtRs(Cd~{N-lv&!AL3BEaVri#|4G(~1MC=r z+qLV~si2mbAW9=SRd!!pB&)*qY7Dt}d)3sNspvhs zEvEr|77^&a6IK>*X-in%QtwZ3+r4jYD!W*)LUnyq)0L+AijZthx&>q%Pusrg0Y)-A#G-l^`N;m}@ghe)L zwbjRQOgnl!IZHl{I3twVR_Uz^NPOq$5n+aOwNDD!>P}|_4QlQ(+~s}E{IK&~m!Ou% zDd@?LG04?tSJssttWdm`LOb)0Fkzgqc}1HGUC|dmQEtJ*qbYz?m(mp^&-Nb&jBr6j z02MtavpZ-@9ybN^@L0I_+0ozNCvB4ox2oJ0iIx|sBYEEgq^g&juUUI;d~iAW^pRXi z)#&+zNngoB4rh3)$GL6WfBjqi1do*T_NOa~S4iFEFIx9Z%Z_92x8GQMQR^0Sz>W}XKlQwOd8zot&qFCia_IiIERC{P_`KHV9TK2>5JTFj(7O)+*0E#fV zJvUOp!3&{?W~--IXvys{T&{cJbNY=yYo1g^QbF=l-$nHGLl`l&hv|+SI+CdtG>6Daf8?cOX04DO?t`)s)sOeH7$+g z9Zf5yb`E`<^Kv{~(Nk*V$0Zv(_Sz?f`Rk~|vF};QuZ@AU072L+=|M9=1oC>;?M#^G z$-|>d@e?V>k;-|v97J7(bB`>2sMi6K&}8Cs57M*?~r{%FsP?K+b8oS7=x3ULbibASJc{RSWpM zYyqUO%E+K9NUDm)s>U>%o%CIBh*!cy8(4h!^M2A6z;OLwN(;C|j!N(!W#bS+zDLta z+a?xzwvd%alK(SxVncR-K7JU*O0>wS0{Goh@T7F`HgX`~IlIYogId4IodzozIGe^@ zC2#W7jDketG;)pB4paZ)_2c88tX&`=s7o+%LrNMBpaQ2|B$|RrXN?SB_hmd<=4pxy z-42rIqJHbYJv1_cb>RtY-?z`k&35+Fw`dliMpBeY_8;CI(Mz}8O~UEtcep47URwKe z(}G7RT*$+oaR^Z@87!?{?pZy2#47So2B^&Bs26_lK(Z`XU}NEs4U!`opX4~M9A!pC z0$?W9gE-p(<_IxJD?`hXLA^Lc`rQ8kL_ zw3kiQ7OAHot=SAUAdV?@RENljwaNPvP=ct()YwFx56ih(%ZWYRjhU%yHvwC?%Ua`V zeBebU8qH}R9qYD(0}Zv@!ctcSgS=8k;ETqKjxD&8P=bx&QRQ%de-8z@&e$S=*1@rQ znZm#iWE}xi09!tYYod;;5wlF0P2Fus*Ub?sH{}F@gheT|6paKxscX=B4QGC@mCA<; zuc0jK1aMQ0TM8@i*%i)MsMHb*vx_0XN}V`wDpBu@1$zb6C>oro9tJe-H`nv6Ac_F;h9&fU zGZ@t{1O!uvI7U(Zk)nvS(!#1CyMo)~V5I`$mnJcoICE=c$fT*fqaiIY)qD=i7joU; zH7j`rzhiRL#8prRU==EY?abiUs|Sc zMiV57^xU-@JUe7|CrG?lVBn2leZTPY3kh$RfNhb(VY;98}?lzS>@TVZ? zlPu_^00PlG?7fEft40JL;=~yuHv3iH#qbs+cI2}F=rj(okNTqFSiJB0xa3ql&NJVH zOF6vss0O)L6{AzLw@wohMa0EBOhxZQ)xN=%DQ)~?HQ6>SS}zSsjR zZjlF%zp6|kR9pM(Zbd~>RHsbBwP* zFa0H^;ljIUyoo|mf_3YkpF_O@&}?A6-}-LNleF~oMI#$muYSDuDDl&XUG8U330jf{ zg#_oF=}#CqENJi;8X7u*42r5`EgGEm!w=NA%^3$9b_n5;*n&uunbQJgc7lc`sU&L0 z)>?^GD{AXx@A`L_!E`?;(L*UB7(EF_M#zCj(+j z;qaMbDL7i-BCCvZq1Y}9@rQhHYUlnj6PPE1z$k*>nG+DO9H;JYWW&I@kMc`A>r0Qx zkyvEakQPkM0gz=rmIRE%jMh|zC_oh#Da^l=_*XKsz?I`=ROwA+nL@o5i3KzVZAOnl zwsUt>YEwB>CNB;({oyWVA=rt)HwwQm(ZED}FE!hJZIbI}(L_9T3U8EU5Ga8}2U!z! zYf!pD-5UGap{*_85~Z>^A70NyN5x(?s-95bw{S*L<^pDIA|F>ky8@(Oz2GHBENVE` zRHGFLUSCnbJdY#kAW7=+?hc&psQrqh0>NGqErG~wjtdYz0_4&vOT+WeT+rEMEr1&+ z%;cC-%7#uLd?><<2;K^}{1ft8g2}o;QY6b3Kq`Lq(er`Urx->5iUh$xe>ga_I|0+W zc8=<2*spD_TIN=Sw8=t1?c?ZZ7nWls;x$<%&?}O7J#qrdNV2+Gcrpix)8Y{cyF+!b zS~BM+y>lQV4IfKpt~;rJ3EL;jNaR+;bQ(py+YBf69-M3sBrQBu5|R=SO0zLa?+e*03Jqp;IjU)=I(! zVLOeZp==SEBZR`b*yhhU>Yr441&m2%mi{pDeU#%7R{f3EX(9+H(+IJ z|G7JF-@Z+zd!~3L5=5aYqmdfa0k0T@3qcbRSY!Ife84ynZGRQF{|W@@h&Bi59s-m*~a}!C$S$b!z zD0ORb!1o+N7VO`I$~}9db(2MsoPEa~oHJ2SjFZD*D{^YA2xK5Gl(iAMUgtxUDz$a+ z6@cav;Mz>1K_%Jf=>l^5AO|ewSi)o22iU*Ln-)skwnpZkckz#G;Wst{L@d*sWc$23?PFK%u-O5gn%zK$7iOV=rWm5?ZCTT z5s>|{tytyt*qJ!mVo2_UXQ&}Hl!D?J_JL2-anDlSRz$WTgtzC@J|{%1)nY==|lSvqNUD_fBvp` z9>O0~^`XS4QEq@^!yE7}lF&CTEulab(Iv=1fv4CEox!aVvA=MyJAv>dKiNh%rx)N;{u^Bjq z)krgg1)YppGYBCXSOQhJ!BQ}tQp1hkW70pWmED9QGYH+iuwG$(W36!I-DIns79K1mKsUr>y0hI3un)rMVi!%aph8kH+ zW2t^GUuXf3N5W^y&O)L+gpZ8&&%Lb{EBT17MXpVQYB1q7r88qSm}2CJ7d`%FHTzPIE6})4pY{$l`m{9LqpCcF8YJ1V zN4p|d!?-js2D$0{(ZMP3VVlh!?q=*g+0@i@`pxw{?!&N27>J&K5*tO0HyX@@pRg6< z5Q?q-y4qSTR2u8&F0+08=8abjoB5bE;sYIplEIn&i)igN;Ww|0xK8tYqDo5d1EXkh zKpi;*Th2GNxwfrEr+boX_7y~5OIurofx&x`mhB^c~X~E(* z;Y!}ZWOXFWioV(M3EQ$7$hNy9jQptc$Xr43x;YM~$Jdqzb=z@CNNP2!L+~-VZha)c z0C%$rhfF|=v!IgKbDEA=r3E5e@6IXk*rsM9J@qm*Ig6%8`N2{$dE21z&5f3~BF8{H zF4mDUVaDoif*D6Qv>WlVR(MO*MplNOJtYa8LwA+Z11kV0sM#Xw%GpJSnMX-mz}-7s zERt3bc#&4wa5%DH!+42(Y+_MMfIM0z73-_2m{?ou>Qb_r5d0;Rk+%4?FUIBQ^A8Nh z5$L89Y{DmF6_5krerO{$Il{$WY>)K74T!BsR~Pr7w4*MT@U78LqA{?Ay2bYK8UfXe zf`nJoy|l@^7T8J@a<(@g0Uiv>a=61 zk*ftjnjFr6lmPhE3$iWd{y0uW`isx%^9tZY0_-S#cs6i(T+gyzylD#b`wCpNqq{o_ zap{z^vyS^KnuZ{lXJqlaWg&u6ph=#qG>XP5h^wi7#$OOH#Wck3dQq9Ou`TZdQh500 z8z%v8g7h=<8BH0(GG5$+UYN(PH_?QmwVfN+AVUsMk=9vL|Hs{9`eEr12Lqe z`baB!diTSwjTPtuBfx$2Suna!*xQ!k_2_MT`#qGCR1y)UjL@k1G996ej``3YQ1j43 zww^jb@C`Ig+Wc~mx+e_{F0szKZt|LWiF%a1_Kl&EHtsfzk`}eAGD2{I2tl+|60-gT z!Is)QI{T3>x7QZ1YUC6Y^ii5`s3WIQG;!T%zlr6$j>E}-zzrJ$$w3O=Q>4Ga42@8iXVjJ6`LLnY?pXjb1> zn1SrGSXxr*AtH1bQogngN4u9QoRKXZ!3QJR1>qmmz6=OphIEiv&An(EQ-+=1UV9I6 zQF1#dLxf1ik~Fq?n^}vhffwy}tKd?S(31OQMEHwI9!Y2cN)7>h_t4ul)dPMv{DEGH z8W=QNxX^4vsJBSc#u8kiBr|UV0XJKK#5TAow(PYTyz1EHO zsMYm5G(`(_laq0JQ^!j5=2F14R6vw@xVuXU#=a4-KD^10y3c@_p%rS$CbF4F0_h%>f&d4Uk<~-dC9xg9CTUjAn-SnK9t4 z{(+aV>2)0R+pc)07i!0^OPvv*<-Jx-5t4F6IZ;tjo#i^wM*x(V-fH#F*V$M0$tss>cpCMLXz%c`xCw zYs{&u2bIH&(XQg~0XE&&T>{E?;H`CEvgn{o5xTaG-gI{QwKt$FmC;9G)yOHO4nCL_ z=q!pf!frl<^ZDv9!r&0zW=Z}1_BZHOWdbioCLOayWSY)HpKdi)wSFo}e!jRkG~d27 ztDM@%CsHSY{ro?WMo`C2=+e1!*)0pQq2vs=e7He_U+gbHYf$zX5Xgx1e!ur{bnVJC z)WZuza(I*7cLgIEG>6qs_(*hPb=tc1*2-X*4GEBSv8w)lsj?1#O{7}E>zi8hj&0D8 z&SpmMe^aEpD&q6Ph!5sPbo@E}FFO!&zJO#;}Q#<>#!*wg= z+qK9Z_R+4;a?nRDr5?QF;+9Xx4p_iEYn|nEOGcYzI(bY2UWh6!7Ts#DiN=3yW_L&Z z`fwBPWF;Hb#MKLsSx{m$s{Kg|<+KQlx1-p;zM@*}m_ybGv?OcM+%kf1NnXQsD2P*q za{@;9C@Qx3y|L^|es)WGYxifZ_8gm*OH|1wL4a^{=<~pTFs(y`O*x9ha@kB9ksd&j8nqSx^U?-x+xESo}r;g|B`kU zOm}?*-)TS_Na@5N(*|FT zeJl4jYFOS1sXHJS#b?-x6^Jj^jJc)<5PSC*8u>*jX}2IH*^ms28BddQ=5wu;y@ZaK z>DV=2xplYb+#)Mi%?+A2yjDl5Fy%G?gt|rRMD3_HL}fHvk7`L_=#LR+!U@AiFlMc} ztTh)FEoNv0DDJZBgWf|g>!f7O2=0(kmIBF-kCkTy$UAQ={XQy0^I?MiOl5EJ4T&55 z((XiSDO);ZCtCd&lq_tldK1&`Qw))u9K!7pEAe%>{Vc;no1Hv?h-9ai_%_>z_tiqXh*W=Q;}T#1_Mo;3YGN#EZZ`1n*gfd*0fEmwLa;%VV(BIHAo=Ju}KL@(w!GE<6+${ zpU*$do?S)FksQy{nP~v!B5yZyBDLabfN|UP=un)WzBg3_q1D;d)B0oN2krT!>;dmV zMSpFIoR1Z2f*f{{!$NrWPgGL}Nf;D}^L~e5gmKJXZ4hZurOEHlv=4o5)2QxaT?)~C zXmLtx#?xELl{k~S9SXI16NM-YqgjP*W#u{!Hv;a#6L>>RdB3 zJ+iVTljlyykn<_`Tc3Qu!%bdKA%PTc0Eye;uP4v#xWX&4uRb53R;9Yj({i5yq%urM zV(?zJ`#BsaTcIqAL%%KLDS96dJic%INza_1HcI5df(`7Og&BYuRsfn+%MxZSw&FubunkD)H70!0|}d3@7B zWFVTiPPDMD*@t)Z#3#sx;z@S~L3}3+k7f>2Bq$Jf=ceA2Mt4AnrXXtyQx%*TOn$FsdU2gck!W%yT&CHaU2*&&9bJ5d)z zK@Dgbx(}99gHsXa_Pd0JguH*Yp|k@_Q|!cdcaiEmOJFq>A8d}E_^Khk$@Nt_;eRXl z$OY8>Y8h^B;Ebq8+}YKB&q+wo-XMzwSk5h%uJZ#&JrrsH=8?Mk`3us(ClF;2N?j|Y z*#$Cmij{^wY%%qVd3i5D)wPudStp68N8AC>K&WxiU>5MA7n`N#fqL>5*Q-k-hVSF% z30&HZ$=TW2ZlW6-{IJMlK=gIf;wAwwIgFCY_!!e~j z)_{Hn;nER#dHJhvqViZDpFU%mYgU`vz;PhTFu`8TYMPFo^_)3#)Z}2FfmcfGYJj8+ zkml2)Mpf7|WM}GazoGLSQ2tv`3Wxch`$-b+9$-@+az21sF=JXRT7UN7hWR57HQ->; zF|5R3T(=)wrX{kq`EuSnl>5NjtDucylmiRJWO!Y`to0GGi-29Axgr9G*tEch3z~hS z!6U`=`VZ9>N1c|Mj0HUBElK2JrK8$j(h0U4Rx9)8%`@yf(JSOP@A$cotqVz#jTS{v z;id5hSxB^`nGyVeG05k{rn>^oAGcDxlJkcX(zVce7b%bVZ*G@^4-Nl0N2lQJ%a?bM zKrHIPK0H>xdLy+Gu1|)~!4+KXCgi%|II%kba}*^XygXMBHaK^%q&Vj$#vk`1`!dJ* zKJAvw;Gi%AxpPVvF&l1-lYRvr(B>ftit!M^*gt?oo2*V*MoC8_M-1m&uhyT*ATPfv z7t4HB%_s0^Qpqu6(Gb*-yCpCN_1v>Alo+NDJJ{GrCIiM;3u-wu8#64SHBl(ATOwt8 zSV^G~s1viFArtibvys|@f;BZ;qlLr~j;Nn1G#f@1QKe%59^9mSkgtLEt9&h=35aXx zmFsd6cFHWBK!rPFODb@7tuY|JEDhb_(Nm3Z0esb)<8i*D6b3+$fn{m0`hL;^Lr)SDY(O;o|d-tFHk zE?%PkN>T!PEwX_u8}9Fy6z&Xud1aufP6?NuAS;kO5a>PT*g>pdVHN~TV4Ix`%D*JB z)MOnI@X%XI#p(n*VfP`K++OT&;-Cw-vxZzuFsYdQB*S}rER!!G+a%4EqB9_OmY_Ra zPqLoeXq%D8s>#HT34c_N164=54LqC|;9B%N3jsKV2q0ziGHgIDM`lPhqDR#oEKf_N z_w{Kup;ed90++%(c(1aOGZSuL8JwS;T#B^DVdZ-iPFF-PLGxOOwgxbdG!VfHK7IWG z(cMkRO%jLV9g9=Jq($LwR9HLfub)`q4(r-wCtv>Kzg_Rt$UR*(8lJhiuqK0XxHT>XmM6UT8G!FXpGRKtSFKop zjl&&}DCpog+*dQP6@!?W{b%3({bTr}d#D)}%Kq^AAc~KxHR+A#oCk4BIGUhc$~cyP zL1}W_Y~eBGQ=M%?g`cA@y1I5lf&OGL0K4os3bzFXz@riy8XDY(f#B`Gd@@}N-aRPW z)^xV9-l2LAx3NgSgyf`D>Y8+62Et12U2iWt!>De(_@lcW(AjMYcMx$M@0NgP0h=mL z>cI&aR8J+1ftDnY(0~1UyZ7s*J0R-;mwiJ zm(wq4XGOcm zhZe5X4#DRB8ZI|)r6$&0rPjV@nW~D)FNML=JU96ffKPZpSugHEU^|TV>MO@V2@FQ_ z@PV0Ea2Y)o^&Iouyn;Mu3YtHI!;C}VSSnCdByy5Ed6;Ek>oK;$T2QRe>&|rp+(9X( zj2qf+!0Gw7rzF7VC>^A+VbW7?k$b?hxia|3x#58wV0ByfvbhHxo|FbJ?! zbA{wX5U(_ic(El$5bcNwMUcukF46Yu)hrH2giT4r9SX{o1!> z-hHx@%Z7O=){!O`GCN=Maw`bM ziCH8w?E>V;v3LQgX33_@;90CjQ}aMwNkbB^8;2w=)Ao$`j8N<|&|Y3;%OE8P>{dF! z$fcG?ObHtgtRMKqu7a$AsIT^05g7!igP~C*4sgmejm7mbdO z`w_bgXhjY-AR2cfDV40FJ&oO(gf7cff0N%cl|0-)z7PFeUXF9399P4|yn z0M!yqq6M@D;h-ebq9kYv9Ec2e$O92nSW&T|d2nUsvyqJ`nE|U-P|F0Ut3!}rr5YZa zs0iNqBdi@CnYzMa_qX4+5z9jy44Mbg_9X&I1&IuiFYT||?K*o2>&~OhS*ZNU2J-4K z2#reg%~OWaLfpEOW_?3wTb7G(R6BPVo1Ns@bhrq{;3PNzwN*LLE+}fq+MH|;$-$ix(x|xn zn8R+}Vho_3L>nAS0*E^F!th!r4kZ=}SXAm5zhc zG_{-{cfJCW)FZQh0@xmX1hAIeks|C*KoIh|WcW}p63jkTg}erWiGaW4@>1dpQRq;!9ue=rU-+K2sqWNwXAR+)`*?na+j6XmWz@~B@- z@jG)={+O0{uJu$PVd493dWtPtFs&x*l%1M0c;m-D4?q@Yp(;6k?fyP~m<0iGgdIR9 zT3y&-M2w?hVnHd|6Yh0p>Z&aA{taz^$_$ws?@)=|#d+QOA{P)p$#l^3#%@m|V`yXs z6cj`AY{1OGwU7F*+D`QvUXu?8X)I80qZ4-o*Q63(g~r^knr?%wgf0y|kFh9bRQSEX z(@Ib}J{cTrn30m!w1|LY@{mJb!{?Ou=X5yR?uczyhu#2^Bq`>*;yCbMX24&m?M#5U z+glqgwNu)22xW(%6qSmh!fz2Hq))tju%!T*N*2P}8o-|46`WiHQ0h5C37Hu#^1k8( z-4+<6H!qqYy~e*tu^-;`FV#8n8MA1r5v<4s6Nz0UfZ-=zx&b%H#Rdy}Q;u&?vz^Xa zgY~jVZ*Xf!^oOA;VGz?Ql#WyOkHu_gqucO#=M{LyKnZ*8+PHV=xu~g#m^P?NuCtk% zxL@c#jM6Z88&}%2JYs`ny7jpk4VM$FmiIwT>2T;3=od(i|FpQg6!0dj+=_kFtH4iT zB{PU;_kazEc5<@4D!@o3kLmLO6_5fDT(WxPp~Yy0B6%d5@}J1&0IA|n1!$0yg-qMK zB@1OuEvHheg*03EUKjyn62*xkpaKgV7~h2f`GvM4q$$NM$2Y!i;V2gY$rP$2Z!te< z8E8bwX9=}+(#j}DS>indw`hSlIW;_U#*A{@?wG(D2r>|>su77u80$86J0O6j1);rn zYt5C26#a*!r6Q+OoW{>KRMYjvtxaWmZ`IMY?lfN6i0Uu~wPp?HSSidZi1H`X@0{1A z$D5)rpGK`^<56Gd1Y07=JJ&HUJX6M*0XcFTzlciHYy!S8wZUy90tG4=#?e;a9GISG zwH@)q6z@bdK64D%J3!8@Xe`WAmzOn<{`gUzGQB z6L(c?rz$x55XkaX!ar@Y{b{}qR#=)aHYQ{zN^DZ_RIu87W-Z&IiG=4lzRo=`YhCE) zCG{n=hs1orwT@O2xx>R)|2GDK>m>bJ_4fddN*T*NaDKvW1IRZ{^P!ONkq!k@JHX#F z2_>R{gR%nNz;TG6}k?qP5h> zmj#5%z*0!RyoW$Xb-*9J`A+_Z z&*zrq6Dp|TsehB2_eflg(-K&F2Y%z-=9SM;ymf=OFGy!3c8dKyWpOF9DNILR5KJ$U454Px6G z$uGWQhczb681M%ZG_Gi|HlClxxIyeUvNxV3MDCIjI# z*Ap;*zH!KfHCtD50@NeDLJ#not-TC(TM`<^%YdgT)^RqQ$` zFpzVaA&ijV8%jCKALj}xML-Zvw%M2%M~wj>UFzkIO&#~FXwI^1VJxP6{x)%@E}{!d>&*_X%jf2zlz ztrH8CAu>WBj}GhZ%=jfJ{8DkmqKi-e{sbD$rJnXKE2@b^>Hu8vy6P>N(eExFEpUhjfWj@ISr zYHI`-;IY2!-G<sulo8<-0$)~JtR0e5yCcQ?B#a7zpiQ28Jvqm zX#}=B^=oG*y}-+#|EInF<>h%aFLLqPum6pIx$-ObgEfS6PMua_m+R?L+uzq^NY8w5 z`;Y&?pw(c|X2QvEOC81`r5Nq0j?@#W9U}vL(j#I>qrJ8z|#ubj3(*czWuLJpi>So^hZ~&gR`P86kA(I zpPkybzE0me{NsQ4r2kqXQ*Wr^{vRIlN^-)lADpGe8vx59(qeiVYUNe26?UALs<3c- zHL+j!{e{+_Q_mp*v#+q*gSLJbV=RZrWA0+=rjWCt^R-y*km-Lw6YI93Ma8ZC(W6K6O=AJnEtv?;zGDX*rTFzGt#&S# zui}|+x8A_*^E2;FIe$De>PddGdEv-SXWg6WX$8g&EfcSnwQr#Z0_vweXomNQEE-_{ zDlIK=o$5E_c`3e&;_Cy;*f$qvF8Jj2ms=tysAWQfpDp0pT@$k`^EbOqx=_fZM{iow zt?N+}+xkiSjY({@;ft;elYIHMWebhPdu^HwPhblD!jTW>(h3?{@}A|(mpISrwHa^Y zsAnYg*WFcL>ozv^#piFGJQmyd6F={H6CkUbepD|vENnvhkQ(>h)=DQox6_h7=#$RR zW)GYb8`z-XBWdB#n0WPX`SE7HhL$s>Q?LFCSKegt1?SJXl4%7W1KpehM)2#;#jTxh z1Q^0SZ=+d5-8zAjha4E+7Efp-t@?gDpUJgNCg|c25d4^?u30=+4o#s9i+U6;G^-i) z-EwsAC}BnFPCq3WR6dkwGBt%}{t`hE_2*6M63(tRH9rMPDz+cE?I{2{lv3%hqlTuv z`kGFCUCt`@|7G`IdUOPh`M>cnc5PS3k@25`gHoLw{{HY*nE8=nnjL$ud&ikuMH#+d zLgxdI#T#ArwFb-;V4ykkYZLf1ZWFkZB-n>ipN{^`rm2dHsLGLt$au2}r{?0s^Ap3?wYMR!_BEjTzaMEzGRTZ#pu$q~ta& zan^N>y~kif;u!&5Sv^b=xIgp1r_;V6pF$hB8byue@s3E%mY1xk+=EI6&{#8*w5E*-_bCw1y(XiOIJ;P z$Zbbxzdz6uMIPO7fRUg!nUcM9^gJz}fAY4c=i!3Aldr78_rG?s{_lC#iG>ikCq(L% zRXqLIm%X@eqWJ-UTkHQbzQZ?n@Jk|dVj;DuMJ{#f%(}gD@{Xlm_@LbGUPFVi3@2|E z&xftUy>eSP>nA2AL~aZG^3(D6E2WcEc1WoH^2@GmvxWcqEkRRNRH);Rjtnswp2WfjE%J$N=r(T;sv=MSZGc{V&cF!dVkvgCl`J-awxelI07F6gkn(cI%$ash zn)FK*j_NnVC+}3kD54x=7OArZ>T6-lP6RZfhI&79C%yRjL$0rp>3sQ-@tzv;$fk}v zA@KZoaVrn5$EVVqEATn^^3#ws1-8` zn4Fr(R)xR=nCD&KNR(~>fmB1Ng1uhDd@*`*+8nw#UWRZ{T|cYk(x*jM?vqqznhwiY zu_^u!@XRtOAB}5f?igHnsm&MNwcw$N%)Ej=T%4uAo$ft&@PPf(JbJwb5BhpV@u0i4 z_;>A3xBdI-)LcR*<#gK>eVTs*J!|Bj%_G}>+QxZ2uk1g3f5By3-oi`Z-@gC*SOY74 zcGc4o<#N=2Nl*n$`~G_&TwgMx11P1u8HX#5SI2L6h0wfcJ;x^PVAKEUGAK#ubN@0+0X-v+cC3FCJ#R4<#CpocZPRnRAZveH^Q4j0xrE^rQUStGJ=kW^r{AuOze)_mP zUe+?pmb{ex$NBOQ+2K7k2d~#HNrjjl2`$Ez*k3QUD5cj1;n%Mcp@%ZF^gESS9o4Z`AU2XK*%iF!&=!xCcmlHr5x_JveFheU@hDB3M~XXfxg`kAZmXO@YzW*2JHyG+_`z*3SVs`ql-OthxCdM>182480tx+S;I<1+2mEnm z$EsDU2E_%J^YLkRe57yn;I`&B=k7MY8@YUy+DA;`XGYG4fN^Om!LgI{RF&v|TksWj zVSMUb$A`%#ci@AmVR_sQH+Q#<5d8)B=e)o6c3*ejFc2){n}F*j9vnfxdEoMIucwxw zKi@2BofKG5T3*;P&`>DLZljrvVFI~!z zTuiUP^O8FP_S!XH0Rl3M%XrTF#qjPJ8ylPI(H}OTXZ=R+BUA&esMycpqaQz}fBkEu zfTs#(0E%kBPMRML*q6F4p?hka9HHnX{Ou-4JHAU%k*0dl@}NlckXFU{LzlmeM0d6S z?K`AT_GAbReS29{%qaYU0RI{&1OGixzT%>zJTJF=dxhw$@D%;>|M($mCj#pl)<{b; zFCBT)c#y%c!G@%t2aRx-AN1hGu;lbjlUJ4}?F!lC2o;d#1>Pl2QE&puoHSD6u>u$C z6A7tYnmFE{o7|Nj^IaykBAT#3n)AnhQeuq1=d`h=-F zU(d?=e_|jLh0QTtblY06_{vVMlg~N7^1-+MTigdH z_sVKC__0BcG-{sF$Lewk+)!y8$XmESCof6>L?_E4U_Rly?L%`(6@;CQOMiGdH>a8V)CWx3 zocl=X3w?uTQlsrtF{>*-JSe`xy%JE%Z$B`Zs8N)8MPTWgk5*r&E z8hb&~QxwT$Qqcu*Yy6oKOrD})Di906#-1j3GVucF?Izxpv{QTAGci$=EP-hz92izO zTalkAgz_*cwWAxbdvnmE@rSCUZh|O>hUQ^T061VR&?YQ=5oY|+{O>-Q7#owlBzyJ;v90+NKob|*)s9}Mf5p$2!7jGwAPPu@}X(E##S}g-2<^WX- z8C>GJp!bsl8Xrx@cR`S)$?cozD`7yYaiVEp48g$k*j@Sxlv5nD^DfBBSoZ`z^^F%N z_sDtwzy9$+jJP{^AXf6h?NAbC15U1LA#gb`+nbQ~f3^3WK~bjL*4&wKf-=sG3ZkNp zq9Z006-gqF0Y?!KP@;f>BB?>51OatMQKEthl7kW?NzS07fPzSBf=yCMk|j&*Z|#P2 zYU-=|@2jus-l{{@Iprwb{r3Al&$IVld#$z6(X8Fc{o)nob<)s`2uul!WF)j81baYJ zF97Cgj2*h7#=@SyzN*c7@@R3MW@cF z5d=t^0!?psP1CGG+y1Ohcd(LuJIRq5Q$)GRSj46?dw&bsuBI>~h^Qz}5*u54!yJ5o zuRui%NOSZ_nev7aSaJX5K^X80I}VuT0y|zsM&@PZ2jIyv2sm^lk!8hYkO&WgMZ_~X z8USNs$SW4*B&uVF34@uneu5k6O6VsnueT$s`q4&SJYJ6RH)L_a4ac)+*f||4h(-I_ zC>O3EGT@>$CAoEr=7_v|_pS(8sVnqx*e*ns&Xg(OIN4h>u3m22Jve- z%Z!gD*{r8IC$?|`kXukXW=dol`9QG`O5DIOcADn&?TymW!MUMFgDzxbZYmGYz}SH{ z_=hS7EZCE+*xK^a#UGoUGoPde-O7f>+#C`K34U2fehhVz(dZUHmh?fG#Mx2Ohi;zZ zgQtVgXZGd^GZdCZU`iWoVInWP>cA5zW`(kH!EDl_JWaGsJ<#N>>iAN4nt!r|JzICn z-QCK*m#CAVjoN%k6LJ4o7F()oE-0SWw+d(4g!TNbRvTKzb?+;}=5c4pXVztk?`9aZ znWw-`s6)+g#$R;nR$1a>z&+03at?xpCZh#}Y6`BW8tc%XJdWJdzSTpt*HjeR0_6q> zTmyp@yumOSsQ8iq@f``m$aW-#-XZ7s$o`p(_`uq1ipj@X6?7y+4~T1NB(;#2IV_Mk z`Wfe0yI*AVTVTRKB%#&&Y%99*14PZp)iMnuHC)nnB-&Y@yW`U!Bd>ks)oZE@xH7Zs za)3wQ;Y{8^EU_cq2Ttf6Ff{xFzHVfkL+lJ36dL3)@+k)~1(@mqP^x|5@Ap$wy@V4j2B&VjNgZ=wL90P6sMje33x1naRu)tNwkOe19oV89h{aw`7ln5&3J z3&}-5%GDww3y6J067hHa177iDa7?cBpq_5?u6JcY;7CKQl^wu{VB#dC3j+ZNf2^b7 zC^H}lNB&uQ^PB z$Poh-4`;z!vO*)GB60{}DHZganlNSw8}sh<>(__!Y5VVDoYHe#_`-#8q#NHPg0FUGaw&t$Q6%-|4@ScImrkh=&ldX1Fae9%R}gutif^VYbj_M zVV%KL~yXhq0)DB(9RoE4!H4%1p5RLKuMyWx_s1Z46hr2Ye8~NF(qkWS;NxykoPhq zD+tgu{+72vE6@Hka6cxg!{C3z3Y6V4n=65)*~ig$@cafZc&LABYAO~;7Ox}HsAS@`UI@=&tn<`Cq&EAfq!S)!QeWDCQm_%SjPZ?YTKQE5hg z5UrM^+w2GhogPx4A~L8t;kWborhy%yPKY=oj=fnyXKM1m>svBjyGnb<)4=iQ{!8=+2S({tc?FzW+GbN(;ue_HOJQ(h(Yj zDnb-Pflkc8OGp>?hJ|~4L3=N}@Pokm_3p%G{R75spPXTSs|U%W%8qg|Y@n|~IsxIv zJMqGj$CO{%snIB;x7VZ`rSCzS5hiz&PKr6Fk9iw!9^jJsA7HjBq8xc@D$%Ugeu((b`;FFM6~L3d!3fAVKl=M)`e z&_?D=?D*ANJZU&NxyUQCp|+{-ZS~B}j$7v9?W0*FD{s11-0t~&{JRho#T9z*dv0zf znIxldS)SR4Y(5GVw?--;O(P_c^5v@_JVbnWLN!7$VVqUg%uvPKb+Z7ZVq_se6 zj$W>9`@CBZM>b;SL&Oxr%fVpUvaB8!qN1RBOFsnQFr~BMeerPF!=vhZYpn&T1qoWH z=aX6v1q?#Cr2#jd^}WU99uxyLt{n-tU+Cqc?t-g-x&eeOI_D0hkoKb%v0)nvX;diK z)US(+qn^!z(L$*elEw3t`FLm4^3_HmL&2)czZIWgdj;mU-SOeHe=ZG&i!D14Gni2@ zQ)b0g5e!WO)z-WWh;W|TKYbSrm({l)zJBH%#~TU{1S;p{%ckH56@&1@%fP9;Yjs6# zKhTi$%n)zyaA)>Z%i=O}twq+EnkS+JWS7GQXjolNb{f^tf^1{KSFCsB_d&8llrpCi zaQT+}@CWQi597y6ACR9lA~KTIO0xNO2FX}uk&kRdPJgy6Qr^X8(ooD}ExrwBUUh*E6pioQZGW7L1!t_cN7=tunBg>anY?je)4a(sXcubmPLeQ^8!3_a%>E|Rhy1Y>dzucYt%y1#8sf$lHjb;26Szb0JeW| z)xZh4t$!`7r~EN1;M zXyyUcAvB0o!jx^35u(Tr^TXJBCm4l_{Mj%@CpvR@9|UfS04{>oP!}vR)+Y{;WyC>! zOADuT&^#)yo%`?70qxMxQ+$w4cX@yGd}_m0_fYmWa`2|^-;ZiyrR!%us=%19u8Q`A zxGqR_V#-v^jq!<0%+zp8N4V$#_1vaY3}znicGIie3!lc=@7`-Ap?9U+aOfwgwkkF9 zfTF~r?{U}ArCOCYd>DET?PCN+O^F^pwF}9>xzS;bpN|$qAcHP>^Cs1RoRSghJ4OPl zLT(h{H05Q~?vI70I+EuW$-hVY8dO1@Ha9fYY|LV3J`_)>^2Rt8h?dS*c0f;z3zyg@ zgX&g}k)GdBt3807SNb8#bQ#=>fX%3? zEiEm~j^5Ks{EGJqE^f5+v>>ZxB-W`~c4e`P{tV3h{OYyVp}BP7S(yi#Gmo#Q_^Ri; zWj!y1E>NPe<(;e^nMg*aPjA%|d!f<7o+@CcWX&K~+}3~b!UaPBCpMj5K=(hf>8@+H z_mKAq-!fnx%E(I3tVzV-AGy~d@z}8xo9hDGx67698+HfuM-mJ2$At5+mGWPO5zxyB z1?~J{(W2e)_CD<00_yDM>};Jok3vI#t^R$6CJiPMg`EiW(sFpKB5nBf}`U~Hd<$>LfXA`{uu1BL)>5c4{Q zsIQl4*VfTtgc{r)Ym$ult6OVT-f!D>xm~bbBvFW);F-(oAjaY3-;IqxYfo;;)Hq>V zx;?{hu>|>|0UdJwVfeb5_p8%F@FVs*(+5~kNKzOh(ZmYgxl9G{aXD$d~;l+18Rd_n~a zus%X&<%?VUXNt>8YVI2)q@;J>lJX3`B!!|FIrTOc@YA-TsV)rD0~8w2vDs~4GhlZ+ zoTnnF)zo0dRD}#bk@~OT1yI2V);d|tcO$8ebizh9+J5x5tE@#u*R;0cV~FFcM6sD-5%3q?HE(XVS@;Mapre3deFol-^xY0H{&ohRT?v zTGTwTAM1?)f=sGc;Fx5OISTJ&V^Sp{4~}^ivmtZ$(am0*!_CJhXOXzwI|q6bF0S@P zpi3NIaFOjgEi>VEXgKk_p#skSK>yeci}&&FIXWx*_o|y=z(rWy=@Y6yrqvegL}Dk$ zm}vRwBH;ShR(4t567PEiasE3Fz1~D?3R!R8NsjX?ju&!NB#9H*!9Gs-R1+LN?RmUo zz|j24gE+?mhT{WrJqKk%;`BbU7Bfa7O64?(fhlP8k3BwzxKL6cVP&YOlxVF!_uaEe zaSMF)G&)J-drSVru#8i_a^*@=99Q=fZ^5UjqYml&I%;nGE^i7TXxFRPrOgf;7K)%w zF10`YxG}YLh`@!Z=4Q_U7JuHUN^3%L(yw0SiYiWuLbSA5izzC3bSWtE+tbK|5>Q}r zq0P;6enR3ci2Q_Kz0xhydAV7f?cafeAT}_N-!1*4#)Z(QfSA`{y35>5u$Us-=|E*XeEKO4+je32SfO#K17zi!^-Oo(f?ZT*qx6$HPb z$-mm4+%?FLl#J-0G*t_V+S4n2(kd=51la|g+qPEOxf(sbh-Z7x9R;2NW{GGNn^GdbDgfC8l9u6P`vWl2d%vH`XT#%dk7`&Rj+kb3YC?WYW+k<;tu!2w}Z ze1bgaP%p~8axX7mbW3l$XKzw^_j5FB;1XS}8&K^};wu;$l;;#+OCmdjEr&s)P)tjVLKh)GUTH?(JsBNgB#g8-7eZcDk=|%8$_`aB_k7GyDwoO zjaMbOj-E3*O{K#3zA+wpcX-#Oj$gpd}sj zc}GILkx&JLy-G^ zT;eTN{vmdx9LCxroj-owRI|iFTZ@lir>8HcsQt@zRgV+&_<`g;cA^Fp&o_IK@dzGF zE@9oiwQ9$Jwi0F6z+BzZ5imMuBrz`t3d1DZX-eZT{N-+uVvN$pYClk$1ewPJY2JMr zb@o&;%AC7)sCJ~;B!@?1>Z<`V7?LZ|z*L$N+kN~u}LD&gLJhHd(_oO9k)ny zow40>jBGHPd?A07pe|-d$^Bgmm6+nkahCy_ePotIwQuI+OS>(GhCJpO0>z*Rgq~7E z9nSsYQg#cVBZg59GD^4g8)8AC)Ypi&0J2QSpJ6Tv=q<2vLjMq>%1`42A-@HeNo<}V zkRMYF$P%5?)krcRJP9GSOUZpf7uw!2+u4u;-M@eTf~%G{T)5&)*Z%zTS#xQe)LlF( zq#Jd~K$9{aaLHplm>8gpwEe2T3nDiFa>HS2*O#X8&@XkNlX@vTB%-Af>CQtHA$7bC z&{-$t@gdKrHz^D|d*Ts{BHJNeJ_!y%{1JgjJ8I5ve^VwkizFVN^dDO*xDwk;G>z&~ zArIi|B80Ky47`s+gwSQ^Mtvt8sbHNw&sgv`N==m@jkDn3Bpl`}`|k z&+l7>HmD81L1n){hvQ+q|$I- ztW9!1Ix>Yxa&q52b1OmHM~*?PLgdrcdWgQytUgj}gBRex%-JB*XE_ z6|3Uam(@~15K+H!l>h$SyJ1wSGJ~B9*B~+h!#qI~i%_>FU}I9zg65lz(SGDTlm>;D z)z#IdCNm6K&SG2Hmd`^-3~MxnhHzZ)n;oxkGR7f*ADLAV`2dOa z6=;se;*s|v6DkcxIf8LR`TdsOj3%1^JpJt~1lTAT)ksQF3NYHjo>i?1nb5=5pve|w zN^a7bkUObgZusgoLtxX6g86epkdMv{51>;TIJFlu0x($>4lx0&_;`LrCfVmJH=vJ3 z*5Q&OZ)uD*X5ANs$0OclW8f_R8Ugm>kJNjC^t8h2SS^ZoEMjIb`Z`6uo&~o&*}i>yyjn;0Lox_Gm5V!_0Dwm_Ex8&K z4W#pCCwn5tkg#MvU5958`VG+kQanbc6FlIeir!(YNttdgmh`*6o)WV$l+K?x_FB?F zA`$VQHjK+4bE2}TOY{<8WLJFQ!v%Vyp>Q&_i0#umF3gT8f_u{eO4BxA@WIu$M0L{|gm9rjK z5bYa1+GS#$WNSqI*NhxRn^KpPz_+XlU0gohJ22$5kh%G^`g{ya=)d<^= zAhe>MG2q>8m>uYkRtD8U0ggCwBhl*uq|aX_0t7$yzt-H5eaxRt%|q4yq#F%y@m0c1v(o2-4yTJ9|1 zxt=u{Faw)FUzj}}(L}iG&um@nB9y`4yNM>Cu}I=m6_fUaTnToM4{|Q+w7M$yz()5# z{`r>vvS*NQgGeMwGk=M3;|DY^=f!44a3DlByvv10%qnstVqFGmDFcey2}eMV?#O&t zL2$)Li*y3D*i*Lr93bhNxCFy}5Hq*lSJf7V#g}ec3(^}80%Jd;SRDl*oOKt939D`J zElQfQC(C?!FPxz#s>QGbk{dcPH#%9u86O2W%to!xCn$(<1rJOHj=nYd$jp)@JMq!( zSh;?akR_}HlAAnf-_J@b%>qb~?U^=rdxByHYAlf=dh#2sM_RT4la zz^DL&nqJ)U@JN#|18(Dvh!9{o)?HJ|-1O_O&xk^F7k+RlEr51C;0q8ise<$L5A3gZ z)fFSLlAgBvWoCu*o+UK_;?q5i6t9*V!4C zy6vaf2>23t?9u{-EGNPhlbmMk17^sM2xBYjjar;%dUWIq!EC%54u1-<>VZ_0p&Cs# za70sat|PS~_(*Bu#US*!Be*r)^X({@LGow=ix1J9b9_Z`zc{;ldm zH)%v;OJ!>R&?|wxde%p^VU~JUIRp^yDl!RxpO6O%*Oj5hLA=25eE=rBISdgkmpBw zgQ+rt9IRGP&u4^_SndeErYm<~)B=JK&5o;10@3IM>a>jPk4AV_s3kv+_$43(xJgA2 z`gxkEW*Do62zwgqi2MPFb$}2}6JE#?3J6ndD?GQ40Ij#_92p+2M*laQ)=9V&(sKeO z$jB9ei+br`KTt27O28xr7zr?_+KF)yHDR6a(7Tbsq&e~}Ix8iF){uV`bw%$jgYwwHku$9J$Sx$A=bv0bnrm{zqfO% z+|*A;2|r}oAnT>fcfbimx_g0vXH10e=~MXt8zTZL)l&!RlMd04X1LCTqEsi-U2q7i zfUBiq0TY*@+m@a>(EBj&?*U|R9XSslakA6t8u~;wY-Ec@{T0kOqVEI10r#DrsWI>v z;=3IQLB&IJ`FI)VJf=%JpL0r)20lYx`$(nERtAH5h&-X^v9Gog1-1ewN18B2D-o|W z={N_RnaqY5MctmcELIQ5SS>xsYszz^;YdgxJT}Ffe^QB;O9Q#32B$y5##YmBo4cL4{~mkM7+3 zIvT@^$llc@#Q0cA!SQ1_o=p;7o~($6k(zv>YYzH85h&?z*gI;b8k`G6pCD|45PPHr z%O|C*t(?#E^}ln@%sze$Y@wRd_QNfBz>Lbo+&Cp&zMFUN-8&EVTtr1k82E&I$PDBQ z(cQcH@xz;vFtE+QZrKf<&zafnpU{iWh0kCSp6Lm%cbd1Wcb;LFIceG0qz}S@ciH5) z38)V45bS)V)8PF!7N?Wido`?H!ApVO2j%-&9;gj-pN6cPBLW{#Z{5r#xB!JG%~R>Y z0brS_0Jmad;PrTjHVYQL>Rknh!3kY~G_#iG$2eri%QZKr?L^9XA#DaJrw}vqEo9kf zV3pDY7PMogwi}l0A7{z!G5YDdN!N=4omE zB?-4svJJ$fuQS~`RrtQC$X;k}BRF=8M`I9g2+u-yq@;^y&*b<(B9`S=jEU<~1F$ZF zVZN9|avCwqCRzdO6TpoGLD*drkEF-Xf&3G%JQY!u%)WG(W=)`eEtt9k7ekIV4NMzx;urs*Tl3gT2X-VI&uv}N)@`q zy&@ZJ10yUH4e-~g)eFM}R#QHZNH~qv5Rio>np0k*=r}n-Dcd#{Yy$_XexLpuvxAtp z(l{E42mxdv9pJE^WpfLzqQXMqbHrtJWH zf;=P1CF#ac4QB>9JyZO$X2! zpnelJp9FZtWW*EIk+VN4XMC+EPCXZz^@`P5*0C2>jevoU3*fqG`VfL_9Ska&c>AxW z5ardVPeJ3mup{psxQ8VmD35qWF2neG)C{X{+KcIz#1SHAHk|qNKRYj}FYo{4ZNTxX zg4>lUsjWDzzZP9mnjQeWPyy`J%}+1wMsUWROhvyn7UmO@r|+GvvKyrVvKLC01r&25 z+%vTGv-bc+Jxn09{9GsOfYTZr2mOn`67{lfvRqUA-wjt<~*_aWB z1+{F+l5iY#MtB-+Bt|Tl#8xH+>(m@cmgdqdSasj~!xTq#u9X{4p zgD}Vf{!OJHvcD(T&ahBZ1w{+c+D2*Vg7x-$69kY3W-J#F&uX17-P>0ehFuLf$!}C3 zw(P2dxW#%-?}BTY)V%tGYuN&!f9f1@(Of5Q&M9W-&+|Y34}WD#j9ISFQ2_M_!7&ZM zfcd*5RcPp#;|glg&O#mWcDtnmY~xVHn3p!reXd{*sZK)g{Q(j&IBZRO*&xCkpOY65{FA=5 z+$pd?QFvW(;n(87J~wx<{Q3LEoq?}LmtfKC+yA*%hr0wl5=pr@*|0(Btq)6`l@=lX`2$B#GG32^?3>wx?%^5gj9 zIL3cYcdHh-f_B$tPYPQ6y!xRI)`DDj{u&z_Qv+XRx=X>?^}&M&(Xp|mqjPp8Tz8go z1oz+OA)P8zR*>RB1NPPEyg9)g%ejAy2g9xqLrunzQ7yCAQM^7|QF4A))*22$g^TN3e$JIV`;G*N<|yZFGWTBj^4TePendgG0wi}8;|PtU#3Mdm3C zhibn)hDyxZ+OeK_qtvgpw14w?-DdxNCco5Jy&fRc2e)ov-ls;RGkZon_$EOg8#e3A z4*3p(0Wc#_04zl+f2wJ~=~G5}dOGR(^iU&I*4NiRo)K7YWMuRaWxK~J)65Uy<>{%Z zFWq+J^X?M^rfZDw+y_IJ0joo{c-5fp*?%{oYyMnbs5V*m$Vp-kya4X znw&0!KQo9C21R&YD|KeNRU=?N{i1W_%9S5MkY*6Ez2PEsP~yn#mjFt2D|hU-Y;t1j z(xU>!@C3iOMVt4y7(`st&{Vji!Yy8&|M^B{tEc38r1Q(8=C&N)8BQj3M*t0bH?-g+ zFi@Z(!V%Qj`{S{>u zoQ>B`a06?Jg|iwdq@O4^>_bq&@)vw5+#$5mx1+PO z7!<=+3=eQe|5Iqo)~)OmqWXzJj$+c1FNM|h^VImjz(_7yXfMm1#!{l6Jn0_GojWf6 zyicdf)!#p$$2s%LtYD(dELmGF|LpVYG@Vb!tA@dz?v$3CcEl1lhr;W;2Osd)HMmV? z)BTqVdPXG1Xr+RRv)@9?@yL-Q_=1~E3ueX^7v!s}sxA+i9f@kiw)4<|PQn}^`#rIuR^qEB+r1X>IFcz82BVsY5%Q)nLe{Y zz){5zDo9+J#pet{FkGnMJXtL$DEO)N-(QGxg8u4)I$0N7+`)J=$DVMVjBU8zW=_Ka z!T_S=L#Dte9Sw6%h>5w4W~vzYQI3_y?~IL&TZ^S<&D~dt3ia$RD=WiZnU1J-oUOwE zyfpx3^lL{^ocl>TJJAuO{-VOO(W+W*5aOPfz;KfHrvT1ZLrXQIV=gxEy_w%nfIyNk zvCa<``@Su&OH19rg0q^44Fb8<6%Djv=t^_0$e_7;rBkxyHa;V+yca#v(y6rc^ddlN z5{?}WEweUP#!^E1hJx3gQdeJr!EOg|TIxG?fT?d;o9ITpc`mL;GMvaFZUOG@QLM#` zme{zs+)s6f1lA)A=we~Ojf&N`8?D1tXc0Nqj$#Md*d-DHYY@!ci(2%+*Mj|Lnb9$& zgJ?h(9_L((A2oDnyxz_&9KLOHU+rrk0_ONEouMfN&Ad;$L#Ep{N#?DY)s(^|jVY+L&A!bkpe_Gg%D+neCe(NztB3FmNN%($ZAl&Rsv>tNHgu>&zAU zGg&9+=`VxJ9rXd^_~tslWV-~s!*I!TSqJcF1y-(Fm6A{%Aeva+)02Z^NnKGzrS^k{ zrKKgI)p<6&oQr*S;51_5dkYc0B6s$c=TRx__Xz2aXzr1eJ-cLUqB|NRAiH02={bG+ zw4$X^^OF~&mX$jq(IPk1rjH2za)ikU9fwmOK zd5i08=r1k@JrM{6I2nt$(y3F+mi~6))8Kw$X|z@}*B9Va=+RJ3B<;CFZ5mdyjYDKY zW`A~1a#5J1P4BG}zg5TTY@J^~24^^k$&3lUZQhbiI9m0!V&mic24`>FkeYHnP6rnT zPpa3U4K=x@FGNmDORF{wfL9Ur&Q#kO&iB81?I34S%$NWU$xBvnavCeBRXufT#Fiag z6h?=Gl_O%X6iYe)YlLst`9Eq$-OA>!U}ydOS$bMUWo%+aP~qK~cCcL3>(Hms#h^+@ zo3YcXTKBE{u!J3Lgy!#eMT){z`eTz#A&=?^UZy49qQiMuX&D*CK(VIG{n>EGI4}Qp z?qfdf$e+8!xajEU^72=ur9H#Dh4e#Z{Lu0!8AYt8AIIbKzx4F;Q0A+MtSs?50jp1V zyMHBKp$hX?%d>1*oBdx-l`NKj&o2_#Cl7jlnR}1Pdz?J#)6%}azN|H2hX9qm`uF>H z4`mjUnaQWiILg%Pa5NJdw>D}b5k#c6f8Ea6xx8%hFq93oX#u9$oAWU;WxRFI+$Z?{ z#0d;sjzBWk_pksUPnyp;<6SLvoBwdMu1m9Pkz#oH%)RK0HfP-*2+8bz5}TX=0>K^) z4UI|jIY*_dr7rU?1iu0=Y;InIRzPpD;oOUb)^gIpPz5HFc^HUZEu<6~YhaBTOdSkC?ax8Z-E;e^UZG3X}jAH1z_7|DlA4^TkY9gbbHif7I=#&%-X_a>mE zV__{gOT)1PV6guS+$1g{zKwT3oO`RUZ|@+GW~TvSU%UM`Lb~WhtJeXqTn#RrMPf)6 z!j{)`ZB^A00N?K5Y8GLkILw^jy!z@j4yf}iv__rZ9!HZ?;9n-Ro8%K8=-?OyD>9+( zEh)+!S7j&rw`B*#QY-$GOQyq1}fkt;MqVTU`34yjYwN|i2+nut59iGn)7>UFRA>S_JMp; z+1%`O?BYJ4_DSfD%7>tjCJ*>nr;3!5`1$kp{M#fa@9JS8o6^H*3Z&z;UQ6$m;S|!t zI|l6^#>B8fFQ<`+dTJYvOHty1zI_sqbNP@QBs;BWrS%Mv6#>1c`nd#xJ+I0_X@5(; zPRG9MaXq*?Cj!NU(LG-hA0Kayr-kas4Q_(t)%Ok`2A}pNri|-iu1RHMW8i2O5@u0q z+tM##g5*my=lIZCxdov-d!Ho+2-Tw*o(on|5(2lI6Jx}6Yr-we!E!Q~OU16<<7`O2 zRHV^DlP7R6;~;B2RB-znOFjIFVvAbx`D3Z+={A$S$d`4|_({U3m0P!P4&1^95(6P7 zH8s_0;td{>TIQv5ls+C!nOgzeza`Lk*|QZ-;^N#vw90N6fVslcpCZGyCghE=zC8cQ z>E}Z?xw~o|K>N8J85wDMBMi%Q5IWeyI4Ca{&!@f2xrIb#Id0hRrg_y!u&~-3_x!Tl zvP`7zB|_}5>_UeeBgCRX(Eo~X=1%pJ5)!xf8s}7c7OH}LM`xl$HG3vF(WOHLp=2L= zGJ|P}j@yxyIWSuA4ZaNd7Vv`(bds}>$L3G@6ALW~!si-cq6mw~&X&Lw=GQ{bzl`9d zRm9k#VxP)~xUMhEsQo;U<+{U$r3i6T4+JOQ)H|q+KUhO|5o_|+Ey`ZeuRn}al9DCNY~n*3-yJ=xHrqL?r>oZvan5S` sS}4iyOwS!SbN_i@;D0T$dx!n?!Z+LtpIADC(RVp^ME-EX!L!%@4|Ibyvj6}9 literal 0 HcmV?d00001 diff --git a/localization/pose_instability_detector/media/lateral_threshold_calculation.png b/localization/pose_instability_detector/media/lateral_threshold_calculation.png new file mode 100644 index 0000000000000000000000000000000000000000..cd919cdcb0383fa05746d67937011d1e8b2243a1 GIT binary patch literal 67649 zcmdRVgZ=$zGZK3bQ!+%RsgtMsFzm@O_dSGUWLReg5r9_{)bkeHO&qv2tyv%#|m zK?6RDAdpGqhaLjpSEAzOwB7%Gs*DYXm-+WK@C)%5nDT#DRl==6WB*cedrY-rgm^}@hGzIEBJevYxZY^(=HNk`AW$MBe1>0!pn;}lmYtsAnc3NN zyBih(FRoU-!c(KsZxA0}mLp`KF6F=Xo8R3zhvB}ztG=A>1{Lr+&ywWqF*+?m*s+Sye<6P)04gCb#oqL5H9nNlzRH%W3;QBcPxUsRk|uXfsE zu#V@fh2yB8X~fv%ik<7J9KtfFKP_Kw z==yr0(AC+9Xgo8s{ig%-KiCwkY!@?S`so>&e41f8wKX#*CokVJD~54cZ?_c`VEf%u z1eKJm%nJE-0qd>NDSD{(*)(_p3Igg)YyWl-1*%Vwia*$K#_;EzVmCil@8i|As~#7+h+KB8G?bZws|qzJipgsL;Htb*6=2+b`uaRoTME9hdwRClm-+%`vfwWrO`g z(7`%&2)E~B!{vEDMol0C<9|m?dZBUDmJ6pFmMOt#{<%^Y_2jQ5wfUh{=AoG2t0VZa zv5xvB71-JuEuZT{lP7UpEL2et{5`#h)aOnmpNTy_e~N$|$5Lh@pA%A8SXN|NtH9S3Y1^qG1Zrw{Qr^*1 zOw7q1zsKx@bRjJ7^OruGQZaB9Eut`^{~|AYl@<5ivT#a9lM7>Y>!cb*hUb?$?b>4O z%F5e;^>vi7lBAWv!uV{2AOcRgyT*N+TSf>Cn1Y`_sKHzN$;I^`Hi?i;@~+Vqw!TFr zuj0o%HYVE8Ji)rqY%N6neC7On(DjwU17}F+z(CaM!S1Bdl_W)f>W6g!IO#mV-!M^@E>{sEiC(ueuG zqlqksQ|b%DO*k+(a~|cE-498*9bv_yag{0Fk9;8l(Ryh zM{V%BdOMG+-Mg@=`T|>;B0Myr4{(K_G@nkA^kaLq78|l3zMrRZSSgvQMpZB$Ki)Ze z-MKDr%3o|CVdbBEYqC`{8#-K=Fc=y8)&rIl2N81?+JBPw=07lpvS#Tu6*6BPHVc<% zID6eVzTt!2&;0zs+y>(3KPM;W*J|^*DE8)~kBG*CR<-Fh7u$2O<610b*!kU+Nu>7w z%Y|CfCaqAFSv?N=0an=k9G1^T#l`UtA0O%s*sw80``+F56MhuS@CX5VV;Qp(H(3l>wD$BO_8p#0@ue^E zUu>d8PPU#NWexG=b%~vcTTE*_C^aBYW(~HZrh+@$RF*6=mRR0M^1nH|U@O>EsuPfn0s z@6g*AX;`6B=lQJ)3tFM#$jYXfJ|79`&?kl1_z6Ny2V20jT4~c4ZB_ z;g#KT>lJjamR2<_(@=31Q}u3kQjp0?LE*-rcRUm8zv@GgWe+J{#cgQc#&9I#zKobe zZnm?{XQMJ%1r!%+?CAr6n$V?LN;5H?9?Vup$;)IvusNA^>N9gE_wWmPqwN0`(KCRD z-#Gl)?5e!U`tEnj0d1f-(2~ww15147$jREKpJ2ZY>wk^q1-ZcY&ln`xGiw_^diKUl zuw%L%jsN8+y35HVe~1nrBdagmy!W_0ST}8f73Zl}Fx7L>6<_PmbO%>`bJ`qrCaA1r z-#`@BGvKmiwdVsSd$M3xDfaS%@WNMFI0(M6YGw?!#Q$Yfo9{qt=9vi*`QqXrdW~d# zYPMGd95QV}zAfIL=)T6q!QVeNuh_n)QmI#jqAvZ#U$gt{kZsHjQn#P7Kxb}t|KLK8 zfs)nu?#yIWd{>2GsJW=bOn$kfV*T#v!Ft7dfEZkP4tDM zdBW{kRo}3#ZfK%s2^2TcOF04Yj66j_rmNaj()s1T>p4MSMA`yz9Aul z3Nbn({`vx}+k!&EW85HGT0;(A-YFP@*+mfv*V{RJU0D6rOGsi)Dw)M3Qu}!l8S)WK zZm55?d0(gmCgA>RN6w4DpjX^BU#{2D6QwptK+ms0A@T)2MHQb9ix^Ov>V1?Z%ri613M!*g)oYKEm|ArA4fWAp@I_jJxJ#H7bzq znpsPa-)DgIzM^0yRc9x%SSRvt3~Z079b8P(5`}u6yj6Gexlo_0XJYD@G5B;?`@bSe zI;iY#y8()j(3wou`2l@bu2e{Ut!FK^ftfTF-7@&P6J`e^LSgBr(}DO)57`e|R!IO>U2;Y;!LCNT2it2cPFdkTs< zlN(^RDpf-MAtO2I+-%gts>--xHw{9nEJ$P;-qXs_~~f;C;h-sDj?2ybSiz13I?< zqT?Ta-E00V(rRtx%nqSo?4Edae3j&9HIsi5-RzcD>xum~%O5$Ql6>ta=*-CQ%U3FS zh8eTx7aDR>Ljkn+WpSZ-E=2+|>VD_CQXLr!6sABq4KE1+?QG_^E115=Ca}1ay?%>S zS%?U-`10`{%EBJ3@G^sIXnXUN zZHqS?Q;rqtl{vnN%1sAr@bR>9Pqv=!pzv@rMqW&`pV%g~WS^i81QEff@M)Z20k6$= zQlKYVFMjLk6MCsQ@8#=hv%U)q7%WyVo1wZir7dU34TMJw2?>zI!Ww9a9&d2yINvd2 zBnm=lg*uYFHe~Z$MGoq$Ph2(xC;+XZPB6s5@iS<5Di@YOr(Msu-{*LcN+QQ;0Rmt! z0ISy5mGFgo2EQdBcJ&k^M{(JK`uY;R7)`W$QaN^xARlhK2harg1(Y8<;o}B~=z3oH zzd=}K@Fj44MWO)k2lR~GSqusZ^zcbc+Rb?T(m(d89&WZetShuD7zgVX+U>aq-1lC8 zO)^iJp;Zlm6RXXtR7lV1V|}gU?#}&d(F0i?OycAiq$-&>wjq!u@=BZn^)}dz{aARr zfQ-O9U6S+fDC~K0e?b5?hQJF)$8}gn#noa{j-`$_-B>xA&lEOc%h)p6#JrNzvZdYopX*fi*ra8}SfYcKS zCgKDT>vr!<(wBJ~n3;R)cM_{3S!S@lzVoVDBkO1j4+{i!C@p_)nAEe~)wLr4v1e&w zu2wjWvxa$o9%?oOZFEA@6nv^^hx$Hji;wh$Uphp*?kLqp6zbD$j9pax56~83%iWv` zPvmz1keK=DYN-Qe4{#RB^-EQd9X78=kLBDL8nK*w1yav+N?D8V)5Yq-u(}!yeEi)_ z9!s346IP&z0kG<>=l;H&MC|QFE?o>E;ptYjPxI|95eAD1k`Eak{kU(bIvN2Bh})UQ z?@nQ;>{CZCxoWpG7uQ_dGg!~My)+-pxeZ@F8Ssj9UZR- zhhjoA$w_Bi_TZS?(Ob?iS?tO1!ot7wKV7xR5%NCH)fcqS7G&|&CM@RR}U_7H^S+CX_c8a-Lwl@8nQ_=mUidKE^miznro4JwJ8!Car z4a%;cMj`ckThv`sCAUW#7c)CIbF~+l1AnkrqqrjL>vcFNqRF|=r3ved5z7o(d0VL$ z4$1)x4lzgjU>bJ92@-8+eBrPj_P94$E-u!pD`bw3^)ejHfpOS;zi(!~CHt0+ zZfwpz2}ljq+%OcHysX1n^I&dot+07r3Y=H8!nB&v8E04cZw2(c9;|29UwKPOQBcX_ zyrq)~3qnAR{&4^=%5L#STqU;UaH09M&ubzdSGcQZya^c#b*!9t1mpGL`5QuQZ}f;A@FkT+dI+oL&gd| zPv^(WZ0vLWABHoqG=<#?ylw=}*oicXxXRYV?CKz+2(4MtzAZj{n|l5PLPrVB3DZ)oXeYO~ZwGFY&L#lT_uw z%VD}5+`-Z=vR z;fRw(zfMbgI{>uI%w`gD=|n+s`eGuQbho1Nb9T#P(2LWxm6g*qfS}len5is-l|oee zW|GLT&{X|~rb;$!>0uB%;n^SIuE+G+wKDpf1I)FVY`98xFsceR%UDmZ+}w>)sjI`? z0fM)P@gPXg#}B+jx@Z!Ntib*kVdXkSw0M ze`m*86az)MT`>L6-dwFLpH~sFlHgMd$-abCN&VA;+s1`rriOu}yj3x_qJYGndRehA z|K_^IQRV@xHggMFwO(nOKQ^Tv1_j-war?GlN8nEcC(0((u+8mPKCzY)p}!e=*x@>n z^A{}75SV&G2bQ=A4ZYeqLczus%7+82O?U#zS-IxxW0uuYFDhUw@0>H9Mp6oC+1J?$&vX{^@K$Z zCl(5qo!vp53A#kWYzBBNSjeSqqhrTl%54k`1`p5*2QBgVM;w8{dmFc)J^fQFUmYA5%c?ierneiOP z^Z2KMG_@*V)gPa2%!`Z(LdGKUB^84)tA;RT5vWwY)#IN1=`WZ&ud5T9Aa}8+noSa3 zLN7tse?yR0T-4U){2>_c3$#OsR_fSbQ$50FL}-~pccJQQYW!1{UT(I~z*-Mjwczyp zEl|(MFahy2)1wCn-2lP-cqGKz_(fHhkh8Y!^yaS?D$U+ZfmP{50epCPd}AtCOh9y< zE$uPNi|kjtde!EtP$GOO|3F-R{s(q-?)^Eu?Z1_V)KCl}0>3spy&G4#$P?)4G$YSX zooYz|EtOZAKT8e^)d$X5W5~uJH?m3Vmgr3SKO(DRv3K{pyoeX;s;j*}Y0qBuVBG2z zM4y1J_|!fx&th$#;cEw5uu%wOFPs=(O8s?*f?$I5tKtVLu$dYkyP|w&#r&W$Wyb z(DZ^R2Oamv_@1=%sfpEsSVDhNl0E&vred1pY&My|`Z6;k#@|+A_alLRbmtvWk;2#* zEEnc9*5Jf%x~-_*XBZH*63r2Vda2sFVr3+feunRf?2KhXTSe$6^@ObGjLeL zRkX>dnw08F-w6q3!0lj?%C$?1G#yDVnCt0AGMig0;hPGXnGy_F?Z#f#7p)Pncr#ST zQqzPr?bTcU?lgV*0u4>f(D04Icb@3na6c{nWCW;W*_u4Fsi^6D7dx$nQ8uKNB_58kEZ+C%YVVQOZIm z)%vTV$>dFRut>5>H-gbRo~ZHbxh;i~c@^T4CZHFC7~1Rx zApV5vVy7)4`?T_Hi?tEiqp9KOrq4vGtxdWFQala6F2k8?u^tjmQ*7$2WsnQs%t6Np+YNkV&ZXSTakqHQOFO?P>jQDBh z8@~B+SxZV-gBlAlL8YI}z35h#t#uP zm_5I^-gml{zt;i2sdGd(HImk|oS5)$^}=ALR>zpmE1k5qA+a)}Ld@i_A}A-Ywz=cs z={Ra9)@Sbg$kN(JahCFO&oGhkB z#sZX?^Qh}5VeeS>5eK_vnZcM&Zg$RJBcq-to9BI2*Wo(+u{T)&7q zp2Q`qU=y5%-z5oAZDZiqZ}=>BeH7>^mAD%V1Mnya*kAJH>)*T&DwhuqoyauF&<_Gu zIb(G?)Nx6$|Gk9xsCy3@KFuEzp^Oas2}!;zghGD(?k~9SUH&8X!v7=oUNqn;O%;hP zXj7W>j1sU@6sGRYH=d_rktub`uo3>B7hsgrK7*uYs+^H{C85XX&SEYC zR$uf-Zl>IkYr$ddw4NMDFbA%?;)Kn}STx+EJh7Xf*=v~53Aw-4Au3VT`*`&`E;LK& zG5r2bE9`_(?c6W^ddXK+x4Sn%PC}oAna@ zdl3NS%}Q)c=CHA_b|sr!=+)nkP8Gd!`80Jvw{xVJ(l@Hadz0}Y(AT-vPM&(LU${tv z(X-Uv09BY;;Rm^%pkN2Np9Q{Fia;7%cB>aHcU%(%-R!J#R{WAE+W}1VTcUg#^x^Iz z(;k)>K;g7SUQ=ISR|Su(@>+>!C_EM*O{6813AUoRw$EUVac~ctLmQRpJUr*HzHlZK zxirbE3f(bGakLTxA)-uP4_3tO?CiM_KHl+eWZIujqc>Iv$f|CWB7ropyFO}1XvJjV zOBZHNb!Cm2k_wf4pDq+sXQ@af1H0?bOo)BSsQ&!lr3InarOC#Aw)UC0*NFV0=Qm$G zM+7ETF*8mTyS~>4kO^HLbR}9$@`CYNCq^p`h<{M!n{2EbC@&7--CZ69Rv4H1DScg` z^?k0`KN%7e_On80KI*iQxL<1X5?)>AH)@z@9k}oic3vRr^V*@ z9?{bZTuT{GE7rL`o)=H*?362eR9=4Wp_nY3`Fpa+QBzrU%@}QUEynV36wq6Q*zE1I z{QP9V&PPnlC9knVf|S&kid1PMwpT=YBMPYXP_*jMxqWmVwAgyHMA&^@|MAAWWO};W zY(%UzmeIHEl2Y9)ZZbNyq$puu}+Y%Y<6da#Uy(5N2Yq= z>LD3S!xEEBFj|zd-|ZV_L7!*MOw8t;Sf7?MuR}nOokFI9iBuFLveM@GQoH+H55WLF zke7e{WU*i;dcP(3OJqo+1UU}snWxzbL>O~g;cym*N+Sd8PIgF?byb_+;Dhi{$Fg<_7(^LY#(`3}?~f_u%omv#Fq-&)c? z4?vnksfyZQtw)Uk`D?_ExFp<*7izO^v#dmHC1az1RUjOOJ;_5Bb2YSY-@OBawsM9| z4!0p1cHin=>lxP^-qEwh$AZZ-g6+j_P9msVemXdqOdWKa>Hn%d_fyLR8tAb>M2;_Y z)@n}N#2)I;v8wa;7oI9sL)bp3w>*?mR5V@zS!UR`~`JY}md!xxp7GQ$W{0%m+L0ARNB#D0gw zN8Rtzr%L7ulk!^6bds>}pci ze_jBu93?OnD4#C43uWZx0!zFEw>%lC$S<}7&ZJ7-W=)X}&NWReJ9>C@gf8fh^~<&0 zZ$etwjtX~AcfwP&9u_(8DtBGQ1xTq}hr+yROtL*<0Cv+$|pPyX=8`eiZ1<+qZB=MnF!ChlxW3r_-V4+LBa(lxz!nv6| zSOLI@<)yzZP#lotkU+?nMa!5Y^11cUK;nn<#J#^27}NR&0h|>=5wE1ZzEV3fj_U(2 zs+8rQlwqd+?b|mLbaZhoErM0n@@4T;vi0nBBw31gkHICM5@!dJ+(x>tDMM???p%#! z`DI4Q>FJ`#eUjs#6SOa}mzz9+zLk~?)>uyDYd60HKFAadrE$GuXU8RqLINI*tv<25 z^rv@jhz?g3(PL8WOtvQ%0be(w7#;Md-&uID`wPmUi92Th5-|G`xgB!9CmV<^SI4biEL(@qGlB+Egfj)_L5g;nA;498jFAG{tUA|9^Gcf zzjIHHQ<@xlZt485@3Y3WA08K5(n&GI`F=~qZRRn~Gx63?g?0IN^|39DW_VPi(hDI! zLJQ|~{`D2pQ-GYKddJUCva+%wG5^ol2zVD|G69R0=LNLMrR=#wc~U%X4)0H}OxN>t znrS(UN=?WX4O~$mq-SJ8b(Yd5y8J5;=hpoeIk{A}*T70g0q~o+xcJNZc!1(rgT^LE z0-m`fCNQ;vRx@Q}0`H0T2kyigwAo+xmK-wgmO`*jHse)ejrLnvUsqLmXjWjNln{fJU{Ij zuC&SfO%Zdz^(P@0t7VHa`#sq%-ZnONUmDrop&oa+mm}+F6=m(xBH8sO@dIRh914KbWy86p=;%q(+J8dH?@ZWFqnZVP=DQ*# zlDW&%S4XFc_~vR0Xshw#WyP5o@w#wNHCe)vdotgddtrD*Jq zM8=wtV$FgF{URKnX#?LE?Vs|rPUB_UF-kNB+OuxA}L zmC%p=q+oGnz$Q&^f9SNyaAa7znKWtm+TRLyYJDI3o8~Cv=K8UG>f*DjpG)9?qCOjv zFPLM@L|kf6>yehf;W|07L=$iuKvURuCXL440-Tg}{TCo!a02e#pH^tV+Xblkhh>y3 z;q|o`e?qqH$1ixeax@DqFM@(V=EDTOQ5t1X`Lt~WEm~@1f)4=-U!xqH;9U=Y9Bij@ zVI^~aQy6#ga97G|w0ODD?wJt4;WSk!BC<2z*sP=N8fj~+K|48X(c zz#<~IBLF|!@+9bUG|A079vqr2hGCzXKmbGxV57r>yzhE-CoSx}chSuLc1HOopJ|M) z-2v70@zB_ij(@(2l`)a-f}SCkSB;||A{k~vL{VOy?Stp-S%LMk@Y<6gkg^HQ7tl9q zt>cZxENH||hq!RryStS`dM8vdsixjPTm6(+c9ucj$6!bv89xZ{`tBRgR;V%SKGdMUJCp>a2-IkC3pRI~Xad}^;FOO0zKl=1vd*3l4qMV$>t2g=T`P~^AIkFHE z$?PpPBj4XKLt6Itp=kKf#nvf!uDo;S{#8;zIsf6Sr9I@hnF{!HUS*b@Z4|j@zoRmX z>wN=>(synVZEdmHDL@Oobq3ryJMKJQiE~Uo8jX$4oo^_+*O{hcV@2=kZM2uqM*ROd zGIyM43^Ee68@@)<=gsT#B-d2K1C-Gk;FK|(Vd`H^=a;r+jEu)crJ~nF^1TUWZ6zec zodk@%y?QZZ=P9&+cyOtSO67HtvwRGgYc9`5XbI#$f_UAgM~(rL*Z>Ts>Q{NTwZq-) znGo%ysc8l4@V_NI*chNi8R-M3a^^uf1T*x#&dmCk%^+jl0ZV?&^N&Uv1?W^@L(z6c zhqdqFgFI}73ngO~#B}DzhzGg`I!OMC@W$4td`=x=>IlV6l zI}jZRO-etPre&kQ$bK`}7Y-NR6IGiD>?>B@@Nj1XE-@Y>I0y=`DGp#errI<4^0=np zntiXMv4cUmel03W@Bs|o>r&X7(^C3qG5!Ed^N9v~%{Gr#rFzP(SR z=-d}IHXC8vr$UQDC@D_t2?JpIo7@U|spNA86Uvhbc*7Oten1lRINc88uK@n9V?6J6 zPccQbGo+>^{$_kg$;?#gO|>}|1X;5J2?>34Nq;0`a$|fkV{R!g;*mAtwK529bc^3S z`u;oM9xa4z`@>J-X#q;vy3fho(dh?J@~{$Iyq=)1ZadEY;lk-1Ibb6V=p4`M*dBBC znq@^bOJHT&X+2z0yh2OOMxgmA;1MebpGV9^!!0Y5W9U6XcGHN6whadszT1jmJ~vqF zda>M%zf#hnedA)Yl)2;1PR+qWbCGqGiX;+* zBZj=-2x7zVpl3*_v6dg@z_d#O$`V_eCJ?M9S42}mp$*?)DOOkHm-%|N^0zy5v@&z& zCW@ZhJuAw~4V`pfX*aOoYB5)te4~ zqKeD}N^{TKb7d?laDPLsy<&a)gNE<@idcV8a0pzccMiZ^#20;=Z)aXwtd9whh9a44 zBgLsS$M50Cx3>CbZ680$_yJ;GbM#wiVQrt#oz=q z12Z~Bb0Q9130eIo3$8$a&LVyu? z@&FEB*nYZjNmyf=7>{g^CV~i?TEO}bdU^-esKmrDDn1n`JVu-p?kvELofewL>?yX{ z;AtipNe5cJRFP(}E!*MeeAa*XRM`?Q=vRt1gT7X?K}yot#{?69jI?MlHZ>S+6WGqF zVRA-AO_*{X_+HwQ$j|#%;q@C%CrT642laO8$QT|ow%l)S^j@(648T*mE7jgGSXfkp zng< zx-cpnE9<&VoDS!(E}xs#QQA}qt?cHu#dR&XSjH;ySwJe*DtWK|LLG4UFL7?!$R^d- zuWbFWrLQk3Rnn;-i?sUtl_?B2J}}VJRVC+MP`cOB_tGm6$vOKyvtl#$& zMWmTx&`2|{=bd_k+If$ zUEPY=jd6GyX4Lq?Sq#I~D?Sq)&gNSSD&bcGX%t?Mv4&w62~MpemVSg}Cilru2UlB^35az>-b-XiIS_$qWBL_N-8Fsi|7JrRqqrC2XU#E z88Q1ueofx7vSUu^j=PJC#djvNt1AH0X;<#ezkTS&#nq(s8IYOIlbG`CMggPG89-V) zP(#49mP^h%#*ZI7*8!&rYZ^|9BZ}tuyRwBym0XeP=4~PAj8q!F0kSj6Itkar6~CPq z4ySG&UDviKn3$3l7Bp|)$zE=`9+6$t*v||fM~VXh`AgyjoD4bn&1If!NK&(x<^zK6 zECxGW|Fv}yUX@;B?3Yjw``CS+tlIKsS^c(996Mo6_CSWpo&6Fge;HzypnPbaS_KpS z)`wcG$%f{ESw+A@%@KhQUv1X6_C7)1Gduv%%M0~A3F(fImsYZ`CPYZ+=Cb{X$ZzOb zoN8<9Nvh?9B&`f2VK5_G#0)To4ayxbtu-;}$J@&Su9+vfgDW)r^`pqj2SCL}j3MS6 zy*i&U*cjZLZ#;DzcbocdGTA?|%6it-)dd1Mieo-1%mEBiK7ADHfTzo#kj3c!;o2Pl zs#ms{F*H+n+{DRtEBB~{&z=_1Iy*aK?336()vFvmm3`V7nXa*%wtESnIfZF7n!vz~ zI7JgY(x+>&hm%A`%M9U;^S_;ot^RcCH3e^!Uq2-C&wj@L1&_QA>;K@SqCVTgpPJf* zT@-7p{Mq3fT8qt6xd38Fd3QuniHR`uei0~3IBmBt+k9@%oMjvxp^8FzOr1gxrY-Uq z#N&=2mzc>is=4y?mWmm`5MBltw3dd4>kOhtdZjXO%wU|q2NoK01@NRqXbXJDD19))oS^7inE?jiS^#GHSBbqFZt z#T5qG0sI_Y*&r`LS7!Gw%h8#gA7`%&G&^nn@o$(@d($L%`;kfV zd?U&6LKT|N^(`QJs-$*HT1}@-x7?7=La8q~?(-zg?Zeg5E#FeVnxE#o=9U7bL{BZe=)GxZ&V(A|JN4t8RmP9fp|J96Y z!FJHasziTu>n)v2u9L$z#dz>RksuO!R;jWb(}Pr-bNHq{I>yvtKmm!DMn3uwpM|-U zt<4x5K;$+(c6X0SUkxzh`{1|v!*4ib?@f>4(lonG2u6m3fBmMV`3kq#=u{g~6%_Pm zq7E>l$jdPw{4S(1ym#+cfQvt1WnU_Y&3)%WTUTGOYF zi9?F~Y`fpn8f<2y+wiD@e|l=J3B4_{WBF6eQLmI{N55j4C8N_C`9pv}U;#sC1ErWl z*`W51%{kwf3{fGE>Y+iS?Ob_e0^3WjF=W%0#6T2royMS{*UW!4rc+yp^5=)Nv&Yy# zL{pJ|yMm7vx_aLEWqzEFWok$Q{Z7#AL>#NBYW`@SL!OMYHrpFv{i`T0i+OTk5xKL? zctm>5XePhmG$}o+gcOp6N_*zEk4e($-)XQ9XJY2mN?yxjX2yw$I4T3Dw%+7Zu*Js!Nzz_+ii;Qd)VfT%Kj}KMmhcIA}+wl2YLyPFw*obSft&hW*50T|Dxf&6Q zSB|^BQ#GqHlkb-sN*2k~%#-P;9#Kh9q9|m(qGlGv#?BeG_qW z_npW!&*wgsb1YR4F3d;rp?Fzae6ByrYo(PHog!`-C zx_zzJTxaTR&lGIT#ze7jgb8rZL4Y)qWzx<$ZHIH$4hRA6Uc(>CdK24baAI(_?FSd0 z&YAnuH4##18^gn71k`Gx7(h`WyhF|hGNd2ko1C*TU;5nX6xaguW9lmUSzDs#i+Ugu zu3Y;gFQU>WK+*JxX#war83b)gjg zccJ3UJY9lH#7FRH@+N5J^|1?ZmQm~B^8dU547MB_leD{wo}UUf<3f@3(&A)jSO6cb z;GQ`R;OlR>BEw7kz^Q#5h};oH?A+{c`@P|VS(q@H0`<|B;W(;F9Ero>XZ81830$qm zPf@8}=u`LWmZigo718M{7ixjhAZ|CUyA!k`>aWQrhQ+1E8fB@Ekw$t=qqW?aRD>pj zbpUmqoCm1yd1v)Y(@e`h&S%XXYYi=BuzGBi>i+y%l5T#PiDz<i zI@an)Ac*NfNKehxJH3J7@Mr-TE6ZX}4^s%*&$Bd0n-k(NH03mgi^1jAd9?56XvyI#gA7J^~|;USdI zN5Evz353;k2&+X1J&FJVp17zneA-T?X!9U0K;mWE$-sX8wTnWQK4|+O4z41#&tj4a z{0PQU$}>YHVsDNZ9eY~7l86F>viXK>ouX9f%~&@bmh~f(h_z*46EGi z4QE;RYU4hT0um1(AdFhDe;l4#R$Ar6q_X|^B>nB$_)NilYV`2tE4C)tRaD&J*yw1yQp02w@Wx)~E;TuNif zPK1Dr{4A{G_C$Am>pJ)|C|mDZog6J`duTY;$+$gwmD&dxA-|CP($gZlW2O4#S@F1a zBMbQR=Ocq|19nA`QnI+=v>?}|+7Yw?;UE`e}Y72LW2-Rs+my0U-^ty+UC+M}FNu{ClrzwZ{ z8y9bL#`8?vq6;l6W8U%D^$66po+vRTrLWyhZGxT%YNZz6r3X@9L!FE zPw{w`_bOFv9`A4d5x)%$Jh@^^ZyN}HF%(P8a5F^y4M5C=5tS}ml@o8#Q*iXX1Xg(r zIU3>Yi>+wgu9Ng{g|I@*>4%2Jx1FYvNXI9=?6oI(vh23(^euGig=F8$zmovv$p541 z8sjqSqWx1%c9S{HWZQ1C?V4=cm@t!VyUBJ2uvpiU;!D@OY=j%V{b#9B5br1Oqmm0djp-9L-y;S97YF!$dljM`xpRBY z|1me0u~1W%GbvfI$Kl#UrRfwg?P2v2tG`flA{Q8bf^d!-giHps#gH)P-_{LX2T*=I z-wD|!`v2L8BrJb-6Akte;50+oIM$*WH3(1m$`cHzc_eeRV}1fC=LfwM;6OozAxrQ7 zsQCnk;|>P@t>G{IhJt@%jutN_2FzoD;>U8(Ts+Ye)os&d1W74F&7)ppoR9b|QKm z@Yp!YXM7X^>oV<>J?mFMXx$EoG8qkvRkPzh%Zy$>9sf;X4%VY)PvX0_Sp^Xh{as9n zghfVPsyy$IN=QyXLp$)MT3%=Nh6Y7Kh1aheYXE;g#3&Dum7?z{452P^WZ?U=0lm`tRe+=n8rmIRisI%3V>X?FrLQGO zV^cV7lFk6{0`NE>^#e}-i|r_xFk9SkujQPHCBMnX)>iKDV+~8y|+2-2eN;- zOjJ}r>Q$eLE)y>0;9@>7E%c`iqUF; zF_9P2_OjWdyz&NAKW~rMPhiU@i|8m?l7h=wdWkP(m3l>~k?-`Dem71VTO!$_h%I`` z>k3kUT9DdZQOUpay}^YVn>t3(G0u*|zEzcBFcYE2l&~Kw&DA0zgrz^?Iw2axwC$>n zY@e{A;N5WUuBOJU%;>!6OIX;tJ}EUtiOR`$X~R=lw_-$tUHSQ@a_(H$xet+=aPOR^q~p)$N<@B?N(aj$ z*vw&M`+P{`He#B(HT7xTq2hULu2obHys56gncJ(n-4kpoTj+{11P#W#^M=2RfB}9N zwI=58?sRIAOeo~C6Eu<|4I>$)tF*TNU^dQlxE=xJz?!?5=OeGDv@J7j1UQbdYda9e zhPR59vLBXh{ehDI+4)!zih(ynwp%PRKFjk)+}Em@5fwF_R?)$^p#N-@nUB`Vg>9mf z-`Rd-tg!h7mt{g%G}WMmV=XK-93k6KY)E-;XX4q}J|=5?DA#zY0rKrN$)-}T@)c*L z0}-E_Y&|Nf=!eGEE+in2?vfUTa@N1QOU#m!%sp?In%A55RHI|IK!3Fc+N(Zok{DDo z1$coNqWVkg_0$AdpUEw39iN;YlP~X!`e|M@ii#kNhZR-5x<6&>3#Yc=Q>303lLE{Q z$wdD5{5QPjW|ra{9qtyZ9_;DQc^q-A|HtFdN@m~WrEUhe@C@#weBoMN3nx|uOJ4CU zpFYVJeFt*s1Ky+znfZrIUtL~m91KVRTr(xLo^3r>WN(K3?APJ#PbzireSIvlFK{%o z+`HTNIPvmycW=r?HY1kEa}NiX{rKol=Sz3c)hUy)8NQYsgU+vF-3-|kZl~y^#kQ21 ztUVyiF$T3zsTC3#P78HjfJZo%>ZC=klF1zW(>)wY*z%;e0NNdRh`922dR{R#CX#1o zGrKkV!f+%2ZdI18XjSI549JwLf7WQ*wt>;;NNzvj;~#j}SxX5<#hx*4Zh-@0ElBa$ zaxH)J>AIxnH_y|JF*LYoA0P#$ix+IZ@yRz7ed1O{&$?w_2bHQREd%-P*@)k6XI^5T zA%(`^)vVgmeH3BA@aAyhC4NLW<#$ohuN)lMhW(Mf(a6u+Su@{&te4t^;7LbB;Mi>h ze+G4OKSJ)s?Cj>7dGlaXvlrzALzJi0ClT=KUiA^M1cX2Kd5QQ^|2h>?*E0cLkQKbZ*$NA;J zcF3~^q9}{Du~|cF77|TL?(me*vz&o4FwJ)8J^^ck=9QqH1qpcU8gK553>x(>zLttg zhiEfIz7xA&;AJ{S)g|iPuT27jf&}v>e>~kBPAI=21N4b%AZ@|;I9?V0nY=KyQu<_k zHnVFEY`PNvMU8ArG(D?r$V`{_$B;H&##zM3h(xmKUWh?)|o2-soZvVkT|g2oFA#Q68ms7xO%&c zB))z!j%#l>ADQb8assEzD3;VYCK(Fg+S6=_r|LLTR3#imHa4j$ZfZW{FMM80P-0Qv zZZCEwo

vQf6omuK++~)pCk~6b7(|S65E#+D2#|-ufhVC+UUd;cZYtzBx~5Xu*=L zxPsSQU&|Y2ziS->Kt+=*L?Sq-nXb|Ytd*{|8*L_=hNAeP_+Dpj3JCi$1swOsyAoRW ztFPz1FW`%RYiN;m&93&|gr5A~Bf3BdL$c`#jY>0I*L)q~01|28fdP23M#r-OQZM|k z$oxQF*Rxn_dU-p4v)^d06vmc@@pGJSns9khZaGRc8~a3rULyp(}BUpm&nKZK2Jt+>csT`c34<}=ewotS3v07 z($Hun(VNimDB8;1n&XXu2QQsj_Wn?z!=fpn(bT6%v-saas=~jJid+)ZlYH#j-CdDy zZAmma4%&)DcqKo^?@n2!%gzMA`Z9l{d?oNDKkF{;g@`6)V(>EIM>pw}=tt+GGqG#3T-~)>(MjO%ERugM`W41AZ z^F`j&YhtmMC7PUPg=*BGtf^qf!cM#vajJ{GH+6xygKib||+=hXJqsmRJ$pu`R?(n@3aSyPZIo%bXJ8II3Qr})n z7D9hQsAMU7ob#UAhX9IUIbPEBsIWXn+ZN6GTw`Hj%5Boob~8HTJ~C=wrTWzJrZp*r zXED>E#R{F~fx(5mYJ%b<(kkqNEHCH}GOup`=TdX`9o$CcuZs7Oz4R zdR|=c!IDKl#03HVE+qUz!;+Mg0_xa6iu7hx9nLFAXtdrH^N&9|M$KY=~LbQ@aT zN70XKVyaYCYY6RZR1?4DK`$b6pA68c9+}4nK!vi9F6VQ)qW8%hu92dIl(ZT`N_rH` z_T;kiMNCpP-=CfP3*X*ac^q|wgf4yNJ~k&1QWxX$tTdW`$lV?-jax5^LVD&ejRFt4 zRcm0!W6oY9f~wT!Hc4uzpd9&ZuFzsB27 zw3<@fWt?$Lo-O9*GS9wnr|nI7o^d`kKAzM*VbGqhkLy7hooSz1wgZ$pWTK&aa%m7Q zYwY=Yv#>@19L9l|>sj~X^=#NAwvw3X!bKn~OGe*R!Q*lyW$&eKsOJ6I(tV>%!B?(w zO$F7n+VPwDW>2+_j0BMsF=P49xNtx_OT@vcA9pNWLMP9<;MMQ#(qRt)@L6NoQ=+0% z(av(V_X1LT2+6yh!wG+~@6)eg4#$`iC7*8_2ge#@m$7TB@No7o`R~Sf=t7^~w<}k7 zq4Xg|+Wgykm;Y&@P}lR6+9oF`npmVRsre>qm=_TgCam)eeWk6Jy6m{>uth(IK%!tX_4y{~22-^BO90hOcfJCgxtbo6p70pD}7@B8RGtzN6^u|4eS z7PwYs2=^5ydEVRXjpyoEt{QmV1cm`cp|0;%;MqM6b8$uxrmyeOQDLWUCtRJT%sg?w zC>YyrJrU^X1~sJaD6if0rRF>^xO)9stVYB7Z0vY7qpUZ@bZJFBXooi5L}P=D=Y2wTR07x^{5W@wMJ z-Q;v8Z47N-;P-S(X*Am((nhaTq$s;oXTD|a^IY!K|8ToxK$@633}O5N|aG0%HNj%vPjA8MQ5n|n|+8ehk7+8laa=JR;& zEHAHetELXjfa2%!?rBZR(|hjjfnSr*DB#C=olI~w^Y7n)qvGWIcW=Oe#cJ;1a%!QM zp@0N<3yh46@>B`Qojz61%E z)VNLTrXywqh54Ql`T25WV@{UGfPepzOqc#yA)cKdU1*g11i4 z-#E{#Ie(jC>2}=eeQ`(YokQ+BuX%7}nJdfR!+@|IZ-)f@>cLV%O?+Nn@3y&lO91av z$_&ExmjSPtWQ==Ei#hoJ|IM&h%b$#7Ud1uVH+QuEc8KmaRu>42(c(aMod-x27}|c4 z1s?I|!wd*L9P}qSMt|t2)xaw|W!tH4&DYYI8g4CFn8O3}u~z?0j-1NpVVloSqpEiX z&yX=Dpx0{#i%fGFDp@h-In%bT^v(3PqRO|v%xXqiaRr@|zrZC(2E~!ff2 z+<0VcQGZM;|iVL?fr2jrL4#6)8&65`qI&{zOW(8jY5c2zq$=#DUkz2g9Bd$ za~aiKSw+1aK4n#|8hvJTH`|u*dbw(pFHr{hB_}64oX6>72it3_%QLB@P00U&e|>wN zp%9ny;bYJT59-2oX*I^?wx_%&k=;KD0r^ySEkI$ZAr{gsy_%&w$yIb^Gn$G-><slHD-C@P|DZEsuGIs%K=x499m7Ch;&0dmfekw%Y#hEl{>0E5V{4l8khK|#rC z$0~tTD_{$L_%{15YJyQL8S#+jYw^k?;c={f3WO&Ko zNpkMAD=M`L7F~7^7U%uh^N|q-wy&I=I6xng0yET}#*%v~%tq20ttTGdy2JLD7<}Cg zQqmGWa6g3sKLiIE3e}s@u(>hak|Az>0gTyoU+AU!xIVf*N`SL2=;g)3X1g93cGWYW zyq>f~5?oEm`vTQHPAXu*j2*0>4Cm)afzyXRIXR>IPq{1e!fqpszUc?Dk`1sMgAs57 z78cb1_4ns#eaBj9@fEhH#qQhtXL`P={R6l>Iq;qIBUtc6 z9tLU1zr>XYhKS^H;N!fe+ErpDpD<~@M3MEx`=9o+>HnCi9T*+y`FE}-lBK^|z*eH@ zU_b9{v^FM~cjm0nuFG07S`7daY`w9_gkri4)D|H|n;{UT8(V*3mT11AGhuzF3h5R; zqpha|t`&}`54^d#*bKy%`%ZwD+jpFs=TGGO$;<1+7E8&zInfskmJ|B&Jk%TX*PsTW z*v4f0!gfE#oqK;$eYF2&f~5w`qS5Xwz1_2sm+^d5_t(0P77L%-3QpVIq{8pA8flsN z7MOc)#s6M%dTanVV2}3JZwy?sz<8Al=m>?w-vtJP4=3X6>oA4Gj_nc(8W4tn5<{5N zV(omES!<8IEj)6~jl2V0Dh$O+PkI`5BdU!=$#;xee)n0?y$T0-Vc~OvuXM_tYah=;XSzc@+)RgZ@&}iM<`*imskXWRCN|6O4>S}wg*5qv z;NL_+%Z*|E7;qn))E?wR*I-5g2v%8>)2{MvqY{~tx?;szyNCPhfwm0GSubQgc9t^@ zsiOKj3Ay?Eqd2R-j)jFrL}>m?)i4Bu??KYh;v$Y`7~$Mq+_&zo|O8 zECKm(LwTdxD$n|g89t_p5B1oTPykRK4XEtmjg}ysJmjJF1tPPe#eoUBKRjfOCNtP} z_Jm1*C{V60cB8VskdS-=P8!9up7_`-A0}Er;N$HH1k-wJHXu1@XbjW;^HtAVgfCqC zc&$-NK)hv;!`uudOd7Ey4KT+FA$gb4TTq#w^iuOPpsCcuxN9v&4Hbqcqa z$Kb|n7`aG7Vrw^rnUbL>8$?0F!f*TR^5ts)Px8~bK29(tH!gHZXJ0_9{*V-~D}I0e z`|tNw0Po`BU!bN;WmSev>}mOfPL%*xYckrs((D*hpt>o)XM%2amCsf>m7@U9(MgMg z)lejm$M&loek8h+s=qCKb z$s0L3e37$ggQT``*E~OwE&W0ml0rhItvL{+iC`r`$t>m{F`BgQ*W~^%J#FPU^8@qU zP8I@|#m?CJ{HMx)I1Znc7w5~12?EQDAGqAENN%sr8LRac zVB>u7C##k|{F-B#kZWF_%_ajvv74Je46MDM!Ka(uWa8bufrgKl9( z@gy~TwyNw|Wv2XU^l#sQBecvAZ> zo^s2RiW6sG2%PUR@C*xZWEMrt*5mhBsr@brwaa>U05(%5L9bnxrF4I$98a~(A>4EH z3{ZQ_U&}PMPK#t`tvz=o7b}D{Hgb6o3@xXo4${n5xh|U;egMs4$F``?d5R?{XlURG zx)>Y!O3+)q=08d6{x|@ev8jp|a=(#O>olPbN)Tcrot`D+)t{S?Y`;m(QDmF&_Cmd} z1xewrnDab@VJm`2!w`WF*kkewggfaxjg^0vNnoBzqn4ZPB9hy4;+u!K#L}(PiiCt% z|Jf;u#w%yjKz`@k*x##N0qJm#8|5%<*+>34k-g=#4*>rS+Q{-PmXB`6mrn@~ zhycK~)V)(sB` zZuT0jC;UFirLpbpCmSx+#kS9Y09&zy@Cm>^5G@vqUURKMm3Cv@S0aCLx+4~_q~-IZ z)oKJc>`SKq&1mpx7rhnx<*~&rrlRNeI5BEI8?4F_3nf?WW@+j9Da{r@&^#WQCW>Qr zIU53i+&~%qdVjj~Yme=*%jv{ThBrFMj8ZxL>^y-8BaeX%yATN061 z%c0qQ^J{%}I%Ch%9r5v8h;Jd;|8oHpT2X0(k=HUa`!bs+|;ZsJ` zM`TlkwzP=61vP5PqBAR&$7c9eRtALgZNJI4IG!yfv{`G~m#RW2DD31=AL9Q}gO<&L zI>IT^O*7t=9GYSLH}eM8vhQ&-LF;-u`AVQ&8Hjxt?1frReLO2n< z59^=Z9SIL>Y&`1U8q&RA1q536arHOwyf=1_e~-^g8#0Erlmzp&)e&1_s{;w?N}660%nAR*frE$;m_&YrLR zo&2<2A!dLE66!hQzmnWDYT2At%e|Nmw=0pR!IE${jVX;ed*XusOdi^66i4=VEJHv6 z)$X3o-DODF;A_zP?cq1V_3EE}wKWvlO3$r6j?S*Gt4(vuanS<0T(q-)!1&*#4O9zq zU2C46v3XO+dhwS+&d9U!G za_vJvTMP>NYug#~YerGs48PcEFZ>}L?8=XTUv{m`c=+EgCKCP^)B@u!@akl%slWcl~%E}9>7Zc*mDOa2eq82 zjw9sF{H#TAKL3b#Gc<*DeYl4}=hldxG+Z7{-P$Thv^z-st(SHf#8&zo;{ss_L|Nl= zF|73t#WY28PG`7@O3R%?3Bu-JMDu1*#3KjibHbp51W0=Nr}?Vhnj-RDXY)(O(;If& z_cQKlHS;n2C(W6wy)=^0HQ%g6+tpl#F~EG@b~}t7yz{+6i_T|3WWTageBxmIc?*8k zq0*N!pocIC1>X&8LTNSefxKMNYTiA zhM~R)fAsdh5U;89k`;s=6B%L{bWN`(mRI1cXl~L> zWrGBey!5PMUzvJcQ`+WclK48p0bJIDpsu^qc!-4>Qg?>(g0{N^NIgBYi=`w)=i@2X z)9DaCOIrRn@hCTtbA(pCr0M?2;tePG&D74UngoocV`^9^h0;(g`QnWC>6XyE^7Ff5 z7~A;tT2;1Da%kUdLcnU4Pb&D??R$5*mYBq+&Ns=*jAThEe=;Jmnuf1=>R3cQ22)JH z7Z}E^XlGOUTYC@}GM-wa^zTg{o2Y6zcFmeOO3QkXT@6>@w^@H0`wGV;42-FY;ti~w zh`#ot9R2<;0~k!qo@H*D&aI?q@t~k?S)v8xN?(sp3O#f{8F1LF<^KX9X?&)Z6qVk_ z`VV&7(Zg6fBIsEI%&wtvh=J` zCUW1XMSm^ujH9ju3^+x!%;E0RM>)eaZEnAWH5|d&i05bW}{rcV+0bQple^T*h8A%IF^gFAr#cg!3v;QJRpm zVJ0&OsxfP#P?UPk(}h|x+%Cn~i!1jYa-=t7hy-}^m?seY+3-NzZ_xdj9WzI54x556 zpbmwukAo81PKUEq9`a7al3MA|PN5 zud_p&J(@Q%=)~OoHqi%_jLir$4Zz#z#8r=}_}XLKL4}#8Qkf&a23VVdR#s)k9i0oD zA<^EkrsOMuB%a9ZWj5=`r{T zl90PS^AqMl>~=Jk&@9D%YI(B1@;peTgfP<~H0+RoGR*7_8no{X7BR+}O}pV}ypA|y zs|7FPIUiCJ$)QgJ>@NP%gTV4mR(F;}pt0O+d-spL6an`+At1WynZxn#cf-z*6^YBP zf4>CX>@|6UWq8e9GV|ja&<9lz{-}JWKX#@?Q&6X9PyQ56G-J#J*UM@( ztN*LB^U*nY{_oUfp-f)%R4l{&7rjJiFM9eVSv_Sww;$deX`7s8j!;s$BJju7_)LLo zmX_uV(S3C}g_M+A(Mmnz!>bt%LhGJUp^LUF;yFFR^gJMopNuXvyLd~(9aFKHHXbYT z`OlAsKI_#G*j&o@oYd&bWmHt5a5r_fa{7Z>jhd!K1*8it>z+Z$NE^ii7jJ*>V3XQwuYi1Cpe*Vu3&&rk%Yh+?b85i&>?S z#DE355aR)6;F|JZF~@G?8liS@KHM+6{|NHan|}Tkm1H?x1qqJ6#8lD4thX(GJ}fba z**Vqvr8}-en+q17fLm-&eE-RXp3^@+pJZfOwdDs*?s`8G z3f947e^pY3vYWd?MT!sq(17^%H3ec~+s`Q8Lh1nUXly*rnv;GicqSYa{4z^J@Coi6 z@=TQR;c;kS3W$}>T6*aG&AHt0)6VYV9lpysW>~#!hMDyGXUhe>sr0G}oisv2GU@E9 z_0Qyf-p|FFM}qB@qqoP-kR~VQS@i&|V^KU9`|W+I)0Y2D{bg#SvNK#b648;2c2PqS zGoDp{{LXJVm?1pAsRf+K`+McZ(HuslR%4`O4vy;QA0)(dbVz`c1<>mJ_4{|%N>&Gz z`!}eRM#n1eGyC+#WD?9cCa@ZtL-}yY3UmWSB8_^30nZ}A%Q=jJ+$leczIFuQJgK@4 z2}^$a{!N-_Wn5gk;nW%aox2K7u1&q8o3p$nWh{?Hr2B2jt^D+wqpn(TFpl)A{yQYk ztOEs^OlqKQ=PM>)x`6sE*HrHEs`FiOS4|kflUnk(4?L_Nl`-zs7`O84RY_4XWU&4v zu{VvoJ3^H4ABM?78RhsQPuD+$Endx!uL%ij?Y+b6-ljaJy>K2R54%_v*16>*%lWYK zMUghTlA#O31qGIBsoX{|^{k8-F6Mv%WrQ^=!ZEMI_qH;+KaRz!Gb4nPh`4FTqb=cR|$Z z;IY8p!j%WPOEc}XPZ2Qvo7FV30pHoY&q=n!xB_eR17$GCN?C@pTAF;@%x_`@07uk5 zUq=wpdo2!_;4Y0I%yp3a$mRhr^?82&H(C)aQ?};1h?_qYQM_cB)V;mvCXEiH7z~__ z!Gw3)Tluw<(ba~%!+O3lZp-d{vP!M$a8`!0h@47bD%SU-;5755T;$=0xB|K1PCAXd;FfEC{K5* zr>ky<_}?eqlSIObjl-2Q zsQYO9nss{P)O43!ALAP}Emnvxe-!k5MB40dOQA5KJ{e;#EJepbR9;p`5WLtEI7>jV#wWBAz%^}j!pJ1mqYr1Qe_ytxh1 z!hnN2&62IIMy#t)C2WB+1k3#fdK_8}2Z_jp`7S8IZf*yJ@iGL^U#g7`Qj{qUh!+{; zPV49YW%lB+|Dz?)Y#`aRid^?C;)@DCXoQB0=N zpR?OOeL>$|v+2onwBb+)JJ7fJo@Vz9(6V`kYO+r?n!QB~@wAlrbko^jHeZ*v#;5sf zl4&4mwWfLs^dTi_;UFYR;mE(D5K0O8z5~7dc+o1f2P9n#of`hE@Y*3X3Cwb|3)8t8v zgTUv?|7>Z!G{HlAdCAqadnl2~D7hf#qCL^;-P^vQ0cbOQ zmiuLC$c!PHs2SA$$9X`pbmMeCNa9)#sJ8>k>a>RvR-%pSWan-P(evWI!2bcv;tNQf zeaVfALemZ*p>+HH`cF^R9l8{UQSFJyn_p2NPTrNh+$2!co{F8wl-i6k7%pmEl;!;` z53p2BQz|)_4q4;vxW&YPvvx(G)Q&38sfB`sp zpt(}3PBh0SF&Z8`0ls;>P_M6p!G0h(9NoHK6><8^o?2g%;>3<;D2HZ&dbpcJM@Ir1 zVEgCfdEO;gfbg)zbvFTX2e}#_Z?sfG!n#UELyD+Mn#rxtWYIsopUhjx;2_=ST3iZ} zP(zR=O>;?kbxz7FltQegJuHYkrPWqdOY&8T-(Tt7kH}=}I=u@DT&(|OJRBA&)6TDE zoTd1@76+UH;0vTPV78G2&==t-99@gDqEXNu#3Dh%iNE#GU+%OPt#7V!JxRGz&#=_g zsN7~d`Q1fNAw$}j!t)$AK(82*{~>Wx?3aFEQwu7PO=?bfVzqA~)jzbIg4}-z=ngt+ zRSGIuT~IB&>qE{jjnR_So6W$L;XH6Fs|jyx#Y7=(W96D_@_?RFtryv`X)_Tjq79LY zQI*cTXDp&m?Rcr%F?@c>Bl#mBDGo&g5N5w(?nVbLp z>wgm(2Y|2 zDG?S?BKGKC!O8*0+O6);V>R5l`V(DA+NI0{>JAH2h%hVRNG^zZcsdDdC;&Dz1OpOR zB^&@sPtL-irm*>*)f-0Hc$L4+PFqQ%Ju3D0vMggF8-EaMY(%(nXRb18vkUR3w!}L) zg(#UYp*xnmaytn7-6ZMa=4$ey#1q~Qb)8?7P#aHijz?1IBZn$PK00O~uEKJV6`)0z z`rm6peOxmI2p114^qG=rZit|3N0WrNl{1Hp188$RLmSP za;EmmLKhs46@O_Q0GEG#6z4;~ganO`fbL3Y)sxjaQeY6+@tlOA7OBDBNXoC@IR<0^ zVqx3K0l|sWjHb2gX4W2CG*6DZFX`fPrY#{;4KM4%jw{ATujMYCQY!nSl$v1&qe_Ob zfN~CK1OG<-8SU0Lgmj1@5F`Jq^bwX+&IkZiPmlmuw`8QwQVh~lGzv4SR2hKd7Z;}% zRAE1$3e9@+TeD`B`9e$+HNj6C-H~Vxq@LWi75PV!6mtl=!4E{bJ&OgCO^z!haK3)`SJbkrTB{obTXpgdUW@X=UUBJY>4pE2}Z0xo=Z<>Fs~d8ySVnI4su|3uTQkK>Y(GrUO=h09P z3`j7TSBXD>YrWlxd-_`5B9vOyZJ8@-3Z=wT^-qw&$m1b%U|`^n*gRHc;6Y2e?T93U z?a2TtI_fuy6BQygwTeXr|61Mn7_R`^Y$i6 ziU}vwB`s*7t4e&`ukZ$P=_>`;$(BLIMHZU z#9hYs3u`8~<1+1>G2y@jx6>DcYw&WP;ZUpbAl|9e{@Lc5I=v@pLc;p5W#6~!(zZ`f zDc=+In_BUt$p}3*`aRQ2nhxFa*eS5&6nccl0`i1w@7~-1;Q?D=QVj*|F8iM~AQ-F} zuR1H%pa+2%eoQa}*le&q{wE}NV{B70ej>nu%7GH`H*k`^#5gdNg1|okh`oqKmr99@ zJw?s*wcSJGbyHR>Ks@>U<=BbnO84+9eHt^d*$&6^a2UtsDV{u5C}fP@0PD@u6U3)F z8a+Im+fWYyv{#~Qqzi%fd#)r)U(%04Y#REW`uYyIEe7*9-8}C?oyy>U%x~h-7yT&^ zf}+dr&zJ^NFYN~_`~@TZ4FGrJ#+~OgD@=J?Ya&A$K+>p&{s5J!s%!`nsHLPnM}>Ug z;b1x$*Im*Dih?D|x#|>s)n%vR^evS25|KYa+6yTGwP|q?j-;hnLVOowM$Q?H=XxfR zyeBDFsArirl(sKv@x*I(kjHXh;El6 z0HO>Bd9mjC7n+Der7JTz85_D{nVsPfUdnb96_q!Bg6CYMmO%4*ucd5tZnXSJS;yLB!t3}CPR#e$Dp~*b- zr(ONGj@b)^L^{1Y*-+$I!n;3Kv#)Gz-tbcO-sa{TYoE%!sdTfMf%{9`#0P>6)h8&$ zuFUgJXr3EFvRMmY&`f&ak0{B4?r36R6g<4JhX*$v)+*#M30h?8CY#5r;_Bp?J;}S~ z;~SutkIPs6xy$=-H&nVpP<`YayUiw9rk4Z+^W;qtM#UF`M!^|XBlT{HIlta|`kScG zh4R+kl663I|BdovZM%Vg)uwL>=aG>OA_}48hm=(w9!?nx(zk;A2!oOXMt=bqYcfwj z%D$KgFwm%8_lfIc!;48z56|Fs<H7*Gnn6C>sW7*x&cw_ABLjZH2@Yq1O)V7-#)E|?IQkebICC|iN3LW*6 zLjkr~kFpAYb_3dN1U3fwHk)0^Y#F=_quuKh(!GoztyXR6mp7G;;o}6J z`nx~s13V)MWudwft=nIHo*KlCQT{sc4^1$@ff3!$3WmAI8Y6nwvnO3|6|i-c0OL&2 zVhimYAv7E5+=)Ezb(aS2WaM z0LOAm`wSH{Q(G|s5B|>xm9Q z0B@;~l|@>)1g-e@ib4lbWsa{BP?5(zuM}_{O>30I5Rt4M47_5G43v#;QRua^`#Z_=2IS=}AwKtqG(rX-%&~oh zVqznvjZyZJEurhZEoY!cUjy_TQwt{kUvp5Pnc25x^?TWrUEP4a@EZEXcNZ63_9OwF z#ewAI25t`F2~n&w)eovnFTbgDFkN7A~flyAF(>z7|P&*$3TRtc>=Assdg z)tK#HJ&8$30!2vuzKI=-yC2U9+#dNQVWFUbBM>23Eg5;F9hg1gy6qEOKHMC(d?kg) z(&Vd<6uJKTt#=!b?cnZmS}yTECLJN10R9v7^z-Oa{a{0$7_Dtm67)!h)MM7$Tb*^g z2Ve*Q{{8|H-yo5RzRzS4-$Wtp!nU|pL%MN>^a&CS;A*w4uKPkjKuvhCvwMi)RhDSMHxyRX+SK?12~&o6*{_`N{Ci!cEWn*#-#xlbSNZpYH0 zir$cy5WPUcIy8T0ZJhlu0sVqO&A};G$&-{>=}3R|x^rV;-d0FQ{L-zpXiR9#8rrU? z3D<+-l>9(uS0T8r#gt_)kLGW(B>s~Jz$9$rHemYNz*ObM2}rzDcG^7EEG#25YJ=Bw=(J(9TSfI78f_tbU%;Hs5NNbaJX#(1 z%~~7R3-7a#2`3tWx!-?ONRmD7q0W}8e=2K?i(~-=3SfHqSY;JTlVb>YNS%=p$oqLJ z9q1MwpRYl>oPq-eE zZt!5O@1Uc|K1n(6EV9&>O<&sX@V@Z-epjpzk5#(*emMOX;D!)zb2)uU?D=SWVH?r_ z=}Mh=O#tuzGIqd0M(FE3YvIlV3Z@IINMeF0pS0H;A<{ZI45p|{+&F_ANOdyisonRI zHh>v(HN;)WAkCL6r7hca|rm8R4%bV2-dz*3pWK=lQ6MT?mcN5l_O*f$edwJpOM~*2c8bxo?HOs9g z1P`0?T}2mcn@3VALC=4P;AzPexL?T)M z4}i^9LhjfoaKCIqx&)KRj~Qtyxjg|SX2?dJS|YQb1PUzZ)qb84ntVXWRKgg zaAe!)z@dZtLBjj3wmLhev4FXpWLpCY(H~!FkqJR@JLQtXuhd8Xfe18*LXIT0UVcnIVGKgbEaaK(`Y! zufIFRuW)RiMWxZJ^07lbAxzmwaPC=dr~?c(WQs6jQH(emPayH1P4H(P4Qw^qGodF8 z@5C-HT=5&jeo#<^ogCz_4CIx~{&gsBVY|7VR`W>9sC9LQ;ks`P&J?EgWIi3uW|YfS zxi>jj$fNb3@{DiukBdo@(hqu~(GsN%ss|>|4*aOpC9wm+Ifq9Td2zbBJ~5VU9qp0% zWH$y%i-He~%ki8YNp6!ex-$h4S>Ukz3Y=8aJM5#=nR@kka6e&$v!9(yw44s^ z$W3J-)`ymdIZCtTT5C@3?hOh|XejGyT%St5a|K#tu&SqREzS~lx*gKGynb_lV52z# zH$puS3o{lplbHk(nV3ns|7@^xd1|WMTjEwd$>I9t#2s#veoa#EG&TD6AUiHSAnG+vxMJT>%+U-Zhp9;@giTr|F#vj#po?a#v0rJ z77tM@SE%dsK9;f7KqO2k$A+9Gete>JEZ3)m|ys_s0x#-|3{P&2AXb?YZDSEpTLstwEOqyBR6zo z1;-A0v?Y3##?q)^LHkMkA+zIU0!zQyaxb%G$r+4<0V}8_iWuX>7#vmidcy(gF942` z#BctKHK!6DpXCMvRI!&;m_(!U3m%Ff&Lhp02~UNV*Rk*JE*?WkKV)rf%lH*vTo`#h zS7eK-WQnM!YSwYz%CM4D(vz<6U}5s6Y13V=&Fra-Tm}v3qS|_&Qwk8b06b~HZ5go1 z`O3tDpUhrqv6(8BV>-U%Z}az*x`zZP?%Wt9~Up#KmLhQAq+?;atNE z;Y$tO;>l2x-qigyM&uRbBh}wcJpneXVqwpU9)E|y_2eGEr}-Ou3pi5)ZSOVG9o>|K zL&~30OUL>?_`#!9)WNe-fL|j2{JLJ-2}O{*5z}-|JzS8RMyI%pD2`=~#<%DpVU4j~ z^t~sarL8ux$owjG$NSJP@?+aOgCC7th=5g%dREoKmIzBrJIodI&Xt=uhTkmE>)7RmJ66uBeoJMW)Jpnj?fM$ zA9px|AFE}^&vPdc{#ciT?bD_06rzAybMPQ8DNqe@W5KNbi{~jEeAj|6XtHrdGK~@=$#Gkuf0Pl@ zRs;o|M7QCl%K8Dt_92@Nqp(ejbkiKgofj}rN{IhHoLIoGYECf>#DMg_j6COsG7--q zsQ`L=d6mqltZuf-MU`-I-dRXJ4p@$tOT@-fbWWigbAGHeA0Nq=dLcIcEFT2nJpWMN z$&HbZthew)ooeA4ux8W)s05_vVgxv0C65IXuJFGJUfjpcZhCC&k!d>@Ajy{Nkgg zQ~MaZNagCqU(IduRz14oK{=>c8m*cfD$p28jkzZth;6o?!96<8sy$yAap=C=l@2{H zXBO6Kc6t46JdL(`9(dT<*^k}5znk#d_CG{@V_4o{`~RKog=HJ7rR7!2wrykC%dS;h zb}ieswQMijSoQzjd!Fa_f7OeQtcck%t%6a-c9+PK zin}A#hMnXd;`?%8h}lYck6&6q%ISVRgpk*44HyK?y_;m1e09B-cJou?d3j+pa$BYh zBjKq?r7MnX=*2_e&a|v@8o;@Kt=>~+)s6Z8E#_5~10t}I=ESh&L^1Pue&u|?zjgW> zaIhB}Y0-d7&cEAb?Mt0n*jYK=+Q8mxPgeS#d@eK`fGyMMdtVOmd7e;PI)Pd!gQw+B z;yZ(5wH*)L*6CF;5r3fhi=J61KqOBrp1Vw0Ts>cmI***EvR&*vD9b~vty71<&8TL< zXQlR+yT=6K&ZoiHWBP5jf=~e4eQ3xrmBvg0)~l2EJzkrxCoNcGp;v9ip+uLa*AXq_ zRb+YwP@2Dx>QvYGc4BRB$FtNU6o{E^8pidAES0R-mLgr@O_LqLKE*UyI8J=O=l!HJ zrw#%_F5!eOb76+pw=jAhU-&q^xlM@(c|_4hfsJ;B-#SP=FZ&}9-q;!YoOa<=|NPxS zs~J=S_SWp@Q&9wp#x*>Q0UdG8UKjq$0I=jW)yLbr)$GyRSHd@8dn%bT?}Im(p~f8T z?@zRJx*)Ab1!k+d(k*{b1a=LHG@GM&5aY5GTIXeLxNk#el;Sk6-mTkstu^L}NB(?! zimXr$+x4-rq_m4|9{?lFLmvKU4za0-rfqIEL3jz}=g6vh zaxxuU65R339G6s}y-|XVZCVU3EYiPTABB8H`$Zf|yJ7K8<9a_5sfX~Bu#reHwAK8( zUk}d@Am{xbc5iolKc|8GoKJ|B-3GOyN;&?^SUO#%pj(9;VQ45+Wk-p&x{B!f3O+~C zv}L;|u#&eN<0hMq?kpPmO?^8OOtsez4BDZy^E+x5qgo! zpoKBMAVzkKUgiFx4Ni2I-Wx=WKP^IwMuj)}R1|N%E`)Dp>9b}ke28n-eqQ%Ebuh$w z{mFkj+i~^@H}ufbjMA2e$&Z)neE7-9DS!&;?VH@`QKZG{-mfHrBALFaZOYiHb4tbe za!Q3$A-c;EX5+LQlL{v$CSfAlFE5fhsn+ieQN1#yEx|)+ctV=}Jv>^RU_l0TuBms4=qDY(NHT(GHs`Dt2EEr~A3H#&LjjZNEv!Yw8uG^<1v; z(?i^^(_XYNzzm#_%?8EUjJ)!_o+X+lhHZ zueIvQa|#uvT&(A#dW7B1@~^qnNr!M2cRFq_KwvPJL_tyPpYRhG0CFCZu_SO-3k`>s zs&ppb6qInm?OhD-`I1Y>7vqejX*ONoTshawO?UTFzMi~kRt|-!v+f#WkvUiDKvDtE zeUimWM92G8-Uu-k5_#=`1iQ3SHf~CcmNe0oupAIkjY3#yHj98Hs)o#O=YC$Kv=Np zm>iMFsKPH=XehKJU4TiIO=7sYU7nXH^Ytu{090zJIkA%+&t<7$`#f3d_Q*4;I>8ft zLYiQxb0`!M_08PMB$Dn^BOK`K>C$@=Ak*82!wQ5=X#T?n@87G*uLZ*wDRi@{%ZY{V zr-ljZJ61Rab>Nsh7%l9|SM8K94f&D2j)^?k_D+pY=BW)PU}~yg4&5N$stpiI`Dg|G zGVD6uXPj`%pIX5Eh0@c=Yi@M*6#HR%9t9EHeF*}8C_c;tngWv-Benr&zu8RfRI2i+ z$)h=U2g&F>*38E?JNq5S#pzfyzixHOMwZ0#O_0Uv8Vi=9pv;%P)%Onf&S&$eYzre< zBE^%V=NVNRw;X~CFwPq%5T7Xw#UDbU=PLuI)KKEo-1A22(7|DDu74j5fj8mzQ=$oGOB-e7`3Hya5kd)89xwpAi)F zOnKA2-$8n{>TADybQ~(BlTr1-Zh)3FpAzA-F3fw`g^B&K=3P5=J(>dOEkr)3GieLW zev0(VKu<$j2h|g%yBimgNmkpb%izMeR_@7#ipWyfg#Gghm7GfT>xo3ZaNv>Yup@xf z&_v=gJRmgC1(*_YuyPqSRxNN>)$qnq16+A5ayd*#W92A09Xsl*NfBDnr4)}tL`C&U zBIhk4ILT<5(ZZIeR&Mxoyk5DUJEaG$H?q(TwS@SZOBhb?rpii?wiG}nR@DYJ5AIAi zcx$j7_379B61QF6?{?`NUaKB)IL*;u$=d7@OW^iaezVQILkNa^iaGN%|Fvim#-Uvc8)be&0K1NeO8POMThp-to&X+%$@!l+F~UjL>cJPwT!$q~9l0 zxOizOPary$8gQ5^rq!uRj_>f6RgX2VM8R1)`gEE*;P0SNF*Fe1`dh{zFpbnYUeTJc z9SG!7t6UY4fH?r(&>Yv|fp?y&de_)fHa`Sz=9c>N6bJHJ+=m>BIrZK`eu3lwGu3Z(8qM?-%mp zd@|rxA)U_C+v%Nq_0qJnO+rj&M|ikZ zuT^#>gN$FaoIB%&p6A0RdMcT46aR}=nRA=0zj>5op5UX#8N~M~X#6w!1VLku#Z(8* zvfx6~2!f;!bTl%S7n;+<)PftFZ@@=5W=If_?Tk-Mq)cG~(moR)Fn%xQPLv|$#F3DK z+?#;$yoJQ)oGrJXfwc|gX!LX=gtX4gHhV4FkgGhh?tn~1skf~;Z~dihG&ke738X!_ zdAxFE?=+XDJgHFn^IIDkTH5Ckw^&s9EAz?NnhjJBj_tD=Yx7hGW~YyB(|~l1ZmX-L zIXEST)kQ27Vo3SRR=X6bS0LBPjI#NLaZ6{uu0PnYNHftR5C>; z=J@!$GXHS9gKD-gx(nH{Ry|;ZHX1?spH^x}5I(0(7|@#x?2D2xLIRHT@xMo6oOBB1 z`!Y9;uTIS{in0!u@Yc-j|b*r{zQP{=B8{Ep5u5k*$J{%}7Ze~1SvF4}JVot88; z(JMSf+DZE)WLiAp)oVr>m^5WlHXA&LRdjrcEqOWJ^tKZA?=9c_3O7N?@eTl&-hZ zmW^kKnIs6T?QFB4q_l1jh|JXY18u-^*;rQWC}#V6I+HrgHx;R5{D3&XTSGouXQX6u zQslqlwel>eleyRsIqFy(G$)9mIR#x~w{MCh;^jqp<-ps|`NfIL!(Bkg~do$SF8(_8%4P(Cj%x}H9rD`KS+6Qjl);84L z&;hFvya|BX17uZS@Uheb<}hZ*NKkkVJZ7%2cRfCCz6K9yd~|;=$3jeonSj_R{5Abb z5cz>&;1EzEyD+ys=oGAnM~B}4$<7-*m8rsXm#xbFCXm&i{M; zojB|Ns2bY!!-dt?n}sl|12Z^XhHK@t4s-f->7V|94HrP4h(H?q%WHw3QeN;!LM3GuD_*85Zf17FpWUIYc-}8_>Lpb0cXrH@N+;8(JaQ4fdtAoF= zn0-mma=^yN^Ew0jD#zfoS(M0BL%GYfx3_;dR>0@LJ|-rVE&8g$(hjSJ*>7=q?scm! z^SH6TKU;BfUh;$8_a@bIycw7D%%r|KM7MqKp@XW-4~2|Hvli2nB)OAX{^m=;k}Hzv z!O{q3=rn#toQq^UNPoa4VqN{y7P^MLas(uE_RtwE+qzGAh5i@4O1-)2@8|-Ym zlBUdZJi^9VU~Em-$rCWypnBKmx}AX`;*{ZjCtOaR0^I9f_*w-_uJ~XEo}UoaYfv#= zs%9~fPRHDbg)1%?(lpEu97518qc!$0u%oLrutP{LggL*K{@u~z@v|AX8x_gEbF88K zo>rNZepp@1W!$|)=w2O3+?JTC{^Y}tw%QSic;wXb00kCnkV#nNF*K(V`NPc+;^do7$XPo*~a_103 zu|rbcORembwT|}cNM6wDw{1QfzROsZLN!TGR9Rv7PHUWfaHOn8^={PsWL19^>Epy~ z8a-H_QGy*6M_T0eL=*zZ?(Xf|K-j|{CSRQ+l`g;Ota^)2xQGzEP_bR)Ip?C@i z5HJwIVvYy7b{iNXrydjZQXj8^Afo5Ykhaj(=;u>HufgW`@L#+P}zpd1DA zdsJi8CWCSn?_1)AzpjtKd49tLarRgCG|_BSN0vu1-`tk|#xUCl7Y$^Je4lFWG_@}* zf1tSZ1NqzeuAMmX0mL^C_{S!}Iib^u*|Q-XsPA(LBExfRZ%aF32tQ#;6<`7r5*&)D zd%MS?fzl>%xk3WW$p;Gdla8$lB3M;N9$+}jw%u>pRVJA)tPwI3(rYU)Uh9wOkM|{! z13pLV!hNgv3bnVIAR+5>yNmD29r<8~1jRmP4M~namBpqQhK&8!m8y^GX!epWR?pUv zKPguEmHlQUb7h_X&(6@_W((7mVL$B6^S4c|4C|0kD;1pI69GjcTT_K0i>*9;C+Wd& z3owSd_S!dQ%c-;9N{h~vX6y!yf%?1?ham<)1cH?i>MZlLIn|5IFAR337E(USjuRjk zC?Svplkhy>^`}6oL{S;)$Bo-Gz%-}Iq)+mP1g4}_bNV2-7QGG}rb9KUCfg{<;Ou*C zc8yssK0WbOCnq9UTwamjwQL288`b1^VL^MbW7(1{Ht~GpJ=6`9!h51$bqakNG=LBN z`^89Ui(WkKb1a#akynDz)#nNRgy$9aD-z}@WAlMe8V3xZd>m?Fkedo{=4zaOYL@Vc zd|HXOX;GtVQoix;X=7J~?%uw>>=Xiv_-NkOq~;x`b-G$erL3DE93UM{h^vl@9sNAp z9{k!FEB4^EA++@w?a-GQ!s67JC#dptQ*8Uk`*4A&^a^NI{W-QGw^@H4PP`@-=GEZ4T zop48zqEZ)$1vvPa&L|GgOlyx(b=OVj1BX?R|5q>MjPq9?ceT~_(Yc-q7(;aG$_R}2 z83C7~8WN(GhfeDNMI?c6k=oIeG-;?lFn!;yfXcG7{D;KxF2vjz?GIM19PgqPH#3mg zhN`a1m$>UURpG7Hvh2>Y*>3=UoyYHi>K*Z8u5FqZKWc$AO5|V}drl?(d-hgqp=;+V zz-RVsw{mxq5@$bN>nc-MB2kSoJS*dFbG-e%F=Ec3Y&GEHf)313FQuyUqK$DhaNNf~fR1BvNMKN*Fd{)$&D* z(Zp#y&qekPD>NtVHE=m2mOn9_heLIxoDAQqq2Va`G?dfzU`l-}hIdvFMr2W6B$0v6 zEuP}!5d9`)6=Dvuy=*-TD3=9Ys=|Ih*Xw?qRSrpG#SV+D0bzBlnLAEw$)cR%Je6o| z?+X8~762#W(@7GbsipooyK$nT8Z5xFpy>ARg~Ix`{D~lkTLok2W)4xn>h8&Ed`m|@ zM5;+f^(ly3NG+et9dF9o!gj}f`4JWb<0rhH z4t#$xH($19WWyH`bXBR!e4OjYc((Wt>VH-T10s2)+x-f?qn>spfQamd{D~c|_Srk# z#!*Kglt|CZNc)!6{)}pUrSk@Q9XAO2&=Z$aL%0coxQDH8u+lDYT`riv`|4R&KgwLa za+j{gJ28o>&2x%lTWUKOp{8B0s^~Be`E4YmN}aS*klY@Y3|aynVPn$emTfZ4ZMBOI!wNA>8q?r+>3VXW;>1G`9om2LAG|?x<(`I z%u*gAD9X+johfVatYx^NPuE!C$x|+7FKLxfwQsPj+g2L=yK+P?3o za?*N6i(9H(@3~~g-neViP&`{wJ{44ky50@OLSLfPil>X~elIv@wIq(BlfIt*>D*NJ4F(+WE@u2@N0!N#hc#+6ra6oT$O zx#2r%Qv5h!Jl``zJ-Kvoqfz>!!>n+Bvk>Bbr@Ygm9CDf;9wyNh^gYb8Zr4Os z>EXAyElqF>vb6rpG`nP>p-3iym+*XIJMr$Wg84x8L; z#2%u%{-`ObTh802M?QTw6Rh>jA?R|6SA#hD^|5)DRXUS5tg9-5bEDDq@Yw$Vy`AL1 zX1#66YLcA1#tlqEaqT+zWG*y~2IR0vC{b`V-)1))hoqUS>#;R54VGFZr!R4~rgpRU zqf>rCf#LE&O4tv#jd^HL)om}CyTJ&D`&mW&V&3XEe3zv4=XE)VxQM!sLF8dU9r-QP z?ylZzCfeJW(TN>}9`!z-af_tWf8Q9=&KAF-b69s$h4*z$rQ`tD`1;eF%BBA7!t+qQ z9{%Wus8ash+}h28IgXb=%HW)AFxU!vws45cu@<%X7G-+d)R(9oS3*Gx- z3~zSfs8aR@zQg~xVKTH*nN+M*K2#^yHtbrwpA)!{wF`@&C3+$Ko+i~qX9rJo*^9?A zRL)%7>h$fz&m$!ocKbslomqV-8cYZgvmm2IY(pG6dkz&f-ERwx)RsH`_zFvf$P5*7-%9ItGE9rFkF4@FcwC6DYFF$~Ic#*u=KntA%^6)JK4_dy;$g&77z{ID zEG6Yr%0eE@$-$VpHh2tEPI*dWV2I+Keu6r~9R1<(V|Vo8roQ&VFIL7PNk(kF31Pub zGfd;2F8PQJvL6`fT4$p8FvD0AW^R zPs%N9E_uNU5A&p>P82n9!^C7q$g{i7sQ55{GAOwlRZaYHi?U&?rH?2JZQuoKpTf4$ zH;{nqjeP9&L14`55^L;C5En`(v~jsZ7%LV@Y>4KNsCKtS(m2Y+$M(!*LA`z&L6#&q z+apv^ls=>WJ2|P77Cf_`347bK*Vj*G%E-KJ_|yrfbI17^yhE`3oF4!p?g_@(U8SRC zzPEP5sVzmscPewWCnxtB1a!>Fcj25AO`ZCZ<9n-8sIs&^sJvCImaq1v@n&jHYn?QC zEj^m&?P13an;}_t-6w}mGM6p*cH}b%s>#Rb50V@RheDd~p15z1m2CDdNKT?5u%4{Y z*duu7Z&gu>-fli$x0ahzt-Y8eUvAPyHF<*iFpvFst!jH2n9F~)CF;|!F0a>`Eri?t zK#d%8I3A&(UXYxhlem0(QO>q&m^g9mh<9=(C!aPDmK1dzU&Yi=P8?}yq`Y)KiiD`y z0{OqJ#C$#I==9}4zmKx!XE?;t2z(rt-%RBoF_e2N#W>>`JMoISONRw`)o6Eqg{@oR zq%EMlwS(C14XHwnC+9E$o!$N(?yDIU86^4k^G<~LpoWi{lDZ}Vf~o#Fdb{Qp*^8LL z-%aSeeKXvQ{`eE9dH7hFI3A8P)u*S^wBKqTzLLfQ_^HQbPX9;IOe!e@lm*2jL@T@~ z4y284q{jB}@#Drcmri+o{P2bIv}G$br-5&s)xK|TO^+i6GIuSAY>tCGDJ|jrt?i$~ zs;AX&<*)!w%zli6lsylD*uPC%Y%2N)G8hC_j*?3g80_#m;pLQ0 z&y_V@==S>bBKt3;bK*Q2Tg;B*?G=BOR9ltJrUK?KtDVrietIEy07$#3+6^I0p}mA zLN4sz4K%CTv`6=Aok490W!|&XLBm;x}yt3(pmes zsz#IS+)jtKx)$i@5?GLb=`70i;CcuQ)_G8A!d>n88!xu0*qP)!m5bFtp#ACmvtcxu zHTZb0KBI)>T>7<=-P?Q+OeU7vX6!y7xNS67IKK$xQ4iUh4E+69nRKe?&DL~k*SG2KZ`KQx z#uFSyB2#XW!=v2@?ZQ>6sK9s2u;NxOAFoDk{a8ZpBD+P@%f(FeZF6f5C*{lEF{NM< ztA-r^B;oLwFlQMgW5{!9c2Z|AAy6o!uQ}ic%m4&n2Am`^=mI$EW7w#uU@R>yH9U7H z%J0HdM53|g{I(k-&K>JKE7!ePm9NLpx=|PBd zGN`KR`3ii$xsNAnZ_&?9rVd{p`TUi>kaQHob)N%uNw}A zUIP7g&fJ;F#ZC@UmSP=FCItJADq?^{5|WaKH$DLQP{8DK-}?_g{!~Ip=PBz_c%)6_ zN-{EEQm3_;($`j9b+4YOUWO`;pH>IOc{Cdw@l$-bdI}?EWhiENQ$i>Oq_%>{&ARkH zBY)xo=x*ILm;W`-G?1z`NIYrl$DpkJpX=M@WVxRmW~LA1 z##s%TGfhj?J;!UUZX(4hu16iBqA_4GxkcPd>?$m<#2jd_S%F1<52@pV9jB}nv1Xd4 zFr!1)#u5TweWr}QFEHm6aIf$h*p3m8&KLzJ1K(4YWQ>8nW!zg7HKQxoY_P5CSy0jP zmk%mv0S4Pcp>!ql#fp{Hh-bTJz>QzxDAD?7p>{c#T5yNYkim{Ol;iWCGWCd)x$KDn z>f}l%D_|;CPU|6*Ro5(xNEuuj833LA;E|QkXWrS6^z4ZHO<_8$s*WhIO{k4>oBRr6 zs{vu1T(GsoB$0{>;&)A&!#GStdV^?kLQQ_6Y5RwqdzLC3*-ayDu#D?Y8x=4T8Pu4i z$iYYe+dWRCq7?P_b4v z6W3%anWi&pMRXC$SxUdtivgboHTiA-qfaGuJmZif?!4j?+_Rz3SNI70Q?F+da&l>~ zer;FMrmA8>Fm>T@SkUb%(-g}5oHyTrg=+LFztB7P3mGBev8iJ6#R2>NB)^1fR9Ua< z+whxJ?QH#*Y`3cQMTb(1qvi_T)EL7Z#1(J-HO8LfdwJH@oB9t6BJSm_F_=>}B)PkH zWTK*wfTuBA`u<1P*?PGoJ+KUL-B15bhvwc&#&^p@=W(tWq z(Aq4-m8t5CX9OoWy?~M&6VT7OdX)vxu2&}G?#t|?3)#!84kw0V8=e%f`p^6(Ms9qV zS2)yOz|{XHcV?2w2|uiJ{$>p8pLPfHi^V=6+Cg<+C^0Fzlz9n~CWEFcphHwQ=V?&W z_y$*}7skHY3KzG=)O<070`n9OfG)y7go3E)ybDiFp>S0fbLGh|m+cPMEW+8&v}&O~ z-z1hKw$i^u;%wcoJ%iWTH9vTx+!xiV2k?AMnY&FYDl4rrWS>=Zesk$5n_g(aFCKnA zppJ+6bXHX1Fz=;bOdle(X5s!GL$MO9(mmTNJLkvb@F%3?vMMCm1>GMIksS$w4eg9C zWGvYJrav8JG`gNH+eQ5-lWd$}0PX&CrXI;m)_!^#Mxp>-t8umdi*y39Zb8Yn2^dMy zU4wr@!R5s{B~KF@HyY5m0qc4O{VfoJl~QB*9Gj2u?~mVmyg;T}quvVJ$jIoTpM_)# zFdwa~o;CUYY8iT(cUJb0z4Q))wQ#bT*DqeZ%ZxtbQuggAGA*Bti9xiMW9K^l0Js0s z1fFMSUE(B`dh)5zK;O#!+AqHtnG?G!Vo6C!32Eux=#TcHp?xb-@!#uV{-YJ=hvX{n zEbnq>@Hp~LH+Yo`DhJGHKSr_d83KHq-wh^6{j3Tp&`Q7xwb(%f?Abav^8LelmcWF8 zzvQ1V`(D856j_z{KDSO=dg0Wz@y4Zh##ozZ!FGs(aP-2mKBh)THHzA0<(`K8i0L0G zaByJz`hjL|h@ZM7ZfoKYb>qg+)DYtsu^0ug;V z8BeAY11&9(Psg-K&XLuR8Tt+`+o~6LcVb#vS_@Fr`(0_H)JO%DFrRFHHXK*vF%HoUc*)!K zH82SR+LfGxV~+e16Jv=25V74UnHOGr{r*_@n=I=O0v)iRxbKibp=lihI?P7uqAm4n zlHWZmgzR7BD*Ka8_ADoVRIDJmeep><|G7IFG`+w`aZICqP>~mv$u4@%50=?9R=~#z z{dz--jt!&Z2;*>Pb9~>)@`z4wmHEZR8D=E3lZH^89$19rKUdmHERuYz&?Nm%w-dvq zREXsTb7&ipQ@`50BcQ(NK1om}b4KaO%I3ucsn;b@5eta(UtV5HNJvykl!=Poh5hrR z2E+{J=nZZx#)-e9pmZ@cf@Ecvodp>FvT$No;tmk!xz)GGD}6V!HFb5}H^%rJWbqg@ zvEgsi(>sUdgo|dF{>x;zv^|YS5NXFO>!Zg6K)IcROke8B-@4+Dn=8^6K9_J0uFtp{ z9p24fwkgSL#DV7+G6cjHXkp`fX3U

~Oyzz1YtZ!b+`r-Bw=Iyh~bl*?|ourBqov z^0l-~&1a)3xMqFifgzvz^bQ1o*qKKH#YRLG3#>?Q>O_8Fm*9`Cc7#z-E5b4rE;gg> zm9M|;4v$lMeW}lLT4SaKHJq6n(a3VwV}ScE@h2g=pM8?OGGDY|r53BL+&yqa(MWqH zMOCv~@bW7glwm~kC7Qt$6+16iu}Zz=dob81xO?}e8B4R*{*7j@{Ij8*2%`ig3*+;!P}wNmXjjm)qixpV=PRrfrz@qFguckWk`o5jCCNlo~b8Tv7` z^@BGPDMuV=NKop+&=}tn0{SCm1sOPT9xg=2EBB-%CA&EmbSR?CSJ@FpH?)jiQHH2d z&CkV0va%3%Rtnc6yCHgQ@GuUSn;k!_dpX&Zwv$1SdMXjaivA?yD}mlpEWkroExCVX zaHHC6l-M6q%3E4fi~Ec2Gx|i%s??l6|zr!+1Y3cG0~IS4hs#+q&kg{axm5QwlHw+kOnx zIh6YI#rpz}mvT{AdHNj!OULxI`93@@f?(K6@(Uw=?URpIt=d&M%}v7a56xi;arWVS zCDo|?$+h3~DQ!%fitQ$tpq?K8sj0iHaurvbNvU9A@USsZR})>{<@TOneY@tenPHRBcI2dDL|&hN zhX7RK$w)i}P{R()0Dc;zAomx11!hJQJ2*i`5U^}NI!7ul7Rf@3qHk4X&m|W&%^$S$ zs*PBAj~B8=;xP3T%BEcmW(ML3x|BVlk)=6)=jjzcV~DyQak9ljNpV_0g1guqnH zC?8(r8L1h_we#S_P?QIorV}X}#t$Afu8i^E{>=Pe)(wc3m&=cTXgQKOntq)lC2xKz z9rtqk%FujbBdcUNk(mT+8bJRXlw+5-BADVCM0#$pI#t|e3{3`S=q1fp2#Q&{ER z@>bxV0S>nmHt_sM?SPt&*To3;mluRFVKbN_-Ryz@W+6eC2d)#|-}yjHkmG{i?SmNH}{9P4|RUId^2Xo8aXp!;Ijoo$m4$V}hBx}$iJGDj6B@W7 zT<2}ndLJDP)7Hj=t87(LSS)X4^}H`Ow9Rvmexw$#{*<p)bX+w@q?UM9VU{PwD< z<`weWC6UpKDpxN8tQ89AltJq1Gy7nB{)W8z4L;>Dl7g348o|Ph_LuC;iKb-)5byF% zhva!9J;Djld$}F(keX0fj)YJwa5tVbi%QFwc^%Hk2E3D&HdwGDrCr%dw6(RR(dt^R znkgwdtNc%`Q)9Kd9sI4JOk|p`m@6wEo3MLM|6IYU>xZtH6k1BN%S_zEo%J!%^$S3f zUjj?vf9%id-Fu1GToRpFxZ3V_#ZDdsu$PvWBshM_1cVI*fbsCOVR#Vc)K|agNT}}# z(Vge#t7v*k`aAYYu^2^DKiY9rc0ZTfH2{9j`;Rz(qj4K;MBG(UzMPk~#<1~8t#ln8 z{LaJiK?Mj6j{Qi4HXqY|$-SFYqzBXtfL^T^KWYqUj$|?e`pyRIaYr2Qo+ygnm9hT> z+`a?J_*8x4+z(i; z^Tc351ec^NFA{Fa`n2?#nNs7b+03MnXGMC|e%%%ljCg({aJ(w-vu^0yu7LmbtvLk9 zYlO?#cCXRti!{iCxzK8&Ouc*m{4!M;9Tj zOz59~+^Sa5l-m{ZJFdXRWm2m5g?3bx%HrDyW)23%5(=1NxT#Y?ToZy(V=X&9ti?m` zclcNuN3NGs3!JaGB=Qms^-Mq3Z z8Dj)f@3uX4E-r&!*q3`^UyaV2IUN9hNyy6fXGESKJ@n5qedTR0nHwKsFkdRoJ3Pru zYB{FWR$))l;^8CDC5{H;GYhMt%d>uShkRgfhYU39+3`JQNON@kvU4<5Vs-WMLao{1 z&ki;9M*SzNDB&CsD5w=R5Z>(Mi|`tASN4oG1i>|T*~Ez^02!u>+hFV8H0-P~0bB8( zG>U!1`at&xk>}vq*)yY9%b@mcbIY)?_8>qTJZ=TvGn+#OP*a%c!7=7~bL4Qzx3;Ix zl+(VgCdR~r^S}8SoEPQ{q-OE0G+hx-R~(gF6o9C#GZ4!I*a#o{yH!teBI;Xqvrns#VV`e}H0+~JeK z;zLARE0;ialqx{H98{w?=f7P-P9P?-Hk{7Spd3H-8l5OLZeyyI`sW)3`4PlFhEXb{ z@AGr|nfqCnhA{Gb?BMro^A>&_;Aa<4Od@|wt5;8K6lE~^pnOFQtR1S~!TqiZ^PYWg znB}9=wgl?w-r#hV+a_bswod8&m=vwHOj@BNGZ24)2Ad|ubW!FD$LR^!;8xV$Y2QjA z4gI6`W@f{^)1GeSRzp$mZoBKMb&T*h|0Joc6dhge!UH}C*Mp? zN{BG-8P=|Qwf+vEHk6{O@@@{!qad#V>!8`ZCh4{d(IGFqQ&y;e2{H|gzp%hJIU|3W z{-|jW!UXAgSGyb@x401bnT1J1gR)!N3U_c5R3Dn}0}@nPH%NKg?*uTc*(LKKrSeHJ zNQ_w96i~ayToPLZp2B23!-fpO;F(yQ-l@mON53y2hhUTXuF8^;NRl=>sYBpaWl&n* z@70%go@FI04OYOPh~VD!#Ha=_ULp!KNotrr8C0WwDKi z1bd48h>YCnUqW;6dnCUt5hNz24A(9zyCeC<5XG{ixU_z4ZEbvVau|tV0u;#i<;v}v zL{1I6s1~qh9hgZj*Z}BiQQn;I6^k7tN3jg+XDj;`%fJD{aM!P2n`fLS>zRFYYX{n_ zdwY7o)&MjLR5y9a=X_{vGKPp#1q}XS^z~?SOiiQ1C==`Bs}|!RIi=f4;h#SlXklSR za9~V18`Fns=X1C_+j8SFM}IA?&(ir97KDKJffB+^pcCXI-xvcUq=qpC#3DxZypS~I zo&{&azrZy@Z2c(k8VQ%fFiyNExv<#(usNApZb9wC!7 z-`!KhdMPf~(_rd%e~*vdw(11hx$$?7-+w_DVZIEaryjY2NS-;23>!j~uq6Uv+zO;c zY;^w-K=KrwA+olj^T}X?v9JUB3hNP*Kf>X$=AIsF(Qmn)!+zI+&C@aUe8F+a0-Ui# z6>JEQRH^h-k=4|ST#yaTM}9b<3e0Ts;MX}nRoeu=p1UTqVP5 zwU)!9fw(9(g)#%EiTdp$z_jH`5gYyYR3xNy&#pQ}Z-et&8oK6E`mt87WJ18^<7BR` zl1s%w=)!oZQR!;?5?|yl;@l~^K0$9)^rBOd#Ih3q zB-1jVS5!KU;EpX0`$`aQ@U#2E1#y--!Qb_bRQl*(+XhhK5#Z0;qN<+`{P>On^8Y@- z$LDs2+9q%y{^Hm4DSJN?%J)e!jh2|dgwDt3@8$eHebUo&28rO&H-F0jTE#zZ(q$%E z*^R!x79jt41U-bT(Bcm!q+|xBj%bO>MzJ6NJ&M48cf>w6{7E6|*eoVUXB#19kqAtS zFx_Z9UN+Zv-tRhqfS-tsS8XsNOqI?1D!YuOtp5B5_hZW9|2}j}e}4#LoAae*yRq}j z4{mQZ1Pf{Xo$X~79}b(p$*G8pS=a+XHKFh~)8{u@Dw+m)5`?4s)=E{Eb4)!Ck$&sb z47x5Dtv#|Q5GjiUyCx7ZDD6{>mRF(rQ zOc9h$witgEhTO%JZwlup#i)OoOacZ=0Z2?ZM}f3EwbmCA1_)Tlq|MhqmudAcNs>F! zg7JAt>hB4 z3WCZ_uOLin2=k*0W0`Q)vX6Y3MxZBCi+w7w0Yan`YyhqpxW?$gNdCuo==v{viqeD8e$PdLt8N9 zj2Pfio0zjp=GiHf49jGPHj0O~9>rxi>TzQS> zVOJX)#`y|e>!e8|Yy^ZL2XRmX2 zogEc&#+Aq ze@+EzO;L=6g(2S|ewoa)JfRO3PM`%JYqXBtHqtCuxOS3qK?+lm1*~)#D=L~{ttSP8 zU^A%sDAuqXQtqQUqeeVyYB{j5*Vj`e!;C*-wM0|XyavXpZGm{M*m`<6pP?qmR#gY9{JZ^SRr%VtzQ=}%kwKI$tU z$d3_`W@MBY^(!{)DabxQpUd=8I`_fLE**~~r8+u)torX^ZK zg`UL#qUaApK8i}J(4ZlP(fXt7>H7@ffsUD>v7yf{Uzqe{JnF`szo37nju)YJ8cg~~ ze$zN>f#uG2(ih%#%;zjZp`yx-7S zRiu5FTA%{3LSIdrPVL?ADu@ER?;icwUAX#yVw09$>G1n{qZCE50T=NbGb)qFG-*<3 z59taO2Xkcl2$Q`8f0MFaF0UAXG&gq^e2?PP1M0eHM-RV=}J)uo0Y81gNx^7rg=6d*-thGjrhie7LnR`|rZ~ zZGW~lghj)|5JJSLoOT1@q8365mvQ@F4aQzAoWrfoPa^P_C|n-nG0|R*1}hjU>a)30 zn$cWJ(UZ%OWFe&*r~sGkVxkeQcp)}UXpy&dTFy{YQd6g5n`>#M?o^sml9Q)xBLl=) zRcQRJLG((8s&;bVGEA9G7a%J=Gp16Zz3}>YN|oTh=PO0ENrPl0yaWa9c|SvdOFP+^ zrf|05i3itUx$*!+o*l5fgaCV9R^VK+2*nmo2-F*0r$Vjb*w8XK z9-{gn0rg>YA4faXP#KUvDIHv<>BKHqRV(@r=6Vhb_M*C1qT37#t(@J5TBp@~e_-03 z`^XW1RLD3dfe{*@50m-m^;mLF^l@zG#|#099vKCahO>Up4EyBs! znr^GQ6@6Ut0is(tq^j)Rq*A=)+#e2L-P})YUUREmbKIN*Z-iX4mhNHYj|oL(v|q}e z-x>1fRaX=#LUGgv17|0aLrsyv1i*ejN1~|c8YP|N%u;==*1V#b%DFheQjz_01g1dx z^>i9#Xk_ZEMf>$5OtRagOuI8>oK@Sp-9^}bNEgIC%mM-Vyz5SXBrT2Gh znnmg*QlbE=b^u^|Q5q$cr5QaIR)F(9kFU>ifz_~poKK1ZJ{bBN+9Bjpi>12w3Wa6G z0WHY+%P<%<+(QM+yT89se)K#&X!;!&kzXXj42*6E6)De=YkRV^aj2?5@yOX*PO?;ybii)T9>)qz#%KFr? z{}T{h@3E$-j{MNO_?>oyia0KO&GDj9Bw4_=#o??(wKOgi$8;V5|6=fIua&EjdmN?VYYH`;EXY?z$4@Q&u|N!I(BL`PBVYw`Gl+}fL~)ED)k7Kx2HNCao2 z!ptJe*SnA`bjQxcmM(xAlk1Dj$6Q-JpqgT~_GB>j5&2;%vsfqa#i71Ls3g)?kR_1~ zkc#G{S|AG+Y^?*{uj^}k3kD{W9F2w=4oAzWCvB_L=|h8a!QI8ZYr(@<^sSr&u=mOuFb;=S-K+^sEYo+`1xmw?IBcr++lVjPft zbXyI)`^TPA5=c4)MKj~bMvuKumw0@;9I?GgQ9Mp&1S=;8gM&zoh6qzHV%7UG4692x z78JA4yz6UcueaaDwo1!LO$EC$Cb#f^4TK(%KckC(tMpk4n@`%xeTkli#`RvR$y1uR zR#t=0_}ZgOBm>JUCEEh`f?Ug0qHgH?!v?&^HQyco@o_M#!u1`Mw~w0l5p} zrEDBncIwQ?N3iJaAG>Ur@rFU@KHQ$(wt5)LN zkC*SH@eA#c5AwG!UEFvi+~P_}53G>^MS%+X>G!e=4nA;3yM69@fnc=<-G3unxJg4t zOKh_?&(mtolWft-DRa*#cj}Yu_7QLaEtnuNz+I$2OV{j40DY~#phzw|{F^CqPkeHD zR{;V6g_$cnMx+_+s&!_(U_bC|1Yk5zJp41z_lMp&agI3f?qc|oQQJ z6&@FAo){PyhAt(efgBTeiH<Pj3AkG`b! zTU3&R>XaU4@dzR9Qm{4%L{EisEWV8^7T^?}r@YnIZY|C4w2Q$TH5uY&l?5_El@$;D zjM&G}P>PI^u{)3PVxHg=@ZIL-SX;4y0&ku#iu8}ki#H#oeEBXI5|*PvYS+g@^SUG| z>wntzt!P{$yV8q|EWZBQroZxL%ek9^EsXy7#f%VW)R*>aGyd@#Q<9coY9;ZXaY+IT z$_~k;?awOh0vzw`$DCs=msIkA91qF>fwYjhu3NXA?5lN-uOE(vYC8P!4LO${@Ou+nZp!gImRn8*`s@3#Cdc z-C&-Nxldb>DsGqB9@ ze(6!1f?^bG?p5tV)B)RDhjm=Zgk;-sPJ%1Kcx%Ir*vb^kvve069#NRBvd zA|Ig91@OI6Kk+RD42=Lav^HuY@kL3gJWd>UoFD(}A1`KkXf^_WVGPvitW2N=h$bHI zS0K<@hPcZg{;~Vuyy1SE+!{yZB&rpPCj^RFCJP5&jzO_9E=?%jCO-Np5#d#N6f{XRaq1*4b5z)$Um^I`A<(pz*ONZrDW9|cZLOcO@c1i zW~Qi(p=7lp1mxiQ9QDAquw?PzNd*Xo=aa}6r`|x1r6G^=LjRCwm`wt_5F|ylvM`-> zyBP&LXquLdc^p&5>2&=ub_-=PgFq&gZXju2o17Nuk@2P-7@W-iOPajkA=@)wm#}@8 z&jU_Tg5ak6fDz>P32S+{WAnc${tKpIvcl~+-#L$8h4j<|M=tWx0@agG?&OE@W5ikY zd0=4(cnp11epdLaMh={>o6o=AGqxZqsoj0mKNH^18 zH@yq(F2E269ZoX=9gabDSW`TnZYzr5diMhc&GbDfX@~IrsIkkc9#w#@EApt$Wa4X6 z;pkk^MEd8xCtVjD{)C68ZfKOt{m~m6zZ0b&|1~6~VoS6%vmAV21gC#|@R>*bbMEvv z#{8@2NUfUxhUR+4p++OTvPT$+eo^`ZYteLxdykx}!>+7UiiU>3oj{RqpdV3-};tS@u%A7lqhWdY&p=? zaG_a?6Ba7Otc=IpJn(;d4k7S7(V6H%&pm8Y zqkb)_Z6HHusl!@!9yi1A2;+6Rk9X|;|B@SOZ$LrFRO!sUghqAJSEsE5;Nda3|HO#+ zN)`4twXyt+<%*FY1MS=q;t9O1N}e%npuD@q<=`F zsD1yZckFn=m+(|j0D`BlNJoAM=I$=Qgps>DI(ZvW`A}24Z28dcq5okflRPM~C~Ip9 z-V|MF1FsXYj-MC$u2_p9auVg;w^6W3Wd%yJtYzak(~*3Lf87mx`txbV;?Fa8 zm&X5mGa0I>zOqWE;BipC5P91C6LlRQsL6W%pC1dW0s!aBj=D_VG7f(iKbSLpK`^D? zJCx!J$l$$0u?!3NKisVrp?fGo)OhE9RKtYs4Xvz?a+Qbt|KOUcxdvz51Aumypq9A+ z{h{;2PCq!*p7H^nzQRW*Ug^g#vH2j*96(7b4M7+L6w3<4)soE*FwGrNJoN-ssel)Q zy}`dGXy|M74XoDDR5GH>E7V>>AhSesv~n9Y?pXO!okO`Sl$t(gyT!E^J-nZV*7>wI zknn*wZVl*Ejt>ZTs8BFH=sxN*!u+o(6bsix8MU5|W>~4zQ_x=;Bw=Cc-KWU@ zhvaS*+=sr8JjjC-Ox!qo&4p5B*lTejPz`mX@X_8numhn6YR37{U9#4m8vWvq1UW?tq5k?$3FuA?3e;r7y0W30K&jZQN^$P&gE}H z=Dw|#tzekUo-)and3ALk@9I@~1y7DgLC4W)$D5XW(v(U_(^jwjPV5#B)7izWww#ZQ zP6i>7Mtjk3HTSB{TCj>ZFfyQ^&?jPkerj7ZfF>&)R8z)a=V)IuG=G%{w?3B!T5sWF zYSkQccRjGigA{bz!V(OqQ6H!$_f|C4GTtu1;&ayuGvNIyY{x|l?A4}(9u>z3Lup3r zI3-&iwCneZw*xTR2lc5JG$uC=_f5W4{20sB>sa~1$|<<= z5CtpJ7MiJmfmzukK#w}NcNL?pzaX3;ZMAUtuYo>7aygV}$9_Ih%yJz0UM44de8-G} zIU=a(*KdH%`f@|n$9l2c1ji~K-ew5yUk_A1!usIDr^5QFpI|(59hnhObv6Gx_%Vd< zseX{o2MRe-xlmvDe5`5A`+k9D6^M@sIXlUd+V?ze@3OJ0;IYGcSTxYyK8Zz()@9by zEyq>ziURT!#zI0(b$^cVDgk;S_47vrVh1jP*Tq0`y7vqlQm z7opUufuCs41HYFeX>7?@pLv}~i+@&&PT&)$6xZ+6OumpL$lo{>Dc4G~=r_!%5- z50E+(lj3uS3+v;BIoRx0%81I@;?erq`S$n=ZNEp_*oyVStehpUo?GFz;#Hx~V^kFE zWZ0~0uP#j!knfKNi*_?3q_ujzli)0*$fBNt!!u7y|Ihw{@P$BKhff%9 zp3i#*%{3xGWMqGRiFM_<%joC3<9H8>y{&c?rE=`O&?S8p)1AV8yb1HFQ!;b)BJFcvc zkbHgskMi|ki`J$71sOL3uCd$JF}#(ea8i5;fz@;{-H=hfX~A9gq_IHi^lY!S>%iw? z8uCsaj#qCtvK)FseHU!ag|lz}xDd~fGtp)@x!HO4BEtB~3-`>y%aSP%T%aozPcOv! zNI7xwW9~Iowsv*Njb~;SQXz8LQM02FMnIKb{lMjAoZ7Tr6bH}TkCVVwDa#;yCu%=p z4#ZV~)Ip&08Jr2m(J>J)>?}26ys;+;2?m1L9ISKR|H&RdN^I8e#JUeJt|c`(E&8I| z8DboEfAExM!tN<3|MQb!XccU|1HU?CDBnZr)n3l+y5{Pm zYVU7vZeDbryy7%Sx9uxj%9i97Y~0go_F46Ej;VjRXG-aVmG{x)y-W(b6zFJk<(}EE zkpA~|C9jI1+I;cLxxZswI=*jxH0OH19HW~Mv2*Je0Y_VH zh$16%Jis&z-2OtzXn%LcA#^_qe=bGbolEvK?SmmaExhQ{!|ZYR;kZ&avp5#S+y6w@ zS0$p^$gkXe#`e)Eb#O>v>l4QC=!N1)FK4?xc(B`?c#gseVOgv9+g;qB zzU)6Zy@6jEPfmU0by%S>czxH3qa8g`Z%_{j|2E72y)jZ6Yj}3 z_P6&S$vM?|6}=@BhA+a>4%+IqOQR!X-tMrDoi*j^&uOD3J*rfBHP!zkB02svrAo_ZK?k-EVZ0 zX)E-Z%|$n^yo@z;TT{~uQAaKsXNodXcToTn(i}-6xt9$ILK#iPs8O!}W81}zLVt;s zvEXD7=NC>HF~?szuYJq}Ab_e=4@$#2&TfW-SC(NB(8zQiZtKdy z&zc>ri+Cuj-($e7y*W^>Qh8zh3J>F0hU?n@nh3y@g|Pwj7hKghE3tLl zRx|3n@>mq$Elhzx;ymyjq!O`}d3~?E7oR;_q#6$-L#807t~gGHk`XiE%7mjUSf}-G zkK(*HD{)r!Tks!GD~8%4$>o2~f3BROY4(53$8aC< zOM-gXF7&V%EEPPsc;s+;bGJEU!FkSPMSG3Re;&csw&4;su$_?~Q8x${gA|$&P7#Fz zwd@*6`;Ddg)8QA~R~`of7Kv#;&U>F56?Dt$OfnOW6OyJD?z%^^J!JQ9x%2dw^kL>} z*!wTxX$JHaf~&U}u#D+zNcyyc2s3ZIX+ngU<9pvOly64!m{bZm=~IhP-ZD^KY%=ij3oI0x?)_ps^paxn(uw z;r*;80?$@^#I9*N`NB8s>4%w~yTFKjyF8kTJf%H?PEJeoXCo2A^PP-x^MAIwr+*^Y zAYAVWB6l68MuA5ya6_dX)a&FinjY%P&3)K=75HhmqicV_lw;|pqI8@D?OoNc`x+I5 zMOH+%T01a9d*+&Wh3Qum(8h~Ap_v*V{(<Mlv+tcn7d#UCDX9_>>q3eGL2;M50Q})3sY!`YcMK z{`B#qzfV3ve8dTLOnH;lJoy6t7byh=FH}iKEH};NPi_@_nJE?MEL( z(Md&N)wO>%N^HI~o!A9}fX_m*@KfXHTOkku$TP^DriFXBwenxwMYAOTAJZyF0f+~= z*V|Vm=_fc46`$o{;k^%Jo#VLC$YPtEIFo%wcAa#)!*uk4Tb6i^&IhXH&c9~&_B;H4 zZVAhYTJeJI@KPkF4`KZ~sdl~JS~Y`J8#}EahJabT&F+%B7agosaxQrM`7M94-&i($ zCVaCev;KIRS+a0@QDkSmRn${IrK&%KeK(2y?WuTUQ z`>;ONe!!gVwnjk2)S9hfh_r>vyKTEtp^3g`kMUOB}VoLR=Pk`xjwpUQe_4IRFIxDRGqj`j^+_av8Ja zY?GnI&Q|N|Idt_0CP$m$7iMh?b&m~<7RHTkStBzM(}0O3pd$D3IGF#fN@8@N z&c;Ne)!svqrptg-CZWi`7aA4`X+NPMCY|l#Y!C>bxq4g&^ovt2*ZG(|N7LvT9Rq#+ zKMlG7PxOnq39LU)>G6fW8YA1r`p?XkLA7;vuj&}Z&)`qWM%LZG_J|C*28(z2%%xj` zBYqJf`n_?n;3*8-l-7Mx1SV)Bwtg`cRKU}{KCj&}Oj~~L@*{}AgwP7S_B{a)tNePq zZX&UXGC$(;;>jNV(}rpfh2P`7`b!@G@kZG$8pJg|&|G7`kAKgGJ-C>9uH{1R3c6L( zUEJG2ewon;{>FsY-&ZKet3t6sMy9mvG~wL*dWQPoPi=~G*_BgH>JH9S)-O^PqMq6PqlFfjK3D5O*{~Ng9b2a;o+=mqeK|l1D z(13M;bmU@m4DRxD3eF-3R+^Y?x8g$S^n};RMZ{M5uD}`Yl*ZZ#buL#8HeY1rH{L@q z>5t}KZa!_1=fGjHl>YTY-F;+G{T`m&$oP|lEHo)1wW6o;F*J|SFfxPL!Mk&wJAQNmYnKjT^EEC;81V6` z5hS;;izBv0g#tzDF4AY=$-0!Kq?M*|hAMG^n-5%F+~ZO-G5HPyj53b&3g0F-r#c1B z$KG6cZro`(IJ+&>&Q<;E&Q1%BYcZmj)oOC5jk3E)9(yF7MNA~ThP>CM?TwbX zdL=wJG4Ny%o}3me2$#b?E)z5|J)JMA6ZXp-OAu0uJqflS?vMWlH4uj^?0&1Pth~8$ z?1tDkrc;&a4xI7?&bHfCKS*q->TkURfxHW$q>XR$cV}7rK001wyc=N34}m}y%w)db z+s)Pt3+aRHSilU}RUVd;p}wD^QA0Z&JotFMHXbnGvHIGTrOg(6{|*`gjtq5c#DwC>8VSx||;-EXSvWuy0Q6nqakrMd(y{kXZlta;sIYssLK zXq>XeT@w)tcgz03j)l54AKWTRNJUk4AB%Wnq)@Xi`dfTMarJhz?`Ge`q3xgVFW--$ zg9~Srwxuv3V@?{%irDq3Sd z$-OgG!#XZ#`TOhWM1}e4-rnugUesN?f@t*4iQL@a9p%FerTSH}V3)d%13NoA8Mj5K zko(5dxE>3!fRke4!_m?4w8axNv0wrO>jh3!z)I$M8{PkU zqDY%Hii}TjcXyZn(#pcZdbu;opw7{_>?sn7EXtG$De}KOIn8xM-5T%|-1-z8ME^UH zV|*Y@*sUgk-PmBc>oa`0us9|r<^ov^vsXI}+7&)p0zDvl?UN$!My1ltJXmkhFS>|rWb#D>r$Z=Rk<`x=wF7Ctk z_}x-kTJdWGX~hc*3q}s3#k%8X2g}-JMh)T~pTQ2VQoRaEVbAUEQO`Qs49H)B*ZSty z#891`;*+7SS0zjvuDcUQ#&Irp%DWajGQDKl8kp1-E)`b-TY;Fji5xEr<{aV z@Z7M4TpCR#wqjPoOJBfpM0!-p<*n7-gSTo3(qSjv$k=d|Ub3 zW5>%&btHK>Vq_AQA+}vBeJ4}6Mr1?jzA=`Xy<()IV50V6_zqvuqQ&TQZ4TYrX5!UJ zZ>yx62LDu%a37nl;Y1>Qs7XY0K#{3rfQFW2y;0hXHq4$!RDb(JH^zK@H09Q{XQS#b=t14sXowYX zt;a}%!wg12G*evQkvl*(=^V>af4<_A_S|xFU5UJA_vlSpD2A4@YkVr@%*vL&CQ82- z8YfT7=|y>r$p@Z~eswE$7eanp(s;A7wvwqx)oQyuEF*YE790;>Gxv#7W5{LPILE#|wmTD37)sd@A8wm^WoXRt0{PA4#^s~rGW)6zqR}$N z*7J0gW!c~dvflE0$(pvD+uixP$@u|`{3K(NqKJ7&@v;{_Q$8RPg@&@Mf}(?KH6h~} z1-erMy&hM-8Xp-PwqXke=KPnV%)`<(zj=p{ai+J05`qn@O}>GrgqF-o43^^P>ABmc z;^D&e8|}MFBV+k?Wp*>lVS^)Vub7|mo+?fVHmCkZ&d(+msQYZ)Ix*%m+6;Bx2vO7u zAX*1-$}Xzc6@f<<(VedRj^MjY3}m8ZZMQN-7nWG5(yLTrv|t3O}m54v;T z3sx>R6S&b_5y#!POe_b<42~Q5^g*7#^FL;c9^ck1!=^mVO6dx-ov5R1_docF+OY^R zYs_aD6wr6wWJhr2^Bs4o8*n-|owwG~fieHZ4LSmom1HqAO$k>sy;av)|2Wh9eVzYk zFluGXwcKr_;6dDxbW|qGj)sozGW%9joT**^ri>7ti+rH*ykSK8jE$Q+AE$d=t+8Hl zFV*O=RyK)tow6n{XS?ABryArhKT9i1WJ?BPanvi_h8K;q2bXEzh+$x6fBzUzNATU| z8|WaJ(1p?Oo6MF9qQ7Ng7Jd2qgP3le?Oh-QRyTNL$)jRU!K|A@q%O1?Od1Q&rdE-& z^k}(zNQ;$4;WB#I#oWB841Jo?RzfXxL7bELWYTu^`rpsV4VUyXbVj4`DnT`V`(o!l zbLlQI$uU_Z{5ZUy$-GXsV2j5YnhCLd?mU79;-LRd(SA7_IT$K4e{``PY?qTQrV+d_ z4rxE>rHe~<_#57+OP!;^zDk(rDh1_m8oZ_SHdNTe^fjNZG7zBYwv~pC_P~x7=L%zU zl5>%EM#JMHU;s(V3;?YDq_#bI7%i0N6&PT$+aUtb>^8&qGh{(s_Pcb+S6p+=W1SY=O-Zvl-+7@8D+m=1mqcyHNo+S_Uu~m%k?` z>}`tbBLJQY0(amWr6;$1)JllHbnNo2I+Zm}!Ms626-T~)Kh>V4T;76Ry_&)q?RK47 z9Y5O=v8l@2Io*EYqxTE78s2a^Fy6wr<`X}_Z0 zO)H8J_`oONoR?Rfp1vhi!8}-`nOCuPda2$)=?Ej9t(PQk5Kj0bAZN8@r5Fi#s^(jG zz&X5!c!*n5yYGkoEz~u?$a}^_q(n7|p=eiIH;&&bB#jzTTKO=(ShY_eq-UJ^Rx1c8 zV&`ZF5VXIUdN?QQE}=Ky=^INgS{_zSVA9F+PE~$Nb91_NQloRIHrjP-)g=v5t#*=% zI4(;B>R=*V2nvP_$1AUvKYuCR3;_m{jaPp)xO5+zsF_VjP0vC3q9sPB@y69Fuh<;1 z8(O}K4#Tx&`iR7#@(V;y>9>%%DKV26OtXiNW-V_TI_YGP*)1@|*kmp1d;pUPasFJz zjfR)*gY`A9HoT?3TWzOjd1|NE7c-AR)V{3*Ox$I%@Z6g#)iw3!)BWb|>N*78JN^LGH``X(kOIu0c4Mt{hinlp)5bylXN2)xylxoup3dzD5DPFUVv zyZZbgiOs1jo6~`>82Az1|tr&~N7v!S8=3xd(_MoJ1O z=w%iiJ_!s&)Oi19QC=%=_6iubJ>)JJ;L$PTmLtz#XVGttr`zo9kI-=d?mj+VRC}CT zdCj?!BQLP_cDu~3VwEH6#)^o+O^ao*7!R94F&0hIi;4SL-%Rb_Uw(&zKK?q$1cy9z zY|}4vX^|o&=HqC64mMAiV{^!R#vM*}mINfKGW5z;gH8(zy@U@B_Fl1RDaxKa{~|CI zXbYMptl}tx&t6=0(8<_N2lM&(twYq#@R-!CWu&F8r>bp|#RFTHmX}MX06^!1H_#O6 z!b~cwpuD#{1*Y&;tN!HNbWx~*KW4^7f0YQ=t@1ykVYU zUI4~Z! z#|_(yqbFtL&3#^-)aj(Zoa)(BSThF`v^LlS+{EGb*0Q>aM=x)~mTv&euI7$Ut*B0J z$oX+A>olDL9;U8`;7Mu&tffZ`aU)uU%LNy6_ozGf7=Ts+xFBn)ZE6)hjv94q>7Yy< z&9rp_v}zt%MfmulimvcO%ID_U;+69!#~iZ~(VnWYIqkZK0jdO$hr)TyS$`Cil!gHT zsR3-$(n60TZ((z@FossH2r%yZTC**y8yf|v_yjQTWC5pic9UjNG(1YmQk2L+btE9r z@ggE356d+O>4|0>U=vSboJT2aQ4C}+OXTa%rAm@)#U6S7&-{R&Io7wfB-ZKqw}^R% z$?|@)#zFu3bJ>yOqjo>*El~p7bo&y!VelITRA^llRNUX%LE$Lg1YYUuw`U%as5Hl# zK$bWLO~9*tv%AN= zqVoki0#|*@CwFfHT3tc{2~U=DvwqMm=i6zYNg_^$B&A-wuujQFcg2lW(Xw`K-9ITT<<1O2? zE7JNo?k7Tb(yWvIEuTaHTjNxQulnyVk>ah6CugY!V^|OwY}$AxUgGC^-zkM%IoM1K zHRz)#g>_n6Tlsy7s2JiDD1|+>K%`RbzNvBj_czB{EeHwO465a!C)(HZ8=8;oy4?rnPupRLr0cBY|l<8vd2rdMzkTRb663mGaTG{vF)_9U~-mN1pW7^{l3a)B5W< zmd?o^`Uiy-wp+v68OOa)J2Hp_Kj4E*_VcZx|DiWH$)69PwxZ)^C;no^Qmhjn5HZQ^_W< z+L_`5LO%2kaODPXKs?@F$l{@Mie_2f8rUxJ>yBPN@Rc#THaG6dRazaKy0K`^LoAs!>e*g~~1FSt3AybSIU7^qOOk>7r9u z&w6ETvY=di!a!Uc=qLzhnYUZD*HrIot-n$d=sTVHp!1`@s~NstrX;@NW1_Xh2STvE zs%zENl6X6%0e(&#&uClChKQVPaj}(=)8Sw~9Yo;G90+k2%#=LtUdr{`{Hslr4t-2#X~wB0{lq1W5jJAw|qaXftMUbjYl zApsmkLv%*yiyUo6cx-%2R7jI%&-C#qB`fn~Qde`pSblc2?ZMzS=epsLX%uU9LOi8> zP#NV&)Cv=u;6+luL~?qP6_s|a(Ta`4PQK;a-kal%Yhz8q6#TSeCtKNYs~sPi!Y9m) zu7_F3L^eOf+TFG^lu+K_%GxC*dBJVzoW+kyxRilMjHPoBgc}fy9glE46K7^%*3exJ z7;aqX@by&DHGUQTg-*prv|XfMJ67oIM5n2DmR@0=BB`{l_VaL0cYC->*jUom%Zt-F z-Q)8g+oGI+R`F+~P|FE3w#+WVK?n=thL#rp52IqS9Cc~*Ae(`bM1=UGq4hg^$Txj9 zvmhGWEXYo-xO7Uc*pg9*eT6B0c=HjrDf5`2pi$RYVF>Q2{D<*!?oY!8LAYwT+QO)@ zZ-9AV@imc3UNgzqIqi5H%~9f>ko94MlZPm?z%^ zXU7cR zF~=2WTQkBEBx(RBvK{Jt-{?&XZQKccfJoUhEc^&#;Ds8;9vN=yN9m2KZUrT77)Tam z;lpg4x^-0a=6^TKDC{M-qr#~6J#2^wQZF7IvfnlVAjGV$!`E%PYU+48Z+nM=e{HTE zF=qi&V4GKm8)TP8r&tVK8k20)lm-rh$e?<$k2@vXPNju<7~S~RtILCrXpYQNIR;hQdn?&$hEHgzvTgA*Znt#^_ah74PkSiP5;VUTcDt`*|k|M7)n;C-o>$ zv`WgqyC2KI{YaBd$n9b783cmPt04VS>!NT}5Rmur{&?%Oh5(}zhGjVS5lCZ$T*>g3 zxM*B)|8z^Z*ycg0qM)IZ|B{8Na>lVyscvoL*kZZp#lZ~AwKw}|^)g_+$#dtd=ZTK5 zJ+3-*hTXZ=B7p#{O}qJbuqLglYV*ljziqkk*KQVrnHq1F;vpjT(s$bX_PWZc&h`~D z>O|S=zFIXN(;WzIJjl)a51Hqln9OB){D>fOXOkEwptaym(wgg+V`Hfu|KhvcpZylT zj@&3i_y*)tl8oEUZr*MJdjCcE3n)!>Xi8x4bG2D2Yw``IM?f0b-|Y!F^jJYW?bbv*RlkfNCd8dq(11SNr>Ihn&!d=Mt>s#7 z!pOg_J}9Dfqe?Xe5m2o17Ow3)qTWGgnh21ww_Zz4bI+4ZZQUkiSX+gAvtiAt$gt+U zfylHEOp8uL>Pjvo2G`AS;}f6#@k zWWb}Nz3Mm&%}(Z^dz;&n+X)n`Iwb{9c?UEXCDINMi<%HBGE#SCYp1BN4@>J znK50JF?{9O{a)l&0s`@_=90vONZ=g}a=@5rd5rs6Yjx%3#rP2oF@DCnjwbOSfl^sd z0(mNcMh}6={28sEuU=mAMadDBgdmZtGg|KxM*B|NB z4cX|zeKxU^Bvgu2DJ5i51O{?kU}-0xe;O3QsG&jBq+3ST{5}3|6^}B)$6#icgfY(A zC!RPg%Niygz5Lohdu-dabRiOA81WDYp;=UKolf@O(!FyJ=qN>*317(kA;`Q_v5QDy zf?PL*^P|N7{r`XE@c*A4{L1`}1=$V36~8L~uH;={)Zm)?T?q(S;+gb!=}bZj3Zp+j z*CCK#Doqo0rugUjmEbZ9Z(mA^%R?fT0`H literal 0 HcmV?d00001 diff --git a/localization/pose_instability_detector/media/pose_instability_detector_overview.png b/localization/pose_instability_detector/media/pose_instability_detector_overview.png new file mode 100644 index 0000000000000000000000000000000000000000..ea8f7a81700ae7084ef3320233d1fcc68131cf08 GIT binary patch literal 136030 zcmeFZWmr~g)HRB&s9+077@&ZJG)Qd=X=$WIq)WQNMwCzlln_KpT1jaY1p(<29zvvB zTKXGH_x`SP&h`F0KVN?AE%5L>Yu)#}=Nxm4F_({m{N>%`G~{GtWV@v#FDj9dZIvb? z+i10YD}J(Gt}BfHZMHivrLrAg?%QuX#P`(pm#*3?TN~Ls>DwBT8CzLf8nW9N*cuvI z*_l||Pi`s^!;5%KRj%4!ur<`TH?_7ps$yzsh#!)Xai8Jl?a#|P!#5D|kcVsFdE8Mh z{(;atJOcd>A8_*xCImi|xcrff>?oPk#d9jo5o4WB_A1Rw>r+?uDM_ABf9fdp&p+Fb zvTwg!p$XGtGLd0&~k!x4!oSd%RcnqH)LewVdh>tZ2(s^E`tRQ#OrJ7u`0pF}#}{|}_wSpUj9AvcU$+{MD{lPn zn}|dI`w{=|g}P6E_Rr#cwLWzvvZ<%k+mK4)oVU^s^1~b{huAg0wzlTJxX#R<9^Xam#SfK+h6c9U&d$#M$w|Fi^#>w;|8{;U>eiwp@1=|1lNq1?v*Wjv zrNozSCMw18+V*|j=o|mzp0~I8&(A&~+?m{)$jCluaLpYeUQT@d|GDP}E2Rd9zMl@u zo7(yE_p+qb7krrQ(eUcwP?su_?3QW?> zarNJXH4-}f?B<12#{)DgIXKv4{;WIMH5vbXOr{U?UAoS^$~!r`##+8%1KF(zVP~V~ z4`e5;SdK_&ZjivG;_K$%&(XNQAAoiG-*ZCtKPHqXr$<`TIS(H`98T%v zM!t7;XPdXGr0a?*yK!=IrfTKZG{h^$NVNGI&kR(%xP)O3bdnU#ZTqt$?-$}?W0{$l zF4@@FeWPf3qQE6T;JKcshMwnQT%5>_ zuX{X}$8$rb@$t<_DAs4M zz5^3E?u)jfi+#^RrhoO6&b1jw9lUnY$=|#+E%Bnyz7X3Y*E#ziA8v2--HtmqrQx@D zbN>Ffbw|h17P(rH8DEyRx1Os@1t%4i@@x%N)3ozml``L4==Lh1;WG7sBj(6ZdFNAVL?zapE;vY;5g1br_`2QcJP_j)sUnwaI9HlCF7=N#~yAJg!o6IR=OgkNR2Ax`!EO?}l=O;wMj z*$Vq}Qw?!4T4kPN@5)nhPBAjRm=`yxJDSWN&Tpxdu3OYMImu~lZJk$8kgSrZWY(UQ zSmt*m;k0_%_fD^Kp}eMn@p9otNy{rUwU+dHp1=E^U11yitu}4gnx-?-RaAg2NkH@` z%fCFk^y4n&fy0NN4`0o7W0w?iV}BMHINSeRFUe(QfK|8fJ*owpmzURWsx!AZ1vijA z+2HiIdQYorYKA3_4G){3we6_wZC>}D62-DYC5oKYK+O&07U7^d2tOtko`&S1~ ztC@UxbkKFW;uN2Cmq=BR?A>jYEkD0JX1ByyNS^8~*BW=Ki4Y1I+^}JTS!aHBY5BtH zLbv(vUp{+oO-%$bInWP zY`a1E>PS(ol9lPlNh*nf$;-t$JVxK@zCJx6=YXqw_ke;<^PjyMJ9qDHesb)B?C3D9 zknP2o%Khg0V%~csXW@bqg3}O~Z$*RdAA|fIgV_NU7egpyb#yqHr6ipr)GLdRPIPuyKDcpbX zKsvBJ+x!$Z;?l*7lKG*`)B;u!rc3QFg`HSML^_n{1#iAGbu;q(-Lq{sy~uZ!!Jj{m zBM&rskL^6fR)QlWX+YdjQbAicX*p{v*(jW+K%bo0CBUgPmaas8&!u5`w4V?b(F>5ZU;A00eBf^%P#IT0 z+vs{qX=WPvbqXwy-Q=8}oozyvU^mq2eueT_LxfYvmyX`vUWbVeq3Tec%SQyPc(Y|n zPHMa6PKdY+$336@-5W6ap`oPIRYoNOGLHqt`3E8$913vQ+9^`)IvSBG0Gm~pSoD*E#)2v%Yd;>LPUj-^8b>N3z7jo`=f{b=KkGR5BK3u4j)kd{ zR$1Rg$Jn?y7It@+-IuqPym#7=xb(~M0?Y_N>+#QDI*m&rR#|&GfLr|xnH)7)L&+3CJKu` zo$v_mU9~n+lu3%mxP~_y=T9}1+mNwyMPUi2PCd`IpN-UbC9b)|%d7GD%y2Ff6Vq_X z`f7UI3ihiCH7UAx_wL<%sp?!t->7yoh-nuW7uz~GsFHFlv#)<4Z!8vH?Az~M=6F#_ zDX@PLMVD9q(`GtR*Cr(a!^#6XdA66lR_C6#r0KYkqyjr^SC<@^PM&P<;76J2d~b6i z>O{t5VnSpCGJSu4Ka*6FR&LrrZIrdyv$g!c%f`K0D-q19%4^xqD|0+nJI{7$o@C8V zih2Dy%c?WqA`0hxg74qvWXo%Z(H1oZe&gBM#w(~Ly|=G)EHEa{zpY-oJB zFG2og1MZHt>#|XMj-|OvWMJUycLwE2fEuiN#fAA!lWBEz3aePtyo~gY`5NKLp^w`b zvVv+~3Mb@txh9jH;2v#E2vF5gPUOGFV?0dYbrRyMmMfK@f= zyAEdzvP=AQp4}jBugo;5!EGcl!NT*E*VNBT>^k`>IGD=KNvdy%}rfJJ}NN%pZ1ehf2lyYOG4G4hxokRs42P>;|$?AM~O_X^0_wQG+@zM?> zO^R5w;X|FIy?ggY7r8Brpn~P&BPxSfVx)svSp)^IqAcavZ}wjvO)tsvSa!tD%A1;+ z5|t>7*Yx@VLk#KZlP9k%Njbw~ZJCcAJqmpO{5esLm*z&bip~|$0p}4ra{Tyld&G)P zfur1g@`Fk~`O2g83jIj22jd@BhGU6tY(~aa9~MEiDs^q&JVjvtFA%~ zB#CE8%LK03vTa-VKwb8!^z_o$SjO?LBCX5*wDrNK)m7do93x5(;!U|T-@$IhE{GHu z7?_3kr4#qmMp%Y~hldl19Kh)f%4}XvU4p%x?qsPq<><=djIE8$)2OJZFn&w3B{gl& zhkky|A?#ZA$htbk?rpX@+qP}1YHXazDPJ9o^2#zOry$-HArK(_oFnztEi&Nl5r4PN z4P@`tnNFP={5_dgv``z$w9CTB&yO#d!DCjDs0+rmk-_$M=f;tA&5&V2_)!R)hD68N zbK?ywD^s)8t==ur*S2uAhbN7Mv}GEP`kab<%Sdg(w4LAL`>TQKaPx(U&b(01_Fy@6p;PsBOw4Yn`10Y#1Z(q@!@ABNd26thyGzgb zzI}V97rBqGqoX5bo~eRaCqIkJszdOEn3$N>vW&bufAPw+3=!=7<-s?cU0rFg(R`mi zeX<&TkzrmH!Y%=rw+qcn@>PIi-}!OU5h9`PDm_!?OKs3DW?Vz-J#RBRqzK$X{{VHS zvv+=BK_FiKr5WSNlSa!_YN?ur_9IOdzvkw$g^L+WtE;PrzQ2okhpc4b=ha)b+o0)< zq6G4xs zQ#?S?k^R4^y$-h|tJfM8plf;2zB*OT@Iar6_)}lNeQGQ$e=jq#($vq#oHUAxiWGE{ z?5NiKksk9JrBzi`6O*;*V6;42NZIDbZE7(Reiq}S@{T`d<*T}f;;mJ=)4u4k4?Q9K z;s4I8nKj0`yI7*T*u#&=n6FA%&XoJpWkz@xdn_9*MSfKzu4=VYPF}udo{GAA#@pMQ zWYPLo|3c$(K8e`pDk@x086br5k{;vn%HET3|1oro~y3j%UyvH5f(Htn%QP*mS}D`lNY?L3#T4bPc`Um3bgH~Deeb$63^#x;iN!ZeEi5< ztDZVw6~ATs4LfmwU*vAHj`#0OZ(q8MQ@7CNcIEc%+nR;W?@YOhe39;WuYca&oTfvh zCmWL$ndcnCPcPFeqS|F)KfZkae4|~Ak5ARSB}MV^A@*66USWHyg~{&p4oBZ&&juMuS0NW(CJ|H=g@4mhpepFoNQD9q%>^nE2n#{Fz7uB`Aok#ik)h0{Uiw(7a$}&6> zERj;!YL%6h`2b*&`LWDgo!QeLHc`I0{^e1K?bG9z*lI0{)Zfi@Y2~{(Eu#rYnk-(H zCqfB%B?&Jg;A9h!EKz#sgls?Cw_dPH^|LLo=oHnCKEK6}R;WQm0B=6tmU*h=QwGcG z#^GFA!J8j=EmeEV{Mc*l{`6FAIHbcI(c`3Ct(@=?qJn|~P&jeuf0J$d zE8{IuZo@=eGF<1!OdW)8S~;&R4)QsSs3b3;_7e>+fs*1ljvYIPQqqd3rK1-|V1ZR= z`0TSkb)S5HWw0`WRkgs;5*_}FoR=alN;sRX$ih5y;wMi^Shi=qqgGy=?pIBarvtNb z*{~`kyKOxtKupQR#3X)s`_7%pSnQOw+cr*4>Zo%nF%r8Q**i(O)~)-mh&&yBkw^59 zpkH_@1rw}1wY@n@Rx-Lg7IYdT3IbKKOcb|l-I|2DG(9)RXDMtq;M<;M8q-@IU@TOO z&iW4zl%$%><^Tjt^a8*O)|mnNR3oI^bcq0Z%Q>FO-rg7xJV~x|BWk(hkeuv&?MD%d}_hC3W)c6%kg6U0t&_L_2K|AR3P( zWO#N0LD^K`WSxBD8Hx>7n+c6*V-o|4k`l0nrKbsK%?WqvZu9xc?(U$gFa8n`@y~T# zrP#G{n$W>m@=1UIkkd1fT3=&ar8(&jdM;{swd}o3@9g4W)M-R3l0;*?9Ko9muRrtM z8Io`%EJDnqeRj%zkg&*XMX3zN>OI zG1p3zsMHBjp6$QKbGv;38B5RXI&t!3*;S-C#UfXSSg>qI1%3S z7cQh)$%&!W=0cmF%u-Soz~H4-Zd~h2&6DCEjle2Hl9e3?d3VEpw559Dz`0PlBBTW7 zVe;&D%H3U=~M(evX_p|()93=Bj)!WJZOIzaymV}iy(na&0_K$ zMrm+JxDks6zwv5t3IcQ00i(ZA_;b&$ZDVk+yISCwYTE9NoMh0Fq9FltU)B=sx5b>R zAorY_t!+kqk(-lp0T@psp)c*|Qww(y%h#v z%YAf!<+_V*%2h6dZ!fsYo}Rc&kh3R*gxa=KQVMhd=$Arm;4My1Pq&#%8fOW&avDjU zeTSy3{c5p$UVoUszdt{cqYy;u3^h9(>(_bBxGEk) zo!*+Po=!vbqRstt4$kB4e92x{U1x{%r3G);_kG=)%qQ!)G<-@qJY^pf5~Bp@g;d>S z^jt=+7TD)^Vd~BwZfyv0FtPyQ#Fd(GtW);Jcdbmu-ff!$eSr(8yw(;IIz3jn2zJQko}SzDWtfQ)*l`>PyD-uLfQBYZL+`9Pc$ z+_sNNpmV2BAPQIvI350O^A1<^(G`N8EAKnGl$4Zwv70ZJ3em|sl8l3yp_Tp~%dGW9 zv>Ve9%$A(q(0e9+{+8{#c4f7dH#ax`hA80s>eW#hoiaXYv8ACC1?DkPp?wnawy1Ol#o*VzP;*wwM*#`9<9$4;g9gXQr>-ZpH{ zMe8XcD=VA!k_Rc0MRT(nBE z8aoKUQ;joI#C6@J6g$&w$VaE?3V=WqpFnwIp+#)jy!qyu6-ujw zFO|Mi0ebrQD^VP1;AC_zUc6WBlD{z476Y39YUQQJhnf*Ts_1&(%To7(ch;Dg!S`z2yM$e5-`q9s8+ge-yd1);_-WuJGxa31 z%S7HFEe#m2FY%sulZ>_r$4O=sMlL|teg!swZ~nPz=Y&Ainz#C;DaGT1Z+w-PZ7vf@ zXo5M9g>!;=!^A@h19HszO@9ll5WCU#=;^6a-u%V^3qb0a)La?TXRnGM%02)F8_YFyDQ62NJYX989o3P|^K^d(o{U5~ddyHw6J+R856JzqIe z6WVcrmexY^Rb6CZF$E_&OynAwJd^s@geY*K*Uin%95f%%7vb31gCbz_+6qAui^pd- zAS}7JmOnX& zx^a+2>9bN-rf~o`yYZZbxw&fl_P1I;dwb`qI7>`$vg2J#&!n^)MM$$Jn?^M3Bqt99 zolrV%_vz{T>E5#)1y1S1BK(m4v<6>c)dA#-3yX^A%+?!ZIEg$JpU)%{@&@ED#T;-z za$>~Gi{XsG6-mI3@%g^3MeP1-Y&TXqube%B86bpGe!;@wir^M4reFskq?H~)+idsxntIi9 z&Q|pF4iIT+CppDyl&x;|ZJGoRX6IU*QK}YrF>r0Udp!x%7Fa8-5Q7`O;=(?g+&s7= zH)$blW)?*iJ_)z!D>K(anflMR#)xw;>8Qvxhvqxf&rBxQrCtPK4TRE zmI+}52Z0Y7#p3a84BfLxq5 z0V#OS8}0Y>9;cv=Qf|-pU7%9@X!uw!8yFdzozddOotXvffB8g9ik) zow|DChWSV`DA04rE-$O+kpYvG;vSi`q$Gl$At;QGA3sjd%rxHHu^+VfyzIgt2tmz0 zQM^#Ag7R{WvS&rW=$T$RazIld8u8PRfrBmN>AuhCk&vmP(&Hp$s88WEx#kUGqI3% z@gJUE8}&48q1FI5SR2%&0s( z2m9>}oHBe%l#ib{ktr&nqM~AT|F56tR>2-+>&{YCzH6)uqOK~5iHTbdRLh~#3j|X# zh#?$c9jMKaE9<4$xwEQ8EF&-^Bp!-S*a)HZpnwmd;Z#HC%(Lp~RYo~w$vzOtFvwEU zhr(pT0OGPrZ5>pHIVws!diW5j#{lbLhu&F3X5UIdYhpG7%GBuW7ImOmxqj&KMyGYP zJU|qNjdM+G!QP$e%qDmm$Yp0c#Gw(lrt8%{uKRbHpC47UrA*eyj2|Ygfb43-Y0cm( z0}Vb0hSt0ykcs$A|4EfMNL;3(x8A;eYvDI6xkBAawurW$j#5Dh#Trd@95s)T31}ih zc4i5E2a0JGzYobkZ7*J5bMtN$BD%fc#)gKJ_RU+igjN!uOK=TZVqfK*={zRn43zD# zN&<0!$u8~nnyD6mV+O*7A7R#ja(_~5%421!9ATIl#Hm|IV5K(8s41FNP?ee4C14RO zJM)`W)N`#mE&OcKZ-Tsec2bV5AKj*9$NT!8HB^l1$8Z0=@x#Y(<90SSilDoJO@Ts7 zSHZ6RAq!G-yOaXxMRA-?uxr0RbD7J<#U&BhJH!@zBvi#oh3@z71;LE4RXKuZcyH}qTNb#)5xT3v%mTE(3%eEz?Qr=*|nbBX{ z*6jvs9Ny><2k0$`1;RfNM@vVS3a(#>w^*Mlp0Y|uTRUYRrv?i;`DQLcutP%2Z7U`m z9x6lYMq(W}<~eEgNOvPpc0w}HN`ozmNPRKMBc7ZVP$lt#vqZ@UHE`K=|s4-rc z8%{x9i|=Q`ovdygKy%5Ls)h!x|L4!^EXEP6r-dJ1E}5=8t+vyT6n2u}pD9It-HLNx zTXFG#jYPwr;o!kIul40_it=ZAsFdFXSDRmO8PJCPBqAMNoQSv%oXTVeRoW>uIGSIG zEE=xtLMVAC);!I->CQF{@LEtaF)|L}x&@j=XTI^+Iyu!kep`4X=CSk!cqC*R+CLmC zg>1`y4B}#>#`gcJ$c5K^^sUhsw&9r8D#^>qsp8y&A$)FH0wg47T{IVxXa&E7+Rjtm z{@?);f!;!eY|VR&ojF&fR$|^NKGV#Hs9v1PF|SdMw$|z z#YIF!q+pkZu?$UL9v^0(LyrhO^(8dh!0~L3X=PnKZzk!Ww_y^)I01@a)ConiaoYfh zqop2ihNf7l{f&8Jz@3CCk0d4`E-p^wn)v+1nL(25O|+&8$ke>e9!NH3^{?;47-F#` zBq=Z7f>hazH7BT+CS$_MR3U6kczz(NaGm;cShd8{!{c|4H@p^453yZ+1=&Im zD4+?1wWa^FwF$1jt1sw%UPItxCkISvU}2P^#5{t6f*7UXplba+)k}yMU(s>F3etj; zZV#m?nI#FWbUc32)nb2fUSziJLYSCG{#HtQi$${K0P(dtVzmg~9E8#%AD?%RjN!Z^ z-@V(xgaO^59~@f-nzOFRL#};KFRK7u=sFbb ztpZ3(Xv%1D&VrU<*>Iv$+ujoZKuD|xY`f{&%3}QIHkiVQ=H%cqoFEP;d+Zt+pOtbU z<)h<}0M=GP0tpHWOM>J=iuh^y{jI)hub+S|?M%^!=4MrJyb6di7!)_ic)(QEKX~c{ z92`W(B5Z?f4#WH3|9ey@Iuw60g3O8rFMyV!R>hj?0kT9K=qtj~HBvf^PD+nRy^(AO zJVrMeGB7YGuY%FbcAC^pb|!pM=);9Xicum73M2dEBSy$xI*^^3VBSdyWCY3Yiet*> zHg8eT&EW-(+oG#&4?TSvj-}~DN8S=BZds{7^w?&A39c|}s)7}kSp_~AOS4nTxFNMV zUByXkt?V372{|Ptfr90x)Dx91p@KX|nW&y3*MxvUFhNj>SScwfl~)l?S-3>(mIP|FNl82QefnfYP>&T}vi z4Fd$%20Kq4#JOyRpij{MH(ZP*p(dc+W1SnSFIAZw9u9qe?C&VR4~mPgKl_0E97U}O z<2HP>apOjA%OiXCydr#ASRCF|_NOGMLy1V3BYA_7&%oAH^ApDjuB=%cW+OLu+y^{& zW}q$zIik};l89*nZeepqAO&!zGU!)9y2x^!GeabQwK@W>2mg?aj*cem8-(*hN{L`T zEYT0~8kFq<9z@|mxmxGNb^z2@86CND30Je-YpF!a=Lt2_Iw@Oi#%+$GvHT`9_POl6=mgu## z`S9O3jkx>xX~OQ)x%(1Y|h zA)j?Zvs|RFC7g#2qiUeg&jZ;L(i@R)lbte=(oKNX2=5o#DyF!&xI}bc1b6}Ra3?uk zzj*PY2@dunUtbk%?FbOvi69iOzyng1U2wok$bRUF<78LrTB;CmOJitjI9z@7uU)XuZJ9uqn$ka2CJ2dLac^fq~7R-Tbn z=#n7%4OA6RU(k&b#>Nm7C{YD7J^JDc*t>+!nVF4Po_Yd1k~M2W)S*A7QurNjC+5P3 znoZQz;^hfKcAN#8C)#_81s(XT619P5J1G8rxsxEsA+nBUVl|P6FG)z4A+%W4(;}K_ zxN@|MTvaoTYx$c|dIlB$ozZ!(Oi)Wd(!lZZD7(PH3S^}n@A32J&)LuWuP{U4QaXI# zfXdNP7zl{3SJ#NaosMSgVhSQcs}kBeIR!-vA{H)VW3%uVFWz9c2zN2;YvFNS07IsS zr!iiEubYmtMO(<;C+EF?KLi6+ODUyz3S3K44KOMs5|B(G`utLB$r_WMp5B+TvXO70 zJks*=IWz`vj-z)|_4KCr^FFtP$uJD`K_?v~h$b{3Ty_j{i{^;3k`lL0M`wBYWr9-X zyZPh8%J%(aw}hq3N}l2987aJd;kuLT<`r-fcl{Z})8GM-LE5d&vLwb;P@3T? z3}OV|b_|mRRWrzCLr5b~Bv(~#?d?y0^M+Xt_5vg}?&bt>PQ2kQo*sW(j%W<5+C)Zz zZ1M)ijthiA0D9|n1Hy6`2l0CN_BMJ2a6;f&)#`dSl95ZI0m*WiF?uQP)upsRAV!=S z8hCvtP&7CCa#*wL6>Fmb$xQMB+UW1;Q6$?-?8BA-h!Q^{d%@SDp?ZU|f*}I39~3Hu z&NcwDx>$@BRQ{mAz~jRMolFd#zoUsn4Om`*si0dYszqVQ4MTVT`t@tsIW&fiV7UlV zW#c2v8;~(O|MfWvzJy^l5r?0goE+Ns8?2U9TMo`Uc(;GB9$7G`YTQyB=s*SFh5v+L zf8&>kzd_GJBm(k-KfBN44Fv_d_7bP%rY07;)orpU0nL#~&!_tU9ZwnI{$S?iRY56C z-nyHHQCz%aqd%|PuF^V`1JHiQ5kjFkM8d(!TnjOGC03y3&fl4_gu}G7DLBsNsP65> z9tCl0I2*2$MGH*;(#SmhX;*)(py?rQ7NA9T4nSh0Ei>WH-Mc%Px$#CnYA*gAQDX#^ zcagL3*B#tcA}p3r%cTMdB!F-p0U~R~63szrIB+vI2j*2%kVQ*qVS__LjM@?YcA(j1 zEORZoxr8H`))O2mjvl*LyH0;`Ap! z*nPwd7_z;{E!U7loNx+Ov}j3k#=3BEdVeVCx5KqXe2k3n#-5NF4OYa^m7T zWd7dutxW`qjlSSLf-MLWvWtf?kDUaoZ!+5CH^}m4xPizqaWOI7b?|5eb)0O8c3c$* zdE$+O@}Fzl^6#}hAc6&JPuvHR@LB2y$A$-7kLkHj-ABa6z?zkGqarXbrxt=B5mbc# zGcocD(HP!}u*1;fEyCfcPhm${K}Hr%0LB7G_?B{-_ah!(QxuFe&= zO&B9f216(I`^P3CFe4))Lza+gp_5$2;fR!v5VX-U;MB^IwJu(a$6w3Mfs!LkQivkt zy#?AYL`}Jsn0xbZ8@5l^xo69GcZnWkp3_4&X+z*~_1S;Q4C^Q@EzLS~lPtkDcdZLs z=0Wc^#)ZKHQ@{oSDaDC#b1UsXDXRdl7(f||o?bUwIe|3cfH-jQpkdMi1Tgg0=*HMV zJ!*>+;r>D6Df3629voX@@&z;k`Pm=~H>~I!TIoafRJR)Q!o94aZ_1--tApvw0mz3K z8Udilv>;^|K88;v9rC><(o9y{I=n++ppyx;Bbyye114}3QQBwNAfWvFVaJ4o7SmSW zK6BXnWItAd(A?rWZ~%#cC0l`Y;?_FhAN!B>B2GU0t2HKB5dul%};Srp4Q z$LT()qL~_DSLFWY_cjK^xC7oMgQgd;tB!j`L3kP!O(a%%@4x4{?*ILoKVr6F7p2hGBg4c4MX*8w!fOa@0kJh5`RI_nvj)&y6JB5s66Z^Kc{1oKv$|Ke z!LdB=^?E(s+Yuq^riQanPviou4lFXV1hhi~r?$; z(xN2j>)FcF=_YMyE}CNI*#~;9+FHPZh+_NUzH#0lfl)UyL6-l~hTIkpMi>PMU#BA#*ZCMa~a^4A5wNZT{kMOGx!KUkS-+J(#FO{ ztM1u=!AQ3nqjk6+sA1eo>FMn?$W2Gs))#xY89=RX6O(YmfMK6PN1!j7XRRf}LJG{x zm{2{?XJlfces<~#|H{hBSY$cGENWrLv9FFP;OMz@y;dD!Fm2&zzy_&@3w+@T#8$5S zQ<#H!L#Yl;oJ0bkJ1YQe%uVmLViN-p z=@^iWPmus*d5ZGv6anrhbZM-sh!nk=u2awg882tKpbB@not&JTsLbAFRsIocUGMv0 zX6L7eDWstM=BU#zq!2T7GJQ)neNDF;h1tDg!i!Za-XC(yesy6Z*@{;chlla3ct?}- z#Hf7PhulcsdG$Bfr~>srmmRV+BF)9ZgFV?Bc~Px(op zD2cuw19M9t5$NdMa83!MES4;6cn)Yt)dS2H@smI%nGBCz^RuuHszeG{>*g$BR;AUx zT4bTaj-S+D&gUhgTdeE<(8os+&bwxiLGYz$f*Nxq(PMTGCO#FQVh7-6?Y4E8++qNC z6M-Vyk>@+Rbzmz5K}GcOaH2mk$B{(hAZBS#1c}=*Y;1 z@0X7UlgCwLTL#gy+Wa$D8`aV~Oofk40SV>+Kreg@Z%4vKaQewPXysa=HS{nP2m$9~fsp10)I7 zg{Rrg#igROv^2>BlXwJAyoxu`@Lwg=SE!r$j^km8#gb2t6Vp)y$AJNo_N;M~PpoG} zHswNr(2m_i76sLf^;M<+VOQbqs+Pr^QteITCa}5joN9pPOv9UK+=~kUFtVk&pU?M7k168 zIvkqR926~SVn7GIN`F|--4w)uGSL)(jI1IK5AY{;W# z1Bi(yLEFBEi5?(Prci~C5Wcq@WM}3&yZz8On#++aofkTt{Lsx*HO-?LQEOb1EqM0n;8^pnaUzZK%ul_S{^+RveZ6=+F1J-FKdpV&C z6_*e2!_sUN8n7?DX!~yvoqzO!>#{G;HZv0{mHCUXFtdfci(GpnA@7J$iv{d#$qhxa8L4-c|+tJ`q`8_sRG zbm{1!vE5Bq4IcBAJ$UzdA72g?pM=3azOpc?oj&YKG=6Ib+xfaoFUff<>a9Z%k5!tYtb4+A;0KqZ&uhlM2Jio!yIJzYFbm z2N5ihVHAR)VM!PB7q!Ej`+QXHoX_7X4P$lfu(7puZAXch-sn`6xK|AoQUg@^76>El+Z zV)v#55y_2bd_(f}@9jCi{n))HBQrJC!injeT&qh!)7kU}V9Ow6i;;@G*2N~eOVSN@j?;^KelrcA z=8-V>q7U#!J-J)n`>tvYOouc>cU?zkCo!jWRZGi!j0eQ8vzwb;2&m zn8L1)W?6!Xo$|Zb5m0vF#;-7mDQYf z{NA4F?y|%yf$4jg_ii`S=lvV)dw$UE3?fF$BNEDyd6HUp`2+CTwG*=$?OwoBnCUw~ zs`>i$1J=(6g78ss@hF`&qWSx+lEIDDA#y#>G}=m3^tWHX<_b#KjrL1z4L94|Yh5 zN=P`Bkg6R^_oUO;Yi&h{WYwO`=X{rCytzr6gw5e`bN~Q0ZYieJRRgo;tw;P_kwr0CBkC*7o~tjATE8d$qgHa3}TD z|H&D9&i8dC{!;-kDrgA_ttiL3>CN83tuBb`&)46Tt(}kFgC`ky=j90%SispHVFORX zTcs`(AhsY&?P#t{+n>N4z9wRP6-9`4!A7cUZn&~4BotX z^BO5HFOLeYLo|ht(YhYz<(*B{(3U)+bntDQ@$} zwWH}5tVxO{mi4>m7s)dfvSUe1f1^z$-HBD<_3u~_vTtF0J4NWPq(>DNia0JK4F(@j zs|0ksgSK2_{A{$sL%4)Sg2ZG(iv?(cqvX}o5)}3iN-Vx0m?PcEj|vx$KW#tDzP`51 ziOE2JbiXlZu&8*9c45ZrF*IpSsyM3yo5T+Gu=HmcQAxxFOfUREo8#(52{y2_?J~d< z{iI~3)U%T|?O{g2w4$yDfcY%6IxY6Sa!lJsoJZC05-`ATXiLywxV{`jH)oS0(Bve| zP+6WLyGPL_yxp0BNLcQcZ21N$y@y}uc!}ci62<2klZwvmC2Gl@X@&*)Ez%ho8M}(F zd&&tkjc4Mf_^kF4WA+A&*LQ$G1i$tz9 zs}?@UoG9(@C3nEw&m?9dKFoIMw8xOvi3@r2=M#T6n!Z`HJ8|f-kbunn^T&M6gleZd z^6aL5^<0pJBr&>pgKDdQb=PP7tRDOV=$E*ymo+lYW}ISy%1;tIMDoY;i4s*oVcr4> zojDG)^%_;uY+>PKiTZ`p92^5#)!)9EjeVc|)^CMEzk8 zZ4c|WEb-enzEbLr&9C))`gE_apI;l9-^Js%FCI^{uikXQ6nO^1pC6R7V}gQI==#qo zDC_}Q8kgfGFHZqA|1L&TQox!%xU97rRI&|Rlp0HHYB~y;VJxC1^ zXJKJ+2BMYUa+2TZIZH+PY*o5U5ne^HTEyH?OX?Bd?u<%kINfrKOwj zfSwO529@NnD?2*g>oV(wcW>Mr9r>{kWM9jckQ*I4;q%IB+3a$p zD>+(a&S?_iEQlzI6mj_^buMmaw8HkwmoMj3pV>t(>KfZB*0mXYR)ixIkgjEgHGe!a zN!?TyH?p>ghJUlz()Jf(biZdC+v#`z0W-(eHGpPfA!Jr4@{ft2tO5cMXW zLviuarQ7;ceyh+`D}^K=c)SCuPSMJx0C*mo2CBV=EpqkiN6OX=NF4)mi^xe&=On6! zMBdF+7zpgUyp)voVa4u2(tHIfk+rw^vZ*NxSat#{ViNPsr!^xZBi!Xy7(2dd00Qa` za}_2A)sCX1D7=0#eQq0&+DFVxd_OX}WTm$k%&q)L97aSpJ&Eg7ie(=^q%hNZw_PQ; zTa@gDxR;pN%C8F$;Aqv<)L2fdAu&?83Ow=-E)1m3g8w6y02&w|rS1_~OMw!ZXl>;15y$(caRc)*r7Y7ZFZa z7acFIcXB!Pk9I8X1PrL+yX~MSxz{g`BoVjnIivm_cTC)wAPfjcrSf;=c&X!MZj48 z0y#3|;4U}2*r~kcjul95bwdY#IH42c5meOF!-b-M1B+P5L{S9S=koGxP^NB>loAi% zPFsd0Ts%F+2+&oNfrk_%7uBCU^tfkovXlq%rfqM0?08^v1aSAZ^nUQ*C+LNP6D27ry8xR9*p3L_$7y;23{;8$Cfp+vcX}D?{@8=0pyzqLzIERrjU9gG}#f8 zvUuFiZq08x@?5KGnwm5@R-KRF@lVo8my*+=?Ai<|p?C9hX&IS!c-+*>oK+0h3R?De zi|YJdUba(eg=T*p_KUNY%RfGD8tX2J%CrD2?HX{7&cky7UgWQ#JE#sH_J#vSF`-w) zW9a}ouYR_0s7~}JP*SEjP6rM2couu|9Nh7DN%@F~BvT0Ow?U5l79q6X(9n=3ckkmb z#NG^6IOFF0uJGZhb-BO6LbT=Fy}JoI!s~`f0OpC`lzI$>vEX7&hA+_4RjdwDkdlj|0EeGevF0m$ze94sF;(AWQHTH?N_ z)cgM6CKa+Xut#8j&FL;EDn70Bv-xtQRyA5=9xXc6jgnwK{1(hc#yF(5UGySX<~R!e4k|iK=ZA!nBKTeL&}9$h}K1<_ZtzFuqwAeo37F zdwY}$y7K<1z?6@Q)oZKnVmct6_cwbs4xao!T)hQURc#k7dtKtKUWkw)-e`_=EicU;Ht9lpvrXP>>FXT@A|&WEa# zr{4dV4>((T_vp$EtI=U4=uG{A?^f-#X*^g1>Du+dkG`qt>6c`f^VL?^h?&~2Q=E$z zWm*HzbaC+%<>btld*eW{D{6ZTb2SkSdCr$x?ieT-G7H)&D8gccH?MYGQn0qMaXo>^ zNe0#cZ7`0QwDFf>K)3;Yfk;azjFa*A**xE;#+gg{nx!+T-u7UI7&(lSE-+02!pCM9K_2DF!bpC_))Oe)k6!M~b$a1c17Z z8ir_&O|XMWS=Ar6wn`&#!`dBf?MKi{VE~M}gn0=nJ>awsU70|bqk&qAy&)@}2y)zHZ9UY?q4bhqAhKI^^>=@5zC-tc-@{I)b-!dk` zSe2YhoagD<>)s^fw^3uzJv}cQP58Re(4b++eCwH>P6v#_0)V0(=xa(h`N8!>fg|bV z1^_Q9V0*B#N5^X^_hji9%)3NqM8w4S0I$!Kg4sc)6x15g)z!SVX-}WxjlyuK2!M0@ zo-?=`C3N1RfWzlp{4@6TaD zmw`+B<_`eTW6uoL*MsnB>)|CZDp4^5rfXdTI-XyBW=koHEB`R2uAjdZe+kTaaV-?eq&w~)N&2?5*YzqquaDLEZ_ZnFFRSnGjjhVL^o1`BhU4E5Fb8>dB zKsCu7V$sgVU-8+hXk@;O2<&WxD+>xYA|77Te@?51P!;7N%iPAx%L|d@nnLv4{+-eB`7;?f*encm$32aS=|ZlG zimFt**apa9A}$NT%4&oGzJ7j7P`71H^SHrEg?l7#Xh_MbMt&vZ_$P!BOZZVeu@WU;NT!p5hTwh`?92fXWITQ)6FP|kv}x1 z{+GDqGQ9aT(G!cM0V=;9hEJ8}#%~DAo){5&&q6wa?1GU~`Op}~*kMpuxg|SI)yQ9~ zh!^`|p9-cJ={htrSyyj`Eda*33Y7S1nm6bns8B3|n}BNQSDIFM&HkV~nJockeH2iY zV6sUAd3Ut&4^*39p=L`Ja!MZ$0J;`EfCVdaUxqdOr+ZFhl3G0N@K`f-hO2JQH}ldkyr*A&(zp z?i~9=txO5YQ0#&|hc@X7i;xfn)QVuKg$oP?3oENo7?E{?0rB?P%J=V!05gNPfTFA{ znxm5w0^uATAImb6lzvg*qF4f=ywBb$F|=S{Hix32p#jCnWdv9mH-C2Z3_#<0z@EX2 z$imth6L>`cPoaTA?`7PQ15=VRz@7o{_!1=*p?P(2cZYOD$6?a6sJ2&RMu^WYE=~hL z>@7=6MtI)l_wHfA8^C9e_1dP##f3nP$jHu)1F?^XkMAZ-ABTY?09GHL4Y_0c?g}ph zQsM&EVc;;vC@Dz?Xb1v@BRChd*5kcLoJ-K6Pg%oze>|+83+%@pDCf?QR&!sQpmOxUnPH|^VRhK>$C1hFZmxC69lu*(^hcL8_csyHvfLp91s)z z^xqq1SJh$5{CnYcyb#5gk?uTksj+c(?uy@ULT`BzM*jQ33ve5W)Ya9^DU0gDW&ggS z6sNTGTV<)#zpwu$O56EA3~Wi=rsRKI0HT{pYC8Cd!_ohPn*Kcs_zDF@Bmeu`Im-Xt zhsV#;6$JlH0DP@9WB$GDVyWHCTMSoM83n9`6@!`lzxQ=nItKmUQy|hFZS=0(B>wlr zO!GhA`EPUn|Nl82`ajP}x4re)fJn=y^8b7lX60u2fA>Mpg=gOuo{(lwFO?PTN`B0R z!ZEDrfG(ax4vOdfetf1||X zcTd(aM!m)G1O$i|w%r0${@4Pigxd6lgAk z$G~&;n0{4XZ@7K}o6q&&6f_ppmi4qSIa;D!0>KWJw1Qgcs{cb@U)MQ@z`z#SShJ~Z zG~_NRc{aV`$-qRNOh0>7829h;UOqyNul^J{g-m#CO-GR319;VET2HC0Origy6|7)h_LwUw{K6N>>$uC zef_Uq*zMNhTD*j684vZC_gRoJpA|9Ry1TG8YEMb`_aVwLbWGEuu7(ZgD-uHcKaN}t z1egv05bXUZ|GV$b0$q$-upy4tsM&6-T^LN75NwAjxR3RJ|N59HKr8q0yJ}!KL_-Z# zvk7p)<(~4AX9{XM^bRn!aDYT+`I2hDyNuvd1t*k!@{V@{$5DI zCwM?}hA{kZLr7_Ulu3M$x4_}Cye|Bwx=%(cHu7=4!WV4m7hmslES~S$96N-dO3dbY zLjSIh$GX&GY=7VEF_GkKuVjDA1E&$SR>rNU5E5_iPJ(~?Sldn@|G!ILraP!PV%LAK zuG=&i!TJcc>Au|7eXE~R{uS6AiO#0A7y`jJ?dYX~=4enn^ERZ$sot-?5$j#TV817^ z9->`Dsgu=u%eL$sYPFcHWs^4N$o?zAM6E*2_*aKY>cVxcOp_#TSr}cP8Ry)jXj5yJ z{~zKzcae;Z_c`E73m}UEobX9j79G&0A^<6AfB(Lq?-b^3-B2PtkB@%@c)f^-24T88rl5eu#mx=WZZy!R85$dpuNp!>5e>sYrmI)cBEDDr@= z>*C>2KE70z09YP0Wq8nry12T^LffNd7VbdV;?mM0;d&$F7@<4p7#$^r znlVg?nXi|!Y+d{^pi_|Afpkd)R|Ux0>TCl)aOTXPyJEoH4GT%U&_Y|^yVo&2O^saj zr$RhLxm~qHv|AU+9{AEVE0sN@z8tgRNm>NkyYOFWr@Xc2vG=XDn(`l#C5+dr8B)$WqX%#>Mb(E4pRoQr1L1bu?r_zlCV zU|`9C1Bn%gv-(mqG8`o4p%b%nUfYrCz7{p8irfU>Pa` z=JRcmiwi(3!|^-vqKyP*4njvsUWr>MCxJLBf1PO%307gmdphw*|NQw_U*FN55!rMf$W8q_I{HOMH5=W)1cV`O%%jV?P~@# z8hisw;GGL%9EjlxZ=&;o2moQY6aH@phDI@G;JJtl4-l%2c}~-dh%QUuWn%$H zp%YlA0tZhcA^@P029vs{@I*ps#ksifp;n~_R!u1E&zLjHFlgr}p{hpOGN?K~UFn%% z=HVd%GVV?2pKTj-Il3Sd=-vwjrxQYmE}ej1xUP?LD>0K)oPsJ69-BCrYx2VkP`9#L zZ^HXJ6B7o~HUhLMXxc*=)($B4aH$Tfl@J{sJh%>x%45iOO9=O+RS{qwsNgC2 ztS^FRQfy`>ZF8)A?~LmCa%)L{4~diC?rgmq3#7<}ul zfEEw|r2!SGZ)k8Gzg?&e%@r2h>o8r8ijJmutxJh83NomVam&S&c@h#2!&zV$R5?LB z2hdlsM~iw8IJvway0^Brc1gZtXee`qsAO-budf4yt&k%ucdCI6MgUDZt1VT|kb(Fm z)MT@tFg!4;9ar5hfJIz^D?i8=B7<^w-xu8`q?d?*V>0Ucdcf{h0r;1C=*-Yt?EL&G z3siFeT`s%;Ym*&d4nrSG2t0x^2`o=&UU&meJYv?d38*n0931M-U@^fA9|Oc-nSlV; z0sZlDY%C$HMROaQ!kWswJVs<)L1q$*trTl;6|b;2<*?o=z8dM8QAc#hj|Dt9M5bGd<7B z`gk1-BHF>{4oP;flVMPW4bDs8Wzqp~!eB!hgnEnLFvr&mbO!DUg4E8y;Y-!y#lN~N zd7(qjtN9I}pmD4_*wZY3`&PYq_12yr<4>TPz_bo2>>#F2enSrlHpxy*e2m~sUxpx$ zYU=7@qL7sNj8^nfbTmG^^hJF=B~Z~7LGmIp18c(^CRYz*-ZBC;)+*Evp6C(iOMWhY zAWck8&V!!?FalUSywTD1zHPuai2+EBgRTj}^~SMwU=3nVmHA5)h7%R1@$H7eG+~*dW}2LuIUOZI>X3Qi^+Vtw4@7Tv?a#3|IlD-6ufwsC5FG7BtyQpv;FZ zya)EybKv&C7R-lfgJUZ~Z4h`+sv8BS3P{Pd!3VrepbF7KB?BYNZh)|UZcOnP6cj7~ zm3a}fDo4T>9p-PLn8`T4qs?5;P#9C*CMk_fSrz?H!^1DnYR#}#3t*jUk6YReu&D-( z6XZy5$Lzb-?l_;@RGcRB6xOE(U^Q*46mJOgx|EI&gJui=xsPmNI>++hmsBeC+S4amx2jl=u?r%WK0o7r%SD>NByQ~ z;EJY?S{rJ#fE)PO`YiTLorCk?nN&-_TI^7^XV34;7(0Hu9M;O#gvI3n`&2B7Uhl^; z6YSpxakBksZS!;Xc0t%d&`x+?Aa}1shp`8eO|F?FYO=itZ29KB{ZiQfQ2hW zvLzr0Xg9U8>lC?UyKMo-3Ro!^pgv1#0i>k^5*bkJ8IWlO+x2Af^WOm0BkrxQ!7oI4 z+i7Q^-DhV3ZRXOYOWi;f`Fzmq`>SZ$13CHvq3?HFj`e9gBBT@3t>m4ap024($_ey# zbNl3AhD?C?kkN^Rsqafopnl1PZMr&9$>5hD3>y$Ke>*VyIRhM-n3xVS*#{q>tkDPqhHRn!a{*O=kDohI zFyFZhjcF)=`Y>G4GUjM%*EKedf-2qu6tzjzK>$%f2NYnwk@25;umLmzmmod#z$r@+5CFg&g(BFIViwXrY-aqd zSe4!xC8=9z&kN^XM%21u>|6~dv)NE36UD+uAFcaZIUo%OHeOsXzsoQc?;*jB-!Z?WhY9+Is@hvKKms@0}g)1@4d(x4zK zVWMU~;I(HL=&@N?6Y5UVjNK}IO<8>{E-$e8G)6oZ;}*Y7+2xJ)SiviNFwGX9p zljIG&0z7_NIX*LsnB_CloYP;u$RBd;(|eryWOv-R?xDP8=hUxxwg;&4{VAU1$8qvq zW1mc~y7-~661r7r#i$mU?+%DXfBqyg;Qdufb!T_KuCF$6x&Motn(K`}&cCx?lfX4m z{!+bSp&X}sLK0MT{#d&R6JtZ_t7C>H$&;L=m0DS1ybwXR{u&p_6@iZ3N~_2julGss zH2r4Z_WjzOM-vf2DX$6t52*^hm#Etgh1{F*&p@w}0e)}sxePFVpc5(jbO^J9%(jrw z(9rHHk$EtMv4Dx#f73D=A;;krr;FxED830(09!K-Txdoo@z1hOfx;=eiA7VW10hyNrtq%f02|+v?xCh|?gg=Nw4=yC_=KHP}eRV!Km`>uXcPN`1$T|lTqRIJB z?bqgVrPOW(m9|#N#-n-VnAa-u=r=L63&pCWuD&Kizv#ld&a<`bI_jGIBAOt6@**8i z?Og2S$evi8@7?##YL({xU*s2V1y9B+W%e%=v8$1?THcytqh&X;X1_ugNv@7mA#;;e(~ziUyUeP>^U;~aWCl%yU58Zl=*C<`)hHx zZFTdSo};5bbp>~0^A>5a?vp8c-maS5C7}FZ1vfK}Y9@SH{0J|tnkWly*5Prd`EEl&Ovv& zLda3Y8oA@I`iSK3EvVqu+E~{*74jad{j$>D#DccY*W~&Q3?1KD+K=9>*+hFB(O$4= zI1&w{$1U{b`JR^BQW7^lbQn`4lK=SAgMSRg?p&GM*L;0^%pn7jAN<5ZuG=f$o%{-uD*^_!|!cDL^?^HUk#zOEO1;9+&KCiI1tW@N6*z%RfoZ7Y_Mi__AWtl1O9QAikg}{?B$s{s2`!5H~ZQGbf3Y}As}#z z%H~2jw*=(p3A-7{Q|@z$9v%Y4>LgdU^X~h`xzp)r^O|ciCSAymIr=tH5z(QEY5U>R zQjF)_;8@yw)%?;v3okPE&G)Kl2v8RXmy1T4vfZiSX+5gtbd^ zmKIM&rsV$9sWV{Jf}eIf?TsQ~1~J?7?~8{8dgg7pSvDF2rLFXr6uyP5vlMavj2tyU z1v^X?i-543LfQsHnTht^qE)!4<3cB_^tFBcj%a5bENzM2*1-ptKT^1*G!x?JAeqEP z`VTH`^bZTW&@cC`KV@#-kf%Z?NzP4VSGYy$>_4_3EI{O2y}tSQS*lSG!N5^6TQbGs zc6q-2kgVGp=j*D~X!!?dJ3RYng#J5iiryI(j`OOnz9w~yc4*?K3a-f{80?lRj8g%p z6DARn>SmoIN(V$SIPkg_ULG7g68uO9Zq`$5%zZo>CHav1vFlgVc{(?y6; z!^7|K{7WkH_w`c+aE`uRHvg_Fv(^sNXarhS+I#`47rZbUI$jI8^=Vjg7DdPDv=|A4 zmvL5)C6EvRvkG>4+GPn{fXd3IpjIY#0t_KbMX#g)h?Isi4Ej2ct-IONvO2lTfD2^S zwb;GIF9o#1IH$;fxsvm0v7tsc5$M>;bXpZ+>NT`qss!lYLA?HTq;F;S!?JS^WY7RU zIh02wn3{?E+w+J#7U_&wC-2_}S=MmrJn;IUX2bAOh=49)ut!rpjYY#jpZHeb3P?xV zL|1?*W>Bh_e;YJ+!@!2cJ=ObWj8ih0-1Kn&rRfamuFwb0euXeYiqD?~BQ!OW@z&P& zH1r?sPD}NC3c|R8N3>UWW(emOaog~BT1Mr#*?S8JZ%1@JXtjK?E_6`Tz<1n9xjV&$ z+Ih`GM*QRug~|~LxS-SWL$Er_=Gal-TO<8+@2L9Ew$A8>Wft5EgGb^yzNibI?xya1 z+`0XwvQ6g~tGmjt>pY8*npikA9&n0FT8$C!GllDv=EdoG!>P89zFx|C(fY+lghrT+ zVRU_pa;s?jMIw89(a{ATT^CXUIa9-FbKxHxSxqwy?MhrRAt-cJ&vW%nM{1Q20%Jo^ zO-XR#E|n(~f2biAGtV2H;MnF>)Rw~NGBykhv@~oC5qFz_8KBE`v z)az!NFJ3%<@I6yr)m7w($h>A$m}oazuTBSldQ~U9Tl13{wjF++9;f*rt@(`5LRlsL zTeE-5CP_25Af615$e;k)&CEnKgh#%@au2#)&^%2d9Ini)tbJ;*y&^1jijaxCzV;S? zg5Gg%9${fb|2|x(a@i}u(UEJV`2%~=7dRwN9^^_dCFc4bYQ!?8LqnMfBGyRRp1j|p zKg6DaL6qR_iC=cT?siU2F`!y=O9sy`Or+F@VGa?9LB@ZU+JT0`c=Wkl9_`UEGayhP z!jzSh!?bNEqB8G;NY(_Pc5#Id_wbX-O6Mm54`vrAWX3&zr=QR)8sF~CP|ohd8J5)C z&0D>CI{j^bBj)`l%6DuJp-Hz9*Iuggd|dNTAHM)PH!Z_0e2r0|`;ODJrHdl($-Me=s}?<-F9rKRFSjYA>Z(Bkp?*85bu|HNn^ojs*qs1QJPJGC<$P z91v9q?m=yU^bDC@c7{QQJj~bc3@shIKS+-R_s*C%d>%=uhWo7ZU?hP9Om3kVIDv?# zMf>5d8t{;ib7o_~`9rT(%iiY@4R<6QK3 zQkF^A@e-N~x-)9hd@Mr-7Rai51K54tZShaz*1XjFqZbi}9l?0d9Qc9ou8ZI>586l! zz{Cn|oWquumvz6*+lE;XF)+jeAr(}uS2#Fu0pdc&`>ap0c7+;wmc7-Fjf*54N*F(; z+qE8d@!*4cZEw1WF|1ynWVc8=Q*dNh?yZBVVLO2rjdQIRDtPBn)5ghWfG=Xzu+dbasSct3JwI8-iA%2m~bR!~2AM{kFbrSpLhk2B_T7q?5EKySnBNSh6#N zV}JXNX|f-&%opd!JyqU}-*w7)H#eR^m*Ia;MTL9&R<-FfKY}5)NSMy_b_AiJSVz6{ zo(3F#Z^B2sf=n@JSDE3o2=abOIZZMoY{wL0+Nmg5f0a`I&&O<^tN3J$bKdaq(GoB2S~-bwK5yF=>EuPi&PTWY z#|78~)J5Znbwxr!bl|&x7_`Ge%|`NQjK>2+P|hbUiBdIH*IMd!@130HON26oRTM%o z-0-&HL?BB3)9>ABmda2rsE~NfIs6$aqik|&liHqTHR$T7-`lV>%h>(MuJm_f_lidW zNN#TbG99ClvF{BQ8ODXMSMF%JeO&fpmFHzrIIX1F9m<&47 z#e+IIqgJEqgcM}WHsQ|hH_ zraqaqUqWTl<9CtEXlN!n+H|+SJknN3#;P{U+MT8*Q8;MYWVC-|L*TV87N zQ^I${)jB;VI)dZT69}4Ugc94D5e?V0H zUD3kmc;j|l`fDS%wM98Nbj=SJ4gXm5ez_*CX`Mmn`Un4FU4i8E*%^15+ zc!?}0Q~%OCIFE>6-e1Sn7|&_%Hf!NW@LmFy%p^@6oU-niE9WY78=(-voT?7Erp`iF z;sK!s;X2S6WjT@-0b*O+FcU2#ysC%rqYx>Ftzh;#5fbg*^8=Vz=TUCl z&wW0~-LiZ^yi;DsTwSX3gZk=4hmi8R=%gzDahoEM3o)NDjrgvW)~9iv&WtpNttZU( zvIo`oBsxE9@yd7DJNl0X0hEke-Vq$KToh#mxi2H!9$xN}iFC84kCc0a+;XSqSlVzX zn#bCw3lpzCWKZgHtmT0 z^HYkhJl||lGA2w0(PgLCiepoZ95VY*fUOg0QQ}rkyir+({(LfNPZA+$V8mS(&&Z38 ztFlXaAN@lx3N19?gTs|T$)|-OB@$i9#2Swq6<#S3_k4vFfGnh1Cv_vNgTiu)nUh(W z6zprCza(N?3!lXJGC~!0#Cj+ZHm#vU{gw<{TWHbre4gm1D(~z$zgL!onjwzPV}M)) zh+G{6vp!6Q&eo_>{*;4qktCRl=(!FH9+q#K`;e2tdV76_H!%W3=>1O3s<7aGtw_g& zaH4iJwtQdLER2U^Scep-Ox2k0h9BhAc=qOm!frz^vaTI&D?(@5{6V^EKCW9( zB%k?gKXn=U!4N95*3V7<7Rg)1uG=Y*#!>9W9Pv3hL%yG8=H}=@Hfu2hihz|pP{9fN z(4W6VWNxQojEv}TzKJ;{7AQ&XrEp>^z|nq}Sc`XQKf!}VM`Fbjzdulls_jEv;o?%Q+}s8Yzh|>1+v9vI-|GQk7CWmWOwG?^dxM@>aX;k)Al4g z@V0|P$ZVc3%>U*zBp0WuRL*YCbbbO|elYe_C}~YPOHCtbG5^68wam6H{uct&8H+1R zu(iF?n&bFa>a!|rf|zDMG(jhKs(J7*tn+DJxFM-H9b{n?@B`63V@y27ZluNQ)@e2s zd6+O}vo}uRqoI&N3}8+-2NHwPLQ@xAe$z@bOt`6or6h~!jnJ4Xe~QW!BbqwX4}Y%x ziQu};fin7-w6xax)uWpp)#egDG?{*NcPNSwZB}kJ-RR?hc$J{sbz3@{lwWO~*mYKB zIXOg`eUnf4lu*5o@L;I)(_v8?6&zklcrtTbJJW|jfqqf%S&UcUrOvv0h3BpaJhP< zF2^@aWk@Oe>SQ-q-@rkN@4LGf;k|qgHmE>Pn*ZhiD`yA{L(g0x7zsFxM-yh&ge_DG`yAcNrD=d@N-L*PYA*m@|UE7j9Nvk`i;Kk$pN6 z9KlY^d6w z;y7WNq!E=JNUV{4c3mIC<=4K>sXzVU(5FDJC0FTfY5;$TQtJqy_HIvQy$O}6&`m#& zx*xH38iLxtyw4yQ)Ri-R+m-2jL6PZWdr~Z|l;YhFcybiyPo=fTzsmF}?D(P!H7DZC z<0oV#mktC&$!WK*Z)r74`wj*nH}b>U=6b1&;sv~BLOfY&WH04PTuXv_HahV~^-f!O z<-Sbj;AAKa{CFF;{15nlIGyqW@5bfY3Z{C&_WQKx<|<(~g(4C1!e}lvN5%e@)Qxxe z{)rQRo?~;}Rg(}HH;Wr$)59!|aFruRZojD=!Lj1vIOUxNYUynk_V4y@j(T^KBlNV{Hg8z~qhw}^JV(r7S z&sevYGoxu1{0`5Kss@=q^Cy4oCjF^4+*?4UAUfEEdx%luJga2WbnhNr_2j030RQ?$ z;(5%pMctitMe%-9!)5AV_QCm@eIdv$u62UnBdaF4QD+;!Em%DsC$fj8wUJmUd^$2&AS&l?g!(d7e^siA?y26^A03?dUO^$dXWP{0 z3<$;2_Z(rWyQahz z8Q6UH%r^N=#YOC6mdI#?`1w0wCaik``jnVo ziF;sK$^&9B5I{6{RAXXdx@5Clj+CR6@~=6F8Z^*_NdPnu9+aVBl!Z29s4din$#e(>Z1j0H{Y49kx?ouOqm}vb@=a!GJ~| zMC0H3-JcV`_78q1nZ4U;N9Sj3yt{&C2|;!w1+H0eH{sTH_gt#g8&~r-4Ots({Aip& z^Oc7bpz$A{QwY)K-cmg~blUrq(Kpgdo+HLxSMc;EvO>`gyZSQ`iL3O#e6B%U~-$0W+l`69AcOVeXy3N4dw99N7L z|1b3)LW1@78EU%=XhaM*PD^uHCjQiVuUKe}%`>#k^LJjV;mE+tWn9osZ>rDNH;zm$ zDlARgEF61Vvzt;{X!A75=BaVIk+FWd-M3`CEt;q(w)z+KwGkWmzfPBYY(uELDBBL# zef{4Z4w^{0+qRu#`VC$M5+7sUkDjz;T%WxWMOSd}d|KJl)%6vm(L!k`ITlO z=0nq2-<7Nr&kFsg&dCyp!bSxDHoBLjK326O;}JUa~rY; z94+yJcO3|Vd;Oqr3X6@^D2%Ce!KnoDxU%@+W|7cbKV+JW@*rSn7IG{hM>zsHXl>$j zf8D^5;rUC%UM*oCGt9s}bW&3h!&!a|9);K5FW zQ0joullDbgOpF?4lw8$uO&w6)Ye@Wj{Gkra0I`AfbN!$m(Yw+J4HW#*fijI3jK{Q1 zQX(Qa=51HZy8mSPVg{KCGrXJ1uEX+eq!lSMaV=Kyc@tgQ_b`F-aMS)yz!Wct!{p?2 z#qbk#+rT1v1k9U}Pz-hjC!2r+9f8(p1e%8gZ9Z@o@Bs=USGF@8J_Kas&y{8kZWka} z_5eZdX<|V`;F%cAdc)8#uu`qP5smw@-B#ZxIF==Wbu)&Q2K1p0KSh>y?{st2Zcv~S zc5kD2K*fhhF@e3tB1^|%^wqBcs2cCUkAAYwi3a?l%$P7(f!Ws%ysZ6ogyIaRnGBq7 zph#ZRK%v@lw1}6m2_gQ~ZnZH9Sh~eu@B}KuEZAJjE4!h|fVlypYeSSgW%?C-eo_ue zL+5LcyuhWzq! zF4Y_;z)az7Y>~3>L_js^E}n4-qPWfJ2Qd#)Dct#Qut+|C}VU z>+k>*#DQQa4=_Iq;0+^vCMxX;(Bj0v?DQE7>H$o+RW^o*v`zw|n~%R|fJw$)p$f+x zC8djyQe%&Q5opxF=^3Pu>=6Sdq+5Yq3Lz5lse#t@+f_)Gsg|$b~bh$OFn?YoHPONItWo@_YVDt$o0q)I7f? zG^USY>Oxp~ujzw0SZI2Mgc%h#b*Ie?b853e^;iz|B-v_7=sWmY7ZjdmK+!p}ti$e93>6i^X z0!lcy@k8CCN9c&a5rBm*$VXLhR7=8@53u6lEbACJg{p5EP^EFb{#0%%;Rm!}%;pTJ zZBqR&`DlQd@3oPg1A@qIg@Jbx-RXo4$nGg-Gk03Vq0yELz{3 zF&OlX1Q08tT|}QKwbm;X9?yBY(MLP zwrBy8SrPCqy&aqI(gnODFXJeX8F=A=i*vz$L|!Gn?%cr0D;dCFrK--%7m%q&4%=|;|NI`L1P zaRy(=Nnq>;o^A?*gC7dY0O4c0Dmask7PtjsVNN69JsSgWZV4V_lwuxi0GEGVTtr7S zBKJqoH6-`RytZZ|K^%abC?HQgOq0SWPz)+>#GEbg_}gUyf&O z^o1?gu~?{@)p>cI|m2g`O5}Q ztJ)jyP3)kT#D#F*38aU(^mIhx0%DWiaUDIc6Db_LQQNQjj*G{RwC37{k~_#FYhd@Fy% z&@Y0*?u{|>I3Qotdu>v`Hs%IxOE6g9z}u%#%9X?b_WcMT(H|35mX^aHtkGr&f`Sfq z6$Thdyax=$!odOW#*G^Yi4Kx1E9gkeEGGrWU-0|w>=_WQP5eoFc=3Tcy*@25@raZC zkqg+{+8no>29K3hh|?oA2qVWMNo9_ZiVAKdg#%mO;KMOoe-xxf{SOW6)G%$?Tb~%R zB=zOUfVqeju(!wQ6&hfWUamTIS1?i`Ulua?NL}(6?+rMd%{%xA0w&8k5WBfXe}ZR0 zJxp!;J)NM~;iwI2wMeshi>&?#d*aDYBl*>eLp z)^RB*#b(=3=jah6z>Yhiv`s(_z>DD5%NKuNJqr2$%uQdP0)oEjA}^etfsJ_NBsj%N z9vBwJg2QUbG!?e;>})}rI1(R;$3*ZGiHNld!I`@J!wJZ6W5I840SaFE1Id6B0npY* zLqw-EuF!9l1V9U{i#7BJlOiG>SfyQ9GxV_&I57TO&OC7Zt}Z8+ zbnj^AD`NTZ6T;EzTR5K&g-5{^oRV@G@(3CVK(G#2p-*WU$jBbU*-H8|K9Lct2d}UD zQq>h#w1@0*Q!a>-gf?fFq~itrBG{R6<11y-32ZM-k z;3{(U@0=Ga6l%YKd}RnGlQ5yc1gn30T6SW+q>O0+|K~^eEe%IP5>Cx(rkuePwzW$r zlz3Dv4wpOre$FMwdx^O z-`JQ3#&GxNTO>hFp&~^^JjT((cX;LcFO)!)Ea@o)OQlJ#=##r9LZ~afAt59$O?&tc zmli&9pX>+H6Xv&6w334%3Gz!24dWWD!$MFm7XeK$S4 zxKM5SHiSW^MPpJzjm;H}dTw|q+Offia_RP{{J$lC`lG`Cc0h@CR-Y6)>i&=6m%R?f zNmrr*cm#%Z*XvggD3T5?FY*ztPGC>upjbU6IYEH;-2P+R&pq3e{T6^~1KIQ5$ zC6;eY*N^pii|rT!rBT!Hl$aZh4FnxBl_SH3M;aY8)7Ir0M$b|+#9c&%iG3UI*598c zTAn0no@E>vFAV>1?wn2kOr^ngf1O4rsH^+4*~kl1Gl}&ZF*6#r3>a6=ZhH({OvD6L ziS83Jf6she(RWGqQUy zPpm~(h_sC$`yvXjRGd7XBzH)6b*1?QPYMqBg@PzW^&B*TJn%KpJ_mRC^ zO4z9TxglB8^un({hXCP7a=YG=(Y|ox13b>k zkBa*3YG-0J^`yuJ$MGW32%WdECbR3hmnX}7FYjnA{(>u3tXj(Q;WWS6LJ-;UZs8A4@v-rqD+4YnLitV%6IBxm zCBz}FO7I&Eqq!S}qWwIWO20>1bm2TA`vDxCF?cUW2JJN}So&2!C}+b8@0>Ho_X~f* zEAKdVEwjwaV9?BdF0u$Z3DOHnSgmupzJe)Kz%^0%)_pBfv-m)tHZF;P3cWF~cMa*8m_EF{C7W`6%=_bKU73pH_48jEYq6(CR-Lw9`!Bzp4Q62& zzv0_BT}}wrzw^_TbH0L@i6ijU^pD{eHGll+L@hEpY|j;~aBt0ReZhP8Corj{ z0@v@@rfrIFmx7P#lGlb9{JgBLx;NJP-T~z7!FxiRL z%>QZ+oV_Joc{r={^At9deisrOV0Czit)~Wx4qwH;A)JokJkyP0j^OR~=A)j$#z1+^ z@nl7uo=pq)UhjR}YC?2A;d4D*^!2!HX1(1zp6M0O&!hDiC=z#7R*58f=8#JknzA-0 z#s^wwZUJ|K-jTk>{Q3&xYpxeM>a~j_UeM_kl#JVXQq&hz-koTb2cj>tct4#MzHD86 zbU{W{bkJEJ~&9;1jZ(A*@V)V=|UBg4KGLMns>c>p22+#I7MZtCyRTq zow@cIVqk<|5e#g*uM!Qv;dI$ZRXu1qy}q;gmIS|y&0)4IU7-QH@Y@Fd<0s^jE$+6z zR=EA0bNtjF`EZN|IXfgaxQB?k2OHG}`)vz4-Wb|u%w3ga`*`?ZO}pVBhDN6OVOzRj z+fpozX>2UEwsxQJB{Q?!06+6DVxoi)1B|(vkrqrBJFAgAQB(GbYm0M-f{pENBd+~x zSR3y%6Y8J4_btCUmFUTBnz`aLeFTxo`QZ13Ms!qg^Yn=I>Dq=NN=7F z%3FO4!~ED!*ssp|#i~bet8|rD#jLHn6wm=cciYqu@OYTm~17zx+RvVNhdx#1Qn>O3kp&ncxo$(W5ts`ovQhkxw4>STn~ zPW8lTxnQ6c94_ZdUpGj}Cv3zNr65SmY)tz0X}l2Ie>0uT_srfj{`{R9?ajWuz{mj{ zPy1MJ^pu5_{+tElIeGk@^00WB3}KpNe*Tc}AIr|u3vDE*0KVY6ddI|TJGs^2$KzL` zim`pR7g1Sadh?!1GPjLh`JOdm=AnL(c1xeLX$-G?yM6pZ`WyvLI7f!$ecmb+$;Io= z2HiO(zJVMazFu)h<#~atRsV{sTl{>CkWD6sPGDt)Q77zOE$;4rJGdZm&faWjSI+Qz z#rJV#DsK6^<7mHqovx}|(?6yFhw`!EHX|L4R(f-?VUdi0yYr#Uy)X1$I20}^n=V%H z?hA=$>r81En_$oc81dvq*;~$|R|+3fPwd7o6udInMI(P>^VFh2<#Jp5iyxIn#(j^= zD!5%HOvb#wlylu;ula#5qMOL)`{M`hV_mDAI*DuL(V^x~wtr$Xpq$@b)%YxI$C%Jn zp&F!Ukm`2U$2O{e2Pi`)F}n9OXjBgMaS~rU8i^X2C2dBsG6xI$d5tW{=_g|{hD2S^ zNb<9?wN1YkpG6?C8-a<5mg{V`a5#TW$#B*e8Xdpqm^_$OmuOM(35D|z%ErVtv~D8% zv4+E|R>+w6I8+CbNa`w*j$JA?lwhHK@@eTgmc3pa#M@cGe$ zI^I!a41Y3W5&XS@uGVMEZp8I~`i9T6PsUvpUjo!kE`d+_kHll>9$DnqaPOa9Vot%tUkUZ8ZW%m2pM{eZhhQ9mD zCMTRe-l|wFL%hQw~NlbR3cfw6q1~L%ne_9v-~H#C+MM zI@gXYoe429QI##Y*49c^tG`xkT5B+q602X1gFXwUj+$fnvBUS}-op}a=eB;87QgIlnOOQy_r--Le!E&&@D&Lh~r&?`Pj?;Gb zFi-aRF^LAW2BiZU6LU@%Fxb6qoC%|;^%@U%S8{fZPEY&2tE$dUIlU^$`kEVlsUJ6E zD&;aVcI?nA#wJ%A;>Itp&?s*td2^kg@4DxWj?JFy!ZKm}SIY4g*Wjy-(v5x3;rj>` zj7!*OOy{Lpa@6zu{*L&51{rKRMv1T`;_Z~D0@f3<;iPGNFNO!IV?H=2=XTzm;{GN` zNVCl-OLkW8yswADH#+~gL|?>Rfu#{lIPW+x%ddIxiQ*&%@wqI@+4W_{qx=8n-B~LR zo49Uz@CWW^o|!eP*M0k!x5O6|A2zFbG3zx@;e^S*1=yXzrluxl@%)q$ zzkGenesfStlvUaiRygG-UJ$9#$))q97$8W7fLcAL@i*1JKOFDM&Z4xNex1$yH20je z7O)?9w#`@J)37lZJ*jT=*AXQVf^CF?mN@=qAQ`6hj_${kCn_FrCxlYcM1hpb%A6N5 zqOjlX;O;NQX3NGBS$1Vm0zU@J$5JvWd?_?+Q2oB_f_b!CPHREtb5p9Ah%Zad$S*Wt z;kA=^t6e2^LC81k7^zHuN9dn@DL=dPo#klGrY(fLzcDB0OdkBg(nIS*|D_CJc><2( zIpfi^AvQ9KXU^GkPNA7#EP`)N5J87zTzV9Aflyte|!p zPUMg0SguK5o&H2^`;)0lCX>$FR$-hkku;uYGcd$+Mh&Lu&s@|9QU)0vlGBb4xi^+R z3s5hg*Yj)p?Xs*azKakWiK9L_g-sO0kla2*Ma0P{tIBgnMPLgan^3X zy_}72d@_qbINFAop@#&Cg(zrBAVOAP%8y?L(m)((Oz~Au${~~PXLIVArAJs+(W4@?TqVAqT<)fEy~@F z5MsJRyl!n=5idwf3#Y`FB-(^N`Evi(2gKnoJR%nxDYUXCrqmMQ#C$Y4)Qs|+ufO<= z`!rN6=ozhuqr}%Y^qJkB@3tMUIs0Y$YF_(C64M_J&1_FNV-9Dgge`7aHoTR8a&*0` zDlg}G-BJQ{e>Fy#VG8|D($@}2Oqk*~DI_#k=WkYu3f4u%j)Qyv;F;ExH_9`+of0Ve0t)aHmpL3_(c+BDp+P!@Z4f zV#6fS3CIC^;?ix9+n5bmVY(UAXjabp=r=$3ePl6YT`My*Y?0Y~E|J$J-bcb1v(~fm z=UJ?`%ZmT)@asStz-Q+S3>5mDI!#m8xn^*wQ!v1!n_`4!F2GL?kbFqh)u!%_KP@-f z;7Rk}Sv&qJ+Ci<7lCw;&@}|a2?yZDivcbJ9u-fD%Cv!={Y3o+MM}PiK9W+mev|W9M zUtekz<&rP_#fg#Vx~Ii;lK^R(sXT#qmGhgl?vTng`7PzyFA8o4t-o;X56|l6Fr zBjba)O)qMtt`QS2r=>`maX;oTMAK_?+K&u&$t zM`883tKIhKiAj+=tY8<=M0wWG1b5iVM#v$bR#|mMFW{}oNeM~&eDF)D+w!(iTJ2WA z*@bouE*4w&^p8Rta_r%Y-Cx0b=_Sk)7!gc<2qwPhKb=(=Hyh7u3KqT`SedXTQC&y_*MQwgJN;z>^CdkLiurdwS2(`zVHkoW zLkm&c7Twz)C?PB6y9I{I{Q^0L!;?!OrtNKU^Rd3y$lV;kNmd#%1Cq0?yYZ7`Qu(MF zwQy8~0?-pmANbzrIFM`-i1Fy_P*MgLc;an7RmCfxYl8hbeVw!=;otiqt6J*TaG zVo_CM=zz@XdzE*E*bDT@F{UgCtdQc8wLznh>-YeS^*SN+=p%eh+qT*VJtoUT^|=ss&& zt%`SS0E(e2Q?el8>*Ob%m(}c%m#+ydnx0QP%>QyVS@6(v*~HzC%JyM{cwV=9x=c)~ zWP+ktE3c8ij{~ngvzOv(<+I^_4h&gled~Ln0{G%5NVnmpw<2sTYeuP@WzSe>*tI;s zQR{jLQ4mu2!`~TrwBOby9Rgn3@!h;5PnavR=VIP@c=$-R%d7***J(8L3g1<=@i54U zV$S^@5+W%K4J9kw4)hp4YQ$IF+t=WBs#lfl?GLz%f*c0NOb+O;4K2iINcEN`|LW20 zN7vHC4;R5U^fM+!G)Ovc%)*Y_&GI8Yu`j$((yHHsv=B|@dDEQFK7EcC1J(KQCEcZJ-BjflS@mEL*P2MCZ;hE0(dEG;lFq9JQusWpUQH!wB+5>+~04~ zgT6Rn;lUJFRk{j&Jw-Sw7?=~8VxGkO{(%Is?d_8W2AKNTr>B3KFAY#Qaou+kDZTRm z_EovA$*su4MoP9e*(QMnoz~8=$@Y@Y92qg{-VEiy=BGlY#KS^OCPMxD``}9$$ou#C zgxYy|3-2&72h2+%Tg$~BZ0}vz>Dfn5JfA$Fd0O{2s=1(oU9vp!w|t?wx!iXmiuUB= zH4wZutPmMJk9)iA1`hogn$8A4C6z6DU?F=N(Uu1@hzU0`}-n8 z%TY^Ym^;-nkuQH``d@#4Ka+Zb%DVpLh4Ve0$Lw`>#Khv(p#ZFoev9ZUXNJqqqLR4* zrD9*sGNY%aTRM`OQ5~o1sXMpJbWP(aLNoO#NC2bTLCR!DP$55v+1M|C+7N8tVZX?j zOYsrcfW|1c4u;j&3F{k#pA3KibR32|x+F+%P2~4UUH`b0_at{o44Ve^J!J~}#AVvh zhy=yR_*Cz4vRG`f&F45pfB~{fDX|2Do_^(^iN#Q1yVd0LY?e*;j30?9R-96-R9}wjpQbBIza;e(q%SY5a^@Q>CuGEN#RW9qP{-a5s z_bsbU8vLlzgwtOoHWk7e#FADusVEjM6Evq^@nM8Y8G?>Ij+ zykCy;^c+V*j6Hb={5>X)SC4^Z$aC5fSdtfC1BqCP_#%&e;Y^RDi$=y4_eEXbHI4k< zUH-Vo+w{Zb2h5h9gLvFN<}W`)@Hc8c5=H?sZy>Et|qid*LTA zywU(%n9T2XHLLr}Nkna*m#ZZ!A}CZ<2lzeklw9s;)a)g_NW*0j&hox%H0Bhd=^U-g z=I_Rt?hmq;4c+(xvsqS}_}glB{6wn42@_-OCeQZt6z&r@gJ-jTBf;>y)j($a%d_Tj z;L!=tDm;0TI}+@?uEU{av09pl8K?YCZER z8bl0{=xff392_V2kO^8rF`KxF_ zp%hl??&0C5&-;2~Z%}2As)Z9*UOEL}Z@3_%G8uwqO9RIK!27g`5_QAVx@SBx0ZbrF(%fNzudawleXGgKxV?G5i_E=yUWOm_C!|tW6yx=JEQV z#G9O9*BiNAV&vH zFX1A}%G%Dh+a^>7F1L2ehf)UAhH-G!E915MFT1B|ZE5F$^^z`n^;HV6Zf3+gp(A1U z|Hb6MdM$u(_1!8k<#5%x2$sQU@g^I=!S=eecRqsCRmUl0)W8GKRC+ z*Pxvi8&5ecx1mvoj)89cxN~~-2XXtQ#Db&C{RA=s9-ddKtu0r!fmNxzO4m;;xyK`n z7x)$#wd32Rl>2ZOWcE30j{P z9A>dSb{IhN5+%rX(Rz;lCCW*ywYjJ)Z0bcV2Zqn{>BG_X8lO*`F#G#t>Q{Nk3tT6eNT`YTESfFerRozxC|6Y!*&<=&uLK zee~QUR|ixFBs7?>zgu!RINEd_5O)(3nzhw#^p%Yi^m$Se8tRo!6qHbq?%Q@s zVeLye46jlgXEH5)Q*OEDY&uZ@Cw4~@)laXSC?3R_m7c-k$CUTs$$TsM-!nCB)&;G_ z@gG%_pY^hQMD6B3u?6IRp6=;+waLsj5}TJDIh(3XPurPTrM?f?p9=Cgx;kayyj>0p z_`7G(@%o-K2$#hllr})r$_-8~yCTN%3slG_rq$GFsdrW+7-BZ|_0PPLKUJgzpOAjD zSiN+7d8n~^ii>YMX6Y~BLgVOrCwMe06#pY%RxYm1{bf&lJe9Vkzu7#fu#{?Ky{gO6 zC$w?E#?r{1ISt|PTkIjYnH5L-G)6{V`Z;jFhfl{_OC9B2sOs08WTDHRZU0zof;DO0 zUUKyu9=ff@0oUpDLZCHV+)_DkGnq{wKA5DBXX0>1vGY8g&JS3#?@ z+nwSn-*K9>trjml(Cjv0L!PiK_o@ga20oK?(0q4hrf82Z$mHeb67$wHAm&s41?nN6 zM41xhR6$^O2T2V3`xB?=a*=++$yE@VIZB48w(Jb?1=KC`?&w1fM6W>Kq@p-5jPPQn%b`(#7pO0+@2*)82>B zrUL^ZFZEB|4<`}E=}s4uSEs?YU*gNQe^Y7m=jD-D*yvu|<95%!?oK%GTGZY6Bfz5( zt)j%!{Hr*H(*I<}RP{^ASMfkarZ@7*L+u~p8ERdNt`w81l1aJp;bjLAsvr~62gAd8 z5Bjc~k*g%z+rgRh@!fNEY)5TyRl*KmR+k845DK-vnq4_Fcy9ioZ#4wU@z=LkUuk|v z->e?!1qeoi&H{wcM>H? zgFD)jG5HoSuIt4@4_~;O+8Gt_EIpkaRv5rNT0D2^a?}`e{O5{&nh;y=WkuY#sVi0886i`f3 ziQl|$fwu`KuFI3Vi4l$GAQ59dd}+nM+*r$9<+sPt(b8?IFR~Qya}aCM5o_bde}10%Kr$?-4G&n8~_ z1t;wa2&J&3=T}s)udK_Ril~Cv4x&!hof&p~STlax439K$7_TB4SLJCl-7lgxJkcz$ zvZ>kP5FI$1*M&rUkkYRrdT?zs>3K zA2&%}IkA|KEm|_^2~>G*7vjb z8GRQAEH|dty$y~vE>(^+z+L9~1p$wDcKv5`EpXUC0$3#J^cH>L+)Bd0bJ`NAZ6RU#CWVZVm?qCR%n zoSmHJsQ`x1w)0(pAX+P<&U0~q(CC)1M5p^b@dqC|_>Z#S`D1pJT=Z~F%C_C$^36E; z;HYxNM=Z7m6l4B$IOj1AEBi!!JZIJX-9va-FKpU@sh3Iorx=6f{vsA=XZ^mk0yeRq zw7vlWl}%X^Wa~ltBoKWeEY$jw#g{lyvDRCvAErB>i1~8KmE6Cd@t>U6KJI%wJMgvY zGGO&#qCX4y@7Kw@W;E*g=+yrxg%jjGj0PK9DfI?DHX$X-YJh&VHMN#*ev$L;=+Ea; zG;6SMCuskfr=93c{8OwcDc}l{zJr$3mWnrBn*uU5g9KX36`W+}uyC z?!BHQBhHAH>Az@ znlNRX@EOVMN#~mBvAI7WmWggXBMJcTmZj#1`Ibw)x;~fM!}l1c{`05Y<+q^kFAEb* z=1;5v$SDSu>qGXYFs`TZS#*K`>tQxPjrm2u30@tq_5KMOIqLu;9w-4p+ql4|78m-D zu26v{a`18{77Kp-ajrEpzWcU&V_Ba3*ENKp!z^A|0mUjjQ70Gf)J*6O4`(FqnKRZ^ zKNJe=L$`bZ_shgDr1$OtCq2cKfQSRy*(u<%Nddr(i8|=0vghn4pBrtfY9EZj%{12j zz5Cbp+imhSD6}xKEMNcUchg-gye6_69Cs={v4WX9$y;4&VP@D>ZStllVPnzmo77~PKONIrCXJU=n6ub+g2?CE(!xX5o_JV2Y?)3iaFz`S4z_RE*? zNqh)k#{(h4ZuH|rL;It^4re>}4iEhNf-?{9EE#xb%B#&Olgmq2D}Vbe-=}21Ff(+| zf^ss{c%sfOoR211|Hn=U2nepW_lAt+I#KZ6l6<^!xQiSl*0vn&MP)L1_H#t^Y0Gz* zLW?!~t~eava8_C2JjF8B67wZOMyr`~d_3Vo6KHzs8%2h42yj6wMcm=QDJN=W4``Z( zxGOb%_11#-`rb$^dT>9*JwD$tRilvFYz7-mOE&JHR;<1?o5R-Vb^wzk|54ut6Bg2l zW?Qh_^Kva8^Hcq7>aSG8T5CK+Ofo$Y2Y=95+7gBnFd~++p;_urEmQJelk2yqi1J{} zWEOn$4B;jDcT(M$AM|yU1wq*QO1>|il06FmdoadZ2wuMG;O4fR@UQ2*PlDZ0;3w*n z`w&3HrnOh8Y>oeS4&mnrD@6C#UK>DBUO7031_Z?bkP7MGU{DmiAR}lj>uFEdJ$lhG zTj-!GNltfkj=*Y|yur5&zvK^ItmrAzxLf?DrJAodlPxQ)~xzi_I z96i?zD=VY?vHE*OM~S*L9V|Aa&d&>G)>Hf1?p$xjc;-V)+em?Hf`f~pR-~Jl0}KR= zj6wOyG&s~j%cHwxH|Olkiznzn@74X>vS}q_L0Sosd!QI? zYIv`EJ><%)Qw6!f*khOyQ11Rb&Q{k%kH$eL$>8C2prjM9RuuV2A}O~ULw&e zi4;fmWaBZR4YahN#V2-WzZAE8{?uW!)#BnHsg;=5EEbyQ4lM~L1UFgJ8C+4J7>5_? zd(wNNl?dC?=)FT$>v;Z074MNTBgC7&4p)rLXimu5w0>^3Rn!$ldFU$PnI$6{$G*fQ zffdqiGKmqxbHU)4UmK+phF6;BhJnm{+gmlACIDC5(r6d6Rz7DLI^6_@%#qDZ4S@@m z4!Rn#U6gmG$uIB3plP^p>Z-4DI20VOlj)V=MeimX*NV`8{`6n#2`Ewvc(=siYq#}k zB}UA@SN19$y7b;BkM{zm20@2JvxI0b zYp;U_)}N;iDGbvKmN!=q!a~Ts;0?Z@_xlMso@riu9whcl6ueDOVYS#~4ipewichNiiu#8XsEr|CD9uU`rke#wT=~q`Fdt3IDFZX^c$h~;|g2IqS%>zNJPDV%iP`! z8#h19_$(|R8+%NhvR0KV7j%rdARQ02lK-w$Ic#4^%Q#*ocQEcbR_YxZsRR=I{prK6 zzsGrQTQki~?{y8{i)!AT6W`yzS{im+XeeZ73T|OB;N}nsgN*r}#P1#j zjgab2YHtsMkH0c36u`FxDbwRve0SyC@WtsU=e_T&`&nVhA;%8>uPivn1CpabE^%?l z$~p~glj!Z!-tw8&p-00;YYf`FU$eN}-WuDAwP3xjBzC&JT{XF^t#cFa*<8c|y6(XE z?$z>C!6#|$(`{ElpVn;`W~~R5$OneA^WzRlN$IwssUHh}hGhpjhij1>&AdtId^yM< zUjv^Qe1Csbi|XI%OR=YpLDvJ$ELcP-bnAOOC=tHFp^AehcJ^z#PoM5gE`{eX=7DyA zoLn~>o0#0Q_qSLCB1Fh2Fu~{vs&6nb{D1sN?144AJ8TVD`k@pvWgT$57SI)eKEJTw zpU$_zBMvLOI}L~p`>q!n+J1g)>r22+EiyEOWyZj0izfBgL03$JZN4NMEg@t#MPxUI zjg6x;?H}R$?A?#+nE^fj!f>d+q#luHrYAF5i9SQt1mmr2FR5w&w(_R#$RQ8&QxH!h z&bPTU8e2R84{Ln72X+{~s`0b=z5RWT^#EhbXSjOi)8|#^AItS|{>~y$-bk~82_-P* z9}1K{l&s<4U;}d!Tmo0%S^ZsE;G!Fvm+?^f2_}LxNi;|=e@9?9S5yLOuRN5ydZ(&p zPp+e0>b9;3@mI0%eB4AGl_MfZgX#3zG+Y+)qn(TTfrLN}s|Zv2N;kSEQG`|oqX*>D ztgOWZq!{x0?jJM-xa~sTyrB>wB@oiQu$p?(+Yj3v38Ps8Y5ox~kWze&@lSI{LQTCO zm0@}aT!A|kqdPUQFH))}4ZzepUc9IqZGmdTKhJ)wm>uc?^Wq8hMAm6>9GQ<}`z}~B z8nfPw+>aI(e^=dz-WW?gU-)x<4rYP5nu0=iYIG)=f3R-P;my=4B)=(xN5tgyy#wkj zOVZqPp7-lbDRxp%jKXH5CMvTwEa;IsTQGc&BK**tIMCnAZmS|6FOEW?%`f7WO7>?1 zfrftI1f1(yOnOU;b6(;#tp9=@$_}(a0ZRjh*aj2Wa>kIT?q?Z+-q~u7D$TcT+(0p& zXpWk}nG7F6N=@{{j&E17*@`nC6f$4jJJgSr!WRDlfqQS$pQN+oBkB{>1B}Oz^pwVPuQFQ#Tih!dGJcdH0c|g(`t}0a!_$bqFxV16+VjwH zF@rvXS2vqGm?)q`#QoBvFmbDqtB{&|XP&;SWq(Gn`ECLgxNhSPF3zq$Kg40?$gQ<8 zHXW4JB30V#!_;74O0>pt3T$LMeaQ5s@UeqidAnv_Ov5Sc$l?su4HlG<= zyw8&w_>puFBn-&D!}4WEB&u^pG&+ z9nI%?JMJA?PzFCC)L6lhuui_&FUSNfzDXM$A?BGsfe60;3j?M)G z=M@9WAR!}r(AR^S2d+2D&zf2zJ}?Q^ZGAj2#@c!|hhL`b=I1Q>e`6)6yEpa&v+>=& zc@l>}(XQNRCo6=E7ag>%Wtsr8^R2}uJ}PQzj<4VMa^V5WtClJNY&wr@k-rc|v^UA6uAfPJ7 zcyH6r)>)}hP`2NuzK{&4=U>Tq=U+4k;AlWA@HdwmVJbx_DF~!iKI*$f#wc$g&KKgp zbik4s?~eHa{~ZfSW&gz&-f6Rk^jW@&<0ETZ;btPnq$j263waL6%Y%HA@`u^hJZ0oT zFWJhv2Jy;G^v@U};sMGbEc3jpw^uHqK1Kv2d!*mo6oDR*?G2ZBp@{~j1hlT_F#*j} z7r=+kn%IU$V>)3H@zz!E%5O`}l2UQ->48`gHNsUbRTr4$^7G4fTwd%4_(M<{x$T*i zrgdv#@0#4WKC2YKUF;`pC})Hls4xsnfzF8I+&mb1#LPbzkzqf2%3$YJZi^1*?43TqVr7RIJIK7)5Z;D(oqB(w;3 z-M7{f^~47KKN~*-qHlc|rZoN%n0j9ld1XS?J@{xuLI-Smng2J|fGR+}@i-IELjGt1 z&u8h*^?kotl$XZ8zD=+0ZNdxH!ui+& z@!-5k65f_ZJX~U=sLq+q^FmWH=?D584*SGxyrLW zoK^FR7QQ3_1mT+_%Xz33-tWe$3=~pebEM_yfX!{12BKuuj0=sV!DfOYtR0FMY; zppvp%`Z%4E^z3o;h_R2a+~hxB3mUx8vo+1!eYn%v`9Q})T=!94qlt^u{_S#Gy26+4 zrN7S;_OmEioF3XJE2?X&$9o5>HD=oZ$}pI!>fPsGe|~4hrPcZIQlgHAy*Pfa+|H|_NpyG1q@WEnkeKjcpdc08ci`8&9JYe z81`Q-J%*<8VbIemR2SAKGIA`CVXvQ{?w!~)F}!t`>auT(o>8h#)TwFM?ThGfJo(MR zJjabsHf#V@9jictEM((<-peRG!eH#~YRAhIsl<(VxPe_RyFu=ELF`$J26Sf%1RS=w z!XnKj!tx)4^;uch=~iCY!`iCz_O@C^0B99R8vxQ?+1v~U9x`+b)C=?n6kho1?j}Aj z;f{C)!{;F1W_D=6AgM9`T;hp}N*`-jWa3wu>bK(Z;b!(eXK{O{`*pz-C=}+EAXW7K z8iharJ2W(Q|4kXB+5#@q$7H6?@#t=b<4TANr*|l+1dpB`CH#3_+d<=iPi&{h0&~+# zsL)RN1C>d|$fX-a+8BH$F&!%^P7~|6&7W7>-GFs z{fS|yAssMH?e#^H7?5Xf2aNhgc{%0`jEY)>%^^54-^sI?X+xy<0y-bd!K?) zhf<;ZlX`b_%Te)UK0Da!v&sVx=psX{pFgg0j)pd~BRS{6#CuO#Dsu_WPNJpDSA!8x zhpz#3@x@KHx0V?9W%W_64SEICg{iis;&kDBbgqwAR#uUp*n)IXQf5IE=6zZ#I+uYj zIRttO!PF)b$O>9l3F6Se(4hW4XhPpD)`Y`x`lMdc( zyC_n>GL5=kYqa&owN;r{Eqo0)TYUwlsq;@#dC@)okb?Q7(5TuA%YU224Bf0=Mvxu^ zsIinxj4Q{OAwP49sFi6*dcZJmxX7=iUofPfK0*_JAZIS)`zF(xz^Tvqq>96(t5^&F zM?b(Cm4+b@TsP(y64bRa+o-nLm)O(sh6qiQwFO;DXD|02IMyBqfnF@&`n?*-zes#W zo&C*}RTld|@afuJzK)YRUTiYr-@mek=#an55B`{9H3zBvyI=^M$0j$k7gJ2joBQ8Z zKH3>GJSeUeAbvaBMa3Krez$fF@jp8w=EourNkDPpce&uM(HWp^giy?s(}IFOw7{gp zYi|Rvtdp8jekW+C#TD?F_3;Zet$-XvPMjYOQ*?=QgXO}i1v$iU9s;1=U?5O@kZOw& zzypU3XqJM#?QDG%rSdfYfR6Q}sW)xa!Eev_y`NdCD)_y-`75h-J|YTd;4?P&Z-n++ zB{XS5Rm|_Qi6(k?rdG04k1dG1aym3Ic#s0d{JAV}9I5W%v6VB#uZPY|Ms`>CK9)f< zoX-MSS-d*>mISp)oaAJVu7A@z3h>CaDwS$xy^FcuniE)HH2o&8yyFF~O{WM;$nOPh zhG`z)X)^27^ftm#XEXAg4?a(zkTbn8YF=7r0__XhU~>UaX2rX5=F5Fl+Xc(T<41M& zI>{8cRG}qw`sslzMNDyV$tV_l1*)Vj$IjSbVV!+{*JK-0)%RM6YSHI-_8-F*TLH-Z zm#G`6qoF-wkDG!&m0b4KeHU*fhB#c0fP*zvBFcp4#<)pBci}11dfyR#$Z_3XsY#59 zrBV7nNu3Pj_|N<>K|ut+QrM7!G3%E8-PuB&N9Ra0A=VAPGR=Fy*XOM!opN^%r6?sv z!7vR4U)|r}Bf!#@1#WFn$jh&Gujnl&c{f_zwV@XGblNu(RzKiI|MihpPa15r-tQ>P6qBx6;6n_XAW*mNK7bo#_2fS0K4hYbI4@(>K@fPzmIh1rvHKQguvjQX)m#_jS&Q%&^x=uTv&;8&qJ<=edc97bg5D=9b1<-j`n&PO| z0T##|cg1PQ6KjY#0C+hQQ3BYnrR+LXj4_2Ztw)P_gl_bJBpRe(nDw6fwH_m~yX4pY zH~0O|GFOGeS{|#MsN!zbXgJ^R_Puce5~kcu-t#e63Kv)F{*N*kY1deDzYabcy8HR< zt>X5Zqq*P5{K+1@X5PgWyacWzMl*ABntg6IRJuu|&344p0<3U%f*6wyVjf2nfTP2v zD-P?mwp8BTM=(!5+S&54Hbk|7lM@8R0C{?j`d{MMx((W|t=$E-XvWu6zgCY)h@SWu zh5l)#BP>dRGL;ZLa0!1b-e>+0!i@N4`vAGmFkXg-$9;wM4uDw?`5L}fWu6{ikZ0i= zteSqIq%>j6bxAwHy^(UxnE%$Eax*^scd);0U^vA<#fP?|n-9|g9TjNo9RaI14P|AU z0`m)ze@KG=h>p0-XVpy@ow*Z5+Oyn<8@}|uJEHtS z=|?a-FMFvfvuYUbqVAXu@MoP*%tb#xeRlyDhcriEQUTlKJ0dL+{zP=ej(7y zAT)yFC^Xr6J{zVZeI|rP%jRN0B}|2umDP?MptR>N6W$6gd;V2AX0DwZOUZbUk~ z_al3snM-c=O+TX?VKLX$Rrm16^s#dlzgac4rbeMDEVn@Q_LX7IYlWKe?BxCBy-SRek@9SqLS?kjfr=e`024jKxSM06Hg#c_Dcu%$h&A@0Q!RwXnwn z6@~l#kdBrX$&X7Tf37KgTx=1XPYf8735f_yZiy3CM>{Jy#R7kQn(-myROJMNMbF;* zv!s6yC&7wyZ~W|x{bM%@TL|snrbn4Z0dM#lFBFpn0G>JR&*3$PM#-d?v296Tr{-GT68{b{WIOBvb?;C)FIdtd zRwA7lNk#^5qSEhCpU2AY*!3_3W6ny{A>#H1tOugV{!&x{l56=IpEebAJ74xlK1&JY z)C{o!@`t|*1g;$WZ0`JzCRB>33k$ky zb|6!@vZlt~r5<8nceHV=A{AZe46aD14@p4mC`Hgm(HG9v&S~?+#HrabyZ2lB+yuU# zgTH>Md|5P~Z=Pq=m3385w8x~iRAPnN%<)zj4Lxe|nA-B=k@suM17?y2HI)LDjwhirlZd9W()y^M#V$=)4uXmk_!%QthvUJb=3eY1D-#nArExnlI;w<+)N?=>Ik3Nrv?OgUJ?Mi$ts%V<#tJ*Qu2M=>^D<24uSu zHxnuWwKiQ*|0>Q>9gkWoeSHC5PhOPOoq*@(Knfcc8DaS7=u`L*L`o*6>cRb?$U(|D z+1PkW9Omh4s7%Pgsm0qk9L% zR!{)=aG(KQ57xt1KP-MNE-nZ_-u>csXxlZVhA@!KW8S0i=mE9NzpyvfIaxTHd}3}=y7V7I$d2DTv(ef-0J96e}FUBA$IOC zL(DA+kU~b|j&^aT-lu2!Fw4f*r(Se0H{s1?0>L2nV^)lZwDpij;G;fD>=g2&iJIEf z8-Jiw_(JJUP%E#jj6p>fvi4ew{pZgYv7eH4HZKqn5mSZlNx7>W^pvoy%g@%)^hDfH zNpEUiexUmWfslr=+MW@$Yql~F?eGPB$*nl52G)oM8wJ2Zv1#^7F)|Un=EP4saXl;J z!>-=b3@24Rj~xhj#^T@G8|eOU4{TTJKOOTLz3uVrBO;r*^eRUItOo za3cfyOBSbeP-pmQ_jh-SM0=4s0GIdrqGHPCiO`390x@?gU;&McjROGe6(CAh+j|<; z@5;1KWnXapD}x3Fa(m6h?qp&---ARTqSO4Jdn>)NfCX*`OT4qdezM>UZ%v4ur1#mu z7$#vFAu>9;^k@!+lvFSkU!75S+2)XLIEndUET+J315t^E0s8vuJ!bGs2!u0DalJQG zeWI&ItTFXhCDtpOU$`yyi$oq7a^{a`ZITUqdTwSAwE*aG*}+ne0B6SZ$~X=|!KSY{ z)u<4P>ps)1?d|sOSwDK?rbH@VA6Hn}e#BS7hCq~pQ>ledVW2vjh6hVPkP46q)n}PejK0c$Zetue7TI%l#rQAl2R@>6J5X$Xr{pnR8zIRoZ|NKWm z2}XB_lvM5_;7LM;ApgJ*tKY(>l99~S9?Bq1j1TB*I7S|>M=+fAb9(KL+fG;)8=nHL zc6oSsw2hBr1FX20>&3svrE&=~1YxA55z6tIjp84R@S(U+wMiBA1R42Nv;D7jiB8$j z&XiB|9XW$SM+sLe#gds!$>c)rkva0RcG*>u6_nS$X1!`%7c&RfiA1CuArQ3OV9UZk5Ft1jt=(A(RWnG1BHah@CnqOI7E4XZo&P}Sv(m{k z=5(tj65qkam*I~(C$!Mr=ut8l|BqVE){#-kjzRQNGO`%O<@JiH@SJ$YY|u;q&{(?x zS{vXgU~msrhXZ?XY&uA^pxpFaYnbNWO5?2m34yx2JyimYR8nHX1Gb7`@apye`37C(6vr{Bs4?4^j6MN(ysiCf zZD`!%?qN-_e)a;0o7_A0*LYIq2oa=+ahkF!!)-qX+UwnSo-OGL5z=h}d?Vn|x^j?0 ze2cPru~glT&}?*FdSj_QdM%^$i@=ofNLar8hU z_`unGldw9M4c1cb)I}G?Wng@~9NBYGY7PLbse7H8yr@CWBt#^k(mO?av`_+agC2s_oF#wccW@41b0Jp4y`vl)f(abaBH=#B3pw|$&v3_rZd9I41VR*F6`7n9XdaKJ71tpG zpg$G9-t7+&p@L4Ze4=;ixsXTOS6F4jY7ivMh6#6h_-5BB&su~CJQtFth?u4rjH}%6 zGS^87eO~+tX=TS(>$9*9cc^y%_7*9PhM_MQ9YGEoQtyew&i-nShJn4}(}%}br*e~P z^fTP=Sq}w{v1$`Q2t*^{fBJSa-_g}R(yb>soD@6m*X-Ix)B&{~``J0zn-^1qTGqh` zQM}=#(nDvr0u|;8#@@FcZ4E(1+cel+3Z&H3+#dV2*2w?R#Tc1*II*o_$nm+ueKOzR z(?M_FK7cEPffV&wd5~SbSTG8$8T~OJaWw0MC@M6(GCk}Er95|3KfNuHsvU216W7#i zw<*E}Wx)0Q@JU(@yK(sPhr>&t&A?|$kuRC8XP>R*xuxaTVTuAM+Ey*G81PhrGexhq^OjBobq0(k8@BSQY=($J%!Dy9}V0pw-NjlsSJbvX?# zYLy+7r}#eTve^qMq^Z1C)NL# zqbY5N+Nq+9j~@{PFSq^c1U*AZpTuc;Iqd7se78axCTj@-;J~4z7)9-~G!7&Y%TbD+ zL?mcBIi;1wGn7-T0Re6IcOUoDxB}h|{m&xt9=DD<{uH|tBS6+>Tkg!*VH9nmpzf&< z?ze0J&;oAjhj}Y}ya8S@{qQK3=yok@IuomLMP zEykm8WA%B4nS_Yv)_x+W!4`u576?}1^ZRneHonfNA*qbz?QH2vjV@kXCML6i-b~pW z%%cP`?!h>XpUKY=LnFXr3fio_2&Bar&eJg01S-?m+^8& z1Z37Bz%*A%X3OuG%ozgh{!in>|9e$HmcwMgcep|Uy>{-hR^Oxdtt~(|zwG=Y+z~S}O~JqREHXEL%VduH zm)C_!NZumo-C}L$_ui*PdcCklPa5&4n^?S96Ql-AWd2FIPB1l8W0j6?FhC_;!)-X9QY z}ua&F!As8N(e zPvYWIK{D6JlF5{zCvbXOGfs}jIzt#WbYA?mF$pF%HEr@_ue8i zvO?J-$tq-%y?^J~`}6(zqenw8uh;#&?{ltmo$Edqy~#RvP)z_DA>ZiJEGgVX4V8sQ z>vcVG`B(|JpWAdMm7AKejmEZ%mOtI(J)X=e2pgETsaCrd4qiAT>19`S}^gPr@p@4 zwBg6;Bnl+gKKtDcaz!e4I6+s zvT+bxWQge8l95osMY&DOd`Q+zVSI|IY959VF8f^deKU zz4mUTs0z`!u}JBQ1L{2B5X$lnjW7#TFGjaG`qjN`ON6U=yMEttBL4kRo{jM9b0X>95XEvcaLD*N|QHKiCDs%;RjI^Aoc` zS%^5i$+$4TSV~uyoR^o^)Y9^rfq{X5pkSuCY{UX%(KB$Va99~;1XY3rQ*2vL59avz zxYbDBb)W!nB_$;*C3ExxI^hY+aa8?Y`QJNU@4(B{4(`QcWf`Wf)@PMB1HhL2p|7&i zA3v5MCmtqeqXtW59hJk}S+wu|5sv^wT(l6YD%OUGP(cm>Grv_ic3?Pr z{6`;{Q0;f5nj(;ya9Fx>vbREi^l|KX7JTUxy;NcFa+@2NEfl+))!F~_15@_lm*s{Z z)vbSkYf$m|)4lEO0+;n1J%bN+1ZM``;F!U-^*%MVG&q+{NTWf3V z0vC;2Eyd%%bP|!VzRK_T5buFX)3&R3Oj;;uy!Qx@VfJaFFX;eKuHPsm{V$XH0gf&V zOp~Hv5?V3~R4ayRhnAj8x*`mVFl+c{t1r#@$-d;nhYt&X)WDlj*n&aIfnZfKUs^X) zH0)Tg^buTcVKnvCWF;ou7R#>`CHl1rIRypxaPaWDGQ{6F{OY&CO9?zC2~?90pH3 zwhdK&utZ>n!Rm!Whm*Coi5buSV@tBYN^fvvL{dpfDR=8dju8wz-htPEN-Z975+D;< zr;S%Y77sCofUls?&^MaBj#o4V|4VsK99KE$YAXgcRArMt^hD*i>)L2CWj4i;Zgl!5!{Mc9V7e3n+0pZ7*rF&BU!VHQ+-Bd;oy@dC$9Z{I z;JV|h$D-bql0)^j`Sz%U86I3ZllRGlDRzuh1cUDe2S(GXe(qXY;m#lhKG!yx8u&B*6Ke6S}0x^PFL68x4-p%;Oe4MI5_U+(Vo z93C#6jHG4@$cD^d96KB$bCOHyUz^{Ce&>iG>!}v+?&(QKa~yQvJq)k;$ES}kesa7^ zIOWABdoeAZSMpmTTGMf7{!7n5Vs_vA(oQ_-UtVr0ZRhN5x}jf_?meS`#btJr8{-sP zzR8)N(w^M$88SX=!ey+NpN5TfEZp7b3iF%z{{7Rp)K3eYN^zR8iCq4{UJyv5=`yEo zgTvXIYu6FHcn&U{$$ObiTY@HX0EN09WnxVUVOs6KcMK74dCGC2)d zhaxjuK{gM3B59TXg{2|}K|#Is8#ZX)tNG9_jV6b#H!8{LI|x?SYBy9iV6!tamiWrQpK^({Q#I ztuR0i5+S{S06Dx!PhX!TjJO{HBh;pYDO;`8K}97cWQ0EfDQUp(-%pa@sZ32#a2R}$ z0+XokdIjR}pFoCj&A7?^HTWBX*>PJ(2b!Ckn}eI1OrzVz?P$3UJR+x$l=##lpTN#; zXQ314_wV1IdV8^9`o2^owJ1zPe`6EQ{NMr2>({SC+@W&<7OSWj7#MpiBN#F=GGi2x zd1G&F`2+=T>XaKxgGV-!j^R=rY`$!;$+UTiuROC{q+zkO`{m1*dZ$HfFvN{YO2Q-} zBI2`~ykXSfBF@e~{<9Cvvw^O4INUUXvg7mQBzdVpoeVgam|ALko_8G`xq~ep9XRoV zKSD)ir8s=P`So=}`b`afDkRivGJ*qxpPDFY&QkB-^vA-<`5=0l`V}g}$?<4Op@W+Y zq=E~bnthA8E2D){!NDJS5Y+T^#0RsPBK(T}v?FCam0z{|Ol}1Al~*(SGFf#Wg{LSQ zwauU8IC2@I(0DzXbaOz_^{Unf=@TiqwJ??$G`aJTav7IcL4tV1?e|bCARwUU8{Cre z0I#k#nx!HY4)?7YQ7_P+3cT2)1hd;KGV~UF*_2`u+P*2w7%*2^^T% z*ldosP*G9qKYn}+<{R*Yw2vpJ=)g<__6)Kyi2L^T_8k5U(uTp=uCk&6q)GHUL$Wk&ot?S;zw`_Y5ZjA~ZJL^3 zi)vwi83M%qH9X1!D;>9YgRlY3zgJl>maYA$E6<<;+eBH}ZfvUAA3qvLpBOtiRjJF) z!*<|#v1yq53^Ea7b#VqB1-Ucq#+7w--Dk(U5Yn+uuZ|Xk%abv;`H<5zl*Q{AG6MpcmkkI;YZ;q#s1!2 z2e?)cZ-5~QpsMVCZxFm8j*FCnPB|S}dmB@=pUF(T)N-eo-!%=yFM=OqMRhg1tM|@; z^Fl{37U_h5`Vvi4CgD6+)xh7#BP55pFyuqdi>t8=nygC=`?W&yS5egTXc?L0 zOI)5Ig%eVF0qO80M(S4ceu6`9>F2;JL_|9anG|aP1QG9C7;)+wKXnt_t|Q@0A|Ban z%x<7}8OoHz0IRIl{)mC~bvwjr1u03uC?_uOc+e6!I&uMr+i4;mS-N@U<&h@7=UT-v z47tYu)wtpLiZ9=Mw4HMSk4a(u=;Zuxb_iLQ-LLm^-Kejkr-mUuJ)j%g{_(su{#K|V zXSW|Z4!75lLyG9j52JXx85!AU;KT!tg~b`>iEPVIx?BBh;71nFJ_Zd1(o+Cf>kva2 zkT5kh<(Ja^11QdFqKpbL)v}2}VT50SN5#kc z!#}`=M~8R8wr^|_I~HfVmuTW64vE`w?$c|+ScZpfTdntJ+)*JLm5*-mDgRvVcrZlG;I;v(ukR&xcS1@EE_gKFF|4l`9T2>Gm+00# zyHD?*w-mZRT!fMi4tp0|z*U5<9QyL70<~-yM39Evt(EwXz0*pFy{tM5uhG>qYJyLnXnwL^rZXD((7nGP{H?4;=QjOkid9+&W@afeJ+ldY4$dM8WcJ|QdPxQ zQBeWEs#}zllxSQj!xBR|=I07FItX_EVE0|!QUrkYqbV7- zc*IQ$SmlYi)zu;wyN`wuTrEdeAAq4sa(CYF`QC`C`*P}wD40*9Yj0}$3Z7jin8sOs zuVUQW-;X~C4-4x6PFZoIM7wTzAl)3GumTpLv$HcIP7(FodkAqdK93a_3#$z_lNPmd zPLWZg+hf3AAq0x$(0R-J&+DUkm><^Ta4S4Uaf{toBe6!ke1@Hv{t0OuJDdYQ0C4Vwy6s+@`D7iY(qSXgR; zWeoxUu@Ma^ELZ}hA=B&a`3gCkJW<{@=AqiE`*5rW>uHU*1Ma4S=S%HPp+GUEwD z-P1Zr8_neZ7KO%JbJBi>aF4~%QxpAp38H67=@>;8+ z)DL{Zz!b-@)yJr!392~1Uu3B&ISjC_7>~HMdOL!N=9iZP_x4}+CXB}Sj378T7!wy4!7MvRJLYfw{U5_e^V1xxrT9NB zfZ#azyy%n|HEJ&oWZer132BFuj(l?`FBIioUF1#5qA}CK^9}&zkeUn zA|6=7T|t3#C|z;>(Rmr^kjV|ZZp~03)-e!P9U%ZrH@M;ej;r_FXM@k2H^~XuCM_*( zdw-vUCjs2?z$epqXnbO#TgSxPAGR~R$9X7>JHh%1fk%cPousX?v$Tq}$0mjRz+C6i zG(MdD+q%oYe$m&P0OZSQ?>+>MlrsCz-UCSFL?xlHywI;BUW42R1v;yMF(?SPp`M}_ z6{P~xvwA3nsYN~C0-#O-8!0%BWOg)w=pgTFf(ZQRcdY6S8k%ye!}ae(0J8j*n4qvm zDKl;k0V`NKF)?cJawKv|k&%`C1!h7z26vcM(>gGu^C!?uZEZtgd(Q)pf(gdJ=ck9! z0KLG-HJ4yCUo{=BLx+x%MivK$`{NNTW;STT~kV+9#QJfsFio3>3h`8poo19_bod0M*eh@yxrz)Iuu%oIrX= z@GJ?LUUqhJ;szCLu9_LR)^!84gAWu5n~b&P(r&UseEX5CjLbEV^yWCJFMwg627@+S zq1^d;e|B!?S9j01Z!%!7q>?5QJYH&mbMU?5F)HGo2kRw$rc-9v2C|Uo)YR~~In&%i z^lA|IoO5a?R{pap(u-(v6Ftx7tZb7HYN5)vQWWaFZEYy38WnxO6P;ijSDqKz%bBE7 zTzAYOKwiW7;w8k*B3ia00^=668L#TOOO)I3S7jqmND5fRwRHC62Nrgh-zO)xjgNom z-5RQREQ#{SGe+OUq_w^KJ`YbD1o3zo9>C$I)Af#sB{>*w1wc99*#Kc+ZhyjrYsVc7 z9XS^kuzgLS*ro#a=0~1aNm0Q0F9LR$IoLOmKk#WC1WJr~faCE~FCZc*q&`{wyISZ4*#3w&sR;=IkbbdcD89nL0icxBJVSKoqBCS8sgHopn_FDWm1|gBTtw>JsHVs8|2f!OJ#KP|kDg_W~wnUF>xQy)`WJ3dVnuf zYwsaFoY*#=5U~}GXt`dI3&^Fci$?{tlLxEymPOkA#LXPZg6|Xj6)5#zgC!nfb%+AF$`AJRE#R40?tjp^ z3{xO>cAZKCM)vW{_M^n0;M9$<(m4_+0Z1(m#Q|V@X(w z-vE97f?dr03wh4-VEdx%1Wt5lZrQ!`xMI{0M20_x4QS0ZSwmD$U!N^}yB-jF@Q<11 zmt@SUq~p?6m6fdg^6GJojg6*z%ErdjEf*)YTJ7a=u;2@Tvb0XNe1>dGuWktgCIH_# z_EPW?Ziib@ad|F&N!zt><~8LzCqu55$>g;m4rYI>Pjg zFqpOyFC^W|-WkgJz~e7k>)GGXVYkjp4n=mAix7W*fAv5JnwLgPVmT#Nl@3rGApaqW zfmHzv!mQb{SCht>?%YutoZpzAS2K&rDS+>$fnr#*hMta2K`Bambn|B;3DxI^ZQciv zbQfoy!cS0aW4WF&M^SjaqeTX)FZ9%(P{%ROG=_kU-i?;?1B3Wk$&o|B$^xhKfp6cs z;5?(PH8(XWD8&$uHMrVRKJYQzK3xD}3OPZVA<8;BWHU1}xlBG3{5EgvW;_+GkHO6@ zK88UW-ieZfFT`OT1_QaE|I)bOXmerRW_rX!OQ(4vk>R$=C~}+2v&9_2+Q(AzL%(~5 zw<`rG52+Ao-*}>CPU>oXrsQiKRV%lZs}()m@!61uEWXiP^a5l=Qw<^8$YC!!I{O3V zBzxWNW;~?8EU+~TIhg+(I3||gnw0jyHv%kBv1OKsx2(L6wli5q=7TH%hclAeag`l; z)I!ygE4Zpy4JD8GODL8Ueh`-rWh=~Yz=1ahtRvvKfJQCm6$I5+0Wm%a!v9rQ-$h_9 zd?AzoY-6^KAK-{5-stX4q+HN1cohY}8!8^9z$|BX6<)hpFky z4T57v>v2UIbdNf*!g*;|3XUHH$u-`b7?juq;hqJPtT9i_yNpol2XKstXcdYoWx}s+ z{zScohlWRUt=9uP+6qd~C^?2j`=_AMd-?LEv@k@i!e7|0hBY-~nUvK9Nxi+jacRU1 zhrWS#F5K18nrY2z^g8CH7G-NnH_+E#fKWkx-#*2(5kg6vZjbh@>y!c&)6ak-K}$D) zj{?SqS$|)G=JX~W9$v_Y*4EbHg46|9_dJzUeS2BEX3zZ!hk1!G3Vv)j3R?q-FGMRt8~1UG!-l_)xA*lymKf>BhZ(e=AQZ*$>Jm zY{Itq_>>exA;~@k)Q*MNcjJ`WTK*ZYUFEi_DQ*gdb=#Vwtq*@?YMSVx<>FR3;&X&H zoz2u1#eC=6(ZydvnZ6j2!&>BSbORtp8?j|B>q%-hUuS-Y-B?k)!hTAK$=1rs%HpQR ze;QOR?FnGto8H_WI5iO$mKOsYyKqfPKQk|!1-dY8-SgB(B2G4iUkFefcs2r$!&}`-8N+PTi%+vRS?yFFE8t?v}S4KXlg=QMHmn8_e1!4h4c|9-O&AKip^ld#9!Qm*jAQ6 zu3!eH<-?eM05Nc;ItK`}z>ijKM+mOxTCdhGP<;jB>>-qg^KkJDPz|=smFN@sTy=4^ zr7CD~nZoP(ovIGCPrNg;w=dJ|Lo%4vOp_ou06KyhZSFg@cMglaB)L-zMLyvEvQ^LN z6Fw$oW}NNx(J(4y7+PP&#l^j+hd|9uKP&nr#(Yg{YxnYOH!?%i^wTTsW>q-pL%0cr6$tqzVF%ukp_-Ov;8lo}SMCM<5) z-Hko*pAD6ev0?JuM>nN)O}i?Er$|8sACw%d!b?g@<^Y92Ua!^9^De?EGinS#$05xC zj)VK&J;Y!Zxh)CB_B^mYpOayNh*FGZK6J1U`_9p5C$K_CuE!<791dn?<{CgD>D~v) z>dfw1#1CF*HAnPL<$oAexv@sUad8Zq(RKOall`?s16wHrU*956AJWLN;o+*@t=wLZ zXJ%&V^M`PQv~XKYQ|MpIc^IJ}fQni8H8Eid;`YAT%!Ed7J~XboILqhp4G#jP5+$_@ zZH6_lm)A=F&b!`$QZPpZQw8HbGDb0SEy?+g0 z--|+3GAQ^atc>h>o47!_*V585cEf02V?TI(Rj3?zf=a04fmR~5x3{-&3xFpFwF99!<^;*6zJ-^nxl>kOvpeqb>g{oU{j*(GeHvLU0G}3R6XUb# zMbpc>fB&NGYvNwN&K@6D(C_gzC-A7ox&IDwU1#arBH4}Nuf}hCZ!FU2)MvcGjmhKB zzD+e|PjHw`QcguhHRicK*KbfC?@0h{em@F&?FKgoZkASKDFgGdWnm_|BI}SB)KF{V zL-;Bm=3(dM*Hs2&{s3voj_!ALbqP4kp&(iE4@*MdViK|yd_dvi>be7XN!z)`|IVE|6-fWrxS0Zq+fJzW z93d7=H@~dwu>J&*p~7`d8(g;M0kLUOe9>w8+{}xf6{DGF= zQuJO*N(%3U&Y^c16KuBEnVFe%mC?ZJH8nM1GxP9y7{@OC%l+}%dn+$uJ*Q4XP14xA z!!L0-4NapkR-)>Mq4!J6%Z`a9I51~(Pi|D;B4`%p=cFfhShWPWd9!<`K(7d}7%j^$ zQa|1^f)vN%(Pz)|joyODGv0>_=JjP9)sO*a3s>Z3TR_+(>NF)`yoZHu?HMa%ZC zX?5@FWfaYxJ>#&_*}FUN^{cd{rDgJuAlLL_R=EB{K%}8t%)`nmzv9fLYVpmMkOom@ zW+@1}t&^)e#cs=<88__*2TsmgDb0QFmQ!Up<7K@`i4k0R@IWiSl&;!u`{^)Oef&~r z{&xbiK-3IVhA*$Kpt9|wpJ-1>BSp(`WPm9svEh=Gk!4IyusC}S&!&33L-1P|vLfdF zie;l*OS)DuTP7TBIZ97Ccz!a$`#qu`FZ)B>B2@lV)KQ|2HhQDdk) zJ3HI{{e=j~*hdx0c6N6VZ}MF4P}03pxze}w0vkSZe-PI9(W9uWXLfeDCMG7}Rel4A z3od^7t1J`F1!ZQNi`Ih~SCBi%NDT-NR={BeLs%hKMTCRuAL?d8``0~c%@87~o^GhORF2|Wpk-gLh@rs?I5oQU0qqo>-#9?Jaq zvi~~3zk6#NO`q5pUi0H3UOBUk!?Ip}vU4>{;mel+8LK5xk>2_@hQxUMTqpWU*M>s| zIL;JgjEhY5OBaCb9~!U60ZBm?B=K=_+Wp=h6q(3t)M98tZfHIiA2XCSQITdAga;jw zXY8?G9KaTQZ~eQ*qB*pzXrLb@0Y>tJC3<&jY{syG$Qse?;g2aR;{+%V^To*8G z(Ak$!KtOk}EMg@MBrpguDB^W=186i|Xt${IX0kx@3t~}kQbokOP1>$o!M|Lwr0u(y%#R$gR*n7^R@MzV^RI zm~AP-lgs)a(48G%`4TuPnzv3>AOp{^>vPz9xQ2C`+H$&tCpdaxFBjdH4+Q-LDIUcc zALOPwoetRMOj%O4CKM(};eKO>(vQWXqGL5+_}_q9RWB%&&wQ%J4=%MZFry}Nh2Fvs zE-Q&>SY?944{^S&Dnvvy6_hvdCe2rdbAehCX>i-Xe*XNqYoH!GV)<_3y&rF?2cEyM znKcWKcWm#1cYRw8A8_-K9A5RF2KxKAjf@cCka2cE#Et-ffN*jl`@jMR!lhV*-~!ut z48RlW$CIenaBtKQ5fa9I;JHiWLlzVfp*@wyfbcSccv@pQr_%23^%Q)cAwi~TV%!%DT#a( z+~g}dc8>}_ntmEI;2kj7-{_vS64|(-GncrI+WLg1#QTiX^4bd>rSw|bRd33OQ&*;~gdF=96s(WEEla?_74^yYgE(lWmfb#-;aBYn9D z*Vf+NPW%jxL(@*zEt~N2d&wXI3c#n~)IHdqmxNIQaydaApv2kPY}~?5CKHhy5Yp`O)c-2Pu^@@K``0>TK>$9pGrBBtb`u9HQ_#@A6 z^X+oNO`RL*L~rhV{5w*QCCJkgReT^TL`1K-u{ndjG{9wNpm#+!@@hlM_qsB6v7ZV+ z6co6M11pK9D!dF_X!~2Nde`DTeHD~BXm&tf7CYfqGsxe^&h<;J36H}A>}eFG{9e$%_*g%3RI z>YW#$8Ja3Pk_!fMSmn|C?0V?;oB0f#HdBzan!F7Nu=(w+IaFn#DE@M5rg?D_PMF{Q zSuc%3(|SWrt~y;eEoJCR4bHT93q#J)+4M0sHtzYtdgdeYq~}Jibt#(-JS(foip(sk zTem`i%aLS?jsG|cXZIh$o8W!${V8L_I*ZQ?Fhni=ryzMp1M-DO)yIwHsQ4VZbLB8A{4R)9alIa9_|c%QOXZx#B)5j(v#DunhVRGqsRs zK;$?gmy+Z2pR%cExAv|Yp~E_Xu_Y;9`9H+3)0lq~&@Q8#3Ny8YrnWpfwh5ygL)62g zZXM4wCtf;HE@_^tzaQs4ptd~u1rNUyGwQNy>yz)V7js@QHt6L0E^PN{o_pctduCIx z2;Ou*cb(Ic4b{}=uF8>P#u_sM?fT%vgia0I#Nx5&C5G<&6(|hq-8S@VyIp{86@RJ< zAPH&NLDQR#Nya^0Sx)X#kybH6Pm9aS0;5v_yjXZ=Jye@6e+I=lF2kvWwap!;e*7>8 z4nUy~nzly8d0K^Rzy;-+9YC?hWoT%KD3)kBIFu_mLB*qyr=+IP^0Be;^XJc!D@TwV zi9{-WfD3@O>n-^IS_&dClKL0Y=!W1F6N|I<2b4ItAd^uOIyl<-g-$hug@r{9ih0l( z=KVqW3PdaD1Gvq*a6vdC4q8_zk2m%`LR7Axqg);j_#zMZ7brs!=1yH*UE#aNIYQ`& zpCWQ2U_2DVknRv7{}=)SLp@eWEBTuO3G7e5Zzt2!hV_k&iS8z-*fBytDrtERpFg-f zR*g63;pJ@yBJnn~K6#9rJxQSJ-j4J>@|JfG4+9$;g~d+S@3uKX6CxLFkR8!LrKYB4 zrKYEs*XM!s_;z9+q6dwNy5a8O(FV-@;npk$ia25Zoz4MSNKRfrz}LI15PnM&WtU5_ z`b(iTHdSjolp{|heF|Xf&rGv0Q0}Zp{V+VO!g*QcA8d){dbNZ^7NA?vHF6i1mdv1y zktF8bpuX`Q#8Gz8p@n56NMSxXIXMD^Be(JtEp?1(~*<7z2cCa(xgNwQL$Vw4=N zvH#j?WB`fyMv`N7+;7ZR>Lc{h5j(9?!FRZ*$uyO`h-d3WNQK&&qe@+IE(Y%o@w|y1 z#VrjJ{`_UK)-*MZN;crp*Z6e&uv-{X(j=S)9|>9RE#Dh6g24kw*ZASXS7yl&@3TJ0 zLMsr2%DFb-U%r38d3w0j9mlFcta=7G+YB(5ZnfogXbs`n+S>L!;T7@RlPkPY{qduq z4^+9i(Zs97L_`{9%a+P~kK56ZP7Lgu5DO4mC5d?O0?aKsbMbt}V>^BaAxxk@A)vJc zE*>aBXuM2ut;mK!gJrIvkFuhW|I| z*@eZ$5ko{`6a6v+?XO(Hzo9K#@Sf53uYvFl(ed=ZzmE^4Wlw*!8<)xoypaO9tX)!WpQjtCNM%lR$zxfPkv) z=?q}4$sa#{)zOWpUBkfmJY!rvyA0bu0BU_5H9jF>;akNzOrhfvVgW_iWW6K(J^N`)$jQGK7g@)m-T65tA=LJr--M#`cDw>fD=H$$ z_BwXz^aQmqsBEvjvMg8Af_};Z^xmKqSV4CsHZJZh)OHBL7_u-A>N>(Ohj$><#G@7| z7`9Rcp`48nRP~f%UgQ9O)EQ)umjtR}eYTYb5=lU5DaY{e@C{N@Ch|gb6i-jj$yVRi zsWP4->i=##WIgMgUi3Jw-|=np$HD!3`zEQu2_8cTnV{-?qEnMPy_|6=7bml7t#u8X zZT+Hw`)5zinToVfA5!zd0W(~~uh-hX=P-Ba56Hlcq8ffTiFp()NFNtI3z{ke^h~G$p&dcDg@BT>B#yxvWI2GWgFq9Z^|YRU1~`3m zRbEtd)hGaI%L`}>G0^`Zh4v#-qMLdE_C#6=P^2bKdI*>eV|md2pBA74^XT|EKH19v znxRM?-KKGZ5|x$~0Z3y30s<%rG*@433}&LjUXQ!*4w?Gs%#5g{78*bXCmz!Qg91S1 z*bW7+qNuS26y|MTz7&q`k9o9$%K0;t&~tzOu;@bfKLV+XL6Ok~xp97LtNf@RI)%^= zMTg=q_eAvRx0E6G{)2-9Pzh+c1d);4ycrDd_w($m39EcocJ>>7+i}y=vVV?#rNJ6==BJiseIhA)U7A80%5=0GM0aH+5jkmi3hy)0Yl%fG*|>}Q&S zGcs=HGRQ;0=5VmCr}U1mut9>6|1oly&B}Na-pB=D? zJFy<)ceLKI{^Ra}MQE`jh~CZm%=3PJP)p|7d*k_rck{~w(15ou~_ zBJ#HJJs}ADiA7>EMzAU1X53YH2c`QhmhjyGu0Zo@XwOd%92O#(K!&tHY8WfaFDr|H z0UL9$Ul9Sn9J7}zNTK{;8vx;>$RMt^f?P&{A6)VB(7sT%{`lm?Y&b{WY%M3Kk$Q2T zDn1}I6bC9}R$plX6mO zDisoW;npDJ-0CaY3{~y(iu#>_HzY6#2x0Wff~5ybrJ7P;V9DZBl7*A5z`6MIL~ zzu_7*|E^KZcoTl~cD9Sh&&I!@9B5o8Fd|o1cFLg>Ro_X!8{<0p7k!*h{hlm-bBJJ? z330&PktZvK6yoTv#T;~njGylJpx^ERbG9%`aaR6n;6pU<(G3 z4`f!PUDosUtAAb|lajJBs7aZV-OQr%-gN(>1>H6fijdHxe0;^+JGOYR6M0a zLqjFu-cw9$EPyBsc-bTnq<}gEglhb5e|ss?2V~)&fisMbj(+XuclFQO+UJ=WYWU~D z(b1BL3k?m89YBA#Sy{2*zEMR@&D+@6*q%6hR}cpU3BTAxq+Gy>L&}H2^XB2%IE%+r z@gV$Vr5162wY}}|dugd1A}ch6V3cxQ|LT*TU9kyr(2XNk1^|4(LcJ|2VuQr0a_MGu z8$Xdl^3OYd6qIb(kv&m2k~h-{8Q{i%#Qr+Z18Pr%C| zzZI>!K4&RB$PklB!6kt7^>SRW#Ko!phoVRPSyJ3obWJK_>=X)9WfE98RYb!%&!#c0tWa#n zQJk0fRvG^H;%_mtrR0gC4B~>tFiMNPQ~Ty6B=v}7zV^?VPTkC&^2K^u&3TKE~$idN3%|+m?W@I0_cKNlF19Yoz7O+6D zNLplW;hN#m~4BDncOf?iyS&Larm!GF;&b z&3gQ6P-2L7OmDJNH;y=t=h^0*rh}%HWiNiJ!vaIy9ip4LUwZB+#|Sv8vu5*Qb+LV2 zq^iQa)lE96JuEpun|}YO6049%AqIIy@D{`*;#g?Sj9xktdUSrA6#El4X{~@sD+M}K z=yFSV4QW^{-k-^l&~6uIK+D(WsPKiEZY>K}>0I;j?a)Lm=xc@?uHM#L_$~QK`ZLKG z!@oxlzXY);#PNwgyG~WnG{K4TP_UI!Iu~88PqjUKvKrIt{C>6Z+*+$6@4|~P=d<)I z3C8f05AQg~4~0L~lF{7M{ofnFM1eOTPr;^d_53Wj=P&Iu<~g~e^2w7e z{QfG`OoO?xdBp+;ty{cOf1@91sCVao$R>d~7S&xTEb_s<62_iaMwa$eFl37jVJmnP zDWz!kvM5W)$n)|l#;Rp}^4m02i2L6PV$xzu2NSk0Y>43dI4%=JU)(^6Qi}?C8GL`J zdhzzSXKoW=O88Xd8kY*a7&8UqVkftaWxzMmH1e$@{`IhwBGImmMBn-0YWkpWxRNT5 zncUButO{4N{OxV`Z1~ZLQY>{0ZY|2|bK?a*@BS6{(%s~Y)N)GusHT>z<>-lc>g;az z@5ZEKow3tK0WnJ2FRzb&?Z`Y?%5Rq&!5tCu!6-i%Npjt6X$YuRJG~KofVrhOBcY>A zgU6K0)9*v*Sx2G&YiG0dW4N;##*Jvwu=RFa7RPwgvY&*T3C;5xd>Eut9E=g7q7QDy z4(v;K`tVk-zvr~&?(7V#rH&kseArH6=;MPsaF;$REgkndiL&lm?dzv~ugTZAiS&ya z=uR)$moT+Y2F#|~?m9Bmv9gdHAQX<8I$n;dzy4d~0TSNmUl{*R!Ml$PuKmfls0o0 zYzVM8cBnS*a~2v)ua$@vDc52((~ zE#H?G+PuV_jWD?|>eWv;x`+3Y=DDBAvD zMnB&&Ie2+{n&WiTz5n#N{o~46V&b@#rwJCMIrFQbMD--TR~iG2UdI-`EUgUH&^NxC zZkz3RIL1Hzw;=41l*L=RqpwtU=j(5K+@59~JU%y~*+y^BB%1B~WjcB9s57c{B>RD_x`GyGlrBVZB<8ME6!>qX;%=B6JwHdk4?tC?+->8*df*D2F zXGhst^hm&kM;>);%>89u&~y#I)00}0C!!V?oUB}3_a|g3g-mL-_6NrYuM{cRprD8y zO%gN_CZ^Lo-B^aSP{I&g6hpBNGY}PK)Asqiy;S({{LkB`4$^fdq+=NLi-aop|Dafu zVH-DlzlQL$b`#fnE_Z+w_d!3{TB0=aJxJEx@&~|VBV*#B!*zM zyBgy!2jE=RO?1=mpWhn4=lEUiXm&A^PM&an_fmxY>RnEsfRc6>%kRJ9ZfnPMNHj8v z)l&IG$j=CWjan_j%5|mBe!z62Tx@ovVNUxlMP8)?)l+=N_}+9$Jom&qgKtm%e8G4X z*d^>ubsR(~eC=$HsKV~%_F^JRWSQcBX;N-P9HfI1CO?D5d~{O!&b&EKP|SGKxi>2D zOy-+F#d7L$lTaW%~P5WZ7n!r6a%%|OA?JJe|di30M z!$mSRD4)s#i}f}NId|tTrRh|{Jzm|4HJ_hqdP+50$|833$8HGqhnR5iqUZ~=m_CsL z)))I5Q+3C4busrd9Exg@8MY6&B4LdHcZ{RaPpf>Kx~y-CG3Lit7c8o z1pP2gmCSp&?3^ZYDkY)$za4TZrrbItH!3~hEzfQ7ee?D8?A>RViHS+Ar7m_3j_pJxTQ6=DpRTuk z;W^~_mT9KIXRhpAz;1iHjwM#F71;z<{Tk1&yb36zn8L3p(~l~`d;5p|4)yTfU=U%J z!<8$aI)b$}&QD)6s}`B0{~u1`1)M||7eDE|*UIJ5edfLLonYy?GY9*fKOYEs4M|W) zRR3O1jwE`B=5xQ{zdBb(>pQ4>h4)ZUX(s~S{kbsrM_`ctM}stjS?RR3W@?HWB+>1 z+vcsaBJZc9IkY1CVk2%mYaz+0iQFR(R|;0ljapG3>DX&8yQAH-eP`}{DcS$Dr2KJM zI4Yi`>g~!uWCpIAkS{7@EH)FoE1H&7$Zg-D7Su1*`MAYs#V*NA>se|lSbL0(szNrb zxc`KH!8t40Vz=Q8?UKv*7p!xI`8K*X<^FNnIQlaE5v%o&KI|zbtqJUbS@N^P@RvEb z)*|j+o=)j3gP~-fme*&UC`GaB>sgqn|2y88YA8i8v57c-sd_4&UNoc^n;=#zzJhzK zN(!(;X6f;xr6O+C0@=I=W@A6N$N8QLg;ZmY5X4`Q6Ii!ls$hSD6w&Xw*u=Z^e4YZw zTmL#)u%7DA8=RI#1Su}EfA8yuQ*%6c6Ht}c^Ow00KdF^HZEiruUX9z9%J~`llgsN%fI2}+K$3bU?5=|XopD|nP8wR2A5{B~^fyHmy_gPQv)>hHuQo{i{@{1A>wu}%xI ziwM!rH8f2--E$un);wKEHQszy>I)g;NaG zk!BH4IleJw6VxN-I)*zp(?oXF*r-%P$?s$;>_(yRh>|ppsJ>5^7t{05>gbq5ilr$I z2d<&W+A@a?auft83v}yEdX}@%5~sLed|q#YfW@pLy?Nyk&)C$a>{`X?kPx|5Qbx9i z4s0~3$OP2PV#`lc`FH+hOnwD6$9MsVy^%j!FJ6=>e4IN@mRQ;S{q8$P@PHDFnqZa(p zO!Qw8D(&DLxFZKin2kMdu9=zJ_bHj?SlZwOH(|Bg&vSw*EXj>#X`%ku-O1${{Q;Hr z131UJ8#QM+Hj#{+Zv2_Que3&}%HXITU(-}t$tlVSShyr)@S89JEN^Qxaw(IAdAE4U zGdjWlQRQCIB8T2aN|sWRZQaAajT0q{@LHYrvkHHlENd|(s~F%^ z>MlJB1zbe%{%Y$RgWZ{<4?jF>_+3mROlARFf`BX>Xaf|KaU(-aS^QI>EyW?+QdiRr z%Ye6Ymn~~ULUX<`I4XTtJFm%z+3XMmyL)n7dr0hg5ciWW=Iv-v#SL;HVmY}2{UsQu zU}UiIf2GskN}IFDD@4gJqp7~wz>&w#uy-yXOVA2e!IG=@<6-{kxUjON6eDHwnH&k* z_l?FY@@5EAWE6(;#}v`>*oyF<@eiqyz1rJqtdgc zs93`_PeIMEoSoCIMWV-4JcP!kkac=(QvR-ZyT(|Y&h9ZWc6d|_|NO3w-lUi`4dUuWVJ_ zJhBLHyoN*jHfU~#%_e5L{9QXCv}u(-c4oe${tt@ftYjinpP`D;J|%L-M{P$S z&v?DEZ+|R2>4X4KR6W1+-(M@X$pe#1hOn3}l^wNN#WMm?V%u)Led|6<4;q@?vW++hN0q} z)KLdtl*%r6e=$H~M!(IsNG+kUNh?GjCqIm&0jZ8H-Gz^(#b1urFDJs%L=`kv}?O!Efji>tU{E-nqH?I4i{cpjjpzHC$0~b@9oe0 zud2zZgmrzpc=7&6{b57V2fxZZK~G(sQO-flAxqbe!2B6mdBH~N&c11KyVgs3xCvKOzrS;gHAQoc4VJz4EKGy2B$l+mB<8J7Or zUD9{y(z5 z1FXmOkNa0j2~kQ(X``a0NIQz8&>oT&8b)dFQfZ(?B$U$LrD3$wLP(2{21-dwOY8mI z=bZn0z1Q`g>pItQ&T0If=eeKz{(e8-&yWjAE~3VHXR)xv&9wW({m+loR_xMEvT|b4 z{A}a@l`j4&(Clk<#fy8I&+mqBR(#A=U+i>EQerlX4Uc89>rHK`-<=|crzd}Yc<7dG zQIdFlgFhDGp6)diln#aO{Wjlx7_PaYCVA`4Gp^;IlXrQ0`N%sxILnr1)wlkVHLF2K z;(Shv(T}k=End|cjaO}z+?}>6(Y{t`@GH4U`m6b_#)3mB>n_S|JJh0?^g_S3=+mBp zncwo9YgQ1_yetqy|82^ncPcw?{zrG`>#r_Lc$5J33vK4z;tFhNG;r3+SL?0+^*kyF0qqCi6anXNs|A+(Af1QY~itZ(8mA8-i z#FsV8Ou9yF71*t~&K2I)a`?-^mb^hi8fljco0i4I>KdxI*~JDS&84yhC7{NjhlB;PU!2@b^9(Py}lq{7EDl(rT+BS`^zU6 zW%3l2sBlTI_cP6!jSOo~o?55)o)H^x)8;3g0pUM8(w@wTUtp9m`gBPt?bJ}Dq?r(< z*ZYqOKqY!~%8zqmVk6d9j+Q2Tbj@23-c>Oz=pP;}LZGh0P8(2!@;?{nioCh%?riRB z{i}u{wy!IP|0?8W#}9W)8FX)Nd6#xa(DI_7!7lapl(8_zC&$KEwzALLu-;))(KjyY z)(L9A8+JtPvVhoz6FNv(TRZfjaAx$sJ@Om>?8Nj%rn~HR`8eOOzjco^=GusZ*!nAc$O;|-iVEC`*ZKQ;sK{*M^QVawodJ~ z#<7E9bsuxq+ROF52ne{k#&_%GFljCmP<+d`-gduebt>I^{H{RQxmR!BRh6*W-y1$O z+}@DAB!zkhb}nf2OS86>`nWP*<=CF{9s6vd)%gBsPr=$FG5DA9#_^GN`g_c8uRp(M z^H*o%I?eogI_^ka>It`Bw(^<`=4o4Wu@Ht8z1}rc2Yf8eLn{|kTB&K(H*PCpGi1=x z^|tB^gD=z4dFJ_@eQZLqH1Ap5-6<+6tZQxt(t)~c_vL@^a6I+!1n-Idohm2wH@F@; z#@=SJJtFd1h<=6JkV`4;l}7TmGg}aN$48ofzlV7^&b>=rpcov(vt) zbn6$3)xKQLoAH1S=&Ef+3&d_0_b`3hd{Oa_9=l^`NDE-91xs{6sjbV|}{sZl|+WX{&IQMRl2{-FJXr5!sh}GF1D-A4& zX^-sg2DGxM<_)Y*>I+Jvy`@wJzI}uvgFr23@+8}1@6~iZT(y0_U!cn7Ch) z>$3xw%R=mpN~CtVm{@!r-}*tmcPGkx|6o@FeJ7=6t=*x!@3qV68`n0~jwoa)Yaeon zi}2yU`0&H>_MHE50nWWrL0cF^Fe7#ubM%~rqmOk@FlP)Tz0kfQX_$JfvGDzc8v~E7 zh}Sso#j-khH=A0w87K_oO@)r_Sl-d7Ru|d|G_GBRAyAz!>cj|)E!uJBFs{LdudMwf>^zHe^(DNs| z#%xcuOV9sF8W48slYLWZr;@}xSEiNq)j!JfVP=_nprbQQf)ZVM1uNH@`D#`+L%-7+ zT3WOrbr#EAPn`xlKcppndFmA6Qi;KT-cXdHI@FQY57LQSglx*8miqc&7e&}suyVbp z3w*QQb~rp-u{@;M?pkwWW5{$x1yp~l)DFeRH0)_)%-n-@A)hd9mbRdW#)zizV_dJy z^O;y$=Svep&&uYCySwbKwc)W~tg&;Z zm&Xf+#U}oqb~g1FlNHUFalu(?5LR^!;411njM~aNl>$mRQ z0cnDZo}RuMb8r?eM*j_aw!e4wDX%yg6cyPsyKlQCsxRkH_SA2Ee#ijNWB!j9bH-`hgJE5$_bnSt7FAo}Oi=*34?HJpzJ9Hm zSx+|8_cnx!o|l(5J~2`A+>QItXv+qP?eB|QLzxe#Kk8`7;uckuTSsXEhS>dl%0b*& z#JT-XlzvtN63DgIip(7v9GePZX;zF0qs!ZGoS|iUf64ot%U7 zOBT*8^G3ITMjZ&f;uAU*yXiovyykrwCXD1PF?6>JUwbub^$8P`zcqpaDK|1f-pX-> z0OAZ6GcQo8ASpA?;X^Y0E^K}Za@YM04VeNDXDk?M95DNQScLBAYa=<8R^H|tm8pBrE5!5f70sx9vv97rEq0eTuchhzcBFS$zxRih^6}%X+W)JN9*sL1_F~q} zX9&`!3{txIt|ag(@@cpBH9Z(G-KLHtKV!Km~dEG_IdH*1&_2eYgSek@y-DY zX7$>&*E~m`XJpW;sHnIv{gr;-)|Ql)#|X9nd`_!-ddv=uDPM+gtiEbx`5G9`EG#V5 zpFeYQ$vXQ(rK%aZ3H%f=I#VF^0RIjQz=EP8XdZV!7Gp5B1O-T6UmfhGo8a=k886Sn z%*-{|;ACWBG`ld<>oC0R&;)i5q5Q$sm9icsjBjTf&sy^8 z<;6K~MesquxeP2WmckZQ2O}Z4)&xL@4foMut`#tqCWc!1%RQ$VXlZHRb#$nKclj>$ zC>vZw+Pzj{VrDM|%S+dLu|#hZ#DE-y9W>gY=Y(Bu;dAErpwikWMV}q9J#=N?mY;=B zDU{`dKI0FZY9vIp9jsFd;|pD>&*nVv|NZP>Qu_InAqRDK^<>FCj;g%IPxR*p+ZNQf`rNrsb1{&DTWaE8z; zgaM5ex$5(O$Po|_Fo*G)jL%;wtN>LrtR@9eEOqne z+u;~Ns7f$mS_Ll6rsomy@f>hD359CD4yvszvVdx!WXBeh>$(yP)nJ@cHnc<&5-=ts zyh~!4fX>f!N<2tuef-P(+2oVPsdXU^n z97|NZ0f9^OXmLqN-{|NKVky-9^Jjnm6>x0Q9^AaSNt?O*`HVr~<~ zABUO+$n@@$-@-mD$;ruCb!6$YD|)->lBs$2wA`ND)>keNCW8M%hNqHqN7&mZVh@$IZau8ey32m1RhqrbzB*HTc5 z_!7YVHC*9pj-SXd$IZyd4W*a9zA1j2sC0TnA+@mQQD{F@?bsTJ&x6eS#A%SRG{Gp) zci_2*?ETek9ywf3Ual+!P44eKRpkH9Z($Q($$@Ph&v|v?mAF3?KFYdq(JWe^ut*0B zz8M!yB%Z`Ax9|w_!~V=qFt1F)-yeA0M?3xB4ifp4gR}Ds5csl3Ggb*7I^~UQ2?&H& zfoL`IM^V7>&yY4$0aWm0+Kluq;RJeaXqt$BQVb75q4ikcqb3d_DTiEI__b@~UJ_$+ zP=T4bM{sj(K9%k!UUv44Y|wJ;K=Qn=Kdd!Cg0?$VRbI{srzwAIrr1^L8|nwA9H)M0 zfnwH=?_{puEuyHX_@V4lqPi&vZeYc-7+3M;)qxaUi{(bNzk82R>&buggLx$O+kWT> zn8&KNmtFeWfbTc%ngVUy5$0BQHwCn{wH;hs>hWG@kNVRHzxjd(K&X(9up5Hcm80to zhYy@&4?i%fQ{YEh2P*GsaMQpD*YH_)goTaG3ad0u#?i6_EGuF<70Sdf?(^3NqI%jJDv7AdQA5o zH;2~2^~ED!lkHTpWapCfr0%vKSJ^M95z2CV7Zr`1#`PN_F#?j_&*C;70cVcT*ZH_Y zhKGkO6GeYaxD)qgST<`9_`Z7e3MPB*#EBCQOF3QtaSVx$#F`@+hY`-CUc6E+-iJHn zoQF0-jwkTmHX}7Pm^i7Pd3C$@a`y5bFRW1`$f@)i@s#1TLpNpZEXc~rS`3Rwl$|!M z$+RQV+amE^?$n&?GLBWmzW02bdPp|N ze!qVGg7l05#X_e&)*zfP8}O#sfAQ1$-BWQ5ds1>iL6q@cm>m&2$8K9o9D=>Se~a!l zepl{6ihv@;0gdJ5Wd}F6Ml4vt2r&?0v8x{Tl=aFwi7PA|fi7|2@modEEc0G8MzzCc z&=Kzbosyz=PF@IEf~>Cq{)-&5^S{5y{TchpjXi|fBNzS#SRVcX0aTA+h_DWd=SI=} z#|nk=?R(&a3)PO*?zQXIcQ5Jc<-pphXYy27o9F&HE{V&De}V z(5-1{Sr3`b*@}k2DRP!VE0N#1bTo_CSL9o2X3rz_B~qv!P_Ga=xTr*}cy`9en_$dQcrP=he0azJ;ZDZyx;<}=k61H zQzqEfZamOI@d>A%Rg~iMADKaYJ!omkhXeYAsp)krR||No=Lkv9dHa^M`Rbd1X%C~d zW)p*X0XK*+h%X)Fn|$C~<7; z7mbsi@Jq3;pOHO+B_J{(p@RVH@89c(l?#iDU*K_(ugu8UNkd0BfI}W1unupk(Su@G zan*v2o&Ckn#DoK4d81c2h#39+{NUX(0LN9NvEgVHLlRyHcDQiOo159#3`feWhbrOCr%#Cpkj<6_3(eR{; zKuIPhwXo$&PD!CrQ&S^`j_~$Vee(&0ebmjHx}&~$dM%#M?$`C1V+U}b=%?)|_Xxz5 zqU?pS|3=(1^Uj+cHhhlXJX$tvk)+vk?v3^ClkhObh()mIB19TEj%%L{`odU)S<7|^ zT1cF9)EPtURWLLn2GfK^kC&1>NO0?EodPm7U~VDq`NyWSWcM%BSZInZ>c9Q|9f1a7 zE4c3DbU-}q7l78 zAYJH<8)^{mJ8j4_K*n*Cz3}nl!2JAt^>lJ= zu+SBAJq?o}bC)@%r>2~;&h#+JWXh~hN=v&60SBLy)U6JoSiH1=C^|XHQa0~0s*X4O zf(93gcC1fJmxy?jtOySP3;$V@M{Wy_W@E1FXeP*e00sBM)YN*DE;ye+%*ZD#KvV#D ztc44wt9%tke)i(=5%c9CX!D!Scf z43HiBdZW-Tm^_75S1ZFQDcX1jQvdTGi_~5|MpB_4H!Ll!UAB9Ac@01mb;2O8^8P5~ zddB>xVSvKK&K?RWW4M6c=;&x6dI6}!BBW&n(b}Pey}9#Ed3m@W_l1u|v^XbF@XF{O zC+uL@q$-~{u@OE5Z@cq~5<+wI8v1&B5n7mF4r^T-bQtKX9_Hj+hi<_V=F+4+$!?p* z29XnCkJna3=JGfCwjYkfA;XV*@kyn3w*4T&I`vTdp;U9Ns zgkHngB}ljhZ$IennxD|04BLMJ10Qfq9X1p-v#m&vK*8OLv+e9hoM+hz4frMr+xG&U z85Q}Je;FXSCbiIr7n%jq+%3Wnnb?9qhR}l(O49>J!shF4Rv$$&Qs&3rL%ok9k3hEEB~9mehn4n*C#`X?*^$a1;TF8-d__P zf|W$vjHO-AzkVRc2HB$3Zm&N>(H~r3WY{!(9lw76_TverR_m}hiGPq$n~uKXe$&$^ zA&Fw7&A`yG5&zlT#>QxLug~8^T%H@)V9;1tAb9k4 z==J`nGT70ORw!pSFFBb{XPt3RS07Gi2SmxF;yEGYH61iuu;Frd+xjBX|Mp_XW|E& z^<^Jc8I05+Ip$Yue{UP=l@IYr1n2%*ja}pgV{jXTgC{CJE3N@Z*g862GljhRPMSbz zUo)sLNE2)S5x+-xZ#0n!rlh4wj^bdo#9fo#zM0A#4<<(&*4yPZXt~rnMTCTyJRTBL zG9Vl|jw@Bme?>&Xm^nC1#yHqX`FkhL_x~+_Z9R1_>0jQ`x;l$Pe?{iUslBVJuItuq z4hl7V@#^sYD$Q1ls0|;Zc>N!os{eXRfR{TC2hvd~PfK_%=ga`cQ0qLRscEecY-eeC z1t7)|mJlrCA8!-i7JJBVLsKr&S}M(y@Z$$L@DwIaJs|IeYwXugCiHJlRarO3m>>-V zuA}wBG2V-Fj?q7@fJi~%NspcvH#iBs0$*76FuI_k?he*Nn-!14EtFZ#uc83vnok?7 z!*h1SZoAWkqhFSVQ;VW^eP_%!Pk4Nt6?DOlFb*%@FiWq+If>Ql*!@x6O1{GH3WoBl z^Y0ey)1lJe-@#UgIEaNs$U#C2lg=>PL6jh9mP#%*_Bja1j-ix0gc{QLmGI#W%`cI( z@J{23i8+=~u5<)!k;zMqdD+pm*))f*8wA$%HRZ;69qjS?^7-@lK%`R9ZJ*gMZUhlS z#zs@|aTxF2ne)}R#S`Y^|M-H$qM`D6Qw&F2)0wKFSS1Bm-auo%z3V+cX z+;e!}wiI)5a@uL>fJ=CFwY^>#9Hu^WbH><(er52m9iH8(<454wjXIZv@2BlgrlIKF z6RNY#P?o4D%j#V@xzv^#)DFeQ)oy?Va1V z`{CPpCf5oJ0VP{Mw$zuk=Zy+?F}T0 zfK28HjoSglsO9*G=BhSpJx%+VFA-dSF8A03^K18&Wd#&cd=sU$-_iO3hm$HE@pQlwzUiO?>$9p+J@sj$A?S-|J+~@P;-H6sAdN>*!c2xR~7QPSXN3 zA?!0hDcFWB?Di683Ny+xxsk`r-j-!L(2->ibTv00$vS3m zvG3H1HiE5hUg%&s|2g>+gD>;B`dmPlche z@fK7|0oW8D|AJu6y50g#RIY#2F6im&r^=?+&IZ3cFdjSXb4}htT&$4h&-WGLL z_o^Ey(I!k+CSG1iDO6_;8J`yX$>I|$u!U7{x7uf~3-DnASPEgX?l);*7_hW0Kc-gk zslxONCKr+te` zDhH3e_uMrtXq$c;tMYGxm~Gg-A9=;aEa*m%M&po6n;D$H!&a7#_UFjR<23!3FJD@+ zCT~tlP1R2yXbRkAl{q$uYF+HHk+9Hkj~svy(`U|Wkbz;j`*i8~yLyj=X^wa)wYIkh z6%|Q3akD70t#^#veDT#n0*{dK%6}{BKM=AWCW31R#cB(+*c>Njw}vwwPLlPuTfhDk z$0>gMXJ_L}^8YXuIA+9`8998A!Ej8vU)Fi#=#zq{1PnL2a3s8QZFVkyD(_b(;zI&o zEm$@ZYf^*|W)uz_J$Z5~w%Pm=8%LkFH&fc4x8F%Q&i-m)50m0)9P~HmCtlnI29UjK zFXXB?ee+%9`jTH?X%jqhaL$Jzkn+#DZ|MOR(77NsLL>d~gIE5O7m?$C z4BuzGT2dXqKj|*t>7(5=H&Q4~ zekU_}ZCH*T3BH!F;?&S)FQ$E~s~~tp(ZF-FiOr{18m$&mAce}wSFo)*eD1K($&(_o zoXPYa9?Iu;@u)eTIG}i_mg^VJay1nBBPGXe(*u|VJ{O9b`WrHrbf`1=z9sEEz~jmy z*+>850;DKL@HpxwE5IZgd(A<-TOTeI7Z;mfx)h0=xFjItz>z}8NF_EF*$SB)k%nKV z^b%zyCwaz3PRMu|80}o~I}EP}4*b%ROQH%(wnC5|i^j&!9>5oLL5q3B(WMz3mY z^sxy_zsam9R>Jg~+8qDQ_;ZSYEe;<$zjjtYw~^~--3T@t8U&&274)H z!inlm6AsF2L!N2bPDr%wwY{3BYprxne12~F-aD>Mn{O!Z80`@^EHQAFNl8jgU$yj? zs=2v3kWP7|Gdv=6V=z;K=pz(bLtXiaSCW|?)TWjS#m%FC>bxI&I;_Kh2S(lyixe@XSMr?{?W4qC#U1+k60XO!#}|(-%u};IXsy*{??_#K(WpGPfc!kZj+y>p zmG(P)zbnux%?)SgXZb84;YAI;AgyUyTQg@wMrVcOuYrkauqFx&X7XZx zE-olA*ZRo3b*o6n=M_wMWW49Z(fvi=zi(>aYF)!5KtZ0%woaEN7$PC=AgOy4Mbn%3 zZNl5P9~w@dNmTNCqrnj$AHVlwdP%T-Yj8-&(GnjUn~Ys`RPV-T&2XK_K)KS9qyU!} zgMI-7R`m4r=ycTs=83lR>6;an>0V_M=fv;5u4bV`0B$0o`1uHis5Em?B~^x)b0lAp z@;|7yWYU`p94-R%(Pf_}HPu3tIdoK2A=%GNwm>$mQbCAJ=;7qr-A~%W-=1bh1oTekP@W#m5aT`NY!R}+|XYUliYZ-9f zYM>Z={8AWowb)^7LxMJ#M^8R!(>As61Pa~Bxq>q++U{0p@t9%HHyV3Gm1YqI;eCbLidR&Qx@p1i^G{e*#bj!0U@*tZgzl&WteLf9jH8&62b< zQZ&w$AcR14q7-Ku4DHi$4%&@-jRB)IY8022u1DV#jzG$q_wQqjx53B?79Q%Xa6OCA zYmNbWVeqN0F0f;>;yx-Ws-2>uw}rRE3Ira*{qR!4dCl_C?1@8#)a(nm;Sjf?p|4d+ zCS@0QGv`bF|93pLvOtJeRqvwh>N%SyD;YctEG#tc?s}Tf^_%M+Sw0O5>+k2&dLN>9 zy%>;T&J1!OQisQ7;a`bKWgsS(4}s;thxS~B6)~mH_Q5L`R;GY@HTR$S*$@c6=g}rI zb3X!jKp<{lDiXlmh;KLoCd_j&nty9|w0nY<0`FGql6r;Q9CXB(HtZRViDBlHbJa{< zVq;fx&W7|g3F)hDFP>txsGQvn}?GP-X-+w`b*uiqq4qNIUtI_|`HdH&-2OHR^ zVRtgMDOo@l+cCp^^CgX8Dv-f`yhY3xyZ|I+rVq!cqU(Y0mRgJ#{8+9eCGjH3kBoae z?J+&B$BaoJf;Q?`&ssg_A8WhRx4>vNdvs{1N#iUW*!swftC5+FjgFg}o0toszX}cv zTm@vS-sEt?>?&K|f$vKvweQ3UsG-w2{ZFUEw`tgvBSs^1*LZc^C&{0K?SeO6-`J}B zwUU+gv&i}_)SsWx+Sp@#zqej<%n-D%o!Rv8yuzt*u3LWF25jB2L(T2*cDN=lsDuHI zr&|+DRl@Y2lb{V|g-lPN3ZE-|P9|H?v+YuJ>YY#lTM&(z%JuvZ6Ou_ynqHvm8L= zfa2YqL4l^qyrCc5h5_V=o!Pw=X4KicTP}GYTr^PMdNXAR9nZCYIv(pQX+3rX=3HMytp4&oazsc!3lTEwe4OoDyyjpuuV@( zt9|tuh`X zt{Ts-#bhrEVi?)CKUu-;eBAjHWAmo=i?vk~7%6r5rmdei$$LRF=5O3@ZA59TMI7Sm z#W8F?4A)YH{`KFu`w;Srrenu!uO=VlnJluRL*5sU3~Nn)eRWMB<<7G0F_uPEn`dSC z@dIe_RDtA*p051ddwhX-MPZD1cK4?WuYE8hg!^LSux8)XJel+3-&JLq5m&Vy&;0I- zVwm_Dq#r>H8zNf>bZo%)@Zm!W2tS8_g$a7b8@~hh$e7C!@dLy>&LGE#SF+<6h)4u3 zr&_hTKsFuY!56N7;J{o+QUdFM?$!I2!V_i=({HeeOfINcIP$B(ZxOgl9Y<2{*jOay zp#yN_Ijf-kAU-~vU<8=@Wg7Nbc-V!G;5@3xVXOnW>>+v)8LydLBWvt&l;dbl##n3) zfMDErWat_dTB=p_41$tx{NPcnu0z;JF~NU|KrUfUhgqh-)zMC$cr*fDXSu?0q^J&K=$-X~^miGcMarv`_uQQt1kTUPSR8 zG@5Z6u~?8@6${aq-TulLU}# zQDjQ2#)B(B+DEk4MOc60{Tlz*UutA&)!dE%9(qZZjV!TAJjpWEYFxc$`XgD7T)MPN zOiD`f^6$xJxm-FqyG^fNpYE8diV6)KHMOv$YFd+quiyBVnA;AQMfw?b}y>^_k_$J6*+yLj@O`IB#t1ZJ5!$ zLtpQf7s-h!wCfQ5ktpnPU46oqtpeJujXF}Nb~D`Cm@L}t!LlPO3}Cy&$0F4As4 z-l^$FA3cCN#LjPVjtO?umfbkW)$l^S`Ull(L_21z=DM`F_zuRb>|3@Fw;oslA~8{2 zqd$EYC*lqOKBkr~gX7hUl{fVH=^hMoDc`D&VHQve3=5H}bQEMVS+zXmlD1K zO`$r*F1HFOV}@b=Ho&qTOWgY|a^lU<{bsM%sj=W=gH{X!Sql)!UfXYDVhR9~SOX>y zFejLBt5{nLjG>tNE8{UKfSd*m=LmHBR%rLL)|N`Bf?Fv5s+zd?A?%N*>EAFyj+sL)tG1JhuFl;>YO zL&>De-#fVphArdKpo(6x5 zsrjNw7%);Tc^;3V4|(mCftOX2QkqjKqWANrFwRqrD`~mloNBM-iWYtGr{qAWiTBH+ z2XFszYL$x-Ype-e2k{4yx}I-spx0pN=I$cqzj#X+1wC53 z!S(H7^_Gh`w{YL8y06tg1OF3qzBS=2YO50yU8HQo{fY*W~P0&2?{ zmAt!-%tMirj48dl3NzS21pEX)fJHtJj=31&1IKF_S-?s7PY?sz1Qgk?tMA}{BJ;C% zV1U>PKi=ksXq4bVaXbV#BF5ce6qb-+!WWh=zeN#m)+wGqt)EZB39G1#8RO(OTQ{0>1p=pWU$25hqfy3)-yGX}@>n&MpGee&KmKEH|KhJ8B3q_4gR%gNt)eyyE`lgvsw;+Oc%i8x&X3Mb~A_Ff<)Vzkcd?v3(-P$S`Or|bT?_WkW_(-HaWoq_rbiRxl{zpsIt^kKOUBkO5royJXV#g?Cu|JUiO5<&|s$T5oUv zOH~~fz(Z_u7_iV)dEWpNTcH$~%fQ0h+lWzp}zyuC0m`y5(phJg)B&FAi$n9Vg6^y~Ds7fF=jRFwU(vy}3eiDe&6LfOtj5K{#ZQCqTglRe*eA4BQA` z5u+jU3OB{%JFPCznaK=%_H_y{Km*p3@h8|;>wU}GsQlz=Gcn!6n{j}f1TD)0qJm%Y zi4QA?w&}%BLP=vFtgd7J@|KYM^f0UM;>2Myg`J|qCE@3lt8C3UpJi*Tt5OY z^@Jbyz+pk=+}Hw;HF;u40ua3yPK86`6_b5+bOHj4Wyux)ZUm(MPy|MhmFROBZMjvS8R>_+2-?; z!rE$655w-UgLgHr;=<)Ii$I}D@*}Z<#&u~vu)W^`2IiTF`Iyl%oDwHHFwIq@}rOw+8_LR)&qQ`wtO`Frq5m16GK4Y{h)kwmtJ^v z((wc*vN&*m8sOZGd~-kq>u}H~;hnbW$YRar@o@wgU-S0u24s(djE+or32^4#<(-m? zJ-q-TISCU02W>rxPyg5M51hVZ4rg@!DNEA(=XA!jX%nY`0$5>f$N!FKP%wS6G4hTW z9VM>RCIGvQoq{4QA%x$G15p-rR@}_f7gbUpwjQYTR(dLS;9J|G;56Q+{+4R~pj+$y z`BIyBJ>lImJWd##lJ`FC!L3^d}8g_uiR+ScT4FTpV96PVAde; zo9bx46|?jg+5?p~7d-bK)<3B5XZX`5P*UQ5Gh)%~Uju&7E#F@# z$Bk$Ua&vNoeWHS*!gpf$fg84(l66n#(95r$TEIY0-^ZIPv663>5%TBTaq;{|HH=J? z!6W-Jw_bhwb3;hh?sv-hf_an|9vb~S>)e)RaofgD?0USpUmb$+ET3y3J0%X(j`4s zN>tp`u{s4_jfFYwHU%F1!X~yCa4ntpJ9~CJtoBX5S%EiKm#s_k8%t(yY)syd=TDdn zcoC>5qz1!bc-2dP|A~kA=1>zU`_6TLO%BEXUd_v@p>vFL()ua>ETo}M-}`Ib;(U6V z7cMC%N{pNY#-rF$`@sNKwz1iH=_}}Ti!+}t&EantJ~o~oLv`p0wsH3f zvs1=&0Q8hPR2EWSQZ)jpiNj)hTGj^&U#QfV^#_F4ZLu!SN-3A~+h+5T*?nsD+_a%` z3oR|NG1QS*zeO^L?HehX?%%&}jxamaGcs~=b&z*}dIJAuR*~qXa#qT+6OXBSle zxk$ndCHc`kGe`sxpFWCFsk;(R;707RCtzY*G_;*J z^xFBe`&*+_(tcjt=yCV%JXH*<$cInQ-RNM^tC@(OzHzd?73RJqoCxJ0fxs*a`z>Un z)q_y#5-(;#PC>EwvLGFoK4EMBY!z;m@Ma%JX)U*aCZz_+UA+NiDJ9cH_?6i+Sqy{7(Jb=g;HTicZj**df`-t6q+ z%1%ps_(8sAyEu9l;L{P!w& zgY?$@_W?TZQ@xmrQ;qAA=+HbzpQ-$8oqdRCU3XI6#Z_8vsgv>hb^m?k$v5g~{QJ-@ z09kMxXjrelYihhziqupowH|j^snWA@lLV7b_x@O*o=J{Gruhp1lTb3gqj^7bmOy z`?+129a)FM*8lT5r$j!TP=9;0)p=i~_m1P#E%#QHU8JhJN+o$W&5OKaTH2Oc@qqI}fS69BgX(G7@|SB5UPw28 z)@W%e@6F}-u{Hkp`#T4PX$^8HCS|Mn_?AEA8G|IDi%^DmJ#h_~;|0$u4~X<{HR-%Z`I%3wm5_F-}Nx3yYdhVhFhbnNIUL z5X_9^-h~nDnuO1Y?CTBD>NH!o-ix_^C|ECnS}^vfr+%7K?oQIsqgb&7P#mR^iev6B z8qRuz4_`xNPn@K&Y|p5kY~#X#rX#V%uHzk97AN|x6nXfiH&He^Ds4V1TO$4Wk=Tn* zWz|u<)fHa9MqBO;b_o@hbZBCU1U-_Z(ZHniDr9vON|r%xI4UdKVx`ojc%&N=cDCjx z08og~Enh-44vKe6ajdbH&IeyYpoWkQWaL#3Ei3P6XdoRDBLdA&py6Y?1FS3h#ZqC4LEhH%?-mgb;|wqEC7&e-X45xKu3QF!k&o89jP z9#)BLO*`kLZxD+m()i+kAIQ{kl~y(GPcze* zeRu(aMaYyV`DS%zO6DoyK;Tc)O15I~A{;d~8!35v7ZJYYB zW2-5@JjywKxM)g$7CG=TvM#&a!Meqm;$Nw)|JqcB>xXQK#rDkg3WWi^RzRL1o9dVR z^_?w3ZqvfTSU}4?s(@QNum@?Jwxtu)oBr9h1NtDz3&3jI^K$PN-yS|jWzb_bGMOPy ztMTuB(x9K8JR#wRUCZtqzyX>g6dqAo?Z65=DcdhetWzu3ZykTfm>=;>pOaRM;Yi3Al(q4KcMd)b^Z)|i|8AH8L6N(fuaOzL`FkHL#gvdMPt)B zIlE|RXn4@WVy;7(^z+L&U8RU_G}sQ&x@hnr zaF|4cpy$S(KyW>T*Z6y)_Z)G@`TxXkMG=WCQGg1C^|K!0zoUYToO`SM20N_%_Fz30ZMfUJp2NkKSB3pR*3iFch~$Ue?@vza6%fq+dE zAaJWEQ-6)cN;dezQ!@2l79Zs(=-YfX|NNdA(8wGhr$7W;vPP^hqBE}`Iwngmv-TH1 z(ycHpPs<&)gK|imm`=m9AI}V{Sd<2@2{$4?!Yfu=!1$_@D96aE+lb^n4Pas64xUs37 z&kkb`AV3iQGCy-B7;K#6G!EbNTg}#ldJis6bW~LJ{ewswY(*Ofm2YO!>~|mj9P*bkDJc=`7l_pcx-i;FcbIu*uTq|_L$?pU^2hmT5`+S zATWBu^g$wahuM?oPZa%@*CCcAts1|e#8~a^+H$Yi25iMiR zfo2L1bC@__TN3hvg>IO29BhNemE~C_pgi%jJ;Gq2hvME^fze-3P|&-yh|7cr&ZAx{ z$ai@*uiWXi1S0dH+~aX?C4@ty<-zRJVCcmaU_nF~fpFAtoiPtJA%9?qA>f?zNJ_@c zvIDm{-(7qpbM`w>R3L0@X$r{cMP6hGAHie`QdwMqYk>i!xefgga4>O<65F%% zkMa|sIMoo5|RMhKQKT$TUby~jnRXI%W%8p`szd(M`{e1YO#yZ`sG1|NTxoJ zZeOXM+8%JA+|UYw3lPHI1NoN9pU10L*GYdw16rQ%xwm)>4!KprbJf#!|3a zUYuvBTF}zeByjTUM5U@GuO_^zt*XD>76IT5U|j|)rd0#jEVOQB4)z%X9*aTbYcEsG zPm}Tu15hH8kpwQ}AjZ+=+^Cc9KX^bU$s}z>Z`GPwd+&nFAqLuO=fb)~M{_gIb<7QA#`{a~CwP)m!&n z)EoXFAt3=O#9>UF`vwO1*#)R3&v}6FLIu8i1EhJevaYsJOl;C0XU7QsOXhJ)AvrX8mR~<<>ln!BA9Nl3Nz12 zMeom_Yk;(LhV!Z^`YwhN+5c#NKQ+KhYz7wCbjrODP0on(`r)7XCJ+)ao+Gvl$>ev_ zy;)oN6^D)4kiy*2iRC3PV3^O|jV%LGv&4Ii!&GN(zvvjM@OK&7{5hsib;yTWImQV5 z9?^rnzkcORRv2ypK04HyyOqS=fjPuB?`3XgwvA*p5_$sG7lU6&);a=M1V!nb$29}Kd~g&Jtb#z%4o=x0ybM{P_Fnk~D;Kl#U2 z^}cNI^*HvPx6?0WmQ);@Hbe~%4OIhJ#9aK$`)PD-bQq@1%}wwpDEhqoyJ{B4N*s6s z=w?iZoQPVIkhxgPR#RX$0J%pps%}l;Jfhi9s>1OBth0AyWG((@aN}`|1937LMaC+* z{yRJgXpH3EGZ=gGW+2)pq9%aMQqTPt;9=*{?$~|)WCO+GtAP&(N-G3Bow*_l766F` zLlGtcCD4J>_ud=a54emo4#H0h%yQ)BktHT^d$AJ$hiPHBkCbW)99DB*SC-QY z#K`#w?YmLrnra#`{P~7{7`ge?WN~o zVQb*s!W*p~6&2-=`NZR%DNH8D$H$>^i>m#z9W`5yQ-(>2Fb<|5cqmZjkyC_P2U0lF zV;wj^{g@CMC7g#&plX`BvVJn$=~TUCVQq)-WPW-=f?1*22q`~L8 z@&{+#tkOFSlUs?|HpCc_%>#1*wX~NE>(;5_K6y~F;{ib3@DQb9Xn6Pmpz%|W@kXy> z7pDNw_YVvVGQ)d*Fr=>}&!J!J`kKeopMgAJ6tv=pcX)~+@Nt>6ZpyST_^ zk*y}$=$2CSwj8mu0p^;qOL05XIk&}YbL=x>&t>^e8R-`ubP9|ZGV_t?-ZC9fVYcV> zqQ_>m>%rJl&2d1+|8zcs!{7W;BKOYdlat5kyFS@>Ik*k$apvf+Jtya^46X7N6=sS} zp}ESI*<&uBsk(%8(=gphhEvHCpM|{;FB2OIGUCE4&N6j@${+6*8M-n=CjM*IU=T$l zntqEDbXX;XzlSOL1`NHG;n_7a_Vw-GKt&muxFb}lO<)ZftHgk~Me3^kGnoGoR2A1t zs7^VJZ?Gx%WyM0-+S40UQK5jHDG(KdyO)<02oN%;rjR~ZXi>Mi)4vUKbmLX$<4@eD za=~_fopXQ8ni#U2z-%G&C(Q82C%+#p2R8}~g)>}_3jB?0G>5OKoWc6aIrV%q5inxp z3!a(SeUw4y=}D2A-JlLVJQR6W9Xr zC(+GAv`B_#n0%q6SH|27C|bj_ys@uUjbPQXB#5~A|G@%6LlA(;H%brm6aFabdhz24 zZi8E998itwW$MkHYg<3q;lRI?h#%VdumV7Yd37OAzIOn=_OVV6Drb5kB*DTI%JqBb9YAlj&6dpefDuW~49;$Sjhb{uG;XMr=tR^l5i*8Cix-o1tm+p)X34HY z>d6ujqSQN@`)H?rD^#4~7eC8j;tzt6I|P#m4g;-T=ofMcu|qZDR5Y$hMvJ;`n|xf! zaGJ7Xo?!sKspyITs(S45YOo2Qrlxkl(1J*y0s5-~YQ(2${I!*dN&DNvURhZVDDAD+ zKLq7<6Y}Gg!Q~?R0Xj_qLBT$J+Sd<7qWrkAEtht`nZ~eekoE{>p(KwAbNfD!ILPo8 zFCsO_iw6GN6%@Eg7`5pcLw~t7eE=$7Ymg~62wGc+(3eohcI?=p`9QYhUDvTtF!jVz zAE1#%tY}zJ5Dhv)lIpImp;3#S3q}=hx@XauaIE?9{K*sXuCr)dauQqa?g?=jtz4Qp z8QeIJ^uxPdPjP6<_$|w0i8(;BNHWMlh4_d2Wd_3HRmj#wDmV-t5RK>kJFy*pcO@WO zFdBTl)RTbbYGgJFGm2WE0NCV-!3TsX0Pe0r^zQEIS@io3>ay~#Cjx|i$q<8vvk$-Z z++VYeM%NJuhI>qG@Fu7o@fh=pvo%zUUV8oj81nK(<9+wfTGO4*`{=d1pKPw;Qsj5*~HBk0lTrAT%xs{%Qn&GaHy6^_ui=sV<8*I`| zAMbv(HgWBd7T(+HC$gQ+ePHCIzely|gj#d_`uN)1)7s{6J0PLqy}Q~lek1kozHf?q zg1?V%+k2ipVw=KC0&O}#b1rr9vynv=QS)G;B)-IatsWiqne}?C7}b*g{pMvz#a3Zy z8M^;M2rXtHH#$~;mQ1a_1_Xk*6U7(GV}8UbW+zIhg0I?& z85gCz>)3%;H3U_veTf<-?_&ABs3<^jjlO$#4Ub=Hg!`4^7t{h-JV2AG?e~c9EnKA(e=tWF<1n$kwv5H(5nQG9pokvbT^u6R9MLvS)>i zGE4YIKrjf(^SIt}C_dfzXrG(t#U zXe1Jrf`^NmdovWh^=s;nCH>LX&6R=xr%TiKLgpK;?^p5TwUBW9#YEu1r75TsuNghM z8LuUGq1u?xU_fm1(6z+s6A=*ra_!>qWw=?|3ok2S7m~HqHiL|%%ex)*`U>&wgaRMn z@!{*F6a;%9K109s`fJ)v3Q9^(G0uIDR5!ZI=f)Culv=uf z4NpQA77^p^u<-i9AO#vY5t(zh7yI5E*e4pI~McieocG}e%Ed}6plU=!Q zZhQ-s=OgT6K!k)A9FWOGgS7L z5f7w@2PHy$bcUNyF{s&JnuV{qyo|GRnFGj%A4`c6dkPf&9^t1xo*l^8(f)!2DaAf8~*aLO{M+t&7qpU z9jhUesw^*L?i4kjFE%0jUGE6oQAKGlKdQspwWaMJyD&#rIX4L~TT#buOKa;y;$Z zTCr_D=K6y}NLlNtA_Eq|8KQ-ZKVsRiYS=fl-bVeYP5k)r$1kibp$ZM8K12HlR#%;_ zqY9SAW!|1p7NWp}{cIEZ)!XbX8sbEQXE}C@AFB?EA(10!;-UGGwu^c7Yhx$JIx_@% zJ5G3BAX+;0tNW4^nMoK=+(N$+YmN&iXSNJ41HD`ew!J10?=)^s&dh@vsUZ-j6d6B9 zamB{TPX>dO+d#E^jPqUA&0&V%s`hL11)JsA5Y&1~#3sJZ2)!p}+U(8;XM(`0Uh{bn zpHuev;Qp&yc}Q(-b#}F6zbGD-mews!)zx^PWI9%Qrs@9b#5O+lgocvg#=`fVEU~Lg z3ZK{4TG#}B<>cmXeRS$p`|t0XcU4s7mwng$*IFXmKb$NajvCq`Lc9V(NzJf{&cWW^ z^c|wce;*cYidNm*h->#^@A}_)bqErKK1tZBkt<}&kC_iq{65Sc+5rs`ak@hU2QWh$j%YAf>=5Y0o>qffPoFd`&W&Gq+1nMHf+wljhLE{nE1D9O*lq zrJKJ6GLrhW5T^w6+I5Cd%kHk{YigyY@cX;`44nxvBo;kZLu+e@`09&;aN_1f+aqh@ ze3|GAbpoP#a_UydjV-phJCdjPimQ*%m9v}Il4o`8|AM*E){9NRKj?DFH1+?bM0~r3 z8pHx;L}d83_+ugqT>aHv?ASP0dw><_Wn5`}kD2pD9W;M_|K6N7NPeNx7;slJcH+Y& zm@lyASO`UtP*^*0c&%bAI8hsvg69c|VLroT>p#!oe<3#O@f3cF9>seY@2eXwZWs~) zKMXCho(sXc(cC1Imd&0g{Qt(7;OFZ6@p>lk&%=WXS>K}l3{l@+9GnMk-V8FXvm?Lg zD3)fbOcFly|@q#I+sv?G$+Q3Sf5_0U{CtFjV9)c*d5A;^0*Td}w;@f$VyU zN&=JZoR-hcvsdMs`T!(ES4>95E4Pks467L*(K zWY7M@#|zH#3DQBRR~Vgs@;Q!Qi+4Ih&!9Owm2W0(&pWyBV{@7ekaTv6XGG4%*|=QSzY^DqcN<(E1Mbws_^{x6#||Rw`N1e z5Nlq@hmMXBR)v@s@W^%1h5}Pd2AH6-Y*bT2P1;+ncu{DE2cdvZ zv$3It;WBx+@Qnf1zT}sFf&q__YEb6DmQS?>|}2sHt703Z$hDDFaG- zk)r%k;lmd<@tSj4e;*MeTKhfBcT6L+1Y?S*mBYfqE*_3#<<5UHB^RH{i;ys9ok3yKPSz@J~y3_h)obtk+oUi*C2p%6K?BNebp@>l4Q{psW_9Nbx za#{4aVqI#w#j`pPF{=B@p zr%H9LF)aL<{6*)r<{SrQ3@3ZpS5?&e% z0v06(F9h>$<~3|Fx+rc{aGts~J(8^Mtdp2c&ykpqp)K!^LbS?!pe8Fj`%P9pX>6;! zl%%97gb6uE&LU1@9&dZDajR^`g1c?~_1~s)7X@vfTmj4;nDt}eeTB$h%?=MC59wPcrZ~5gqK?BT)pgxT;S}HR zXnUxWZ)W~LKYj6VPeMWh6-5x{v_tuA+5;BqX3|GsE;^G3XlR1?26y+JJY#k^nO#`_ zWkt{d#I3Zj$fcU0BhOhPWc5OKXdBo1&;2KGC=nJDi_A128{06>P@UxRXzeq(P;LyU z$~-k{J4leM?1xfXHR^I}$6%k$K4H}OH?PFvwLOM#q@Q>baQJrf)HD&4jMy;JRNYEsDbDm@Mfw9YDyCaVd9iya?6AZGVb z$Ep*>M2OCG%s$*2Re!`F2n+;rb?xm#ezhL-<- zxt3S)Y;WR#m;bWn=I@7cj6Q7Tm1kIZ`RDuh0Wu%<`OtKknr(L{lX5lGV##^OI|AwI z${c>!C@TIISJ`{6Q#DCBt`$k6V-p{PB|VsD^Gt#+JV{g}tBw~p>#vo)PQ68b`dk99 z*7^9mzxE0Xhl$&N!39@OUKL`$aWHo0LMs9{Q8UMt;vmYdD=#XeC=I#Bn|JX!HHyug z;uAnFz*Er@4haH5hT1xZ{BwxBlG5`@OI#FPBwq)Xqf^h1yzVY)@92=j_V!pE8y_#c zwilIas_weI^;LVCz;U9ukhCX336SHjf_9ofDq-*?oKRw5E&1m2*$K%nfz}pJeafbB zavI;)4tQ+{q#6Nrpmzs&9{K1|D4Mq`=H|Q6j1vqsA%|BBzENo6(dRF5)%+dB@8=)K zX=DRC9xBMo7f@e=HA-Y?ihhX*Kx{50W z2!GhRJjY?GAy$_`?0;H-j6((qt30S6{J`>BKO+2hTp)q;Q$O*`1?1HVcAu4D;E33H zV1)XvO3zN)klikAuDauf<%?>x1|QOb4-KB}d(SEnbLGtD)I}}UWwE}?KAVBqv!;2m zG#Gv1;Ni)e5s9HiQ3^sGQ?kRpu)$wQWNm_SYXA80G}s|xt~f@p)8U^Un3sVt9kQDp z;9m$<7XbTDoWhVLUnp?p{HMT;&?4N`U&B2fy>fvXO635A1tTfj%z6Wi7&Q)b$hl0% zAB@$j2a8LsuUN3XgEsryb$Nol0rttPdR$$k&ETbLvMrkv7Wtl z<2c{BMESAI^TE{~+YXi2@6XFBv2MIpNBX>li!#)8npbeR?o+IvbQyorvN31h#l~M0 zHz6U;In{{UEAx0SD~ZS=mkFwZv~&m$96_HP0F0Za&@}G@`w_a+XN3$KNBBtC0}Y?G zsE(I{4Y>SuXfxosp-X%1PUL5O3PbY;7e%z^ma8;h=!$K6*#L&tAwTJ&La_heQwu<4 z2wV3GI23|DWaB*Of&0Lkq!{;!ADdVb=K$cK#_a5;v{z{p&+;?J=+N2Iy>!yGaR|@9 zE=yWuchq$qzlZ#WZ33FbDOcb>%9$#=_KqutTK3a82zmll=z*^Lf+Z>5OP$3ttZaFo z3u8rXhGTVS|2|t^FgAJ-+N@GhS++SWn7@4|h%eVa}+SR5dZ#iAwP8nxah8HIJ?`hsy|?m*s$$OZ44-bR?s= zlZdc6D4GKa5*ht1815sYtQi$Vz%Lph!YNh4q7ba74>Rln-(r(tGppC^yipA?d9&O!`0 zuyuIq4#KpllCC{4J-|>_PUhoNmuG}q>d7G}O91Ig_ST%(qNhJH0|SEFT7_xEv-mKE z$L8-9eN9YmEPrLF=_zA+0G)3L@8-IlhLhmPRl>h@(P!%BCpILpYQH(D3~<`|WF5kQ z+haI^1l)w&9DX!`hiv=NUSSX420lxKvjslqJbTDJFIXxhBP*+nV!Y4!K&wm;A^=Qj z1@chd@IlRjY&`ZIVIF17Jo!juQ}^rUyNp7-72gudK7aYHMBir9v78m$Cgce zj;?2TY|ZC={tT-*`R%{ru_~!Iv$JqF@2*?+79)!FF6@0^o4@^KxSyc`6 znF(?fYHPUr0*GL2PJYBI>Fig~S5W*Tw`s28A8xwKKH>V-iDFm7E;3bkUZ?iu)1oWb86HE;u>;ffbAbs3+3lMMYiV z#Utb(!2biZJ71hUb!vnhq91uQxY{$d$F-^7d`c~&m~739xB+BoN=itDY|l%$YKVXW zl-Y#!3t<>!AgwM>Z)0T*L{D-V|1JmOhqSy!uRrjFMg{@R48Y{NmT(3=g%82r)%7-x zez;HEDS~lJw?v-p?gqVC|C$MJB{)3Xyr=JosKRj9CPtN*v>(Ub&|HT|QShM-a>ql( z?Fs9<5`26&_j3rxsE8rq?W;M^YG@kLwVH()`rg;vnA7F#o7(4W zQ}!O@&FUqFE_TMyrkf=)(bdK<_g**bKOtpV_xd;Ff`eQcYV#(bz3TlB~TJGgV;o*+*IR+(0JuPh|qo?|Ncnne+m_ z5FnJdfnyOkFj3m#zY>1C`qw*gCK4PWD(NkDcC*a=*0i9mBVz$Adm%sQ0i!SPH#7TPA9;V@&s_%#+P$+SEXf~jY`u3u_tGn`tM%M(HB(C) zu@Nu2>?Lr$KNOE2HJla*j5zdumwL>XV7L|my(!{B{luro3jZh7@ehDc_z8HID!J*t z`rYTxe-w3WdQxOr7*eTq@>8*a+`_`bL5C4}7){9_{(Kp==d50H%I>+7S` z-Tb;XsOgeJvbYu?{CBib;OOe%$8T?D8A`i+{z7!zYMd5}vxdCSRjRtJ`e#zLK*0oC zZr_euN&61y5pQau%8-1>!@<##mH*^BSB>vR;+Z6>vF@W9N5yr_{G;%xAt(#}{Ut;5 zDdnxxR~5cL&ksQhet4t1t4k5?1X}Mckl!NfBt|D!;B?GX(+P95JSBs(z;N_zv}>$G zQd-NiM!hCLaO99`va^L|f0r%4>ev(wF;_uP-vz_gA+}`QuN6WDx+yt2>GrxAtb6wF zzvHr{wNvI21#2``lSZz8@3-?+eWTm{_UDDdJk&qYB5H+Wd?$TzCI4PIgdFrCPU zc^rzd?EJ``MPu;S4`^J&moFF1>eMvD%3E*$6LzW?or-)bbml|L18U?qc`2yc`Hc=6$ifs!c$Abb!H-%`3<61el&e3(UeT6JM z#}!qJp3TgUt}407#!au^y=wxxeX;jKZn73(69UUeWJ`!$|9r5^!^_k27x|t(va2&E zFKGg*!`O}|OZDp7uk!^k5QFuAOq=j+V-$t(^9Z{99ii3>05?rkUDyO@($)|mk#>;c z9Q+r0)t=&rntbD_inL|WG7kxL5Nnzl@%vG&#+B+Fcm)|53)_`%BWx==EXAYLDgigQ zg@EWT%8LV0D{9Zg#nq~kJTf^cxFU1j%{wZJvZ;(L@8%J8Xj=$J{&OP~0`Ng<{3%QI zm*y4RNiU)TtQ+a`ajw8ds6Gn6uHA>58O|>EYzo@@@$vd&wBp)%x@TtH&~QVPiSMLc z7XH`jz{wI)U~DWq6p%Nub{YXU>FS=2aT1EsS3@TsEug^{qe6^6=qiPDYZ&d7O74YW>JmX~vE|mtzF2h3O_uPRy_Mn@{y`J9DD<9L`i=8v=BjovSdi0iBJa-kot)yV) zS1TL;KH=;sW~wrZXMVp99|n#=kdA4>k;(@VTGb_k_ASR1(U~f1z3_Ku%iO`8N#J+I zVDL9bD!=@Too*c2j8u1FBJZSRFW8ze@P%DI;?_mJNsy?;bgZpIc4F0?$AF`p@Mse_ z+=H9)#!$FfmlmWH>-Amwo<%7g&3PB~h~$)%5yJOdMzP1(wjaH2YJ)TzE<0J+)w@of zHS^v|N7qQ;bfr-BcHH{M)_t@4m=*>^x?4Wx;sAJ3^Mv;}R@@JN64y?W|Kb^5`XJ-0Xt5b*9VFBOI{Y*%BPq|$#_~cJI3-PgI>yC?)+JvDH1u5Zw1UV~OmL%96 z+M9%L6hnOw&>iiG6DNp%8Q=%utGC-ZqY{W7Huc^bkQ;igBb%^0T7V2LU--qL3mIzH+=Fm`1Yy<$ppXhy9%=tUsnPSf7;Tv!~~pX6s$I?h0~Eq>LA&`Wj0`Xz#LoG~ChQb3Y-Ta@Mi}y;T@EqbCx#2x5ZOyi& z_w!J3wh*~)o_to{+n?lo!oqqLm802ekLI8%`tCc+^VqyC;FM98wl+)h$;}esReVHf zJwx7BZmDS9x20x{w{uGWs!pXKU6+t<=GYK9plkK-6EwNEZF|~TnDF?q`>npd`a`y- z93gN>y~i*{)AzBXa#ItA}E!k3|Cw;m!R|Lc9{dJT}oZ4}|Pf$oFuV6~%E#NO=AJlK&7j zu425glRV2vln6qj4F{x?s=E(B!DXCSq+cKP0|Np!)dZF0XBX8cL+(*1;|2C(EVn}w z-Ew|xQc{x2sbm;%3jchpbhE?8DO!S%%PsY?(>S5;hr*lKuMx6kREva;!?{QV(C-};kJ z(-4{;@S9MuQe$dFwC7_ew1wU!fE&Q#i<#NUzU=lAwX#4$+AMlLLYZRy= zu$1zbg1-bGP*NiT0;|HaY+NPEJx`-@a$u&{m|ta+|3&U5*i5OL}8_ z2l-xA63f`#ed9^0f(k$0Jt|xMs4l6OzGdCP>GWKMi?Z)p{EK{LgY7!~70GM&xL2U; zx#2xZ{W$HMg7%(Ys`ocGQK0nHvZ0UJ!&`bwit7I3hjp* zE-hw03)wE9c{EiEIto#$XvP^At*djYi5j_^Y&B8}X1!)w>223t70?Y9Sa*wb9R*2U zPnL(>K9H4zV`x6ajV|tpCG*rGk@h*nTXv{Bbo)!(P|Wo7si~=j*H(JIeEHeI#Tp@- z2nk{XnWw@S#U2QwiGe282R)Fie$z6mRi8l4pTCCS%R{KG48sw`AQKt*VWE(;XJ+jx zv8nqjAv|fU*n+7sRWUcHKq5mtcCF+E!0ju((0JcPOY!_#F9>U6d+nnV+Wja^4aTnj z^7A7h@8FiDZl)F$^h#sX>8<5mI451yF+6AV6P4B#P`QNc=ObHa(+cu(JXT|_EXHI( zTGnDEs$Z;}IeU@x@R-wHYZrfrCZWH7*ZUs#=_d#+-6NZ~Y~A{;UxKbtZ6nP}I1~z) zLLGX+B4pNeeJg+RSu(b~{Fso&1}2I0ReQZ?8AafPdaASSuWt#lvFUS%>vQj5&uiz2`%vo~+H* z+db#%*XVw~`BI|5tf!MnW9}{CEXH~B-mAeUkv?ZZyvb3Db>*9c1Fa`w6F?Yo$xvwV zv5Sz@;z_b=l=id^De60UkFX#ULZDuBY%!z^A2bITxzpDJCDrGp0g!?^R95|=LU&*joHX89_ORrfZ&4&HL|O0U*$I4 z8WAGT$HB$LCn3R(v>Yu-_r3RD6OqeZZ*5Wa)RTRNGO3G}U~&d{_mYnLu0Iy{OU<}< zhtU76Wqm)vjC8!#N|P71M)gN*1BdejBJ=0lF*pc<3)R%o7&ct1uwEUW2AKI5v4gbv zCO|+SLVk00|5L#92FJ8ak>izfsTnYN6|3_vM<*wuog~PWFKLL_z&%6PRky!wkxSb3 zKsMS7TY?`RUMCO^2$~P2ZtjSkjKnX(_GO)MLgvaf1s(s5wOQYr zt5(+5^EbB<`|nd(LD4%>@; z52&cv(#|?H&vV(vMy*7##`%2`(0x+1*S8H5UiMJ<^#PL7P;!{oO2 zxI@>zel2Uy-JUr8+5bIxlW0k{PT-;+*>~ragNl3hrZks3*>jxWl6t&jRNjTaZZ0UI zh-vTcR)W%*&^^npuiRRs`2j68F<=3&diSnf{$JLCO3qXBjIAL-E62YILcLK0_cQHy zf`(BBR?e3AQ}ko$Ma+T^gxEqoo`=SwYlniCPf9BOMJ?_o7-v2_H&^d^@(mA-iYAB< zZCMSLIZyy38c(f)b+s8<8iJtds%v)}^wv#D$=tK6IOSx9sqhPq3aoa~pjy7xJb8dW z*Qm~-fgnCBz|2isti0F%Vx($LJ$`Z=!macU3U6~utGz+{6tII1Bcb_Y{oDHXt$dP< zHziFPG3f;j5fLPK^YArR)|3anY9P;u2zqi7D&r5h!mDoljw-1|ydHwW?!wi7|KG|5 zAhlUW2@x*VX(cISpGUg(X*wUDnfeQ9Yu8lT+nh_kPoBX;w7&KWk^2`%I;AI%xJ+Kq zSp`N!Ot-MpMkHeQ5GLB8634XG*qHQM6sI|y6Th&;-Iqmxq!Y1`A`|W592}!qKER zxShc6I3C7s7=FsRcwg7qC;|J&eyEO2$5ROu$Pt@AzCZds3@bfkRty-t$ng<=VI6uE>W*&PFQ4+#Uc5D+6)FEpy*nj?|4Bw& zLC68V)tdLSTd&N}AEwASNU`E6!*gQf?Txm#+wJS;rIMC=cjAK9{Zc|z+%Le$%$#zx zcP~G`{Pd+8mC&rmd^zPG&yfqtZBQI ziiB5r7=3OKtlNnB%rU4xgJP1#peGgnq zI8NhH1Sf{{`yvdQ!0CyDt?K8i?GbOr`_~_nExz}{1Un*Li*A zq=+fvCk}Yco`^Z7K8-fM;QE(CG2D44dv|1bi2>w^8I&d!pe>A%rR#Y;?ubD7VYpPf zDxNPH_xLTElmA|mdX*R)yug=xl+4nle~L!UJ4x9TvxV9JPKTT9zU0+A2YInNu*-?^ zL+^mTz|_z;?UUPi$EMfMJW*VhW(+l`GF$sctUqYHf9UTe@|3?3-~=pBmPIL=fX&ApAz9 zZ!XsQRO_1(mNTsO;HFERU0ox1WLE5Ql;mXizSZYui}UjH2}oPpHMlrQ8iIQK--z^) zvNDdJKYzAN6&Oq;2k|sOiBsIhIN{FjR=LEcz)g|vdiKGAdN|C)2c~oBbn^@~%RhR6 z*5I0zIf0bX)^lNK5L~j?xY|pfDtVYX`1sUxo$5m^2`tpgLD1{K10~T zo;?az(*prQ0gg;7Y8;I-PppUBG+*aEU>a7p&$2&XZbJ^~Zr~i+H|xXUv7Z4F2n^=;({n+J_MgWk-Qfi+`bYYeq!li>(DgTC&ow` z+4KX9>6Bvuo(8K0F@6^3ZgalT+fCVddAAW|tv~eunu(#>jWxUUZ-n)4T{rP>AP(?Qoa(e( z?MdD`*^S@oB?pzh^!wC8(MVvB(axXCkv_K>59G+vqkMQExoQt%VpyTxO>w2E*{gnH zkp<4ZpS!x0)l z*lG3kF|94#;T@ojuyC0_%A;QWci{0F%1lqx^16W`skjY;0JdQ;N92PCX}{c(@IPc$ zhA3hR2(c6(vSq{b>XmbC(#mDt&+o34Ip{glIGI=6T2l`WR!-k>*N`)MVOv~m{?oJ~ zwx{WtOU$K5IVfp%>q>H!*JE%!`KGz(XXHh1;^6pJ)YE&IDA;uX)gszQCE!OR=Tf0& zvHVNJ-S1DclTx1ViT9f_J^HF;o`UO~PlD=OoXz8{tsCrxNtm_+a`nkj8w&)pj!)~i1h8yViiP0B( z*A@rzpX?26!%l;}Qg4r8W_I>R_kC8o${&)bf2_~oU-Ry9GmB}3v!J#FU^pg;zG zEGBdaK*>t);Ck11`JVzzrvPJ?MZeS5%1X<6`6$u`6$E+`j$WI_f_GS%GlN+Oa$g z`rclYDT=306BAuo!_fw3PM2Cqn78d9s(vfCfftp%?_J;$mP9f)kJk^em@jN_jOo*S zc@!5n-0wC>T*=9c@0TIhkI_-8{^EM}3#4Mh7Bj`0@Nb-@biHqas{t!uwH1c@Pf81ZvOL>zKakUuxMMPUN!wIKofXBk}_mFAI*EF85o;%@N3|Vt`PqvnO8jzUgZKG zXy|`J9`O+48@Rc{ly-VwnEnTwR5S= zD&fpA1<8tptpiA4wr)}rf}#Vw?&OhY+k;o~_4xQY_Ma+YdRF_m(O0%NeO603lsjpr zi8-Hr?$_I8hmqPs#?5z!FYzn-De&?Xdz1Sgogcn@l*je78yGMVXARfW8 zc79$`;$`GTd;lSB$1k6?c<~Z|9T6vaz@(zNj&ZpA zx3{;Sn}W`TxP*ui&wp1&!;NNcGi{<=!8^sah9K>FE_*Xd-2&$cElfM(w5wixFwnbc z(N!ZVBEr6zouazB+5s333fj~+#{>Y9tTgUi_k#?{f&qGG9G6X(!%w9BEJyN?<&7J# zJ`<%Dvc)rhdL(NQ*?tfKv(RkW0rMLL5XICE#R;MiakDikcT~9Qc6RlfBoLX$vcASP zI%hFAOB$hp)F>+^uw*K_wX!oa&y36E!#Ve=OBQ6i)@EV+6e=gD#iMB_4M^^=^Mb{+ zxMAGeUGenZ+O&!HqIOB#Ht#@a4dCYpA=;MF?k1d8_{c9oR31cm_;+CV-ssHRKbF4X z;Ha$D7B>}B@%ye#nM6iKbzD^@@9SND18Nh1bptfpbgSpC`Gs+akrSsMW?T+VM^IYy z4il&q@l-y}uHmfs`B7bV82_n%nt5nIrkl9?P{O0&RZE`*K^?4X;>~&}F6RxSVeG9w z=_qA>j4FPKJAVt@wYgJx0dsga#IT(~pH-XKU1uuMmhd4@0*T)Gb_a=U9#=%K0|x5< zdEhPv0}x|DKCUcI3kq;T_=0Id0XSuir@kG=!~D@xLI>db$02^peQco)SSeNWZPNO_ zVJPoLw)(D6AP}sgBwHm8H2^Gb`HPCT?jSq?|3%^KHz{gII-hkP(sD zEEnZU#NfjnB)#U8=WRZVl8dm(C|G1xJt{9OWWu>L^P%StMd<*tC=$NFzXXX_hUEIO z(d`cnp4*%?c|Q8wJB0U5&nqqrI|w=XEdT!NE4VcQkUiGl&UKZVnwl`kT)6GhVU&?a zEk!T&tR^)%hyDwwPSnF5&EZc=?hmqG6A@t)HQeOjE=m3VAsN|e(P~tR1tld4P19@^ z5P%7K|MV}FmdD73J9ytGMPdmrI|zlT$OK0qlafwf=~0Ah7#nZF4TlUzQ_RP*V%M5g zyn1yHEX5>n0>6GaqFO_3hsYx;An6l_c1)dChPIpNerLG z%LWuuP+S}k8cK)1lCHM!6h#va$&ZGf-X_4_L{fEnQEv}(M&nu5VjgfS5OpM|aMZ4h?wWmkF^mQ*4l!IDo^^(iK9r{na<}a&vPDu+w3pV-E`}>;9T`h_(op?F2(zSI|;E zksD|~)g_FEqyeEJ5CuLwVj0z?QCvw&N5=%M8Zr=3q!Lqz;ZM?xQ*eF(u!;#60ajQ_ zc{wMV1AOFSm7&4HMIFqm8F?QS5<*LSS&%tOr%&G+>F!LR^o&Q>If6?b(H;t#noPv- zXM{CjQbpf<_jCLhpe%S+0>Z+9u+*Wlgm%7bV(>B^7!lWuv94KJSwzYuwkL!EM2^3d z$!6Vs_?i{Ao-Q`yH9rOQtb< zm@U3;pq=&JtGt%8BCnqPw4o5dV~TwE@N;@l9vr|#a15|CE}E|;P6zg%itO0>9F==? zm$dRMMpgT%Qad|*JFsZ9*woY#a##MEJms&aPj}6>uU?F6irB??mVYivdFaSh+V&vo zrGb3ZcEh9dwGV=}o>*Wc8iD4JV2daBmH9sdC?0`R_?^Bv4PMn9yM(Qso2m1Q}i8JQx_LAuR=Z=)>7lBM6e zXw-(miKAlIjpt38e)hZ{w4qbFYq*QqVsLUDpxM-u3Ta(UP5KQ4=phLj8pe{AO#;Gbk1nkuswzRsNJs zPIX6?TeBb9y<3xoy_?P5(rjuf`}46&64&l-$$lo?^dunIIkl`z&*obTy14h1wtFDQ z=}Zz6*oD*5YA|_7V=5#|ih57=84?*!;>HsdjVSLbN-{Hl&z#A&lG0K>*k56GLNRAW zq2GH^N4HVp1ozX9k7mh73belzJl??pCDyCnwO6TH6KkB&kEN)te^jCiL-N|WDW^pV0bff)qA+cr_S4InJng`xLlcrY*&XB;&x@1fs1k_9N14MHi z6Kq=Ez0=O|_%o5t#PPY-=NvyD-{gM$e}k1pcgW|pdP+~miX9%sX5JBB1!~AMU^mi4GPNzjp_dVf`T_M2r8(m-o2FJpw!T%<39eiL3i&h zB_E&I-QS>a=7@>(e;K)(jD*4sqh>8%P@h@y8XvFoU8lI-Lupu<<`EW1Rp2gG;JD}D z)ezgM-MOuKhL+aZtW5qLZ(>VCSvC!=)KM@71zr9=8s6B@c-l=tD;x));-yO|BcCB( z1MEO77V3~~`_7qyDn)j(lC`xE4!R48ZZ0lOsIL|;a5FJQuK#;8)g1hew>3=tbjrVe zVSbjEmcq8Nwwhn&{D-S3%BgVA@L|bH=?0y#jECZvu3DtK8Y6`uiRV>b4$c=qD8cvc zy%M)!pC|i#;XHFYy_l%l0-d%>DNzQNDfatjlhx{W!uer}wZ@>v^qWQ5M?ayf6-} zwF?fm;Ju_FCok{0D}aoeQ)*P_d}7Vn3Ed@|<5??Zhm3>M*OCH~Pj*fmTieC|`pp}{ z!%H~ZF+e8Fnm+!~aKe2GlQ{Z31qHV?&p-kaYvC?PL@gz>+3=5WOE zvPK63`6e;tu>egGTaM}3pf_h;ll;C@i0Q5Q=1-JYRO*_TghLy=3!d({1Va{A0pY+T zRqCX-s=@K`o@3QYsj2&KMgh7+^g%;^f3=eFYF>^W870k&wOWbezxn5Wy*YWB;-H(1s3njDqCEk>^|l+v?sF8X;_ZKZ9dOr(gbIe zrX44A8Uzdqgav=&~NVf># zGvm*sv`E$b7Ur&83exBB?Li8)8v{@C-}i316Rd1^fWgL8u=u2rbxF=wI^6iO6kYtuC2*!u|=UC7?W%i2%}Xce&iM8wfD*l&X6E-0X9Q z*Ss~ofx+N#4vSpx>9rvn!H7SK@TdCTDcq0~ zF}GT%y0>>M7~M85bC(pl8P)kz;^4$|xo2L6Ie=k|f9Azv!mh`0(^b}1T*D*t-_^IB zdnsk<{%e*~XN-)9?jaoX!o=5i+qU(}McrF#=+37pwfX2{tj$_*nWo?>UHd>v^9Lrq z=V{$4sg)mlJ_q*=`kcm%@949}8m8~rNZ}V5#&A2}Ht{*vhJ(yZuje$XK&(Ri`S(H9 zkkPrM$kQ}@e|1>m6AhitiHzAO&lpB(;w*a_DTH%d*|&haFsMhwm5#UF$>l_PQ4up1 z3uYwAMLtNLA}`-DLq#^O%zhmaWokE%R~}W`=R(1=lU!qWREyX3qSQUHC3KHUi0> zdVGv=(otd?JO}ubY5MQ@dG5JrMMQ6qG>nXU^KV5hUECde`TWp#nN9D#7x+na4R!h- z&RIvaaLREAv~8xNy9Jp))N%{juHlw8HiQI~Knq}9E4JD!^VZsG=usq@Y#cqCxVTiF zR{!_nBl7C;lq8}Y#7vmSl^F|AD_Rw^zF?X|7x$^+ZF6=rMZJuoGmTwRX**! zrW0CEYIsaT_f}hEh)UY(Z0^vNlZaO5{g(tJudsTYu0}ygVZO}q@AH2+S&v#JcwsN%%1Lt?-*=R$JGR@2E#vuf(KUR< z!Y_Wq8NvRr?(KOm<&Gq9T|^&)<%5>}Lq%If5wp+41V>!rmgj#wxph8!r+mFe|Gw>2 zN%CnjgkL7eVTdff=bv*M2=dRbnH=cJ$tm5CDk`N;^r;Z$U&S|oXNP1D`mbHrB=svO92XK2s7V^< zHA5eDhYpMPoE~?e@Za@ALByV=y#7NAYnmJ#*2zir!-qiMLNYY`6x{f;PEqpI}pDRA*^_v{J z4v4#DRpV@CV#nvt!LYOdEkvrGwUN1r4mGY~oI3|+#?GzQw4`Qi!i_BOqKKRX-PE$G zhL-V`1BRRAl?MBNzlnV@EkCT_mXKBM@KkumoxAeGafkgLcu12>zs+tH#b+HJ#;4W_ z(*AE3#*CB5hP@42NMC7xS`y8Tg}n{UL;7khl( zwAO98r)c}|kR6Xq$v^-aLQ-Aa`EN6!PoAM!19Ik%tpcBaNuE=U3!Tp)&fDhZjRoZw zgIJe%lJ3&Kyth3_$E^2UGE$ET1)baSr8{?QPWR640c?3KK1a{NF8`FicFPr;VP$zr z6{%I@&4KobQb?21ahH7C-{-8$|8Mg!O;8do;N-TulzR&fJIkGMG7GPDRZ|ci*|KlQ z@j9)JZ?)FXGG)`wqt-8581C^&aL{c?Y?uKwgSJ8*irnKgD@LP8B_K*i&`j;mQf(fb zIZdH><%+4QKG$_2As0il*~2y#b?sB#yDHbJ(G0%=wzrFM)69=R=54*MH~Y4HnK^Um zQm=2HcE@EEQ6sr)SNIR@=F{+5%<6Ih$Uwh^Rx4n4+P!;HIZ^-J8qQ(Fy|Ku7E9`{V zae@7k-cd@&4OoW(7fqY4ctLk|}(%9-1Fp;qeY%mjf|DjKjQl4?O@MSe_$! zhx2orP>Qdlrq*YrDK=|QhI^eNJCL2NdDV>UiH+`=7q_BpdVA!e5=-q&daLex#lXgLdSPta6?dJNy*G4dL#Tvk-7EXEE`175| z8a>YQiN?*Z+IjG{C4&vkc01Pf#nld@3ET>*jpoL7VKoeVCax~xaTXU}m`_1p^mW{< zSe5#H)$vVZe;%d+rXwLi7E^jzVVsbbby)KpiqZ8<&-nGLG(qsOcE^4X zYa!apmx!V|2W8r$*mRfNWWoeqdJr}54VDf}H&Qa5ee_R;LX5&!CBp&em{W}=RPh3)d=kHNC;L>R)lH)|AH z{UKaJs0)zEeB1EsoSC*ZRqcZFT^049i$)3evVV9frl#)};UzixlYkQ7sz9~dqpnv- zzVhC8W}RVeO?pt6dB=_A{1bJr4fG@2e({6EiYzhTIvE;LoX2|cqM5RVKovi8+51N{ z6x+7tTK`w>d|z)QZmK_b(eV%OG+CpFWfnDCin7#Od#6$&zIv2LLB~;qH00SQtZKqa zyZ!XyNrf+KED^+@C&Gwx=gujhN3X=Gg@xxTe7Ny^`)KJ(R4vP8e}%tjdHVFNQf@8M-RU1g<)&o7Df+&) z1#0kjn5AOr9%+ZpbQJuQ&W_58ipfGQoDG)$&aU?am5}=KEXl9zG&|W}Q2{Zw_=Zzs zA%SM0b60=qlKe7mi5cDIU%r)=w)e5L+ZH@E=qL2Mzr@4>njl(94vC|a1r6&>>U&XV z;7=KJ-URGkbCCDRwCtp|Fatx&i5nboOiX1yLnJOC!Qwn|7ss3CdK^^^jl+kW_M&K! z%8AAqKz#_LJaWN|2d^?RX^NT=<(T&?gs9AY(zV&8j5A&(?~`fI3a9-+$H0>MC#4F^ zXCHsw83w5)(4UDy{WYNj2VO!Y$%O2HKYu*`^@U=`rMLT7T5=c~=8V#=?)w?G{a}8s zLRcIp3Gr-JTU0W-k92qPej7S6yvz?MO5QPyD1`DpP#!w&Ek!Ap{J)kW z#ozD0T?H^vujagnm#AfieXTbTYk96Go5gF*dSsO=)YcOQSJA!cZAw}u5ihIRYEW^U{C@f(*|<=h?pdj8%3Z6&@$Lo-UVZ{N!t{lKcxX7StnOQX%B{^~OIQ47ui zCKUlcXRDhda8%A%1NqlIwvJJ>7037O-+u<>jUP%LSC0YYbX~Z|4oy^P8o;ak>LspM zP%YvK*1Y*Ih4yFXd37_$^fGdCemGVaA;J1G7%0JAo7+ndkD^CUNL@Y4QyGQy-nQ*OV3)r&{_-=&=6;LP9B|4Er<~HvuOPx%4eKFeu2Dj(}K3Ar2yf zNUvPELLwaH8tA|X9m+RikIqv$*bS!`<41ZcEq5cWK!Xr+4Zf|wm+oX*h_8N0g8sSG%6R3 z@Bh;R>@8`A;~^NzA!niBifza|eFbSnD5j0ue$v#}4}nC01BGEhVd2Dr3kupywiyVD zp@pLWpx1&aC^k02Bn(%k#N`SF(Y38NbmZkJwz}cuVp=?mvr%y4yYu%{>A@K{^z?Tt zyibvnFbNtA@ss9|KQ&oDuJil++3%|UIGFqNZQhxUHCdK~6WKgbn*up@umogo{N49p zpv<4Du#jVZGMoMku8m??*R^jPhNyW;2x1jM#B*_RX=rHpVJsRo2x`G^+#rbF zk3Fz%B-_%#US$(kT zPWyL@m9^jR4>~z~IQIW4qnSO)fLjm6dWho&OMN$YimgmQc?6l-$ zGQiKE9ufPrZw_?bWo%sB47X46`r&ySyAM-A`$Za?gqi zDUu(AT0}y|dzUVsvmP>ca0j-Eu#uG2)s><;2A2^b;yzowT#-|KB3c8gm9BA*=|rDD zmPE`dl>a{;!nlmZ75fcYNSPm9pcWz`$y+ZY=(0aAw=xlOn5sWWVMvk?6RWRXUliR$ zN#1lBSD4_mYcB?W5AEDo32MCzpF$H9XC*Z?umD0mnf}Y#KREcpKgfF09Je&<&fe$K zI{EY3J=#$*F{!^6Ym->^@eehaY=oF#uHs8f{9LK05vX)jut`Xc<2=qT+>pa9T~JlV zv2}JZoJmNhPH$pl3);|rPDrdUgkIg@acpc5c$_fnnA6dOx*9sQkjpmGDr1hv5Ni2M zGEvGUtH(ABrh&JQk8Q()V5AL1bycq7{vnQr$Nl8^$~o$aT1aX8jk8q`uvy!@OU=2= z+nF%D;3mh*IP^|p@P}hR{8L2Yiiq_w_c>k=DJ;#Hb73WY?+7wZ>ZE6@K8A(d37%2^ z|Lp=yy{Y-JddDh(;dXw`kVFUDWg;e}13I9s`X}|ew6lOKK;wXLS;fHH(kB%jJmC2A za+~`>K63TJioo*7NRFkK+ZZqEeNVPRv*n*zIsGE~RunOF5b@L@qxktqbIDF{f;J&0 z^jCb3?K^xm!t)QSJ`Ph*EPqpbOAHJQvUf-bu3i7cNkc;uW>Z~3%*tb=t*rTR)y{4! zF7PG?HMMs})k#NjeBX+V)qTpXjgE|WFydLX{3yodsrH>kT;F2=Sf2q{~+{`b<w_mgGGs2S!H)eKq&-&-F9cs21LuY z(%-Vcz&6MY5W&$QzkZ{U1`IRQgV_;y5tPtPoI1`*D5L$kRj@3(z?D>5W zoVp&vKOBLZ6)N#ZMV+P507d|sH1cZAS>_{d5Z!?g$9aIk{e&fq)VXFCMxOMdYnp;2 zX^f6^hhPCG5tp9+#Nwr%9=7_m|E-BCGBTr|NZ^a3k?)uPk*8iX#vTIID)2VHAO+?c zBkhjvws+tN2Ek4Lb>41@5kz?*LLLDHja(18P)fX@swfs`uO)3ydekj>3%D4Y^+lOwuv?#0)eJ z2s8;mL<4E7b%0`;+laDxBfPZyNVcOnbC>Y?^>?ark0nybjcm~nGr>3RzPFV7AvRaU zP0xNNnfbBk@@)SgKp&9vcSS>~6A7r-J`2@!mr_ESNv-p#gT2n5V5S8S5+%LJJo)v0 z+~-bJ`PbtS6kJLwgx%zw0(?A!lX7~SZJ~rj9}noOAUZt2=#E+dXxb3CP{&YEo5B4R zp1T^#3iZ*1hjJ|tBalEFX6M!(^wltYwjaNS;1!(up+F3H6yVpdgmM!CoCn#;)8Jy1 z5n|sdK2=i#qsRItE#-+zUTYHMI+K6V(^H&BVnedki_jjz%E~Htz2`1#^9^~cyHYO< zM(SpTK}o#%Ek~00@7bn&Jy5Smo8sMxD@nw zy%2mI`);2w=zZ|<@gYQ4sO~qx&>8y$AaseEozMl9Q#KEZ~Bzt0?|U z>R(r}N~+_OGVSe#P%gsgB^rOVxMKT#&Ev<%tIpw~64ug)C@Q$x=S6$uR&=ZVbwI5b z`oRvkAwuzjG8NPvvji4Dd>!fAhHf+GoyBS#0E@2!B=tHhus(_c z05GLn_EIiCp1T5R1U_h180LeO0(2SEYn#v;Tq=K=OuoGOU~k39nH4j=GvUq2IN zWx+`t7WQRy?fh>*ij)#D`GticNtHV;n?(HOd)-rN$$$eYd_@PD6&=u6iad%o=b9~P z>h^eeV?{2NkfOk!tmD=wZft7SVS7qK!uACy?YzQbC87PnEpJU7lBB?Rpp+_aR@`m| z=a6@70yJSj%&TDJsi&*^7A&XVd{=k3H}qPDRYPY&QyK(ifb(hB3Ycqv;7jREFaW}= z1z8I%$Gjgp^8D{^d$%NFe7&xYb}-t`VTdI}Z0p-GRQKER zpUv5{?rv4Y-M@M=W8u~NiVB_azo{WxlMOjMJjSHA1-df7Smb+HQl>;uJVWht(Q@&4 z)cm-=DgtL^wFgzq%&v=4dO)B64ZHmXW1$*0?e+O=*-+G#L z94wsDb)-wfZoSVI(74TGg+Qc%HUA(b(Ux)ONU?<4hQ1Q^+S_>XVsK?+(U9{$H;voX z;ERH=(2ka4xkrlvWSi;P0Z_;ydp~{b$D40W=hL(G!I+Dd7?M5yJL{O1wC%6qUzNfZ z78uuaM2cm?a9eAQml%#*G54zTBcz|NJXK41M**&;87TI^RN-(Z0dyKR%#W1u?CtT< zt$TK$z>9hYed^u;uN!*IjEuv;dnVG=9l34N2kbZycPUbv7#dD4-D~*``2$#i3OQ=U zz~HZCKSsW@J+MEw0`@y#1i+`Ql3rjmFCb-wIF~nK=z(XwZSQpW`5%-zAAv?b3TWsQ z5@;(;$DM>sUyb*B(eHRnAUlbS5;M$C&)ai(?hI$H{HW&odE>KutLJ|%GT7Tx*NtGh!TPm6do_eQA0j+u$C9L^q}FAe6`;lW5iN}m zJt7QXL9PMjP}^mb36A;pj``lgi;ee|&l*$!8tu)Y49hPU%U|qI3 zPU*Bgn@_>f5Wbic<9G*5V9Dlq}ifq zWiel)qn~a(JVcJw6{At#yu`e;3j0b<{hBsb>?6IApfIIL#MIuI!Js?w1ngjo`zyEKJd=%82}$%eJ9a2Uf&u_PIvswf_&W^8 zJ{8;0K~Ax}FZQC+NpQvKMgLBH(Io zo|h3oZ1NmN%?^aa5LK%s4cqbG=gIoc{hM5fde)&RQr(rQ+st+e>4*f^q6(n4-08Pu z(PC8%(MYnG$;&IcEIkMmP9fprAHw{lu#B3w5xCR=@F?yVLD8P41jl76ZqiQ{GcTd6 ztS0WghN`Hkd)SAfmir_s_MVEnpzV8HOjdq=H6T=xmY7Q2=vihXq*Ej;_62}h zuimqJmEXS%`ISmY^7-fYJDk~GpI13$6bkJp&{uGsqkQKM!1homAnRsJD@G(Fh?&+O zuwHr&)k*|tgB-dD13wZ+gHH?kZ$nd4UZD1KZ~JdHk}g4US^sJOr6~li_HoN6mf#~# zFZVkw%Yesn6vfQMq@$n^{F$8|#dr16J6}3+6fkx-Y(N_ec_Vjc$8eno$pcWz8>8x$ zJ*z0y(cv9?e@65bJNx_J^-7<4v+_K^t9jUj*e`Jm#@Y2Dmnaj2Qhe)Glql2;8N*jT zCdo!}@K!_s)cGEyCqQnFjh$TwdgVY^z!$h2OgoRRQbAT1Ac`lN@+xrPJ0l;!HoDvP zi~T6VqEOowBVTbLq$IX)1rKsP1>@uTk`Io)l16I}vmh?_k019TB0)OqQEomn9dwH! zvMWzNE8h=#ka<_!B-X;Sk@BnQu~nA3b??P8PWrgw=jP@CFhb7Z76X7;ahJ0<7^TAD z@$&B&QG?Ud-55Q%VaG%FssQ93!bZfdkMvXTGqA)PF z?$%22nJB(H58(hLqdr5UBy=?TLaPG!v3Aq=aYs#PC z2qQf>!h~-_bKoLSC$9>XK}BGx@JV3-D2-k&FboA%-Zj+250C{`sLIn#ttk#Xw;G1guxVe#HY&672 z!{1^P8aXov6@ex9Di@*QdR3JKDb3w-|nUya+w6!q8Q)@;{fRaauS6 zyl9uIxw*OR;9wZ~`}Zugj3L$^x=N7KWAOC}P=~}@x**-h(D0!dE+f&FeCWeeARW(8 zMyuqs4P6oHEGY@(d;YFY7e>e-#RHjVVgayCuo5=5wo-(`fx;F*Pa35Tr$qXbKe#R!qvgYPVwY(>Lu()(TBq*qRIjwH_ z9CG3J4j-XY0G#+tkgx>J$WwqV1z;T1DuSe`ze9h!7f|+2L0K$r@1V#nPm^>n=4W2q zQIA`<98$;kIt&d@ep2;))ZbsAXP#l<2grJavKSW8fvCXN?Qp<&=pxm~Hcz1XW);qxFuPF7YW+$yE1$Oo z`bM)KBv|-?01XJpA%b9eoU}0O^wE@eUYztedkvt;uy$@8F87a1{uhXuidvt&cxNK+ zN#E5&naIOK(FwFb^dKk<$=Y{7Bkj+ASi^?^>&M|N8^3%hVPTOu{HH8OF`)gdlO>8b zDmv)ztl#5v=W-1HT%!j-E@(gjiU{=Ti0^-qTX#Q%%aF+j92U@|Z{+tKMV**qog&Xo zN_s%ebGEj>AD8#Fsh|p)f#HjP!Y4tyHF4zhKNKI1_i!D=1J9MBKZoDd*Z5PX98&ZL zYprdo$<57Q6c!q3-Ua+3Gq2ptC`d-noiJSZC)+(cvZszAIB3QAG{WdUBF z6*;CuSPa?JnZw=x8?df4&MRb~1o0kLElTulCg)nir?+kd6;8-P(}n(8)zBMI)Yo%= z1Swzaq+A;%rHRG}+z1Tu<4<>pfKcs!Z*=SEKU)TpF;&U0Gj~7JWwdFcqzJp z+EaAR&0lf&W~(q~@$4^j3PM5_l|7X3Bov(=BO{TlH}uPgzlwjyH!|GGwlUB zy-7KZ#WktSw6rR22+~1i=_lAY9U$cY-!&p~0Ge!Tgm&vesJm4`8XxIrhq~A?)a~sJ z+JR=W<@k7=rtf}0EAp|E07K%A~{Db+VhCEA(VTOre-F2U zE9}OrO9BG)Tx_R1l$0FOv$j*}>yd5CF76pu)vGZ=aplStkO4yG|LfPUO&0El*OcH2 zJa~QzTI3snngMzKgBq~{CFRZ~3U7X>e|-*#pE#XsLVh}EXwIL#zrTj+-c?HyL2;lI z`0wAY1U@+j+&_5Ldt&;75ja)@Rm4nSZvnDD67c+pQCyT1!w=-nTeh@v&h+wM&B>W8 ztlPhlpYwBUs3Pc&HS6@_$6V=TAUp+fn2^7J7N>V`bitNt?mI9pT;HHk?cRE?6;f3N z@-1H|Z=t^B>Qu-L4!SkrSpO(1Pp6gXA3IiaPY8MXqteoTCQz0`Qd{u!&>E*%P5#eb zHSfMdj7Kwy8(0E>2?BX?Aag~zS(=#qJ$XuO!Tk(Cg00nLgQBUB31Yh(Ut9BFB!Y}V ziWZ=v&``%>ZteW z<9FVkEf;BHq5gJ>0pGBl`@tl-w6TACb1BuJP_;39zCQva*uccFqS>&PEk#XoOq&~% zd1>lniV8~v&3!06kP;CayUGQ&fG)0$FHj*u9hDr;e@9TrYa=(1^$2S4Tm$6R zAn~LG@c}mo?vRs{ql5jAAD>K3PA0DWi31hmG_7TzhZHz}DS=^cj}4o$HRDnFT>im> z_t2t^ZI$7zHO}prUOl{O`em;RfU`p6KY;|7Q6^eI369v{1S=8>L#S`DIaQNlw}w2m zb6j5g_zd^tH1EaI>T$nRoxKXV1<fsLrGx`{GPQL?9L~-dA}PzGcwcG9=i=c<1yy`GZh+`|Kr8q*MTP8Xy3t z;sb;g#Kc}RPT3KZBY5q;5?B4KVZXa<&{>1EYW*HdJ8Rx5RX8`-?hm+lc?pSkFwA2v zpEyx+EOo#90_MBhR$IZWeOFod~cN#k4 zZOY2a%fXju1Ky#+q9Uz;z$1eZf3W~9H0|WaG?x&EuLdg-35k*04@?r0R z>X%C>6xkwLLQD~et!AK=IGpO@_3O~BbaM4?7sjS|S3v5-;m5WQJ{AI)1K>7$0B{7Z zEebBfSSSsHt;PfAA@(ZO!T%JUrHA!_N+GAA$pB0_cD`Q|Bn(q$UZvNi961)MFq9g$ zeepsYE$v`YRiN_ZhCQhXd z9Hj|b=4D1X;Q;^o{o$6BqqSOuMrldPsT>VTYKI3Rza#Xf=hnJSrq`wk!3j)##q7?V z=@gZB|6`T{>2mIfW60gTI@?i13O{#va?J;{fZt(so*Avs>7AXOyPFuE^Ho=xDNReW zbLeAK_g66=pg#IL5GI7{P}5_bFt-p^U|v14KHoC)-nI3mjx4 zlaf^A^+v}>F!9)P^-=iwy)|Bp_O>)lJB*H&#oVAwA9zKe*7V zb_${szlt5#)im!~Oes_fuYJUG7_Jz)10jV{{d&n1Gk|StE60(vT`zMElbTQd|!1ftj%IlAmvzU*kQ7M#x?G!LadDZ7hgK zZ!A61qY_SC=I7565d2kNE#2Q&Oz8WQY1~|1&MCaVVpNY$O3}5qD`3P+?(Y?i5Hiwt zrP_lrlsuD>+w&^+M)>B=@qS10&Bf}LN=G}P#MxeaqL9PYSvo-*Tv?^E9`4`go}$0YGLVjs-jT zk5`d__`5b+C*rK8H_`ZOZs>~#RFmzuXQwyXFfb^oHgmbcy2$7a;tqC!hGJB78b^Fw zDD@SCX^!yFn23~}HpRr$r|}74?Bv{zHh!Irg7ym9B-e4iLXMAj`A?k^hzg9Y$kxYK z|MV)tw_H|)KdF&j!}lgIVqA^TUY7neDh-Px0%fnh6zwm^Om79aw(+GG1yf&1=CzuRe~(wXJKm2Wzu! zv%4^rOp)VK+Pk|eqno~Z?O>rvOCgJ9FwUIi@qbKcjeA04WLI%Ne9w+u7cpC*0aBCi zx>Yq9+9HKqW;c07M8=Yn9_r}@GZK7!V1xQL1}my5CS(wk+$sH*$7^*m_8xWRV$Ic((u^r;JsLs%otNRduvfed-b4vnN|?-* zsZV5Q%PiB2Y)U96N9=k>WIC?vHL_-^-dqBGLa7<0oUu;^ipm-{r+yT&17#Q+$BiJy z=*EVQ2s&}Dm-AW}z1pDw5#_(}0m`Hjmm}*xvZJfV8&wtytth@ecfYAjV4SjknR)}= z5{otAo^5}`bLC3ne196v`fLaz3{m=OytK(em0#5#?ImC2*l~k~U9ga}ct#G{Q$ANH zXWi(;+swZoeL8D{z7ov9Nv?G>rYldzWp@idFY`5`iQyti9_gkwJrDy{7FHEacz>b8R~@)45_8`o# z><2N9#R%vX4Z!4;_PeOh zQoE==F*AGE_f;&C+F7xy+8-SptdgeSWSt|RQIc`$Q8X5Mxln zH=T;dBWKu3N6UjNVw|2k*{rXtOgheADaM1j69Tbh%3=R6ydy$0^U90V^x1#=%$Nk>AMi@7x z?PRR7ZLdyFb^sOT$@92`GwUP4OTiar9cHFf>osv&H6b)B1cFy9x(~`{R$X4IE{vBX@<3hZ{1=KWLY`)%SvTxa7K@j{H~L;n$|P^} zD+o5hukpo%8#t}aHH%lQ&thucow8hBCfGRXI275G>}2tXEK2xgC|!y0@R(jxBEaro zc8r&r21peUK{G#59DjWbd#O)}m4la?L+BijN+%&wOId#o7ij0RwSrkyFOVy9-j2wd zOqm?z9hmg#FAc*^Ho3354E>u6UvG#fQ0S>*8>7b2TB+i82qIo~a}{oHKPq~qT$3bC z%~_U#j{DjE>rs}fZ}`k>1}WTtK}EzUDblV5#e`pY*U zBX7S&Sv_2%Xkc}BC)8@EfHNr}Hnuw@IJLr4W|sI$%w2SFW!$%+3UWTD0`JD?R{ZKr z7zHJvHIkRzwDb1V^Wa2AUX^W;4N;xer1rXhkLP{(c(q}qd1afh4H>-{$Cz0nSyXR^ zMUZ!gr4U6?a>>Qp%=)ff)-Q+z=Yf}IS^D_;qA*;v6O&UYsUzjHjBr}4e7uVquB3P8Lb*be65F-u2V-?-eA-j` zX`G%-3l=*UuR*WN>REy}5C|zb%|+oe5@JQs1QkkC*xT*ps#7DBUq1l%%YmL)l_k~u56i!z)+=Ln_6RTCObA3#wX@o^o>uV zLnA|9M48K9gwsG1r&Vy2(3f6CCD3L#tDoN+m&YJIJ=t3*HQ=wJ6|_J2eaWyjsVcL> z0}g{Usyh-v+4{AmdXLDXga}Z{N*P=+(tX@>g8DzF$D#agbK4RdqG z>kH6(Y1N7+q0E^Il76hNhuxgfW{!y}N1o zJ+*uuVeOfJYo`I=ct&sa;D{fhaHcR>>cfA3VOAs@%T3ru_ZW-6XTl zBpGg}0pWI&j^C5pF4Kz6+r3ufo0omSB?uBNOjvFDQZ&2V=vNmLzdUXP8n;O^Tkkx7 z)px3Zz3PCSzZHBovk^j|2jP%n_7s@y8 zL$H?!9yfn`Mux}t?^T^5a|7lPG<+{rb7#i29$)5zzYCV{sZpEuPz->FJPGdE6j9!M zT7JrWiM>>hasJF&7<>Ch6{TNUN$4e}+fUpXa5)nR)!Ca;r?9W!0!C&1%c_9RW)JXOaEt2CPWR4Q1a zXwBd(^2pbzkaUfk&sIZZauXgi)|KeLY(m|Gi1*yA6JJE(M>Q zyw$j2lLtwbqus}G0jLEG7GaIK4FkcV)QwN45WjxCM8h?yQsh&vk$mc6%FEo`-O4Lr zwo9YffXaANbrL@xOwGn(%0O0Ps!j29{!2Wm?7c5!+v|j>dR`Sl4)B4vhX=*5j;l)c z*cs+4va(M#HAdlg4_~A{5{Ic7c>7BAAf!L|hyTl)`hWk5{d0{Y%=bwoO}LToK}$Z7NWcH=&Hn+? CPI4&# literal 0 HcmV?d00001 diff --git a/localization/pose_instability_detector/media/pose_instabilty_detector_procedure.svg b/localization/pose_instability_detector/media/pose_instabilty_detector_procedure.svg new file mode 100644 index 0000000000000..ba45b1f52600b --- /dev/null +++ b/localization/pose_instability_detector/media/pose_instabilty_detector_procedure.svg @@ -0,0 +1,316 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Get necessary subsequence +
+ from twist buffer +
+
+
+
+ +
+
+
+ + + + + + + + + + + +
+
+
+ Update +
+ + latest pose +
+
+
+
+
+
+ +
+
+
+ + + + + + + + + + + +
+
+
+ Calculate integration of +
+ the twist subsequence +
+
+
+
+ +
+
+
+ + + + + + + + + + + +
+
+
+
+ Calculate relative difference between +
+
+
+ + latest pose +
+
+
+
and
+
+ previous pose + twist integration +
+
+
+
+
+
+ +
+
+
+ + + + + + + + + + + +
+
+
+
+ Compare pose difference with thresholds +
+
+
+ Output results as + /diagnostics +
+
+
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+
+ + previous pose ← latest pose +
+
+
+
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ Timer Callback +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ Odometry Subscription Callback +
+
+
+
+ +
+
+
+
+
diff --git a/localization/pose_instability_detector/media/rqt_runtime_monitor.png b/localization/pose_instability_detector/media/rqt_runtime_monitor.png index b3ad402e48ba7a154489ba02935817e050a39f62..9bad665db17e53a78459096e615399951ac91ee5 100644 GIT binary patch literal 86975 zcmdqIV{k7|81MOuZQHi(oY=N)+jdTDpV)SCVml|cZFBR#ckivOy8CKhZr4;z_4L&A z)KvF(y1$?2iBymihl9q31^@tXk`kgy0058`000aR3I1~>K~#!jZDcFq>|F4rKv{69CbSgL5ah&Y)Vx>(xV z5vo|)n*Lk_0GJt>Sr6Nr7}<}qBN$nZ(uxV0SdTJ-SU3(N!dSVEOA{%Bqa^?ULV%>G zkcvn4MUK0V{4&mnz;kEs_61);cgSzd`e$UU$|q6(h?F9sE(xKpY)z?kSrZdeHibs-x7|)3oy4r>qsj%5#JJ? z$iGlOJ*#jzK%L|NpxuF^)YRezJ^7~XbiA}msR5`WG?~Fg(6a+>b)#@v^q#)i(Q3QHx-S3)NNB7Ak>OGs-<5N)c@w{$`Pr{Cytv%eEI~8Ndw=da|L2B( zgK!gE8F~}Ob?RtfM5^WA0}{#b0t;3Z{YvzA22bsdgLY3KDBn4#wO61k+r?u+jbl?Q zY72?)c3|7U8Ekbpdij3gyYuM!ceF=?BW7k(R-o~zJlV`BN6FDJ>L#`C!>BgS^1!(hCgRN*pMO?ipv%?cNvuPyfe-G3mP zYhZSgeqT1r%@%LCsTxuqhi>s`no{$dWRmZWQn^`lFU~Qd0w0)xLfRr(%Hq;Tp=e!H z24@Z&jjyUeQTs1h8&gej28QxL+ zo*X-)GF3tIy;w?|zTx(S2zrV2OGgxR5TT%AA;A+i;4@(c(dsye{JsYL%sF;u+Tb=| z7}AYBcz6;i@bS%{Px@|eRg)HP5tXP0eb%CS2N^YT^;iawRA(vZ>9Lk2RJ{0isS%pn z-y2r)wM*ndyK_KD8IHv+0en*ft9ik| zH~j4Rq9mGWlV5m&;QfO%mj^D0!U{anm}|=4pRn4kFfoJA9m}O7Ld@tg^ow`KE&yVM zwTo!{y|Zsv2CR4un7%mEXeIMJ3@?d% zhAV}Q#Eiv4ClAH$r&Mm;oRxuUA@Ew+jN;qnHbtW#L?mP~raI}~xeVr-6e>g7z2NcL0%a)^iX-SR&IckA(i}GKC z_Aoj&Vo+4e(C6v(^~_%_6pu;45qR}mI*>KyC4Bv0!$<74z1ofn*V0U}9~+DpA@ z*G~AG(SjTu-ZE<2lr3Bj#-geDrKZx*4*26OG|9wM?T$G;-IRseED7ukk9*viA30z# zpT1eyvwKj@sNX0P@exie>Evy*f@{4Nm>lT+9-qN!SKM8UJWrHlj>YL*QBu89wiC#4 z{BF;RxBL@0685f)_d-vR@l?aGYKeroI!5>`@f@$5>;B_^hF*hLYv+=m2xnoi|an3>YU#%rc zZC|sJxtvWY6HB=U4e5%@`}^Z_8#T!9bQ{wH;Vn*f%Sx;)wf&YD`b!S@q;zH>VgpCg zxd$hLr!zI%_D40FJZ)}z1Zqucv(@hd~`w8J#YST!x?=dTnj4{lG)*8&VH@XRK^ z7uv-H2757qhah`!@0_i-oXHH? zWL2MxFobJfUiCu8fc0zmdp^pISwX>^QaVO|Jk^a^SfO#Q9|HCDj_=Ru?lmrIVF>{1 za!Y^epjU;xyq7ojA1g4Cv(b$0Dd{6G?_iqKsKvSqkTD!790ylt4HuZukQIyFZ1QE< z;RBXWgjc4AzapuvNq&CxK_cl9r&T)#1pZ`gx89+tc(nj)1izHJn`WN0r@Z?e2?E(B z|3;rm;@g18Nu`VFGF+&F!yCNcPNCVMrMjh&P#kxfPP}`)etsByZ0~*wuMd$Vwp^T1 z-CEv29CrGnU|Hpi$pwsN_d!`+jk!4l8Auqek(HYvLR(ieUrJw*=lowA@yl6bnuW$h z(vQF7+-%lU(=JD~`()x0iAH-~ZjQ&;9+m+n2_p=82)SLW! zH7<#@31kC`JdMjwE5Ho_y~`yTXga?fW6QKD69~WO=ai;Y5$&RSQ6GY2O&9d*(|q4D^X`{h$Mk zm=p7&5HF|+H`L)32KU9|?_)wHE-Lo-YtZsTA`VbS93;Qh$H9~FcPX!_K?Y3*DgFTO z`HB)mhe8n}b36$`6$6A$1NnLK0$GWkwDjgov2dxw2GrqaUjVo9TWZO|q8pJYZDb7b z9c)!jz_Ldvimi$02y(fCRg$6`w-$rr6Gd{amFmHYdmy;!b0Cl79(_Yg*iU-8_0)=@ zT2@{?Rz6_E#CatoJ?{k+KFmd!GW?ODpPBhxwKx}5wu-z?{C4T{zcbZd>OJ@W zS!Bz!2>s(WoHhAWtP`2)FeU1A!u3C35hKxf?_Y-U!2G^pm`X;pu_|&jMcb3h{)@*1 z$24dDSIJdjfvOZtRj65UfDO%GR6jsb7l#0$Hma?h4N0ezqDR9I_cpAG`y+5+%yNZe z7J)k!9Q)_UI(nh%i+Fdx>V1`gr`*}U2GcYG#?J(FiKY6y(zxZ*#9JMzNbov?yF+sn z7aEvcMcAmrZM1@G6Cg9{{p|rk*j>&C>Vk%($EnTfUp;Oq(`Y75_AEg}B0vfDesg{) zEc6V+XT?re|AbC^cy@gD`%0nI2)BIMKRH#mIcUb5CVoTULa9~>4=lqJ z!T)Kd>~IfDJ|6x4SD9)@$qM)B+YkLs%e25tmfYmZALC}HVo?DEAet@%07X-w1_BU8 zy=Jrnnzd4P(?xH=jNg?_VW`XgWte7&B9_2n5eDlPPoJo+vn}U$!>a8L-Qx~os92dq z*aT4`BQ_*c5pPqYh6No!2r7aS9-wA8gE>lj5gV;=Eq)q-tNnWn8@m5YpS1$iplbn; zp4A>i^7NZenjOiB8)F}+THvDuuj%?QnLaUC5gLMTFKAuPy6En`h+;EdyPsh?^nr?j z5r=xugqVksfy`28e59w^jKZJ?-1d|X+-Ng6U|77vjK`Y_G+LdBD}Lu2ghpt3-~Ni- zkPihE%ij8AkLQULr~pqk6n~hOr<&t^Rp2oWe1vq_R1)5G3V|<=!k6(}kkD!q#6MeI z4L;Ef&DJ@NeV8*Hj4M;_coIWVRvK+=c}6sh`&PoH+F1c!IY)q9(;sz?RU1Ff#=C5J zDo5VKoZ;>+6k*_FXB$euKrtPUDxXf6jcKMgBt@O>L^im333@-fKsZjLpwXlR;ZbU; zzM#AbA_dQWeRMqlU=a<_wUEeQmWI!nP7DbFpKMi{-oW6Hv!JO#t#@=Obj~6f%+tSv zCHx2rRgRG`1q^}7WiVs?HobQT$a5(dtC&O4Y$iYGPrS-MDSaN0+)?4e}Nw;G>(J*huyjC7`10-Fmon_`-U?{#l09nI%2BKNmlsLFCvravA z)24h{Ip{KS{pTeKG(PVOM8Yka>^B6LI_tr zu;lXmWA=c6AVstQ-Opxn5Bf)1b* zo)qtWJ=J%J>4%`BtA8#fTj?|ek!u$({H4)X%MvP2DNLJKXTOg0=OBalUK5dFXVMnp z<#;Kymq2GK)aQ^|BU~$)`usa8)}&y`vcP~D|9DzO6Zud$xvkzE!OrBFLUd#Eo`-%+ zilk~WtGoZ+&77ITCG!@IJ^Kw3=Sp|5K_1(1m7@KcI&?-VZ!o>52(iA6W=ZD-{V|#@ zFm?|MIS(6P3;6~c9n>Abk!fM~VhlUZGZjpSzq_^1D!3aO=bPE5rcl_gO{E=b^%+() z-4I{@c}CntPzOxFr2#CDd@H(+Z+%TK%px0@0T_2G(_R1<_~!=^&7OQwf*8;=W;OiNOwID|vh29>?aG$(`yNgB}8oE-?9x zhTJ;Yzxa=v^`QY!GqPvtwj>1_mKtXD6_5EWi}e7Nuq&61cGgJ5fMKWP(?xt~|C{RD!Em6-;Go^JSj=35qH8Le>&#`Sf<tX3bHJ!8?4~MO{yWLD%!><~9=*ap_Em*uyK$NA%+!PyR_#e8dl3uM-B zhn_FM71|6deBF?H`J>6ei@yeKifiKGbI;Ya&MrQtQ~=qpF^S&|$i?GJ@Zy6S(rOi6 zH|)M~ExNT>kPddllNNHb1RIWDLnw{2p6wHPGV4C;3X0S`xxPBQ_)>&@cKs8oB^0_A z6t`vgV<*ur>r7+9%eUXqgtIY7yGygFazniRI~hKG-(v};_5=mDpE8m~gEaM&>o6dd zt)r6#@p>n zJub&56v_4WD+wfVGt(>VT$Cbl%06yRt%%a)9em%FOb)#aTxMt3!*DN&%*^~0*S(7wA;lxF|CwIo z5S^-u#l?xXKXp8gUhbpNeDdGVh0eN)G&(kF7H%-Mg8(w~47{{4nw>&{NunOBR9x4f zFyW~;h1pImlCTa3{n9q=TNHb$gE;NVCG@Jc;~ z=+O|}{T0^HK&{Y3bi0C!?lbsj8}<&(75=4+7q)rBJLezcH4_7G^r#;E|&fI%_x{dWegx7)NpGujTk5%>XaWTV70FAOs}tY%$O@K-FeADhYW1+SsOU8Bk5s-&O1gy&j*Gts zGbCNf)9B~)Znsj!z?t?94*qd#i}UlVjYn6uE7*FrW@P6zH{tO$HeVUPv!f6?jW-=`eoNO#$b-05Ih`u7g zs2nAR^Ocb3`sGp+2L@CWZPG}Da2^o|=*f0CF5#J5R2b5l8xO*(H zYgU71Jj~+E=%@-T3Mk>Jx3@=0^9MS`I4&}M<;HA!!lL%!M2q&*4SY3TFC0vHJyB|h zezS?0aR*8~z4G$es3T!VeaFpGe-w{ErA_$p(_uYpWfqFISsDwFa8Nv z@^C7ry2@^b2$(W}%-=sfN&56QVA!%!XL7yOn?2im+z2gI(2!hTrvGI}lbRJP`ZGMA zfKQ~DozmVx_jzUoZ;dX@@gr4Q*4*#O=B;EL7Q~hv?a6%ozNa?j1;Pad&EAk%J`Kso z&exw7G5bCCUiEsC7+PhhDrYt)NBX&N{CdMxU@AsVu>RPy>3!2?D&^H0w5(AiYPw@O zw-yJlSgt1)>P*+F_QMm|dQ&k{*H=0O&+}nf<>p-7ad2ogIc-k~qZcU&88nlyt!j

cnd>v;ooUh2^yulV`(&Q zNCR+hmkBA=-CXL{gDO-=esPgJAX=M>QZV0i3aiV4bO=IvwO@=76wJ0uM3ad&fWGCC z>pE8=v&PZP6%Pzjh3BPFC$!$*VL%e^LhCD%H=(6K zOKLYakhB6-_^mxxWCIrFrJ)3_aK#f6{zwXU%+=TeXNp)>M?DQ7ps)f{Q1G}5u9ifF z(a5!lz#5o`X0!J7rkU|gSa^CWE$xq)LO)zn*G3uoRqAI*A%LfgGh;H@$ZMDUgHAl) zJbA2c`H%l8qbM|dMAWVh$%+Y~jo+H*I(<{{C&Or|<$bViH=;teV?f}~CJjqxBi9rX zT4;LSX_h3QqNvs7B*iFzIu1I5#G3P)Ynl%86YR^GKF!94#qeQ1c(1g!Wg|{%_)ky8 zO!fZ)fm_uE!L($JS`?7oxx`ua@bEFM08>zP<^Hkj7ILmN^eGUTdBkXAiUSXl$fnB2 z4$JavPlUy>C>fSAtO+7Wm9bdZW27KiPaK<)o}8Vh#jqDuCRmn9qJ)p6aoNlPGD8KseY23jCULg)yn3KA^=@~ zb%w47Q7_?TQdj3Tvjc?cqhx}RK~yIoq96O~a@ z@e~JOUo{e$bc;B!sUJC5k{2~>S%fVV*#1YYE-Dt-GaI397X2+eAU?(Y%-&);KL z3a0-g_JDk*ApU{w!j6H&#O9x&pF7{ZW-RE0(;o z4i*^@mo9OSsf^MQWetDAvN22RDJ$>ZX4^5=w_N<;^Az)NG~Jf|1ZxTN?$yBL<+qZD zpOfm(h`izoc+b1sfuLs=uG{mjWFD?s_|IboP_xW9vTS~Yv9V%_5X71d-Z)wz&&W)# z9I;xTkXV{(uR-SL(@g+n*_-39(J&ugxo%1OwjA&h)w#FbIkE* zQ|{oISBc+)Eki0Rv%(Zna769p_L0*1J!lvIGhDy74=&5{zQ>oi1An*IKi9x6TXM3b za~e*XN?LPSIlEy{`kg1Xh3U50H_uW)ofI@Z6I zmU6~wu!(3s?#yKsh0s>eNs$7qx2nv=lb-Gsv`>?%41g4p%c(}eqy3jW(am-8I~Q#F zjWEN_jvc3yvi#BJ@7F?_!{$-!hi%{Sh0azWbhUtYO?MiWh0m&@`N!qfTQ2NudgI5* zv<(L1HVI5>z_u(hZbb5T-wx`OJoBhc9F%>QL(8}M0vd>y+NM2}6?->;0%*&0t6m#+tN9r`&q7zF%b_bFYy#tmigG_%H=^J7y- zOD71}t;ClS@p4HCi4TGsf;GN)52s`B`HSwIG9Uw~zhQc4NRJ}4i?aTr7jM&bX>N2$ zzkk1A+-P5k4G2S)|%BNWjFn(LvQl;bcu{iScS%~ zWGB^q&kwx8(u{#dBO0F$8=f9pv-jhY#h-2^P>H^H_^dJ@*8DnQY`2?n|5Hr+jGsxO zB`hqwCm=QFv?w#2@`+RT(8;yp^7w5b%^xWcdwOIhgZ0Jc#!Gq8h4sJDxmST&{+I3_ zLbEYUSWWu(!@U0$3*Z1ePplf*uhfLwyh}*_>sR4`xN)79)8a4mg=SBSgNvvLFpk?{ zetCZarge_JlWu{uq|-fWnVfp?nP2utWJ}@EqJS?QOP+fe2H-{pS?fw2K z-JApQ0rIhvd2HDLt$}eb5|GDJbpU`Zy|oRegw<2kfOtc=Z5=Hh35-mz_0o{T?9UFqLEhGdw@X2# zw3GN$x(+V#L1n~;0Uf8p3T9~$-PCb}Yn2B!YeT--dI8@s#Z8?CV)MJrR=7COvp}xr znfdNSMtqilvoZrg_ZDy(0SLGHve&Rj7ulH3Qz8EbfaG}y5sl_szwqtBnlqKUVs_=w z7O4FXgg&H}XJ~A5q)fRr*fEEvC@_g5hmKA8FVzA5EP~9P`L3hUn3-GUHmq6=&Y8l0 z@r(&39RKT;KD=;}5?4-QFe#a$&G!Z3f!Y}8Pxc5x_nXn_XUx{~|Ax)_my+1>Gr!)? ziWT~|aIK25kEVsno_B3<{e;j-uCB5}o@qS$#VP|;BcUyL>{yH*HJ2j~PF7EphG1H- z(VCX7Anmv~j#pTfd7tFYV={$m>K3*7t8Gw+ZF+Ru92XAAENcD{JDo1*+@*$<7Ll<^ zku|mGmCc)?$MH|kn^I3Rd||qN;N>fq8=hXouj%7X-Nyb8_$-153JFaB%WVQk50M2K zA6VFer7i|<$yJ?wT{o5(|NOM?2s|WE3rvdzw}Md*VI>G`US4QqIB#_e4=%wr+ZdG& z7Zdfz2FT7r;&L2)TyBIgQi1^m^snl=RQcoXjq)@c6x_m#xM>V z?VHmfo!LRf4r7z`cN&lV!_dx<9AWBp2MIxK4V#{X5`u#;8Y*tWF!5Eak;dvi2X?jS z|J+obEwA9XaKTPr^~~SPryEs@_S5%I{tbf&3Y0l4utNlNgA_M;6{_X;G;2Azi;Wyu zKtoUb?*04!gx1pgm;NmF1>$t!cdLAZB^J9EmJq)EvN}9Rd&1FYS%`l>w@QsQUXbO)8jM8ox zlAJi2NjbA(qJ(o7nHkEqf!W#TMkU}`@0U&8NsoU{02A!EANt+B=V48wz#gu)E*w2~=zN0laK z1vz@k@`CtCI`p7YQvBUFBSi&CdGfxC&d-?O(~)^;3o2|jW2ZeYIp7!vse~BBwqETu z-n8kfAp;NWgnr!_ekwV!IxkF^Y?$rAFM?S#C#tN)yl=O;b4UlGp#%iIcBGRi%Iu5d z%{>O$7nZ|ra*<;$AzNI47>?g1^OkDYloqJKvGaUOEC~`1_go5`&ul|HbG(Ho@Bcfv z>k#zd0pI2KD=yEC(bic-wjbXyZpLwV7^8yaKua%qf)OqTJ9{blhqT@#{m39rqm^Q5 z^_aa~=4jL7g+;Z=XoN*cm(Jg$e>V1|rq!DDTonI!xBKy@t<=(e62R;((*6rsfXia= zOpNdH!pFXlE?yVkNRc~3fdA7v9?aLudo*Frf>|qL+P0R_-BOA%OUd&R7@e6?s#{Ez z$IhIMHKR}rMuH*m=S2#e?-}7HpL^Yo<)IkA2e5|h)LTjQV& zlw`R z7Ydl>uVsNCoZY8X3gSgMe$mBu-ac3k1=;rg(hGCbA-&Lvyl zKVByfpz_F+7u8d+%$E}gS5}t^n1piGUJmPq4UmFsrd7X+nzvY5L2=?AnggM5ID77H zleb>cLU~5O|Jz>V?MND`0LuOgMV~9(1$4WK0Yn_eniJzWM861&(;SqNe_-L*bE0t8 zBA;@w0Kz^jVzRo9=%7{84ai~uyRc-R<-_p`HR7cGVwkAFb^-JYa6pLP&}ld%ZmEaf&Rx|;2xyTeGe zFrsPk!N**H@}sgaQJH%>r{`{oe+Voq%wl;In8|v1zXUSE5u*M&itmh#7RD6l8T)^O zSQCEBUxOoqJGo!DJ!KZT1rV{|N2txy0<_IBBKc&f?*Hx-doG?Bj-;=D?w)DkCJdYgr4 zuZFJMa~A(L?f7DQAW_vZBrHe4ELc0kP>fuFB&*=_2D|a6;#lx7q(GLMhrwlukBnuB8elth;sTqJS+jcuS12zQZgCuGPP2C=p-Rx*r|AR>X${zjf7 zSss0Ag^@HX15xuoW zi$B7pmTH){p-+{jWe7MWpoC<%okt7d6&HnE=5Gj7@NBoaeiPK2waBZCf5^Rd>E7pa z&oCDWp|f2eJ`%kD*hOp_!j3{VHktIh;76}YX})$i zZ{$e@@=1ogv;sf`@gQ$^0y;O{&4J?`jXvs;t5-qMu_diu6HeALK|qb7^dcio+c~yj8fM!f~>7QCD zSW?pO$qmo2f|x^N+>cKLlW>!a2;WY5;RpI?MC&obUYae&bjo1kRfV>R=e;)q{d~U_ zxnvjSonbWPKFx{XSz{9(pKUiNyXtQMS&rDis!lvaq|Yr_O+~QX_1g+V8#G(K|F?t=fZ$kQs>pc5idMu{4!2Kb?LXMxn9+=tP>dxdeZNo9OqS3XUyf^$EGY<$ zm&8F9alc_dTL}J+&hoB}d%*X~d_cD#neG+}L=WZpM>gW?GLrSf2LYP!mSFTbu;bag zSuvOEQBBg+3_i*}9nRXo@pw%FPJz{C_@Px-4cbm0+8WUuo3f z*Z@XvI}&YuZJ?-rIXVq37ZR?1aB!P^H#(EpDxHi_4L>gKk&j3{MPvqndT%|FkC9n6 zx}CTO8};6L1qPN<~A&)WWWK6)@W1 zFrB3k4dZcCE8DI?0!M%qX}-mqn>&K>L9~nG$tpE^vEs_4|3EZF^KeZq8Wb2f4~}&5 zf?dg@u`t?+R3u{oHe02rB)uQ}K+xcsjXaXV0&9;tdLqNrVT)RbJIhdKWC~~1+vd!@ ztbCd8laXu}mZmW$NUh$?xSu%?6^tnzW)=k+-}H7ir0Z?4e; zC1um2{`sje=f{5=o+qBx6UR2nJ)Cs^sI}TsOc%>syHYbmeY$e;)Se4+)Pyp0M6_$A zE^hwu^N&UyVePlMYpE~Yxc|wJ5^7Gt3C5Ax+wB*Pfd0`=nU8X+e;K9ge+WJk;ewej zL~2@$>g&)yY!<2~chdh)3i#_2t_E)_xmb6yJbA2~xv{uX9+T(WCy6{UOxgKG?_VOV zS!Iz@&7TZq!t;mBpum0t|>#^r76OrGoxcjc;|ACoGaiVTwcR{F{EUPVQ3=ZDg-_PDI z1q#-sD^sGhygHb{9$=PN^2*TxJ7dh@;D|L|kIHSDqbz52H!@hvjuCV}^ZZ)uMvm65 zD4SiGYyDEe=lIP^=J5SMUv*|G9XlQ)Cj`f3Fs6Bgt3(QhvJLiK5DfCgbMmv*)jlwd z>8is3;f-FR{{GgMQD1B*{-#XqmXtV<#twNsMFO7Y{lDyU$_J`g#r9IVzAu5PvBXZQV!^woW!l&+g-h9<+L7Wv!g>(1Gdmjfavvo~CCz;C#m z6;M9HSe}YgrBktgFG7`3p1XUo_ho^30Swa&%?+Wy_ITG#)ylYYuHa-az zIMqAEwXj~km}SuQf=Aq4wTs9N(8fmw5SEbb9j#*O$eRUPMw5r|zrs)FwZ&iz`NY|h zWD!<4>-)4n!hfwE`D>e&8htN!&$=I^X}FLA8S$6v)vH5A`Xkv_gOCm54VH*J-;iEG zvS0RsphO&0gUmIZ)7tQS1L__xU4LQfxeX!dm;=L~Z#T1kBflU* zly=8M578B{Ig1($^u1hKdGT8k?2dN%ML^yM#HzvNbR$%_Wk>Nrd3LcsxI6B=8(Qdh zvPP}1=Z~jhIO{2eQnFm$LBm!N03cZCXrt9dM^3|UD3>SHdmA})4uL_5j!SE9;q1Ce zqfU3BXz|w3;0C&OEKnl)AmIGl%SpfdzTRd>q(^x>jE3DKHN5_TTt7Ypvd7EXa885srJ%Q93ve=q#rH=FeBBOhJwGyewzi2 zCA-_drZoLROF|+?Kg9P}6d8)UE?FT8a^p|z6~zG_j3D$)gAUOY;%vCEXWj2 zezide<2aAWv-LI{k0P(*<%1Xq6VGovgsQsM17-&JJb_ZN(=nP)Sg4G%N@le4=rr&M z4KAFVTCAT*Z&c5MZ9>cpOXL~d!1`F%2<}}QoG(@TWbk=EIb5vNGkh@}(qcSU&IpR* zrC{^Cfu`iQ1B6lfh9pTBTI)-bVi0XsEJd)#N=wqKGmVbLNTtNJ*nL$oJCG1W{n>qi1g8=#!?_<3Cw{fT(zdt}<~taA zcZ%naZz8qy8Xa)cEyx&QcTV?tAu54}g>o%m|zpKtuyxA7!l^7f?X zl6qJZEZFE)nLb>qgI!KUs9<|3s9ha}jf0?O@eJm^#bK6OcDy?Dx!Pf7nOetEBvnw7 zVr}`fnJ%L=v%XGo`#G-HG*@PEbTX2;*}K~Zq4~&ow-pCvqg()L%PM6>i+75IJfv9) zXHqauE(vmdk=;N2&)4!N>BIVX;w-1s;TTWk=&{P@;J-lrxBfM2dcAu0PbBz9<@w@s zaB}m12mK~$3fjz8Vn~8SLG~J{_6^jxSa39$=8a zAw!)PjeynNT}pKTU_!Du6cAdJp)uiKY;oM@LMp4N`MtdYpCH0q9_G~7GnLY8fzAZ)Q2dOUi_oco5fC<=*=?5E4L7|%BYG=7D zEe_4mb%s%xpVTK?JR8fB+v8ahFaEXptRCt>#3q*qC<8|tFfhobDz0FR*gr1@RN5<$ zA^G{S?vylPV6#Il{KuOp`jZ^n4Zrx;GBv?LD`+n*G9K-}`8RUYdGd7PIvAhcu)R5S zzcW=;xy3#cvy(<0Vg^8x!Q3eakGs5G__yy{3{H0;UTE)Uh8OlV#7t$sp$#7#TMC+! z2rAuk#zYW?gi|x7tNC!tVX?jk=+<+{^LDeY#$f-p(kNDH`5BLHjh`(aQv}Xwmfqg|vZ^ zUR*%b@(!FckciycO*kCw{nF`j09HOf2w6u1@~ywx_^Er~zYnVk?}8(k+`M_97+sU^ zeAP#m*+Kou&54bixE2Zln%j;USo0=E4J0sLzZCbtBnYlO*AkK73dBlU-a(3u==MSp z8{b*+0e2(dk5XRVcQn*$UQT1638SBw-q{<9=Ir$*9Y4M;9(~bgG8`t5K(d*0Si&OZ z^$F3=;t$B%2UhDe}PEv*iUPbVbpZmQH~0gV>-9i-;W zlyb=rtA@`fB3vE4D7F&zZ32er>p0639ASG>4@mjLcW?omUM^GT%qb+gC}8AyKVe3K z?Lph?ucRsXa}81H1DASEu5GP_9uR<7VPxHYro2^2TssSqd zQ1s)@?dGl~jvi%sPwFg7ec0iRu}~RONEsxD`&9%43-`=L%vqkxpew9s1b^pWg3O6^*4^Q3Qj8^50oY$6)~P7(;-HW6V;R@&#~QGB<9PJ%r6%as z8_(~i!g;FpViASYM+#vaceYF#bt5I9!Gp%7!X6H5;dW#<$&-7^-L!W6Y`^~a#Lq^L z7oF|eKh6uTS5$@@5b6)5C6hi;IQF`D!x5 z`54jrlDtCMmHWX$_S0&2(Sqr>J-?0I(-K%!hg$M>w$4aO3ipTKm|(2oI+r_JZgO(g zN5_fkMhk3#>hg7a6|faBhfyPwip9XhC5{qF7j~@vYhwKjkE6-1Qk+$4$I4yrC7}en z=8%>1N=U5iRioIVH;;E;H%q%YiELl(J#Hc28I#{$EA2{KG#A0e-be~byGPU*coJ{~m@3^`N#5%lQruvsGo1g?uP5BLz{5zvbEd(l#LBcX zf9xK&UV5wDjxuywV9KWufp75Yf-$k9{}l@m43k`yUZ$dlz|QvKFhM^qhdZOrqF(3z zPxS4xD>)|`p0ReH!2JN4<{jai;jHIG|Dx85K%gsSeQ?-R_^U%icE_x12mNRuFVuhr z-Y-P;o}_9mi4|V1z-U0yr*U7lgl)l)8H?x=e(dN&o0=00^k+-Ahw=|1t(l<$F}=}Q0Z977%5NhjkP>`cojP9V zSiV}Tc+PnDLcTFlN{NUhtR2QJAvj2+d5zZ)aemKk_ia(I=k1j=t)=(Zui)Qq9%MMv z+L1?WZ97M0AZ)oPBl`+KOvf6!YSNxzW&?Y_3YixuG)KDYpuHvV>h<7dmL?8d{TylGQRm#N~=w zolsbBUS3{;>lF&s^}|bLjj7&o%7oFye)g_U0WD^8!(9P>)3F9sMx=bH2vJxT9vFlf zwOS9+$@l57>qRhXCklmlQ+QHRL4#oCXw^ysxJ(zFWpAeL+>$z%QGQyXyRs7tKgt6I z6lYAj4c@C@q~m(a`_etQBIo0Nvv2T3b>THc(Sw51?5K%mt9gv|O5f2sIX#n;Pzde| z0tDy6=GQ%y0#;>N)t@wDv{%7_(!a(jK;pV@GJw=hd9?4@3KCkLBp#R(&R#LUZ>IO` z7nWP!y3#E%=`YUYQR7z|@~R8dvfjvwjM2+gSHx~%3tR%^F(}F(9KKh;G?W#F9SWia zB|fH56P**_n;JDVjrX%Izv;Iup)bk)p53!Ydv4C8(Kuhudg;`o#Uz*ZLk+Bti4u6p zgBniR$(=`q7DIk%%N?n&GF^W44#z?h%fgjUQsH`VAeVk7KhluST_wNQSFR{3ZQ;Kw z)@?=;OBHy*r*k$LjzlpWT3=I9AenkYJGWtIUXWANU~8nDp6g2Z3jK1e+PGX`)c z7se?r1{~-bnTAK4{;jrJ0xBD2JLK&7L8d+x;hHtWukvJ|razetWNM-fNJC>t0;yay z93%H-bPeVk6xYUL5=<#aBqtZUpztF5M2-<0P`$K4I=-9aeKj@>olIKM+^EfNigqxw zn5Z(l%*Xe{mPH>G^V&^ffoK~BA@=hb;}yvI@NjRRO4)Zu0IhbrShIr;gMjQQi5u_T z_SI=sM;AqcpJ&os9WcIu!Iv%*ksxW@z%AuFu7VZIO9ihbq0XwTuP@peIw~k#JlDaj zFF4f-Wj`bVZ*-g$g5X!O)f9DLoWwJCO`xA3*%>X;H_wnkYT?^ngRys>ZjM{QwuLzz*SkfW*-X`4iBs28eB*n#=GQ?2IA-L-TEu7NykMH3^#+B1bl^3 zSHL;7>|J(J0%HqflDeCiXSN>JXx*!Di*+ii^`PetMWleeAU`L8yz27kKkS} zOZr+NzfcVn9&bne$LgD!g5zdL6`odNWMbP)!`W(;$8qo4eD2H?lZG(q10fNI`_uEZ zS(JY<{&)s&ADqa(Bi$>0id{zkEWMZCNIi0HwVt5CM>f2jR#><_%TV}hOp`(LA2}-R zbWS#-*NkP?CY`>&&2&fXPq0mcRi^qE%&kmw!@!n02Pl#D-vw5U&9~Vtgp>4}jaK>( zo6k8+uX-sTj|9mI0m3hBca{R@C<-wKeW&(hO+f(wrjh5nlf9$T+^z%TE8bj==#aAx zPb)D*A`y3IXJ4g4QC3#iQqTK`?XU&;*jVEm?u4fv3f^@;`o(Je=e(QUrwa|#=basTRjvX#W^7G@qrV-PF_+ zCA;MdG|uM>lqGC2r=+A5D~*H@Js7jF$p)Ya!Lg>>sT&A@sqVHx(|~20)5eM!2mq%$ zt+Lz&CJq!z+$h<6E`#R6DpH-FpRY7F4c`ubsl`b-HF({k{OSK6C2mfTgaZ9CJh|I^mIGajWPX#{etzP3Zwf< zjMd7+r$8OOa|1O~P(UcpPJY@sGIQDpvHOFRFiU=u+~|>W#nAbZi1wOBUekx>3fUwk zU3~S2Mn?sLv7Yfc&rj=pI(mG8u@F=Ag8-kN4V#hT>p|O%1}ID7Kz;+qO@D<)0*rH|X+=&@RrZcey050)0=(ZcJzt zw{LuC+<#mG8sF2|pniel;6NyD&V*iHeBF9U80)=wo+h1x^TFle4aA)?nPFHHsHNN` zz=_QcyN7M1ucJsTSvT%&71Te}L*(N+)o;tH#DJ`wh>Xx$ihorRolT)Pa?1jAsXC|= zX3E1IgcXA}2bf=BubfY*V$b?_=hS|WeP?1wr}Zqc}{7g z#m5X)K|ECicZhncKPTTOt^R_=$(^1*`CeU7cCC9yw?FScpeH(6!Ljh;_EI!H#KoP7 zKKZ;;uj#(R(rt1|Cpz6MPfrB}kLO-LPqBBLx<~D;zfJR965xOWiOCSZBTEU;-)vaY z8*SVh|GtZhgDnPKfk!}KG>`HfegI>)Ng3$7Y3euGQ8NPwo* zmLjGNY3RxN_R<$iM$R97VtFSyfx`T!sxn{n>_EGJNzgOy63eF}x(TCl+-3J~9mvsr z@%k+rFdtCzuXq2lC6r+#gmnDudRB%o^=WSE2PZa`N;)imE7F1_bgHXIU+mGIIqE}q zrY{uaBX>G;bI_>g!0BJ$lRS3AW>C69k`zk{^M9}^o$M_)T$MT#`!fazBU|4ybOO6%;T48imZ%O-%l^yZqd zY&gv9J}*UidQnK0ogPK8I=kazM{BsH+d4KHnlL<<+{XJkoaxpsVq&a4=_;~AZG!T> zb5Z8m@4BLY+@3Cm-OW_jUt|bhYk6El*63pN7asEP2FXPd3&3DcG35$rpAkam2Ckp$|@PHN)ne+35Lqk!vcP@Xjs&Qp)wx-}q&?m&1MV10d z_LmB)GM~BSGCBq)I$p(&n?hWp4|~eUURo2(A`{OsO4Au zF1mEWRI>ipxedR|Ebx+z+{J&X%FawV>5}FnmIe!_yb79d& z?Ze3na&C38&gRVZ)TlWt459ZxWx|=X0W;>M#uE)^Fk6x|$47Xbu5%H52AWkMfaYvJ zYil>dsY7)c1RzvVFqHh^d}^_vKP2a0GH_us3CUx|-271{sq?`teW%@DpN3^Dk8kRmxY;KHzXx4+Eeg-XM6t|NP!<8^ z`t{CWbnoP<{~T8&n8g(DBZDc@AuplteVDLuI}|`vC4gH)9*^ab1|z4ZG=s!^G`mL{ zkv@7rZ-jxr5udn()0s+wxy^Ye7W8Ly5pv38n#tJMn6uRli>;b7n$#Yqkm60cZCgH) zYA{?uc6(%nKWSE{rOTF71ql;xnmh3MV=Vc^DJv5@B2#|vejnXdrt_ogq2TX~C;TQt z)lVuv4nnp_!=Y!LrFoozu`M@8L4^=~6YPyb61`3QNgFoV77hmq5(!8)D^#0879tx4 z8xFF(<29>|b1FP0MUz`(`%T`__p{8Ut5MrFs6!LBp>8Kr5S86JY&^1{bQ6~=?A&RB*Cl)-3DbQxV*r|r<(*t3f-+zziD==OsHZz+0u)9Czu zN=bj-?enhxUSR8-U%n%1i96*`kk;^7g``2bp-y&IjWjD@ATVFaw#Q@`}E*4yU>!{eF- zGIq>ykDKj6YW2f)*3$F-e)Epf>RpcNHb~DZoIX{+L|YAYJ;4Cbad%|6QZz&nj2$eu zGxUzoDu-#DaVO0OrJ;t?C{tTX;P}4sIjFNHU=vCJ?C?V;J;N%zO!N&JAp0!n%+3#+ zzhVnrS&zew>nYOKR~dBX{`RBM^jQy_IMLF#-G@JxV~+)p&aEROeas|zZHw*eH~lP1 ze9kkQ%{AU1+jv`3?saxUwCi-G1mLTQuWoy1z7~j=1p#mO*U$}G4CMT6kK^ce%`^zGON1z zd!GY({sp&4bV~MqV6w8q`ez?}KU0dmLhUx|9nc$lGQGG$q~P~e-{Na5*Y~*!H5@*SiFek_GE#JAHC?dLZj2Z=m-O5}AXR8+-Rn~7-VHyov9m$3?L2&jl+=@F~PP`s@04`{oUeAFM zw=(#$H>)eyY?-5a-K^e076v1xq|((<J9A@n=2MPEG)GYCc_>%i0yIvq8dWV@PnbWRUmIvaM?Q9Nm)=%`j2WiL!U&f z`R$=n$H&U(?PrgSALI=BocO1kNO7`Q>i_mUSE~UN5C+SuH5grluk*;(U7!`V)NsO1 z&~$?Az3DnA+4S60#|2ET#=Ln^h2;UB_Mxc8w)u0rlAS06T@igaE=V_5&06a|KX6v2 z);-cU3~k-jvt?rCnM4yN;jgorvNMdcv8&r<$aj`4epMu?L}=Y$i;G6i4jWj230<3@ z{HIU<7AgF>g+ckpgE`8Jok~48(?6I>#s$s0!caG10VVtPv4L{OsawI%LtpNZKe(-{ zD=DKcMcJ|Pg2>s~nVy{3V&F=rfA%`pt%#j45F27#<+_oZ{LK&B7WTc^eMXQf}RGv5x`(k?Ts}gwo4Uqj9#*t(`ej*j#D6e>0G}|DH zJRILgsD@D(n70&e@Q}M3vzC13@HJ9M2o0pZ_9_Da778T=DiLBso2lAKC=H!)+@JGr z@7a=g`#FMl5(tPzm=Ezj)~f!4qRm1zdvhl6$50QO|;o3pO;pSEcDLUPCH4dzd&!v%FF9-(;vkT z(Rs5hlPuSUj1F`!@g99H>llH%PsKOSaVn?-wdryi?QHP&s|ogrwTeDt())MxiNL6N z)HM$x8i|G7?V_6BwlC}_+1`vEccrYZzM9%RSGSlp>C2#a1P5S=`#kq=>^9^fF*;W;{POVd=O`zX=_$&r?d8o#LTw&C zet?{_&do0c&$buc6MvR$iphZP=kE9rULO{bV?;x_wmaHgvllueP!H@%z9bIL2N57T zKc(F%OTaH(d0B==qOG{q&-|sa_x>R$D zHrQco?=qHedW9{@W%&z#99iGtER8J0NV>CG3HUN%wM9fk3eyU)tr0$#GmbGYV`F7y z1#kuM#c;nd`xF*%c~3}Y^W&G@N>09ft}^v_ahYl{w~wlFgz@yH7BPD?UiOCxp-C?F zuSkQhBp#&)QpHZb8-m)Zw|&C{!JQgf8Gi0R@q%}QW{*}$;Rz*hWfA#<#r#1L#*U{2 zT;@1-LAqBJ?BQ-+h~Wg3AHK0qWh*CggPY@L}=;%2hE`i&KxOS5vx# z$KwW??JrPN91nHw2W+(8hEJep+YZp!vt+?I1UhbqvGm@i$zCP97v9pE?^uDZ=Z{`J z__!Xgk-tdD&w9Ao^`yzK4z1a9nM9tIxqZBqOQa>b_>Jgw?{g)I?r88>B*aw*J4Gq) zLaTNHny)^-GBY%6-E{G)G_juFvoEzKf(OY{$U zADjGu#EzENntuOPSzB0r2?~Edj=hrF4;5y!NlbiFVqQsK-P3-{I`q_pt?Mxx6*G^H zJ%ZsV7n2(3Q*Zw zm=qx;t}1F-#s(QWqioiZUmtV4>@|PtdJ<>>Pht3n*BJJh+f_{^y41bVZ;3yZto?9E z%Y3X zZa5`S*E>bnGrg>7Cr;4dNUZH>W0E1=Ng6v;)INpCO-yH6K>GVpT0n;A>5DeL`~!ye zVl|LJg&if)uy(Qq@+tek^G{bg&{ZI+m1+&gqzWN*uUoU{i1eIx!mTZ_bf)#S}u4R z7iTj|t#4<9N;!S7dby;O3W}4tL>8QiAk&sUwZ@`zFaMHGa_8s<^0?LWGlwm=8(elF zUAo47qp2!1&i(5zTx)$k_bTJn{6<{`a0>>F+hNRQz5vQI{q$4{m2jMMg`4HuMM{g7 z(Hy3?$Lm9E^Sgjp1fX0nQhIM$D5CC4TOeP3c|W0c@4&42xxII6%qMd{5oXs{P$e3} zv@fA-LDT)ZrXc|7v&Vj5zx!8}IGi~r4y!Tb=#A%cBjwh|b%yI183jk$(vs_oZe+7$ zVn5;GrWL2my+IgC@;8PP`GtAcs2tE=u*Fk@G`<70`|8cTbqc-nvs3_!+oo4;GyOrj zfD109O2728Qi;3uz|TGfX1iHm?@()=Qyio)Vr=WXVY zaEIsmApLs&@6|gzsX>Qe0qpbN^RX3z@h%gM@YOeZbhvka^<#@!UmOj4gPpmYYTK2j zASt@_DJ}c&O?PvATqMy5;;4Sqp=oJ_W4;@Wl3qmfnFpje$8lOicaz0-Ae>mHIXlxIBNbfd1@y!mJ))1AT@6 zM0uwvJ67D|_~ESPOF}_E5P+&S3@L?u@V$DJAx+*X_a zXfX8Coy#gZe&rje`fEF|St~m+{b`iK0qjKD+~7bM`1*2fs9NGk`!}cSsfK&BR`~i& zCyMGw#_~Vt%fFRRI2H8{Zr+%Sk)&Ta6)i0oJw|zyS!cdz_zh#g=Qbs^7OtY0s$SaT zN%?8u?>8FUxEf-OzsQ-6HbL9r?K?U>eb4yX_IFn;uqUtL*1!iBorsR@%po_Tn&D;K z_08^IvHijtwFW>~)B zK5lN)l4e#JqlcOO86XG37Hse^!XmP^TFg;By5)%6wncPo6ySwcwx`_)Nm#RC_Yv7- z-aK(#Dk?=X-dCl+KqGjAOoODr`vWU5#)Z>r3AZGxxE8sxyyE$w?Jq5+qn{gU8;PGK z_>bn}z;3kI19;LbtbgyVx}*qH=k_xgE7meZw3#b(z9*&wE$RC*yf$Wyl3p(=jtSv` zh@Aw2LnC7i_H%aDms=@%W4P~MnmT7Vo2`l8aw^0o&75NSm;$%4rOQ%Bj)KDK+j^vU z#(t?_=n9KmjXHb>rNHtXG&(Gj9%tdpos>A#?Ta&obId<#D3Xf&$FxB#sf#-zwPA$b zcx*fKcaY$d^d8gUYq?q_t2b@dn-#l~6t!tTqem~jv!Y{}dL{+Du=X0AZZ6J{hCuG_ z%ssHo^7{;8t!bYZ4aDf*z|2C#IZt`KSP{tnte~c+vU+Fyid7m(bF|NSUF4|A!E`Q~ zZo^+fndi#R)kuLo5X1Zv{rV1#{KLO8@N>yT2?r~L7+CIHYt)bL5TefKBhLFY9GRd= zpUA1mRxdZA?6UYiNY-VJloFd8jeStADegww{A1ueAfwcdp8W&bT+d}ADe&M9Yx_Xs zkoboD9#M(dU>MHMs#C2y7dBymAve?0noS!2B#c1d!oeF1!-w;vcY&G&V*S}K8hl%te&qQ4Wvg!jemxk_#UfCh zVyVLkFXS{RB$w2(=!FqG9pc5d3-3vBDGOwUz{b zBT5xGgE%Ni+>^chEO~g7P1WxZK&ypc&1lpLg;Fm#&A_u&umgRoSi|a}iGF&f#>#~J z?_>z=+tLCM{Uh5t}_I9JXbP2TaEQPJN~5x2EQ1GjeM@mkV_y00~|c* z`mShys4uOaq(DTb!%cW)VDZ}x!jH=%sVw>_gE5J&JS!@sj?rLb{dO)w+peGrtZ(r2 zdhpjmD~dO77ufn|#5+0VB7+Yl*L@joRZm;Ep>7p}vnKK?Mnez2OFbLM!02Lb=CcE< z-yJt>**psSq6;MI20I24)4GKJJFV&JqSMR&1IyvYEbEAz|%zoNIT``_&(M4Wm zIqitWWf+Ek7eJ_Ze3^kNnyAmdcO)h_tM6WKa|^PX>@hWWBZi5WG^-qTJ4^T$BdS({ zi52{ZU?TJRv{~=e2qJ4lWGTV699hxWnu?c}ALumXcf`c~_~&as=-0z7(jAGlIf|;P z1IY%H;{g0+P6wR+rzl!ETfcEwBgHOMsW6_l&`P=CH(h_KT`ZEgooPPvVoD8e6lxL} zgm9#unyoH{wxBogGDCTo4g3*GTDl|96F=WNFI3UnF$iz)fAjWwJ}SLv)#RN#kTWsj zVbIr(7a5An&cZX8qeMoC{zH}X*7=yF70WlkoZ%>5zv7K6mdzqb`zdP|Ab_iU2YdD9b6gB#)Onp!w~`r{^5^@ z8awJ|f4bYD;zs{Z#bXg!<0EuIf~zwR4^kF+y{L^h8;obL!g-ilb4Vo*W`nZ@yoa#Q zm42AviG!W>o7xWHm;piRKNXn=rPk6rj~%~$mmP*BM#K2jHn6^&f^mHthAy22N@4NG zu&3eqev5nspo0EB>bs1wu0XYJtJ!@&L2=mxS7mWIjgcx^(k8z+HKM@n>hiv` z4}-y-Z^91_9@}gg<)(G$sy53#*Ynep(`S212KE|RDg}<5SK5J*Ao^?(16GiZgTyN2 zL#aR=DS>Hkc+T%Kf?%KymWV%=fM(vX|JneB_66@S`B1}LYVJuRqtcHt7pNKl(w zyFzoCalPiduyy$dGc{(Z$JVlug%ztYR3Y_-(OsFx;R=-ReSka!G|i@DgwYvC?&b6& z2(O*wYx8Sia9l&m5|27**y3bb~Lj z<6TYA!Mke{8uC?U!sa@O#Kev!mqJ1Tc7^xaYb0fO5O3Z;j8ikkBlU~GIbNUimM~wXIvwcF9Flvd# zKeOpQNBI)457dXkvaO}^Dyu)Q=OW=oe`YprCI3We9&(pwjzm~~L}S+FNS_ErFXu}f zDOE9N#0~~@_;2iVX6gyl3C)r#tIi61x5ZFH_qH?*#KbA05jiUg8ETiv(6~BI2vua+ z{JKO3%&>DN!W3Q=+FUS~?&v;+LbmHcMf#~%D0gArnj{B{TguZv4Zo#+w(zd$&lB_W zp@iz=#Z~BKt|yRZdM2ehY!KrSq?Vm8gDCnP6?|4DXB|w$l2x^)7SsiiaWxp6fGiQ! zI(c))uMxH}YzOlP1yzrEk*t*%q#H5p#*ADM3YwVd9`nS+%g$~)nqKAlaV^Uk{k`p3 ztlnM?uL*GmNR4YttlHf3)O7aE;`MI#DLt3&%zKtGl1d}=%0By>5)7X)BpG+57aQ>N zlZ$1a-E3#^tCLpkgc}>@e>LU3H*1aKD`&N(4CfC_`y0rv)x|P>+=gG)HQe3MV+m}k z?_EZhuap;esk8lC-d5Re>f@E?cZu{gO7>v%QlHM=ifwDro%?L}$cc#yMzZlQB-K6! zu0dUpGt1NJ#0RCX?~AJ^yYqh&X6*M{p`(B=_12iI1TbPQ?2=zbUz+mHnZ!2OAD^&VT@&!!sC)eP?fYtrtO<$#4`lnz0Ty-hb~>|nU6%1|3Qa53 zFulFS3nUAmo_msiXK=5YW(hS@`ZXWjmiMh)M*QGVLh>IlV(*(H9cK_qgUW0V2-|PO z?4FK5d{ATGQ4Vss`OG66)uVIe8cynSBoX!9nB1N6^@oUX@`f!d09`&EVw z;kDmNmDT){^j+{nzE7*+gFC5A)Kkl&p{B&-b`G=pl(?xB{oOcVT;kuD^~MVSYSy27 zpd3;z`=DbY(rpzEHE52%5L5LJT5Odm99&16HhknoW;lnLo;p4}zO6nx&wulf-Rqy0 z(F7ZfxOnm%*K-||KvtT;=h#%lxzCVw{pD(a0t^ISPx*eo#|x#_{L+`E+}eETvOk#7 z!d;DS#=CY2ThRw+!tT`B;(gBgllZx8{(o)thY_Dp&f6dl8XJdmxy4<{`ES~DBoX$E zpfdIMXPFL$7m$CMLY@ntORXJ5ZFhi2o``dLwHcu8`X!C{LJ=?qz@-kYd$(=L5H(&i zB4>3IlM)yzQbG7uF19<C0$-~gwNFNxf)_MH=x2i0>)fD%g80~S03MF33gnaf~ z?mxq}LiN=OgU#SrU_sRgpsDa;Jmjbuy>4?J!^?l76Mx>~u>+Lv4QwWjR}AiYZ*}}LMmZ9t zWH>>`9-~g4vOFu%JSjFm@N>;i17pkmxB0BSmyKDuP#)(bY&)y}?wv#+}D(i_gRCC}NBV7IkmkPQC*GpnsP|JAYtV{Vp$>_g|n0zo(yl)jKhR>T4jf zgnNT+udr^xOpj{n!Ah8BG?DuCNnQn#Eca#me<*kSR|*|(JkARv?=)vm?SBnU{Dh5UJ$6?+qm^o#s7icYN-x1wLf@qK#YG*Bl$MA z%+=bpyfpvXLIa@$pH!<#5Hyji-6UN&_-8rS95uN}SRCF3^OP7GGR(Tk>(7rO(E6Xd z@?XApH&XO=0g(VGqO(hBc1@W|d&k~!C1`72ikQLtFUAw~ZJ*_X8WA@i$l)mC^R-#i zf`mFV#7cUt9>q|c`A&krVGP926o=F8;O=W?qeEL&a!~D1dS3jL4+pCMw$H(>yQVt@ zzV9-~nGSA9L~-B{BONxPO5*@FO#E&ymE+?>TKJC)frP`A^98tTg(27toxOSL0Vp0W zqU(F#t;M?H*rHaGF_L=V#Cf6RS$UtKqN1Wyn`Z>t)61KhMgzT@%t4*Ujr=vAQVQH> z1!Fo!`>v9=UpE^zZ*7$V4R=jCB|qs1EH~;gqUyPJy0QYCQL#iB60ZRf*^hGbsQ|^} z8ck|IQ25KKC8s+BMJ(ao{Bb5}4;!LxiTWGBn*kmLCW`c9MeW%k;hs630? z3Hyu4x4G+fbRB?cncF+V<$L8`Jy8gLpY_%Os-WR$ZJqhz`$xT_m$Zwo%-6q|*Iy!Q zb*8+4TXz$`4jGkgdZ2$_DGhPmp^roGUfsf2T<)9p*D%*2*@cxRj8$~yd-^2h*%n)~ z9$w>@(&o8Pi^Rny?=vpsS&?wKCQR&uqf;uik>+$U)UodQD}hQ;`=C?@xjhy0H(?XL{x4Ze2Se5v zx0sCrYQ91eDDN9E;8?0SXH@E~{cT<|u`3A2*`rs`+pjCI8rPhu<)su4@f4J4$EP%R zLhH#72Bd&$WIO8xLJVyP1R+t3ncVGD7O=nd14XzQJwrlpCV|CS1cH*C-cf!^Ht8Ji zY#H<6yPxw|x-yqj<2nYM?Wa@i&1x>!e+rE)U(viQ#uQ#G8C;&P#Y!sR$M~DU&>7@h zKjluLaGs#yy^SDmn;@lmUMFjmCv+uwJj?UmUc=xCi>C#?921>g{kEzx2S8Tkoc}g)msC)y_jwV zcHgGiQ|yJ((=EmCTAkSY9r~-?N4BwZb!DE%Qcjg!&f~#}-2Tz`1IEZ@T4JpOQ*9cg zX)5ya=PRROuQltppnt_fOC2$${Fg8a9=W4#m0Cl5UhgmSAJMeC%bD299$+>z)fPlZ zR+~}%R&cGfRQ;R7!Wz%$;z(t>z71%f6$V~c!1&`ojTs!TVnf|(ROWLOxtuhEe`I7o zUA9a8raf-c_-tbk{-cfY&r%1%A^ZHqX8#BYK&-s~`k&Q^(kW~=Rn@t|na}Um7v6b9 zZ%gNgYL9YOT^R_UT;PC`g%R!~2>ou$Zl|U^ZAHbz>iu5atGfk$zPitN-dghihwMQ{ z{=)yvGrZn$9^a0hMg#T_xk%ieUGrv0_%1|trj56bCqk;$u=}#7^g9-bS|r1$tv=5e z@BKPz#n+g6o!H>-e7*};0*vXY$*BsN<5i^L?)fcmIcv-$u4E*@pL02_?txmSaS|~u zD9+cB+b=VCYsWHZxHqhBsFw3eQ+}r%^WQ@w#D9fGAwag}01E8WtV?Q$P``mJzN-hq z*V@n0#m9(fYI4GZqeFW-%9pk-4D`QLfMlXl_f`J@U_>=8445EJBidwk~i%K zla+HUS3%f18fM>0pJM^fq3_)pKlt&UpJ0Z9Lu z0BOnnQ8RrSV-a9%@$%}xJ9VU2%dA25NF+siBIu5v$Y;pdt_BvKeW7_;pHaA6cQJD; zV~Jq_83q<9aUz|eJL?%Lkju4$0$qM}Ots^AJ1=#*a%s@P>Str3HrA0mm4=tl>HRt8 zME5J-sN!eO#+V4%d{Nr|&nV~F_KE-V2x0y?!wGsxm_-xfx8u3sU(IekuVp?DQ|Bbi z9+~o3omzkTQK?TKeV)HYl4~oka3Q z<$M_rJN`U8cPRQKM}3wycC;x={m235QrRE6XU zv6aIp-`!Ly&X3i`>LEb5CJLFiwSbj+uLPd0Er_iy#r4@SBx{sXF%~9!x7>P$sA}%Px*=^*I%V55URKBY`p}`()N;0mCgr~Vu<f(Gud*SqKR|*IjgnOlBlZFc^4xuKn4af%6a>u>NvjXtL+UFbD`_ ztiNgB<)w2vA^r>fhZlkS37)nJW1GL-F7`4P*(t#&g5J^e-PTJ+5RD5;j7BTdy80CsJ|lUudw1|daz1IH3q0bMn;oSEM#x+*4g!{nLyRvA6( z#RDIVwh&JouW`jNI0Mu{S|0Dr)EySad1W+TD397v4`%vz3O> zQ94$O`*cLT! z!AwdTN+Y-CSHmp*Ih-P6&~8lHlZ+lK)HTV9a&|J(q*A;vw;qpYGV`&50wI+VQfpS_ z^ve3ot*%rEAc1h5#!jv$=)dGrq@-34#qgx*WVJ|p2kMEB1u|27>JwhOlycdEPkd;dC@WoQT4l%O-)o(Mk@UE3Isu zECCjZG0A?==R>EzYC8KH+b@^V99LN8A4i#*$Zp9kd!t+#rGIBCpz$Hlr|9dAR3-j& z=w2dHOAL`Hu$*)tkS5+1G|N5ok6dN9w-)?5dzIyWs-OgrG>M;*ArT#nS<$~Iu1S1t zrjFAqs!|d>X09pm?O!nJXAB~nJ3xJ(6(L4>yxp%_;o*uSY5kDcKPy*i#5?*wh5bN$U5trxC&UYXHkTxcyMf*92DB zgzqBi$|zOYK=a2A&zJe)E=YZPJb**cvqE> zI$q>5 zzf2nSUujrB+^sPenc4z8o;!d^kGx=Taych52#Jnf!;)Q(WJn^49613qaFEe7rSeW< z5GJ6B4*n`6K5y5&n8|7p5s;;-;#3P>K@zt%ucLbX$$`nXq;qyasGCfW9s0iCXDb6Q22G;mfmiK zJs#G+B9Bx00klks#$orPLXrB-0Z& z!!eioSY4GpSJ=ujgm#1v-61fy1Zs6;bWpP_*e4MR9MR@uFj#S%x&E>kf1}(%YzRoo z@$mF}6_2SREc5YuRioV4S8*x?m1b&kymJv(JQfs@IaBq8dpIIwG$ED#f$;Ow?Jbw} zdacrsn&th5K-e=kKYN6nwu#nc>##3MXXrVo{WaY_&i*FP_~t#z-~qJ|hbPD#U!}Y) z$wU5NZ91sGID=~QH>L@uLQ!TaA4DF~I>p36(2(|5Zu7*1v{0@g$g>PSo^Y0EiMRf? zt2ZnCUi_0gT3Ml{Lr!1t%!Av4F~7BA8hr((-v(q+Kl4>R^rJdjwK=}eRFEJ*=w4Q@ z$2S{6F3>f>DF*OpG^6g1xbv?(h3xBr;;P{s4nkltG)4<}+k7XbL0hHp1=U)}CcQMesMYP(i@H zoC0@jj$LnRs|=prrb^^b2Z|yB42x30kziDOfx=&yA?NVc;eQbKma%cX|CVPG$9C)( zV#mzP%7ceYBSrU=O?skEgn9o0d)CczCxPq8=oBmJZakpA_|^U1D~QNp_R zz0ZKLubJbl9flL(+ucQkKg8d$f!I0g@r9Q4!koBfrVX)d{?JjqI?;z7wrS%gia@zw z--LQ;cDC&*DfN+_Gl9$X9LxNI=9G=WbWBi0Nrne*IM#8ZS|<~wAJS78m8RQfMONyE zy!CGONx>s|Mui(6KkHdITxp^BFC&-nYraDshZf)K&+?nUwW2JHddB*B!VLt9rYTai0vf+u_)F1Stq_A3$^3p|iTj;E(|c6@xCULtTZmY2KRD@r- z=JgR*cx`Rjqkfxg319Bx^ba3I%T&GqMHRoDB1!|JwPIskrLHfxA=Vg-0n)#SDU7Fa zmU5&>?{?rh@LGfqNxU8&zA0DG8W7ZBFg$A%#(~je08pf-KsA~u3j4}k_p^tdPphEH zXBVQ_Wrom{L}-b7WmWslSmyDVM9;`n*DGE=Be?y+yS5(RH0R8dESWv5xxm#Drz;w5 ziKBamZGB>mz-MN|HT1)5gyN%L(pV$L&-vt;Ez}QS%^w?`)f-VH>2(&wvaEYV3i7;f-*k=_4Yl{FIT#gK1dY6=Qg9PuEnh}FF8!@w*$MJ-^jJgZL zqb>sxRyi-Z@QfXbr4U!L)gzu){{sj9DU6L1qA)Nt!Ip7_f@ zBk3}72g5v#C*$Y1#{W&v172NHQ4|EWrc_hM_V9@{Q*IM*@Sp7~d-ixk!GRsVH8k|7 z+TJ9{hD*KDw|Wf`r*XGNtKPX|B(6$zN(YY?)Kn#@PRg_Vih7(|{k^_sNX09f?{x9c z%mkhC0a;I}HPt&z^TWrotFN~6W_#>epW@R|67VCf0wM72$ZiWP1e>#|~cI~DPxOU3*iQQgRVVdlQ zM>e&70lJL6|GuQ0h0D29R;sg0XD}w3xb{`m!c&=bjvX#HDSP^7o{w$)JPK=WBwz#F z)oCc|;f)BiWCRzq&vb6zlUYDttkh>tKFd3Rcv>I5eo97~KWFZW3J7-mINZXjXgUIY zgIY1t>H+EcN!LG6<;&|R$+~);f__ZdX^+JWxFp=uACwrc4q9L7U8p!HS39u~BQGmM zVh}&9HpIILHiBC?%(m1i7s=z`4Gn{W)$*exKpd6{PyB%$J;Q%CG4oVit<-Nxj(jL6 za*T?a-`~ma&CMpF22VygJ#Uom*N2OM;(PC%a+LQf6OVSRS}iY9EXXWH-nb#>{z;Z+ zM>CAFf`-d&f@m_3`KCSQ!2HOSqz~;=0z%hCCJCIK!WMOhNz$utH{58L61wO5Lt-x+ z9?^i%+H*-fM@NZOmVA(2+wrBE{(qfLeUePTVDb9HXhNgknBfw(zc8Mub4LO|;9y`N z7)^R@S^K3X3|n)!F-Ruww~V5ows#s*WFz0xv9ZpyRJ@nihea0KRk0Lb3OAa;>CjvL zvwZP4xR0V7OgQfC+c9@G>DZ~OK&|h6(KtQlhI3S{PvkaCv1GsgCy0_y$reu3KB9}> zys&K5!pLYZERuJ`{r#F+U0?EIjvC1NIjRX8yvN~o9!^f|i9QW0@Df**;1y+DMguro zu6zIMRwnXV4pTii81He@N3*Q?=A@&)svNAaG_|t|-`*y2^rl27W*g1lJF6??Xd%5U zZ_4yZ9QNx_C{GF6f34^=xl;$(u7pLve6xm^N{N(qwJR2iwNqt-=Vl()N_0t+vo;#( z6TM)FS7rK@=fb=7yiH;jeJNUc65Grf`#^604dpzh!X8qvY|ZMisKyo)bsObvPRU3S z5)nI}m;POP%T9cOQDQQthMArs*oe%_pXkMJy#oqeM^teXV=y&EfP$x}uu=5rs`u)q zAx_sxI*BkDqAGjf@;3#T?XoPK)+<%MoHHk;vgfdt>XAnswJ_goR#|kWj55n>g^;l$AHvEj+!u;Ho&2~GvGjl!d zS!N3LL@)m|kNjIO68K#_wPvWU>$$F@Z**lkTNC%v(D3ut`M1H}<*$de*6W{fvalu- zs|*ZHh2j2kEw>a|zc234^j*Qj-!e&$Ai1@KZT4U8f ziHi9 z;2lK!hRRa0&QEF2&>0TY4^QH6!npB=mlZtoH5u!DPLK%NSu-A$p1|d@L)Wp7CeL@g z1b8RsFXyDmx?gwGy6GJ|FYMtN*bNS!>77rK`Lq0+yaN$a2*Jh@M^``U(3)@-5?c&P zqk_+DJWD?Qelz{zXT$=&U3(Ygn3A`W`BBF5S^ao4Ad*A12MOU6B`P8uMr5lfut!+` z++-~o)HmEiQDZA9f@jTS;Xx)KjWZ4#vU{W#5wUnSbG~XH*7W-nN4T^n>yl})!1b$w z>ZnP7TzL|W22ReeY`S*8mQvt$mV3xTuTpibo22WDPbc-VAI@+U%}0f<$#K`K6wX5F zGy=x?QH{QIzbskDqdEaSs-naD>G%_SmTUjWRCe&TPa9>^U+`9euZ+)`;jmTPkxOqDQV55Vd?ES~RU4f7LAaNI8YxwON z-Ttwwl56>U3O2q>m{p+NCS z1@PB|%UK^3T)LlUu5lz;aV> zR!Xan{k%&gBQAk18L;RX_vSC{IarG;*o|kY(u+l%&OApk1Y``0vX8}GSREcDo1N#C z?&yT=3YpWe@l9V`CMd|65uM|{uCaT&eKW_2eF}Hod!FwM;9WY?N)51@b$s~5F?}MI z_WaLw?H!uPv)Z38SkkUXgCiLgu295PJabIF(2zn;OC6B-?nRfzb0Z~o&%<|!f4eW? z`m53zr}J?-E^$*jiqbkEI@1!tRA-Grt|v5OYqq3xHKkoKoehK8=l&D#3RS4_gz}EI1Kwx%wJ#SG zg*7`cH-{cRkE^{NWOC=u6uw(OFOQ_4 z!LJ{d_z6LpIa<1n8NnN&{=OZ+97vAa9m<}K;Ln)sv(^Z$i=D`6qh}`IjLcwMi2k0h zAQWQiuTX?2u6IJ|iI-$tsZ1WXs0KH5SDX}j)etR|QZhhgrSgE8S?8zJs+d8S?Z>p}>7hxImQu}JqnM|KT*~r~ zs``!ktwvq~vPziX^^_o=f~8)^$9yigplTImYE`8(>`>P?spCDpl0xOu{I{JzWCB%w z7Z(DY+1Xjhrt8UG*B3i*;#8nS%YRd6E@D*>DW>vg7XAO0Z%47uO6J+7<}L`Z3h5TN zMwsPiqjYah`}#aT7MguCN2+CG&2jc#KWt~T87xon)MZ0gxH$-0kIZPS1MNAdY;Y)> zZ4H-aZ#+ahC7rmp@&owqH!nAEqsDq^WY|4kzjn{qp%@$rh_`r91XZ?ZRx z=AlEAiT7EhXwM`j>DS+`rB+K9_`BYgDW;{u!yf!nQ-j@!-Pg=+(#2-})r8Qv47c9} z-m%W!=0^KDJZjdzVS+lSn^RNy4t zf%a$LhaB(sC=-2inuex#Bum=dA)fxCOVi6Rzs3sOh#YhDt%o*I)6cVQfzObcdN>=g zaP!qn_a;pIu&RH45UgX;?{>=dwG4j(9=aZwq0L5#ebtIDglMZ@=%L-kS?jOmgE_+m zH=1Sxq4mSB)FJF_Ld}R7lW$g!466xYlMxs9M}Vi$0+jc=2EMx~IPIv^sZy(DP3BX< z+tUwk9fCz^4Os@dkf|^Wu@65tJ|XFS56Ed%5ti)9jww5k5RLWEe34v&kNNnRXEi%@ zz1eW_cpu&zrNb3p95bADbNI7eFs*-RbI+rZ=(efQ4%jtf{=iU!2=&yZu&qR#)I}TO z&M@44DKtDCYusrKA}zdn%k+1BWyHk2J!s?X-p_(J{ZgiElrMF>Qm|qu&x$;LuCXSK zE=bAD?I9CfelQ>=BwmCp4nKo&Bz)dvHR|Nd~Im zFlxK=R)xcB)pvqNyiK9!6*wc=WfvLT-c*tmhjnDsQz7v8jIdE?-lRx#bt>!J?)v@N zn=5Q})u6oDQ>u8NaI8idJJjTGheLUBTT9lA5=4Ve5!>CYtjr$Y$!{;CMjCJc_qc5; zM`qmZ;@ z9TCe@6mWS2ODCESOWopM)J9$;`G89w!G6#m6Bn?3MXwXo$KuumfZF9nK8-ga`!BZv zpG#ZDsDT@Mu%j3m0}2)tX5R*9WnMP$2hNX4(f>S;@8fHb^{}@&LEy~EQhrF%jT=V8 zEXk!1yUEBH8wyIB;|r{3iL)N{o*7D{OfKJ?UD%7gzjmL!n3Mb)Rew%7bF??e#$w@&U_Ev^ugJV{Gj_sQ4ZZ!?1j4)Ct1XI+TluQ18WVF zqm*eW4^Ku%ChiD-z?kw_<(Kl_}Ys-GE1>@wZ1YX)Z<>y)ID=uJ}Pm@4Ef~kbx1MT1))*j9A({wha@ryp@1MNwA>^*S*2CnQPbhHKN^P5!Rpf9d<%3=^}VW+SvLA=dsTK zczC{UKC2XXeW_la zPCRh%-Wv2a&}pr|MAsHz&P>yhPq1?uO!7;hXAQj(9bj5A=vv;H=eoIIvw05gi2h7d1WR{x+a2sPQ%B-< z(>>yvkm&5dY~sX09L-x%pw}ag6XW6e4z?C4;#qK!IvVL?UHPycZ~y3WfVj|K@P+Xr z*!%}1&8oJ@;*UI#+a!8iWEm*}*yp{bB!jXTJdZ$a5 zmdu;=DWa&f>1LbNaaPPm`h%W%4$-4B%P6isaieDF5sm5d^pT=2o@1RiHYO;;JFM>d zTQYt)DZ?d|jyPMf#}E`?rmup_n>lSj&-jabU}e7nie5%HUMD3+mLE$( zSC_8GX9?zpUMw9a%5b|#lmQ=0LIoC@-jaRXeWN@EA&Id0x6EjYl*0P-$kU(daMA~6 zp}#hQ(WK_Fj_2ow6ymK!qqGlJv)pX!p7PnFLTHrf{;e?=y!VbTbDn0dPHk1(_nplb zpXVifhDUV)EDF;{s#Y{*lxFk%lH~UfF5;6s#)8IecSP?QjoGy6@ez#GKpQ8LGO4d8 zkG#TtYYC`Qs0yE6@$F9B1wXx_RZ~zHE-P1+1~alXp6zod3#khzG_hp2LNDa6m*)7X z#SKZzSpqZu)Q1~1Tt%Qa(k1Kx+oIwU69aSOTTNN(h7{8UIRoCS)+U~?8FzaQ1RMRq zxKkFt$Qt(V@?JKqPz_w*>RH=ZSGz4K+e~r(p8FTq+02V~`*-k247-tBCkDFR{5nlS zfZR4!b&;Djy8rS5z;dP2QX$Emtd${%_a6W3dr<5rqHSIBOvBXS&X>gSb|)ApC$Dur z!mh+BT_|Ft?^JWB6wWcvFcKbF!S6S$2p-B>`~LG=0>&*-qYszwFx`RZQjWdsRv(s| zIedhOv)4UR|3~!gFaZ|?=3jScyzWISqqSAQ^;#5kM4~0Mgov|GhWvvquTRXcL5S1I zgg5>BNS~>GwUKNNO&QMKa$4g5eU>+u>x(WWEDT7NmzGY}!yY{U6)fs@#S@7bO-q|o zk|`y`49#jG0z<+vmCX}5shLrdjW8riA&6Km>(K8Hn%W2~+$_krYIj@GH$vJcDQAqm zk1lMa7Q{5XY9=U6=x1bpKBt|iB*o)0gj&p5+SJ}H_+<7Ksow zNmIR3EBw`%B>ZJxu{*%UGpf#6u<$azrS$6T*XX&h!#MJai&`INFEV=cz}J)+-Ltu( zt3L@$0WRCm9kfJ|a-!F_y8hU58fGWMqd%m21C`csNV+CwUsZ z-o6gKjRT-=FdP+^7s!*h-2;f)_LEBc4OuZ{x>-;!+@Rgh9@945Qj5Q>7*jBB$zk0; zYD~OZ;<9dU4k3?=qjp{BS#5a29UO)&&qU;jT(pBQ>dw?BFec!MIM}MVbZ%|H{&SJb z>LvLhw}3&my%qg&nY-`)^3j!;t(t z6iB5yAvFn+^Pb>eyZ$e$8Zff@hK-(gxI+U;Ma!|{+yb3EYKZUxliOy4;md7a%)i+d zp@viYRIeVtM&rWdellx-W2ufe>(Zi!US=`>Z*QVEgFaEJ>7>r&o8_2rdmoE|DW6fyeOK^H!~k}fbf1R z$-z|OG#WKgN{IPFflgSpj=*7TQG+ES+88b8miW*B=d2JuBQ%zT>YZ69szeRK1KEW$ zRaSWH=ajlBeQnnQ-fRXMi%~r8%pjOB_UTKGS=9m**DQ!LAziB>CO%qxY$%OR&=|`2 z%iZY{hG8fpK^imZ39l7w+M!h^k27j~OLeBRLhW&tzKj2xF^B$~;wHbNhEP3_%Y)>d z+IsRiQHHV!t;q`d=MPDl+0v~eTk&W}lf>*5Xv~?Bsn+)kOudv8hmw6Sm){F{_N#G* z5pihZxQ0V67qa(oJ6pM>@T{^Ht1%qrHPO|Eky&+5L~&}_YApsvuf>Faszo>`a}p-g zN~xwCMNG!@U_mQ$M0q zBtm7q)h|KnM^CUvq%8wDEzbEdN*O zo1Uq@aQAS~#kp+wtp+rj5oJ3EqzoloQpUz(si?I5pF6XHF4K1IhpuiVxRd(81II$PyNXtg7Wtkq%alEQ{( zAnLg#oyi`;@<5M==kU-1CDod(dOjJ^`sLAI9}-(1LZuhe*^4?`w9wETt+=Itk*>CK z${I*QLG5ffNKeC#nwB5KAD@#IkbkI7A=q3iA5 zlqp73@RGK7?}*j8A5E=6wMi+}d&wh1P1~cikR%f-hiv|w*npeRp$j8Dftmpz`otYA z`98AKeE5vie7WU%%e=wl@rf$@=>#_I$tx&{rA;zXAx82Ie|i6@EwG-|s%YYApWISy zN-2}(9&oj1FQt>&t)*XPftsQXWh#Cvu-fEQ$)_|%XPTo!t#RolhBEr5^zky- z;+=ukGnKwv=mf`Sd+_q6V|(UZ(&>jn77rhatFz@}dtZu6|5F*-v*>@s&_Kem7j%?B z=NsRPdgU-dw#u`)M~1Sj#AzC z#10aX!ITHbvrk)>OJUy_0Z|JT`#gYR@mD7<6SxGp?nTF;zg0pj!*}%Q^uCbgHlC$vG# zlV7KV#jf9}^*P~}YqE}d?+NF6M69(17h{#qRM-5QlgVo|=$V)xmLyqTZ5OQGRB|{~ zg2rFI9o+@qf9aQ`QZQcJ7j5ukMR{f z8j?GH8O0{RZ%M%Jk~#bBFU>Tz)?|H9H%!oRF`j^(!x`uq-_6&+77K50b8y@W^a?*d zMw1`KyCO&K${`>iKXfHK%Z~M^oTg(~n-sq6@9EY9O^*m?cl_qWK{hlkex=(-H_#rL z%Tv4ZoG5{CxBCJJcWa9uC^H`Bver;4aimsx!;a9Nlj8D=GIrahU@?-NWa!=tjER}r z4nQp^mD@FN74An!106^40Kfm06<7w0`V)*#@ueqmr z1vfLZ!yWQcMT%lo=6FkwlzFl4Sqaj45!&wkvyYUy9a-qH8Lx#mJF~X`lXK!Q- zZz0Wm6&t_5FOdSLYbE#;nQbd{Dv<1Kzzd^ttq-n>Sj50K@?8Y!qO#ydVedc3RRP|T z_UYB!E1soZfZFEi*Gx=*N6Jn14Q36!cjl3cNP2zF`yX+dT&x!4~LanoW0~ID#6RYCtAEQkA^vpR#{H;LI_3e$Fd?>6KCF9%z&sZq0{O+#@d2>3;@% z5Ro0qX0H@X6hG}lx8br2o)EkJ3nDI5*XZUmqSsYFx(Y13zA>Mk$*shVnetP$yoZTY zSev9)v3We-+rH6WAA8{81*$g_cL{7ynetBGXFd!fcnkm{-ecP61&yc5Onp`=pw&L< zIyg9#s7``AIT({WoIxwCjecB+{9Pvv*GoJWx*J?EA8jjC#wI^T%6w4M?i$hXp1ZC6 zOrH6Fg2{AtO$8qbc8F)^|T&b-$U4ytAAJBdKv*QCihJraQ4-)E7KV8y?S!MgeP zJ(os{uKn&|P|tUX%*_4E)(*+jP!peYe%?ljusA#5mYrVFQ8Xla0N@iP40Nc=(z8rH zVBZuqK(#dWE4qb=9<0gW5&iGNFBd1JymiQ{OX-A6}oE5lTe`+`8~?Q&$vS%O?Ql5taMV{OTLocqKzuq21LxXasM|iPYBKbp z=y#JdoIzVAbmtUPhZ3eQW%d7tE;!duaB87^t0D5nfLd)KQ3 zA%zkR8r*;W{Q2^=LNc!6&*Xsn{|1;ENh|#SEAc>$@Lk`O7X8*7i?|!<@wK>JxxEp# zxxiY}i3xBUxvq(kB|eTs@1PWPd)#Ex@iA@?+@z$7iC)u;|HWPT-!X|`=mUh?`le7~ zXTbpb6(4a@BDN0)K%~Q-^>|9bjX}bZxVzpN1{?Ed?C;TQLC($%=A|cm>-E8ws0 zW~j8<02%vLpHMUr36g#Q$Sbv=~!`%HzR) z#6aPA-4Wwaj-$azXX^a4d9bAx>-l&Ww)uoz#cz|FTDEfKFMEa`R5YqM^!|+94kjEu z-a-f2;!1tRgub};QXe!CnUYtpQV>${wLia@scg9a}xY_iAhoPhR zUlcz$i?v5*_2-}1&++^a1NkOo+ioh^gjed-Wkl)8Xt~aYoIax|v^YXthZ$VMp!8j~ zJ|&ZIHF5-M=!uDpNKQZWhst`wy4O;w^m-*tr?=-(!C#^za$7=OSn+{0-VKK}0yfd^ zdb}5~$7bD^kc>E9M+!gsRr(ZjLnTwZRzDZEy8kqqK*~?{@5hZjHZOd;;Jc;NdX#Hm} zkjtbjwcuHN1x)ltlNdaCVW@$0^JTK1<+EY!@(}mUWTn>dh&ZX~o@{bX-EZa~FIQjx zcla@+{|SP8Y}pvv_)h0lfw`IUo*JEUokMqdkzFF81=aj;;`6YHZ8J1>>&Jj6(dz~x zE3yBQYBhg$(Z{!50DD2;*jAM-ZrmL$BNKIG!;$NSg0>SD5Us+@Otx~?EODyXpZ_aa zIDLH&0iXGwsKm{#fA-O%P*>TN7auF9=lT(hzxqhmAoIii+sOj4h&7y)Ku9n)-wgBPM~m z7#)0o(Kqw$Ipwi+DFiVO--(NTqMxmMx7vvVHQJHT1FB~t+!kGD*Y`XBD|GQz*7SdZ zF7*G`=t3d%KOJ2>79EV{DY*_*66JuP3!)G06lxfiU$M68FocS63)lHdS2_jvmR|=-ho*A%hE>ZM4zlLC-EWB; z%gn|&F9ufzzn>hMPKOg)O66!FUMgq$2DGAou`S_=6I1GF7 ze^pVW=Rq>)J>>49au!5dvNh*M$;r4%OaTbL)EVQ^K4eNy{ZVYfk7w_6g!4*@nUujK z>tnwj`DMtrn-_2@airn>-Kl}$5+Cc|_3+d-KKxoWZda*^!i`8l{tW|tHI=BvlP9=~ z-npawNh*!PN7xGW&BU38hbq_O8?zs)pq$5V$RsGoiH@NI1n8@XJGdK$6R_gH#}f3e z$wjZ<%VML|GwL09Y_`oa1 zExuYTdpBlGjB_dG$%jh2(N%c(8oG=q_*s9b)AqXd^X}*S3kEXrHUHld8V_^A$w*b& zo#;vb0s#l&s3kG@dzE@(Swls#kLFZXQk1(7%rUFJ86#oL>^iaIxdk`K|Imeh$JKLX zxGVzk@eJhlaF+jfoeL8KSd;Uo^cew83XMF)H~Q=HN=RC z65p)GkUMYpWn|Y~qG-!8e{VTV0>u>JmB`$G2AM|4Gz2?>R*To1-c zm;RW(TcOQ0=Z|c%r7B+4t43nU$zHyzyb^HyJDCe-YYwTiEq9Lr)RD+D`;)NDJ=rT= zoZ&cv34uHJ3!*I8L0`zAOT^3JAWMx@Zlee*o(+yhppnBb>okYH|TOqSz$sDh!&{yq=1M-k4_hTA z_wqz=NrbPTKGw2>X|rK z=o4J$3-O<=Wq^-|o7>t{CO@yYo8Num>$Ky0^MPMEw6)zF`@3nvJxjCJcLAOqsfI16 z2P+RIq%zEvrd!^jma>Tm;+}@XM4Z?mEfS1zJ4;z>^A#1WAOHDm_bfc0;spD zVcv8(h(ozTHte6SNquwFluxFGqZ!*HF|8df`U<>Vx*;t!bVAh>%v=wW;V||ioV?%P zR&)6u!zM1*e@H_HDQx{@y!@D_?Av>l@N--UfyncBBZs2~ZzJ^cXz@g55R~XZIuUP= zrwC3GWOikNlx`r6%=7N}fs1yto6oBLX%ZvF@2zU1n&t3Oeo+!0e};^`%T?hw{YrBa zVb}i6SLtNMACI%c19;CJx3ovp@*iFI=Qqnpnyu?^DlU~9ARQ1V(ZFMDD)O`FBwL7G zp;>EsI&rxI1Kq$p@z{mJkzP?ey^B{Nro=>zbZ=T8SOFjWi|eU8REI)d0~eOLK`<#oj9cW#E>^UDdR-e*{0Ni1wf?@DC%>-K#_B(7IzshCSIiTPm@Rg zcCoW4e?vh$bZB1xl1{1U)v0T}*r}-Pgpj@ptfI*EM2|OAON!|il#ryhEJAY$qir7o zLRI&+4!H={#VtbN@vAk~`_Sm9>aE)=-&yhlrtL=iLGNK}X4?xo9!w>EOTe&5_F?eF z97(sf6LbYoW}UkvEHa$bZgV|o-%`Z{5!#z>M^Y6{DgODfb4zfSxE=WVaHol;q%^$B zLQ*6A0Y~_$djAiAEB`(!FPXIv|23WYYmHI=#8!=f;iDREdu?}Rn@e=iN}!L{HafYf zVB!${Ub<$h!xJCI?9QeUDz4k*;moQg3FU%MIJ_C>N=$QfCv9;__SPJs`8DP^%psP3(cwfO38 zyi}ZZ&g~Sxf=~FZ`c)(Q-7aH&oKCKFDwuR#tHloXOt35@UREA*dlj7nIb!G^zz&dW z5s#NT^NTNy;*4BAXZi=4xBi0(BCp%~;ApDM%fcMrfo1c!j{a5xbfG&whu>venp zX^S>&bg|p4?zoH>u$jo#7V6N$qF}kW_CZ|&rHE}f-vCHfh9LRu}t zN{9|Lpg$hC!2Rn0fwkS;{E(W~&UL8HGsdGgAk*EkjhEQN-u}7VPY1(t-^M_Mk5b)YG3hYKfz^179LT~7@c!Lu znYlFhSUguu;g6E3FS{w*a%fe0u|`XBQJ%(l8GAP#_-d-xz5V=_(iGT_(v>T}W>XhG z*KP7M*DJ8KSua8AA2KJW1Szi7_l%AiY>mOS&8pR$Aw5oB+%+3@1ROS=sovbH=^GSX zModPEAL@)64hDq_ogI8IVJfA6eBTJhzIjp^OLCUBoo&(VcBak&d;I<}PQB#I`HKQw z=X%rf>~-A?;s@#4Hd@N|=)^(X?eP4Xy4XWQ0lm{KpPO&eq-OKdq0_iV=dQ;xH#$&}WT3;1r4@ZXIec@dpTjd|`Yj{1w)@TH#sk8^tKGda-j#4hBR7*p9L(Vp#Aecpjj|)08 zzghRBJq{?-?4z}}Zf*Ogj=m;lO)P>q)7@Ml4`AOsp6VGvPUx2RdbX!YXe@$iEJ^bh zm2hffq>NSOL|rlRVvQo%zCC24#@79_3%Z0A_$6+O(Y;XRBCaDjgpI+j)#AroK9>*8 z*`+PB&IfvdHvtRuTDnAAlIjm)6TUb zuF;-oyz$P_eEJ)U6oEvfXxO^THC8rgwgI23gB6`yWJpVmx(!BhaJoWjYs`zaVpe(HwFw*r+&-9 zYZozye`?yCk%T{c0ubdYe&qAzts^_xDvVI@4gu3fXX%=|_9%OJdnuN#vdL?+J#=#g zankaISV*2RcYAr0gw8{=F~4jypbkc2mUw^?76?0X8u1gc|32y_PvA|>~+{D`q)|Dew@}i(3$m;f+u0tl^uE98VD9WH z#+78tisISZ!)2HA2lQc=}#s zBi~`l=^38{_)u$AC2o2g!?oe8$_Iadv-} z@^q+`gc(@X+}eJ61_D7@)qvlB*xQ-FM>Q5l*?~P39&>LM&^{aGbbf9p0}_-*f87V% zSW8^L!InoqC9)fUcY;Y6G!y1#o>PhjcY2ZOZZlW5qDfW4d}c4<+ugTDP~Q1-jx^T|oP{eUg~vp|tjOHOM- z0el-JzFDP*fa(bAGIOc6px-oeqp-v*Cq_f3Kiu^o{O^c}vG2s&SXNTe2NU7nbw_3u zDNz$irbF|Rb#(bX1HNpdsK0?qA;) zneYHdAKB08>^Dv*0hF=r;#K+i`3ciXh)od@5z+z@>%*ea zehe?pOF${8Y-^Z%TJUPCgdMi>c{%FAOE>o!6SGKI;+n4 zFGVGY$WP$)*Q>O%6k~X3DsL+~`qy?NbC*Aql?+`aS3S>b#SHmXSukQsZ;uVu{eP19 z4h^HtkKA7^l-CH&6X8;R&9ULv#(j6Ub6O&eqBC#heP8zHl1`j9+F?EqS+eJtY;hdZlprCP{w3FzG+Ks-bQ+#}T zRLR^wFfBuU)q`R-d&iG{xYMG=Mn;ou8NE{rEL7M0=-4nHIkiL9ZFpC>+~R!@LQflf z_h*_V*OMI%8H|ZcS#XRH1H{}?g`o>eS~!;r*Ci2ISBwAY&O3W13p~dsE3#@#o^CD* z3saktE2oC}<_nnK4>|x#EqSa86qPI>-l6gaX0?W@CdwNxjgUKEDqm4|gh+EIl0@VM zA#6Cwh}xh&%a~K=iZ%Y$+fPYF;C@k4q252IAa7?(kWp_qCsbE>@9frA>2Mp-V`q7Za_7 ztG~(MEEIwxbYw~&U@xt2B<$9eFWHoGpd_qzYytq>iV@Hjv#e8H3wtDo8J*iyY`pEG!}dhe#jMljyV#{sj@mT>tbfC`LT|ql$}u z)@wCzEWF@Vd~e$yde)GQXbbX(++XrB*|C)U`@c){D3~QQnCq;q1y-}j z!z}oD1Hnx^OlG45MhJaL^n_7*K%WDsv%;+o5D}Cv!s8k>5er+t=27w8JLL@0KT7z0C&8&cr7$@#E@F zOzZiLL$k3YkQT=f4AL3)XQ;S1Pg-o<%vlP(pVNQx8hw2^Qfz-6kkR(!Ot1A!IZj%| zX0Vd!&+kFX6MS9$PdNzxbY{&Se+}A+cTApSeV#AeM3dJPLdBT78YyRx2u9oWV z>hB|;=V^SEq+9oZ{v-n^DB{IQRGRd#yjJBXJ|Ucndb0BxS^j%$jxU#|w>q*7uyM_P zCaG9IzkEU&TzvnuvP*EnRat21ues{BID=U%ySB;ZY{T2tIoER)r#qE9;rwU~$K0nu zK&9Pxets*dx zuK=@bptU!zR2@|gvX4RoWk|4Fr6+a)8k5X5QDrDSY~(T~t85A{wO<9~gG?YJAqhEt zmO-J9%?Ci{)bHxxOO;Sx44l{*}s45+@tRA7pBRQeglmT7T2u%})9r*WP*)FlD{@O5bv0bi^>IWK`sA4ccSXz8(Pnqe96HK1$@1ARI5=xKQJ}TdbuK#n4U@v<75FlkM`hl|Tg5aF zGmntgt}m`t2gew&lACnTlA}aCT!-CNmwtIKVY*sqeZ7@_B8P%LgW!0I3xY$`y=|Ey zQAbE%Jy}P~1lJD}8J+ket1u`I-(HP<=dmXC%W z&h5x0yvu&S7j`oym(mAUQM9qGWgsU^6j)_@6gKZ(Aph9dk`MB>x%3!#deGR}(xrfa zbp>g1&27vJ`N$z_`MWHM4f~sjU*tzYAH#G!z#q-1vBO}{Kc|j?zAx^KM+af2b6BZT zrBqNcw$Hqsx$5c|4D;@gGvdJwBK;yp6spo$8mzd+Q9+*I=28dP?pxIE(x7Kyhhd`& zSua{6OWD*KVhB|i{s?Nc(B)bI1{!9m*wbUvvUt97faG7&iUsM+?(NXrjOI`q7#0W9 z8t&V~N2*WK+({=GB{H|MTm9z;k?nS2rm7FSY-r6xDJkTCAzW{5sL@p(l3QS9c07=v zv3OK_j+yITG)**3aeY%PM$7c_@^gx(xVoNq)U2-?(IP}0%!I<5vHgujRH-}cdlkWr zuD?|Y9m<6=nPPWFI$0Xi`8QUw9HCMQC)O{|&Tyd7$NreQ3{SH%ZO^*Iw*y}%@CH({ z6~V@E_`tM>$@Ufpe=p`Ak2d11f4Zxp1ZF_FW?Z68XBhEa%9*eyCU7JlQC=?crOy!C zr??^dclCJax$^o+OQ$#vc4F1to1=Y0yNg`MUbBuNl-dG;$O*4^UFE~p^4-wQ;ROrS zK0Y}HB7-f1`G=81QhWudDnpKUL2x0yjB-a45}AL~?58>pyMM0|7=&^wHxpb=ocz7Z z!<^jj=CO0*iIwa|C8F0tgK>gE=EW-b>geZa-B+18X18CSg-~D! z&4|u+;0O=TQ32`xi`j`}c7~PvZK*GIlV)M-%cH&^eo^LOIS%AXY2Q?=j*RieR*c-p#{R?Z{rcT-_s<hrS(4E+9$ zesh~Q{nuZeumN0?OD{b^eEMZ}Dfq3NXt!^}oZ-MsD@T zViC^`1xEB}JLHi&>|uEA(3xsa%6bk@=U`amObX%^9o21@>g%`&__^WS<->Ovx6miW zwBpx(n0e1f+}oZuMbz97>G>@bm6Vh*OTdn_=koCts@@x41_MerHW<0e;#4AH)sdpf zTJ9+RdgwZl_bCQSz1jqc$jKv`huvx>Pt>Z!)lvvBiFZTgTYWb;iZhb|`aMo{mho_? zU3|YQ@s>6l3bWQnm@HY8^9 zRRL{Z54BqpKU>;a%s{tBTP>AtQ#wP+gbB*6OQ}&qm(=CONvE#OGHb~myF`ftK%N+7 zRXg|~F8)=t;$dac|C=$$JbZNeUshoHZaD92-qj9Z zq3EZIipmvtNwz8g02taY3e*%A7bnlWKCqvq##(H5qYP3wE?#aOThsD+8TRO z1;7)FlQ?JO|3DkO*A98^`we9e(N?ma zBx4cp^cSs42nSL5W{)zaonmw9pegRZF#|T(=U-nFsQE*)`$r?lN1BX(UK~|LAxvR4 zeM1{8S%1s3(HsS-<1PDD)@}pYuownV+aF9;-(qFI(o8@l!wychoPHjUgFud5hsUf@ zxPeBC5iH3wqp29q%kI#%hf7t_0S3+SFo6#1=S}jK*I!$AGvVP5GrZT^lRD_G4iqC; z;o0lq$&PLoR9ebcNkM&=vYDoB^*vIB)Up~+KY8m$o+r!BE8nplj@gkI@a2zXP}-VL zw)vlvX(focbH5Qty!M@!dYb~(kewrs#Uc;)=L)M{#B}>?#Q%k?ExFsh-Eggy{D*Gn zvg}_8+p!Y+f{Qy(CBjOyWxh>IhyNhxjVkx)`EHvU@789WIjwvY z=pK^ZEx#&SB3;OAwG+ebVlW)1BbuKkjnc0u0%O}uPQnrLnqP}PNwVCD z7#-*wi@Jt2ls|iWW%{u^3p;;&HZ+D@E`=EH855lz#MQy2waps&cfn>vHn=es+tIz+ z0Xb&aMj!@b|NQTl4chOimu8HYbKgO-SdaAl`)rUHi9Y`;Fs~f>>VoiB2`o6e4VgeX zesYUu&Raq0vz+pwD-RcB7FD2JcLR`uEncb#`N|A&FGFf9c|D5%HG1?wc~D({~CbN=;gjM zmYd+3aBDGIs{BSqvkuA)4O~>lk{&lvZlX))gZ__@U%>xAK>nJLX1{iz|BTug7xbTR zCvb3p5M52lbAY_g5pF@6ogZ~lapQ8L>avvkA4TJhGI2*|?|W6&BBmSfko zJ_(m#S!y*EO>i;h?n`k}tEO?DwVwKhT+V-3ZPrwLPgeBn!yUxgQR~P?p!XV4`%a|x z7j-C3)#-rw5IJX>?+YAT^e=rJBVM+hboP+uBTj)>b&{oyYo0Skwyc-*#JvLe*~&wi zp7GPPHc98f(cd;6f2p)1-HBavw^|fSg-zxJpl>Evzs7*&g8kJws{V<@u=DR)36g{&EM)z1UsKA!~kT7N$!fypHX-2 z_&~3v(k2P~v3nQ|k!4%!f-4iWyGtIXoyV!S4Yz}}?m39v;7KPHs|G(sh>4?MG-pm6 zzoHT5(5^@7MMAcn(&$M`c6pe>5DV=u2TVv@Z1hhX=zmxq1rE5!kKvJ=d*`vT>C4QT z!GpZ}?`U z6F}!VE%d282jhXS4aR&Ij$LAp-K;o-TfUDEWXlq5%0+B4D{fu$3#(i;33%&E3npPhI2XZAz*oHEjh)P&5qC)zA%n;-GjEoC)PLpbe# z*L!ld6cn)*5#&5bo-b{+a@h3i9lBE5Y}M}_%rfxI%pp_)Zx6<)26qA-T(Wd(MmFk3 zxgi*wFP=Z%$tGE|k>CHT7r+&~U;c}fCm~Gxnkn`hL8$n#e`h0w7G{U5)o7oDUTeE! zws7n*U1QaAFY4lwn{vyH_Dy@InYM$%&sTDye;(WaQ%x7E%u99{fdMf7g{G|h;3ooc zc<&-we;I0wak#rV8U6;C{|Jp|&wROPt;YRplSZ`;-D)X%*zH?BG!xN!e+T-<5qpZ+ zUlIUx?IXF}It**har-j~!m`9{bf^v@VMJI2d*+3yKet8$2RuzwAK(eu*A14pp*@$_ z@jbe-)T<9+0G+P`_O*USYY}x9%2BDU4@bK-uDs3LT1-iXauoKXpA2R9 zRF85sl@Tai&Uaf7%Mwjzre*ze76HzE-lJb|_9uY5$$Cwr#xuU#O|8vadwYSYE@&Oi zR6c?P>tj$9zB`@|*#$os+;-FpB~xN~hTEQLTN~boawb+tHaf-9?>S>{@K@vBY5BDA z>y2YB5zZd)My#V$h`loTR$JNeZPG#ePx<=k*J_}APF>}``bN5J zI_BP5NjofiUf0QMs;!oEh2%CgBGFR~r7Z>Z&06iQ`q&d@uJ;_x*H$eyaRqbxS$bci z_CV{CJmEl@eZI+l;)N333Bf(hIio;GgF2o>=SE6YSbf-`V5pJC(tem~Du%3$JSA8F zX2EidCyQP&b6ux&_0~`ASPiPuOn^mFAz!$&W;cFiL?0JR1U?V#7|JTgsJ30d78MIE za{DyszVlfOl0~zCv*Z-7j`w+0AOjOmHfK9LGZLn}|GxnLUy_FNmjzK?%=|?(;H>SL`&Moq9^Cm<@_dI{sZ82Kl^QGwhLaRkvx9OGek}X z&_t&5>B#E1iVr8DlX;=BcD#maDQwAGwF6UXi$6U99U)cO;{?3ZO?lv6?r*q0G65br z-NPX!f>n1wnqvFJGl2foVNHUF_0)b-6jDpfF13wH7p6jv1KLw0He{?m_i^WS!R@uY zLS@+B%$8p;b={6(Gp2%zUNf;jt}Y<5CEUP{#`l-av+rNzOQam zgEd(!a?;dOBlvdjjLH~zHVa*5eqps5d9QmcHrRlI-ed(W=`UZHr4L?iz9xe+_xf}( zcbN9XGCZ<;r}{zHj1nA6_U5yS#y5{#G=E#J>4k zkE%d1#W4l{0wMMi43=7tHPy2+6^#j7{a$Wfngyy*0c1C>pB2IuNHw;~FQ*>0-x@9W zgW_vcDo-x{o~ofEs*fd=m&m5u{Z*a~q6ctvpixLb3r~Uk)jq;qRAJdL0EoE7(SsMs zo?4#_KTjpTiXjOeAUZnRGQ^Ir;|fm&8)eHVH5xz_t4xx?Yr>th0$9ZR+U$bkCW*0A zhs&%uP==!BDm_AA#8>rRb*9D1t`D%3W;B|4aiKqlO}`8t8=^(uAlgZ1VSW@p2}Ozv zKjbuCTj{S|jwErHRJgqSh3YTC7%#|6+|1GKF6?c7MvN=YXaLnXTweFelH(_h-cMx` zcoL(sg7H|80r&vWZXE{kMnlhsUg?NR0)!MDQ3b5uPrd8@PASlWAhZAeiE%|!Lb!7b z#Dut?jrbq$KyqTEzzgtnj@mc$+y|#;aoZH+p`t4ZfDpQW=mX{j29`hYo?T{zF}Gxu zTAB9lOkjK08oj)s>g#H>TPDm~_ zDT}i=+3u=W{$XQb&4B1M&!JY|_cN69;mFd35k|0BO>Xc5!2P?@8_2*v})zZ8wxb2f5+J#H}EX0WmXdy^JH&(whb!L!gJ7KYa9Q>mD5*_^D$r! zrDkJR4~_Xd?B?1s%A}{%=Sv68EA=arQc+m2zu$eW?jI_!Kg~DH3guG4p#>zA-PvWV z%HsZc4y^@H^5oV&1V~6F;tV=4&vHnsKY<=BzJ>c>X*knc!K^J$D!^Nz^jCnw_*3YD zC^)126yKMcRqxUmYEHeWm|x-qY6ogm(AE0+X(eFsl( zcqMc=B*i&g#}{m*zdbkB6+KRO>H_RJar&!;#1C)!RYN9hh05(~9&00%h`Rt`6v))` zn>refEUy(x4kNt@O?n+3Db-n6QQK<)h(Jcv*kDL;~mRzC_3cbr;Z5v zN`GNk@VjQ<4-q5JDGKt(&6TRj=1PR0UDf>0SOggI|CB`_xBEYWMc}&zRR3cncz62$ zn?~?Nat>35a1RrFHIg>mcZfP#jyVgPnOt#5d8Y=}=^wOTESZ6W8%JsXOEv>Svcs3Y zDwI}Bbgy-Saja0}m?TEdVJsFjMhDM#X;i|eTuFqXDayxVSGJPLI?%9>|6s$7LFm%> zFoBvhXsLg=Jh7UDtb$PJ`b=5ffsgQ?wm^y;ms?4+&N$AL&h9!y%BBkY!3ii^+_g(J zEW<0Yy}*t?uIOZK>*mg;0;9>8Na01k9zs+o{%_v_uQjjTd6`CISYGBz72nS8Bu=zH zQT^=XHS*?{mT53fcon6#xXHa=w#Fg_ld)=Hbul!NI*jwpiYoz{g9h*5nkkBSV+(Z5 z)(^k)+|mVNvhpU-fn$Dlmx4ud_8R+N?@&dqV*1O1>$B+>V=*KPW)>g2-AZ2&N})^n zQsV11%lWp8C$NS*a8}CThzKt7G|oSIvh!gF%_5v=J`sRdR80G$HZ-oK!&j6n-$}se zwXGc6r>{RBpC*>1#c2B{gM`txxR7wto3Wo*`69oFDy$%>O;mj#f=2zi!8g*W)IbL4JY}LSzvvo zOmGlCOgjOCKzCflQsCu^^0{6c{ci$g4?txT=beNHAH3wnRiO{?kr4U_zs2^RX?VqA z5?hwV+=}IUAN{dNmb|c9743*2D>q9%jxfVn+(~uP2*>wbD#2STDQP{)uM)6)@aTmD zUGW;A9T#^pdnCr>8gy=a-d7O`!lwfy9G|wpLgEni*likUX(=Ref{2`(IOon#fq0~-IANOAm zSC7aw+ovNZ63&coVa2&v?${;Hq+0K1Z>YRo^FP|175B{w?oW~4;JCZxUd{eZ&Hk5o zyPvg{w8P>TqnJ6QStVQi(nYC>^r$e24-N@Z$j25(B7oHV*OGdXmXphCE=*bIOLs=p zxB84jua%3fr!rW8){9=5ZhLI*K6r@9ZPOxAdUWdNkCWvT1!uE0m@+f7$qrT60lFp8 zFyf?|UH@v?wytO!+9h`$umI5iADucl(9UOK;F`lz)Duu~V%S}U$@XrHeAw)m=@oA< zimimg>p-Twjy*K*(0Qf%4y_GYeLIy-caRZEvftNP9NQ< z{e>P+{$nq@A$6{TJ{=0!(Hj#Do)c~x6wO3kzmW62BX^QEjEVrrXM>Mh-GUH0n&17lj@ZqYWNH_p9!|! z(HO6A4<$))j2KPoP6&g|KuV$#bfxGe#b+YQ6k7>iNcPZ>J zNY8(GL!4p=Sn`>JB)Dx_KMZ@v*YJ7pWOx3gxZFn@A$0KLi>s)R!BVhwU3~M(tK?2e zkN)RQ_JWWy+@>??`qQ?wYkVv4&tGc7bs)cd+{T!N*NpNiY-z6Ukk5$ywDFzC0}q@L zyTvLZBV$EWIp=NG3IDzEd%8KeWi|Wi0b)^Y5F^}nEyzl;oNO@p&Ld>TlH-wcJu}*D z;$MWd;}@&;L6~^=p!Eud=3v9DivQFa~{XLfwLzJ6^u7ceWNT|D&5bvtJkBrpc$B7Vr4kd#?8`a!d3ic%|Yv@AImFAxXoZxYY07wv70X}io?UUvH{DeyiTm}M)e=m z;d_UEj2E79(|sZ|w^Dm%$HWF^4|Oe?1-xFpWM5$Gonh;U)Lwoh`mVE%O+zbUql7i!h8#Z+DIwtMsD=s zj?tDsK*Qo+!N4S~$p>YcRWw9ZdAjG{^@+;T;jNC5pF-sm>(LEE1qK5gC*$c9EOI|J zxT2<~PWtqjOGFZmQJ!~>AKN+QD-rTJ96v7IcsqPdbnLg7YN0F0qxYP(`Rbwk@sHIC z1{ zUU}X9W6+5D++Kgc79UhcP4NyqFYo7l`)XaD;ec%c>J@0Q8fl4=<7WFyR0W*}friaJ zb|WskS0oRDf!REj&eZZ(c3|vI(nCGYY^{@w3+fSDnCszEr>fTDBtN5MPK`Pf!qaK9 z>Fmqz^Ew_0wgxl`p?o-&;XagsH#8B^WDQ@-!!i}V3(FM(_uzQG{wwKLRKOX}E&KdK z39tX-qDl%3&*rzu6b-CePBDMAkeCPaZg+cJ`VmCKP&G<{6C4o0w#Lm>?$c`9#jWGO zdO0?MX*%(OZI#YWq4#+;i?Hlv$4oM>9R(z{KgL_1kALulLM}(+AOj8(){v$XN=3m*VEfsCO^0M_$TmBqjl$jMwaxq2ub!4dE zx_t}nKrPq$oJ|_*)k_P;QVgc)bzZ*(g#9P-u4{uX<^QhF8t4_2opYuCKk-?|x;CHw zj}%tih>o2Ps@BQ9l54to@?*96B8ezyx`noIb+DhW)#@D7x;hArFy*ow;)T-6 zIGfycx(5NGF%D;5d9<8Kk24;ZA}B6WAPRvQL^Cg3)e~2PQ5Ms-xhN(g0_tjJG8$X- zuaQ~y?Z33y|5H6yFvT_!uD_UusC;eEPL!mn9!S@|QlDir0iX+|9cc}9skJ{rXyV_r zm;VoTYAob0FDif`43pcVx#=Q6ZmYLv!Tmn_p#51%h+jb3)F+EUfkONEZfj}A9*>m> z=8lpQ%(u47ACdQi!OIE?k)Gf$8vjik{XYcO6g|%s|9>uyBIaihGl$kGTWK@_u?nq! z9zZe|J+J0E9ylrpHu~nhD5bub%SS@uqb_WplZG4mtL+XMt+_l=Hk?ThHF@?8l5o7D zvE+WPY}4NT?O_Fxi%0mb@Eh@;11soxrmQX$@MU19@0c3oKQMULV>g2%PLx?B z_iqaAn~3Bkpzd_VEiRS>M!$qS7tRzyTHGQezCyaB>XU}6J*&Mc!xw+%9$cUO>QMKL z>MLw`Zw=Tvh<$P5OKENVpkOjKX&cH4LQs0p1O>i5ZTt- z)dFp*^(i+*Zy0ZELw`9CO?#mUQnAh%e)dp`z}#5<%Ule46-p!o`vx|oB-;H->eC8k zo5-%;_#(F}+Pv#G!A$Qi@BHSx#6Hncf>jU*TBn+oXA4a=aed}~!^=h)YieHJKZol5 zWvSl4K!)(TYM}PI)tim_G_rQ+kF1bI3X=NY5Z;`O|1AslStF57Y$Bbhcp0KicSac( zOZvcgWGUtZl4|KK%1)LFAu`9f-1%szr~<&F?}tRdhH-z<{oxhr!^x{(3KDYa`ar+9 zD0atuye-j$VV(j!tZBIMY^u#9M##=_i^dfckTygsMPE0yGpWO%(dA+O{|yhepe)8RFQq^fp4BA1fN@9yl-+A& zfzyZqYxsa-+uG=U=5$(pA2{jEMd=izS^jX`>madRkDWEx@#5C~?lpo_uxQCRCE+3D+P^97Qgx3s&Fl ziCZ>Q`DXK*(?s;?RBz%()E6kfiny55i_GhJ zPCrGXv94^aFNuU2qkSW5@DRNejmwM5y!b{%*=-sf(Yyw395RZXB*Z-~zl}Dpv8P=F zk}A-Cawuyms&~6J`V@zrC?#pNt7gQllT$V>3@TL9&lOWD4C?VG8KyRPVh$6b>F-M*mlwLRKy!-3T4*R3&tY&9w@|rtD;E2l% zJYpl7qyEAT8tK+4TEMw1e{QIwrX!%N5w9x0ja?0R9T`6xFx{=o$X z;vmg;#hZC^IGU&9W(Y`7zCKv5gH=vErI^~34cF{gEbO;;U9oH!*jp8UW{lNA)0#G1 zT(IUb%KxJW7k7<9=iLf*N^wfj+T~@Nm90|RFgyF3oH@)XXw>%?HD8z%+QG}pWCf6B z#d}3+bxtKGp^}0{Pf-)RBO1^p^a+YqslfFO_B$~rKNP4rs~vanEOTJSsq4N^>*FYh#<`D5E!ZrhK|O@D~j zHVh6kt`$pY=Ac&pa=Re52hBIM3>h!&A2%`c|scc;W7H8B5Lw;4Td&BaMA6QJbQF9XB)nTMejdF$t+rT#IaLg85 zfe5`iX3W}?q-y$6-r)r}!IATEWDKB>vdi2`6&T-I8D|3_F7OR<8+nRL64$3^0? zS}!B2^D>5U-+NthDV=~uDWlljh77Hq!jW+!fXt+m!PlXXAu>Dcz)ZO(S=`|}z0s`$ z^PJqfOTgdEL*f=0(Z^GBwyCMXMV4yffN%_>Q0_Fja7r4Iu-laerrK~?+!5%W-W;ZV zMsxG=lLJ>&)CQJ@5+vsSD$8Ai(VZHvd6oIRFHf6O)?D^+Yb#ijol#KHdHH|F`MTI` zOeAdi#)^xS)1F@0Y0PW5`RoX_;G;FCpBnPLocKYHWLEQHMq9Wm94Fsp>*DMde&f1B z3Ya`Ih1c9!4CnFKMiPZ{?NEouiy#+_d})Im>B-4T|3=CYlN2R(@`BW4`KL~fcFB`n zuV2PKLoY=LIQ(-O+>sR^5NJo?C0aHVAu)6Ji-Q8h$}Bk9tF?91&`cN1W+Vq`68rj5 zM^56UB|Nwtpe?04_962{?P=|}V@VB!S8hr~@wiPsUg4b#(nQ$z$r#0oZcHmq)z;uo zwTs;Mll{VqL=he58vPn;g~dbh21h3iM;1aWuhR&?1jC`-&ve2Bz9^h~cXZy?}x z3zdV{G1i*CW}BfrG{31tl7O800M;4B=q%JTdCR`>qeOP8wnvjTdfqYcjGqsjBwvdE-fEqeS&*lX)Hl!wg%4b75U?jV4$}SIG(D*5MV^$Sp>^T}x!z~N7+?It3Guu1v(#RWI??=j61kXoC=p1E9 zcDG-C*`w1L4HM`_FY8nL0PhPk;g0xa(l1F_szdt%U&YKUh`~w_1y(NDxEegBe}WDj zu7(V0o%AD*P`1ac`&e#4bmD8c+}qc(TeNOK=HOhg%3a$oyH+5|yW}9Jc#@H)kSTOB zxd~A$kvcS)GL09`;y#VXColR-HdAC(u7y-!oPI!*;C+1!!ForCy7BUyZpMgZxHlQ9 ziT;fDwrc8X$`f6<-5eJ^(46jYV5~WuHD6h?&GCEHW9cvLuV^{D#)4OE*mdnoey`y* zx8zi0uaQ*(+Z*g8$v4N;L8EY=)05;Us+>IHbG>tS8B;M?)i zwN*(wu#;r5@jBwaQ)0qKr23*-3N2hU98Q1F%u}AwroyK4;Z)MGlif^vUx9wG$J*lJ z`0i6Uqkco3@HrsH(J$Wei<*B>UhJk zXD&FLxRNq+r~R;*L}sFE3J-2p9O*pEE2g3`8k{8@I@+kRoZIgu`9)Z;p@H8AA?zkeh9b({lhuzca^~vhK#`I#A~Xs(&)<(kL9!XQU;>p;tuCA zLt$TN5*;lwu`a|Nc4s-;QWd<8x>}*^)4BU)dSooSf7qJ7)A)LJiJyx}NQ{QquN|8G zakM&!I{{k1+xRIJMQhMW~h?u*UZEZd2$3N8TdBk@9Z_z_t4cNUAvOU%9<{`nF zYZW$!Oeb;XOtW3kmsI?s4oxUaUPv??7Xl_eB_1s`UZ>eE4#I(FvGNKUG`*Wn+R)OB zwE7f^Vk-;-F4L(_7nT+Sf6U?yB3nM*bX8i24qiiy_bcZ}F;kEHigKlWIByR#M|`8M z{$W;yXVe=>=gT>v{1ehuJnd{?GMXOWgu_NFlkM$V8k@er@R8v7=2Q;7lU-(bDY`V| z^G}Is$L1_Tm8hsO@#Obx8&T{SGfVRf*3&w8u>|zWK{eyy%w-7>)32~xE%ZINWrg!` z8D&c~Bi3v$*!f z8ox26y%AM@w?6fhxbw>Vd-dwpo(l`Q4$e^b!RML}W&7%n04fJ>-QI!=xiVe0aI9y~o@&(e!zDJx9_^y=u=+Nl7U=W+ zpzAP-yS=-=qSe}?E{XARUz`UHiq@(yOETYF^tI-LwtJL`f~uVdWdD42gLKbFC1v-v zd$On0*~kP0T|T;2-;F*zin?=N^(O&+$BsGeA3z8l>?z-rW>)qXU2c9#)L4#)tRFtp zDR8=h=J|P)H$^jUf}FD&5d9`k;{31x9)TIQViq_^Np~Y@qW0Y*@Pqa$vOOyNC((UV`$E% z6d{=kT85{x&PVbbm`vO2r5cvFbvdXDHe(0KFUS3SnC-@eLbl70Mm|8_u1vZbpW8DK zKk}%KfH||@$Z`>z(jjjv&Z#VYDwC2Hz1Nc+!D|TD5&Ib}74x( zQyu(5f}q+C2^*p;CUJX5NgdXbUTsfhZQfU(?G#|Qns0klE4;RjNckweZ>WNuiFhtt zYNk2;dh3=}#ub;z;W=Jw3zFj)Wo}(`U`{luG`)+qqN1S|9sm~FrAvOxvDRo|>DSS*T z+Eek$>QubS8F}mK<6HE4b3nzi-LThwK2>x6X&kF)=Ttb-Ej4NO;GEJbnbd5uWy*0| z$Lj*f=5Xjqq9(UFYyREq{K~LWF*TsBT?ZCxZ-Uo1Cb?(#2Sh_88xSb&=!5vatHVja zMdYj@v4fFlYFV|it>AzSy?$foTqPSH7Q=0BBD;Zg-lRPnSSEvEE0xF4c7XayDH*JO zVyp~2p~@*w3gdoHRb!<+h#mec zwv#WHgXq;yfWV#E{NxjoDI}dO`Oc9V^vGs%6>(fMWcz5|<^QJZ1<|dBNHS(RI zh|~&aVmGm{D=!W+mpj_*7Hfn+-`vAlM10;xA=ASxoM#(bOr1|DOD%Uyv#6fY$!z7K zYlDp}7aGwhW{S)UiA_Vg`s^@_AM1ns~BukgQU7KN;-JeO7 zJ_D*lVE1s@cb}OZ##h3y-^puXRmDO>2u2bd#&b58z?9pl+rhFw_U;p9W9r?gOJmB+ zN09V?dVaDuiFGLEF*Qqd1EV>QNHkI_!u_U z_GqowA#2xNM^2l>+4Om3-CAM84qQ=L{06zm?}=askLj&gw1cyzo`4&ER@Vk+JOREV z@zklz>yZ|du%e2<0T3Gpql5ctFdhE9h+iANnB6`D22COwC3JU1J6#(I3AdF=R-=TX zcK$?(HHvg15$_V5TMXFE2UN?~$fu0jVaYH6>1s#G>^>&n&p>$9*u6T>&9_jru&-Z$ zOrO({`-vD&CVG&~rKt6w-q(g%FDUwX$%0yI0gf<~mvFYEq*#*Drf;GlniSyHIV?R+ zkE!F6zW&lS6`NHJfkkIIF*=~TDH^ly!LiTxLA$abOX=v-T3DG{A%$wr#n4ne(L;8p z@-$YA2BB>6ZBs#V3FxT=@1H$2mGADr7B-ge2PMOQ{{G;;vB0C=-=>LwrjK?=#@n5n z))ZzQp2>Ci z;N!O;4NfT;^Kbd;b{fg_Bryzvj&*30G67S(I|C$@$&}vFm+4lrI9R#Z>7IEqrP(Zk zEOKQ51V^25yaOJ#f5M83urj?%$xfdX_KNQFGp59O=v!RP1kp9uX{0ym(I}0e9xwKM zTOc9>HF02;ea*s+uXQkF0KdW-hm>8GBlfV>Cn`hUdD>uVE>*6+;EmY-MOL=Z&IqA- z-THtsJ}A(J)l%BvaZ|O8%Y$Hw8Z!-KAqC==l^{k~-aXu*#$Fvp!N!)-*Z)AC9)J9X zgU*ZW2?YiB^=qDAqY-gv5-k^1ai1>Jmi92R9&!_QdvvpC%fnoI5(N#&}t;pBcJ{qkA>Ak z0Ido7tr?U3YAW)B7N)?RKI0h9ue}qPHWX}er=3Z?kY-!SQ*dsS;EbqaeBjl}6a-^O zR+||1^41;L4lWuZnJI%qKwper8|X)^!Jq-)?~AG;E%K7DW61;r3L-tK1FCbx1=y

O5j7sqpPsOQ-yt1-lgY461?8iE!wb1FoIuK*of6P;96|eI zMkD+pi61mK8tN)5B$+df$5PDcw2f8*35-J$u1pS_%@Q?*66{9x0BN z;fWGW4JPac7WyGi{(|x;fRoh8;(AWdK;%{`LoARbhW?nd+Trn6$-$pd9lRwsGpT8b zA17~)B%Qk7v{%Nr%vbFr1_`!izEP67Vd&BGK1g2zJO&t~l$^E8wm=%uLg$L;vwK&toHpZr-tciwG zr*gG>etne~H#u(p@rJ%K9}}JNThaHa-pdJh?w1&Mnmo`DUiBCnGUV+GO&`y5mzTl1 z$igERM6&21*X15|7_O6);bU}UAzug|*Cc6X4s|$R%Mg2ax_L1CGtIRf)5lsywC>IE zLA?+{1u48(f}UMPhpf4ChNO9i zFDJ1#rY#BO)eI$LOCC&oehtjs7W3hau{c&fuTJ#qHWw1E(xm?aoav^$cL-6Zchd}L z`LG;$;B7VDG@hv$5wJA9xo`@NtFS1&*sZ5gbAf*xQ+`0>Sg^9DVsestp}hd~ROaA@ zmJg>_r*k`XvRh0P9=nE>>s$Sz8@=Zvny&5epD z*-;~hNnCX17Z&VsoVrKi6BXf9Ub3GhW!DXifp?CmszS#)@OJc4wq#l^X6TcDm1c_o zpXfz2LGdMCgUsar1dF&}-%WpqX}qnM4td##C~y?TO<=9I>Q%Lcr27~4eBrfGXdhrd z`!a>0tE*5xaLY6hh~oStA^-fd!FDygzY+z}iw(IekU&9xrN5dq=uL%agWq5E4kp9h zj`nz?B2pME9#6Bbj(l!B5kA9sC`J(Oe}zHyuE*8I zsanVjgBZ8*KS>M~oTw}@l_{-X<_511iMFk!_h(JXwj)P`mIp;OyCpqXTpuZ);Esf; zkK8hFGwS`pzV>EZm#m<)2v#2-R-;c7`zSmmeX;Ufai6OZ(WWLD2A_k?mk$K*Or}_>W*I6FtC&io*PF5O8x=+ncilfpI0pY}HjYmKBVNLhw z#4cclr=#EB#cbd4Of}s`$7^s99(0EB*5Zt!K0mT5tsXGy2x>CmEqK!Q;x>VpfBmtR z$3l^9qdU^o1gUxJa1^X4>Wb|g!Qd!$f42?SO+25sj?)u7q4SpDv|!(#y)DatH2`ze z_{8frnt1I<$Vc-aNx&W4HkWNQDsXttE7M@}=e@e@!#CJZcq_T7FJ@$z$w!T4wviFX z%Lc~^(`x31x<0DLQs@XIq-$JF@LE<&T_r^3-=n>4pJn~yyXM7Wyez$pYkL@DW)8K9 z(Cnj8Bf%Qt^~#JdOywgl_i#*jBE%K0j+GbG?IbB1s(E}pQ!4zyY+oiQmvc?lNA5ZQ z-GWeCNjr>Z3P-1pvMTx}!)4S|l70{Su_+n=sgygdlZvtXzp8u7s5bw$U9*J(rFd~K z?oixAafjmW65L&jySux)I}~?!cX!vo? z!ir4v{o*ZpU9MMj4w28!@ez@y*Qn(0u}F~8#@TN{i8ic%Wa~V4>=MPQ1b8)%n*&=z zJPqpIR#s#_B$#Q_`<*RqZL@k0(FH9p9@M*Uc$bNWupik)bM*V9BHYd;OK*;9b~_?g zM(wm`%Icvo5zz?8Z1G((%6CyrJfy$Y&cb&TTO;pYT*~rQEz4(>ai6LF%7rEGtr4OY zNLI-2So{o?T!x-`oc&s}KUW(0GOgE^=cPF$9jgGGvEnKiBO#Pf5EY(+9>V3ezic_x z8L&v?(fJ6wqc20R?_?r9Tj5hk8u7eUje3Lu%LY-A#J7=)?T@_b4_bepArjhoj~J~{ z<8aUu{{jVhW0+0WO}MTr0WO@WEe?Q~GIAR;mgr7r_ZpStae52yAfM4tv<^MlOxHK^j451`@ z43ovhcMEYSL@^MHl&X;?L?96}KeK%3GLZY% zd)i~;efMvQL-EUF=f?-^n(*s9@H&)}f&c;CRkB;V1u^;P!>n!rYxOSR4Zz*~uOQvo zSn-izKRiI%b5y;QFu0rV_OAfpLf?7$hOJLo2uk?|P81Z8<+#|&ecJen0oB%tUlALE z=XI=!yw`SuQ`Jw3Gma!ytEc8(^gLX$`CsAEdw~eulO43(L^)?;9Z~odhfnP-+#Bd8 zOuE;cp?#h;lyRP^4TMOAj^lRCoLDss%Auu`cLpcc6hjOmRvYY@)FOo1+F6%|d+A$g z69qMo=fgd5kM^ktj{jH#ds~bXjFa|1jBHdxSaChCItkB02debS9 zf4GsPT7sdlhSQHS#L0q$(GJV9wZQ&x;rEdh3g3SHj#FJJ2ompY+6IxpPaUU3QBZj}faEV6oy z35=$%5)~hu`gAY(e|M2-4)KvOpBrDKT{7Nwus?Z-(npUb%)ytdia(d&Uf@6p@All% z)DAU!K*jypKU=J)FU+P?m*}kZai8S&pX1xu8XhsSvHzLP-nymmjII4{#-LK^PH?)c zgLQ8~Qu>n6)7y{OF`W{tw90f+WKw%WC~-I0zTWZK>jDw$?g8!gp+G&3-lG{ru>I*& z*vW$}I9fuR0}J2g(Ynw6vVx@Z_qZ?(kk1{5JHoee%-o{2GTe-p)sG_lTWBZFCBfLv z)mdXa!+}V`yJScc#A0N%t_fUeyiJd;Ltlpj8BUaXMv<6Tp6Cq5%!UlV91F+&O9GzV z5@Q3@{HXhu;go^R4RN-(HDD#(BaN~mWZha>poo$(P~D%P=5IsRk$zS75%o{AAlPa< zV`YW#P~V*Hp!Dibb}7NjAXA(zAHQxy;AHI=KIVY)$3(pk%-G&cQ&38C5qzH4W`Af@ z;H^N>gM*tFCE;6b9ILhR)>VB{ay!ZCgjQYN^TYE&dutngR>iB&yHC{gC~ksiAo$;b zyegm>onb;-)FBkANFOIwe|Ir^V`V#}uN(jO*y{dDg;1d0P*8|S z8=_avZ3yizxveLZ`s;8r&?!M-`C(OLr?T*Sg9mF2IrD4bz2V=((+~*;5#0z~30(RZ zL#G}x9SSOSObMm2(=KqdPiZm@)ckRg%1h<}qRf%q-D?zXU%qEe%-`cXv`StuaiLVmH4%z6rk_zeZQP5eBspj3iuY}WPNjh+HZxQ6bgqh z7@lWP6G!{vG)ss2sl_Rnp_LtIvWGgR))nkk8mH{~YiX~z;xO^*xb{{x{=0(~mY|(J zcu#xaHZX1=HLwx8GTEc(I3KN=7MkeJ%TDFSDAel6ao`r08ueh*atl1#5a*^|r#yFF z;ZGLgQ0g|aQ>LXf&#=dGyUTi|dYmqHwn|8I3)x#5qSCpp_H)22oyYOBgA>|e4whHU zOdsBztqM5$aCxL962{7!UJZIy3UO4#zlRac%L@S?sn0#)Iyb6~wO ze9;ROU%4jlj!Id`)a04C4#T0IuW%fVxF(lrDArILO*k_7ZpBkNgs$AV;;X0O`(!ij z-2R&%!MT`+d|XZ?egsgD z10>0H4vfq%Uv~e*1mdsC3($~)=1}=Q3fnmxp%~Qy9GY2U5EQtOj}H9ZhwYw}T_d3m zX@4w=F`Qi&{YGm~b;+0TLBbAYM}M2-y8G-5&Cl(2HJeo3g3I=XH@-R5?1|G!_Pd zu_+!Gi1%0-^p|QI|65)}V78Y|A%HhK4Aftl3~$1)oyetlYB?;afI+6W%iltY0JKpwqcx9ZhAP}yW847-jXrQ1o32l*=f{aBU&q;3QE?SNs-H)Sav4GP0 z1r&)mlAO#uFWHZ|L^Dsfr7INf7FgTP%ZJrv)vNu~`aS+`=1+b#@YVKP=z*9zv5I8V zVTCmtiv11dOX9qKM|}!<8UwF(3TYsPON}!blXB-|5O?Kb7SL=9#IZz^QLTp&`QnLaBdDnFY2E65%CNy!9ufA z|Dj4)a7Xy-e{%tFtZ;_bhl-)^VNI74W4g%gypfVcGVz#VDK!5&+%d1j+xFEc0uQpr zy?@~F(5Q54z$Mn%AF0~2Xz;jSFZ}%#ZWnL`D^0n7A`Xj$iKj_3WAHA%dJ}`rp6Pk- zI$~atUsOQibboy7fnNV9_V0}IAQSLdAAtRUqQ_}kj)xbVbTPLcLkeaiPx!pZWZL-Ct-(#xM1aWT+#r8V z?9J@$Qxd(X_~SQtgi$C@EiPxus7TERnc^VX61zEXcM5O7FSU@gO-LOiq!DQ4JefM8 zH#}>o3QVs~`bXzp+8eAAZYzSzIj-@b3f!st3I^4iEK~l ze>{@%L_(na<_7-j^YcF~8eJ(nlAIsdWXz}=L`3nN{^Py7A@%yK(Aq+^h1@eoHtU+> zg`G}UqS;)&b)HYuHZ7Fs`OGv<-C}dUq|9cqCYhT9-z{68>xGSw-F>-lt@^W+j6ajB z54LUsOlltJqbSCpHbGG4jKmrY23^!6BNhp=}sBYW8@c4AQUM z!9(jA%>wnz89P0?vxV`5+Cy%rbtNV2;>2{i;V?L#{#x`=P|eizTTHsppRK2`?HF7a zzuZi-_QK;Yv9!MK+50+o`Ag{?!+fEoz8`v|j8Ec)mrP8iD#J}_u31~dUD~>E+ zFWP73q?H_eI+jh|5U-*0n06u=2->}0V#n(Z4Q51|E0nhUIPg&}0Ye|5K*r)f#yOhp z1!o>25|X#-`ENPbz5f#~Pe;T@|cHZuJPRwo3zHJWYsPZCcUkJ<(ij5J|81wQ~ zME)31&)TkP`r9^C&SAJeQ!{R{?w%f2urke;KPK2d3n*@-OJ98<>9UMCkkIwsIN6c) zX@!isegdC1)p@^hv;w?9d2-$9Pc1>=jX~EsF`pmHqurX0?BTPsq%w2V+Hh3(dfKqz z*j&M9Kf|~)66K$#jc!H%XwL}8!s~!Nxxy9=>$~Ytj`hmw*;=Hyx}Fi6AsBwS6tGg~ z8GOjt+My#fG_G~>(BQhqAAvF7A*>C3@+;*It6+v^ba;dDAhc~u+|62J>{L{I@8zk6 zO<}d=E_2r0GSmN3)-+(iFQ&m9>jW~cdr{IXRdEvVB@ni{X;Qm{@l2FpER6oCu4 zu<1V%5obk){AIO-{I)jw9S`jLxzoItz9|d|H_Ccvx*2IzJKqr(&zpEfb_}`|1jHxR z`_ba8hHx2$8CW|Ea2I1UOs*$2kv}0YB~8t1gC%qC_hskpB6GHt>ip{4vYh%# z+~8@WNLmb^?b|@agkAD5D?-ys*E`UH$4{Y@QaWb;{~I~_ne`j^_J{AkH-Ig3EM=KV zPaojm;MH88b@F$Q040TisWx7h%jabB$VZKhk!7;okv$g4QC{Q4NDm4|SFg0C>f!O0S+^IW zp2rvRA)ct_*|W;JTS(ldanFZKwF3+WCRq&A^!>w^X7&eVoCGrWTsE?HXea3=!>*3*pc; z?rDy?yy5Ga&kXI9!arRB2aCVmq_t=crP#{lT#Rz+n|2pEKk;kG1O^;Ryex#w^bM-D zpF}1$B$db3Sw+WB?J<-E8%*kuYRv2hMLI!*VuiVfrgiY2X^u*EWL^#j`r{&uCy>Ae zNj4RgigP-PG9HD?mm9KTzjU#n3@6y177pJ=y!Fjb{D{;>-!Dl5B%D(vp1!8;_q_Z* z)~-r#UODcc=$9N(xg@PaN)fUs)e!0X2 zJmP~}3FrRMIGOYK^lW~mpx`s*05Oz&F+$zm-ofgkorEz9TX4;@O011&o^aoH1~_il z5Xrcx{bU51x6;vc0N20PyT8p!j;Enf|4(5o%>Nk1QWJecl%TG`l;TLb>0N}R7qK?H zh^B9EV7y$OO0CUeHFvVxllsQ#bm6je80)g<3^<-m5pTQE|N4Jxcgs`%Tf4h(3b}M4 zKpq{k>X9ExLUU17F}#3smnt1mgI`F1Yxq^A`r;`|zeb`H1R=q7cuM%MbZ$G2r%}8_ zOF-W;OZV_R%I!Yh8Shz3yD`W3O2lqZ2J8`d-C3r6=#_QgZ0o8;q{c6LdOfj6XVun2 zp7>IU`%mn46Iz0oF&~bb9VZy{Rrmw5mIF7SMAe!5iKAJA4=s6~%u#ydU4p{++#jg^~RmR~`PvBdMM< zr7vvj_)_*7g1+)DBB#Bsl>>6aJt4cR%eQ)jFIYNq#mx#fi=I15n2LWffRU7fJg!|2 z%L}Trva2rif8^v-cdde)Hz$_Vqay>0l%?pNfzX=PkVB?!g)3_0TKDPOexD4>?kr~s@qNUJT#E!s?8T1on(=yl| zPQ>a=d7`Un!5QIcN{+*1uwyhPT9-5%;=M*tz(}XM+TY&9)j=YVl!p-C35{|F?BhgW z0<^!Cz=}H`iEmiD)*{{>mk}bbUs-OPpE=z^(=Ov^O7z|6p?bH6wd_3Jm5uSmYhUec z)3aF-n_6V?gjdb1Aio$hUrcS)WNyEjhBdFa@#JMycX^gcp!AZ9T1IjW)oAk9m`g22 z8cluX;wEVgN^LaWxx1P6k7o$115%B=&KnM$D3*W4KE{SZGJZW_DcuhCP1x&0D_?*E zAEW*Zr%vs3CeDj1Wcpd^zr?;C|HQt((E{{|vQW%Fn}fsOP0K1GHEM%r`bM#wES6W!XM{RARL= z7iKJOVgB8DzpU7D-H=_ybSTST<|{DV*~t$-!As0aow0_~GpL-o7Te}C8lo~_>`@{p zDs;|-Og%Hbbh9w}r^OIqoGuuCvox86R|WayU+%_DR3tmJFi0jwkUmYeF$4k&QC+Ds zC9zG@S2=@Z3Jc)PK-4r=s6!n|5$zC|%Xd!ZE0c~}Vv_XNErhgsIGrC7!4;&208QcKMde`EnWb=E4?=KB=w zH?K^M^c$l+mCo(_ZKCT|OW$Z@p^_E@pNV)>pEPr`_)o&ww$|1KHc{AkJhJ z8Mw~(rL)d=mV64$z91QzlqOY>(KU0_f(g@NMH#P5t}GUjG-z*Z#=+fy2^=^3cXEd& zK_eEp8{sE2#3gHl9Fl(wO(;x{c`l&$dt@fi5LZ)4PIa;&l%C3!V?OV;?f0eqb$9@F z>STo~G5+rGLI^jRIz~e)*W~gHER$y$Q1SY=qP2j-f4*p~`L9H40bqKQ{@ySViE9s( zlqg@GG`1+7q@(fs@*7NUcby%2J9xVtcTgm&XkC9DrZob5AEnCItSNu_%FOsHo9^xg zV%~!++Pht()0RstPE$A)sCt!NtXa}vi3Dmns$w>4i?N*}c55bA@RwQ2-EZ6MP6<7;@8#?+$GRWQZyn;r*o*N+_*r$b<|gm=!CQNv z^mdwRhY1eD!?V8u8P{x`skVR1Z(MA1S3U>0jY*_KZ0WP{^Ozw0mgGwr8Y+~t@M*a= zJvv1`(B7$A%;@N`d2Y=P2ORjzbF6sVbeh_@Kko4xY^(k%A zw|g036DPq`eHIs?kyr1uEZlHD@w?QAA?&J5fq}|Q#3-&x^=Yi{Mz-kZaM_O0o)W6? zcMm!_D}tw^P*e^B)YG?3vb)od8XEExNpct-$dm6!+Rf}W4+ArzS{Uyj}((;P5q7$aJRB9QGTB5hz$v8(t)j5bzkBwP% z$4#~28Eh3RrNNSKapl6UHh|jBu^&&pII)nInV;G9pTj9U_OSd zv3s#N>)0*nv8fjKgfVE72jXP@+`Eay4c#-Uh`E-NUTln~tl6g@>0}8%o6SIV^iK$0 z%8C9LnR@&!7H(#o&Lbi!U=dXHlgx&Dp@wS7kfL6 zoq>5!1jXPwH!tfJ#2Zt}!xRtpv&BXe>8zixYqYZ#FNNvr>Xl0HbYL?doG*LMs--hd zz6_q$SaSrTqZkkrj|a^=fnooH{Dg`2pAs(NboYtk-rin9Wo|`90?rc`6{^y;S-G;% zUg{6B|I?G6wNZSBD>el-+U8{`5&+D?|EcaS2+rgBpC$+1yiqUecx^q-c9hDpeo1X> zt#^lA>E+4yZ}nWhSmvIAT^kUW-s`?!F(xcQF`JDd_GHz3){fUrmU3kOj39<}GUd{u zy!f*aJFr-sKEu@cl&?#rfmd+B-ezwTTma%;r?A?vsjZRpgn4@O-VV<#OIc z2ym`%HamsM5JJ9>scriB&AunnUTrrpid&PhRZbqEuNX~jtgp&7DRSP!rq;Qq$PGwd z(PlGAW>qIkt7jM{;lj1DE8hs{;9Ksd)2FkGIiJlc(pJMf!|(WN#+sUCV1F?xauKLP zS)%kip6?@E*2`@$wmC8E^+`{kPksKOca$}Fdi6umB>GOQlVA?bn;iykjrwYD%bL@0 zR6m3oDFOyu+*RnoXFSm|hE%hE%vw#XE_J5bm~M{&HJQnW0y0ops|-SBN~AMVibc0v z_9^G$Nm8bNY^=z=DISjS$ePe9iko-D;qy=oWabM8Y9>`Koqq*d%tK(TjVz6&O+Fa; zto{IK&R`@7>im2df4Fm89vn#;$>|OC2#eE*=%#d5G%f0Qz%#uf10=oyFWKfbHQ|sRK^ys{B@O z)K!fJ#@+)c4B-eP2&7gmoQc8r+Qy!c3Eqj|uiYAvw01V_TLVe0jVc`MjU94FMw?=> zrc658m$rx6tI*)R@&q4nEv0P&pbV@mX?dL)QtZ*8W;_;gjM|SflWmtB=#PDH<6L96 zYujB=C0iwoc10x?@)z{aYlDxQ*TsMR7Q?S|5u<3X4J)}e$yBQ)2>U=sbul3_jh)^{ z(Hs%3iAR?5j6`OZ5`L+yPtp_VSKl?VO!^2G`+<{jJg+$f4%;VFU zGiWDfwW4D}35Pmr5UW(CiD@h-gwg~Lv~`ttCep16rb#x~UF;MuhHOkLP_uaP1J>e6 zF;M=I&AC=!O$vIB@MCF+V{25oR*6hNMtcuyZ3IQEbn>0J(;~i-9HHH+QX_LGq`O`r zF|@ddx0@0^yC4jvJ#SFEFyT|+*;wbh!h#dFk{kmWOl6F@b9|G;jPrTl@X{|pJLjLu zA!|>GU?P+BGu9BX|IW~MgSDS~m7hE!&cM(@E2CrUqo&$?>*{!ojLKEV<#fgj83oc0H2W6Z#b^o*i3j!jm%oey2UxjL1R-G)-h z&43^pp3d@N>!A(|=i?Si>ATw2BKjkGt4PbejJ!s33yS?J`G#)jVf|%PEo`Lc}G26KGyGgT;XJKjCrpN?k9qxlFa7748yG*9o~^`cYGSBQ#C@W+WOlZ@fM z@NfUl+xU9Ktvi|I;_B(?ry)MA3uH{kNwuIDGepK_%21wt?D$ zPg@YH`s_9`@Gg!Q!Wuvl#OD$`zDuEBsvMsYTkw`|s2J`D$7jmm7LX86%{bgDd#0(oO&h0^wmZjI`Ysy|N#FFZ; z?oDUe#mX>Tni2&U{Hro_KM9saG*ctJ%y3sDIj2e$H0ZT|UP&&YN1Oe**D|lQZ+ijj_t2Y8RAzfffj2AR?j) z$?sclpWbddCMs<8KJ0>t6_el^Dpa}bAjVw3RO6c56?&lhzPniCHcD>n_}Hf_X|&ra zM9-}}mXRFi5L#b9&g0z#OC^5LW{p}cKen(u8#4YK4<`~h&H%Gib8ir+QcDzjO~zRF zV7H-~Woxd$k?Ink#}{7Mm=o;}1-GOqXLf$0>3;n#D^5yAR(qTG`3tPcz>k+Pkblkn z*c>6ikE-{D`6+vNR`4Z9KGDfO2IbbYATUnt|)F14%`SCG0um?9R~1 zN_D)jA`BZ(Uube;sFimy3;)66Osdd&NCXbMXE7)$CfOsrS>>YJkaqxhs~l|~BxH6P zV83^;7abQTC}RcaC&SJ+^7YQvX@MLF*7?H_n<6rBdATs+Ix}lO{pNSY;Ox)&3bRFz zoo{@!#56O6EDHg`_kQ*5j{3zHaaIo>TKXIM>!Bm2?*wh3_4k?>f!aKqq!Q_u@&OPk>F;^YmNTyVm*Ahh_~+>{C+9QpR64J@OtJGk@}3{ z8LS4@YYIdRxKslc(5rtu{hmp;gTi2ygqRvzjOgGv@OBu&OVZ7fl#hYXhsJ$RCL+Xa z$2T!r)YuK9HFIR6qh#r)eADC)_2$n?L)aR%e3@E@PGd;Frsu`XM1uSD2%s9T4tH^uue-@jvS^%n zkE?ML6+ti!0k*tgL*`v~kQncCOnJO{FW=cL|4i=oyE+LleCjQ&54Yo$!c93=Gx73y z0(EM!V7@`F#XKo8IeevmeG?FYZb>Edd4~>P`1MwAF~jt2TR&8dH|$QTyDpP2kviUX znHnEtGWSY`k-qWkskurmfi-r}b3A!G`_MS9%&+Y8U#a`4PftW~%&jq3zxcu%;b)i} zi{;b{GgD*|FaCJ{X?hV&2mbY6Qu4@Ba~H~T;lo)KMQXhN*Y5FVKL{1H@umc{8M z@q?aj@HuVBcthY{Tc3h~WJ9FW7&=jaLNm;4Cx#3gR$Q^1o0aF#{#pnf!%}OK4U9S6 zhyZFw5RsDymY|9<+1(+hwkb94eE)tJuG=%hY{DA!(|h}?Spv84Ns$T)v&SdFB3g=q zGohntM^Zn5h$VS|{z;F)l9VGhQ!bs%Q97@ke;rry$=z;CjUYBlF=h;4-&+EbJT5SB z0=(y?K-^aPb3sy5Z2v?>P_teAfKbMeNV92n7N;NQ3v6LuA2KR)gt%P&&AvQVLs@8qzctYJF5wJ=(M>|+0mO71@U5z%Y@wEn9(J0h~ z*t>JS87T_UI|_aBBSgS?%A@G3x!rN#9wxc|Yg??AmMUUnjv`I+P-85pyezIgv{s!6 zQb$#9vU!fPELr=hlzN|YIPy|+-QPlxOU5p7QU@bI)V_Sb6D!udAqCa{de*&+5BhlZYdjpeSbR>u!{ zA%101Pws6Y%UeI_-d)A0SHG-=JkQJvqE7Xlp;LqJ2@0xOW0<_8ea^C0gz$d-Tu3}@ z)Uqh~E}o1*bx`Zb)s#UeI%3s>Y2~Hd6Y(`Q?hC6GMFy9sxTUjSHs|o4DmdYMp@)tc zF+7$piGumHo@YHJcD=btAX(TtX$tpa;cR+uMIprFw&@R)+$J6QL4|7^--5#yf zZa03ESYF3yhsh=`2+AfE_(Aj&6^FIo^qZ-57=}8)+eB}PcE(77R#wHI%@sY}GFheB z+L;Bo=8%w8>g2*PoUh@`Ni7LH6n5x`bO?+4$y3rc;=3!%Lz?Qu;Zw!&)ZZvkAhzilJp|DPebaby zxRkjIAK&d|aAt7!2iDtujM1{)F)FW$(%){g=L)akL+W%as&z9P^b3nt2BQgvbrz|F-w*9iKbu+yLlW$sF z#E}xN?{puhKJGS}wps;nz42C?hxi?W_u*B`Gc_ffK0dMI?QHGpx<4%0<*BzOIWx!n ztJT}(X~rEh7LWwwnnPg_4Qp1mCP(UMQL7z+;nOIzcsu;jLb0So8@XYpQUo+QW(Y{C zxHmIeiu9y2Xk&}{Ei1~Hg4fT?BJUQdMe1%hQk5?xQ|X~Z5Dt&QUMIXJs4+a{yt{AF zQgzhQw%?0VQBW8pOiQ5m9kk@J?0(@a2R9?_Q84POXk-D6QFN{SrV|(Yl zf1yrOaPANNiXAss9m3qg6f%9DT2wjhxiaj@ws7vT1k<#1p4rPTLUY$r&d7gD@W>yPL&id4$dum2*6^=PN|TwDVZ9AXL_|S}Cui3%4*YOJ_To zaHkn8EPFq@rC($W-8_Y`*N>$sISb2ONSUSP=Yn^$wwXn_?G8k+ml1^8jh2A4YE)DZ z=BRh8?I`44+w`j{af;_z@b+c03p13)`<>*i0IVVvl%e{EirLC&!Zr5PziC2qms(D< zL_Oa*R@nz?KB^%rM0j1E^Y}gnwZO$am^3@$3mP|Lbs3k@MFUi!;FoL@wdB152)gn0 z?M`}+$p-ulz#nU7z>50Y*xq=q|1HbI>wOQql?}dcTz_D>2{GfnCG5NZ+WM_)t|0H5 z7G1K|Tgl=pFQO)0!L4*&+;uNYrptrT#+w~si&OHB00YlxP1d6=%cJ_owFw#DIpzbN z)Gh|EvZh@8sZDPn;O?%Xd?|6H<<3Rf0uX>e#O{R0OPJAH>Zi7a9bCnT8Dz$fRol5e zoGHs>y-qZN)Bg1?5HAdq-|R=B-C>u0bQF@F^b7OjFZ7vNP5u2MmCJ4#4&UNynwA4B zZwhKDz4v(P(o?POObE0-;p$p%t7*brS8`n^903SB zaU}gJXcd%;JAt5pwcodL#^cWDRe>g@+Ljx~{nDw6p%MS@!>8mg0n)&;rEm3g;fQep#=TpTmIE#18!hk;wE|=tn zOEoUs=R?xVD^EJg&f$E}y;l2dkzbKA@i&q6+Ky>=Z(CM1&Z|AihOXn~16}wmoiSa- zIq+%?X;tlgfSG5e3DcACo%`dBJaP%sEbgblmnzFPoBiAXaaxaNRM~Tr33ooPfve!v zqk{;$QN;>TIyGANT$)}0Z$M;#nHMxutn6P z`E~?0q}MxrLjL@W%|b0_y1K814F>?KB%idx=sg*RaSkv9gReDJ_kfIxJIJ2~SqbQT z!tx>m9TK_##l9ixy*`ObGB@VIVNE%q(bRq^`s2nDf+q78FVvIB!bV81FJM0SZ9(hr zgG$>Jr!f+gv9(zsj14{6Kg52p6%f%UYtAn$sip5g@l^ShIP{anUM82oiz|QK7t|e^ ze2<3or+OXx=3VsffmNtjzHhb* z)aF^65P{vS(O0_8;mNQi#=a6VF`sTu{y2Z5tqD^3w;q581|?G};sT zKV89C8Xdu+W@VZ6 zb_R+iq7_-1BW*ev1BFmiA903Ev&_Sqw=COATp|emh&loS^54Zn+FbK`tv~lFK3={( z{`xL14zqlB(xLd!XDoT>nmz;&)_>ztwqEWlzsSV0D6!B?a&cv{wWl~B%^;?;WS-o# z6p)C0zF7TIj#lUR;GkdkB`9!L?RNCDlLaVwJHaB@&_jHzyd#}`0l2n;7D-O9e}t4* zVo6D=*A2m@mGbAxuCl}Bqlh#%_WSbl^e5jhEC$G)2VOl(ZpJ4_S>5q^AndmuT%P$c zA*&HNula6ObILHbz8aG4FW9Tv*?P}rI09IWq(1riq==PiQuYe-tAjbx@U|gfSU(4D z|H`7?&zPHyijHN_H5*y_upshMAudUw!NPWVl@5u~L9#tkfpkn0RZjo2#2R~WAF)SD z7UOhnT(@_1u8`sCrod}FK(EZN-jY*_R$LLnXIrg0g_n1{N$~|$*REc-wPer)mTGih zHm4BAsgb9f$TAyP6dkM8;G-k1Gm#twtbO!lj+yix-pScc{$y}pDW!IY zPB?f+w8r0i`Mx2f!mKNuDVdadfAqG;U0&f3zR$ICh=XX}yS3yO2Wn34@LOh7v zhWzMJIh?xiOk(oaA@?S1`)=tXBxFN{-FzSh66G@*OjN6vh|B>F7Ci&z=?~JVn|!FD z%oKW!S)Asgdk|=!bdg+}wub660Ate-pMwhFGg$&fp%HS;As5YIn{>bKTm%BJs%=e{ z1(dU>vwz&~p<}B`70xh1^U?+E2I!h0i<5*wyJ56kth*e{W9jSbCv(}7l87SZxEAo< z{x6K!#+{v|Ej)Jh89t*nJ^p+2n!|+BWq%l91;z6aJ3InwZr1YO8w4P7986{<^b|Aa zl|3}qkA?4{)Ru&h1epX_pH8>GAZmZAmXpu*>kiBQM8RT#7ZR4&^Q6x!>1M0-{;+b` zhcB)F4w-4PFzeCA)A@~L?ZaTK0-LRw{(1A=FJ*NCbRiT!_|T*cRFlC%LTW=Q8U@VS zSiYf2vU?7EpnLWGt=v_!KXBrXplT9GfM_5(A|mJ2#)LauVrhZ$c_*4XdnXXJ(hurJ zBM?VrfJCd>Z&9W@o+^OZeUI~sNZP$cc$dLB3KvHw1K@C%thU2@B3p7f_}p7 zcG4&COpOG_T?)28seZv2*4rJm{Q7W5_ID5;IN65PeDpPe)z8b0aktQFC;iX$8W(wE ziRgN(V~NHk0eLyNE-*@at3g=j`Z^qTY+b4ES{M@c_L_(#7iIi{uy?V@;pYnq!9nD~ zRCwe$FXNEw!dnNRo3(To^$K~^gT|Z?GUxn~qKCiN$q-RXP~a=VRnD{dYxR!MDoooh z5c$U2Bh>9P_zIcA1ozp-US>5M;O_?*$_XMgoDK?DIge69QX9-{Ue{&nr#xmL3WW-P z)@jhZbUgtiyL5&hCHZu3{!q3`@d<&h;aplG>;ojZ{U3lENVi9s%t`!y8~eYE9)F@0 zd{@GKnOZabIN(z5;Ppkk_n5Yu6`N$=)~Z9XbgM6T7*F=un+|L0${gM*{zVp1(0f{7f zEqeFcMlXQ1I5|~Gr2m4=;8#tKD`+hZz+_?1iqw+bpOgy4#w+e|%Z{$iU!@sV_-)7V zYR(-pNjZe}tvym30C>&n%n~_oK(P8_hjdeM6URPwa8_6XbI~lP3Phz`6l4AJeS&x0 zNhRe-#;_Gc1Dc`D-V{-!3f7rjRr9uUheWydTt^Yc^KcP|=SXOrw;?QMr=0(QLar zUK*6UW@qNDayG97*)YOUz9v5RUb$5E4brjA>D*+oa(%oq3=BE)pZ^uKaH1EZ3(K9Q zf13-kG82|V<1T_|_=k!VeAMO8`X@?${jaR^pZT=Mj|B0c7!9K=|4-nDxUh^+ JrGT#Q{{hI~h8X|= literal 438840 zcmX_n1yCG8w>9nrCmY<|o#5{75^Ry+?(Qra+}+)MaSJ54J6VDg-1X`oYtDUZW1mQrf$}b z4rH3v_7)$FP*5Cf9GrWdE$r<3IZ}>m)A)K6hQ4w4m2jxlsfI5p%P-IYY zl46=(Ij6baIfh!9_kGj+_ghtUXC=*vxm4yD!I*6g^%Dfh)u{0lQ5}d1P{mT_$@Ejv9jTI{1cITDgCSQ*Lx!8LDm6$J$V2*ox!v$QmNJuNalQz((hY|vKW zN%A+)yY#_cK6*cVkSN%xYn)nRb{<-jUcqW<*oS; zRDL-G-?RGm^2D>3^*UgY%VEc|1AxcpwLQvOprWY7YMuGn*v7sRk{UAf?Lhcg+_1}PQL~biF-KGkwh8Htz45{Ukx=JzB zm2~KE8K3wYnW8D= zOR+CdAT_~RGuT*P1qA5Rf4SQNDJeqk^XQ_#+t?JT(t+*HHjRx5`x3v|cSj|ACD>Nz z!4I*Obar;G11Q9CrHADdTlFWUOqBl@Q`z}ca^D>t&-e3ck=vy`=~WYQ8B^u!<=~16 z=yG#&H7D?JYZDA&ma8Y1>7G7%A2Dlu+aQT_&@~_$YiV!yB&@gGv?bcsH&8*MPn8D% zjcB-PTfu@T?6kDygdt=$vi4W2h=^q0UlH9B#tWuG*B zO_w=M7JyD(jTL~f8^>Z2Ol)K)Gf^~?89Ub!Vex;?lNWD8e`&ClgvA%XrdV@`ad`O9!2EW z-A_1NBZsIZ6jUro*Ain$Av<9gni1S>Y_(OJddzO#r6OW!+O??&QLyBuLp5|0e}kWW zYCP{{hA9G=p|LB&h&H)0RMfjWK5H+yeWRUwb)Wm!zS*wfv2L^Zul1-4on_MqE!tjJ zMR}@vx2L?hxtV3c2px#FXp=fMHMPtWTmn;T$Wr{hT{6z5bxkRVnA?>6bpF8FX0o^Hh5K|@)X zjcK|#lH>clUU;!OH76!-uFaXvUd+$vM6%=;-#4Z(`riE=-p2Kd zh_FX8pxE(8tRQM?aEV;9`jTpK*0=^{a{@}YdHn>#x@P(I*(ghZ92zfN_Gr8jFEO?# zEbwK;y>4R^AV-BQ7+&x@At%Wjj!xiFH5xH@(p4P?rysiLeZWpaK}rIr;jfIQf_zM5jb=Q;wNJe4Hb2&H248&{hx13F@qrN8Jg8! zLUmzDYV`X}LT)+;lLKZ^qAhtTN51%m&q9sALOKg|G{qpBq}I{l zp~-5K#m&hwhONC&Km-1+ZadNw7Ykco>cqG=y6mR%pGFAgIrPYSkS>hbIeS)g!mu|O z&I^rro!9x7l8EKw#3I!wBvwp3CYl1Gipv_}%)UfR7ESrehBUlu2hAv-JUNO>{UhuL z0Gvd}hdkH#EmOd;JGJ|)H?plMDFfR^Vl?*47L>O#GS;0)%iho$iD2VB*TqLrg)e^Q?MB2EB9c1FLG0SjV(o!HShOL4vY!rYo zbgfw^k_xmHg`K9k$-5Yl`(L$|JL|nhnR3@_6-TqNDV{18QEG92yhVlrJ~&$ZVUq<7 zq&cX=h8eg~h?Lr{+U`oS4IAIr_Syr)<@e9Vop%C;o|}PAo6Ehw+v{JyqUwM%qH)~$ z#NiScsM<23=`W*VK!Z@JKdMv`>gyd2(g*{8&Z|rpb0Ro0i2+<5$RpW2ZjfNIOT~v(7Q+_A?_A6FzN+%XpKQM?13G-I(`QR+xx+Y<;i3jHiQWxFHqYr zXMtDi&!h!4pP~kIpk*6|)kTL3oZ)9P=orXosMKOKkV1cec4;}B2ZK{!rfWssNH|Hn z*#xF3hV^Ht7LT{EeFq3f6yQ&QvS$6*wow`}(=`LV9@jw>Mi&fGD>r^OT3{b+CS(&k z@f{CSumtiY?!~a6fE9k9xsA|}GW3qPbdt7z8o%MrtiFze? z4UO+0YPaL8%zcX8^UN@bs!%3@Zz#l`IwoV(s;X-uY`IjR?3Yn$uqSi4mhA=?$Z~prc zC6WK%Kf2>gL@>eVKdyM{`u@l$<_qOFwHrF!$^Fh0O3p14S@wGa3SLESyDS$^Uw6Jg zv-|M!J9M1&>4J}`Cu}lZ78(tGM(}R12fhzh;W2hXU`Z`r4#^E&7t1sIOt7W}+rxIJ zzJ?+Oz9Q!3T+(HGw6WX0lcNy`hFRr#$G<+I@ARYx{s^T}qKaMjx=8%8;qiQKy{`2q zWxm|ykJN!06QCwTQvw9Rp^g%GoK1L-IZ|OQ>gfqBlt7#h6b;;;_Kq-ujl4R;c%_Vt zC5@o6An`lI3h*B5adXq=e?G0u30PV`#2Gbw&wn4tp{`zOtd09qjPaM0XIdV|^MdyRa=*u4I&&N9ip&j}n@;x$1_MBPjmk9slN{8JmrV`tox1hT#{*9e zt1YvLdv?E<{P)D&=>XdE?j6m#w^7d({Lc?h>2Kk*Wg>%)0gr@6D@}1`m9z(n0{QdG zBB@CUYC3y&>w&+{&$^P^jW6(7a(oC9gm^+>Kdp|WB$t0Irtz;0@9RUwof)~v`Pr?} zXf4Js{5FE5@27n;<$84O_J5|jN&eP}yd)Ns(jI`Xg}}EZKx9MlgZO`#I$jqlfsjLB zf{AQL%$Go)peoOrP4Jgy++Uaae3~P4?Fg~Y0EzY*{PoIOy_{6Oj zGT+(5Zs+0V=lQ;w;hfd!hO)V2*LdQXOLi5(H#(KyS-&o2hzG}nAB@iW-pSvbrb#PD zb2S@OZ`2mQI(63YAh+NQ9uL+>C_K$iR1IlUVnkD=PrY`kJzK| zCN?UlF#AVsXK=Yv_UI(<_V4q+_vfdtQ(sSNo_Llyf<0AKE0MnsdtA)?=C?bMUFid0N5F5nTp4^3 zu!N(;03>z+3F~B(uuIlPH~3XJ-ToF5c|4fYp#2*d z`5rEC4rjYRC%heroe>HpqHb|~8J;UwAypQ!C3wa-4sQJ9jyyspDyz#8C~PEDt|Ame zOX3$qEbx`z{@D9>UI44-#-s13a?bCj&V{-y0-mCMt@_2G6suNtmpDWTCH z0IaeGkDRdNXj0l_brioW@>^s`={1MFBncWUj4 z_VtNDz+ezoF`u0mbYq&tr_A9*86`_d2RYnQkXMd2DEU(wv)*rLN*PYGQ(cm-10w`< z!jUiKxuZ9T=ldTo8*^{u#&iFAr?c_a&za-A^u=zoDcJb+>eD9xPna`ow3~+}pVJ0( z%}Q750X~z(pM7f0uh>5AJoB?^(!cCqUdFZ$61@re_Lvx>j>b-?VTio*K&oN`=4mZQIz5cK< z=}dbUz^#dl#LzD*oRFt;|MW$JR8*F%(U-?xdN(f|Ra3iK>`NT~LaqUPH&7^QL707m ziIb1Mh=b18{knftuRhenW++aay(xI2pHLDcSl*{74RkJE4+%R#uKd-nuTDeIdS9QRjI;iuREuT z&?OwS1%q=x#DbB3C|@z9(*QnU7EpZ@seckwnB%{14Q_BF$v*n!Jzv&ndi`m?#z;jC zh|lDgr#%0gI{n*dKsbj&zHib&IumeNE;7jrz~zQ}pePiY&I2B?0LFQwBfRm2P?1y*k`$4Vp+vMj(V~+5x zp*E9Wj>WI^`BkiDr#G0k_V&xM$T!JDLE_xOG-lgMG{DqUJcCRQA84=(UC?bi*KWNf zj*^yidddDo7i>?v-sS*V4Zr^K^$Cup>w&n#p7nBd+HmB0niV+spawwZyZH(H!VSh? z{46+nt$?q=zvq<0&gUowS3Xnzt~&Mg+D(6hCg9=1v9VN}rRy)Y&$!3_WKVQzOuDMD z0|y+ubgWQR^Hfie*@kkIL=s0#o`3ZD`>D>UEJZ{dVC=K-^E6!6*TA@tcKA;scW}yr zZcN$fQ|99#)HzOn5c%(OcGUtge(?xK()I(L%`#jzK(QqJA#`;!LZ-bq-%Islu0CjMu@14u8Z`C3LhVTPfGOY>? z63kimx$xF~@BJdYmC}yB?R^Gja!h|tj*f&nZ4n({lEWD*r=8D{t|GD|X;hqAIIdlt zya8IR1VA~w$RMsiA_S@qqp3J3Ec=pINhjM-A&Lnonko24tXbupC6`rdTXA0ijf~$Y z&VE6)$3QY(!;CD4z03U@8yS~UkE8;+o_vZh+Vsch!s-t*a}D<6d9!jc6TYJqoYlaY zfMHWopWAhe>gY-<7Ze&-YXL0m@P3rS*5O8IcU%cE#jIHaI~xiv@zxD7Caol!R9W%{ zp14&?GBh-$aHy8F(?rWAA80~4X#wX&idcrTbEWG#f-V ziBCz|D;)FtIAk6Sm-E=h$?pJx>V3`UZTvn9GsXAMD<`rasctUQvdoe+H%Skm#e|I; zg#taL6Q$K?nn8m`t%ZgFgfUY}_D91nj`)d>1^Usij)upMiAxcyrHHuze`a=7 zPAk}_zauCPX%Oj>#g-dy0mseWWWG&%ORY|uo*)5m(Hp%SCf^!+Z+=h~qy&_*H$lc8 z>CTwZM=7;L_(US>YFO|d@Y(xc!usc4;hU-*u6j|$Zj2i&V&WCH;)NQNrE8YW; zZ39xqVfWbhjuQAlDe`jWe#4~K)}qDd1L4ccMp^Z;ZVLZlSqo~n-giyoYc_t@zOa9} zvJ$cQIa8=8@M<1$$Lw;V;%M>|Wy+M<9yXqwQ2HLwGZ54meXWK4xdhbWmfE}84Ad2c z6(rZjM)1(&>>*2rkCNDS)E_4f#f9 z++3!C$m zDO1NYc^Z>$|9-%0qB=%AzY9z+P$0D`vH_G>Jm&Pw&y~yF24})Xg*jGQ49qf^MP0Nc{o{}yA8f_q?E1Rna+L53 zPr=U&5Kia)QK{kkKU-^_hRrWDidl*p-<|cvxP$qazX9zT%w!Y=bEcI9DU$t?(%vgm zE0FBcT&cWnPkFuQBqGswK}Q$^cd5UP!Po~VUgA$T|C9zsU-r`szPR>G?b+cNAj8xy~O7b=0&NkNoaXr3-pxq3)WSU0P zAq0=J4ZZ0zVjepHEaInAOZb}3Y(fPvS5r4?`yG~Ltm$b-V~*g1xxT)>)0Feu<3aOB z!rj3g#&+rFn(z^g=sV)QxAIhWS{Cn$cOem@SfMB#a&SUpxc1iT8zbN8PYJ!I3;s6y z)sSd%a3D!jc&rhq+wSy{ihM!v(^F=vO?aALak!9v z&`}Ml(&5tMiVu%un4yZ{s$s~{;xCE5Dj$g=8 zf=9BW#2aZ7)xeEmrPxY^J5+Eu>ivI&h};g%x88&A)wbH=v>17=?qce9ims;zBM{h+ z2y&3g?TR|-Wm8j-kx;P0$#%kaRd#MTm8}-%MwoOv!YZtcx84&m=9@Lmw>H9wJQnEv z?&e7gHKC}AOy;pU@}R72LfWsc_Zd- zKnm%CvMaIFvpt<_S{T&3zD`O=W8xs8qA1Bj%C(@}Nyj<{03EeQL>5-u)A zaSmrY48ib9FxZ5DYQsB1sFgVtN16^Z#~#{k>knS@dm?aX6UroMA>@gcW__U_ZXxw7<%XyWf_eIzowAI*lPXm z@M4lD8yJzZW<>4K0AWn)J`b17*FqlA&E%2mBl117EFX3=EPw|J7o6j<>vAkhLm z3c)QxY+E@nr78x^uzU!4p^d(1_{zU+uJvkHc_L6r)B8R~t8vR1REN)@V_gixWmVUUbD!)z~UUV^~xI zyBD|~TbKOGe&eb7xpP+qwd1UNc}71P+3!n!SQM@tEUwvIE1%a#?P>Jyr{v9-5xL)W z-@1<>)ifnZRF$YhqwyrIB!j+;EIqz3a<$6FwIa@OPhXq<{uqUsHU%sR_?%918W>n9 z@hwG*@LIl~RgRked*9!;ETTJZOIvgGRy6sjz|78+3@C`6&cn2S525Sg;LAyPI2{DmyL)i#y;?& z-=rfoX5j;AL>05>U?Tt+!J-i7ObgY;lJHP+Jen=j5i3_D`4oLje>|1UDS1NP*FztV zHmx8ewNMS2QvJGi8yH!t9f|x`im_Y5=mbyl(OpG20NT;FcG{nJ`9smaus!Cc7^{%A z#i$iGck9rQw$?S-K(zKVxR558T8fZ)O{6dNeA%PJg(1A~XmV*`loiOAHc%=BM^)gm zGq0fjl0PW&K88eO!nMl>i$P(T%JN83Yz#+oRN`cH!jU7TMM{G=&Uj!9RXhC+13!Jq z4TD&QC7t;dRd%mIMIsvATRIk;z|H4iw?vPx&e%JPz}76Gnke*nRgp%3T8%b4RVF4g znY6lTP2L7(Ml&rzGA;P2OV`H6rfT`Ot=qxZgRV}CA-0-y?~iJ7kOQ@DR(7_vqhtLt zlwIuDx=?4aF4NM%iiZE-=7CKtagBCW{hBLZG(}D8t@xa;yy!Ud|8Vu-mM9m3j?^;c z2cP9;#Wko_A6IKNqt;43&MLsI*Jm8Kq}#tpn5{?mP4Kk%?(EQ?Sgj3em|m%T1GQ^s zGJZda39+!%@*d8meX~)M6Ywoz2BUSi^HUmBTHb**G4;7@d1-osq7mi#%zJdivuS*( zGTdq@eo$qQ4f;}3{6i~3P@FtXb}z(S)LbF6PPChpG+ZJtRglV+-7 zbNIf(wm7tMZI;PKsOqlwOTBhBz;oqg?s>fLJI%kHLTyCJ*pJbX;dA8Jq}d_!9ct)v zD{69gP5}omJ+6L&-ef9QFB!S90tv0RlL}TvkD;+FA z#cxn&4ssiW$MZYUSz2@aGD%do+FsmZ->Lrn#El^Ts6`uWLmYN3R%bhrevhxxHZ5rv z>E)RGLv3#K(5S`kSvr|VmaiQ#R2p9Ftx9F`jakbru+E^x%RbVnn1(YWP|*Dx+{#z& zv%PdGQTtYEWN>gMJG8s{ne7KY`k@O16m)N`AUH`?A8l^Nf~Q&3`oK!i#*A*lgYwNH zE46L`tvOQ5y;jC{y=>0npIYU4>!yeJ6HBUF&u!`{4U6rZrwa8KO|0?ZWH(UJXwO1x z{oJe~PuUV_y2En;KJ4;$ta+xkt3ASPe;O$Q>9D#+!uv#zZF_WW-toJ^U(31CHEU_s z?f#1&wD8>)qIZWVrtDu@}~n@(COF2-(Ryn zX!)i!t`m1*yKh|2=C>+QUemjS-^;qbGrq>G2%9Sd#f=Vs&Q8{F;?hQ?f0-ArchWf6 zrj6-)a5TtZ>1Ol(PfqK9;mBYE^AjM^s$Wa%ydYUvg&kq~dMlT7s`mZgiQf!09N}g= zw==%Z?u}887~I+0n^4^5;gmg5x3-VvJqKId*`5$h*aAnS>wiTe*Oumb3~qxa-r(vCCd?pEL77{_aVD(CH*oX7aVAsqs0*wJim0d5jK& zT{rF3$-#O0vP<5n933|bT`i&!SQu-CoBS3kaa6Ui2f3|lL>+DFyz}bu?0hph+%ZAB zFQWByQXcS9%32^Y_B$*2x_!9UNaK+^F?oKZ+CuJ3IpFo>wW z?5@_?&h2h%n*Mrr>B}s2t>3G0w-Blu3$E%%=doLPxEh(OFgK=e@Z0vL^mxk-2mAiY z4)qs`f4u#XJTDdS`WI~E;pu&b6X%#H^8T_`-f5xI)EKiVwbN_K+-JwUnmB#HPa3n-o$k z!|^;xE}0h|N-5ML+&T6j*&w0VVsd27-hVoL5z?r>ZEu&1*Khm|uZX#mLwOf{4UI=y z1QQHhO^gc*U$09D>9M6lcuyzy+6P&!v{+LLc=SZMA}?{N*`1C5m3ZcS2|{Z5QvE9C zgY)kAbK$?E>VsLTH5iL07BE`+RL6eZp-Q)tvm2xaq=O^xu1ce|5*a&o&!(fzt(ZJ(ry z0fnU!!=@!MJp-m~B|@9_95b=5Cbg!m3T2pBA2fD4K6=Y@S2tVORvoRHZ@2y}vs$@R z)DLd8X3cN8)`rCcf2jIF<4?Y4g^fu(EsjZ92V3T~NkkxBO~oau9^2eFVlhG;xutyt z8;OJeo2ki0?|GUCG~yf|naW$MbfzI*dsl$2gs%)DA&;ZwPJ?!U)9&;a{x>p&*o=O# zw@L%>fG6V9m+`2^NT=>3}1tb#9c=nHztTen{ZoS2_3?tjPyip8x3&kzr=<*;Qrfq{;g&_ac60D4E_=15 z7#%(PI|DwlDwBATNodP*v5r)%33aW;E_MQSe}#IAvZc^H6RShQ(Rz8R<@{7lX2M0G ziqQ}RKvRipsh%zQ{Zkt+3voW}^$|6=*5+2yJSsWsEw9yIrywnqBeI}tn zE(sp`F7AEevt+*|x8R9cr4@@6tE(xbj0a>6ZtUP2h&F*$sQCmGhuP^i?u&k8t+7}b zmizs%`+7sj7gSLRMF%PmFo{K1J)gHDr38e{M07lDhKQADa~uTj|NXCYDpXbXdeG+S z_DHO=D`t<;*yJ^0(r$fA+KRhS*Jc1I>N<+uZdLEkz!#PIVoz2cyXuQWVDsY`MsIF= zo*U8L9moB^=E7DPMt|Si{ssenz@$%#Lb{g*dr42L26RHR-}H+EJv_*9}~qOV6Lv28fqcmUyjr_qFsd>Req+iExyCII5-E)`iKjC8mt zPOLT=R4QhvCwEf|9NV4f~pmjt#(T@0ey0#@3Gn@Uk1R;>DdFEOv{ zwtZ*0-*%;)X3-yi043Ami`TF-89!n(8m$cOz>d0}u%27?7tEg8tPfP}G4cf-BiHyl z;{86%BN3ib_6n| z93kap=i*hh!+W3N1@{ztFC5<|+Iz3y5$=OXx7=`4Sak=xw_i!x{%t^Cvh==$t6V!8 zKM}CVJ^b;k+nX7RHyi#5%Xc1ftp_&a9>%NixOz+oOu`C9ye_S-GaWhRei`GfFI{T` z$(;2hE3NwC#v_Rad3!I> zzZym*({VccEcJDymADG@y*<{tX$ndct4#Z4_@4O(<>JxNnj~?2XhJe}l?8(-KZ)d! zz8=zgVVN246D|j&4wVy)9?lkbJp4O1nN2FygdHM1>r2n%B!yL4X>rCGBXMO){*?Dy zf|Eo7!XffBaL;#90Ly>f($02WSw4X4ZF(vA_DAU4^x*-N8(uiMG@{fdixZ1P9Ns8_ zFY`=hpD$mUS~s3|{FWS7!r8@L6>vZpD|7hG4)aSraDB*`<8-x0~B0@AtzuTjtZ50M$lK=LqU#b8)R@qJdk zpXX5jLIjbR<}jAn`SU3AYr+6rYwIDNwam5gkPnN}b{Xm#q;dLA5v{G`IJ``gI*sq8WApG9f|{K6-FhEdPabv-`i4Dw z-MRZZZ!H5{h7yi6y&$UxofpLCyJrFpRueykHy(EL8-%Q-lf#CQ@vMtH-=R0Wm(M%S zdjrM|1fb4eBj@$NcFd@0_9Y9|7>hQ9sZ+$hnd+hvlH{r~1Kv?M!;)0kvvRT_ zQe5unG2wJU)YFrt@6fv$S84Nf(o%yJ!x?H4{I3t7jfdv5P3d&eUj^P0zsL zAhBoHQ+7u&oP+`Of4K6K%#tHW=L|1z2O|3r)TzDPbpI6Ma53%87eb9@H`IuA*Oe=69sgK$Na){Z6tRU~Wc>qqm|q)R3INb*6*O#aWU zP43Suenq+mNNa6pWx5X!|v$Qf`k(|7!}jb#R^#D*!B%FNOi zmWhkqe53~HlvvbC>Dh3p3kf{c<;*^PJv8Zcn$%G{N3shRKQSp{B9y+g+uWL(xh&?l zTI1^V+-3HA73m!*7rsRHX~jkM$J22i1{JH)B~tAO;l_NB)=}E{pVHPGF`^o?m{0_a zWqC7y*r}|o@TlS#YesR4?IsZhMWYxk%s%7zQp-UR1+(*|TZ-A{;U)cVNPo>MzNCjf zX?Cj~Y`JiK^OAaVI3H;=iG^UXGV`j(=ZHm1>`T}8Iuwcw2$@_4r;%^1N+${C&=4)X#Q2`?|CD7?+#eWe~UMjntnDE-~ei%r1gO z8zuX;dUQE_X-BjU5iW^th#B0XFg80A+nDFO7qP#E)9E_adwZ&hVLXN@& zQl~48aq8rgDQZB_w{Uv{4|TfR;+eIC>AJhXkfY zauLtonWvfcf5whkHknNl&=5P*(Zn_&posa1YC!+r-i7OSapp%JXQ(ur*0@&II`hXl zsSW3K*2i&HlARn>)>4&ba!~-k9bal2^NpQ$d=6JI_C#zAsm}(qu zmk%$$y`l=f-q@wF=>1gUeb16&^t>8RFj6jIM@AmlO_(&7zokQ|1Bt?Xoe=PLTPpr2 z8iqOV$`lV*aEYaq3TMOYj>heQE6XneMee-=-m}*qF2>$LtVY-Fy>0%eN|Vfnca1SW z$V}4pW9xT5`~W|$%xa6vv4QeI?{q+7rPbyH^?7GhvNAu`E>JM7Dk7{`oDPAVT+VQm zps+|>3T_uY`IA7-yXRu6;p3uXQ^3%th%=F_le%}|(!x;k>h)&e*ry^h94%6(iOkO~ z!{Z0Db93Tg{{E=BURTCQ5`T{L9$QqM*I$v=j`eK+{+<5`)$v2BW)D`X^)`zcR)@i= zp_?iL(F;XGYi#qRvKqVMf&Pu?)IBkrKkh`XxP1t4A1%&{OH0EO{GYCg__|1Amf!(8 zblQw<$PFz3~n$Z=iT)CTr5r6|9}ki_8VoIus7g)uaz;a07Ety5YodFC$nX_mB*$uG?nh}$YI7AW@ zbtxCZdMEwLA`ZJHRe(&+E-eINE;xoRw8@HkVWA-USB97PDb^FP9fE~e2MZKjtoY)N zTv%;34DpAyLgB*!g2&{=Aro+OsOMseIoenFNVR53pBQjKN+1|53i@KB$}CH4m{?8B zWjVUZVTKASF6+!_uH+SLslMbY=mQ}o{Si6Y5t%6aBD&m;5;UHIV^~e%LT$PvRdjvl zHsoZtQ#B;{GyJJ>@1dFHnQQf?r1Sdp7yST#a2jy&XYc8G-(sWM-O&c_Uv%5E+X#mP zW1$JuYHih856m!fvurHNVGt~iN$t+JRMoJyTmb-w7n_j&b8{)v%W>QGeBXP(N1PaB zMql8sGnn*v&1do;tIYrAB>t7Ho>NE^`rKY0sK)@;D{q2k!Ab|ug;deSpai3h0|U$9 zyJT0Z$)H)yzUUIp#$+-C6JEB!Y%9f%^26g%R=}9fsELKhYk_tr1!}F zp)8j_mVl{Xw0z5+TESj>0S+Ko^rHeEr+nZCf%hwpFfTQ%H0c zygY>9BQ%m!v)z=^Y#NL`>M$y)tCM0Dj(O+I+MymcZ8+w*w$tC8wrcf-s^P8R1DEU> zt5)7)&e}}_+*$j0N|!9Z($XHp_1o%?_c`|U-W)I5Ce-V-*?rl1ZXxS=$;=;pY<=lk z)gkX?eKyeGzFiyJ`i%7;ozRm2Ry+7Z*qIynN++joad1bhxl2`R#q`O^y4DzdZXZ+o zI}84Yf2OHD{EVqX%v!VF|CF1XvYWBROdWA&UmBR7rZ+mC?VdA ztz4$`a27WST~IBnLXj^*ra(wg`TP&wR9l&)A_lS5@+^BL*Y|K#NJhLU9;UU6j8k@W9GpLuM-F@MK73MI+nEn217 z19O{NzdO+reSF-TQcWv~%5=6!3XN3QFQGnDz>|eG-_PasHtyWN7Tno;@#eX*?B7wJ zR@tYuC0lJiWh-@I)L2$6A#-PN2kbi9U7IYwgh9yp;er1PMHtbD{aBqd{X^B+vfLM6bkD>HY;7EQce9o9A_f45K9_*?_&{yrL-TebfsGHMh|^F0&k=lp7p zUSDl{c6K3N ztk#RC1HerVDzUArw4OaHlIMKR17PNtoh_k9W!MQPJW$!|S#b|SvF{hv?caN`0y8}IFn>9`Zp-RKh|+RwZ<*IuRcfZ75RkSG|6Z(W+!g$Uw4E}h+*ncJk@zMjZpQkTyfeUD(H;O?Hy%vJhn!D~%bb%+as zEZGbQQ|vV(*p=^FWG8gVKyd4c?&I)07h2}UuC-7di~m%Uu-!o=YmM1qomgn0vxLS3z6 zw|1@N!oO(2k-|j-oF=cJ+(ge_Cz>D|&&cWK#%u4g=>5$6lUqYmTKhuc(B2fKTOG`AC@Z0-Y$h-dWzj3r6J<{Cl9Rq2)_bfk=_f_ zAyO2iZdkLb$Kt5Q@0^I$SA>TzR;^{421SlIkOcQsC^n^qSr~0${=}znDO|_Rh@ayF zzkdaT1vNcb;MYCWZ!gsFRrx%4JqBGl~<=zE2QA?tl3>Z$5#)dD4EEyBD&0NT9~9084wlTB?-uhGickPkTg0A z2-pH=-DU^Ul+(dwng1Dt2S2~*ERjXdzmUjC8jw5Ji^9L*VXD~xu-sQ#)w%gWYXe`Q zBUWvSA#f@?*Zerb6$yod}yeU0sYWxx7! zo^at2F@Lvh2Ctc6fO+@5fPThYS7N_`QpYM9deTV-VPJ8hU$poPlVn9I|h+z3AiYP~!#*72SEWdz>*G4-uGQ&Ixbn6_n0{}OOH>MwU)C)hZJBjYwX zzbc2EO|)2Rqap(i4}*R!VLB5<5^3!#tl<9=K2+E=b7~2k$&jtIyQUknRA|S>P(3@t zwg}um9ZkcXZggxXVn#ln#!9OXd-ZMR&$5~;l6rLlCB7;SLEYKEhv#;C%yvF|dnv+} zA}g9UW+$TEPne3RV4}=(Jsg$aayf3LJUr-5;4MqZ#SQH~+ZGw`fn#p3u*+2#y#|a! zfe1*mA~1Tta51P~e14HJ z=qQ&hTH8OKMV8VDAy6|z_F(Af_ixjU%dDFEDL9En{4p2?PArCAJx#(uRWEy21P5CTNy|`lG(Pt)JX*}rVh$g2;&aK( z^%){*)AvgoTh_Nws_CK!8itgiW#iwLTaeb2FnNIcIo;O#Lv_^PzGu`W%Jr3A(;*@n z{gCID$NZ$<^JY5$t8-BVW{_t}hF;rWBt08(Tb2!zsU4AM+~_Yaju^6l$3IIQ={908 z-|_y16+E0?ixWAi@_UsgMrN7$zvI@NwJR=`gQ)t+#dEmD5fXkZZ1ks1W+>w$fMPp4>@YUZq^Jer#pEx?WLX+uz# z!i7uFm?gc`i>9ECXlka>6Cm_5vI>6QvRkrWi>0R)pT`{hyT5*Je%ZAsc(v2xWo8Bl zSeE@@!2KEIIv2+&2mC*Df))g2=`Ueit$L@IQSq;zp3ga->aqcBhthXM4B`ycy^!L^ z)0N&x9(!eppV$G0Yzb>|*~vdr!ab>`RfgZ_scFvdRt@N^#<{dCHi$g^W5Q)NAxxlP-Z{ zm~8(K$v`&0Y-UM7_wL=PQ>U&SbG9^9F5Ql@*RB3J_Ls=`mH$5SIM<`cJo;LBZv)Cy zwqvBEMy=ZP=+Ogoy_7OHx;zn8FGzx+qdfn@3(TLt!tPgv9TNm6;-#g&4G}8wV+2dL zLkNxZ^mMMd`WoVsk}SqrS+;6*>(!@6uU@!)J|;c$4Bve_4?~&9zK4pm_1OI|`l>az zic3P)6jJ6feWrlr%a-uq*fA6Z{88gl-a3mK3jrvD+`~H=H}*mH98u-2212?X$lOqLJ59qI8{{c7r%QsGes-jG2c7$h;h zO4w%4nt(dV^;ku=WabC&@!8ykC)>$242&TWOpI6r%&h0`Aa!;G?&yGjTka~1gABxftNyd zZQQ_fliz07fy12B`yvJmxQYaIly_dA%J<7QkXKMd-R5l>b?@C&i<3Z*Lx*;A^T6w< zT)zn~JvENEo_~yn?Rs(1h28KWK}k%*L=zes5>=AT8?U~>oQ12XQM)0-N8CZ}TIuL! z5gXTU;Dwjo;>giFF6!5xE3UYZ$q$cV+42>n)~?TO!|&#_MlOV=P|`$~#T?kX7k8zG z9NxQwaSx1P@4+kt3U}o?y#B^3tY18f*Is)YlXxz<{3K7xwN$dc6j` z^70h+?%PMrW{uH-JzLf=Y4TJu4rOtEpFUhQ=o-8#z=AJk@XpNnWFI|B)hg-Sa@W0_ z-n=TaKmM4lnL5L7>Q9VI2VoG(*~deVO=R_!10*K+xVYZ{&hOiU1QEoalgYEsOk~ZL zT{LOcfuTchBR$zm#+Hpd`P3x#9?9q2o)>f5O;_U)1-$;oyUhD$9@XkJX7HVN)1+29 z9%oO{?ciiOnEotw?%6{?Db{{BhgaTwkAvAoG^ksP;iK-SLG4ru5AWjfr(a{k*1a@o zQlE#%U585rm^|@uX3lt#%dhFrm6u<_bC2E6s-M=A-k>?R+%b}t^<(kqCL32SV9-^| zQ7$*v-*g)tI-h|I2HCo9EdgoAyj51JEG<~VFWY`0Bo%}TnKEe-(?9u$^SX8A;E^DM z2j5PMhN%RO>}S-NhZu7IcpBEOfy;h3i9*N#7y+id@)qBI{~gI`)i{__1iB6~#EM1V z^U7QA;5TErZtxJgc5RJNe)jCx&c%KEQlnl|UU~5aj_g{`%dfw~rX2_9*0VPQukTNs zE-A_0&vTQfv2^Wb>eNc-{-Kv6OA5I4>dUDVukr9B_i<{oMtu1GyL|T9m(;A+f?I|T zr)m8(c5Gh7YcIdb#vS`PwM|#XKR6nfvdt1u$2Cj%H{!T9f#t!vBjPP|X3w4+_<9cU z3iKaWfVAS^NvWYwgrtGb>)~K1M2jw+QCOb9mKB7KrpMB>c}to#Z%p2Rz6`j2951~5 zKDC4kDJ_c!sU+Wh@-eTxG?g*WOeVf0lSf{fZneSou2Fz#1{pY@Kiw|7npgoP_^44W z700aErR!)y5by^znMK&SLH+z5;kgIJ%}W&%a|9A5=0P=S98 ze#?AAAkf0W-3>ziJU)2qeR7Kxk3RMk7x(T$912trL@`sRyv&GEkCU2Sg(Ck?%=q|I zX3hDAN`+f^@!6?RqdG2K@#W{Al2|#7S}7^aoxhm4)EW%$-C1w3@e1+ol+KtSa`IME% z9f<)1LYBJZ@WDf*=Zh~GGGrJpPkWt&;6X;* zbq8H~U&-bD&mtwg8aj$z=XRmnxgGf6%f(E5?hRg@cr!{$G$m2W&-QKG@T9k;XPa7# zA9D{ye#N9IuaZqN?pQ&i2DKP{&s}WYafC-FOrT|_b{ImVcFih0^}-}XLJFFuvwibs znzuQX{Jb1S-ZPqJEzjh-UOjp8sR`^WFc>}LKYahqZ1PKD7(QYIpUwQ3(PJLv!`B}n zH!p|GEDh=Gf6647yN{L2mT>*3XDG?t$D@xvj>{9v1zj3)=UpSn$|>Q-TW;pnH{Rl| zyN2+>ixati&~;FY858dK$td=-s_5mt5GJ$!~wnb1%Nb>(2~D=sJZ(`P_8rH5@v$mus)Q zl(#F1w`OH2%}B(S8L!YpF)GZT34%jJw3eGi$LhgrF1J3<-k*t~(qADzJ9 z+lP^r8)DSR(R?OlihR!!jPXP+WAIStGb#*Z6Ei`MNK(xWerJTigGbsBPh$L2gR zY$zEyiW`TI1fvkQ&xgySbKjWpG)PaRPW2c*{9r0?zCVjGqwizE_e&Ud>#cnJ*;}kx zzn-dr4(Mbo5P0>lUop^WxF;k_+bf0vyLD`enN$ZiSr7C zu-X-$;G=4lM7D0-j>1ikzJ1ueVFf=eTf~ANmT;g*(6UKG^iYtD-5IoN*VZ<^)x-Hp zDo}w6{5zpgVb4cRnS=s)WMvm1JaN>lQ^%4Jng+@=QAREwfASS|T6Jg1+I4(5^+{4x z9v^%#lM+KGsOwxi>;b-;ql^`da!&urPg zlaHp)VEzpC?c1Nli@)N6Ztd8zdL@|!#RQdyl&Up( z`K>pY{r>aRN>AbWH{RvuftTS`*rxvysZ2Bi96q>{S@TzO@3ZgHt9N&vdwL{pS-`q& zJ6ZbuQtC8p&W*Rg$K{^tj=~ zdR+FNuK^|rm8)`k`#5+an%5A(j^NGOh#Yqzj_%UViu_ONvMYJwsbcU(FR8#Se2 z^;q`rUd@UP863(gVAYTFNf3TM|NJYq?abhp-A8$8+B@{>aW;K=b^(vX)I8K|+?+;@ zsuAld;M4ctVc_le(DB^!xa+q5#0GY=aQP~V^h#7pZ$y_aT{)|DQ``z$g?>EM_P-aU zWS$Nq=%`J~mk!!a=$b&QQ;U{EZ)S%F;%e0(;L<5piXaN<@se1(4o8xcIcMBB^y<~n zL`1=?kYs1==ds7earSxVapi#9Y0$U{H{N_XXLj#}@aJ%G_w$(W++=$9yOgxbv0U1_ z2j^dMHNx$}=hjJY)Qn)j&&&^J()Y6doY(PmhFo_gJ$qfi%dfwSRJNBJ5?8Fwx#xA{ zn>q6cnz1x*-I41r?ZzFqT+itHA7aprx00S(nWIMw*|IB#3;UiEopa=W4XNDCIvZ#RIOeQZ)_a3YE&i8?IJ5H2NQvTz|>r% zr&S}?qY(%x+&(vzlVU0M7h2jT1j;Z`O3}1YJv61r%P%4`^Dvs%N7ZUo(R?ndS4|@~ zI~UUkA(aa$eBkkro|=G11qlX&9LPKZnog0alU-24MHgR4@AJ+AE72u}=ECjONKW)1 z1AdBvU??jxtU@?uWENB;%BfOTb_7i*{6#sK%0-nL^{p_8Zj+>VAB81BGBY!Yi%S5P z%Muc(0v3Jo5#yhFh4ec0X;8l=I#z&wsbTA%tU$T~D-Gu_n|5&PEq8ItkejJnBb9=j z13Ylwc#h;0(el*hRF2m%O*_1dDbY2TC99E^ow_vqwL#%uc=OeL-KIc;W$)665XKv`D8b zi~TUAWs9f@HxkR!H7?GJX-GmMj(&sg;Q1#WWcIXIxbmV4IFwgRiOYvn2D&oQLfOoj zHJvA4`jDCpn^Uh|4RoW#wo%nEO>hYXnxcBuD&*%Cp_ITxq6>jr6G$US$PA%$Wm`*H z6GG{h2eA-v{yD7)J-jv*9xDMgbV{A41_Q#%FidMQf)eRI*$&W&t>G8N4R^) zU}Rx28jASD1PrijDU}3e$2b-e6)2=IFQ0^@N+2LM)=OfXheKIe1ce(zi$N+&9;;#6 zO6;mG@QiNal}0bhRh zDM6{>6()DwGm1Ozz6Ytr+7Yh6R0@{>;g031fj2VqhOw+)|1)h*Ys9rT-^{f)4?zkK zCg7roxyyc}O5-*(tyjm|5|k+AnqPqmRN&tSYg@MSVhDlTmqO28z4&<6cRY6AXmT*P74f z&u7QxEoe2X!NgJ;#Nf*+`XB+Kn%?q)x%}wE=2`G zgo+C|av+n0P%I0VucTF{E>vsK1g}}Z^0^D}ozavH%hys&EOpbX;x8(oSKmG~XmSew zx#dxEZ@r3UEt_$8|5i@9^jzE?56bPq?Y6gEp@Wk#!ZA5gDx8VJF<%f-f%yVOB{Xf+ zfF~b)nEnHI5gpMWy$dW9w zb8{#ESjROZ{)5+JY4%K|aA^j`{sM|a%5n*^r))yJ#=iZ#ID9k*kIO}sDpk4p zhJj3-^gKeVM$0y*q3Mn-oipnNv6WJ3dHSi${p=&!G^~am2vDM8ka`@g+n&zSX`fTK zPE`_f2#Jm|s)UB}#M1D>%c$MvOb+hYNq%M~LTDsbNux%y zrf4ZuY(r2HakUNW+kGfypbKe*WY9GGXEy-Slz26P5Z*}L0)$eyg$BZlK*J>z3Jvht zso^9ZEs~?y%JmmVa*Za8xMcvD`*&luZV_&ak_wlQAPdRKJHn*{uEYzGj3LpX^vm=J zPQM&;tpXLOz&{684o`~>5C~lKy0jn92SdE@`umK!^L7lp)NkB^wq4KT_Tj_GKXQQE z1`WiWP@RE8?q$$5mvC_HH)u-Xl7>Zl1nANPyqH2ms2~LWXv!q}@BwbVZZO3GxN`6a zF7A0Ql|6n&-@Ap0FTKmVQ(vKV#~$1__HNL5RAVRcXM)7hj=w+Z3cwXav!ej+6hvhmT>m4`IjVEsPyGg7_MzG56!wcyio5wCXvC zp|@R!2Mt}1;hc_bdF+Xo=-8t>4?i%1XC^$tw{vC?RBo;rd>btr)FD9v^j^cdni0x2}B@9fb<7zmlq?2o_Tr@bB~KY2g#9!F3i zIFPZMF{8(!g^rS5yCLHq9!-_1af}^t3zJ`XgsIQ#XfdhWG3sGzrN%SouiAyDl_HP2=9XhI8%O6`X%TFZx`54P)*d%b=_KQ!L%otkVK; zk(Qds`c?1J|LSE(<>kDK2JxSZx>K}k6Cr5@0`J(N9q+#T4&VQ#@uk-4ODN?iYb#Oa?1@DGv$S+ zCLMcTk6k_Yvt<e2-zL1>bwfH6oX^^$!S)sz9!0L>GYCKMRz2opd~9YY>kN? zkzhG$W-X##(=lv`iwlH-L`S0GQb7JYBtt3)dJ*}${rY#iFmA&`a z`UB}VPBWOyaakJ4zk0MjP58X**3LQ=CC0h=N!M?&Q)RbTk1DLmo&En4LX zmu)dsQF-5;=Y%IJE37L_o~(^BlHc4N-hw@jRisVp+~F>XWFHkop2jAFu1N1GOTwi9 zB^()xV`=5kd5aMYr=Sxa+w{y5D_9JuC|z#&X$>^1FI?gJqgrM6OEhJ+7$+TfxaCeq zM3oa}jWiH3DBTlQdPRCxBRX`5=G2c~N^_`}xmVZ*PYS{2jcZu+!%~c>e)9QZx$??> z#Kr1p(gaj4mx{s-+bZS-(AjqT6n)MwNpne*fKLUdgMzzbu0(*?`8hVgUhi&_$^qhAAqpDhmckPWy4_e z>{%?I@*+(W5=ay-l+-vZ6^n}U=rm#&je7P(cs${BE@efJ8ct|S5taAHA{^?ECoB9- z2&E9h3WzFIH1QQ-?XyCmNvD$pC>R3<$8H2Fb=TLY9rN{O!PWuN@>FBN9MqNE$5 z^jn3Gyb6@CoFyzV*Po|g{}`Eyis-a_RqFA?lTT75DUshCk>7kV75-B|jK`!(N(=!J zi>|v+5bG?&eaYk#F6Au4;YBWw}QEQywlQR=-S>%t^4A%Syy^yZu%UaHrsO{~|0 zFiJ>E^iYtJNJw}vgoY_};wz;ggQ{&gHcG$55y1dEjZ)? zQ78%IvuDo%7B1V%WtVj$)*Uw3uutldc7zNQmuA0%QNnj$&L*MmX`IrkDLy69|Azuh zR-gj^B>a{-SOFV0Y@|!)PPRH2z(h(*y{HL`E=VcSG@I2EV1!I`mliqvDbR#NzeKoj zB^>J`=SETP=6LcqOp6ILrGf4+7|M-lN`!75zojxPPhES%RyI59WQo$sWd=*XUzm$5 zqg<2Hs^6;Gp{)@;P^m{9n(rLAf8(u0sSke^(MnR=o}82A8epqa(QGeNqDoeT9Yn-` z!x5pZ2qyY^*?x~^7NawmMDEeT;}*h_nQFH1Br+SczxSwt3)hX1)-B z8N&Q!JL_J5l}5oJS)2Cb4F++UmVJb26q3DhGu5kBX31kuQnOA&v<7wUv^anW5egh) z%9LsB%*Y1KKq((ho3-S&TL&KROnp+Jl!AbtXC8foy6rBs5~xc*nFsdq!dtT$IA8#c zYga^0G6^Z29UUHTfmU;*|M?YK-#U<97V2UT5rFyw3*41`YwMJB6ej^MjiR5 z5v71u1D)6_2Cc?Rae=Rm( z8OEK?oD~a358m0u}g& zAhJnWQagh!8&{B=luEy=ZzQXr7*k1*MT{SDJ2h)HWd4#3NDWJ7qzubeP}qUxZA}7Y z@}*m!LWIN53;UWfBK3#wSAdC=i`a2hvC1*An7T3wUu6&#;mw95R8qtT)2DOl>1R;2 zS~V`Y_&@yo^LER`M})Zl-g|g+`Yc=siVAY*f6dhl8F4TEph@`IN*Gu>A-Kkr*E>KE%54c!9|2ujn zR$`x_==H-Qgx6)C94w<}nU~GHvpSOMN@BzErJR9dOJge?OoiK*!08>@)3!kk5DE=R zLC$V&yL~hn`wK`-NZ{EgM)JWYv-#}Xb;QIbbL-$sXy2+X4?Xrg8GH9)C>Oo{Gmx7G zoKN*04r9keaOG-=ipk1+7(9cA6>_3Y2eMtI_=T(u@0+O@S^3?U z+Nl7}CYc66xVG zqS4Zy$}>j$)$uyHIHpA>RXP_{Ryj=W|2KeZqiYu<5X3d)6n@e%@QsK|e!<&$dW(1+cj}mSWmV-Q) zUDycMQIfcn@eXu{`(8qg0J6Vf(I39(e3U+MiN`{*Ar%7$-@xIlgZOmaHi^(NLOQ15=b^E; z^JcX)1`fHCbI@4yC?CB)1EK4HhwPj@2;?$(;xkN~G7Vjm7-j-jTzM@IKXwP>?;XpGPiCQ~ zRVScgSu*DX=FEAYyT`wb%aeen!=zVUBc)wK?!5Iz4i`xL1;x~A+L9OEoJPk}s_^WD zhj{s|Pf3h{tOA{s+Ra$HXgUkO_?-JjkL74lG0IT1>ClylFTcdvAC@wG=1g9Es|^Xs zZji;~WbWgwnLjXL;?s2K&=wyC9nPqaD=v&au~XDFZ`1z;$PX;zh^%jzg6OQ-Su~4Y%B2l5jnIeMOs=Kx7>0I4H`7y zqKht~YuBz}kF{uVzW|gbs8+ikMIi&PG?{tMxxC-03-5L6!h4-NF|B6g1&&q*G8jTiE1zg=LN#7|?KPGz`htF!b?5dw?_$%Q zTrff;#CXx9NiY}!yN^n%Vk%I93jFOMu(cQpEAE{^R#pxkkB6Q;&gRECpEGmjJU*Mh zmRoMUp5%BBS(yjOJ-m~5-kQoe=U>S83l`Ah+|Io7_M5Ezc`Iwzt|zT>6{dgqA#2wD zNX;5)Y+SvJl9C{ko_~%tYk%V0Zk>sZi{a^y(5b?b(vX~#H;gslM-bne%WJ^m8B9xv&|CDhL^ra_*cy1B*FFDM~B zVB+@r*k2T&;{_L?Y^F*HJ6yEeg>=PHtzkV*Ii(4$o7E@QCBUWI4s^C%4FF_ugkyy;@aPtzL)ea*>r^jK>>8tk3(` zk5&aLP=UV$(bl|H;N>8Bd4)(_=lqK=qfWIr9(mva@{I&;y?GERaf;ldSri@3;>h76 zEc@{X2H!N4JqPx2diz$yB~)g_h+(89#nP|OrQ9*>5q9p+=IR@6rbpM-+%aS@{jR*8 zAD69S(cC$l->DmeZ@it)zWNraDGaIDy>~bHC0^QfI2+;C&}0Y^3{jGo%aJ38Ig*>r zu%UM{W9ApMX?GU!aq&oH(QG$nI38e9rDUYxr`TU;+W-oL<|03@5Rcbm8T<(sgQBG!HT4IDUt$}hkzCA#gr z5dsWNhxmA6o3)_EMSbn~dQq+u(nJP|*s^8|X4WAzCGcnlb{FqO)S)JF#rs ziHTfw-2k3?dOWGVAUk*LWJ6{lqgu8lFFzNTZpUX=2K#qzV%_E)R8Ox)d`cSo4(+oo z8{FVZ;LKB-v3~Vpip_y|bqx*6uv!TjHq6e>+|HsOR+3($9!r)jCgb2y+O}qNjqFKYLG*9nI=gw#I*4ytgV%${Pwrs#1 z{mY&;58OUCA*FL_n~q#L>Q=_xdk^;v9mb1qO(oW4<$I_=1uF3G#Bno* zluj8}&hG-W}&kkHF5@_1=RBEPFvKUd#$JI9ug}CZWfA2jK zQ>yUH#HXlTyE=P*`GwP3)I+ypbrlo`c>n#6$;m6AVdEy;cJ~NdC88mOj|+RB&5RG< zWBc9%G^tY)mvEuG6Y0{aEh$M>hy+6kR;*mbhG`#>UcEX~UwM({wc;qw-OUHHzu~rF zBk;N$w$Dir6zwwq2cew4j*h(b$4ZTs;QsMum2St$wtXyZGy3PEbp5;RGE4V+1^ya{ zaKuy%sdRGu28Qm#CdgIQmr>EQPIXnk5snx=XAbovZ#8hisu zG2rpU6RW$aTKg1kxc(a6p79>dKX{G&fE!=ch9sob<@y`0!Dc^tg1U;I|X_K>eL;?g= ztn~`~ckrvZgMS+e41?@#+sOF%V={hRLSDvROkI##w-$9ecBEFnepISeA2gR0S<(rT zsuWIgNrlaH;y4#8+igBN<&X&H5_F`A_7i9dE7Cm*h~%0qZN(V55^>cJq5_#bGX4ny zRapqN@^SPk)^^zg)*luf0OGIJdo+O{x8ox7lvfl>ihE?+~&zAQR*??#nM@fJl=pv(g1&0m6wO{Qn(GbqYG z!kRU!Ie0i9bRTu=*5%a3HCeOzCk|xhAaxH_YuBe;%VzBOc^TVx>?5GuR7y*y-5F;R zrw3WRd=dLH^H9P?Y+^E}p4OULX>lCgzl)t28Dt+h#F$53CC^u#yU%T9_4gCr(b=8QAikdhRS zCi7UkW)pFh>(Ho94ZzR7jD4)xl0oNA9jFu+^WPk*tf=I0;Ub+q!Py8kWv@5K z$xqp_740;55pL1R$!mMf{sF>#(&%0VDsTdb4i^0ImWT z5LP5>CgIG5rPj1UDH%D5Yw%mAt4Q*0=QhVHSvW;fPDN2rc5JQydHF@mU$~YF&OZ;2 z+jX2;Rn&h1X#`j>|7+@NjrY2Lw9s^s*})%|7eu$-;*N|EVVTLL~$y*jA;A~hwS$-fg3h#q;uy^ zC}nNNLbwTU&k{6epI0VI=tzZ~YuB(sVxggg+m4#zP$)~q>>PKav!+X|n58aZnVq0? zq|Ffs!vuMl%X;);#g=`P1Qq$ASjIf{BBO7)2zQybN9du66gnmr)z$3klnR1SC@Ii{ z$2N2Um#|_KN}(gsaYfCEQVi376=f&p$&t84m!w5~R%IMugmc1msw=yfl+w_sNG|3- zaypMxN(J4kz<&#+Glu+G2o2%(05Tjo9;}6hvQJ6EnbN;TPQ(dqaUzP(QueZrtWhVJ z&2KCwp`(Z)DJhOi`}RPpV=^d4!8sjTsgE?>%{e_Tz!VxzmZ;xV=ZV5@j#Y(2x=!%< zsE#%5fZ)1zViHBAq;(1w!VV}demk?w2{qDcpv6Bso92m^U)GF4Nr^ate4M{!2Ju%v zUw)bLq?ReL+NltKDjb?nR^WCa{w;~2qA8FIDXp}T0?lIVl%081SveDQN0KBpl%`v$ z*Rc9lN@ddph0rxLB~Zc&R<9=hoTDXza27Mf|Cj8!>}(Rp zx&G@YZ!Jc%mDUF{oEA?+)9&y-;t*d|x)23YsqnMmbN`98FkIm8p?kkOqgOf437c-8 zY}!f zOw><|U|I~r$tJYUhGbX=6y?R{!~YzlLP&*a+p%hYL?UQEBklI+5H0-r2SO1&7lqIf z!p_kl6%lO)go&DSudYX}dTabOJ>o_uu+|?+;t~R-Or+F7vlDPBK-26z<<9u(pe1v~ zz#&{NL@C3TaG4HcB1D8fI9WQ5Im~L7v!9ACM}a1y zMimTT1&)V5f6%je9VsHV4Z51M8qmlf;e8CCjt{?=JMDh_px^CE^B|anYR;y08|L2vU%sNsjS($4^7i;$C(p> zLaBVd`TTvxJpLm2Au!}IiK6}hghh4HK$#Tf?%~DBlgTSCIyMc}ufVzY%_*<&!{Q$Z zDn-Vg-4qoR+R~ff*Ks9&KYoA733FPXefAlzz4rRa%{FB<9Hsn(%zP$Je3|U5+&^9H z(IZ(*eClbkit`EmiE^gB_%ff)nnef|dG9~<{?QxbNht1w;iSY8Q56f6a1^b_#w>&i<}vHNX}mXmHaQ`q%p8wO$)$)8RlssMGwpf+rDL7p zT@cl}@Uzhf^S8G0Q#ftcu!3MoTRE*PMu_U=7!LQPRpQe0F> zNgz<_v1m;%QX+#vX1?wexr(CQM40aQVXa*wj@mtP3@^Y~`wJ4|}@eS)Us(EdFf z$~*$n#P9bLkS68{F@R8-?iu7B`GprIPo~%i9Ea{HLcsvV{*n_O5g`OpN(u@JPw>eK z{4e0-Nc%-Z?j^$Cqg)tDN!cB>YGkcT8RGlz7m}HkjS^8Dr9%i5C}~Z769ZF)A}3)P z;Fpc7`6Xi?QYhY<_6DDQIUmE$9qgQPEoF&)vR6(^1W?TOZR?r*>U)#~Lspxk@+n)D zo1mnXv)E~t46oP3_qn{ap^k#=rRg_8L!T=X3Wj^-k5Rfcq`b&Qkjvh7ci-<^#?gxI%x zE4%jXM*_M~AVaol(W=(K3~wFL*DW2BS!yKgx4}@R&8!;u3y<>M{O`#N1dmJXlscAO zaOm%b4XZhP^e~2L^4!Fy*|c>Nrm`|ot5W@K{aJk>t^SrF7JW5~&*ywciQWFv{TWrK zG6`pRRgx7e*RX2MM$2%l%s5(eKp|y_=3CKSpD@y)zN6ql3$ zW_VsX%x&5Ji0u23eBjo2NDA_ES-4<6hH1}D#{ntoUNf4(S74fvIVY6~nC#lQm7_-w z6H?ZCMgvor;fGYX;7B=2n$|j^42z*ml##>KDbFzUj=LE;{0@fRekV^(d^voNRqtN~ zfo0$?5W)lkES&QRBkvf&l69L2X;74($xF{X%DBg$rNDIfGi6EQq{W6wp)l>illHhP zVT(wGfieqteB5|G|Lkl0h8a1a2vAD1^PAiKY12s|ZBq=3SX#&1aK}lTpr|mZD)-fd zBKzPrMh(B6sqfAt5GZ2dS2GxS*B#tB{7(Llz4wl@s@V2@zg2UE&JEp7lY^k5 z=z0aWZ{A#Y^}33gYwCBi7*?%X%O|798$&C0y+pKBbS4?mYgAc2<3AY5>djjS0ou`? zC}OrFf#WFFEnmXHqesk|2T;b$-?MWok3RM^Ik{)qz2g_Q?b(k~iiux*#`Kx9a7s?_ z-diuT{orA=jBT~+4)E5@@6I-+&9;i_y`tPREMByPeB0HZ?mASS60nPzGkpSMznV^w zHn4&VvNd0@)QnurdN!Z$-?yLFN4!R1H!OeDfgu8BZOHoeryCjYzlHtuyyNhv@#3C62kSmDG&lJEZ4|W;FN+4 z021YZw)~On8s`5-fd~OOWe6*Xc5IM7a{?8nULgfaIS8$Bu&^wNR?5ZY$Y}m~Vc`gg zZHK@Lp)sLhPa(%%?}+RjXjHfuVfjs4l>#S(&>^JJ?l|s~KH+}R#5qt>;+TC6pAMsJ zjr0Xv@25mdW1|NICR`@`2pvK>+JNGvVOsPd5QG7r3z(NkT?zth;$jrB!Y9I@Z8xqM zhtfVX4$6$FqXiZrY~ja3Ae0T34+o9Z2G=G$0T2caL7$J2Z@-DOg4hBAI*h=F#&W#? z4p>&iaJRKYD4S!uf8}_fI$^*s1U_wpFqveOcFZ^m@CgSH=6oPDAxGlK;P2F<5o-vP zjj)1%HnJD);uE&(h4DvV5DpRx7pvsTJyfc3tRS{B<78%l&ovl~_xz81=t5w|UrX0W zF*my{LioHfu-v(%9e3Utd>igckwRff_i!Wxjus}ADHJ|!W1(G7h{h)@v<`z%D3@U_ z0z0tF5PqLAkkAn_B{PQ==pvT=G@Hy;*U+Ow3mgZM%Vi*x#}gXm3h?^s8TS95gO}Qq zpcmIGX4}T4d_MYf>U8K$<0kbfDLBoXucxr3tO9pG@-RtO7$E}YFrh$6%VgQm#UO)7 ze38}}=2Qoy#MS~w*=RIj8?=QPZ!NJAW?ktpj__llKsZRGxr_qFBk0Zxgjui3QTU|| zKA*d7y9hT|j|izK$vw;$pL{~cn-jSH>W(a%^9}EhnMHE>bV`Z~35COCTvDH@Uw=i1 zCiSo|Yfnq?Y2`v-!XScRS!ktkq;P$aCaPjP1{Pt-K!no)?Vxbk6WnmPkTy61Ap>Sk zxl%WH#~2m^6(TFE7hSsd!x9Qq7~x_VBRWinKnt|?8K0&l5aCjGZdyt5mF_ z2xD#)TL_d8SSo~+U@Hshs@KS&0T9^uqWXqm?AdA_(djoy19>%G& z`GkvedHSAVd^2|;`;Hu7$iVJ&>)w^_Sy^0v(=Dvuz6T|xA(lpfDrV&KPx0=U$!J~7 zvV}9bc0e}0d-vq=XNGe=uZS5_zGU!#o^IC{_^`vkA!My*;=ahv1$a!yozFRh~p+m#k z^vLQ#moDA7{f-AXcq$i73Exflgh5viBCBr}f4lQu*6-Sn6q>!iZsc$Mdz00@J40^1 zjbphbC@t~Xg?#e%%Upf!AhNT1@!%8BaX7Cqau$q0AB9HiB33V%$>3`T(k1&^?t0`| zutAj;G2*!w=$qA#tn48yUcVEx&CXv|Gwg-|^zWZd_pE_ToiP_jY4Xk-;pvC(rdM`< z`d)V%D_5;YBhgxO?(8uhy5m+}dh>U*-KZrw-+@Mn>}0BaMQH|>5>`O&9@%JTW}^_S@1zaPDN^x)&qCK0v*ARVSo7|k^UZ{vee zUt*V?=gZM=a^2wT7}%!|ci#6XhtB3xoPU}(UwMIUJ$ll2z(8isnUB&Izdt1lv@T%b z4^wE-qCMSu_M%g#&b;v2XbOr;35N=p{MpC!>z76MUcI>W?{~1{;4zf4S-<#u2K4Jo zpPv1==q-X*Lxg=bE4$E`P$m6gSStFL4G{u5{&V#A_Y+;rp34D6RppX@;_-nb2=ZMOZq zhJW0AGyQt?;qP}o#DSA%(14{woH%}vTZi7pjF~gZIe&&{pL&dIugRuIpT4~M!34_C zY*@8`K3&?8)vG&?KK3x1fBu=Px(#N}{-f>$#&`p*IO;a4Plpa|>E5|Dt(!OP*=PU& zAOJ~3K~z*HRCb7$hd)loZhh&UJ(xN37g6TT`wRWM|4GF&qr7d;4YaygIVmL;VSb!C zmYS8zla`)NohzF#dg5$Cb^)W`eU{p_tC5^ij;1ZzvS!0Zp1A)Zs%O-sa`lGnIdK}{ zFJblaWj(jJ9>onO&XJZ<1H*&xso>ZYmkPd|K}KK=TT-KRf8uD_XIb{|IBxr}~iIK8v3X5iIB z89in^jvZp#rsdpy+YJopKY)P)Z)D!mHI#r^!?6a2EM@MTSv>vtaFl(P58ix<4xPKv zqeoY|bkF9S?-vsem+-}ykLca48-uPM%!v2KQf39P5xhNO1cL?)vj6{%cfWFEIu0l1EsdZt}PpA-+2(H&le*+{H7}8omZac z?GL}e2|>>3Q#|+2=NLTTCO#cCnhwnxvg^coLKHD`!ut%l?P2ml4qAFflxx=MFgrG{ zV8}K7>5^BBd2rmAt*d`kQbkRf`J1D(>tp-FTFdK!mz}Wnnkm}WypYGy!-wb zLS;Ej82b^|Uwt(LdUxZtJ09g^P7$TWIea$eBl>3bBzr(M&yD;9EflAZ9^(3e{ki=g z_i-|(h{f}N;JU#B>DDWY>#w_+W$QNMVDsbm<7wWi6`lHC&y%mbOPL0QLSiHTAhPvW z`JY|>^Dc(`2Z|1t@af0zqY^7H`mJ}d>@x1S;~^|3jI@kr%+UfI8*PUP3yZ?CF!@Dc z#(X-7#2`%l;xnFo_7$dm_6m-cI6|X!7@@-E)LfF!dvAZhHFrEl_m1tcq@QxhiS)|O zrgP686qW_J{r;ypa&RB`gS5V?C-1)X9EpjLd-f;~JpL?izVj~4nl<2y@n0}w);H9u z{WxR3n#Y5WJVlFUb@}G2PxxxZiQo6n_3h;67E>C6313XWDl1^v(7RZ?Y8`zVRcF-b zPkHF|_i0h@3dW3`z^CthNYi&7XVk=r)M(a~H}1HOP|g9e2mK8T!HUJpSh#R0BR~F< zlz72?Prk{S$&~lUQ54dQ8T|?I@kyiv^Vz#; zDW&I5^4v>rQoU*e?z`*n{Jd;7i{~xm%`p=xmu&ISlW(%&m)*3vL{Vl7-W&5FRnyCp zB+3{!VH%e-XlVQ`DufftrCXWsmnN)=Lg{H1qT zx_kpIDi^V8!>_zM?laPo;&|zWkywPWA{=9$uTz5vbN0kx(rVRZ%qQ<+=bz@@`<~{+ zHEpqcFzx%*3?Dv{Dpish^U(+V^O;xp^sVQ4;kg&dy7eIj59~_rnUmb};JZktfY~#q zQ0T<-{>S4va`ZS)KKlwc49OxhsT>Jr0=gx{&R^CrZqj!Qf9pN!)~JZGe3YC!O=5B? z!$-bNYLdmXk37P}$=~wmZGCw7?t6Ib?Qyhg(~{{k=Q4TP_q4A!j4>a7Ox?CUc;)(R zgtRD^nvBHe;K5^j`uBSna>Gqz_v*;k6TTp?#NwlmCvf!0DIR-f1h?GQpTjvt#Fwke znDOKA`2^DP^X?nZQLS=@*%VzIi7qSR-4|bE$_H;E0&zU>$bIx^Rgr^7PI1SB&(ga? z1CkQs@kh4Q{|cW()U4Fu5FZbJj_G6Hg_1(H?K+IFc2$&?wCr#d6TbYE+?*nw8~zTT zkDEyU9u3*L`8UG8Og{R2IG0r^&yIBqd4KE_{&CM8^y$`=yNBM5(2^FdT5?GRAN#g! zU|+qO95{M}Wh<7^sBsgHoGfA3OV@El{VRC?lhK?ydxo)}&EcI9uXF9St=Ya~H%E`2 z=H(AQzmi*A%=N?WL`ok)jHgx;=6rqu^;&o5rDyKv-0_1v{@4S| zZG1W9gFe0(KZ}n(A4{bQiH!Sb3?F77{-p91RaV`ZT@!btgqi;zSY8zVIS45YM!)zT~@^^Jvwg0gjXm zy74CZ_U*&rtv_@9ZO_xTQ5BL=XlcBL$_|@LP}235S$+@}<)? zJFaSwz^Jcg^8P1dxvWYiO8PjqcPEu9SLXAH6G%u1Anan^{^(0?yZuf&wQs`gucz_S z@Yncm`b3T$IZQ^idW`-2BT{@8J`YDJAc|4_tNgo^{}v-KR93{kU3Ft~j*IgUK7`WlRw_{ENh$kVwh^_m6VcV`l487w) z;zTY2hrZYJ=g^V;6p=#xM$Jf1lT=Di!N;*b?4!hlC$uk-)btF>`2#e%yb5P?a`}1V zIRbIXG-}?83Q2Kv?a+qjpL~kqa|hXd_!y7B{4$lQB%%|GN%9#ghh@vwuzb~4I`!yA zA`Z%zMxU#PMS@oX?XuT|C@d}_r_iEZ`wnELl|$$d+CGOCaipeake-oF!z*gBe9kxI zoIJp`od=k=@&jHT{t`h|Oyx^zQjnL+^w~>z^w9^YR;`K&!`h`-D$L3yb7|PFKd-(u zlGMZ?t5>XH#oBFj$?8MUE+Z`B>C^XW(5c8kA}ML9R7g$2B8he#x<|cLQgJ@#BpbIM z<%tpf$*7QyEKVgc4iFkkLRmO$6sQL_)vnh!kVs@Bgn~%;pK}q?#l-Pz3&Yze(G##d5S~9uk3tU23VqLSCpqPNT6q3_3 zNXv+)O1S{V1;;slzJ!!YS5UWJ0}_KdWcO;z2gBZB*WP2CIh{k#f!B~;(IPDY;-p46 zMXXq{l&@EwWZL&X5~o7=d=@$9&QdX{oDr;N9cjh!LwiWCaVd41*CP$EwC2#+Q{YP= zy;4;&5=&{(pe9T99pd1@BOE+*p1U4=1iubpVbQ+Z0Gy(8?Ap7RKKDLLxe6HsHK4-S zWu=TB_Zc0p9>R4u4Z&ySvTD(fOkIAMA7;%b5H3UeEKZ*~fh~iGxN?+F%fON*P}sJ4 z{TK|B2HPR%3o!JyTj+9C8?-+_)oPg_4xtE=RK6-{X{q>P{D0zt4*%yDsWoTLoT9Ms zJR)35VVO-id^k>s1#^Go!KX(MP=1Pv3aQ$p8b!q=Na6@2SEWU}cGRn2v0(CtgmoMP z|2B+{^%BTP2%;Q|#JG5Rc5cF!wJQh&g5V3VdF@J8G-{1Vu1?R6t=Y6@1&`eGASJ~` zloTsU>>&B2WjF*t2C3hoH62>kVEf8B?Av#MjfaZ)Y5rmaB_wBF!P#?Xp>hJ=wY9Jf z4j~f?v<h^6c5U zizb()5(UE<2!ocMGz=s{TYmiUaik;!2?XQG>eqvBXZ^@^otv|M({^5eq74Y|;=DE& z@>H1fIcHe6^(ZgA)sKwKbV9kQ#05-$w{F?ar(gfT7vKFvz%C>#(l~SK1P%fbmrPuO zpLkWu$-TQ-uxKqmZN7=1I*+3hsaLx)`(%jP4O>ySaXm6Hq35H!ZIp~7rCfR9d_^4E zxtE+GNs|`ss8GRA=Z=jT{?Rl}oh<+*u@cfLmzF}g$V%|w2Y=xK|J}-eixFr^NQ?_| z^uTVkZVOTp(i$Z!QsNUKRE!-8Lt+r66+XwouL0Y}1z~aWY!2Wf;P-(JA(ahM;z)^* zkerf=W0z4n z_b{L=1j5`>*A}U%sTAd%Gw;WTMzDRwBDQYd$+*eiB2I1RiMJ+W`2@j09AzbC2HB|v znVHpS-n=m*KA%SAv;?#kB*zEYxZo?!o!x8Tb^jzfa>bK+zU2?@!hCZ`Yx#&P`k5o%Ygg%p;#G-dfHU%4VT-PMmL z@4lUQVQ^+CphJB!OUng8af5yVk;z0dBtG8aD0U%SWGl%HwwqBBM%Gh79e_vya|GJYlqe zl(Ynn@7{-y%4KA7-|Tr95C|N!CD4H&m1|yG%LpL zcFczD&h-cl$baazxAX=T0zrm-23o@ zqy)nhl=-QDNfi@-)EcCA@7y_PE$~S{LMbeuupp1`Cw;}{eaFcfl1;h91OnRN)ok26 zOiJNX%3#jW*kM6lZW$FX%Ooi=jx%RZ5V9RCpT*(hC-BF`WBJm!^TB87l(mCN<0o>@ zJrD81Yj2R4T8TH_c$IG5S|Xe-hYeC-{2$9FnSDNz?k5 zxtK{amkn-P5*HUFH8seYGpEqH4v2tpdH_kONeuhPT?~8VF;a9Xw)9gjsM)t}7UA4t zS2Pw0$;q^8*N#_4e??}{to_6Q%=>N>xu8KL3= z&}ro472pdd5Fd=gLuk5)Ll?8_8iD_X2d=-$e^2>u;R5v~CeiEKfsA?US-$;pJWE%s z;&fgZhw`LlR3Y9z!sH2KS-XALrs)^RumIUGB%movF}lo2E(lBt-H z!O5*FSTcVuKP}lzdX1KJXj+>w?>x`u-?p=Q!%j||Dy4GeYFt(|z^fykVePujY}<91 zvQVk%ln~zaDYH=tP{P4hVMC~^B{%{pBu!g2BQ;6##fR^+a?t|b{pd5g4H`;PdTsi3 zZp|zA4QATZDJ)yHk@KY{JTmy|-kdygkZE5|WB1NoY}m4m{BX!SAe$zjKv|?Dr&70O zD$hLePZq6M$4^Vvg0=`L<1Lh0qn!|?3X&>bLbuM%dFO?@S-D~*Yku9&`mKiv1QL1v z;hXqo{D;h#K8K~tx3h2OVL}9`SnYD&d-Hit?AgG$&!*6?Umwn#IKY(gpR;549@hW5 zje;`J+9K@UkQ3S_=kRvAw`<12H5*-Ok~or6EAzxZ1~K-HXPEWHVYd8E%iGbRTn{wvBHa;2t8mrc3 zq|ewE%Do^Evg2uRMLk6R9zJ>JHRjG)!5i;RW!UYvQonvxI(Kf(^AFw6!XFnif9VDa z6euf=YX{%LhB=d2GH)io?%d1foks{t3rj?ovjz~7E1I^V?A$(Hed3=iU$KgrKdq)% z3v6vJvc%)xEz zxn{^P_8mTf_UNSi8b_6|f7f0%uKSfWD>t)Y?awINM@UFyz%oX3Ne=f8y@3xWOedrS zySH!Uwi||#UsQ&63V8dKNBR3hk5lj;x=bu0P7dt>9vVx5Ki0R4kvw;T^y5+VHnnv1ThJw!~2)dUITYO@OMk>e0SU zGd3=p%X1Ij&V6^?!^~Op3C72x@PY7|SSA2|Py$PYDLB2C?j74wuU-r8esm;(inY1t z?qOuc`5E)ZbG-B3`vw!Jg~7$yMf|e*C+5%liH|@3n&sQhGi30M^lDv?a|br@#w)Kf zclJu|d-P>Gb#6&&yv>i_O(tBbseNffj-4$fkd(&FgF7%`%t%(R*~FTS``CBk-XOA7@{OLS$@*Ql)BLP?J+^~VQ%h&VJW5Y?UP?5In+9S2cb1O+ruf&1hwv%)0 zl(~@T6X1_0BQ=>tv*)s4lG2lW@!?2zZ{N91I+wPSamWrOQ069^3=cl5`J8`h`IBZP`O$y`V8nt z9Azy0;X9l_0!x>#p;O21JpR;UB*j@=R_AiIZrxAa+SMs>H0hP9)3|PJTD57--krPo zdfIf(CB$@Bh_kLLa$yusad58Nq!$+O`F1roI={Py^33|>(9P@ zd--<89QN-&LW>s7sZyyjZCW>H&)$Pfn)(ezB_a9@7(|Q44NbPk2uR65%5!sbIDYyh zeX_F&NQ)x}k5jQm9U9iVl(uc!uwunpe)wSy+1FgpEw@}poIgmTM)j#tDU<25=CE?j zdfImAN>=Ya)T~j7HmzE-VDUW;t?mb2*=vPq(ZrI<{?zUnpkIn#aaXzi>(I+FW^g9WJ@N zI+^9unEdrD)~(%0{kpXY#3w+Y96dU=qd%U3+w*Tj$O!Ubc!K=glQ#Yg)Bz zLC_K$JaU@$S6xL?AV67R9ve3POsmd4s8TT#DJ+DrXw|j_LFr@aH#6C|`B&Or)rqbh z+f$`dCKWR>nKWrCn>YVVla{UM*Yhe0P95O8`5W*By2IH3M)IO#Espn}6O+qh>AW(X}Jh zs#N6knRCpVISaqvPy6<*XxIKK*00;h%$eU&P*O(g_HC(JDU(*MTC#k}BIeAQOI%_q zgZgLFu3eGKcBke9MN-Tj<_1i}r0>QL|<(E~!$HnKNgyc*zRNr&pk5(}u>A z9l_U``Iwwqo{sIWV#AuX%$vV}g5omTw{69VV@K%Fr7Lk#a^mPooVXM^b!^Yo*?l;2 z>=fV4_?BIJ_RyqhQ)*PHO#S)|2o)DIdGZu?@7+)9)@{kp$)QTE+B9m?m>QX>EL*dQ z>uxRM$bQW2_*&6_q+`O*e7xS}@2xw-7# zwV#gNIuW!KyS8t|j!&n3yEb_DwS^Ekj>FlrXGu*>{X?a6`qXJ^)T)8&YvS0E6XX^daz=R)(GM2!aTnIZZ_Mt?xbO(22`tFnLteX zC65N|-1!2+wxm_FMjSeNn(CL-;nM0E6c-k-cmFh0`=82bIB|Xt^Vh=(@k|mhL27Zf*hd=FY{k1igB7rB$motXs8)IdkT4=6pU~ zx^<;;g><@h?8J&?%b34#5v2+S^yx*_ishL;a}K-qAE85sj&$qLlpWi*Gws_SXx_FH z5C8LC5&{ksVO$;0>F%b0Jclb%{0pVA;)Di#D<3*!kBhW^CD<6V=8m~?g?WtWH3 zFw8PK26AQ`_d+`;EzmB@z7(L9gOn0SIY?=_!6tu_2_()B`G+VtI9v)WBa6bq&o zfTPN=q{LAgDg34`Z!EN-DnMFpDk*LHuQk$bZ)A*I%#0-kN^3(2gEIV%F1R{E>*1y> z(=PbO(r)%njZ2;5X8dr|rD@koqX6mTv+}3!`P-A9vwGbUD#aO@Z~EB)03ZNKL_t)K ztJb&yIF~fnJ>f@HmXW+yG5{3<^l6N*QgYD*=1@W|P)?ZVUHTnI;b?{QGHGZB zOIne(YIpu<7sBA(@s-{j71HqGNg0)i5I87&?%G5e+UAHX9gXnPHi#$%l8i~U6$*ve zxpOBqYSiG5%5Ph?(xKy3-XujkrVWm8iJ!Hb7hTH;6a)oY3OuzUaZ|Bb!pK=`q_ofo zlyW_H;jp=!A>3>&4hWxR#!h?KJ7Gxn5m7L{Ys@J?I3O)U*lxyIBZV^hz#UJsCcG1Y z83&2EcqcJyTWLd26A&o z4(C}s^6V3olM)k9cUPD2m~!3uuHDBskerf2N=gcs)NRVzjav{%H;aHY zJYsI{VO;(#EzSF-D+gn+y4W2JLdwYEbJ~ z?~OI-;oNp>?U7t4mzE`3q?CXUO9tH2DiH$@AraCS86WA&(u&YHm{1ME7;h#VDct_J z#od@S4OU(C=gfzmybGK6Hhn%}95;hpQn0^|O8#xOhqeiN0p%G}y7!$%>FG6^^h9k#QGhMYwg=rC?^~4vMFBT4d93fFcy7Si^ zuZY|&wD2K?IjkbV=Na%siQRp|+x(@$**+TB=`h=S5Dp-B85AT-MJym0a&|w zSa`;a6o!XSSf*3T?TjwumcdyhBqWlUltf};3JHm+bjrGpkPv8W5XQKa!quJL0Y|!X zOG_+mMOg22^mrdxrwC&(SwfpRFD)DoEA1YXq^mC+H==XFdJqz0S}VXt3hnAtht;c= z(yo0+7H&Go?RVWpIm=@2uFW)S)QIGSWRemRNQh4&CA9*hCQe6Vx$E4>&u3Y#?)7M7 zw7WjMIcy;;Uv!ON5wJW|xG=g^n>Kpn1X{YRevwQt3Ms&nM!#qwBP8EGcW;oc&Xs=| zfd5w%p_KZaR{XEcF{mR-(JK;+GBAl6UGTE<%nZPgDx)Nh<(^P5grZt_p#$N1bUd%1 zd4v3uzG%2mN9QHCDhnelRY5;sPW_Q*orlRR2S zb2oe5$Y?7gipd*EFt{@BS@V!fg6a~)Y8=-nw4!6 zWjnGyz#Jsd#z-+&L@%azk9q}SKZ!~)GC|xAG#5>TnBsX)V&;n1ZBH)08^?&>E2eHM z@=k?e6Y%8k;9v>Mo!1wPHUObeh#fn2P_t&ui(iCB^V`;6>3CJA$d`4bg4j&Do_EO< z?}|p0*5o3QxZjW(v@n@#P%7fdH4jG(`p8_>o+k~2(nilko)O;Z&OOU`b;Z6l#(=*_ zqPQ4LGupn$Z*=7Me?+~l5R@34uZY9v9u}kX!4CL^;@6V`G7ca~ooS0=6=_5+rVdD}fs-wqm8=>RS_9H( z7iqkuVT!j-qLPlpEVV;S;yCx&n51CtcOpaUhQPEY<~xGeElbBPcz3O7*DGY+tRs!P zxaD5||Mx{l#OeLz9Xn!wZRUoj6I}9@$o##~t9F4g=$HVuPa4L6Xs=XcR>h{(jBSs= z+p?pL^XN*vdSq;FVJ_&(MN`IvZN)_!yhpJWJMz&!NHlRMEG)NEQPU)PEXG|U(SyD> zCegJQ(XpP=MSzGSIlU^?s@0%sm8w*&T8(N|s!}Z@1;6&JHu1ZDC|3*V$aVKvW7Z?a z@w8PGGwZb)Tm#T+qIBmXDxyEV|005ne9IT9M@KH-2z*-MQ%0X^8Ba!~8dR-Tiz?M? zQmslAYE;P}HR!vrI#22m=!l38UW~Q{Z_A3^8w3dN=C@a=JCZS>b#K@5b~H!&?*F?fZT#(d^3GMr6pl3>Bn=6D{UNwNE6`| z!YoXsquvWc3nHU=FVUbvoY=aaTW-9C!{>6%_HEl}+d*i9!%z`L6_fN`2tz=P0HR7; zyZ;8))L za6IP=!){p0#ELzIsZ}1Umo8-cp2K)9f`}_$nsBBMy?AHs?8`f9s?Z@>PUO}h^pWRJiNImICfARWcg zgWH(<(-KMmTS#>AX>J@mkR`wThL#d7%;xL`k8MYxwVOW6Yn^L&c^<}CgEeBiYw#cs zI`*@RwnZZ^3k#p|P)SKx+i2mB2{BqA!>n7oh81gn#V5gX_eiBZZYq6;GmGqBuMb)k>u4?JlC zEGrr^cR?@)ydvB`G2f3q0}(8+xY%fm{o{@);)2iru%8hF@M3e(!UM!e_+32$i4?v_ zv?8{p7dPmFcEx@k85?=g?@S05VW0p)`jFCuM=c>Dbs5qvuYKMpkr9gNzd&NS&&JBy zG~#zMx}e>z6x=q+2*l|3()8pdVrr8fO_Knhv|`#QkXAHQf8iK;;~Ry)TsSr!V90Ch z#e*PX|LGQ2rWei5SUH)7`oJR_^Tr~&L;qF&&C9>u*DEwq+Mr4i+6DoRi4S_BOG)kD9kj4!kLJB)#D?~heb}2YT2%+3Ft>JA;uUU;d@421w$%zOYET2O7 zP1sop3tPLm3>^Y(5>naPEIb#6&jpK2IcV+RSUwC^MY))iFz66kYS$No8~$|LCndf6 zWix0%Z&R1sA0aFp8N}8;cQXiso9EI2^KV_mr17KpZO1OkEU>kQxUrFFY)sx!V^V~$ zl;cJYHI~rW+HH?J45j&J8S&iX965ZDGQg1*QW$2a$Qe+UB2+PGlN(k@fw17_TW_X$ zv!<>m&YU7mwBABlzQ`tQynh<4{p9E8FnZJ&3JM%-Bw;L*r=1eO*tNF6V8L`4beYMe z?7{;~+l^P&M+jR8!mh348Sft6MQhMf<9Qzq_Q(d|U`t7h+nZsrhMiDo9m0hE%RreEf0^r15h4T_nj$3yVI-E2h9F$q zW{%@}7*!b(g`>e%5(uMonCRAEgEl!&y;`*p;1q)@L2FG|f|APo>_WPP^ifuNj?cz? z%(m^jPzY@8qe0VV488SwW9wT0rDz<&8bZ=N1n4k0B?fnfz>xxJ38V)0~{WmGmX z8}>!YCN*!}OmdvQDdsAbX5 zFK+vVhQlBA_y0+5;)2JbZ~3#H{JuxxPoB6Kz;JO-Vr%;2k@~ZCU;LIo{?ecK{^I)n ztd0LCHT}87{_H)`Z^Yn@fA>DGTzq7@@OyuifA8`yHv*+4L6{_IJv&F)2o%oMt1^<~S>LxgoPb7oDaP16>XPf4X|vo@?=zXPRV zgq*utKS@SmhFlYV+A!GowV%z!^v~Jpf{l`wCRWU!!o6Vi~Jx;i&fSaxz zNQKOFI(F>LFI%>vEq}y_)LQf7yt&Muw}d$0_~C=}?wd`uYL{^DgOB2bLs)1I@7_+E zrVYtVPv*v(Z{*nd0uW%A7INFo!^kXuDeu1j2_js|$M3#RojP@B+N>pumaRim#@SQ* zxjK6w6)IGsNB8bbo%|IwFKx(*3Fygo7I~d)i2@27hj{)y(OG? z_Bgi=9ZKaIb?Dx+58>QAN=rhttlyYQnYCH9b`?bhc|7~n(^RThiLTwV`EC0_Y@yh+ zW)0ojwj;B0CfDA0E#J(T!R>cGNnvprp`s$5dFTN~ef|YyM1vXtLWj8Lwi}uH-E>NU z)2H^)u2Xl`{k)5>KKqQ?m(-+M&04(o@i=2TyBI?$Bxg^Y=FtcL$(eI!kvM$$`KMf7 z_i|d-YsB(ZYmq)dxU7Ju9=V^4v^1JFZoz`3t5H?}A#CP;H=QcwYSF*%wUmTyMtwSt zqlb>**NUZ!7Sp168|u`)lu=_R;s`-O?g{>R|NUHA=W;4mtjMiH@8Eo1ab&KAp^`j?zwkUYt5v2)uRi>;W1rcZr5Dgrgo+D!`PpZvQ>zx8I(B2n&Vwi+*tBvn z-P*Mvy+S70*A8Rrjy?42)s2h_<;WT^h$AOX0wKaqm>aLVk<@Y(m^A$xe%-m3FTa`r z3X1Y`c>d{Us9dEoJ+gYU@8C(afU}48F|bz`Dp#vX<;v9={>oeAmfD;LbR3j0 z*r()_3|@WXZ8oo;PurFa7(Zb$nlg6mJw)T?Jz2eCC3oF;4MPX_deamXD`}=)d zGweYYE?z>N8nxKHXE%;VUW(_S(OgzLlO(^xFWdKkRBT+ohFT3C{=+%8wOHVZfnsZC-gcc?>-Wc+ znZ1wkDS4jvHNW?H&g}=`>@$1KnpI|9>t6SLU5i#MVch5g*s^*FgGP*D_NQO)v!7o~ zesKj4KKeADem0MT`j+v+i_g=nA?Z4#oL1_Z_Hge#4>9fB3wd|OYphu|m%mN_n7W2~ zetz)<6jTl1_37_%&t11-=jB2)%G;lP!m{OGFlIz=p84}bY_3(znmvazPnp1tS6xPJ zYct<&-i00Q!rwof$K7||$q|PhMBR=W>gyY5ji=dGQ_ImujSmj!P3sEKE=P|X!k0^y zlR~m-?OLqd0(uS^%=i;dX4ae!dFiP?^X^|CWyPkgBxJ|{L9MV|hje=@NXg7M-{px% zp5k|p{E5e&ew2!`0#a$P!v$P=`E@M*Y7y68ekzYW@i2#ygm3YMRvsC|>cRaF{)x{%`-uMidUMCGevOO9wexu3 z(WhCpW(8-QJPy)Lq*8HEE&S#2C)uzw$?I>u%h{8TW!ecxvZiJqO)br=UA2)XUU-Ff zUVWS|KYo`v^A};~6f%1B;S?3*{(vv1PV2Nz>$Lw}_JhmDX)o5vQZAL1JsCE97-NPF zV)OEqe6wOPmHkgc3567CQt<>Iyg!%u3+J-CNmEwU-()(<94fjGV8GD*sV)ff$o=~bH8?R4iZ(RdJx?_&j1W4sjR@s&Q`}b%69ufZh?BCh6Y7Gq= z=d<6?gE;5Hb14-rT`NnF+6f%v*;!Sgq7o*abTZ2puVBi^UVOc52^Zad7U&rB=gwi? zqUE&h-9RkbgShr{7(E}4HgR9O_tvp@Z!1qdbt7f@E~TLa55BSxL7aG7JukibD%;k7 z!;Za86xX()909_jv@A-Wo@I!}9eniu2b}xUyE$yk7z*?uteC%$Z&rTI@G;}aDXe7h z;6ap>qs>=P}F}oDOVw|ks`^Cog4Z5%cbmXZX;|vY}&XU^}+iL>Rv=`Q;Y|0xsi&ZJi}iv;WQocRb92BZkwjXBji!dX_I1EhQ~-D6Qm~mq$2)nG_yq0HP zd7b**`>5Mp%eI}h6m$qwH(o)P6mQO&%dr!uancDVVu_s$9@q!V*636VOBa2{^w}Q~ zZ`i_))NrFrk*tJ2jnD~*wKC(q_gL}uXEd}WDeGH`(^ki#1&g@y zo~IZ#;y^5sB9)9Y`=do%ebY^h9C09Ftq}2Tyz$assSWkzx*KkywWXcCO>M-Tw2@gv z(cZe7MGHP*YlG(YJMSdj+Q!Zud)c#d7fK1rx>PY>$UsU$VH#`q@cyjXELyRQZM)k% z2yUZXNw?~5bnjY$q!vr0O>TdxnI+4Xan7~B;m|{eaM+M4-g@rOeDe7Mjvv;WoZKk= z1`lL#mEy?5N3m^NBl#05xcS!G$P!3{EU#~;by}x&TBrT@?T6P6_7^s#(XJnYugH&v zaMDR^%f=QiLdSXeug@{}^KZH3j^DC)`5NZV{}SyQK}1a$VL>zuVVxwIPJ6_nUh;rW zk&_!D?V98f%eFi)=HhCPI@y*)LN+>;B9%^)Us#MK4N!Bv?BEP}Cc)pr&ST1HQ@Qn? zCz=0Q7ZNhe{sa2*-pkK0WBLrP`Srad_H5*_H|BadR}!Ip!fG!#-eZoH7=Aq=zz&BY z*~+=+ol52Y6S(E}U-R1Q@6h0au)~DIVGpVR$|dP2qIm_LD7nCrhHp#>3vGo>%%O4- zmJC9CMG$=jmUfZKWX1{+M%odQ2|pCy<@OtIqGoRcH{9|YR(<&y^H$b)LHve}rn$L^ zK?4SG&jSxoSQG`J36+$ybNwoWEeU%WaJUZAwh+oiYS+{kiQ{UdW#I_JR~E7a$wbmb zH98K;1M8=j)_uhR7OU2^Pma}BVR?fNn zGU|72=QnrU&e=b`iXr{_bL%gENivzDC?XAYM-Ve(;tCT^3OgrkIJ}g?LSkuH_0 z&&xrlxQqgXLyKcIcZ)zpC+;B5XSFC2@ay@f$O+Pt#I8Wu5!5P=Gz!Hq_0tLmN|6kR?X_U zb4aH(wvedwUY>pGPb^-(iJNb~laJ;t?F77v`*`^ zPWw;Tza%ll=ku?r+05!yYx!*cCw#Pc6$1y3AkR^xo9k%Wx08KMO;q$7Oi@`8r3GQa z!dE8%TX{gra!Cotkj0WV)FEERorCtWW<#V?9!-ZFTY^^ zyiZxXZap>I>ku+00B&Yk^HP&#F4etyQ4((F=HETe*vZrAQV^!8u9m89)l_$_rnD%J zh%jt%kx+;oJ9ZOyGzy87A*#BRQBjt|AOG|?Yu9aIN6lWGxPwZ$v^2KUd%puHDX*le zq8L;Pl%}|-n3c;`vUT%znp)c#GkzQ|J^xo$u2{*ZpDkeV+T9EqFodX^Kx)ThhEK75 z+gcuY=u!66H3vLdp`0kiMTLB|XaQ^2Ze?F>6OQAvUV(5O_B5pE(rXB%6EEM*sGZ=6C!S=@hRv*AzX5?wVQvodXT8h1 z^_yr13&0o01*mGdUMi*Be?(0D`*uZ4C*%skxUTEDP+Ka!4#Jk63#K|3QCD(?KunC9qu#iZpXljqsWAGtVlyspqCrU&s!Z~@AmgKVV(+^m` zb_2Wiw1UV*NDC{J&(Og`ng0BnY+Ap8>C@-2twC|v=!3B(9)UP`tk7tg#!a^J{7cWV ztG>|-!;qjg>%aMm*WY@ZB${+8&hyW|%z}kW(aI%OznvGJ|10~NnzKlqI<3<>tS~_gsx{4p4a{-rJegh}|=yZ-4Gl7bdZVc^T$xClcXW9jqvwPz=j6Y&5 z*WdUn3QEgB=b~H}OC~``k}^Wd3SlV+p#{>i4c&yyM-#@@8g1twfRNUt?E=sc#egB# zX~hb|p+}y;t-rX4dwzK}Q>UKEhAo?ov`!{hHlQm-*yQHraro#F)YUg~>W`)(MTk?+ zJ)cCZjpN6T+08b&IW&r9y6~F6N9)9pK>S~)a{g79}9lyPwSD$%| zGftnzyw4Y*WC&X)49&3>;?BEnVfD(d7&g%uI8n` zKFP7;j^$@p-bhnxjEd@BJn;L6S@z*frc5}2i!QsCR;PeVEfl4ES^G7Iju?m)Af&7_ zU1cFegej9wVDHX#j5us4#l;15>t4;I6UK4DkEe3f_~Tf!y`C;5r3@WBfCCRcfImL? zC@F0bH+u?BIb|}JUHlVnx$@^6KIUYWuirwK@&bk*HI8morTplG@tk??<)pPFYzc;q z9L@gwRWWVyNnC%+?WEEcX$)xTF=RLwUhrdnd;OK1dB%AR9X^7eUVaf;SlB8-4sp<$ zxC=_zSV|K@deVXb0ujpR*1PUy)AG+b`tYN;_J%tsDJ#LsDd*aoZYI8GEys>OnsYC? zl1;l>`Nc1PiHV#uC=bQ^zzqOvruDYI{#gb{KOl0!pQS%zcNGCY{Ec@69D8LMRKQRmf#Oy_j&KhAAgb=J!v$%!7Y@h2aDDLutck z7!m*>l$1n>qaD-9du-zm= zh7JE3AW2~9FnAC_YIFRQmeIhArBFx}M`@e16(OSHC@i!LW9bBr2&0kMx*a8Q&`LnM ziTZ{XBB30bVrkC3_!=&`@NCXG^F$C~lt&li>rn#Ww&Tb=v=D@J8c6~~4$8F=mIxFh zZJj`gFpet-lf<p1Vy3pxI{u?QW*tD>N2{RwyO%O}n{q zAZ7Yd=6F;rU@HfSOG-qrw8D~*LJ}g0z_hC?EF5fvg0N7a6CgvlgbcqT5Y`DV>eI#% z7Pf8!ZIhNcUjHW%Lg1<}+NTh6o6$1gknakko}h4XgiDw(K2;sUa9N@qEEGb7aFj(_ zLP(zLb6@yLQ8);2N}4_(mz4B1logg1XjhZACAQN7 z(k3l)iI75Jk@mRWER;u;(;_x<)xzFA%433i*i9(Lq-e)iLguthFmgbBJrf`|eZ($i-3pFxWV0zt?EO^&D2 z>eW3I2|^B~_kWGK-tfs`1j{@EU?hYvu}{j=TJ;&BGJIHp7@JpWB(os;Ynv6uu;SZT z!Ur4?kNnn;eatuI*`^(rE%=Q4?!FIMIf%gr9Dv3}i?Byys!SZ268NO2e*JBsy?9Im zWu@@?TMLj8kE+Fh1#N{*9}0nTHBu*-{_=CYH1i|6^c~J^x7o@qZ%P)pbz05nP|66q0)=YZ6P8di`IcnKNpV5Ef(=i|%q zSs2X^!%Hg&ArR76Ixv!7R!|RtmJve^jyBq|c=r&1FyeIxZQ97|3$VbJ2DI5xFV+u? zKU5IT&IJ(?L@1zc*Mzb}Cj?k|0hw?ogzL0U>$Fb$kL`!|1Ol2A0zp!T3;^*KlZ_6TyH`2s|skTy+;vV;(=L%0W4fo2Q&!R(~*#w3}j!oRAd%1?KO${hj({j zbZ31jDf29TB$N*cRR%m}>1t-$Re;Xuc}fqoWY%3@Q&O8Ul#6y0Ius$Tl~I`hI`~|I z%9@APLZgJ^m0*!AmxWK{EHbG#u6JjN;S#pB3)1y^*2V|9xJi&k0mD0_C#@Z%N0y9N z4HZ0__PnGL?SnuaG(o2GkVa)mfD*nwr~vGYycD2?3dT=Rd4UeH^`G32 zFqIjQ%D}BGPn3(Fq3)A#XEnFSshROmTS4pkN-0u%{hwXcpr2G`+zFo?Ju~-2 zke{0ktE>P7nmYK8pCu#bt6XS-D?C}gpzr-2^V`<%L;q(HJZB(Bi}Gsb5w{0fGg&Uv zpnbm|1a^7?JFU|?t!t8M7b%kQ7M6Uynpn!oa#d)2?JQrU zM+dOXi&gUeA3(JLL21w_6q*!v;L*z{rTR!fBBeAALoXIk0*>-QroXWJN1oaMO9D9K z-8Z8J>MLDt-?*Nw+jo%m7G+0}iLpW>h?9!fv-F$Q#L}*LTLu52f z%!=vD1bHz41y@T*FMC-B)i<^DYnUa=1T;4{ zv1q{p(n_Im5txJ_<$XbFh1BiTY~943rk2cz5k7<#MpY!(4B*u!fkxp7JAf|PJFUz( z)mZ>oppYmL_HN<>dPD4;0YP-=OR`$dw`@!rG=li<=XeO&lZX<+tB&?I19+PZa~RuE zNG#L8835>;cb%`HEBx82zf*B@C!wW(=|A+3UvB2pEENO48d(y9nMTgcn`{%%3GOkrwvh0UX49R|pd&gP^vS_q!Bi>reJ@-FGeRI26lFgetcUqnEJ#taWeYp&n{b6sj_gCa z?BzYPC>oID0VSbvv%!dyV9kmp>}ziEJWbz~jMp9z^}wF+q}I^fch_&2H}_-ThZG!} z8i?on@`TrvCdomk+gQGGHLYnfAWdiJo_#PWz39u}X@ut??a;&mA!VRLni*LVDXpxn zfDW>uO_N&qe1Hg8w`wK7zTyBHp73HfzcViYo=QT2*2JLu&IK^ z$R2zmm?Pk~o5=J<_T_lvUHi~Gqg1lDW*d9=?IZ1d?*BnsLFGipk}~CG%|V5W@ictdJHXih^@BeP{B{X$)v*%6l^x+*lC^CX`Pm_9~=bgz_XQkO$&UF zpo^9%5{aY-6dZ5y%sytyc-nMOnqP_!MErXJNbKBP%B#DgY#ZM@=ZmEWi;KUs3V+Eq zAS)YuWEN`|9i)9||7%&EJI||w0^yKK#Bd#j5Q5UOa;mDTgQzGUNVsl_eGP3M`LJI{ zZxPlCt!laV?wj~v@iJ1u(`D3vgVqcdS>IczJP?#w&IM`O>uNaX)RXvn)kZJDApo{rR?X74a9EsAiXD@PcA{hrX0E*`3 zCfXBDFk7TH{!ugb(tJMWb?*JcA87|1ZGjb`Yqwq$M5A77_;fE>b?Xp?k%8y7cLZyW z{j+qjv+84#hZI7ab`Lz1J{M)so<5{D-ci3z0;xTTcbsglH^55q)FTfw|BKH^(ot_Z z)BZYm27mT+@Vto*qZhI^BN}01K!pK`uFyv3+0${xo7LJwd5)U_i~hZoHh;c@{Iby_ z{)vHUm&|qlg6Nk{>$FbmwEy4Q51tqzwFcs>{CWv*&iaI=hGr_tDwuHkSsXa17#Bra z8CVi;YvpgxJ;(Zu+vwVRFlYYw9J-e0vU2%SX1(_z`|9f{s_f3RpPWy>9u;g~|1Iyl z^(Ncv+lk~9FzMtUama`RDaf@bDlP(P(YR{^FaGT{Ht%kxFq+4NDQ9x%A%h8vG&{C! z=G8aeX2+g-@`|fDZORme4;_H?&oTjoV%O$xdH%&$x%jHvs3^8sy?PysS8U|mGf(7& zXP)Mpb=#<{>dw@&rqQQIl_Aa58Z9)%1rqE6G%n3`+j#l4ne5!QmXOpaCDF>IvA%}K z|NIp7jjaqAb}&CW;|$6p3YBQ(<)@$Js}DbB%A~OzKXxRae7t~<=YK{hn$M|I&td3* zDq>B0dHKb6*sysk-MUpXX3P=1GHX6pU3ob@EAkO&Ea6~lhsXc;Ff-on$>kTHLnPh6 zn=?OVXG4t9V~*tPNk{X@Ll3fTXFYuf9LSGOpF-ElVu}h2u|g(8d3VhkUVnQg+xIjv zX3Wu?c+v#IB1yWfo|j*n$*MIq^ypU3nNvofQf=IO>upq(*!=Wo=hC}-H6PCTfKNYP zK$jl-aoQPY(Wh$>+c&Lc`dc&Dx@#|kh7MxHA&0SIs3-Su}*Ty+~m`gh|O=buDraXvb1BXxp}YuE6`J9B7jZ|CRdj2W}}`rFkc zlkN1~e-u;Cm`Z7W$eeI`v4sZMx(MO2X8BUyoIaD5lxE`ODRj#V@yVivoN>X$6o^Lt z_Uar)966C*g${4MGo2-?YpAU3#-t;MGv|XjTyV`zR25mQS-qMi%eQg%=@WSI`Da+Z zdJ{dm^2(5(yeKcCN8mt06xH1ql!b2xDH@$6S= zGkewte6eIL;c%2oFPuhomr|y`Gn-{!FQ(^!!Tf0IG`i#`dHT8688z-y4(QhvTWb&w zI@Q43d0+C;ysya1%i)Skr?GU!T2xL~ju|t8hF!b(+lw!7-c^@VyQ79#Z@tCNx)%Bk z8_798Ig>mvKv-lQ6Proe;hhtB|8yq^?6gknv`)*me*vk!M!PXSn)x^WKJQZwA3L61 zyLRxCv(IP!h8ohI=RyFskPPb6gDDe_Vd3JXJofC{Xi|JSZyw)%y^iC@9z)HBjhr%h zG7Yg5%NH-^?N?sn(8EU&u{Bp+bsZaPc9Lps-hG|Ruegq`-Fng5+R8;2 z|D2lbTd8l@%^R=3#i&C@bI|YuX=tqFFVDV0ePesz9Tn0X08cn+5@%g}IbFL}^Z5tw z@bx#}aKwaD=+(C$!b&r2NM9zNcsw7>{yTqp?r$U&Ecj$T+qP{Ym5g)e%{S9j-^?Kg zkK&$t?q&X0D{vAqZn^qWUVi0eMjUoH)m?iSH5B18W$LM%^WzKX)vbc}X1>Ai9)6UO zqYq>K`t|(c7gv%%v2ej6X1wthZXp(L<-Ipw!-^J=CfgUJ zLAo^U+`x=E9}ojJZ(Po6(`R58mQqrb!%4@Fqer*yTz&N~S+`@Cp&e2hr4+IHT3&kg zDO%gxS^m``F8s;a6qgj!xA%VR+EZ&(Hw5(R+JzHOIF?krjXQpQ4+$)Ul=Sb@i?h%B zDaV{J8B53c`|S7FRo6gU<329``DLVqP2WC!x#rp%`Eu!MT3dGW&_fSXTG^e0MvUMO zzk8UcpLvm_@{f;&=TkPaac%o*xafjQuKkdU*?dp6FF$)7}{sCaTm`&`wYDX9L$m9 zCX$~Q;!l6Lo44P2o8yl?hW9_1$K%hviAu$JZ`KU9?)5qU1h{GD&3uQOZ@iHq!wzEb zkfDS`3tul=$d{|Oqb0QLt7q1muhW`r=abJr#@ge40X)QH-AiF^>BXs@Dr5SiaFC~V!N^6uvH81 zNK}JeTE>{8j$-jw-!Oi77nUtu!bunW60Ib;#pP_T*~^GQU75LT8|_Nr;1K`=Xp@b+ zbJsprt=Y?qufIdDsyq%H(v$a>{tkqNvZB~IxwJIZGJ53xY}v9Mg^P@Y>9t=^#tiR; zY~9KAe|eeS)!5lQGD}`svok-Yx~hsC6{BwV3b6C(KYSzycF|brUA*%A z3!H!b?VK{{7{-nq&N*kC#{5OgXtfF{?=ysnQ%**ZBHq?QWvGFz+tyLpr5nw( z%|Ro& zldn_A_-3>ho4D|kFRAJ^lnbu9f~p*whWch6yyF(0eEc?2kzx)z?sN_t(go3!5Gu}V%*t^p@t>A_%ogn+QU!&;pW)B(}6EtEe!ZPwkjU zrgV(^Zo7rYo_U+5+9uL14G3j2IJFYsdGOMSIIRt>RQKwQD*#(jRbD_tV;yM>8=hJJ zER%tWN4|`gFrYP-M+;)=r9oOKk9SY#G%q~;BESFr6YQz2Bi^zXoP-y3DG)d`G&Ycw z`J~bz;)ygTOq#^mKblCgrJcNJ5oP6--V*G^PrA0}j&ab5CK{XSDJUsI1I2kcl;(xl zwQnEBA8LDW)g~H^aK!MQeE!M%tgor1sM|1dqmc~Pp!Sn=Bs~TU#7Q)>as76_TDFzR z6OJWTSI3>V+{J<~zoxCZfr!(Bt2D00(_PNQwrQcMZ)~A^_dZD50ykl_tbwhoS8&VC zx3g-~Zqlvw=u`~lg3^MdE4*k_FIQQcSi7CucT-eSiWLqcg`j)aD)#K!iY8@}gQQWo z>Djf6bTWpc%w|JiWl}-3!`Ag{DX*%)3R?)Ny?8tY3Z%9{NJB3pyhIXdnEJE;5zgi0 zv(9GqiluB=xrv6BIKu|_WzmNpbI-5tX3LJUB`>L(>NXl4mgBtjiVe7blE7^ zF)@b99L1)zxlb(CPD^VFCsaanOw(__KK$&Gvrq`6whZT=*Jnz(G&Z(VURgyN543r} z&2{~I3zXxa(g{O`qzwnBPnV>%A6Y9ALUj0}I{{#)by}x&+J9(2CYBV@^N{Ln}pN2|BwMeOB<62X)${2 zk$m$0EIyb$hoJ`_h?LS}m&;1s(Kh8>`Z9Xh0G|BaZ`j)4aKMlQiP!BS*3`(A*IvV! zKmG|_yZ1y$3#lE_$u^RX#?gQfSkh+rkbZo*;3Mkm>Pe*qv6M!+nvH9gQ&rWK^Dn-D z2~(z0QdEi*5Dw?i-c&~{mLQRIyc{M||NRdf!p?2$X{p^uthI$DE52p_kt30o$sjlJ z1{#Dy3k^be6hzrGC&b}L9LbJ#t7)#QC!S1`Oe-q7mebx^PyL=+k|`TUcN7J*ioUi83VgDh6Iq$+t8Gqu5gu`JZkdrT|uiZ&3ktFVD z%Da@2h&8cq*Dg{iiA%V{yz+aXu(X11J-XAcTRGFFp2q2?pU&~)MibVp)Ya~!EtU2X zLd^Gib}wVi@};C=F=BBCmwZYpy0CZ4N|Nz7v4o3be!1B&Gz)tJ5PV2Pqw;w(+1ha#;l*_jZKjDTeucfVS zJ9*s)Gv?@tlt&c>;S}$G^eJN}v7iV~001BWNkl80LU|>J~ z_~I;%IesFp2qA$kT`IZ!ic5L$-n;l)WhIGtf~u-Y@=HoM_reQ!@u|mHFsG7jyY?~U z$Wswkl(FN-@$l16vtaJ0Og#Q@F2C_se)F3LxcZWdiKjK)_CJDyh95y=!(K8p8A+Bc zp3B5@ZsYGC{hfmcb^|RDx%r%V?pZwX$3O7i`*XSQ%#(nS;l?u!%!L=6&EtQ4iEr0$ zBGJ@HNw5Bdga8N9DxdPwZk#c36t~`TH3bzt$c+~9t9$OGd!HU$`qQ8A>sxQ4qPjnM zIXT>U=QSL2lrlPvxqse#t|Bc!*zoKAXmvV!}CBFt|@|Rxe(P@Tg{d z8tj3?M$xsbD<98zhsR%=MkruS&hq$JQG^mqJ9#3?LhhJYk1*Jh~#jryUV%Xrm+(E1!Gry$i{1EG3Xy884nN)HPPH-7tM1&|v2=dD{7WvFui^zv8Eai>f&0xDz@1 zgkkJIq%XHzeKl2OIc(hCOm5Uu(9ve57=mj_QGNlVhV$@bH1$e%;knmlm>qTQj*iVeljh zEe%>}WPTC9y7LYmd+HSy%>4ir$>W@#oXgn#i@5aS%Q^qLKQQ^|1Msje=brZ??tb7g z7Jm5+d4(nX{1@kQ*pcIz^Zsr8?BYvEr$ab7rC8xYEEz&;2O(Spt$Z-^ZJwL8f+rup zmq@yvt1dgABc}d>i_ScemCNSyG$*lH#HQ zaN_LQvzz?N?ue8_yseG0E@eoaq`sk*aDFj)mP=hzD@A1$h-4cru@psR<=84sZCw-j z`32-gAs%ySY;Hj76qj9lFUK5r3_ri5v9T3Ui7 z6{%#Ly>+d0sjMVod)i|&iwlbLwZ@mQ%Cb&bs=QkrlmLV0B+VWH4Yocg9V;t3bqwkfZyK&8_()Yqec z(vlLQIU$;x8)$7y5DG^rE-fVzlC-tQh{cnXmzN-P3Mm|L9iDvZHRgZ$4S#;}5egy} zmUq~Wwu}c@n&cbh#M!&AmT++e#d*0{$|2U;Mq^tmt^#S<6qc8hYeP#z9Vro^BtMt> zeS0Xa?m@&(lWcFJu{lZFNn?d`C@w7{*HSb!wb0g{G#S>>T*@lS2)QYmnp$a&#R*3u zRF&sZ*U(IEVLAC>K_VWbv8ffMT%v^~6ciL-xiR+EwNhMKPL6Gnj5pKP-cE6OHQ-_k z%don89!gw?csx#1OB-pW$SW$Mv>-%07N@ZxhSmxhiBM8jMo6{N*qo%OqKlDZ(*P;j z+v{m)h03aGql4@wX>4qvEuKOMO(?g3;?ffAR0|D_EyPohS6E0{L4-ssMnh8!rCekr zhmz7VA|gS3V;lLUmE=f}I*nE?P0j7J#N%jTQC?a~UN}u%Lo3n33i87Sq#9bB1TD=e zT3X|1DJd;4B`0jr*4#pCYa0TKNKOs~<)tLr+HsOe%F4?SxWro8X-T`3loVr;q^W){ zp}Y$6a>J-(E42-2%FD}$gsgxazf&=!(>m?@?Yl5Q2!T=xDgOnzqn-AD-Le%!esB=z zIw>sC&hPKOgGIY?c;?C9QGgrx+l)UXlNl*dCP3a-81rhYGrCcDQEukHfb`6JiHi(n zZpN~H4?vo_y}Nko*}sur5M|Gv?R@yf8lHaq5uEmYG&Z&qR89*jx^`#q&_RSSf^z0u zIlCGCvR%(nWqCjQ^vW{$*;CBLm%q|{C-^?NuW_IFac2?{NX%v5Haik3BaP>gL2I8l z*e8Wk9v_`iip6g`)4-Y5@<8zR&1;$d_Up`=yMo_6ct86O>T6=P0*<&$EL(<;uH!S| zlR^7L(ZcJUtYiF4x`#rj7|RxY!NMiqGIQ=%+;iXk95|>Kt&O!TUAhd{BeO;bq-8U7 z#KDvm6$CDB@tx6~QQGjS<+8?+_F_H*Zb8dy2A}xb>R4F7u_uDI&x}R?m^3p+{gV7o zvpY=-g&@VIjq6yyX$O`S3dTt^TEJnW55*3sinJ$NXL<3PnLd&pDAxFO@@ZxuV37`L zV|7sM3H*=RECQL-imXOMcT@@SL26K_xloA=6?!0F=qHx=8NEUV<4lQ6Uu61B1&JRS zB^mE}1zKu+(L_VOEinJMDjgb&mP}U6u_3fAHgAVTC|PIO#{z zI4qq<1e39AUgf@snbBztUi`iSTGrxV7A%WQ%7>M;Q28J+i$m4}H~}Ec28vn`jplIZ z$YInswbHB4ew=mD74+*-#iGwvQCHhyg6%O2eyE^0z)L>yt+|J%-zt1GCe6a@ahYj+ z5?eoJ%)~YdzoNc0n)h>nExmg%)j71c$omVW56FUB zXV9eggVHXcP?(;*2XNQDr!%nsepntd7hc==$uqu=ia-Q3$o}1fKJ`Ft(4Qg$BZINx z)guzgqqov!M|E9ET1vcv;CX+0aY+fJJ2Kkq94# z$e;rLCmPuS>-cIa*{Wrk=Fjd#|1Uq`!@tT2%0(E;ZK)xdXrrm286`~nDFo4cmy|bp zEHB>AJ1EAhhNt@CKXag%jqoJkgs=D!^n=Q(oBx?WYk?MS(1ZT-X4)d7LSjD8>UDo0 zYmW~!7)aTz6Et2&nd@u-7<}$OQAXD}C_>`ZF+*maIYj^OTU%QjH8nLzOL_??86ccp z{y*-ZeUP86T9Sd&|7iaw_TYZ`9q;d#pBdlZcf0TX@c)wiTP-KP=d=G>*%`v|tcm&G zDEFUfoy@iW_I*44=HI&R-@5B}`}yCiS;h(S?~U8w4eZAd3qjYeT`4Xu{&&jmwEs!= z!+Qep6e2t)n8%5Wt2LJ8pi~ma2@?w02w|2sltqU*o%OoUS_;i|_;@Gtxxnzj2`M{# zv*S$2tVsShO)-9kMaCoHLzxVtVfK3GJ&=|dFPnp#N|C}Q6ps3EB6tevNv&xeB9&Bx zLN-!n0T>@Mp%6l%wTlq`-DL&@3hxPY*2K7-f zTh~<04LmMh=~=DeKV#avUnq0Trn8<8KzqtC!gz3W2F@USZC;t>h0_`z_8>AU(0)BK zfHMQaR95{0Anv+2ZWfXl?od?TuYYhvP$q>-De9`uzI< zfa{GjNe1{TG!BZ8w=Ggec}7d5$UK`!r*RdyAseJ18^EAYt7 z4n`P{VlbWkJ7*Q=*TL6v7JeTq836SEiYKt4p@BEvc!QSKW|B?bEN_!$Xs4vk+8F%@CbH&?)*00$DZET_p-|pS)#y!o z8*8aigv?7->r7(7I=<&x;m=pPjWi7K9 z`=9E}QLB*n2djZXvCdL*^%kUnwv6oKEW=;-=3k#dRQKk@Nt0Q>Yys^QFzS%ug#1O1 z7<+eY*-f;pD|wNyS&XvXj#keX_YxQQ3qZ&_>Nn3W09z}=@#wXYlTPu%6OYpCh+`Rb z=)r`v#`2EQgJWPH0J{Edv*tz?C=^1W-847d{2QiDJ)Kd99fH8}pD<`Ub9qNn=4?-w zX?BIyiiXAp3QG#GYzwV4Uw^q6N5jE~jlv4LC)+Ffo$d;}i)QpFL@+jk?Emldynp=e zA7W>(hndCkp8zfzlu}%O{qEP#(*yWt)jEqUu0(H|FMXx4zEbB zbnhs^f4_mB&7Hk5$u!hI1ML3UBSWSA@BqJnf2cGa`{$o4zhfExcHLhC{1XapAqgvftHOfcVZB@6arsvqJgn zq7MSa_x6duRWr8`-|6G` z@1o7|neyhD&YCD4)*gX(9Gm?M?@}Sm_r2G^?wT#sH#VcRV#VT5S+sN|akA#2O3~W5 zhcA|_BJP48L*>6NK%w0>9=`u>KK^2f;g|EjtkXfA@vhB|{qhe6eRW?y&a%C3Hy58X zm1V2flM2AJLioE&Z&CL>h^`R0o=fJ7kLR*s^Jb$joTYB-?{LYki`OrWjXSvZ#$U3d zK4#(?gNJv#e;W^=L2Jg_qH#^^TLb#)S-qA$&22$ncyDxbA1B7bd9(P#gO8B%>*&Uq z^ZsnM)i#n*0CqYKBX7_0-Tuk+nc1!j?-<`~k{nPPl}@p4)pB;%Hjjp2-mGlJR$OQ1Xd@0r3E zr0!754(}Kty)j|#=elNg2W=uuh>jHgZ1A>HuK!Aw!P=mO+hI=@xD|vM^Bvm3f58PO zKq80%HoyM9hs%^IzB?KG{`cG4=hp0`Qu<$MKe#8*;D!`U4ZGR3r;em6v2*h1+N~SK z`3|n@;HVHDfRAU`5#ZraQ4-HpUk8X1nzqjxV#a&m~bHnXE< zGci}-+F`nN?Mg*SAw|9WaK*L1ptK+lH_^(bZR?38B$gGSs#|x;N{WzZVr>m<-?58C zQlld|R9APQyr>XMc*z?8Xkx96Y}-~tw*mW85Khz5)J{`#lAb*(*}8QDjcsYHNR*yE zx>FoAeiflyY|CQOsizYYCFB5ZqKz#(cF^9kn>~AKNxK4}AeCrg)28jDT}8N{h(0~K z5!NpCJGZfB^=hihi|F39lI|5n)a~2NzI{!&Ru0|&Kla`{I*MxR`~RG(>h8=5At5A? z5avN<5m6LHK}8e>Q3;v@A|FxuKV2Qx1Q@+D=SlV)u}V?z0Y@lzqz@jB?Z6xB(;PZoVti(qjivj`wvkXbcm0OBPFqd!o&O6 zuyGxw$CGK?q!B4`K8_deqo}A1E2$Rs^72Ry_^2!|q44m2DnenBQj(~ZR)qLtz*S(VFbMe5U^G6>@UwVB&D<_#q099mk}EljRY#VW70bp#!@(SrWqX#Zfmm zkMzUo=2@lt7ETRPGyhKdIUEF-22WdV)iRM+iGUYS+o3PG)V)h|6VH zTvCp$9pX}Ik(--KJQ~xAMxRY$kxgAi@u?FO7M{Ycig2nV0?LPp5DFD@@L(a8A(L9^ z>15|*VX6q?2nP-vq`0gSGd_`q`3;CSt2lIEAH}CbB&K9gKQ9}@iy}ISy|XsRTS>u!KU@= zIaM4auR%V2uN^={Iamg0r;Ngb$0;re5ucJmUcGt*Oq0^$LJl7}Nid@D$H!BzK|ZzO z6=kQ7ao~86hK(AM;QLcz&VT1J72OndG;|U*{1p-ja=Nk#BR+}bfQ2J&GLEU-2&C4I z`+4Oa&8q0lwcYTHKA@tPy#Of?QlD*mS`Zihsu3`lsrrJPfcFaI}NZ zG|-VC<;BHFLTwTf;<0K3s{Wsf{OP+LrZNSm_J z95JOGa2(33DhY`}YI2fGFs~GbQ4{h3uCpEi)9<~v=g36G=e;058K$c_*X*6 ze`NXh8-V~+GUwB`nfd8bI-PqiCyyK;Eu#UGo*0c`RUa@`R#h;6?pGW+TExcPMf4jy zjNyYW;_J`n@Y$yeY0;)7d-m=nH@_jzO`FQ{9~U$6iN|T%ts7-UhcS~fd2-4Nq?H}z zv4@^z>KpHHXx9qvee`LXweLphp%kBtfZLFKl+$R@D#sq+R5GH zpQHB$dDx;^zG4HVCrjwvvpwa7CJ#LRGTGT#l$RD$JF5{-O}L9t@H8Vw+((NxXOWjz zhZfD7a?8Er`DyVFv~8LP-U1^6zbs!v!NF4uzwUB2{W6~!bAF&nyYslPb9)-}>c$td zKjCCq6+5=drLO?wZJmYmG)ox2$K%u8I@ zz7b!%_ZlD0TS;zS9vNxzjJ@YhzW)9@=FXc(UV{c~-LRXXw+`j1Yp(%O?oqcPEd1tc zzL>j+%zC-(+qIQG!^Y72qK-^__%V)49Ch+qFyf{gNpMc_$%h|MTB#{GT*Rcw&ykx| zi;(SO;ljma*4x8?YX|b(><=k(f;{@f6D*qhci#W-bF%9<;>6*-T-s+4!)_eN+>bxt z{dvo2-nuOZcW)r0X=na6czcZT)dk>~->wHQ|%W%vjY9$&dRZiLQB4)kuEtg$)9W9#W z5?7-Z|832x-RM>*ES#CaE& zKsbqMlOMuD+^O_`HF`DTlrU}bWOfIWdHa=#9#jXEp$MKj#Mm+SlhWcMCOmvMse%7X z9mPf|p~{O&`=jg-D9|=28)YbLF|d_^X)2fd5*x(CP(F{Bz>Q)W62Z0R;)saH;UIvH zxW>K;cxpS~S9m8}06rY$qRlO(Kq4L=sSoWbPAM&zhWi=!ZLEKy?f)wOD~kM^i>+JS9F(oE7r>C z9V=yEziVXI$r4$+WVYOL`v^H6iO8XXHPW$LFZp5RR{8FWSQy72nIX zHx8F0;fTC2{sEc!&N~vcLo)rT(elvLnX>u7e(BTwJXyPYj|3y9Wy`vS(!BFEvg=T( zXuDMGa7gT`BQooSNpjDVvm{h`M8=G`PTrjNqf|OtoZw-(ZNPmx}EKWzn2Z~8%$@g<>^rtY`uDj?juaM3 zq^eAw7>!e$!&a!&fZh7OA&t>3sL!`nEO4uovva*wM<>gn)`mNjL(BVTe@R~ky z@N}tEiHO!(M2q_s3Cr?t-jeHY8ZM=x<-5;kNxvIMNU;{NBS8sAf>L~}Q2O=gDc}6M zMiwt!Cf&Q7Cnu^ZWcQ|3(jd(z8xHM}36DM~w_HC+N-KjB3GSA=N8K)O&0Qf{wAhg< zv7IW}w*E)y+4lxHrnSufbh-?=?QS{hXbC$Z(ZO9Zu>Y0v!`jWVdeOHsXkdTYeX3Zh zDvRa*hsMj`n?^~|p>@*v{7YozhQkt$RLM(|o|mCRZ++~+D; zzWjFy*x;mQW}p8#iv0 z)2C1W!>?t_mc_0;apHu`m@z}N_U64rMC-6PPEZc5`9?C*lI4v#OJv>8Ur0uBk_>-f zsuZ8xBmJ-FDt^Q9mfr@SKvcdn8A`dKpb z!*9Inie&LOuS=4ZDNn!hp_~-)+EJhJ%<3BGfAHI%i?=3fEwLKL`pNr{9g)L3HcI3A zO=ZCKx66sDh*XIq%jUl;jZ+ilk*PDKw8p!+PYa8P9cvFqL_|m2`4DRZ?^-7$BDVWC zCnCCXzYM(mB02xcTclh>BJND8(Qc75?yYrLbZDPk+v9xceB~`t6|J{+MB5=bS@63w z%m_%&L1X1;P{h$91qB5%`MD{gV=oz!%927EIqU{`@VQr{Qba_DL?k3yLLxdO>wo)6 z&hOMl8Z>GwuYK^j1VzM_Dmi&*i}dZ?OLBAa<>{wil1dSAbd?0l3uW|(Tcl2A9l7J~ zadPZbsYtj=%1$4XhsTYTy7ls<|Ikr#q`XQT9g$FJkvuZ?PHB)=Uj|%%s~jt}y;iA` zna@v@yqvnyqi0XqvSX)I#@eDvL_)FF{Px>#<&Qu9_=i3HSNY#lv}X&fSg}I>{S+}? z#-L$XScZjZn)u?9xVT+&4j`m)|B7s^n;iCOI?L4RM<$j^)Gf z8`R56AtlbCqM{0|OtdmEOcS4BkzFT~U@(lTYogE|>dXb-i(!zOo=Iv_GQ~wjoGREy z>&~4BB>V7VV@kx$uoH1J!=ji&1mXe=8gc{kSFY#8`OP_W@Hn@%Y|O!(>zFv{S&mnM zS$33?xcV`a3*cp#xzcN;+Z8j4Uw6^9QMapUb>F)TkmL+IEfo1@1H$!^&OZN-6UVpsu`GDwRv&Nu=<440b6 zFx=w>Z6icbhJoKS@JW~r%NFwdE3*g^Px#a+Qk%4M5qXv%x|~D%cd}-~7KYt6ihy6C zw5HP~9XWlf0Lwr$zm!077EPMuV;ZKL>njn6Vu}C>ML2Na5Z5%yMNE_WIkm}3)oj|f z16vG4{P;~bn>s#D(Y0+IR;^x4$hWSgH7AEQ&AZr&T_&33bzgX7C1V@roBh#*s>D|0TV+T2sV}h zrwaG*^u&o26qOTKae~6r0S|8H_OfXx7sDqGN?gV1&71a+on4QVq(po^MTb_+`1OYu za3Vv%^5G~SmgT2o%Uph0{WF!?aSwtGFZ11tKK-$FHT4>vPar8CD_BK5HgRS-r;3Hm zTeouCjW-g}HnxWL-P&<*{}F;AO|#~WF-;T8@Nw!$0VStT@WkU!ks2^Doe0f4cEG~K zz{E5K(Uol8ww))R7*8N29_$D$8@I!(0udjUFAl?0V3+gGj8|E(^cM_YGW)g^(C*@k zUA1kc!8GuaE0KsM4mf$_C?|pz`Hfm&Dw}$_b#b)KkrPE|9K_Kw1t61gQhJR zIOIlp_vy{C!~58=>i`|QT*jDDH`1|PV-_s>f#QhC#HlZn)gYf{`8m~aSX}HTQo){` zTiL$r7!|<~aVe>^YTJR_dRYX3Q1CQs*KOi(;Yku|WzfFE*<{yFzz&!2`)?aKbmSy) zDJgV3yCW^yoz37I`g7^Uow4lGgv(Fz`|m4B@j0B|r5UX|pU-vIUq|Yepjp)#( z6$#?5iP+Hr6=ct@t!&=5kMdIosX&2cRp)JZ_&m2nDA=-s7bj0;>91S3qFFa0KpfGd zU7M2PlRP(hIzxuvNu&H+rcHU47H!+nE-#h4?-)sb+wP3H_fDR9>|x?^>T}OcJ$UJ< z$0;U-xpP0`%{SlXjdwn0{QcMR@kj5o{Xj8uzW9VsKKX(P_dm$=mnSgw#p!I=aftUm z{D4p2`H)A(j^_DSr?X+vH_ZS32j2YPBewmzkmskqz{FRlQ#a0!6^j7=6$SiHE&u-P zV8P`gi^22(3A3-Th}L<{QK3rwI)t*z`FhT`)N9#=`^VhOFTbqhvpEX^g{>vV185Mz zAmU-76(R=O%OI2}_}QaVh(eRA$*3KdkI>d6Bqwp;z!q2T3p|6;HCSVdw%}#4Ce!(X zZhZRLBg}l;BCAOUn&j2v-N`eEPfFv}X;UcLww#Htf8%|`Ky)k>1yCf#`@t^dP~kCB z8fCiIL_+9_(@c405`)K0W5_iZF#Cg#*;oXKU|K%HwhKn~`4dU0mCCMNdr&>k10w7@ zR!q~>+AeiXlsZLufPR(e;zvASyQy4F<48E<9wKp-}#feiTBxYx#urU07EJFyF zRbb=8YGLaS9PQRa(XIvIzCEGuT(Q9}E{*EhsDl&hOfuS?_(u@zVy4TX)1V zO^=JtB~noyuU_5UhO}&y!6$FdV8_7{`rmdAMMn?w%kn>Xe&!q0inADb(@>Pw7|KCA zRUj7P2qNG!;%Jann}Xe2sk99eO+S_qz!1fTmA_L`UdcO?g(+Z}imHkV zcVE}qr6Uq|`Oj}yho9E1A`}jz4cK3Jl&rj_7(O442Ce*P5llnl(m&LMI4KWHrO9iQ z$I1gIh=gt8l!YS@K~Xy~k=&e2UY_+PiAez$y5RFuw0kY4Asjt&l)Q{ufF`+CCJ712 z+&A_Oflx(=;(v1dRp06!P+N82R8soO3}JEN!FB1PGR3YX{rWK!md5Nj z3{^9CRJ-eh9YPT%g5Raci8?_Nc4xlwV-UdI1?f~03MYan%8O1i|C?{9-{wLZou5I(QLNv(hld||j0t0J!l|^WsMJh; z{v~o6G~&%>&8e4?9PMBXQHZYM&6lR|>g**10&cEEo3p#~&c~mSo8~b6*$GU0`x{Ej zEAaaRT-JXW)2H0W@_C;y`jP4Q5)w&BPG#ClFK|{`33I;vinDrLN866ch*r#={WU)= zSi}p@jiyzTT;_cBB^O?M70vQ8nE2pBeDv)Cf?yGuvxh~|Zt-$jqPl$ERh zVDPQu=+vbX@yh0g0oSr^WM6*#Z4(bX@+=o#*qmmy{0ts(I|WA$^U@o0xa7)#T-v=G z?HeVqXw0(|l~htUE&%fHg;)Gl{{L70$24IS!t!NHm^t$u#y>uR6`Qtm?)eu}Co!4e zi39A|xRLseTd{8KMt)xQGuyUp#xyh{9vGL1M-$`2!E!Nf%F74_P<}T$BN~+DW_1CM z8$Tjy-Wg(JmYMZ* zJdAjsLE~mk*|u{#KP~-%^_#c4d3mBpNlW49B}*tPsX!a$^&G`AJWvpDbg8c{f<1;lVKaHC<;oFaAGyBuO^ZVM(3?FqDAHO+^ z*I${%!w-#T?}>6cb-WOt<7PmMmwmVV*Ck}2%+2Ph$Dice`3rgfqt6M3 z!Zc}`Py6<*7(VnyKK}44-hJyswC$%sP9`r+e1P{q_>?^bM;JPM1n*3Lg)cw*jHf2Q zNLJ%ET+pdKmQ*1+?2)Dj7zSr|y@>MTC;4FJYjo<+;ta~0Xa=%~i7&o31N&XYjHyqM zSUZQD>>N@O0*DCTe*HDemoKNdqKtqE>8Z(-mY(Lv#Y@o2?~WsFa@WXP*t~89Pd)V{ z-+#G)9eWO9i6T3vJ_imSWXaD%}4LV)i zm6FmEOndQVX3d((oVnle;P|J&j6<}8q1;T_C^MhymFXI}eFn-(;Fdc^Q?PX%QzlK} z^RK>PYe6AGfU}x5BfDM}qeqWs&ez}Z?z`_&bo@9Cn>1m-zpm`ZRq8fNOUTK z6G5s%0c+N*W%VB` z@CW?7``)|!ylgQSbnA+t94{KG(2j#+#4+jlSJ<&@E!Xw$i{*qtYXWA34VzZ;#pm<5 z=h3Ixw|6`3o7Lm38E>&`-yzCNibzPw^hJ@7n$Fm< zBk_mI>DO-nhbtn?cxNVUTC`-;$dQb?^A76Pt&51sWxe~bdD|9VdFfe99JGS*lP0oq z*>_YH6|!K#uT)lrC^}L|!SzRE}qNJ-+#i|4V!ps@>CZ8u#l3HlYBFOK1C&E z?AW=TQFn}D>5}i5@Wcc7EQ5$+)3y7h96i3DVb}L#{#W0y=g48c{PGKyFI~$clU`)s z?u}$7YCe2-Hf7~59Xra#&=vf&Xd!FXZ{zikKV!|hRbi%l%Z+ayg8*Mr5rv~ zNLhtVMx8p?SftgeO{DA;*p-|vDJ3a01*IT2D~*5?qG10XN`ji)W-SrzP`7R}rc`jG zsF-a9r^%?>0HtjFiSFrJNl6X5r@xYd|D((QOm?txk4PKl)MkM?EBdwlur zcdS{rom$zA>D8?}hLymOn{FZ@Wf2GWZJ}ZA`CQVgAMe%5Vfl*HWal+w`l$QJtDi$j z@d>UUcqM^=AJF9G<#XRXcT+n(C6+~@;?kJ%>YL2|dI9Cf4`Kyc(DuBGY3L-90GP_; zfk*G>%Q;`Mb?a6vGlc=yUO}p5QWXCdBRcy{trEL!v<1-rJBl35o~3M(;%NmF0s zyM;fod+$zC)6y}Ma(R5h!_52oTZ&E;5me`JdGB^4CnWR7hHbR#d@j9vUqt|mbK0~f z)e3k~5(f-}T^AR|M53EwQlYWT=CTQJk=5rv>0?cryEZ`^$chC=tV-nA}y;f z6Q7yDk4sjudHWu&zWx^4p4E)p^aP%o{47=BDpE4Cx$FMNsGXcjo!t6-{MlzLT)ddI z+YWJM-)lIpV`J*q4)DlB53+j0Ru(^p zZYBw78BBX=8sC4vnDQ!{m!>^WmkzC{syNEXTZd3T%Z~}vZ`O)Ig9ejq0TMy502B96 zIfbP3MBaPjd45>Dl)VK7TsiPYI=5*{?OL^X{%^1F-QRzr@Zdh;l9Py!i$nQRd4Bp^ zeD&?u?A%>|u9bxusKvymC-Cs57V8tcS|N0wgST_?B6JLBPugsXl_X`%YX8l^u>Uuuy+O{RtAIH7-kK^0# ze&ERdeMq}@oZqc0Av=tv3`X8Hg8aty*}8on-3JckieA02MAN=&cPdpa{Ftb?y4-j7 zDC*bGBqQxCZoBmsQd5%<(O8xV%HrBVgQ(NAJ)#`4v+6M9hU-Z1#bKxjJ$qeAyO5uM zNiMP21WSu3F4ok_ZcbMH`q-5_u?#oj8#UFngL~>=1aPc445h(vFttV#k2ZbYh=o|F z$Z)e|l?5T&#vvYu1kP&Rf`-{CY}mYp%P(xssj_nVbnQ-3N`Nc6cjful7gKn$oFRAI z$U2qIt)_Qi?z%$npJ02|5Y%=-roE zwNhx;rYXN{{)1!3k0Qzd;t-{1*QOb%rbB6QIT0WpyzqenkC>-L^Tu>+ox_$z#q{fO zDYcTolG=+D5B zoGjRbQx#;^t26j0DTyXc^2x}oPyM`B+&TI-K6q<7pL{u&+wZ=YJBM~gOp}NTU>b@> z^|P?Tm6VhebNFxxVG%lZZkB=kZGY}_C#C8zN zRjM&flZ1o>d_Ex*3Zc-1!y&}5z_bYX{ouIIs0!OeL`X_X!7?FSS&1_IM8Xb&NqoRh zLY##isYEH$%^XLtYVQ1hMFRh$%fH$zRnvU?vp_7~EoU0Y0D21X(h!vrd-6kzx` zt3wxBcj)R-R0)Qa$Tj^3agCUWHt^D~h|kOCj@xfTw4y;yCXTYuqOjuA>D%X8`YO}S z3eyV9Fi5V~kUQ=e?H=D6E^)6Go7#19x$U-*IJSxD84KrKZ~^CCaFNT9FE)l~(o@nI zJfJU*2%;Qv^P2O}*w$_bL?fD}k2<-HxqHkQZ@~veGsL4dMp*$9NLKTZ24$=_C>U9cd`2_W_3OL_8;t0c{rN;9)1+<)uT!CHZ*C`HnvfV zfT@HYS6oGpEBb&ku(hW>;!oi6URQH@uf86!i)P@!8xZ9x)ii9>oV)I74$8z8{?jBT zW^n5*!(uFpja#&#Nvoy^VH62O$$g_y!YT|JH*Z6;7Og#oxoUmwTG2XD09A*7$ z_BLgZoRUUXn#s-sTiCOE4>@KcVKF^$oW$A|VNyA2-~gW)5jT)2#FnAEACLBK5GhxuR8WY|EqZrg>yE?999%1<38Tv0)#F9lciLgBKm+a3|StE%D{raONCd=_=Hvr)>R|KOXr?Uo@_ zR0#pUL84)E=eWlhG3ri+k9>ePXT8JCSGU42%vdEY1my^(kw|uS9TE)1hChDeoJJS( z>*_Vs$vzujyg|SZWv5S5Y9x|gHya~Z#FD=+WZ>oPsEjItdT;G0h4$(fQ{DECi(*9W zrgk?rUjq3Jn_-`Nhsw$z35LbaorPS~?P?mt zPC5meiuP^KR(SoGrTxG1784>#TOvOP|BKWeYgFVPF2( zcmVNdke6MD%Q`n=-}beH?S53AtU}vDM!E--_%A{Xf0h5V@;^cmqf~(UjoVU@9`Mei z9V|~yNm&Mtm%ia*@!UiRLwm;%HOM;!mry$5VTDAZ_&bf*3T1iHZk`H-)*59fH@U>N zQKp5h9V`>dD=PVU`AT+u@F|J4YVpQvf1^|T=8S*%K~`VyMHYPymAM84xbubnJ^63 zD2^(yD8Z9XR563fZEx-Ioq5zuT2N;6WkKmE_nA9t4W(mR9}L0};!WrgH?t)Sd!}g$tVXj#o{EvfV}(F)gn_f)Hy&k1p zUF+D$`sa#>Aoz((sn58_9^kHVPjO}UZp2FvtV|O9X3Y3iI)W%4T5Nne=t(*Ha0~-Q zII891HEUEVjo92%2zz&Ip>wBBgeyyF*rXk!Mhv5QmY>0cuja+Kzot=xe9VBKo_$Bq zsaDAVu8tHdTTvjG=ecpyF!P%`F@z?|RlT|mH!^I8{4jD*RqNY#ZD|zI;d+F4s1xpq#;mH{v5TBgFxJSnG z(wpyaV&^KBE?>onyBiy8r+n07*naRCo)vyRJA|qby%+M z-!b~#&=R#IqfO?um4j;z3a&PWs?k?o`-sGB8m&F!$*YXQ3!@Y52TuY}Tv)o{jTslx zAYKH{tWmq_F;hKYyzzKO`$dy=swLE-u}2-PpJxo#Y~PxOXY8#ds+i#E$vU1Ew4prA zuW~c5&Fc0xyt>uYK{&H--FNv%vS=bgBoblAjveIY=JJoqpS6Q$&z{Ylci!pV*{Nj9 z){X4iyPr^{CNV9GvpaPn)e5p`$#NQ>)qw^XK7L-lhOByxIJbQ(P^E0!wwF!2in#2` z%SrMnjM!1X*M6cw7jgHnVSKgX2#<}wkJ`18Y2LC8Et)sMkH!ub^T*nC96f#-e{wqQ zI-NsyS{&Qgu3%TeVKhF{>*mn0LkE136MX-}FSI)6Vp`_a<3Pb~)@|H^<0x9UYe`1! zG?x6hoU_kAm-^XtDLrz8HJjE_QeH_`b}r|1K9_h^#pZRZ*m}5}3%hn9#V`DQ;V-o5 z)QJZ9xmXTZMwA0js3iI_E6@`0aO2R9W=w-jxKOxJR^w zM_9XY8>cF&NK8uM+zzcs2so@VwvdPYCNXvHZNeL**Po3cRRU1jl%%V%jvp9Ni7aKS4qO80U zUm%{w&05f^StBe%Q?UPVOg1h?!t4ZD^T!|Pq$DT1A_jk&N%Q8-BPS>4FYVy}?=HH;SBs9j_CvK~RP;zjbdajBpaMw*yaW-?4)7`vMSDcI^fQfu zsJg27wD?e_g%Za#>Zqx+ES_epQT<4-p6>rV!{bly^5@}E z!<_MsCu?5d3F#^Y;;?7?Zr*{G}a5s-LJPg->bL=4D2#8q3#X&d%+VZ0elYolObBP(LqD!fW#9{j4iBoO_Q+dh= zUZ6HQ%+GKJ9IY{p|C-bG-)96y-!s}{9wJp!O(L({C}q?IGPD3;K%os+L89`+0q!3) zgkLuA#~}`vpxb2l&HY%vbvM6nEM@Mz_h_D*b%qjzp#aB53}3abwzyf^uA+pAX+}qS z1QCT+7AClnZ~@y} zW5v5`k}|mIj77nJ4pp8Jx^|CRefD~+^ zQh?$yJ$voz9mAS2r^y}5QPn(C+lc8o7dW6ni;0+?TO&4tf!3}g6+I;}#0@amo-~}H z-To705xYpcDBXesht4np-4YdvbY%t&T+b)AmTJ$bHLciavOJkT)R_w7;O%V!qRbjD zIPS5$(x82wbg8%YyD9bV=|(j5(Od4&4tUTasCGc3YfW@E{bdCHXOx;o;J-aP*j-TE z)m>>Xk|NRQl1jal(1s!4QhP4zNJdESm%y@Mg(_fkC@}3c0 zxA;K*CKoAL05Nhx5QgIIUB^)c<&+uDDa`fnaHmqF6m-Bx{s{o>WAl2HyT4@|~jb3#7 zB02)auH^PxhOu(hy6VV5bbBAxQKdGCeQ6yVB>?}>0Q^@Mt+ktI&>Dlnp5Kg!|xh$0){V+_UHDXM~|!M*|R5?_3Xi=Juanj^LF&O{3?bF zx{9=%P;Felg16PqW8o?usk{+5YhO| zs7d0EJyC|6M1ew#INYpTw+>eHR7hMVf|y&bqU(@~%@oHGv^LOMs^=xHktH6GSHy7P zC8p;PY60a#DHFpmVn(jpXUc^hc|D2YM+{$VZB?GJFNXCGCDvSMhT-Zy7>JrB=5AE)LJpf}>2&xY02@ znd>KNOey1+9~aOuHJ^@cT9AlBY1@n9x%G=EHz~pWd%%5$7tygjzu8@;93th%`Qn4u zXnXkp8a2)%&TCDH9#;!Q{ZA#9n~0z+Of>gB@-XpqWToM9)OiM^t0}4w2b3vpA1QD_;?)MAYk;^>V^Nk@M`C@W#2Zpd z5F8W{G;!FD!f!Z49Ko`z*u4bTCNz|yVUtG8{^Bz->t(zBYeW#Sy&#YK{(dDW$409t zC6S3zih`YM`DMjk`rb4MzkuQQGkNkPQtRYl5Jq93J#3ryHVAhdR!3ngy###4HOo~4(;H_ zrN8prtl2cqNhBpsc=Cy-2&86UXpN!7ySs9u?#f4cMiwu=Fon$8nXF#=8T0oj_Q$8qrayr@#t@rp)CO?MP2Rqbv>4QCgl>HchZ z|Bp+} zHlV9DXw6uSVm0vW7b6M{P$tA@@Yv+(vB-ZE4|ztr0m?99^*6i_cnxwD6dF_2pwU+b z;yuS}QTL?hjIfxCn^odYB4r4ssfeBYMC~l^Lxx8jUTy6Nc#-Cqqf=w}MB569foWoG zVi?u!j)y&uItVq#V61Ib)VPZ}qpG@NY83NNiCi_|60!JUG?M4Fk7c_1MGVxd6w$_t zMg>*P22l#5`fgah>eH@h2m@TQb>S}~@ISHq+l@e53zn+n)Awic#Pe@sqDW6mX5h&C z89t~xrs>DfZnaLIJjx??-Nw2NJ4noJ#>3A{=F+npGXKjjdEvR4oT?}#E~PH_j(e1A zuj|RWpXT%MefM$7v52?Q=zqh_jJoGGjN=D+VBE7zdE|e*IG52xkWSFFY$$(q# z1kjr8s}^(Z4a4~8$KPq!FopSF z&1e1(o0;+aSRS}{G)q=*At5=N2cCSAD=+Paa(pO9Ftp~AnJ-fm-<${Tzk^+?f8v2h zrf~B3VQOb)AUX}husM2QGed`srs%|J>NPowNiR;LT>~HClH)va=U84ytHXWw+{~ap z7xDZvFR}2aB^Ze*jJWGTuJ3mNl_w8#+t4u-94e$m>n8LY(4Si$dWoe!E}~=8Y}e;j z8nK0uLxvKclF6*UJwv2$6XU1MqF5(0aKJ#G9y^4g*9~CXz9Q1=x8TXiPjT+qt$6OK ziCoybH&Ex@&!ZRQKM4$M1UI^FBx4@K_ha z%nn^$VO7_vweEGV9GbMen&-znOPN%~&JDlt^ypXFc_5p5HLEgt%tJW&r@5^|8`4ul zOnHASRmzrR!q^G?`s)fxRjkLuPdv%>*EV70PxEu>78sAmVEy@#&Wno|e%b6wlEe6t~wYNcWF_%TeM`y&}4mt*POmpb}rr{E|1{ z`;3CTY&zU{H^YVvCJ;W!Bac4A+D$va%_F03VI&Q%fd{8NsiM7xKpIuX8dxkIP$L&kG~|!O0`LczF0!KAJL#I#ny014%5G zCk8#jeNVm2)pbj8>uq3xfsu?G|2hHXvVZ$3uD+rzHR@L3+nH~& zd&f@3k9m#EojWL3yAdypf0;{bRPnEJ`A5u&{!wG?rKdv^m^rC1~XbBl%cfiMwUvHHcrI2W}|pb`~!OIL6wg zm3S_9RYbAV9{So-g1p0^Ih`7usP?Sm3F<=6+UNzoSz_+tdIw}1W98Gz9Cl6rU9Yby zuJ|Zzq*yC(lp#JhZ80ufKf2cT+_UDm?RevsXuoGWMvG|^*x1U&^1L?^Zwr8nCB8zd zz3Y9en(|-{o@LiN5*zEe#umZW%1acWJ8C@R&CoL?_14 zx8xS}S_$3(PsCVFJy{Hg!~e!A`MdnTQ2ufy&{hg@qZ~c3oBEfxVBDDJICWqbBcFen z`c;!?aB)M#HbDI1B}(wZxUncZ#K*Ij@Z}eC>Dc&D4jws0(>7fgG`KHom;J_LgYKtE z+YKB!c9yharFd`JXXKwe!jsR8q3!k8(6E?`gGMVw!TB>(s(uk~e)bBdcdz5I5pU6{ zU_1PM#k11YYfy`tRm-w|%Qh~n*@V@rR&q)6 z4g^xuczV=785T(8r$s+AYt|gDZr2K|03u$5nsU)tWSu$7*cV^n#vVQC(y=ugR{zG6 z6XqhyrflVkd@yY)3YW1HCNuNv1zhszb)*+B&eJbH&W+bzOPN3cua9|}%wrLze*Ogo z=g;x%s4+CCnM&F6r6D9gLVRGCy_u^8iDNTG7s67elkd+{~n-+qUtS2dwhisG}^ z=FqflM+OcZPU%n*b`nf{>m9I)@%fjt`0}gST+*lkN-2UW%-M5CnLPC~9vL*0YSnA< z{EMUc;EQ?O*`)>leENAh^|+UpI&>xwDz3i~YNHF@5GN{`vAas+LOQ`4?W}y*J;ZPw%VQw(kg|C%nrgHPd0XNAkv-lc`a)DkGmA&v)~eaNYGC zcxd2#lrCKYv0RkIKw>77jIxo!d_qa7y#M)R(wwsl88wMj8~0E%B|z!2Rruh8SyU-u zQzkW=pl6lTkvwwp!;F9PEiNjX%!ubFF?ZIt^tz!QS~ObOxDHgQQ=boKe@8~p!PYsv z`^FnwbHmNNIPPWM`rva$j~>soDHBMx{h$gwMc&)bir}w)9}x8K7T*$>kx>>b4+ClR zsJJWLH^luK_^=S|Tkv!OUgBYG zeXKhYNXUvmFJ4r90*mbh4aPCGngl$^LgA1gl=5x8UYo@?fEo$gvSkZ@m;YYnFINHu zOz6J|DJ3dUzFIZvRW48Gra!QA%NFW2x(XGrQ94H6`5c}bJ(2Ghd`-TaPLq~hKp;kl z)KVE#tyYZ^TuxHt6vt0y;izPSDJ7{`wK~PBBvGSMNsecoqkg)Dp+Yeyy5zJB%2%yK z%@Q#(N~UpW-!9JWTtS1T?P+#RTS_C8DG|cbQE%BO|1bpzDkYijx8B00H5+kSUCfp( zTN!lsKqAo?lU{#^*3nZ(L@ZntB)M2RWlN{RsUxiU?N_=DpF*t$^+^|p)(va0Yv*Q) zSG*pTUV#eLs#2;%ItmzYZ*4BHl86upS|k@MLAg?Cgra!}Lb0;dsaPq4lG-7ff0mKY zzQ~V1EhW_sbH#N%32U=~DL04x`!boka5eLPyql0!fD;XKb)Y!SF0MjhI6#lP`;wL% zBt_?ub!;mxDWsRqphO7=EB^@VmMy3Mn5k5(S%b>OLwqsiC04KBK*UNTP^=tPs#nLt z#f|23Q8|k}yEam(#-&Jl70Q<_W%8I78CS%m?&TM;cgA80!@}lunRM*fj$lCeZRskW zd+}w?Wu4&sxopm!Jx@t*I1JX%0p;R4Q5OERmUf+Pq4AYXu$%)_uap4@+7UkaWIFFp z{Rqj;LRY$yh>M}0NiIRLQmGWzVN}>VwJTV?d?i)uG~lwUno=epbh-9w-gN_D7JGmYNYx8u!Er&H*-Bn1Klm2Z6lu&@YWC6}gTnUbU@=Xn+y2g~v{-jtG* zuU3PKp>kYSyAr2Q><87rxTwTfBLb<#C{?By>145K`A_WFb&Q*C>4WX&pkgjn>r|mw zMrCfhsWNy7QXkxoHWBa^LNK`)MODVsnO%-ur+YDb4&J zeqr^x&3yaADo_!FIRj7-3Fqcugo2LW{yCh;nU%2^J4?1}H0pZ3j?V zumT|p3(uJ*D#7(!Hd6GVCIB`nSc3Lly0Y-;SNLXbIZ}$3pBGtZ@$nx0O$FpR5R6c#xJd8C#|$FhC09b?4_C?j`{FJ>rAG^BXeqJRg_6Nm@< zn7LKrCLZY85Ckjb; zAH0Zd-vVPAW2`Hd6(D4VNYXZf##MrAA{p?(@W%L}4X2?}ph6@iC*#JlKtQ{uf3{^o zG-_CZY%`A4>eOZIbMJCRU6Yqu2$CK!2whi4v8`Zy1JueYVna(fzW(bWBp2?IrsfEi zn9L;!+HotMDZ>B$AJG%}zyDWsn+tR+Pw_~|zW^@EvqWj7imdCz-CYOlfQmB?U0|{L zFR9IcRE4q0{;$@dl(GD25$yj{wZY$)3x+abG5sHnt#1QPNQXyuec`0Xf9VUZ{FiBt z7sFTS6K5y*t^7kkobT~Juu}dm|96)7%>Pw@P|N2I19og$$*(^zWyY*o%v-*hOD}Ih zMo8gi@8$T>V}$J#v=hd46;U^Uwu2rThWNopl!I-1W_rs)D+>z)*f+=+FKj|P5_)_7TfhtYpKEeYkcK+5-ZE=QdOpNHP^GRi;8(l%X%Z#&x&d zPwCVUL0t&37?Hv-Q9?KpG{nRqi_P11ksHROH$$jcA%hy#OEY}%qpVr6mW^BYBii!F ztQ~YDpGZt_lu6x$6{K9*3|1^y$hr+X*?T;jYrA#hlgX1<{^MdknKpxEna8>0(k29) za016H5i&O|=axGjVE5rO-l0?xNKL0)xpFN2?puCcy_LO(j-!-~vJ+=gJC+BL9Kz8k z5==wcNuFz5h^aKHRIf$p1qDgrv{xmED^=PVkxZO5KX zoB8~`sa(;dp;2Oe+4Y4>0;Hr>qFd)Sj2rnF`N5J@uThr}Q3ARUH_-1M*qM5if|q^&%R5OOr0*G7Df}2`+eJV`N2ZgCnz*A=pM6g~}E~0peJKwnCJvSc$!B zm#|^=I#zDT>&B*ye<(|GQmqbZC;AaauDhCRU#%Qq6kW#x)xJT+tlxnbvD zf)@T)im${<9Lpu>!jmjtzLW#U&SUb#3NgSD7l;5cToIyxBLWgeFt2?zoVZK(-za85 z#9OBSW#iVM!)S4c{mZ3-;9v(5mL%8L>Eo6E871L*{C7&M@H{IP&1K=wD=6^Rh9AB9 z`@O2@`|;2Jg6-`0fg$nYTZ4TUvS{xoVaoG)HT@MO+9Wm5V#xLdaDUIxpg=6+j`lNb zncI0vrgvZ0^#besFkp?rA9@T~Xz?(ie%&sAm;b)y0wwUz4-xmw+hR=8k-|boj(nC^ zCQV|<$bZtTMQe(u73aG4E%<)X&)jqW!vrP5jW^uP#EFxrU9&0{sT4~uPU#X!2Gh!mIa|SGRl-83BXDwBclYVDM1=F zX~}zUO<>l?@AAapM>v;Pi0g;$BMHBX0+9eIDJAK6{k2rCQIpPHI$eMFHQa}JlQYc-l0%Kl$hOJxHb7!w!j2l0J zyn-;r%VhA@l*vf60Qx`$zmNy+xtHgjdx=6Pz~h4-V%egvd3fN%Y|1>u{rw;2$_6#K zr`PTLylge&-h7`jY3YfQoypD4qVZ)Hc?yc}rt@Xi0+mdc z>#nD2h2mV(u@%MAQ>j$BDt#X4%cv0}x%Kv5^Y_wjHmGe~I@$_>ddB-%Vj8M$M{axx9I6+O%#?zk7Sr|KX=7lTn(W1x;GCrAvpa z88VEOBw=j6W*_ryyh#L-(x_NA4ci7~rC=u&r)q^Vgp?3SEJ=-ZiOZd}QI_uR`X<0g`Q<}A@jA;*rL z!igE2n^{Y#WRx#QTF6FQsbrKXPl}}w6{1wBViYeH!cHzh<#Odn21BwPC`Orb6)Bb! zLXkx2vgJt*7>h)S;>9RYDjgL{r+oR+glwVyWlb6M$Uhh}YB(>B9!sH4;h9m-Q92p= z-qV|5&pg9{V@I$QWSu_4fdfa4Ql>S>4j(2ruK+=lpO?eogNOcu&oSlE<#^~Z9cJ&g z)pWU`J3p@2$l<-2Tz1LjO#O5YNIpw`m`|gIjVN8F0*?)Piu2jojCg7Yr83G;tKJo? zT(jM?#v9Aszoo6j7evC*D*h`mLUU~Udah`A37>qq05_V?=JgxcbL1?B@Fz;RW&Fq@;t4sq=0QO=&vFY)Xn4ZZwyZ$B%F( zw-86WAQ8@=%i{3i0~|ehf~e!*htnW2@^W)Idi(?@&z!-sJtx07~xk%R-m9D zFNed24{-R&C>@t~es1#T7@ih&WQ1e_GaWTqFAq?3A@@ev!+XwUyc5{U9+N z6}QNkXf5Jub1$u9B90@j_nvkmqO~Jhv^cISjuwe&@!m5RyKY2W(-RSK#r4KSw20$q z5$%YpBc@eaB6)mpT;>H~Bo-yyYNMT-%?BBUVZti-!Ec)d)3G1kc8#VXy`Vn!bp5eRf29W2VK-uRpe~>xipeudgE7 zjf(5U#Pwf$GiJu$5v^lI+UNJvm6&LWiZ-L8JxS2+1@|>W;??Re1+7Kvuy>^+j?R~u ze^>uLuBp?=d{nd(Hm|jaBU+;3diRP;ponAo?YRCOy~^CMXo*QoM07MJ+HvCZ>}oCA z6%i*QTATSdZH$T*$9zW$#SvFx{uqiY+6{|%y?1;Oa~#pG_WJJ)Le$7sR79fjHLk^R z{aG~ExUM$$bi$&wj?YD6-D-(MBC>h&X35UZ{==W8OP9vKo0XL%Z@u+a;`!soMBIpo zn-jUwfddC*%$PAn-q9iw71248xp9f~x~;49>C;zk>)u1= zEnX()y^#?ul9!Vu<32@}Y#aBihZDUl-4o!H+#8|9EVeOq}wu#9T*oEML|w zTOfUU+#nYmDIUtbw;|NYYYwr*0s=4JBDioN1LZs*ROD{I%T{gX%U z@AAL9_|H{(g^f z$L)7=ZL7xgyQ4d`Yt*1d_3G5DUXvO%>hSR3;fCHo1wdJGvQA}%P+l%x+cN38Y-Mn5 z%4@%}g2Yd*Vu(fk6RvG3P&P`L?^p^#mKCSOKzVsly&#u(f?}mmw#TzC{`(FnkDtr3 z{h>2$AYk&Gdg<p3IkDfxj5FQhS=+Smq0fZn*yt&3( zr^-asD&M+g*`Uo>CDu6DaoQH!Bge(89XsgB@`Wg;3%K_F2Ss^&apKJl;vj`589j6$ zS2VhUK94*{o@;wi@-g=8+C_drl$@+HoH=!xgZnah`;FJg%*mUC}k*RB$mxrA5P$!)-9=5w;oq_x`8>1*H9>+B}~q#-3%Gnmn$x5#0}l= zW!F$=0PaP z)~&k;JH`#TYvU4n-h3Sm8#ZFV;E|jz1Xm&~`s#gdyzUwEE{(O2O%4M|kns zXDCrN4ac^<$C=Qm)zyr9<8@wrZ6epTznWXRb)jXGnt$p@{ayagE`ND+uobjHk{B}L zMG7TUWW(_uxXR;h63fFC5ns)Q27(KMpo&H}T|kog2j&0&6GinJwfKJiLT|(J_8*Dy z;pfxAO2bb}Ckh-Nxa?sJq3DK_P+E(EbraEeMadv8Y?LmF1LlH|hs5`kzr7_Q0TT`) zl^7c_bPM9Ou4o8_`8+Xj;#XV5-BPq2el$t@&Ry7;*_o)F;%)X9&PBq3>DQ%-3`Zir ziecV2-?T_%PA;k>;knGjb$NKmP#zpQ5?6WX7p=LXSu=L-%LFUg8&88}bW|b&vuJi( zZ-nC`76-nnZDf-G{z~Dg) z7(5K|jwc{Ecr0w%8%5;{loz{Rv^wR_sCnTZK8m(CK^I~2QW%9x5_5Lp6kO0fEfJIz z#MNRBZd~{|o+9c~im1dL;$xFg9sgjgii}DTjoG7GDSD&dUw7eL|52^~&H*=(6w<|w z z$SI)0BtV4N;~{MZ_)O?&y6N8C7dCYyNz`{$>_)H+=6o%`KFbOem?4oSc(<@$FAMF=`a40mZ*qgZ?i6 zZOUIh_gZ@#Q93}f^6*b_R{AKhNG{*ZTSR_-)PRBE!U+4gqVfk1{UTpB?C075V08>F z`a-aDQ82;if0 zwWqL|?>H3Xo#p!lOUTI!7g1ik1}bBT6EtpIX)2OOSBmm<`FpwLZNNSg|L?Ig4$6Cw zneh`(K`E+K`j{n8@w7r<2fdU}9OhgXPh`N?aMTyqE)D4@u}E z3hX4Xg4oJSNagXjsX#iYWbd9v;kD2NwTWxhc!osZqT|V(pP|DQms2N?^X2EC6Vo1I zS~S}74;ucQ$Jn@j9lH;m`h901u6p|E_`GQs$FuI?39P>08h-;dWd9~Big_al5<*-_ zD4a^6v`Z4M7a-(~i^q#59zm_vjyI-$B%-=-x|KO(BtG|N-SRBL{wYQOPNBoss4LAx`--`#z+`{1h!vp@He>MT zmnb<|2UxgpIW-$L=l$uknfk`_6bopBxm89!mF-2y1k!1H-EF-0?qoV&*M>CLCB1lc zUV3c`FOL~Ttx9E0Ab=7>NUSxu8doJ#q4s6G`p(--dv83Ik|Rw0@Dn!g+|8P`yXbu9 zKlozKbjFPsz~Oy+SifNdB`a3OwUZH2xb5a{TzN?Y&@n`Vr4`z75S7mDcR$2??~J2W zvql6Q2TNQ+ z_cPhL_c&Il1hH6{WGP_oH{VkD`^cF8Xc3fh%z9ETt5z=IuDkD~*FE>Lh$%WR~XWwiVoY$L$H4N?`u}9T8nmKy!zrWM!xV0 zVZd>{O;#0fc+YyC8aa-v^AVqT-rL~4Q>Q*p=9W$DK9)r!p}Co&{eTbOzT#7KD735b z4Lym?S&&#BD}I{K!Bg2@#HovxL~^IN66RTpT=6mj#0q$<|NYFK_YDPr5^WS)rEtCc z!T_#YRPk|%MbEHw`6^DH^GI3as-{tF#3wfu5(>3axXMpv=D8XXZ%A}pX%OYliG`(H z6I1KB1`6QO{Af>2Hc^I}faS7h=MLU{?R5&m5i&Qfq;A!+Y}vCfuFQdp#Ln>Hhwrg$ z%N}B4-gCWZPdqC?*2%prTf2cmyr|&9W88Z4_58eMlaZk!LMjL`Cl()Ke*wmG8z|fJ zz-vz-(%348pT7T+9``)VnVbSMr{48uFV?F4WLp)CuvCZGi+0c_#?@g8^764&8Wk#3B`IiAEG>xEnu5YY?4X6%3b7Ss%a$Zb zITYmQB5=Vm0#PVslN<;T3!lf)LNw+Q444#WwQAL-PMx|W2aEH_19y;r>=0AldWZA* z7S~+chC}OrWWYnuP@vMeyU(4JD-}Sri^jlS0+uH$whaLrM>H|<;0t1rbut?(m_p@? zE~egPm(%yb2N-z&U8EKxH00r6*@P5t_pF?7fi3?BRljW4NB*|Z>q1vy|@gu^jH zp(L!J@lu#afkPzsG(CDfMp~)rJkq~6DFMZSy?a@(U>So3+)KsM)%fb0pLy=d7udOd z4Ih2-DeZ52m=|7tjj6AVVb+xAIDG67g(`{U)MAt^SB5K^HY5<#965Q$xWl!^(hg`p z65p&ACnuMWKmMG~H+Ci^CG@uy@V|Na%jaLTHuxQh0vfRmle?o8O1UV@K@%{_fyA(t zYw|Q=K_H01FGUR}mr6vpiP9huP!UwXGVm_TSj5+)ItSx^GlBCOgA4L+B*ua!4%)U12cVa<)?5_@%OnVL1Y_oM3(?}BEk&z#ZMo*! z_6QKLeQTS8*g;|{$vdq@J(b0vw?q^;1-v<7EbBIGinm$&oQO){icbmZVi5x!1yNXb z&>N>jDk=fOIaxgNkNeoYXAcp;Q2~@P*&+PQyNDTUS3p}fE(Uwpz56X(T)zPUG=kxw z)8dVzQi#&nw#m`#WvAkN_HkZ(VHD@`3UQRln(QJdj2sy19*mN&Vj%fwiF*8bmifNV ztg0NeZF`vx{FyQnj{;o&q8+zb;wCN0Z+HotO(G2Cjnu zj4(U8{2~m!~n-qhR(zSq!3qJTuinBOKBrpVww67V?9JJu+kfC(m_cC<;ju8 zB8G)n0Yn@Ewu_P|Hi|GNmq8#Ym9976OoNN-6Z2YR*&a=X0?mAW>N@P@{Me8fsxotUbjDMaP^A=MeihvEcE@*SG!S(X<`f`fN24U8y zfBY)y!4SmKU}=;tBq!?-Uwtv1*WUh^T_`2)5d zhha}W#`<3uGUfG8IezpY{U3OM`}+^#bWVf@ty|LQvTFP=?^`lz)}U4UHiQeZ2~bEz zsgk&a5IY4|D}uI7a!M*2SFd5s=1gkUtBd5H0UI}v$~9eXqD%_poH$73 z3Kb|`x-!jMwIcYZ0-Y3y<#Em`N|mWVlP1k*)ubg=%9f`~yGH!7@Ei6YIL;4?H&CxZ zL&_$*Y*?{`rEAwy7>n@c#IdB8EWy2fdXt-Tj$k6CPv&-Z?p#Bc>pJk{ zh+)*NSC?=kpX{@TICb(A=W}z>fn*$&%H3J(HTeYE6 zr!IUwcL6aSpfKk0+wzsDSd2q^x6!B1T{Laen(Mn>&%7UgHXF5$lDTyYcinXlEn2nV z<{rIS^2>6s)d@eP;IebW3VL?y!hw^g5sZ6mvl+{cdHyAdmd zPx`BY%w4<5+_i@g!s%oC81P^}I<)V|b1#lVdzQ%K2Y1o4`;D|}(UhUXN04>C5bOZ4 z{Bw*LGK{O6U&F_re2j7nm_BV9*LAv%?zi?}#hOikLw43t20i>JEnBqap8M|O+wbSn zvCFOO*?&B4^-tV@sr-cjpT7(?>lJLyafXW zJi&oOC(tU1O&hjw`uI@-IPA^b%D{dPa80`oy!rYRA|klrkaOk;!-o!`ZM#nNx&I%; za_F~S0}wftJW>KuWx^L?>P*>=Jjj1zjrU%wr;@_Pdv)P zMT>a)+41Cuqr}2tCX9KW8FS_lHL4BqoCg|Sc={>6U-$zKinCcq>2==&Y}~n@uV#Hl zrw;9CcTIbyefk-$VcrAp>fGEs=FXW%ettd>W8Ul;bh*AWw{^XlHS0EFSrCgxnK*U~ zty;99=WRV%wrV3-sn`mZ{_q2Bn{;I0fX9hAuyXY}&SxIDq_Y43AOJ~3K~$e7Ai~;J z%jkJq4?1=1#OGhmAqo`aW-<1~(R8}5Ggr51!;mLOarS(~bAkF)+5U!Wb2j@NYgesA zyI~g2o5_tgbftN-X581eKU;SnB&J=I8{>zC-*RP>D|z_Q$BAjp)(z{pulHTFZ+|Tx ze>#Ig$K_o18OA<0jCO6?a^uZ6Fn#6>Zom6MPG#oJiU8f!{_h6!Ale0r9$=ERLm%bh_Pvh zh+(ojXaW*8im4SOYFVJd9uUIML7uP-8?=CnB|`3*6HJ`&3R6Cs!|nZ^=+t1sLsY;e`eUQQ9L*94H`FZNspVaBj%V~#mbFPvO*Oe z>VFSA*Dhl4pke&HY%@_i%|Hos8g(ve$k=g1Ik{&YqhAkd5B?+)h8`i%bl9wMSrs9m!rB}$aw&fa&ClXH$$D>icX zef{X&y%RG&`k2WdeM7DK7g45CW$HF;%sZ1_;Pk;A41N3w#=bm>oqG=b3Dh?i2nC{4 zk)S?huqUpC5TMunw-e4g!;Lrg;Fop#dGwKgknB1vm@}QPzyFa_=g+fr=^BL@XOtm5*``>U!VaW!U!Okg+V~rtJGA4ekuPxfz@gNv zb`cNU-Glm7Qn|fn4_`V%aNI%OqDj5 zH;^Sum&wOdUXfV z#St?4&Cev}II?cd3fZ(_oxJeWLvsH^gXEm!$SWg;$lD)HlRP&nZ@loR3?KJ~9M8#? z2k*X7dfwYtep)hLUK;VR)VlOq*>m)~gmccwZ_5_T`eolpmup+dOK*QHvBIM=@ZN4R z=Ka~SZqH#kmwiw^nLJt=Ue#V^&YLfeA z-+qt|U3$o_{U_oSBau_Pq;ZXs^8QzgWaGY5QgA*?-XHUX+;LAoS+s7iY}(;3J1uwKew)1U<{R?c&x_^8Yud_;A6H6N zPL}lT*-?7-eL%kdWu^SMaGsnx^s8Lm@j98e;-Ku>dq5%uhveNiUzF=^zFn3sT`Dh( zd{(-2x=FI~bL8VsKbH2bTFcVqzsSaIt7XrDOzC*zZF2C~3CTWlTJG-FMb>8Sl0wm< zB`o3-leiK2Wa3B}^2~FRCtB7l{Ysj4=qd;EMfUH_ly&Qt%U3f$mn$!AC|eF5m!FsX zB3CzVB4-KsBG+EiMkc=h zxqLhKD{0!MqkJ)Uv79`zS*~o}Qr@06TNW<(R$4S~D^HJnNeW%UWHd49+M>G$|3S+VjrdHnG~a%Z21MC%;+{FAA2d(S?yckg~Vc67hwoIN33 zI(L%~-v3yBUc5*;wQD0wH*AxgyLU;pxlZj~O zth_z?AJY552jz$5t7Y`FBcx>IOJwb~9a5NoL~ibKlMH?88CkykH@WAQuJY{5Z%9r! zEYA$MUuG{{DBBP0mm52@lezPMka_dwNb9DT%Y^s7l4#*+>CvH~44*JXHtatw**OJL zlticKpNZEOlC4CeQQ5L(%m0ufMnvTF>C^JoTW^`Fw4pQ+9roxRf)UY&(2H zV&3;7BI4?ph+Amx<7$cd^gV9OP^IVut&Afg;ugl~d?XeY9rMRY#MO?tZdAneXs$%Z z`{X!oQ8F449X0pSuA!3>SH#VeJ-au`w(Z+x>-HV8b^8w4vOQA{o<1WHEgr3tPc7vM zu_Q=t424Qm#G{gO;PfKzdSnFfVec4#HduY8m(G4p;L=XII;IQ>({NN z-OV@Rps>V2J1*OI?`6xD)nsMm6U{csw6z_ga?J)bZ*diM%BM2z-8b2L=onfhQKD2i z8aHji)y=E0VDT>;J9(P=l@*p2&snI+s8EGQjW4BX?IfnnUdFC1+c~#;F*WKpV$hIB z$*?sws#L%@Ed8SJqhtfc)4Bfo>sY;d3)eTU!P>R!=ryD}mX2_E?=IGE*~z(+$2pRl zOraLUoXY@{)?ER|PM+rQ(X&jM{Tby;3KdIQyuWZaN;yO$Ijq~bjZ+7=lAMypv6H!I zY_wQZs91`IwX2}c9cJ#V**x&*NUpn~GwIGX?A?;d`pv6o)T|Z7%U0#e#*HaiA_+@r z7Jkw9pwZaYtDOaH^b!wI+#mz;bse4gFnp|0n;%KDc47;{(W&6(kxUqbW96LdQ z>l(nZ6ms2q=wHm`k-{uy5}+ zDpaaL)GkS_s#QFPq`{RLD5pcCW|uMJ)vw5j3R^eq;OdsGD3$DTIQujU7cSz=sWU_h z3dr1hgpvk=hr-1c6Sm?=gwJQrr&E_+^y+mxA&${_{&Fk@mRrctBL`W!Y(3|W@8Q_- zLLypFT9J}koEkOLDXD{~f^(j$2-f_(oEkOj(zDksR0svwxBn#Xy*ie5AHRrBD#oQ( zwWDSIlH?pc$&ByjlM{^+N;a8U{OD^CY)jC#jo1zJFr*hY0Bi*R{Ba zt(%u|Nt26Nci=S7+}VI&ERS6~cCl^SYEGR#N4^sVFG^ma2qvfS%riqh%%dk=Ue<#u zbuQ+L7FW@}aYI&b*u%1gU*R;V!_H%8nfTrl)T)?*{ZMb7d}Sv059|jbIF7eQ?GRVB zYDL*Jm+h;6WcjL94CvJsaiL^JX{y!8AYF`8I-b`X_&rqC$G~0?W&b}}e0Q+Hrz-GL z>7o3dDlZjY(4(&rV--|>K4H)#8Em14l{|Mgi$M7(V|ny3wcb2i%CE0zq`6ll5j*wQmIPfF9>YXY$G_j#c;;S}6n{7VyQt|> znUsjOFXO)FLjA5@Wqa27-`@}XQ7*d4t0IH_w=4MX0{)U`eSI|0ij zEhU5#bwLLcp!GN?9fF}CX~7`6AfJN#JStSKL@0=f)^nXAE7MW-{+FLIdGZH5^7Kd|XDV~xyS0daS-c2Ji^<3kNFgOT8H+G>z;K;O zB%A*I?u4?JGq~R!6h`L|_PGB7b|Ajt#-dU3@(Rc(SI$(cH5tW|C@jn;tN}adMT7c} z1_z5kkq3>SU5zUSs?Pt%-g$>fQLJtMSKU1`n={KUEU;`KEICRN5LC>FS=#~=T6 zDM?9Q#*e>(xa_u6mu|)5OCl{LB@%asFl@J%=5X#=7LCn*;u7PL0utlBB*tqTI$Td! zX#~xvE7a@tF|uC~UwpiXUL(&UtFRXdJ|Bj|+ZS6Mpnd0J2sg4}%??(tFXOz+ucH3o zLGHX|A}5}A5km(JX6>p~giVF=I0+chR)Qv}YYNh-V_Q2($O_wWfJ(7_?Mm*OF@x); z-cMqvh&6jZjPRMc{Csv+YxMU+HT5JXCgIf$gwRM&Nuud+1y(2kngR(kkr*wQc%>9i!Zy3 z1fSyKE3YKIO-HP{Lui^|C+{c?P187c%mAKy`#p*V45d*^rb9s<@4fac^A;^*%B1Va z*tUn|D>p>KA_Nu^TY-cXc!ayY>^j#9-A;Y*dT5)SL8!To+PcGtxOfthQ$U3AC3*>% zCjPKf$;z}hJWbb8LL%{#k>;gkXA`CrXqrGshka0)POPi$BoW)IS~_uSIua#>!?WhZ z4gQ-|L}EDxU2+{Fdc>(FqTKk%Uq&B7Kw4%tufO#^Qfj!Hx{}y2(uP4mD&jp}q;x@< zw7E9jcx2&53Oi8)e?xh5Q|fYd{bZ~r1JI3pRlCOz$tLj zTfAPI4^@wb^8804Vw>VB?jwO7f=Ca3{@wqEDBO7WqtNQ8{J$l?I|!6EoJPEId_P@#52i~=FY4<;tov~@9t?D06C6v4P28(H z#JPqSB{U4D7ON1p1rQ}|3J2_cz|b6mXQiVX_L;b_QzvH6f0lLYHd2t8O4Xr8I%z&4 zic{byJ_V$Z->HODS5Gmv~TkJc8=#YQmOH zMWSm4Ijz!3O@vq8c!SeV9709KVF;TL3bA)j8E2nyJ^7uBDJp8ux`P4GG?G%1*t2sN zRh1B~C{7tp6u8)Q=z-)`N_<*B!I9)NYIr@b@hI}{%$LyMvf#iB>{xO z8>f?;634bJTj|sx7nNvXDTNf8lhtgpqqK_dy$4g$tvjl|lGUZvHeAvLVG&1Rm!5dE zFtzoSv@hz56$p@%ok~);6`Iw^g16sg)QI7DLw=IHaU{k0So`hQWDY8%Rf3@Jz(K5B z`Yl6>+q3bfAF1|x7}UQv-!5B;t_wV_Le~WSj~m9k8z!@}S~7IZnV@SCcpD9~@{p32 z$0@`6^7!-{NX+g+L2)60!w12e$;in@C*7aoXtq zEO`B|j2b(ff-H+>e+U#*?5!j(znE_QdK22eiNrYjIGvE1%-;Q_l$ReQ(`%8JYMW*R zFmOnJ-v06%)^FNIL8``*Wy={o_9Ap&62decf@c?m{w=eia4CpPiLP{n((r0_;*NbJ%eNU-^v2hI%^m=td|MASW%Es@g*in36V8IFfeV zJJIrNEf3v(FJsQXgyfV2%F4?r>OGi}o_%NzTKu$X3kVOIE~q+KiWTa`j~h1QO-QCs z*J2_IOj=Zyl~K93oV_)>_;S?-jz4WOz58__UVnq7Uwy{#0o_=!^anZ>6_AktLTDI< zt&XIVhovjwkjY3iuR%tu9CmHlMCE~FN!CN8BzpL2`FeWv?n}GY>C_zD!{%N4={0Z& z$(qTk)oV#<)t0V>9RPun7M5x9uSiu@m0bo;X%6s+X3$5WpooApTUWRdY0f)UvEQ(D zfJ@aQoGfrR87&a`mJ2rBL!@#Jb?)C?tA6w+cl@JkBKCkIh|mtW7Dhzm8NV)$%}qHe zL;|D;+pIv!rnyorEd(4$92=q;3sTj;0Kml&BOF~3$~|A<9^UM$k33~Zp8iii@86N; z=4O;qR8>_u{j~f3&vQ|VU;Zu9dN3Jdy>n4ZCuY4`BxQ!lXS)hB2Q zh8cU&4G59QX=j|tZ8K)^@%&e~`tl37?$$fG@1Z$deaRm|=$!M1KhdwxKq?L#Ko?lBw90A6voAbFZeBZXyK5Tv&7R8( zbLWzskX-OwDTkmfU(KZAmz0-k#E1+MwSSb~5q73ZCIHg#3yOuGJZq(4YdOXA$r1bX)y zLj2;7xa7hMh%^0ovhwk2f|5SR&?fyuE<5i6diO5jsfQ*KRyJEAOPP}sc(Pt1A*%QCTWsd@msq_-}j zYp-Ki{>r$V)7l2Fm~)>!oo-2enSyjB7+AH}A5VHBJaFet%z5H}nDsy%C0$CmW%5+wC4`ki znHF9Fx<>;mjM6+wdMCfr`d-JVaee*qBwDKFyIqM|OKYcV)?wH2?56&d-_yKHL zw}zR|zRnZR_rl`~GxwQi={@vh2L%3mvfzycwzop+NC8rl2uy_1Y?>X-$(L0Eg<(?{ zIvY4j!>xI1!!HN6Nej#2c{HTM;pPBA-K9!$66A!EXi`OZMO_?V6F1r4v9s!(KS~=G zDj}WhUE6jjG0>GnQ>LA9?NoTt9Ntp*77zt&_WwrYFfEWs%_hXsAX3Rlh=_C9P0@1h zCnERzmq4Jyaq24HSdi<2KucPYXGj;^67}|oNNJ+Km4BrzzurcH-|uI^f(4QL#a8M0 z=j2GMp}ohro+rz;hC9`3Y!Lsy2m+NtN{MNjv}xPsf9*L(<^Mhr>bF=C|AHuh@F5<* zZz?MfB=PKXvq=O(*oahD60880ZpXoBW+Or*V(Esh&Qusp*!07i0;~{d5YoID%27<3 zLWS#4o&-#Mc*2b+&5Nn|@S1)s-HWN|_^cpO_hKrAZZ!}H1~G(=-|}$YCD(KAxKp|O zkK@pUCnn&?#Etq9Rue%j5h*mhQlhIC(7c#ZL)Q($*veX00W9IeRN%7$g!MR-0D~5U zWg)aA+l?h`H=9lnTXAbxcnK?r6QHReNQp(fortJ{=!8(xi>dptX+=Y52rOk2EJFxX zh%iZZb|PT!6anXNafI=r34v}kVd;s4(eR-lP>=8>fHZ7yEfk?}h^w!@p0odOJ|~SC zjh7Jiw&RNwr1xOjG&M*RahPt2GZjV?f{-#$8u*YP1NN9PP~nh1akUW{{AP zih)GO1f?*A7ZZphfQe1!ZeUZ>Si(mbgE#_M7=$sLHbW>FV9VBRbm;KQpm4*64IF#y zu>jQ6)Ua^jLaw>ynkbmTg%zfKN2P&qVUO)vRn9@twyM}=7zJ)6BnNCMB33=uff{l1 zy6QLO_8*YAJrSx4o+ zFUl#p@ZERc{r;9f0Vp8|Svt}IE&yKVgon^Tk8^+k2t66l(3KnT8x4X*;BW`pl}Dn7 zKY{S1B5+)0Mj`@XZosLI~$Lq!mX&Mj@2n=0wz>wRVI2#NKzySt!9GegHs6w+}h6XkS zv-|CQ&-T7}5t@qpE`%5GAaoIVk#>)rXSpLI3_M3@8n>-B(2h(3EfGy=_=KZ$;!p&MbmAH%T5RyT5Dw9|4ZDN@q^%fiE4coGDHEOeQO7BT5gpW zR}?5|TcA)VY2wv94mr3T7i{Bt8&Jd<9(!~RuM=jk;U*F22xr`Vk>Yv+9Ynk{)dsx;u1jr1926kawehel+&=J!mz0!o#|ml=aKseXU<4>n4Nn{CsI*!_xR|j90>v< z^&4fxW1Znqs~ z#we~6kzf9C5{`2E6a&##B4v zjDaq(Sc2+KzUUmgB5l~n{ zBQqlda9n4xqjQ91g_s=zJBPzba%ZHKhTrY?k={-l9!fKW#)54*`) zbgbQWDCNur+rR^McB^HD@EG36UZ!n0*r)&iAOJ~3K~#&MZD6kG@%-_++pvrzd=7qy z00!X}^b-yrsPp}p5)}4(H=`e_sB6$}bLsv zdQ9bW#|?|JJ1sG5uk*^lI|}OUDxdDOzz=30?uMAdXYK#OZKS0D^?WCVThS(Y9?aUXT8(_lQUo1N`dK zz%ET^xmKOXw%~5h8itWfPEJy!)~u%4r`?Rq)^@;pj7tV*@&7Wga-Zo~6oA^w3M`M0 z^vn!Av8UF^W)Q**huB-uNZZ^Tyt?+YTRGKMh3=5H{sxLdxt4+0cK^Cq3gVMeX`7r1 zN;y>oe&u`aKIJ|J74g_aH;{j>2TB;Erne$B-Tj_pnMz2eU1Cb)K1wMpDbY2}jzRi| zN?+k`Zf5_1eRM4990`+;x?ezGfoh?qrU5-6gY?Asm_9gk7|NYbE~u6u>_7l30@?qb zIG`Viz#uiPH7Ti%g(s3QV&ZSEXWyYFI^?y%tBJq4gI$wa|Ji2ef>!slsP!STzgh}( z;keVW-NV>bJ*p~e2pfsCX_bLtctF|pa)tJH##R_4rRE@F%$~x59LlL8{Wp*}_D31! zaLoZ~gK^}w%e5_<{08&=Kaf~j4S|Kfb`OuteVvh~UcjJE*{s>Po!tClI^?9$SXag7 zZQE%GSY)+nN7tePD$BOBySxJBNuWp19%LjZII({=;)xDtbbd>>w4wy1Dcj}vi+V1a zkf2bQ%~h=4u${c39^_>v6AXqig@<^rK*uD|aG13l_tL&gS5h-loG=p=W0`Z}+N83R z>8uz#qEIMlw?+GV>;Gq?7x~H21yQXN1}SL@X?Wv&HvLUR@400Ig?%Ux76H@1Qj!F( z$I&hBBo?tK@Mlj}5%_3t6~E0)asj=&{Rrh80Niu2!&+cpXX^^f0qge8Vq!UVY#kdo zM)k4wU!Ctq<^M1F-SgQaLCk>Ag>#B^kFo)p>MNLj_hZ!7HbzfVV6SuGS^|Ey3C8+e zelAK;QMR2~vu07(*c5R;+m1Lpw$EL=if9d5=aG?&MYqVkQ&E^`!Ma}(d#MYdfs}kO zZyq0iwuBbT;@w3Hc;n4?BZbcFwI5{P?k(JK>vXDXo9&p!Bl=(i#mWQwsH|`N4H(`P zSbj=(Y^0{q??klyo$laRK^%?u;?vKu>ibnk1cCq3BVvD%;U;$M+)az=xVV01Px!@K z2oPG#5m`ld2_ald5fRIW;bsgA*Y@%&)51pHY~HYrDHCs|F%+b%Y!5eGe;wr&)tK%z z%C6b`($i0|eAN~Jzd%60EXOhyORgbQn5L#0c9oVB!m&UG8+r86huOHZEb@-U&pPS` zkw<}^yFJ)zLK87tjI3kFh85iVm#1k8{8DzS9b377e>t^Hfk-FaEhzc~C!oPDqHJFl z3+MzWT_LnE$~?pyFF(z~556R%oVEx%hA=wlzbvr;kjN(Z^G(`WLoonI07{1W@U7Q* z@bQ;va=s~l_RZg0l(J{5R1z>bynhpq&3=sS<&~6g`H}O-oyDBz7t+#L#iRG%#Tloa z&e`Xm%abp>$mVUEx%>|oF>dUsTz>7XtlhKEVG4CU98T@+h)=+twbBLinp-E@X@jE( zl~f36p{cO_Hz$jH>knUW_8Dh0@2w?N9xUaWtFPvhuYSN(AZ37c-!0|LQ^)bv;;$lf zH^Pl+#jdUG6s@s8(KOKPcx8lgsC$TLL9nYWDJ3zF$bvpnBF|EmGoCss9N>`|w{i27 z=~UL#+jCP{M5Aq8y=1Xr^$PxY$(4NY@fS#?P%a&zl5VMY9PAqN#Apxg$*qpuQ~qsn z0G~Ss$^seWK-n%HedHl78$X^~Cf~*vOTQ!J)NS6pc>}Ybo`*jeLYYCn{`@m;nmn0` z!?kvsmBKC_=@yVYDo5q_k>4EzYOeZlHWqn=YL^HkhYr`-MdE)o8|q(KBnm8xs;Vl& zj%6+uOh}?Z+L5hIz>ynQg#H0Xm-J<+YUv@ z-^9++QUX?Nww{X~BudpYQh}6zx9XR0EG6y*O1Q=MV&2seW+E5LyMO() z_9+mOK+w;jLp4|^%y5YE(%mRaMgf}wgvGuC2dHTZAY&-oB8`$EmVUT^yC0ZIv#{A1 z5l~rKNjMyGJMs@k$%@?AzN>Wl=~xF;m~e9)HT8{HzhvQ5CT7b49=P`&zWjbWrik9l zR1R&2jE;<3^E7%2an5Ct4OjqS8fze2u4`H0Bo-+J(gY=u z%FQtaq=i%xX-bem>S_;CTVEG>wOaJf(Q*GhMM{uO$WSBx<{*uY3d?b`x9L>Ojgu#F z(FNynV9yrbeSZmqMvY_do_#!Z|DAll6GjG77)3^vl#(o91jh(GLb5(-Hu)QG>imOwCwr3Bpu4B)1T*KqQf zL8!(GK6>wMc9&JqzAsc*36U%HS5NO07 zXraEvPm5&|M&JCP(gyhI{f|?{J{XtAsZA`lyBv|_ugc8St(6^Kh35^ z$O_~4H)BeP3^&u#c$gM5Yy;A80KdP5mKHzZaM;mBf5%wxFNzJy9r9+)qWR!1&OP^B zzTa_>lgEvtRlLQY#-70AFU}{dLR44mX8E^ku!7BOUcZJr?|Xs^FT0ZTjC99aB4Yj> zm80_e$?xtCRtSXjQ@Udd->lk9LsJXsDX9z`Hj;vNakc`I76=FgoA~n6kJ)#il8l`8 z3?Dt3tP~HWyLR%!%C*!rG?0*<#mLbo(l$GV>iv6I@y#-->iu}U2@D!Clun(BNY6}U z_=uqxJ|Fefd-?L~WgI-zL}HwezC%aSskj3^735HLHD7(bf|}X}d`W2x8#;u-{JdyJ zt)3O*b`Z#j4G9y`Ix(2;_ z6jN_xW1;ZZRq^GrZ>g#%Bh=D@r93F9XsWB?{l%Zq*wje7{9*To453E8`0!Ke z%l9yBP;dJ7>B`zQ8(Ft*9fmJ~!NW(BpO-LoKh|TNQarVi_V_5ZkvvM6ZjX}C~FJZ*MuDti|dsH3rlbxH-u;D|< zN=;_K;A69;Nn-x?ZYNSJcI|@2=VMl2d zqecuOPK5Yw+1L15=hMAg7km!j5yA$QOP72`>w;p6iVF!hRq)Qo-!bC2(KH_1&We?* zKu@Aq-vRXQ-4!$qQ-ZGPWM!r?_ViPTOG!lFXZwatEdOy0K58kitfdzM%?hz%`7$(Z7E`FD)ii0F)WHV&+N#teN$w{VkDM*f7$C{F~G#}!NC10?wqL!St?HPXD z2vU<1A=tq8-~Ys>t)(O+Cv(PGr;?y4)~x!Tbz8S#B&0L$^fO5C1X=y#IyP=X||Sy)(h*0kBonzftRuwerpUpzxbjiFuZ%wJYqF>Q>x9RI^jRapr9to?2& zw@#hGs`Wd_PPAwVYA91tTUo_pkNkz8FNbl1GYEz)KKkejI(F#D-IK4x3`0$0h+#uV zke6S~yw_f$f0shsSUB5?DTA6(8oy_y5YYhvu?n z+iqIr4PWJ9UNM`GH%zo@~x@R@>&_gpxY(Idr`Xr*sFn3M7 zm02^UF=zHIbSrAZ{r5jWPPZ=PWDe!IxpR1A&QsJiw9vhz2iM{LwkQ^X_7#9!Ixc!&vn4gJ?*0@7%%2!N=2~eL9QYoXd^Z-@uw5)}d)$ z`W!o!ryjo>9fcLLxaW@PJUsnQ9((3_!ZoE#y5SZc|LY=7=-ZAy{RVONga?>)`(;eN zaRP6BvI?O*oN?BfJoNB%k`p|(HBkIEwhy5MC<~T1o-@;4|se2 zA~Xey-~Wg|{OJm6{b7DszLZ%H+)c;~uzt-dZn$|eyY^KOI9$QY&%a20v!BwlRS^UYDPBtXOMuGUuMrJ-Rou9Vt zLeavfpS;hP-)%%G3$yt!iHSZw{P2AqoBKRLWhb9#3WSs_`{X@7Ub37(FvydS-p^ki zeTWvnpP$xk#0+CU!D_+`HeskRci(qE3qJY^DGW4BGSV{1%;`u%VjSOmzL;ySoj}>X z{Ve}>ITLQ2%Kn4C#X!m`Q|I;Jo+doLCEye9Bk(Cxvz1!z7cumZbjRerDV;nd-VaHg8zN zRhRvV9Xob#sOm5~_w2P};ZzvQUrT~VXVuD;-2KpOT7-_!bdnN1WaSo-oYfXAKQBM` z9HsjX(o$Q+;EV6U)WDLYXQh*!(~hJBovj_<2wTW- z6SAd&)Wk$yedRS?c>NuM(&D{0Ugpj_?x40gKy_^c5M=QOi@0sdRB9V+i)PSLeEa1G zJoM0gSVHI1k3V7Zw1)|59&kc1bQNOxlDC+6^9?jM)UkBgGA7?Wi^Gk_sW~iI^d`66at#Y!dV$y8{)j!LyZOsK zkI*9Hc>jZU7~Hdf*|X;I)0(xs_4a%YRyFX_tMi$^U_O2O_d-d#>WUJYZHd)%ZkT!- zUwruvC!RPGLIFIwj<8zTv3VUcAAXDxC!NjPi{3;J)-Y+}RLb@qpla`K{2?!Mo_vyr zr%&Rew?5#y(18peI)J8{ zeaxT#CVd7D8twDiGUtDu;l1}h;M%J%<*Toj z^1)|c+hpllJQHr7%-1Wv;q((n;~-}U0YI>0DFq=~nh*2-*J~L%VhpMAKATQQH#m0m@uX`yHKnB}X|nperA)Z- zHm<&DGAEok94|KIl5lfKV#5TE%2D~9H?IqXbJi0&}{&hUvmXXS6{{ze;Chq zE0!_rq%l~+=1uX%CD8BKku=oRQX5QS>8c+=jmB>Zy7fPv%dfhclSU5Yn4!nAt#mJq z0fUUJ4qS2NmBe$Hv(CGgZF~2Vn`_|4A1NzLn~q(%2st0rGdAG26%_f@me8HhW z0Htp5IchF^385J&GJBdDvd zCruCY(&F#&TXuG-a(~|(GD?b||@Y)tB1OrBl;MhTZNH?1ZwlveD-*H@a*;%Bb5aC*m89Iul z7Ks-2^Yw;}G?^w+fv)P=e_#hcZr#V!yDld+HJ)wjf8@3K?~?k*llXYaa$bDzW7@ZC zhsO+a_`oW3Pa307JDXm)3N2K@yl0-{+^Z*X$+(jkw|fg0oqrDBt+|L=D}h$|UAg+Y zKVzvN{-y>}R0Vqv?8cv-MQu2dzTHcR!?6ImR$38e$g#b7c;1(o61HyIO|Jp{$jFEz ztGFB9lr|I;H}cizAG2}W9#WiaXuDRcL!7HZJoEA*ih2%b#y$7o(QDXNb{JhKG~uIb z&px!ut0yZxk%wRSke~vDMs{8?W5*s#nzAsOciUDw1glnj5AiA7aOZ7gCqP(QJTh$x zPyNrGG@EgZJ?}~ec5h9Jk-(BA?{oei$CB>x;ElMmh2uI@NMTnBiBCwR|FEGn`x_Zn z-N5<{+c|G^0T^)%9CiX{99M+bs^s$X##7K^C<8}~qI35Kra$-?)r}R@DM4H_*_0 zCX3$voVy?S3j+oZ#fLD8|XnTdiMraetn z<&9uT;&czHxsiEK%w@=^QyDyRB>jgT!-Ofb*>_++*@tl~_mSGV16{gy#;~d}!WQT$bnf1h zoD@%F!&h!*nWg{}p=D%#q_8zF=^a6qdk*g|UdH9)$8+wb*K+-YKa(JplU1vbDvUyq)xJH&oeDAJA*zG{7R2iz zwrp8Xb&JmUn{Q!2aVEzO@6YO2zGGKeIS7FsmrVQOdFtP+3(&5QqB69ePbi zXvqv8c`PR$+nMJVujh)X*HT=ZgHOUEGiQScION!G1j%k6hhC$n7+KBC#&|CtEDz|sT=iBP6fnaW))ZYYP7B&L}t zLy*kdKFE6KT`ORcx_0a znWU%269|QgPJD+Jav#M#`q)P^X<=ZYtPpN)nVT$v5D0G^ zXPtLGuPNsn zBu-E$i@Z(+_#5A*bWb%utl7zFCy$}Au9n$%-%D7<(<(WRrkZk0(?S_IV8OQ53Z)^H zG7B%0Vx$F?OOB6*R_PCiG|03f37oAv$Hi-7)`eD>dP=)isdap*0p@D0_`n>_1Emn>f%AB+(2p{*ntw@L8bggiMJ)7^3D-Gxep_ zy#2w~cw{5zoH2%0=_xTzGvUVkM=6G!F^F!f|A`2^@d>0Q3975hs6KdrR2(a*W+!!6 z%0f!ZiGvh`OzGqeC=8*YX+D%@>pX9yZH}!{$_T{@W(yu=Qh&IPhQKy-FfVVd3^uvDrU}pmTSjfNykM` z;PrS32U-ZWG=ofL>F1yFFufwCR6FDPNo!?*L?)3bT__9;9(doGz7i4K|hQ8(~W z`R~Z@9~0sCB5cLtrh6f$+%{T$r|3SCD9LkPf^ltyMw zHk;S}$eAY%MM=e$^8NHVX&Ac1A-u)rs*@osEgmVf$P4#+JqRSh#(L)+cx<35EH^)q zS6_aC5vPpf$_Y2K=F1Ow^6e#fluaEWg@@K{I*^r~%C*;ANls2{bReuj`R4Wbn;Y0y zUQSU#KEm)Id?|Q50;}OLs&yJ#LK2zT+0^W-zyS8wHL}0HnNCGTY+Sn|vW06xM`(g! zqXskmfjLw+#M7luUxd&RQaYS$P6C32oHqIN?$VBzo|wsj%0{m2(UZpNGWPB*3O+#2Fm_d|gU`gB3>(M=QDs0Q9bw3aaS@=A0ge?h{#fBfhAtgPFsdwK) z^WL?rzJ0Du!{_l5Y;Ld*8A3aPrKPxYCq7!f9Mj)|Owie~vyA*sB?t!;TS7x1@dyiD zS&^g^+o`8Hq}m1u9ghlNgz9+rowqpq&(rwB>BsQOYj3l4PYXi#V(5x+Q!Ppg@Fr2v ztrxzIotb>wB$9QTl)|G`LUO9VzUl-NNUxNKV3SGnl3Bn<(r%h5>y)vAG!l03ZNKL_t(~aQiJ2S^U*%l6;C_OS2743}1xi$d{f& ze!I5JnlXii&(37>t$(6l&u(@ilon5~o?YqRvlBO8dJ(s$q~bqR!>IGGqen?0pDNAa zMO4nA+d^PEWJXTg1t7u%T56d&>q)evw!Hn?6a4AQTe)`pRlM-fE!=qHjf63{=YiX~ z@#dT8&?<|)d-frXJcJQXzX3ydd**ALJZcO{K8uOho`WR>cTKyS%!ClZKr>2cbnf1V z^hCw%2dDAe3y*W-&67E6=s*&^f*DgL^2GfHbuAK2hS<7sBV$iHk<{Eg4sI_av!D-# zvfHgYho%2iq;NHq523>Y58TO^aThV+h7jkSbt*g8E@$SWk8$fGFVMcAfc<-RVJVG- z)Ku=6I*DnwPU6CguVCS#`J{Wm=kN*sR!5hka#a3V`Q1UFJ=JaI{ME~rFn!8hG*%y= z+Vn7N#HqCMdGMOGeDlrs^dET=&%E$g%=%LHRyCk>Jp#xgS&X{w#8}(ei%K}0S78fX z=vZN}l!0`Lb4lHU5-!b#ljWv)7;)lQ=D+(jH(&NA+PCk>l5aPV-+cfsopjXYXjj`v zO-Z3=aW)UlTf%#vE+N4qIbqZg?wk264?p+-)E~lBwnME=hg{};@FB;KIn}{IMn+l{qbw~^cRIKa!G!Toskg}H29 zyN+S~in(^uWNyEEHn&ymqQ1EavhwNIcL>e(wdl%@m_zzmx$I+3zIZC1E%}Q6o!cXn zLXS`2)KgF9=~=V*=9?cl^TcCNh6hZ`v1nLIIb&b?jRFjmDis87~EF*=s z+4-DsOfk1!e=UXG1|WpN^;0L%p*Wv&&p(yxuO3gI{>NhIitBHOfG2^<6=`&~$ zr=2~Tt8coQCmwr-(v9D+Yi}h3Pr8U+oeSByZUaIyW8RRUd+%dN_a^e*>#s8Bwb!vd z^TH{4<xVF!UV3n_FD2=r?O?&0gg-b(z&oR&%M5Y*$+H|5vrlt??+dH zf=)fCuUx=wx6YujeQR#Gc!Xo|RP-5q3^{KvV8$(zNJ~y+{hn%O&76s#8lgf!5Ja3^ zOIGQTY8XPE4T%7B8jptTSkzn-TLq?Da5ka9^HZ@E%q5O;qpNh!&qiazZ>8UO1MA z@1922zQajMO6HpDF5>(P$MM9hyI8w)07hynuDtXjF1Yv{W<2yH8@BEtF5aM|_pzKm zb~uHdy7E5@UuEOw^O~ESsZa3YyeG*`hP!UQ ziK@gdJU(kOhbwk7`n0S0%fkIHyuvDhY=M88!FSZn57^LO4 zW!R`=@#%_F#+}cA?)k(ClgFN(M~{K8vSITMa@%#}qRXzNeRe9th8{<=N~Sp&=IqP* z^QVi?B`#RS>F1tHVaK+lW)(8?v01$G#yhlxbP5Z)k(t$wb1oc9`!?C+Wal#X#bC&e^X9Uy8$x0_F#bE3?XHcA{h}Rf4rD|_kSNaSr`@cc)ju42<+V zHf$-URqM8#I_{7765Fuy`_+UM^ckJch+~J)szWChfAA)+&3}u!kU?Q#0foH=vhbsY zys_wW>gpRwYn{uOlSYu4p3DUoo==*rHHw_VUu36%1Z znAe&4Z@tB9Z@j@fZ~m3E%xqp+^bsS5kH8}uXqB78al?8NZ|Hcv$xOU+DwX#?&4$&h z88)yFN{<$XI|=}g%I_&h)DAx4r2oGp781>@VfKvM`D&YD!i4d}VUpjeguI+AG&8`C z?K=>LkM{W;*|KR1hia-39v?Yv+tRhT4drDAF~c4Ti`rrZ8(6vWdy4xE#%yY);^2O| z_vwv?Cbn$eO$mQqOP3Ow4(%tPB~Z{I4-sr+%Z}Yt)*M39bW*b0(yb^T*;3EO%{yso zX+rnLk(Xag$GlVmE%j{JxQF`Y5XA)@$ZwxRS=oNd%lD#rycBlrM(gxM0xiw#*l~c8 zZk_Px7WK7NtlCsczrOuRON_H!QOZwaeI4sImJ*au(xnK?e~2a-PkzUId`hCi4XoR+ znL~9gcy$lC?c0*yu|3ycc|9kO8_OxDjv-WE!`2<89Ip41n3zbfVFjH^I+2y0PU)^)?A^bQ#FPv=cP$|$(Z|7x3aY9O)4OLk zgtVzNloep^lk@oUyR|&~(leyRd+bwv#L{bTOhSPbs^f=MKhnCOC+*tgV5k6<`}eYa z_ddd=#OsTrbC2GnCm8J9x``n16t-{2+Mia@d(dE#e1gMOm2BO$k3e%Xi79Cmb}1n< z5q9p}&E5kw2rQB^TGOj{4?Jd&9XoeZexQo9v{d?bFJ$B9?c^19CNnXf+Cx=r*|7`L zv}luGMEmw_Ay~)i^*ia*wFeoA9_p(qC_hk1r(V7A3gK{`xxgU=n$AyaHqok88X4)S zY~H+$hWdImUmP6@I#JLzi{{2gHf`EQlRrrNf)3<&$m3vHIeW_X5|q%ceFusg4=dz%WM;Qkz4`X<}^zPe}c#oiL*Dm%Rr~!|UKD~O9;xj2L zub^~)1xhK}b*9S7)I z(uH_KvUA%O{6;EWJ9R(>n^?7WJDrM)X_b*0(QV;ym~Gp(@qgHR?>H%nuKoL49cDJ? zUBZ%sWI+T$L69UEFaUxeC?*g@5kW8`N>BtuMZ|!jC<2DtoFigFB!htD95<&4UG@G^ z-7~X*cY5@Gf6sGUevoCSr>nZEy6V(*&bh9dHEW)7ZSu5(l~Uy8<*{V(5=M+15mhk} z9x7`@XqrqyXsp!0R3ROkCNzR8R1k!PgQ*pNiVre>&J5Q6b^u8nO4)!-&u*>x=;KdV zzNwJ+-d)IPHL7@2(o7ia1)wPh)6J`5kpL^ISTdLYvHM?2<3nzqxw%x)JVBug8##Nn;Uu1a z<`EJj+<~rJPXUG*Ny-qM!a$9Y6jCwQo$3{elDl~Mjc!biGTi`ehvSD2@Wxy3kdu?i z?wvb$V!=BsdF3VQRnMY45OD9Hox}dbB(gHnBk^{pd`34O4~U-pEBT}~Bfdup>xoK< zh`^<%LV+tO=Pj0=I_jwxi%1ox{PYypo$$l&GU_YEk%PPV>dQ}=_uN~|dSWImTQ-ll z3jbb1POd9DUa=|`-uIO7#!7+=v2*ig)@|CtqjMKBedbKsw`xQnP{i?L`6y*XZ)ynA zvNA~U$GIsDvCb6{TScWfw@UFiu^+^?Q^kxUQI5Nldn@)r>27*%*n%gQcgpYR>kIPp zC@d<$FfF|KX4yWfR;hxQ0CCEDsAzj*-v{G_M~lo!wCi7Qx`uXT{>}?jT2f4YegV>v zIut;HWm{xrXXCRi94RAf#vg%XDEB{si}a%0KJ?-w|MeRFEhBKr5=M*|q2qYv?|Tuw zE|yYa7$U0R5u-t@grxM?ZpPj?jIVy#N)Q86==i*$*A5`Rw2U>s9%lY?vuIE~`}dzi z>Ka9?1dsRQDb^!>PSWEerK?pGv%bf!s~#Q@A@BF@4;sNN-AA`>UD8=6`I)5q1f z-_4!34k1wm(R$|p_pz+qyLYpA@nXi0AOEKVC;!Rvml62iQDTii3#erD{n-;*Cr2c3 z&UrnlQRW8s0}6LT5+=eGWRDG%J*i!>IAdvv3p8(Bm$#R^#Fm{001HjM;LzywHuSmtVy%08%6Q(W0q8xOC)^%2N=%}9t~y3Y zR63!?Y;^*S0z|6%{ipqBNAKi=r)RB28(!JyhQgv!_U=2%9rxZ% zYj9QGS3Kh96Q0`(HHug?A@=Ow&6XW|nLK3@ty?uhpg4SZH!r`u6zS;9ZzW6&pPzwO z52kKzuA2vV>Z8HQ?Fi$M8k^oH!n-m$z|p%HfYioQr4UR;D3 z8D`_UpZWZopNVSCN>VbbGJM2v5=^hvr?`*H<=u_!+{_wl6Y!m+W%Dfdtqc=99W$n^w{g(e|mzhcR*D zmwxvlO+-R9zFe`{MfXe{vVb6@w2rQlIzjEP@>lt*{O>8kaUA8zSN$j4!5SS2gA*cb zCTerYlcI<)zr_LI$S{`i$Am3P6|0aH&EAY`w#ucDiE5f?fpCxi0XKm_f8D`x1IDf2#d#Hu6UH<(k{=S93PrjHb78p?K_3dFJ0V2GIcXq;>v2%Z<(5OcM3ul7dG!=hsL0xJB3iABJK3mAcpQt~ zYhrpA(GxCi>Y?jG&kvzA!YYJIT@_J+IYoUjhPV{kK`WGU(R1Y5-?_$c_M?rr|5nes;#sU$)OHg4L8X_z`2RDn>!T?eFVoN8@YA*4pelsB_ujX+m> z7m1-f1X-W*Obj>N!$BDiN@+K%5-0a;O!PJ)c7DVl?n*jt{Q_YaCxl=q_dwvq$qDx` z$L|6F`oL$P!y2@9I?9dRi%>JUhY4adk56j*pE6T){eR-V^?U6O27@?`!`7`^|LwN? zt9|lk-djpNmdB1ABR4nqA6)%c`M*@G{|x#UEsk_B3;~XV!a(OU=xI0B7>GG_Diw1&kGfk7&KbYTTicq;OwQL_sqHX$2u-;nAQ~m-VRjy7r0ZO=U?FX~ccDwqo-U)EhoE|W<@GOakbDIt zg$I~4^;t&WF_l_5aZz_|OgmLf`}FUl2%&=@_FobAU<7g{<{6{vE|tgEn>_+USmYlo zVAGlnC}DDF-xlt<<922*{fH*Day4ax3Zi5Yt5*Jq%xXd>Kp4@P03bw&)jxgC=PPzI zdi)sTQ4lO(-cxh9a?D+{Yu*Sy(ls8U@0o~EZjpFKv%9ehjkqE8UxtUsRQBrXjCgmv z!ct%v4xvCXt5$8GydsDY5{1^e)kc(qFv@uA%{Q?!n{n9%=VDRHu5GJ%=&`q$_v8$c zvdzfcCo<}lHmu{#q;^KHi>|gRW_0v>=U~Q+on9q02kXg@^4}k|N)PpSuktRfY#hhF-@jL9 z^k0=%i4(thVoU%2U3Txt4@-n`oDiXqz)^~zF!1?Avg5-cxA8c9?Lea{5TplbcbOrP-xA|V+=hN%da zAf=6ifzL0nO%nr!lobR66-bqUW7t@hiQg1jDI^l3B#=%8fj|W^K8*z7;DjBVuz@d5 z5~wI8B;!z~NxaYJqMZsuSzwr4bK?jqtP}(wWd)&72qzRG7_c-6vrtG`OrSy{jW~ja zMY7Mpq=Ky*SCLe&6~$%cB-l1_wjvx35DFaQ=kdX8fHY^f-K75AY&PkKN zHn9Qalo1Gp2`LL@`H8b_OhOnkNHFN&NDIR-2?R=5xAqtE3yR51QpCmi@CivMSVTBv zBP~C+&!^qtvVvem1(G;~sW9z0${mMf+lQgT1OtVH>{Lw4!mnJ^!!@FU6~!2K9KtjZ z;R;HFCVtz82p1DlCKbv;_-qnwZAJ?TLK)OMtqC7~`6c0mOe_&5TwYAbRRJhf7RnMB zN)o8ZCoKI)!^ZFP;WH(9hj+4d<2p*p%2B34qLs{yCuUO-pMrtZ@`phP3lm}6_ze?F zg$aejI8xvs!LTuXK73MPnj&IhX->8z~xL|bUeO@K1o1FYwg^<2pU&rcsQrX$8^41;$} z0-5*Jo;$fx%2mX&(AS2QzF#B;Hu{7_;&FvOlnD2zE3t^8?Ow0A$$TQlbc`7X6;rj8 z`UAtP++N2CMfgAgFX5l)%_`s55nK|IRFn?Qa$Hb0qZ1Jsv5&=IcYh>9!zt3{JR@dvK86 z*qwm%>K{c+9U}5VRBozgcE+ zsf$y5gt{%xW%A?)@KqdT_EXQW{QI9th>K_Y?n8{abtKme?q3N9LrL~+UPbRdS2FMI zuQ;o54sR}go#kr}GHc3hOrQP;zi!@1QDG5%hg{F#0av&PkU%KO+}Sh8w`w!?_UrlN zouy2lyO1hrK4hQ_R3cIs96xf9d+(h@NpUGhiULe{=n=Y}nMHZ9oO$zJ=A(B%Wk~<7 zv^cE>4?H-BqOxMj!xfx)PFKdst^ z+1({(KmHV1i{54Y=xf=(_G@N7|2nC;r_rn1c?=(P5qFOt&z{2tl$3-SG5QuR=-G`s zZ@-;R7j~!DMHlhf3orBeS6>qdhw;b9^U(A;MCoy73=|QU1Zb0)h8go{MPCWJW z>&%}!lVrbS?1+(cxZ)Zv?R{Znp;k&FRDh{>jUlt~ncOgZ1c!HSrq5M(^5QFtIQZ)~ zytd?Z@=JnbrnMM1vM)og9mRVfRzL zS`F&e$!6@B;XL!)Lbhz(LP&-&;;S)Z>Nt{oGR7!SJn`rwtod~l`||_z?Q<y-j(Y%)j#V}8KsHrv;WgIDyCFM zja-H}QNhlghe*t-PIj^nOpCBIumzw(7=|llX6nPEse&jKbqkv(B6vceVo=a%eNn9S zBtC!`P{}hLb^8KHWfK-A+KI1RBh!6HPzYh8fRF}kV@zq+C?&RMJxtw02$fr}Mz%$y zZLX27g!gg8j`BcD!?j{PTr?agX8+#Zh@`6IR?UhSmm=C2A`B3o9VlGm3x($;ifyeS z6v$GJ9xJ4BT0N;!7m07WW^I<>0n zaX$I<t}I--KU~CCBpeY1gqQ_ug|8n}7bEzI_MLdtiSK7nG8mQH7_Tdj_*~ z57%CM2kW-%q+MnJfh3F|P<))4^%^nx@uw);^D_fSOk>Ta?S%F%XW<*4vFP=s)Xq#~ z-0kBi$U7Q&SpoOu4pXCEH5%5h!N0$ZNemryBLjMLCfPa0U89HN%WlmR_l`nT6f*Lr@vJ_(9yMy#Brc^EPt19Q zv=keuBp-d;in?{H6OFO6Py%iqJB|)#w;|i8VBIG#aOQbExo!MdvMjLuFlp+;2;t-7 zH{ay5&p+erZk9o5F&Nmk zVI8@(YErXaHmB9-!MR<#Q*iVsH{Ez6t2S)bOlNM!q~U~#QxYWv3toDKL&u7k`}_-} zii3=u@F+?`ob6}m(CfM8nxSl3x15QyUgw5eM&NrKN1t%TWnGYw3@E|K+r}Y8 z87tTR#_XrxW@!Jmgbg2kuepxfuI`0jK~{CXSEp=%e;>eP*rf>Oqg9L-M~ek02t zqO{!Mxw-R56om}G>MGuN=M(N4b^#Ob9M5@I-^tJ`E@0(PD_OAMoya~FW9yt?km(mP z>Z<&Mt-qKeh(YiOacui4F7G#z3Df7%_4KOTe)mK48*&qucRQ2K8`tr`q^ayUl24Cb z7c&0V5&Z4d=Xv3kH;GHjWy&Lua7NR*Iu_7<5*dAhNYVC>8M)?^{=rCKpyy^*WEUINDAqcW(+jj1_YZ@c(7|&VlT2a})kkNJs&m?h?N)Lk4 zO^qHj6c|FHT+G_D_$q@=VNf9oi=nu@oGMk*F;T4k=_|&J8qWnI@8PzahLCu2$4CBF zG5;2>VsMn*!9xT!m!MKb+&5t?heBDr{>mI|SDv?$>JuW0REjWA%EY_wN#w=NkX1UAJ!hK6CdTT@?TXV z??pJQGbR7b0AA2AHikl&3M)Q=#FP|rYt^OWnGM*zXB%P5hY}%#C}r=CjodQoR=S^m zF_We|%CV#QKnPQq#KotQoSaOHCbdcQm2<4107V?8kw|iK3RS9SP_t$>g(YP=uAOjX zF*WQ2{7H$_tW}$|q(ll2?q}ELUpb@gIn=6Gourf`t@b1(GU^Qi;qv;$*<9ZLGS>XO zhNAsP*t+#MTDE9N;gKEOJ@yv5_Pmh0?w-hzqlNmcDy+y!P~qUH0LKeUC=dJTcvfpN z(^JXL%)+w3a*A2?&4=_KIFJjvU&7M2-lx1I4A=-|5^q~1#rX)82HCuE8{IGLNk(Qi z)vMK_{b@DXw|fUcD-PjLATcqK#Kd%xQ!;4TtO@aPK6lYKP)dN|!}ceV;J2|%6NG^s zpF~1Z0`Y!>y_;5X>#*zS-n~1sX3Ze4u$Zt?gmEw_XV3OceD~cC4CsF~UAy+;({FyF zthj)E2aaLHXL4?bwxp*fla`)}fxQnBM$A~OJ05j zYu0W6>Od90;o?hsU^!(heeo$Sx%e`!7;p`%H*Ds3Nr(^{*)R;zyb zm0ERcQMYC;8Clioc;=a`{q|GBfeIYkkCl{4dRi7;&Thr=qq`{&hg^MDZxb*;3QV7k zvV0^YCyt6lCH#6N9>E(Ig zqolNuJqPzu7zlIZ$R1Yx^aDSx_?f)J+Zl7)SU&mc7yNbtnF&5tF8_`R<0n%RR9Fe| zC?m$f?EYXV2SbL@@^=d9I1%H_Lu{nd-@28< zTUXG$VSN_9^R>JBh1s)X6DwBy#HQc2yHDpO$bs-O;Jtd4+eRe_DHA13O-}8JC#lGl zZl1lR@1xv@6Iz2BS;mjc-lay(20T1>f$QQ|loc1Sch5eG%F6YemmbO}L1^_S52-Vh za`m&7d-!v;ja?%Z*Cf)O*8oQj9^i0ZnQo`yW}=1N2U1R?E^TCKKGK3CN60TO)A*PQ zV=9R-41(ol>_51hqlFcCB8r-*TSVYRDTDmB;U_M+s0(*Yew;G5AB56|m~?`C_5Mv+MLbw8FMLjB#sKPam6xv^*o=`TeW4x=({*jP=XWz4(!^%)q{r6qInAj4jsm( zT?YX;yk{Gut{X~=7R~5A;9A!2*pEbVeD4-+zN#;0v}(-m@Q#gD59C_P>gOZczyUt1#XV2>>N&n~gyxiTDx1jrvaRzkztRj`D@G!%j$ zufFmsNmU!Nbow;D`+hBNzWohg;Yh=ka}w^NAdyII*eI85I%dysguwAORROrCBn-`Q zCPNPK@d+F`vXig`!%#?Ugb|Y|soehwKqPZ+m+rj%;bdN1;wPnALr$w%gEyXfh=3z_ zW$BybZ(YUo`S0r-L1CbkHvwUyFp2Z~5KaY0j~yd9H&q`Z!w#~vh&#sI&V|D!aZSJO zEME8;Tk-)VF%3Z|Ad!HbV3Uv<&z^mIaMal-9QNfEQ9m&mA;XcABf`-qP%AES;uk1P z3rrKjfuI|>@3@Bd*E-S^r50*`QViNgz1pt(k1t_UdRLRa_ zSJ6JCVMSt^OiR+CV@qCoYbhNya2+83i$4SYqfnoVU znMh?KaqtnwAdC~UCJQf%T}Z+zjA6SD9MdKtHI*hU+VbL}rKI>IO4uaE1*j-Fq*Wur z#k{fP4fYp>ng8li3i9%Kc-pfd3{1l!TprNLIi`)YG|h>^M~#{dIIT)N@4fpe>vrWa zrb8RbwthpSrVW_(!V(%(%LYt*@d>ANA{7;tv1rMAJn-ODYS*m7onvkz94tqX6nXC> zFO-1zgm_F_P*_-ipc;k($94M}Lbx7S z@-{!L`4w4qh_bL2_^XzY#Ayv1(W2Ga96Nf5Jv+9MkyVA}O&ZapaRb(@TSaL_kfx0q zQ?1@cv>B5HEam76cH-n{nr+;Z{sgq zb!B&Q>(-@F!xq#(tuc;rIJ9d6i{E^geMgFDetH`&?>~TKUx`Si5EmJ`tdP%>)di zf@L4S&usJ807RbPG{hN zOE|Q18%y4JgMxBJ+m1cy)x9H0{tABl;!8gGav4RAk8?Y9?{r)+)o|Tiup_eWfT|W^X&Yk+^FqY9nNCXJ@@j|^RMv0t^Jtx(7jY`(3UqQ-Oa*x8AysrAyyp${k~P`Q;~={Md7ZlIrl`lQcekF4Yp^Tza-Y{H^(`{4Xk%vV;E~eMm9TkeZ#gLI|v^>h!SB03V%`@Km4?UJ_85fC>x;+YUEbs^wS$M z;L0nw_l{dBJg^7lgt2WONhz7E+3*|ZwP{LmQ3*=MgJDs%S{2@Z^BroWrcx!bi2m1H z#pp>>NRJmB-o1qtzwPF>)?)}eAwaqdQIH?LU&eqN?&iY}KcH!Ys@gG-oJ3BwY!)wg ziHedEn%7J~8Wx5V?VHT(TsCdm#*Ur4IDF&?mfH<796~A|wQ4jXHObHP8Pgef)nEz_ z9ir>S7t*+XE$URy;@TnCa@*~9B8v{ur9)FP(h`|F<3ajd(uLC-<5vaqPz^B;ccyM#FH?Q!oXAxNjX)xp!dbh zocb_{W3T1YPrs(9EC~4V*?yLP`4N3CZp+#qzUGe6V|nX?kEvfHjY$*lr$}Tl<^J&; z+qat$BW~fLnUB)ESu<@oq9QJ_|JjNbMyOJro;8L0CeEQEE&(%CLP(`yDw9B2DQkaT zMf=`IXj8>cSSgO=PNp%TF*YdFSI_c=P2)d2hjV?!5OgYBg#> zz?Vv^vpZ5Hy^vpiT1k)nhv<--4$@)chP50#bcoKKnv!5;v+}3a96fx9yyNNIcH_;w z`}Ggli3xR+s;r>S!l9rM{QArs~-u;d@-+zS`4eQ|7gYBYdVSIK4 z@4opaM`R}FOum-CEnUh>i{Iz$3(sT5V~=A5N||`iFr*5wXUA4bi}GpF@qA88v9N?- z#dpj2<)@zr2ZQX%FXx`&-MN4Kt*qXzh)c+z=aB=nZdH@Z&%c0j$HMU?@XRxBF#DND z>C>|{Hw?Lo0+B>~ji!X{3@+(X9|MPjyEgOM!d>JSDBk|)JC=X7gmqtk#-Pgvb3BaB zsDJteX3Tqr8~QXs3CG(}So!@oTtDPS_7oQ3^BEMCdCU=jx6gPH0#1lC&uT}jGv;yo zZDV3w_}&Uu%C4Q8sj#bZcIPf+CI&dCOs3D7(jkem@5ViCMPAt=o|Yo@r7?W zaA{k<{Cqjn-*}J)4I6Oz#od`U^%<1Yhm~vBbH(Tfso$Ux11{*q8*`_#al;CJ{Ph4+ zAAO#NjglBWa%a<+Vx19%=_uO30XxWyuxC}C~-ThjY(6k2u3Zh$Pyy??`TT26lWp zojP_R(Y8p-uEp7BwINOjEGvO-ozJ0qZVvUEoyiAF=A#Ps^65vPl8~B;<+F7xp$u>$ zW^UQ>^cgsi8;1|2<2h|WI`r;;C4Dcsm?bYf&)Z+FpmWzQ#2F?R^}U4Z*=ZCUI!wdU z+t9jc1LFM&+&TFXhF#r{k3RT-?^bQ$rs0E0%c;sU3tp#os>PE}Jj1@DrS$B2Hl~@v zHP;WLdCde~Tkssa4wZ26fE$@R{XSNF^92WwlrV4JQ`D>5i1d_fI(0e|(>9SvGPASj z)#E&p6a9Fh+`^Z_ocS-4n{M#w2XAq_G(^27t!UA>9&vzaSUfQ0KH9cx!E^JT=9^WU z>Dr|`>4u4kfnoSah>PQ~+0$rLGn>UPKF`WEYY96FUuqR*Kf8#_x}C>6i(lruU)B(` zvzU1Ac#_O~{`TGn>@S4A1BP(R^?g{h@Fjdn={)xIToMeEMs;e@v3*-WxEY0Uq-8at z_oV}=o}J2BEgKW(xk{t9lIy{;>2Pi*hFmj{!B<{PQoNrU)$4NK19!4|<#L{W?nRoM zc`hv))S-2Yrrdh_ZERY<5r0w|7hT?$w1h-jv^s;=UtdDe;r%=@e<`OmZ$+!7wQ1V! zEJhB$j=#P90t;XNgf3k=6KBI2?K^YVxRHGM&O&}%xdvrtaCWEj$Vy8hCA%I^J~^BG zz3chvn-xr+I)%>Xw!w~1p;z~F$xZ=N2-0)w(4k`|k}OlZ2ECvmB|s#RmR*~3&umVT zDZq%QR{d6d^1%`^5<|SQ@FlkG*oNbn#HVC3>7H9TR8T^XO9wN&{{<|0;UyNm{w`fE z?2Z|iM$d~bq-V#|c;%(%*t&BcDH+wcpnE40<84q5ZMt-2=ylgH>ZTj8mB5J0V*U&B zsh@4K@WuJ8S-+96a*bElT`Lecjv_TVfd?PFo9&x7@Z_B5soLOln$)jDc3KAKb?b>` z7$E#KZrO%*EgE8(@l3e?LHhJ)!;)8D<=~-0eDP@*Ru)$dx{9hvL5>{RM^1JQJ-YP3 zpOB0r44O4-LbJw=FoZ#TQWEEM>_Bo#3el{}FgiChdXNAwdhYL+*n_Z8L5hy;V)5e7 zsnYN)zFWVQ6<@zast<%=fngvGg_0pR)+&ihufBy%o7XUW*g&jc3CUIJvV8R#mVNp* zXVkBS-%u`jw8T&Xq#~?rYBxQXAJ?qqo6ibj1vo zVu~Op`K(?0Bg=pOm02&m!QS25xw2P#zJC8RHg4KUFyxS4y)mzU@Bv@Hw~&GZ+gZPH z7Xe}sFl{s?WM|W^Z7aTi|4nx7+QG_g`#Ga$Ke}~2pXt*k^2B3Psh3*=WD-}89LuI( zS93%E^RZ<)6-sgEgELwE)2C$G<*Zw?kw7^FD@=O!xq*ELx3cubS$z1)JPsE+Tr=!u zrap8(eyf-tmM`OQkwK~S)3w)S%z6A_Cf$8AwjCyfpAOxw;P8QMj2|(GZL5D^=gtkh z_WFAqsW4dj)pu;!^c^|=Vm^BJW6A^I2m>W6Fr8w)|KeK?Q{vfwa6kFQ75IFqB>8+8 z${{5)i*Qhpf3yG$L2`034i*UsDFn+(zzI?sC?_t_j}nlYk^~MMI-EyEFhoX9DhfzU zPb1z4QCeKg!J|barlq5V#7;`VGW}GPd(qUf^lN{9IM`q1|Gi@AxQ}S;g;Waj&m`Y; zU6eve8Z>Us%-N5SB8Z3*NW)^t^*5s247Ra%jK@)7q_8!brz98j>IuRmEEQHt7LPqM zU%T>Z*QVpy?KO&|lDJ{`NE|FI73Q{E$Dj-Yqsi%9*Q_-Xf$h)WuJLyu2~k>jh@ygH zTsQP;cJDpJhu=Ixi>58GL=fQr};NidVMxM|o3)G!l?jYMEdNUht1sZ*x9E^9ZyS3&h!jhH-n zGLE#|gIkzOF1eiEz58jleg#4~FwNRL#odi6@^VEc{5Nu!Uma;2{hga-EwtqaUmDIqm7#uDy0I6Qc0& zes&)?&bMo~a^tAmsh*mINtt&2i?~QclY>Ai3o9vy*>j%3!RIc-7M;5G;@mF1bZi;| zM}eur+<5b?NW+Je4zuSyjWBHtrD%CpM_RV;1VU3pfWj1E23>svgRUNdRC?1e0Mnn! z)kAM&$koGf3=@MOqeqX!!9qz%vu3TBF|!qjIBnZ0MM_!@lP2Bcl1(@?Z_|$EZQGz# zSfasg3UElEPNO!AZ**47S;VGUlg3PaXd=qZIyKyl>C!8%L>U_W9)8nEhTm)v_5#JF zA}Kwdad+JfhL+p|nD&4sWR_BqTdN6=Or8X$meCU;nd-F~bN~I5w9%s!h%kl_>Bf`uU!z)X zQ-X$|VUs4zobd<_0z)ZU&6-Kr5*Rr2yK*QF7N&rV^epbW=bosDp#YCeJfbk7R3yRS zUt8T2!9akLqH>a}*C#zQlh9EE(@;93z|e_SrfKQW3)3cyt>es)_@u&6eq;cQ1TZ61 zFc6Uy5)#KyC{xF-)vZ;Hn%U`W-?5kc;!=vs%W2S}CH^Fvv(9WzMaA13DVAJ+^91q= z1hXC(&x_C0W8&1AoKr!f$(zGVA^) zNsde4^2;vAR2BUAJY^~~XFbBzpMJ!kp*J&i!sVDo98%aALQ*{|4J#0! zurQw^d4r&|;euyRk3hnwfOrhx)x=Mhl1SlVd1XH5xmp-Jc2_k@>SA5U)*Iq;C z?&otx%hs5}0^!pej?jH=11O~zJ7J=vbctj^DFcO#g{I@y!ev^LO#s40m2@j5G8{%I zhnHVmz_r(2Pv;)z)3BEtXcmn2p^7PxP9c( z^ePL_Fc6^CT7-pErk;O>iDBCAd=WZe(vu4mU7A3fN;VH zVk6)5JP{}iCAEgHVWV6U5<`G8Y!HUq=N=8Q1%~AY_!~G5~YW zxLZH1AwrZD9-&>!=G3cGpSrbcQ@3sd>NjY{lg}(5tSp2Xhf*LNi3t(+nQ|mfSh)SD zAROZBFPAZF*eC`L9E|NV7=FX$`Vn11G$fWrs(vu@3A>^fM;8E3SnYSkPvGt>Fv{Wtk- z(+*x-@(wAPspRBTp`x^$akt;f8?Qaj_TM)1^|vbtVc-Zu8$fm(i9Xo$(=rb1KSWV} zDIxTncd)5fuO2B$l7-LD=GTo|_+j;ClG0MCQ@gr0hTJ5TpcBN965G)83NJ(xmo?Bx zqHE`KsGX6>teJC3$;svX^IH%oKFS04-p9m=Q}D+nV%kCW{kD$Z_Uz(7VHpyiJ6;Ou z#E3~s2dSKh`UzGXwHls=Nr?7s&fuZRQ@DH56t3uV8CJNMcJ15n!3Te%ZOdl7_wJ{Z zmIRTmiRmES_d{UDWzg`n1~?VR_~N~{SoZagY}kH~nssVo`~1ZFOpYJi$$|U;HBW1b z6DnZQ%g?d*a6aWOdA*3dd#5S_Wq7GJ`e}|I&8Muwq;}m#$fCU*KYV~=M@m?`VL#ov zccXso9Ar43mA|Z{q(t%7yI)eTNdt20*5kB#b=kCL6%}PAtXjK{j9Rr2aj7(@TZ`XT zt)il&lpj`YCb>pKnl(RzI=N|l^Zp_#0zp3gem(y5TpHw7*JTg*4SndWWBf-0_ zU=yZkM(+)Hfnt{7QK7ooc7_o(0$hF(VVWpukXz?;mj3MnmrEb|$^g(I@Y$Xw9j53DdJ-f%fr6R5>!-X?U%hqia0Q%%7D#-u{jUL1l zaYCSPR5_*6*P{1v{T4z95V15B(j|2jkv5#y;}TY`y9AF*OvVK8NBdnH>7Pa=~zq=lV#`O3Q=)qUAG~CIBuEnAh+E45T1sNz~syh=d)$!F5L$rx-?67ju>uV zh2iOSEq2Oa&LEblVVnuu@=J zu_U(&gyr(>nT#4efl;?jh-@OlMR=pl_MRd7ES^Sev;thzoQR4|r=GLX`C-|W846WQ9e-5O?}Q(JQdK5SzKaL$pUN%QT!|BMNJy(gTB09e zXkuugLK^BrVaTA{RW{P}X(bR-D-7A__Y6QePDIs1I3f1#*u-VM`w$37+IQ;1_19iO zolLelC?-eGKl8~Lwm4j|1At`~d0AVT&VG}~)m;%fUhFm>}ed|~8;B6x* zQ#P$TT+DUDt|2Zyjougc=G!SxF?Qn9JbceEu37OTug;#v)00av{V7zhp5?MexP5Ta zgt3sq2aeS5fD`7H5jS($HAA@gg05WJ<1Fr(Fd8EvhosELT-oPBvf~2WG-@cbrc5I( zy$VGo6-<0|2zFv3cir~@Q=fQ-wcmZr!Td7DOqhr?(ik}4avpx@5pMb60}hv%jD2Jd z8JTss`=-G>c>e=z_+=UUj|I4S^hByBCvw}UL5v@FFC#{crl{aJeFqIDJ0UTKr0B2m z-&}-}N}C`5DXu_Qn#|iEJ)1=eg`k}Bk|JJs>0<^D>PK37l54wfSA?S=aoPPDIu9vS_t(YYFx-O`sjF+&k$c#LWVc$X>!dv|PS>5|0^8+!-I zmW_cRpoiT>G{dNHK3^_dO=_*CoYAmG)D`Axu1cveU9Lg>3TcTyY4{0@mb2F}7f2j8G^c zHD8&d2w8q`+kKLRt?-UJvGm5eJyA`a%7b6I_fOt-l!KPIGqf<774s#{VBxrKHi1SY zPrX(}-_?^ZQA!aCh1jxX3pH!jJmvS-uV2r(=bj5dUS1wcmMme!h?~$_#-)^$l~Y&} zCLC0lK0jHR>6oH|14jx-OUod^4s-Ze5oTg4)zXr{DWbTvoPtuwtyT>~g%L6UR$@%M zB&eg@G;}DRuPfq(7v@s0N;XL;sU##P;!|N%sGPjKQYyk>r0pX;{r_X{y~Cs`wzltI z?cF^&&yYcKmMnq+k)Q-oOd#g0m=zP~V>*gQF()vf2#5-pP*L!Jh$03Qkc>phLl}l( zQg`pF_5M+NcQ@#HUr+FS&-Xmmb@j}2&+gh)t7=!Ry4Std$|p0dC@_*A<-voL9;`qMWaVU&o|;1O&V3ZrEF?WWgswVBNog5T0$ju`sD-%bAE!%9`xI6B+Be8c%l>H_9(V-0TbF*=^uy_AHGBUGBO;1Bds@PXj zN>mHE`FUh#X5iwXy=wOCs~{TlNYBb9Cojj2d!(BE6$dFVFDE^_fb6_{!j8r@9tTPf zaItE$<5u!_`hnB0PVLg6ruzkeo2 zb^P$d52;tL9$mV0`ORnK&+)^Kha~Otkc6H1>-?c4??6{k{(h@`^7Y15%XnbSi;RBqIqDYV#j8_T^P@Py zJKK(+T@sM}RDi&l#KtM&Z^((8+vx5AYT;ih!s3MsNN?7b4&9FB$tV8GLCNHfJ8w-& zj}&3=u8ll1ZajSk^rJ90)v9Un>J7vWFlWx!a1&c+k>sw4%@Z>Qgf zK(zpcsXV~s$rCub|5-F`c!Y15No0kUgjPdPc~I4DH{QrG{rYg~X=hlaJ{VVZ*rp#> zIATPq_A>p0d7L!pTx#VcP`JcpHnh(nir!&!G5KmMa)~2e!5Ao&NS+jk#41EWJQuS+ zb9QXq!p9%X;L=-0uyVy}&L1*_DWA@!Ws}Be5zF6lD|!F@sdOH28SR_bPa1NIl{w+7gz9rBPJ zG8)P%x4y@+liWuRpNEH6WuI+hK$$3uzMV%^MoqeO>4YoE#}pscR8FGaq$&=78(i@l zdf-1)g1CpaLI=W`WaMO$of`@+@YjxP8q~|SM->O^*2}_Gu9aOVo1ENCa&jHCK-vC% zTyxb$eD(cm5C^3U9>Vok45eDqaYIq+)T%|jdNqBMu|gcEz5z~`TSLRlon(5pt$twUSV08|DwYNW*vOm2EE zb?W9Fg80`vBGW$eqNr8Bk-t<4b?P=u42A(wDWqhCsg;o%%m{3B2Z!2qvVxT$z6{l> zRo{M9$H>XANlw1PpmA`?$gfRCp20IwT-TaKjR_G>O{I379Pm7hr%B5!q)t}yc-yHU zCei*wv#q3%S6GYSEQml+QBm-9oYZt`*G~7}1PKvCIBpiTYi0TCpTWfg<)G5CC``+s zu&|bOkaK*3l#@noZW?(7ht2R%8u^8F$X7O{svDf5+;p;YGsw;bjK-)S$IL&+UXM(}7`^ z3Y1IjdiA;S<{QY)$@CRNL7OC#Q(}F@#YHLK8NjiGbR)($xy9qiBVw?RnMJEaIevUT z7Zu-R1&nKzQgLt{hcnJPi%Mn9Mxg!c720UDa(y$jw!AYZk|9>HkLMqKhzHxBK!b)ykb?3d8QXR(hL9+~ zufAfa1f_(_uDOc*nzj7R$H#606PN$f@%v`5{Ktc3TX=2KWR5)H9Ex&WZ2GMv1rUYj z6ZajAMSPS(j7B-uxxg;^wip$tGyXL3_d!Q#{N!HoHfRGb24e)r4g1a+es~$raylC} zs>d@gJVo8wwQz&>i}95lH-TLH*r_tg0+hVwhM%>VQqOrzsz)wvTXKuAnn$;Y1+qQF6;#Z6>@NWhPY z4K0p#|MMk?m=IKMd3{M2_&jO_hZqH1<;MSS|B=9>)3UO-^4jY-_3UyhF<)_O)uJhV zy%=YeR8TiR*CO+W85)#(*!%d8LmLpZQK=-H)(ukCafn!wm9fNqlBop&ZNq9mZbk;T z-aV3o<%fQ+PVL&9e)<`trl!;V*yG7h3uq9;sSt;q;}7XcknP3g?_A`n_$d5Z2!|aG z54*&16R}>Mq&uJ-LT+lJ4Nly?4dKwQ?L11w&!oyp91_IekL)E$H+MJ$Bshe{p%f$~ zT#VPNER!`pq2m=LGfI3a$={3U63{M^)tpm9Qd9>(o9MeCZLrf`9!RBmVE54dd`({V5 zc3Uw*6|-i3z{OYHiWfP+1?QYXK~WK1j_$!1-z_EPI2dKU{v6SK^!CfV{q84dJa%nf z%)o&sQ>Ru#uDoUxnlv0>=Z2MZIkF`+@-jH{>~q;rd=OEoRF&@KnzPTRR$gNsd-fT; z*nXb)%R@A-SC4ibJ1}F;0-{t>x@QxE`}C$}em=c=9K)NF$CKZnJxkW_@=bXL(UrKO z8QiBYHS?PA$>(1(_oGQ1*}g4VwVHC{$iHB!OE{@VCkl!R>2dO4mapG}hr{^ipJTzd z3(%rj`Tds+=+l!r^_z0@$Ooy^8i=ub>uQFaJ%k#yo6@saKdSfd$1C5%F)bTYSabyQ zzgWlJhC;-TefHN+aFSmV5EZYzxtTtj_pb9qIx{|@KYS9_K1}J z!kMS^A+JUwIvqcd?-qW`CFc%d>+XH*+PsSX#~n${x;3d)vo`nsVBc5W=%Kh9y1yDI@P2gQ$bNHE|s6kL*N?Ce4^Q?R~0^Fmc=%hF^CRW%${L zk^ohm`14;b!G>;(L2LaFy^JybOZ=C?h{g?tIicrC3_a%@h73K6p+nDN$dDnlYu}O1 zU5;kJNxex;O+BoRfBq%LD*q<=^$*vhFvj(fs8j|FJd2@2hH}n1=fq#f_vpcCgHNY# z-@fGLWMPcKi~Z~E|07<9j+OCWzh^8DeFa5p9e4II`rp+~`Pb|CJL7$5JLM3W{HX-~ z?<~K{|Ne)YgB=&qF*f|Xg0@|b<$-(e;+IuRd1~}S)XBSpCQX~5{Zm;^ZU#?1{TM2o z!mDq8#>5HJ>HgQ@Y}~w!qmS>$#2YW>t9hSu^?9f9*`goWyloe0X<7Vj-ZXY^UCV=G z#?qlnXIiC35DYOC6?=D4w?Px0nlyuLE5BvbBhPYdk7F@=7IVdQcW~>dQFQIxj{myn z5jL;?8Iis?Dlj}NjM21d--6mT^I5!n6)o$x=ZEjVp?$Yw38iK7(8CY$U^ttZAI;*` ziPP!Wr9I+=kRZvoXfzHb`%8IX)ID_W)}2QmeVFgR{))ejp99KJvu;h^nl=Sj!Tpas z$E2z6anJC6Waa1a_$%Y+-={aVG9!$8;$dblT*u^h-)H~c-8?} zW_?a>emb#Oj4LkLM?p?HL52<+07&|L9v*v!mcMHGgzFV*5)oGJiy``A! zg1Ri2JdM<>6x?tc6DNGY-hKPD_+rr#2A_Kl>({Ix zzh+HZb!bWJI*Jqep3Ii*CEPLUetMsJ8d1l!rYJ{Q?{x9dN;7rp`@Hh%R9<;$JhgHR zx83(Vo`z5;#E4sO<%SV=vhb^~c;(dzoOJT>ILhJV(@x{=F)vaOhP3cbT*tvE#m>#Y z@XYh$_^-b{!VyLJ{AKjB6lJGz_MkQ_S-Fv?#!aDF{TxP*eun2BAHzcr-$R-!zH5~7 zX$BsnAGn9Qja%`>*jI_hs>#jCMr(%)FF2RmMn6PGdMaPd{gg>lKH%k-$5T}u<^0R8 zqE?f}G{`LDjuAI=_X97`xPEQ!y#G<=e$|Ek%~Oa*qP+9TC)CQ%BfGK~Wo&-a%F;4+ zZQajX)88Z8@wn%KG0a_XJZE)p%tH@6K=0GfV$2Iq@XSk7SiNjDiqi-3Q0g{eII+*7!zIZS$O5--2@7GoZ~9mfeV>i!29a>;Ot(nBo%;v+ts z@g6U|_7c$pd-==rljwTV$uw)*iBLfqDI@`Y%6A^)FjVMYD1q61+O%nhZ2JFfQA%5? zi3;Ha)Dk6V4UP)3^cY;%B^He(9GiZlUB9bb?VeV?B4%M37kHxA6`;!6MtSOQ^3H= z+!#YuRn_0+%>G&aXO>Vf8U8blA=Ys~`FybK8VzXPwlzn!YRsB%eqhzorPOcL#`ky? zs>=2=>8kH_x2h3&g{6LZo@%`T)xt2T6O znZuMfa@o0eKdl>v6Wl}Pl37rPBU&`1SuLpX(o{CCUPbA;uV~)!L{2?-82QRjzaWDY z6G<3aeU6$^3bHad_4HF&vgjwyKBh5CmMmfT;EVC1hW9`Cm`~@^jY zHFI!EH!^?L-#F)%C+T=hH?lB%GkYehRxReJp8W{tH=s%LmgMDTfaCD^gB|P$_=~g{ z8_O`Wpoj*wvdQocfDvlcX+qPcb;uP>^x$4zpEQ+k7X5%JujGhMCsHj2r9y;sHNR|H z&#W((uxfKLsbS5I?Yl7f^=RLuh_VXJb+?WnH!F)YQ^CGn%R!}6RIfg@YkGt#HZ%XT z*~VM4W8uHt#~m7Fi5G^Hg4a?_J70 zkC5xwyrqF>l2PS^XOQXVE_O2?n@=yZe zl9HN6qb4nBT3c~^*S74~zK>m-VpOXT{mvUklY&$l)GnZSSJV&n6i=#U&9_D&T9I3$ z5iMIDK`t@M_wC@#H>dLX{CSuI`zdNazy=^zE@`<%)T)t5j*jx|J2Uw9`<1M{#ITqsPe;ljUh))#=Jf8nmJup}gPdxF&_-2{RI}4VC*hNWDCJ`43TvEbeJRP%( zV=Rh_9boe0*Z6Vceja`5S(Ywd!<_kx5oM!4fqn2((?Wz@FfoJDc9LrZLPBbKDxMK+ znmRuTpfBFaIW1aAkF%{eX(uA4#s!Dn#qL*tk`w-z{Q zv~Sjk8E?J8{4c-d{)e9=vf)R@y}uC00fn}nyb40fpp0kpq8bO!vnk$`@(qDi`?>n^ zq15So2G2Zy74N?D4!>v@RG5%)keCp5K#TUx)IoS0Cr$gb`7s z<<(@{+T}JTV?0N*{h4K}_r?0=@jW?%p=YtQEd0-QFKmP%qU_)8>{c!LJ zVV4Q&8M~PVW6G zuT6ayNpXlBj3Hv@ZHy3S3^|Y6ZXS-KB1E-EQSExX^}6u+V}nt~2AOt*)YMc&8)9C}nqgJYe(Tw9M=umGj1t?of&>brney_h ztlPMgr(c}FsxRJS#*cd}lQ85`9f|tiajA&F;4{wTsypr?OIH)ap>Cu4gvH8E1jGsM zo22|Dp5Q}yvPrAW?OZlX zxHnf2c|e7ew7+2YPHy`@rZgm}n1}WKuzDovcd#b7ffDEETNfuO6jMAb_a9PzyQPW# z$NxHPI7I~?`AVvPFibdw9mY@m7fK`&0fE}JYyamWYy3mycWC~af_8%Z!Tu5u*Fqdz0hD8vIRHP3KH(JF z9o3Ch-_2#tj89m$d_j^W;&AZOl4{eaU%x(u;R^10_$f|4^FoTUGN{_WgS_kv za}sE&k);z`V^4!+k=mtH5b;=Av7 zchVblJh~mO6ClcoWnUyrW>#GWpL`6D-ghGh$fa@97C5mgGD9A9>lBfim5q~{4x-6O zfrQ_^^q3|dSrh~jMYmP;)dY*8*V^rhjp8_(Bz03Y+AFDpO&s-@rna(#_V0DDOW#woeWi)hykUnC#kQTi!ljZ z&p#9y|6pdr0R_uOB6^~KCL^&y2LZU9xE3pc))rrrg+!>N?DVLRBI-5(E^BUvwxG_HQaG@UTtZJB{BI1i@f1{wm=20Z9bFPD1Le zFns=I{P__Q??_x6jGzC%I8#9qj99^+lcF)&i+|OAF7bMd*q6lH@+T+oe`E1Oi~T1D zKUnNE+qZ7w{PQm0>g%rKoGY*9_~TEeFe{&qZ5lH9?P;8M`EZIit>vgrUAW$hZFkrWX@-^S-E^IF_lhA$R$57hld{<&E6ebIl1p3uDbqC+O=y1 z9y^{7-+7z%?Yi>Bb1%}MZcUV%&N&xe!Z&~Wl;gVhVfu_YTzlI{PVCx_VS@*8$Edrx z_Kv&g*zqV*wF7u~{>HF-`xYinoJL7$Wqb^rj2s^P>lmg@8qX;M2lK_(-`g+@%H{}h zl*^b$|H|4`%jnpl6W8B%FL{N9gp|U#Av`C8!rWRs_+K~i?$kHw-tAbfyXGcJ%gV^F zRmih1Jj2Q#zoU1Lo?L#_4IGT6GW_bxc;)E_=|6A~^B1k=#+&aXKkRXQ_oH}u@>K45 z;w5Sq6cQ$eNHmcGEEJ|ev$h;_Y%hLUw}#FgTg4Yg72iticq*06;DPvQHAr*gsh!{~NQ57utpLCxGuIvv@HqmJ&xZIXz)Nr z-F71*Zy!a+PJQ`#(=XJnnMbD{$J4ZNefsr0kwK>o!x%$YpmW#b>D0D4gZuU8=3DO~ zB4Lc<;)4tO znaXiJPN46A)9Bs%Bzhfx4CkDEI{CTjoP1J$?tf@3C-myaP1jz?9e3Qy3BCIA;OH?_ zM?IRhJCc`P8po?Ij^mi_-MIa(yV<#?1dlWX2Ul4iWltPDW7}=S!Kjc;W~fp@xhNAM zGrtBSZ@-PVUmZ)o-o5#J{z9~qnY48!nc`F!oD3Xn))0(h*hLqze(h?yw(ra>x7|;T zf*OPzhXJP#;o#mKoP1(0UU>O6j_%Wo%P+f#TW`FP9zA;S>*u=w0MI~GO^ zx^fRQXU<^NhHXFuQBWlcr3?_U!J&iQS=nb%w802Obug}hN*KWP&aV}yq#}p?ZD0O@ zH~u99D(c5v#2zS&5b*+~AZp_jdbS<0c)h+dby%Qzdoy2dhqNqEWe?Zz4sT&nb%%qR z{%<+-t-a6)k*YF2cxwW0OnsLK#1)la3rBoK&{u*2J9ymmn~?LrTNONulf9n*TOyi&mOs2`twls6`29y0W3-sqPI>&k%Vo$lw@9goXc5syL>nU_ zM#N~*MvE2^@r;NO@r;qE5i!9v+W24eL_|we>@`M2v^F9pD#qB)wTVg0coGv4qa&h? zC!UCi7ZWi?w2n!nx>Po9+#tJ)cgTjdE2aC1XUH2Ld?pczNgx^j&Jr_5Vmd0uRErMk z6%p~OM2si4*;+g?5;G#AV`9XJ7$ZhU#1kW0w1}w^5l_VLlV@z-jfwfPG7^hMMf-BI zvJo*_#E20S+}Rk3d7kK?9Y!Rkjl=?3c|m>l|DM=(h>6(#n_z4rqQzLT>X?XVF*iDt{v;;_EC4reGiY3YHj?^7!lE;C6I6Mu_t0;zMTDr8PAuU3B+jI zWMZ}&v3=CO+{I`+$BdP0EcjeUMYI;tIw5cEiD*x>vC~y_RE%i*xA8=DRJ1Xojj{7i zM2tivsK6d1+&Onbv6NoRE_I6Gr=DnT!G5KZDOlf{ZLwV-)nNm@@ zM_zm7CHeZNbrKUT#_W?--+UsC8?=_!-kT$3@!8{vNX*Wf;6_Qa(DR?N#4HPDTr55Z zgE=Sh`l5%lJGdrTCqyUu5nq_%H#4$l#~SI?u92K|*$CP1_d6l5_*3nF6tQ#M=wM|{ zYRex}HgDc6k38~-zaJ$vO|-;|)2<%+psZWx_G-pDUR#YpOJUm;)k*kKiZPm+`&FE#pXBm`80(5 zL$+A-5oNDaX|@Y0IImh;jEZxK6d^x#903o?uhaG*6c?%MI6<-!!1(bO1JipbZbq@p zBn?i8I7cRam<;L0)5j*<5f z@p(Y53K34pVxys7W4Py0)*kEdYOh!@ZxFUq{@ku{Erp-L^k6ArzJ7WIx zB^W|zaq&zFS$PHY?>C5cEnBl|>(9J6?ltN(?!fc+j-+nATFjp_n-4$xjwfGvof?gr z(yUp1A3L)=T|4(QNCez8Y{q7rIVGN(TD1S{DztL^xn)qqKnw;OS5WSfL^q0 zUXKIC8yR`$EsT6}GM(Eu#Z@Wf*Qv|EfrDt&pq_7xw&p@33Zoo9cBer}1e*>p1yICr z2#N7?Hv@5xQv)W3R;g&EY<_oLjS9JVe!gj&gF1qz(lJ1a0;Q`FH-(ruq*96PQ7WE; zwd5#+V>HGjvO~qhC8RXURAU?)T-h;E8#B*j&XUKm5J`XgDM zf0qB&d-E%V()efK1X||lL;o*_)oGGW);>-UM{(>~ zHzr~#M5J1@j#)H9EHWnMfZyKW^reJu$ys zO&kI+{_D_Mk}kFoo<*iiQp*y@asQK8yyrUp*Wr}~xRdxtc27iCi9{>nh@IB{`QL{p z4zK0V+LDV-uH8r2yf~_ukcttbD@AmrM0}($B4SVc(J~QT<)eL`7;RCcO8**j*gXz! zgf`kD&xa32@<9F87ftdP64J9cT^y!4wBF#o5q~avN%e_{HhxQEB2s0MM5E)VtbJO3 zOODBvSllnD-AmxD$s+yL*AmZw{lFxDFOEPMUzA2fS4uGZjWH4xk*E<7eL%#->^Cg9 zD-k175!7$=uiFs++agiPf;&uX{>%2xB(U@(^xGWLpTykt`)NFhR9DHepH|5Jl79pV z^u$P&9N4{1EY1po_e7*W-A9?i>=y>#ijD2L3G-^~&(!wEW)}p06|N2xZ zi)k@BBAb5tTFx5OUvhGC4c4TMyWbRk;%hHb| zKPyAVPI_NC&mat>Rbogq0zMRMmu&qzsmwOu~~q+enprdpOS_*il?Gv(Py z?@7$7l+pK$lyt|H2~#FW-$8?9z`%Yo`oY^IoK_^Sy!EkY6O~cdTqez$x0Yp_x5)z| zuaSmDX_B3tD`#GKm8{)SEXBLl$%*Y6%HWG`k^RwXx&D%&l2xOb{Iq(F%zS6Oq~|t} z*QQJt;~kW_Gp0-D_H8A%s7TJg;%eErYu_R0)*n%R6A2Vgj8`ewUwFQ}^zsC$G)Crs zG)elOajxt&0eWv_?~e6ycAukV{<0Mk(Pc9JnR}#r|BGZ_l_!7uXrf$u^#yYN#n;NU zH~+4{&ySaLFCH%2sw1K$DlyMmTTE<^JaF&BGVqj(#q+A=`M=yD zS6?_x%3_{)6+7hA!KcZ$Yd6T0XC9GJBkz#CF;8}F`$3NDHAuc%8;PUSeaLy83AqLe1!yeL?NPZaV>XBX_RAI6YMplgRfr30xb<>HEmV?6)!j6--U3PV_oe?GR2wTJyLi?tIJvV?GIE`MiV6Bz_ZN&D)1my_=F#P7INaAL6mwGU^{+@ z>wt$66rX%8j!%2`iPr%V85c#I2IDiPeG+m) zRN|wi%C_541fG&6&H_&bC!G`^ECFXup+cF6O7X|qW-@V=kgA1n62m6mCv|AUMBqTl ze&&8QhnO)wQlx#Nye~`9AQi0pc{$sPO9*mUBzdfmz^aIkX7YSH1dQ~riHCjxA5v64 z8W%!K80`laS3a^366|vlc%B~i3aIo7*Uo2clel@<&?#{#95OEt<8b+Mx6V|`Cyd*? zv^atMlzmRbN4!mpFoG*$Ik*8=%m=zdBBUF!sEl&rP7m?tGXA%Vjg0u~D0Tq~r0__v z`5bJ<>*UyTJ_Ae)jvu<(Am{*ekNa-B@pk^6;t)eumvGlDH}T15Uvu7-*V5~xeztAK zppc=EfUtAT@e`8?L{d6{}YB;&V^3@W*A0 zxP2toUVAl1G-`nBfN~wQ8%9hFqa6AT8Opj6dEv?D_;T@TDpBaTqlJCS8n$de+g43^ z_x%qzSh|xX%hypwIM4bh0MHcx^(SKRz?P2eLja>#oPJh(|NS-)Rm&be2(pL zA|poJ&h=MZ&X+SkV){q3sUi)7gX<_<9l?#1f~4SS2%9Jn#tA8Y*|40OZn=$??K*P% ztvB=I7qfX_^fOe-p)>s7Uy`0d@rXtvR7Vd|UR}nLjr(ZWxEblhs8z29B_;dVSB_o( zFzi22LAg%l$d*lTRFrN&a`stS`J6Pdw zKDK$rK+GpwD;20O4%*+bMVYuc+i2^RWyGK`6t7&w^~0}YOUVHniX>1@M9?Nd!WZ$) zw~j&ud3wY_C6e#}p}0BL7|$wNzYgl?4eM_C+co?%E|@ zDLXbS<(5&SDLznTRR{qkzT1P+KslR!Udb=T`|N(5v{`z_phX8XaX&JA&<5)*h;j&0 zyV-k|^V6dFY~NpMY5UsvUXBSea&WaM@I)gHcsj=YBS-S-tl30-6Mi6f(FWramW}p_ z=Ei`DVq*JQvg9ZBR|Kkt<9oXK-}Upz8c#63`OD886Q7;dT&}J1paavUpV~?#Gz=vQ z?Z;>Inb+~(#)wT{<~XcfwT4GVKTK6D%KDW*(z9C!)@<446XxyWE?x=aUmVMVrE7@d zo2vbgH+Fnul$C5_@rpH6VZ)_J)gFdlehFVMU+we#b=EN|-?X2~yNK ze*bK`viMja7-NqRdv=+Kgb{@pg*JXJX>AbEY+k#R zlaBAos!iJv<)R4rah3e=K?rD#crh@7a(z02qY!aX%CXN}vX`b~JdoLXmt2`kD zC$~T;)Dnbzw*57LXEbqV6G^0D3rPP-x^+@9!a-+R`vb1)Xues|Jn+vymtyZ&lAb?Jno4e410Tyg1DTzUTa)X&RL zGSvrO!~)__P_r2q4w<*Zw`4kJQlc0Goke*q8QH-eOCC0n*^BNEIh@RezY^z1Bp z9NU?d^FCq4vX!h{yNv-uFQIko4orCERbG8@JSX<(Mc3weY+dpdvuDj?&0bB{*A*~XmDKIi3e zFSBL)EkE-bJAL4(!Smob_D5~PqkEYPFd2?E}?ZWhrKc~Ffkm{y@GK5@%@jPN) zJkvSaxP((O2ssXjM<~U?=qS;c=dXDh#1M8|8%j(${?e^M#c-9zQ8vY?ZBC5Qe;rGc zR!1`If`N!qG-}!sKgW-E_4_%rl5mG;Z907A;y>;VS`&*-cUl2P!?ZC>%T=-Lkn^ zwIfKZl*b>wp9PB+6Ls)|Pg`D4$N|A6DmF%-qqOxJ^L1#~QFsA><(KLM#awpYS*%&R zjwoQ8rQMoCw@G+ zeS5ZY=bd-3x74OaGblg4oZVI=;5&s}93?1;T27#qG#*&xNIVo#B;=A%Srbs36S7=B z$8|6gK_fnJ>VdM^LB!8@YqUqCstOHc=Va5fXAe>`(yfAGqJRO%r7~iu@GQR!(N@_F z5D|&7;IkP#`|MM;oyH=xojP|QJ2wX}-Z~q0MGH8tix9I&jrJ@G?kHmZ*d#)G1TeVW z6qFxiF*gjZi0%gf`Qv!NaoXag7zB?c`*RDuvMF%%w-W0gO(IVV7m$m;a_~d zpn?!U*gV`iIBJOvljHeFj&l4kDoHX)jCMi^w1~Gq;gb}}!$4Sm?aBK8Dhf9gCLDH& zRaaA89VHw}0Y99FU@*qBYm*8gxEK{MU`-;(vT_NIy|%IOsFIezraS`0(1sUEw9!$D z%8E*2QO$v}GL)l8Nlj8u^2l0$h8Hs^%a6>6RVj4meq=ywL;^B$-7K{K<1#k(a-*DSzU<%(o#|puZqgDGE_Jd@$8|(bsfT?R8BknOzyew0iJs1 zIUacMUQ$#3fg%29i`ee7l(^ARJv>Dt5 zMOu0qN>@@+Qh|`d_H8@K$jBr&D-#tzfXQwy&65Z@ifZsoZqS z)ue@79PKgsuTRjv}1*6O%&9s$K@B^30Z!8LSguaLc9MH#nQH`S@PYNy#D44N)N`UQL`39FFcPfN7jieWdP;n<-Gj- z6a2J#GxeLd=aS1Vr%ByRmi@Sh>C--9>(1Te*RIR(;n&iuY= z&K@?5-aU>*r=@c+Qcf75c*|;Deq{pdx9%f5Gm9bTU&^t^9);^@Hn01c@vptc)}6)V z)vC|A=bXdQo!b)_jd85GY4e(8jD2}LH{SCw_430k`)MU#f47<|FFJ!4UU-JZE7noF zZX+(g>IzykIs&7t6NV^7OlyP~X<{hZy^U91n_0rP=Kug807*naRLG`vtH{a9MQe?# z6uWnB;qk|wV(>I4uu#Wl->T+`5lX(4|kGX5qNE+8ILWzKmLd@{UeWNL=djz+S zxQ6stF>g%$fNjN<^y=N0ONaL1q0tYqZu4H6x9-d(mtH`fT6sic9-=)`5w`xajyEPx zW7C$MoY1!~Lx-GA7$H)+m+=!PvUueN8q}@Lbr+qC7mG0By6ecxbGd!g%`|OTpAX-e z%G}Stq23Wqx#Y?#XjH!@8`iGk%}JBkuwyUnI<%*I_a1z=cn#NFejcernL1@6*^S!L zr+07C2u?BzjNzrR&(g9>SB^R6SgK05Gy2I1Tz1)&?B1}HsZ-x4N-C$Gc{ZmE=!=L& zj76*?(f-nd*lpZn{+wC7`@u(~sVbKLyq8Xc93&QD@}%*6{^fV%71iRrORwOlBb(tk znkC2=ivo< z)#H>wC-BURQ@Q@i;nYqmr&42;WFOU3V!(s}g)6amSYip{|M>(5jUp6GR{%#)VhJKU zx31&vyGBsHetk9J2M!AEbuPIUJcmi_oG^%^&!ee0G?eCZ_?ui8wV z8o4-BaqvI|TDfSYFt~)X@~BxOpUE#g!Pb>uFyxG$6y{{39TzX0LFZO2Y1br=dv3gn zDQ#Qv-Q0z=?9!hWEt~NLArw&*f+37?XmO|1Ih?Ys8FqW^q*4ZsfTh?@gUVrJKv?r<_d7 z#`SpUfrq(x*dWHg@+POAI+Wa8KO~t1Vek`lAFFRF-?_~?bBU?o!x`_eYVCUNd*Wuw z%F2lxET?v@98yxVSo!ltR<2lySF)L^ssp5_y2PTIZJXBf)AFB~{Q5M`Kj%W~=KaTg zX#On!jf!I*<$ztIY*5ZW5F1tqqAU60(;57*dK+h-e<5M1=Hd%3WA*Cw7}r6gh#3gE zX&irC4{o~ld^T@f$&0T|LQ5r|&;N$aTPwKy(n|?dmU8BRzU;4zvUKqZ=FFPIS?8Zk z+lE=(ee2Dv*tiW{QN`B_zNRt~qj>!qzWsg~LoT_VX7zHp`r4b>bHHQghUJ`m>M%-T z=?uHzLRS5>imw)YO-urBxP$?=ettS%eEK2F)^0#_6<>ZnhvF&+70#k-_Y)X?&2VBR zn|R{MrzqDt&P8;^uxZ8jEL**f^6E++9CbT0=Y7p7XPk*Em565--OP*(`VH*Q<>wCK z{kJAC{_T&@62?u<;N&3}FygMeIH6k`W=@^JwYNP;*AseElo#gOtFK|prgfB*7W3h! zUvS2mLm1eippw#5ClhAv-Xh7uj8hXchRCz5ew&j#M-UCmMU zPD&;{d-mbFt1f5Fck_64!fPDF<;TT8uyyNt4px_O*X{QaBg`3t2k_cc5Ayl*bqge z2uSZFl#q~+`Xo;~XYcoqbIz0CIQL#>oVoYC*Tv@vDbI7xKD(^7_S(PoTV}X|B}+ad z4(!>!g-^d)MJTTwdHEfWKJ@+inJhL#V z_AMDlVL48!UCZ3rQ&_pHlyTSJ%#eP^5cK)5g^vM)2Qp>q9gMwv44c-k)XO%;d|}n~2nw@!?-SWW)ty8FBh>{8l52 z|MV8MjS&v*+s%tlzraZ&MseoxeVBjG6uw!#9@`2t?T)E@UmWJjYsOI@Zea2I9}$no z_-4gQcJJBeL|Qc+C8NCX_=C)O^m#^&Ih)D@TNroaog{oAPCQ`<3m$xot!pL2DnZTgIkZnj|B z1M`?V?G|=!TE~ZO4O9^ULIBrlAEg2?lix3~VhxAjL0w&e@{~X^@hdMj#L%BQ->7N(zCTHe7Pecv`j2XZqwD3Hki=8F~iu zW>075rq#^5e?BQKav0FF6S*x~aMNuQ2xSC0c<>OHT{n>_w_V4UjcZxGVJicM_M=0G zuCy-b#qa;{3^`eT-h1b5R)4pN#+nHJW?JFr7vVxSoYN5{3_Lgy7@RZqD)QU3WYmb$ z*wjeX-hEigM|O5=PCW5sMxWA)6{|N>Tv|@Y0;hDB1HX~v7j)u;69+J? zXC`ldyort9ZKiJT654br;@)|)$kG+>zV&B>ooJ@)!1Dz4%ru4%Kb18rH*k92d{(di zmUC`64IyGE8E5OZJ+#Wr;;XHPX^;}>0qb2XkQ8v>P&vEy9ORFS7L%Xjqg%TcytDE_ zl!_trIN@lF{pI`V(Y-sRhiZ_PKTj%J+x%BClN16-cX;Jp=+riG=r5tnY36vD?BQrCbH{Mu8tFdF)v+p3k zf9F#QT4&+28>l?A30rBj@6wH~ZETFlA>MxFHO5bz!SFLqVPKy^eskdktXRF4I04$W zFXZG?hGU2XRwPVbN}RnVJIHC3M}$-g3)o$)a%u-R7CXis!K$UpXy36D*N(rM+<@fJ!7#tOe+Dl+ zcQ;x}27``2o#T6C5Ur|Z@n=h^kB`UjnF!4}Jkn5Tx=zdNY{Y>wV$m9o8+IaopNW(@ z8JRg0b?Zhz)Ux>XC1mHeqqeRVEn$(Cmd>hG-?1f9L1Q?AX$tn1SCEq4g3X(EGbA^U z?7Y?tI<7ArvofgIvd%fOQV`JmWTb=`di;rW&9T|={WiAkJWT%_NqJ>8b02z&Zn)p?L918mcI}_U^=1I))u*?S}8LJ?yRYGjYn@ z+;rD{&X3U=zFfM5(jyUv*2Mt{P}D7(sF6v#4n6qm`>)ZdAdk3m2%v-xS*^S9;;XNs zFx>PQFp*4~J)dc_A9C=tnoF`Jvp85*=2TZwiZK^o&X|iYLux)8`X9l8gS)UaXTA?S z?qt6D@^qx;Z%Uj~I(N@}fIDZI=t7~%C?%yOU`JT|=U1t3ln%MMJIC`{=d*A3X8yGJ zYdZHjmeWoiiccj-$!W*Ci{Ew10&0%#ynfQ1Tz|_{61od}5I(NIE3Fn!Kkq-HwTbVq2=iKp?|7pFT3heEi}oueSo{}OTLK{Lv4 z;b2iiX*tY!@KI*YdlaR)^HwFeXZAcS5kMdaWashfTd$)uBT3|(JP6h_?!9*gsG~_+ zq=I21&*J#e=VA#BAA)(0Jj1*N&*9BeC7c+%t|BaW;z<@f@d9zBAq413QP8<7%U7+z zbNjSpve_@GA^%s!Kr|t1yoxkGrf7dQNhXA7SkjrW=mwqgvZ$-6MwtPWoj?;&K6v{r z{fW6yHdwotrIyE%i!X( zh9h(XW!YdD2%$MUKnW@#sjUl>-=RIOIU+ABop3{hMtoSB-;JEeBu>k7Xq|sH4kvw6 zX0;Fow(aH*D~p8-=JWZt-*M(eS7HYISdqA+G^9XaQB_rj?(>u1rai%+!ByjLC%a=; z8pDS%f~jQZWVqKApgTk#E~LJqjC=2zOkw}y zY2UU3LiZ7k+obulWEngMQ|92{%B#a1+q)mS4pzo{_%Zjn>gu|nz8Aw~uAuAIZsl%2w7AA(9 zb*vB|LR@v@t+f5-+*tEFOOBS-STf z!jjjXBQrHb+x$ENhTyjoZlOo-zKHlvY~@7Wl^5~GiSkHWL*R2QX@a!O3=)>4vZ{_y zS~|gC5U|j(5tc)As2fft3Qc$BSv(OX(imYt#{%*Ty3($7dmbKgCT;Sv5r(8qZiqbx z_F<;yU_z_Y%xKnq$yjfzxq&#l+9yF8w(F^&?PK4Ju4eYKnxIr+?c z@?pAkXzlPzD(~phO;pni2MZ~{l(@K44X?FMGLVBfluCf`W8m<@I>|l`23u=3vX+z> zn$J;lI5=uMkw7<&uJ-iviepK0 z%D>3}QSsI)Ha42jJoMYYP#jdcP!J6_P+MJ1w4s8P+YfNwWuq_?QGBuytFfB(>o?Hz zgfkd@?zyCYwVeI?%TX>VvZ*w@^&||#QNFs4tvjT}PG+1$mmqD0ra4ZdM4$|(mZ{P} zHyylQL5Hqvd1n!&rDfP5gZjnRMJGh=UTO_(N2dRuXGyAfW4X?$M2pKl+#x26QJJt7qM=a)zEY z96xackWgUB7_n%Wt;IDIcIiU8-$bDB`3zEmJ`No`KwVuIOw&e6&+!5wZ9ZSVp8hAC z#+Y+{&4x@r`#<{HIX*Qs6hS()>rQ%5r%Pc0UAuROM1oLeI%Ruf*pW(>e)A23`}HL# zBWRjV$Y-#3^Jek`tw}c|g+05nX~Skt>RZIl?Zq6b)#=~6E2~$o$3`ZzTZIq|IB_U% zPPw0bngJB7dnyzA@c(Z z?alROF0KGgH=5exL01H5y0bnE(ab4wFK3uqv(I=`N6uB7-_mm&MQR(q-&+a7Y`Vx% zE%UZx&Hw5;>Pbq5rZ#9vdZnfuZqMn~lO*)QbzYs%cpvvZVQ5WwZBG~IK8KLJ`I!H_ z1rVGL7SeXf$h~1|_S6D*j;LhAh0v29_W+j8x@y*6!rffZY}lJc3X|gn&HBR`FQ3so z8%9t5-S|OB)cLU~$|!`xSO7nLo%|yI|BK;FCU4i=?AY^PCCOc^WaIjk+;G!m?AlT~ zbv=gTj~_vHnn`XteE64-IsKfAx&Of@7`OIwYQr(w6%;v&RnxF!#GT!;SENN z8c7^KLMgIZwqpFm2|WDt?|AD)lSo4Yty|}jnw8D-8y6@I8 z`m&q({L|0q*R?$;9WAvbmtS)OFFd}0_ug5|jaOZSt@#j%sIxB@I@e!+4G%xLkhR}` zk6m9!+aCQ10wQ4}?Ety0I&krYXLH~5>G)EzNKen?fk)=hwp~XiOqj?Mb7%2VY7SZH zY0R26i8Du>%KW=;=Cuy3x%sBcxqjlU%$xTF*M9K<30vc$tH;x$QwP3Zxe_U(jzLs_ zFzDWQD4jZV;H%F+F5|DbhF;wZxqs@_PCP?Ox(*t`fC1k!{r1WD zWt7yMcHBGbUWBN?z`_(U6zSN)#FiR{bcr{V=fF4_=dZo^JYTNdfUx4UY1f&)-3m$T zn8gQ+-(mc<*HGBC7n5(ehRy5NGvV56@CP%=X_?FXhvqQo)Kj_S@=KXL?M}=qP5S*LmpUQ2w+{xKj-Nv~W zoI!o~2roYW0)6hdlzSRcK_oJgc8lDuw0(bq=P1!MHzpQ zpId(D%=|}V_#ZhwfA4eQa2QPpcJ12rk2Uarm`EvIinL$mb8AM|^lo*Ci zz~@7^t7%O55Jmu>-9StWqMHUjJAxI7Ve0{65-@erO%N(dJgy<7z!Dm!Y2w!nkP+hX zIC0yD;WzQ=7Ag_PiUXR@p};Y~RyOgt!sqj02pcIaYGM+K}0Utq4V#R8(Y(G->qx(z(B(SB8ZR_~`K9Cj;H=xGv zpM8PlE7$Pov(LIE)I>6Nprnfh(iK8Qh(;n?a2px=+FqQnz1=XlKs z5Hu4+6AEdj5Y#l3<&2vWKBQ^lHw+9FrY@?XnL$!?fwF88i5ObQk1q*AaF0k;j6^g- z0zV0Kbi*KI>S$IYG212~4dR+Xy5EFY9r37*G((_km_9$Ih=WWJk4tQ+qjVjg;lm_C z%u)zn2tx=oJ5Hpb7LnQlQ%VwzQS_7)OscUgfzmVa88*_25>MD9Y?wCZS<+gx=Dx|7 z5RF?X-Na`YPBaUNz#<+AV_6Dm1hEa16b-Cs7=r2ev^dI^#4Q7(W-F(keF<}3c!zEs z+7s{@Xr@U(fU+AWTyI)+MM#o|N_KdGjPu;av|aYQHuO$dkbpn2E`$IvGd3AS(F zPC>zsQ(|n~xRGJQh5=AfQNf}`i>RomNJavGnz*M1Nwwz@Be{^2f1pI?e-@?rXASsI zi2^k*Gx}4n`;WBqzv8H=AN1)DfBr}0?|oJ&g=JZ2nwFd&|7a4@{{(3s4IDjsGy?_< z_-}5}FY>Px&*5LOVub^;@S@g2=*>_F{~~ci;SvMg--2K;Kq?$nzt$JZ#&o&CL?DO~ z;Kz%M=$Jl%&y8IoLimF|m$=nL8E(Z`BLzPW-U&U004`wGmqNhh=Mo}-&(si_qVnJ# zo_zKtbYBXGD{BZh*qnUg34Hna2OKJINOBH>qHX)m3>|tbhOY$~qFFd!58=~we5PZ7 zk{r@{Iw9SO2xvx%1H{Be=q7q<0HrhnILFu?-AN#zV@W|!YZm_3`~(6f0St%y7lG#Y zWBOdBCjcD$QNZt!2kQu-lM(c6qLZYe(9!*=1eC&$!!4$1Y3QPf|4aC?@B_Ypj=*Bq zwspMu`Xct##p&FmyTfH@1PSPl!SnE3j$7u#AMz*1JOSuh0G|Q=$hP<6P3&%RhjLiv-J zPhl7g8$O)8tW1Kz0JhLvUgsc&=EE>`5Z=8NC<9+04bwd?F^p8FxynG-4T3=}iG6ag zI$-)jm`V^3O@}iI$MNy`3~Z?o!XW5(nZ9HKT{8%V0$$A0CFS;$8gzLkk!YrlZW?Ua zw2JRH7P}6vbGQ~v&*F@cXAsnd<6z^AGe!Wvq2WVIW<%<}3=E%e$(_B}zKPH@0s%nj zNEbW~LHs&RAbZ^)nBKxY8a6P}(%h4;3`~cU0y|pEAD(-GgVhnDjg9QyUCpd{*J2BU zfZsjF!mB<4pkW3xoSM?f-zfByG#s`?4NWr%`aqgG!Z6W&LDEx0&T&1iGpq;k2ff2s zAHIMO)ARE*AN~}dOENB+ornJ8;?*plK7IN>ah0PTh@_7D88~d3KVH(&{4Y9NKjx_X zR7dHbi5mS>N9iAF+s`F`@7^UPCA|Ln>)dh29m%=!zd;r+Ui{zPgkR*}EQYsSG>

zX8=?GN1_0X6wbf=CWgoT1aMAoo8S{p3Wr0C>qg*kvY0#*;-OE3`+k&;hn;c`(;P&Z z1JYJU86So7Ugv2IoSIgWl+0Yt96g4*a2V4JFtJk+ZF5_&Ib1=)swG(_1V~Rybul2` zeLauQp!tv9Be~FMJk#4`Al)hvLLrp!TvH?l8UkH3m2Pw1=M|fh&5rL?lKj}~8OQyw zQ7+@0aT` zO1mp3DaAV`^RQ6@Z>T-E0B**wNp8n(oM5)(k}C_zZJmxQWf=+F7-L;U6^CHmPach#JGk=wvovE6&{h!xk-dy&sBt6~Jygj06gp=## z$NUh{?3<)R=%VO;P~Oj3&#t~`R^3y&eWGa6G0D+P-q?k&c)AE&ZQ#uzk^KGNZR>v~ zO$_->EogR~q-t*F?;fRhyeXwM;Sm2eox3?m$tx+S9resV-n4(6{rW|Ik^gOCI8h0= z{1))9bO6D@9%x#S4xM|_PP&_7&C>@q(zdBJ(tvNu<7?v>pCy<9QRi9O1_ zauunC!oWsHbB&KD!i_ElQ?eL1XfO)frRMM>fc^uHb<2sk4OPOe!r(O|ECFoR6aU(=|jiP&8y5QGBR3n>ZxZSo3&G7xmmT|xFlnKBptYB zk7ijG;c%F=tPC`q5`dOl7BJ}usTh%H0?Z%*_n0$z$7El5W8*%HvT-sjMKfPSCfm^5 zrASU5Cwxt(&OPbexo4C0RPNKb*A>F63GIP41V>};CDM*i+mOJYnu%X)R)Iu_A8bXM zoCwe95GZU6oQ;x~s^DH-XeeP))cY8^yT463$;lOWv^b9*B^*hh2Q%<#&1)ifn<)40 zz6=Ho9Gc9GY;s+7w~S)5!TTHe;nO4^`tN<WP!P#}d{G|9bqa(Vyg^SE=S*@Fvj!vC$`oh&(kUgqN7-9D!>BCuzp%lBV`4@4Fv%j`Mp#)5fN0 zbMT+Y-^`bvXHI~-_M6RKFJt|vOk3~%KUP*$;O%mowddz+-!Jlu{8z)}<*){w(z5dP?qeo2l>W(qi6v z<2C9V8@*Pz|9iwNu7jimLg^ToN$1Ha4=0m$8ezL7-IAA2?#i87$2NG*odT3((eIz( zgAYCc1ws10#FmP$mww8pOTQ%H8gl0XF-nWKGXA#dlvg(%z0-9a2%#cWRhCj+-{6$F zqp6N6o`F=jkvu0Zif0Z~Qwc(^ZB~qf2TF-V-SJUgc`>^wH?Wxl?Wsep`L15Wsn;n0 zU2hr_S9CY>Q;DEytJmD*Xefl$$fDO? za(Kj~&Ee8RRM$5qM-`lX!co0&)I{~>q{ElyBvd6xR3G5JS+m$zQ{%el%8m5lj+ZlL zx@MwjhBJSaPPnR?KRmaP{iRMndI8)YebGE>)YRU8R=iDG(=NxRrg$qi-f#n-ui8jm zZ8-}UE@b1D-Jm3;`*ySN$;X&I_W}O=(Z@vMF_wS1g!vCXz{8I}$<70Zlk>}4$6i$t zr+l1r9dM^}6$;BmY&UmvoA-3`!IdO@q?D(hdXn$A?g13x`a0^vF}I#@j3X5#JpI%{ zcI`Rf-rsvQX*_piA^DDGzw+K7o9_9;&6`rn-LSdIFz#?@!dqBQ!xc6OJ3(1hn3!zl zJxQD$pYm!pIS2TKM({QNv~)iThiKAeA8X>G zlFFsy!3{n}sXMZl$&;s1QsolO3c$7;!-sM=BJQ}@(p8?aY0kKIQb!=9mNbygC`c#1 zcGQmBOK_41rJ4+;+iOBVV?!MW_7!7G2-i38!TTRj-xx-^{pCa_671NygUYIUk|xF5 zFbTkp@y(LO%zNl@qQc#qD8<*yzT)r^$LX<^aQNT6D4>o*!6ICW79o=kj&Mg$B`e4_ zH_q;y64HrCDRs2Ha3Kqccmw+n9K_b$KP#u&hEq;Vy0g=ZlDkK>3Y3(rSoQ^bcJGGB z5pKF}ET64fk3*U6xgk#9=qNXO>ioW0$^)Joqr7#Q2(xYTW~_wm>KGRia8%=6_=h{L zQrJWy4Sey*5~^zI9G~C^PXE#J!+hYQfBHwo@g*FCu9OqK3?DA#!*}23KzSXzwr%E~ zyYA+Nm*1qJdJlI@n#9CO_pso1kF$K)5;m+~!OCXhaYoj=Ng6`e;luU@U^>{h_hz- zXWV|n}Izct{ zsZnVfg&b(ECXl29u7nWl>f1TmI<@(#WF4dst-{{>q!li94vF>+?j(SDR` z6TH{Yy*Uur2#;@7McKV!4cA_E89jUS=CspB@y@$ThzbE(n6=-0!cCKA(in}QtOgdn z`T_$_9?i}}^$sUuvkEo8L;`=2f2SBfB#Qi3<0*ua2y80K%GkbVKhbE6P%ub`?mfuO z(y@`)%H27|V{F{8j;h*5QZw@??B0XSpib4{a(3+6OEeb42&7TeyEiS;Lxigiv17+J zY8xen>7z?wS6b)hlHEF&u~%J5C=?=IU&-bz+o^7d6EF?h6&BGpFB@IN30K#$b^C7W z8lw38DHL|?Om53;n($-*HsR_rHg4HL&w(e9=7%Fkswh2NOYg3o*|cdLhpTD`rDW2r zsEDkzAW}NT=Fv1pj69V(JsVKOBQ1uGh6%jVr2si`3)Jw!p< z0=DitK>z;z$V~C083wwHQ-9P6rb#BAzH7lrV zh?Aa~M`2Mn(n1CoTyzm>IjvDj60Wac`;NWTg=6IB7tpz|6Pl*5qV;UqzL&Bi^<<=) zbZVujtSDpImtV0zS1_=DFVa&}*t2~%2M!z{l$JxM9zDrQ4bV_m#jc$@sj3T;)he5o zx%pI7)=|{8GXWiTZ{32HmQCAst=)qyk=*%j-?WbOR;|g&&4XAKYrfx2QBf}()Kk(xRY4 z7xLS+MI^%P+Eq;X;R>XkAiY&vx^?SL$n=h^n_`$UQOk-I-_p6)P+DfCkcc+0ZA%Hg zdUYY%7-8#fVF2v>-b+uBBsPPf}BZ z#2RW@wq^?hdlxa`)>~-PKEH`s>R+mzeq4mmQ1M!J?%GRfc@^P(yNO8+DWOwgdoI25 zO3wcEMU)-b&W7*TaqRIYF=fhabn8;UUq5)CiX*i={?ya7?bMNuT{_^oHoC4kXAvq! zX~|xS_gB&wi{T5U)48x4xver0M3J#Nwr$x%MNODMYC478dyt*#L&n2w*|d|2BXx*S zDn&gC>D|8%mtTGX!%jH`VV6_3Z#V1Lu4PFpAHBNgFl5*XTr=*soHYCdq>_Yd%Gk1f z8x2uKR!$qb6crKF5>%D$WADC0G(_S^%^<&XA?@<>nvU}|&)c$Ts3~XF+U<1d)t`b^ z8I%j1l*ReC*+GUWaKf=L1JJ_&(Enj?|O_yGM2*exNwRJn4j~PJAG{LHG zSJARv5#2lHa`-?AyNk<+NkPl}wsh*;!A;Kd;;H|*IQxAM18ae@*t>BfH(WoF6GooR zWmjKE$==<}y7w;DZ{NdRxBi+$tcLQcYV25?PnLYZYk&HHXMg`Z`E4>#9@D(?HqF1t zFY@mbiG6*PmwL+g~&M)ZrBG+<_Iy=8*?(!EZDzgm^5%x)sYPuW8_$ z4F@=F)CEi!dj=o8`zDJPEusJ5V_Cm_Hz}DpEPUc&R(!sMS+k~d+*ub>QCd!8LSz0z z^T`VD=l)r9nfLsQlx_K%>C@-aYuH&-lx*XOmCCaVA14?&z@3xsq9G3L3%l{rr>nSX z+*p1)?oxCGS~9EDCSFy-O;=yW?-qT|alKmc!TW#W`{D=>-7}u=SANNX%0|9hyPbZ= zpUkZjuW=(Z5}|Aszy3U>W>0RLbQP~I{2i~n_ZcS)8N~j*#mKmYArr*HhgtUdUx~#m zmVC92iPP@myi?mDWrBkx`&l2#At%F6ZP`|)&iEaLU5lu$twn^gnSb9zWJ3j0Cf&v{ z#}1{SeJ*7O_cM0l{e1SxU+CAhwKEEu#8Q$SJ9iKhDRk}Bk@X+F%lDks-N^ZuU&57_p3k$7J;rgTk7UH?Q9SX;Yz`c*BQ>)v8#eCXzK0jk zvwaI*ec}<`{%8d~2A)KE$YA`XCt%A6TQ{wvt}KNfUE8o>?YAsg@GQN06|rMq8Ev~1 zF=yr-eEr3zJUVAC$Bz6Jow|3TsF!5s?B{v$x%p%oiUqUp<+O2=$Zgl!!2n8Ei3*Dk zUU?qbx{&K`naH7C-!XpD{VaNWF-LZ8WYvnbl$1x$XU$~Xw7Fz=ZOP23lc|#-GBbi~*?X7==RH6{MvU8Un@F1u-N{T1@X6O3 zxb^nix#ZU)+<2kx+65bxsAk4pH*wZ=bGhM)Q55gl#_V~|@zOK*GVlJ`91iS@b+6T5;EOX z1?3(gswlsI`bpk-|0DVi8A{E;ErjDXntRk3#)(|o+ z8bk<97lf-0@y=_nkl*Ea+71n3+cs;~uHo8ozvYhG#uII5q#+vR&M9}&reiOjeeo&s zx^{3bE}f%(>{_0GkJ}3Z@w@4F@%(FlCSq%3<+S1I$#--6xU>25A0A`ILw_WuBz2JlgHJk_ zCl)?Tj}CcGFfs`-NKjY4jVpe08JA3)&74W+@zjF(Jo(Hkyt3$J?w$20Qc50qa4NIz znZeHDy%-s}oHpiio}D!wVJXV?ZDs1@skCdG!`rXSW$Kh$*|1>`bx}pzu0wg{4-YwO z+-_je%P;W3`>!+SiRZ9OHZpm_WFCF%BS!Xa!6j#(&985n$J~kMaLd>W`Fc}1{*2a~ z_^VOOoj;vWz~{uQe};N;-ocN+Mp}(byZZr#oO~t|r%WZyXP}+jpTWm;W9*Idxa91C zSV)v?xvZ{m*c7po)8anqo zmT9wRkR}scdC_I8T>dFTPB|IjoOlpQP3O|9$0LC*pMTHW?=5A**psM@*bEqUCNuAy zz@DwE8GPLF?3i*pM;at8a@sOu#!OOGHD{kcj;(w5aeOP`g5w3zs7>3#W4LF=okR~8 zGy1}bY+AdCXz4P(-d4uv%f6yzKvG$LBhkj{<_XGp8KEuOwV_v^9;{ink)b_LVfDA) zaO{|C5klv}E3U$}bhdoIjycc&nR;m>F%Zhhg4Lu15|kb~%%9);oM&Hpov!V3*u8NL zqsBgfRD#UxJZ_yl1!+aeZ1n~!R&Hd>NgXkK>5Mw}EG`;xDrU5jD=)o`ekWbXv?(_e zvg2HF$z`lvyPS4~T?w`B#+19Jk(rSKx}b8*g^tltfN;t(*&3X4*<}nH+>eYzn6JZ? z3_AW)CQZAUbY-DgRa|}J4cOApfKNW--KF0$=7KQ@eE9VURaN^~wSF&;KK?WT4UgeC#;ZZrM&60$V!A#Xf1_mvIy} zPrtB;)SS*d`PgIV<`ItEJPU-vGy{zJ^@UirVCRA=yEb`)1zHBlq6JgL5ZwxZY;U4O2O;D4$LbE#Q+sy~~uD#g1Wi#KeU(X{izD?`Qbf!P>I3Itq zg3CvCM!6W!O{>3T`FGoR`>&sq?YCI+r$6$$C+9Hqq+^-+z_au}?hJ08d<#BJV8lu> zR03T|kO_2ufV0jU&8X9dks7Jui?>?w#@ip#Z|c=7`|?YM3>`sgz(^hhJE4pQ%J=Qy z{-@vMnHOJU_;Fo`mv7?yYwtn`#al1GM&I83xq89`O84*Lk{hN|QxE-mcjo=Se#(f` zj$_qVpL6ONCz6#NqA7Fwzbi@-BU*oe2j@Ob0~vh2@(c9C>p1DGaU`q+ShnNH`E;Z( zut?#eao6$OgSVmEhgop{0y1+uvu5*ZT4o0EYHcVtTVJ@F%Zln+TDI%MM<2ey&b3Rq z;)-i|df`wm89j)npIStV&iz>a<_kPB{dS&z^;Iq&J&2D#|BMDb#G7v~rf2Ui=(uzdbVs@$BQq&%e8mRWWqHUFz$kL_}%PB zIQP`SR8&?%dM=CKTu5#4R?Z(glZ{(;(78h%DQ-5ma`CMhZQ9VkPj42#@g|clKY=w{ z572ec2u>M(I(v2>!mli3Z8>Wh@s178EHq`Ldy4{?A&26OmOq8+_7!>vFL#q^x zin9GARGj6XeaNy;m-5%oKB7nOPDda7ddYSF4I7PSS+HQW{Yp6i}px{6uPNDBo91zd?Ez z<~aiC8N@0MpyzgTLEi#RB`7H=X5Hok+&N_?K|O|&HhqQ-q`s<}l#~|ackJj|JR2n? zQW;L6dlg5;8Yta&kes|c1dx}VPV4j_+xPAwrt3tL8H|d6VKTH=8&)p=nC|_CliIo$ zS!rpQ$p|2BR-PcgM>pzfKIC9&6>Ha)aQ29iB zIF#(%M_%i8=z$<;3A%Ub#3%2)jfyuowQfZKQ1t3jz-P-pCu-TGnoTaCljM`iIp_U` zcdnnsp*?$f|1Y01`kE<}6mMtimIK^*_bk%1ILIK!4?NcM^wAX5RF=`YeHY9WXI>9I zrjQ5gt0}LlX2aIKoOSN6-E0pVG=&mQ$u&)A7)nPED z+&O8aV}xxBT{oN!o)T179wv@Sey45@*|&_LyK8C7)}0)vsAkoUVgf2o&n|7zWi5kG z7|g=SkFsk|IUBZ?F#ewTXv#)m{{RT+;zT6~&CLLJ@n22i9aXvjwSP(!;o4eiYa+DF z>q%~YI}(kX(Urn9O*a_~Y-u}sh5!-ebCR5B#MEpwJ&301?xw|YR?t970k%VjrIbSH z0i+Q0>eYoVZCbH@-Fi+NT1ahun6rkDB0W3Em@`k}(La90zOpb^Tz3l_cizLVN1np* zr~QiCrcNWzmRJ@jDL^w3dI0<>SSUA^#QhOGivO3=S=cTx;RU0s8l9Ocvj7n%mbMbnEXbCCKjBjj`je=A}O@Z4H%UjQtNZaw=@ z*rfwAr{BTU>Gv_9Uy*YSDKY*RaSi?=|9^>=1lLOSpS<Ppnw*&(k$t+3fWFBa?%VMT%7kKZyM+plXj)TZhtL&<4z^{HnvubQ-P;fr2%%$ZCQ5S+yJ+I&a%wWBFm%{SM9OyZ5R zzVH}2wQ0qNZ@orV%Um9O{0S!AIhoA#6a)(0Xv&5Jfe;31p&(YYp3;4L0I;P)i;<|W z;IRkqXY@svG5_f&x%A?TKuH(Gtss#=0m0N3Was3vedBr;`7GE|T26MWR%lY9*{)p_ zHbPiV!hoCYpy>j`(9sddh?g;KqNLUo6;|;0<4@7I-yj};>E!0-Iz49wu_6tQldn6WV3rV%F6eXh&xWxhMgt&Qc}rEPosU? zZ2lj6=N%0^Kb@um1Rdx5EZ@9sG-}PPhS~JsAUE!oU=Q%q(d*_ZVDDeV2 z+_dsaf$7Jm3~YCNh)Sea|6|EY2=naIFOXQjF>PBma{a?h7mFD{BAHnQB&Z0#Z1~32 zeER`ECW_*cV)_l}%|o+iGy9Pzc=W-0Db35KRof2ar~7zf&g0n0MYL<#lmz8cieNgl zD%#_kv_W}+M9TRe!NS>O#z5fTFHSVQ0(>N=WKl08h5fsKV%wIVv9u2hXWl>=4*2x~ zM|=UaVW5?O&(TmTWnhSk#z8x=xVHN)0-`arg-8fQ*t_olyUPzzTH1hm>1m`UCG*v1 zE2uhB%g3v}Br!3Wtn7T6G;PkyFV5wO2WRl%;x~Ee)wi+n;qw_NBY=?*#59F%TQ<2d zL_Wf<{z+p{P*g;Msrh8dJ5(O7Wc?32@CE&3=hnkC3@2Dw`4H0p+X)U+fE@+kfZ@mR zWiV(^AM%q;ZomC*tY9)jhxfw{*YM2Tr+DhQ=Lw|N=k7bF^2RHV5u}=%Z<)#V12y;( z{Di9yP;ulig3Xtotzz>}JDK(HQ`|7=I)XtzwrCO)lQ4}4hxhD8+XfLMnZ(pA3}Dyx zUx;85HUUEs#$?>YtNHMq`83YU;{I8Wuw`#K5s71D_(#SDxNMpV2#}DN!Kk6f@adAp z9I32|zDuvY@fzVkB1I)-DD9(uQDg4B<0j5Lr7t&Kdp$e%IZO`@#g>i*di@)Nga71M z{Ld4g$NVntj`|NB1P=Z}#Ni-Y`^oz}a$gAtw{KzXwhG4d9zs?^B9W?HtX=ypjazl$ zg$3{MYM#l@zwX2K1+kRhRcnRa2utU_F1B-jG>RBco47#(F|(EXo++QRSepU*3_6jA zpL&ByS6)H0mM!`4({E|eq9fuN5L`2=lX5MIdg&Q7D@x(+XXmqE(c2`Ons%+q_~6lJ zdF8cN2p!x>#D)Y>WM`%E=7&o;{^VgU9Rw5<w-e#*-au``rR z`*uAE)mGxguOU@@wtNZ4pLG)-eDon5o8+VLVWg(hu1kBKc<2E(Zr(=!j*XlZ$_vpI zgYMnh@$ssqWasCxZ|hbhAqlM%7y)WYp|GHo_GKwtKj|uZ4j4jpjm@ZYMpD+SA$|L` zXY6^SIO*ik5DGDB)Cn{zuFrjw#?ZHaKaLsLm9x%2k2!PhCA9Nr)~ww?UYld+*19df zZuk+?h>@2o!=Qb){#bWC#*0tP;r^$e#WX=_L6o4qDOn}pGwU((#6g^N$|#P%cpCK! z3a}2;k{qbz$+?fvpty|fhr(c*H&OeQdM~~pfN!Qc5 zNeLUb?4?hFkHWkHc5M5RH(q}YvuYoq8conp6f|ta_Dzp*{~fa_D$eHYA#Jb>hh?u@ z->%s6=5XIF)5y=v;O(WKGHdpID0K+5V~%z<7%CdI>y6MT8=5#EcW}Rsj2?Fvm)>wI zh3Sbj?9!ShO>&rd^CWup>rL49GwSrek`PEGNi;7$`5fn+)1L-;3z&HEnY3-+o~K`2 z#D$k!MoCr{QzndJ(&Sq?Tw6uG>^ugv&v$g5h9JHmow{}9)#v81cYh_Vo0l@US8Jw@ z8^!tKXE1KsLj?V9)M|W&4kJizgO*%*_E7G&gB;lXT#dh znKv^~gQ%b4XUF=_xPRvD)T$td z4({aMnfDS5CUKymmIiGGkd~Uo$tMnB`P7Fvp?80Ri3v=fegRo&37mJva8i?l*hT`0 zNm(>+(}vECGnhMb3UeQRfbmnNGve5RG%79R{wY`U&}{})ksv|8$&O9yIOVv(NNOJY z58Jfs+J|5;7~LBDQ!-+S<8>?IWUHER<7J$G;iZhf_&hpv>%_KSw(;(JpD^XF`^YcK zX3I}DwqX)TsK+NohX)2ObO9`2E5UKkuh?n>O_5+y>KGiCsc_ zXZkk$e)5YO(6&=ojvdsWfC&v6HzlW_nEeM1k(`vwph1IZR9Z@DX$ir^6iQ1Pke!oF zNu#Ee6c*66a~H}QH>aYqn)J*ph7BJ^%Vv$}H(($MiD?`%A|F>wsh^< zgCvkfeY$s|q_mhuO`5WQe>pxg zfnx>^q(#%lQwVVgi8fpg9~mv*gN z;x~L`XXn$tO*7JxoLta_C8acL+6`$ zNJ>uUNJS;Nxp_2e+LZLvG@3MRNhnlJhmM^X(6286zaPZUh%-ksbja}p4I#fck9O@l zQdwC;z)&=8(uCsDX0&e8fr7j|I&|nvLV}-2q=x2A%E-^IM}xdHmaYDp^DeuT!mM9spN^fnQe9nxflyXfMuVb!OcX`M zg_JgK%7DQG$V^SaFoevUJleKxM`~gMS@rAFzDp1Cvoi_!{M64Ypjq?A1pEO~($ZEeM** z2_%T-X?I*h&>`M@a}nE)_!xi9cupNMgt3=jPP^tM1OtA$^yp59&K>C9qc5k8IFn1q zUPwW`RC06kXxg?j-Fx@ryz|fFgcAmml9Wh6gA#gl??Q254xKu6p-r21^zGM|UcGxz zSWrY^aS=Uwbfd5!kKVny)3$AU`VJVx+2>!t`R9xz$>;cEw`kvyZk^hbkyekK`~rIS z>Ox`tESHW6L^*XaFu}0+@rNH-`TbtTT{nR?jT?}jl1#(0<_tdWFZAfqgBGpY(ymh% zP8~LktF9bFaZV=f+IFN}yY_VI)R_}cJdq(M4WU<$-n44jl8#-was2S14DQ#Rk_Lqg z7%+eqt=iImz(9KR?m?@T%^7@bFWR>2MDIR*8FtzTjvqXLqTDn}8#km)r=FZ}^2wZk z{#i6C$|vAv_4#KkZ-);b=DY8{rB|Noixojh{g8o}KY4 zMZlj(K|wK18_-WIw9l?YYit=;G$x4s%&PrT%ntz9E-n^OA)Km%z3jU3y_*4EB zqLgCCjvXj*?ZHuv;2#YFwGC3i-P0zqYFCgaAHSDW;#l;FQd7CQECKDA9w6$}5#oykqwzrbZ;f;e&g5>)mCPmKO8V=I^-n=0|yT{)_bP)|$AdI#r0) zMWSTJUYVl`kveBaJxBnDwAkU*^Z0ojrhi<&GA|oMjHnjZENDa%ayi#K6R{Fkf28Vi z>Fa3AfO0b#h?_{yh=L18gAoN%Q4U0xV-LYgTXp2nF4lgrhDp;N;J*9srcB>s;^+YxLf_>2G^gJm>%NPJx&E?Y|Mczj*JYg%{2X}4jN zH$H6lTz3qr-{U9~bR%>C*>*^73-#&!5kjOD=U@K_9M5iH(7Qtp$|n`hR&1FVT+C0ER=CV~aB; zD-Z1E`U#h@a@_`p*-|T%1UYx)NqoIw6U)EZ&!V@UrD;KSbOvx7dR<~+oTzaxb(}MH zV>NX`&^$J8H*1X+Y|;2kNB?EJxvYQF&+Z`e-V0kCbF~?D8@I8m_A+ePaJKEQb>0ml zf>xStU3;WMok#I*eGd2#E zal}TQ7u!IA*qEOAU3orE%3XksDDaKlBc|2xrVf2nO^$-hQPJ^JiI{O0NQ~!7B-)k^ zsPJlF#sHez?mz$Z6EDB~3Kw5-8SUD&bru}KDYpVaW%JfT`&|~+j>afO%Qk{@hKj422PD--E*Oi)3u+ zHhezz{j!zWv*(bKm(O*R#*&_(*t_!=?zrO~cJDvv0#w292RQSBi}*{w-oy{aC`|YK z_@X97A?kDMz9rEVgI>qrG{5$ax;eX*NL>)-wr`AL{2$Y*h`8E+p9@-0F7On`auR>{ z_y-vd7VuJD`f$y@K1ET35?Y1**j_EgPext|oig%BFWg63Qi8*kjExqbJ7?eqnt1fy zDoP%$l!{V{dyvp6kKvLyD-6SQP0-@xq$WPySzIn{_qUF=oI_Y1zsYRew2b6>5vOj- zX`j-DW%L?+GMSm#Tzc7+)K4~}N$cY0C<7G(e(^(Dd1DYfa(e>Tei4XO01H7W zaT5;4=JkJyx%yA}Q~sBtL`0l?zQ!M~1;hoL*dR8xk>E@+Q4kl?e?-q?dZJH zcwj90827u_+8v)3C_eA6lRiq-nJ{8kiHbo#Z+9DAX54m)&&BEejRF?;dCusiXL60f98ENH05;$Tm=JLEeen-cUTVE)jbg2$Z4AS7PnDz2iD?3z!&Y=bLt7|! zH;>_qW@Qavfvy1pIMLwV9UXnANldfsfL%9}fZMmAFpg3RME{jKIO{k6#F|>w{VIwv zb!@VaJHdn24$P5gR$fnUAY!;nRm52k#ZA4Y#MRfu76(UIC>Vube)*Y~UwWB|*G`NA>!Z+K z?C{L$1@mNRqK^9&t*2`w9DQb&hj zB)CAyo8p}s2EaY;0iNG3HNTl)B~G&^#FP?p)Jcjcg#AsFVcfj$X@F35HvrC|2v)d; zN1t5486$>MFDuRMOK;o+a9M<%M@n60v!ip-3ldf2MXiwnh6-cb7M29?`+eB9<>cj! zsfwt(<51B$Sdl93x%Uw|bn4CEfqkR=LJCjArO?Wct&C_umM2Es(1{1wp5DyUR(kF7 z!*}2F##?W5@ih}j@|zBQ$?r5={5A1)@Y0;A|E_=k0eR=0cjEG$|L^2~+(>ITjha#@ zQ(<{XHF6)1lNZ@Z(7W^v{68v2vCMX+J#GOC9wM3#+TZX%r zbhu*`S_>a7S^9U^?ceMD7ZX9EIgD#-YyaKF`BVPI;sc_S+`sBY6{~{9ue`)=qmVO3 zp6o)cSki5AcgCg?z>fNr#eAR~HT*+&-$|nm?HD>@Bmwt@^_Gihj!V1+$jy`L`nNe6 z5))I7u;BUUNhof|iO2LJU_dO}q%#=^0#*&P?zxLLeNLf&pKdPcYn&!79?0NoRg?!m z9iBjE5j5lcR8(yD=dH=Oc1)#kw1e*T?tQ%dJb=Px_tx*ZamE~Od+=d)e7TgZ`)e68 zY#2ee9RG3zWG0fCd(!>T*_ozLq|x`4K#Qtk=h}-FK`NjVPe{t-i$5 zS*SX@`zUDlB<6rtr;Qv~>fAG42XeH=LZbDLU2eE#a=6v1si`@{!q?wr=t(C+dJ2YN zq9ms0lBk~1)6#l3cL1L#53sp9LT$vfvI-m%a3yaoc$q_HAtV2KGJeC`aKs>bY!l-A z(SV^WY`dD3YrdwSv@>;`jp$hO)yah%(|F>JD=$)3@x%HJEPU;C z&Kh?W0lyjDcGYS7=zHO|PYkdA;mc@ZV&Xq{vG$N~^nbz8ti}5&|MP2AXTw^jIR66( zjBZ%f?;ii(%KsI>^ScrqXMSfBc2pnK(FD43=mtV!)dM1oJ^G< zP5{Rz&~nol1r%V1-Br-%oQJ3BihvyfGm(fmj^-fb<>zqsUAK~y6lC?Lula6kCC3jN zMhHm2a$C&6(cgKHBIGXU324Eg;y{r=Ok1fiFq8#$4HyALe1w$)JOfheKmaia8Hxl2 z%8HFa|*b=Q+v;_^|{6%8xPy5vxwb zoW_WPSqC^fWW=ZdS{Z}|{AdiT8vH>l9KR}4+0JuqL6d+s4NPp54uO$~r$;s<;%@Z= zF?UGMZxlx>XXprG)uQ}~M8t=7``r{lQR|ci6H7ya0Z!15lbJ+-unJ-siCE%jg6g11 zx4*F~0S#uFbDn@nwL7ANgav%cz|=J$HV#p`-yL}dVux7w*+(2qZO72zCu10(B!bc! zF@sJIXhpzq+s{nI7TiDpL5mMt5@K;naqFT9*j5O`XFKCZC1NW@5RI~H!ANmA4+Wo& zpzQ$K^{DV+IJ}i;AOXXlfGvWlY-iYu!cuVo4hqoKu7=bXbZVa%M9+0<>(;Go+_;gxef$1@)mK$jRsZfH{3-upiGsj?tvH&t7oM5N@{hmd#FP4S z^`*m^HTx+Rzq1@9Oz-1{GVaQYk*aN+K6(s?D#8RzgW`sbx%P%hv}@Ud88=O#Y3ELy zan3nxSo=Bm+&7yaw(X-~<7Pbk&|Rb_C)e>aLTTQazkvJZJVB-S7;@b4j30XvqAebn z`4BJ9o6i{|PvorOCo=ZZE7`Ya7b@W6nkjd1T-Q5+4J*e&NyQfmHsSjsiJA4rif+m>(=$uYtWSGcil&; zlKOoA?RVUI+nwy*y@QmLEG`>&4aW@X$Fha5G5waQL;}h9O+Uj&ox}MTokPXWos7Hj zKIY7Q4%3F0UV4RhS8nE*zMYsn{vzhT_$<%8`ZiWgHJy4L!<7>zP?WB@_s;uR@b(H4 zg2_y{{u)j^en4!}blb}gRWSRZhk5<&WoYf^;!8(y{9pQV@7)ivYQ-wF3NYlxX zcl=C?4*j_2p1UzCw=wpLoA`0Z9xVGH#RZK>Pfus-FFz9rX(mm*g=3HH&#Gn1xMSws z?60*mOg5}q#^gI6W&fdH$*h-6MNJkl zRzQhqh%5`+KEV6$eZT{Ap5x$=3XU6mEK?^>;)Qw7GxvoTsjP|6xqT-l-ZX{u1kJ72 zUd5_)KNGPuscGrlc;^H3ZC@W#gqNRvnNL6djAI9OVAQZNiK09ZQ8C-Cr(YFM?-?RgbC6lH9%bZToxR^1stydc@xD&cnM4o@<6EP=-R={}>VZpYo^t zUlPY0teh>ix6Aos#W5jiWpL`~^O$)3IO_RAtoh(YK3}(i`{zDIuy!w3Ot_tSX=w~Q zsSWFX-p_OMUZO=|5({5^mWO8D%U$=+LgB;lEDZDLL$m4LcQ8{=8bUy6(t?Rm02psR zedXmB89wY(hK@QLi9|?9sDVHt=Z?FI3r7#7UQiM6Y3{yf7D}borq9VRl)AP`*~vV z8`M|7a{dKZa{j~_4C&FBDbw#`$vqH6a>uAY1!y-yrMz6e?jLP~-1ankS+jJfe9a($W&E8geXXI|vSS&z~@ z*W`{n=P>`3x4G)vzHItsCl_6P8z=Q|NlH=>zi5c2f>Iz6mcRQZA1z(MZTCMwVOAEI z$+bNHL zlW)JB-aR{#8wl~@>P58geH@ofoJei}KK<}@-uvJq?z(?A*$I{0H2pyqEc}4ek81+r zq_c||=iLrf8nF)Y*sR;wu*=V*Pd`Jt-zG89$CPPzlU&e@xzlgs;MQ*$H|Z9#%bJl> zeTe$mxlDif32L@}#)N5em~#JYii1^Le$5?x{>6H_l)=U=yP0(%*m?bnlzJ^C?sUR!Fz!VMFr^UeAnXy2lg-Fpr&^ZwZs<|J{?Et8n} z(Bs@S@j@m|ypFCTE@Ra20qouOGuKRcIgSI+iC}crX`8COTbT3YbDTZ?dU~~KMxv@> z$CmGz`{J8Sm~;zGOS5@+=5+3PG%uLtZ z>za3!8!svfY(b=g*Pnl!cUOGJeGflLZbk~h#1vM&`zFD}WFC3>S*m_o$C#_8GUb7} zv@P**)wQ?t&4z6xms-qu{3*s>e+%7P7V`G|S9#|7mk9WRjKBISveMI|25Ye@nSJLp zb{J&IL=GQe*RGvT1ge;bI8(A# z3R?`!gdiF9vS{4ADNP%dk&>A~PJS+}nl|OYFWad&w3l7`4>07clgVjN!r&7IP%p*L z_Zxpks{nzdBy#feX#o2`1i#s~5qb48IC9u=;?=I1QN&L|Fi2)vki^6w?|$?tja#&( zOXp4$l@!shUvIu%@iC%pPzlt}EhZ-?lhouON;`A~-kK`P;EhGgY1h6hZCW*_q%fP* zpuysWuh4h!F*I#jM$48B>Dnfb6>C1H1`~X#U?J#w-$sF$9~qQ%Q;*P#>b+cc-FSrfYV?8c`bEpaj_VaD;}#c5Q;pyo(5 zYu9|uX=k5JQR9Xbm6V_(2ids!C(ass0}V*#vgt`5yY2}L}qplOf&}`DcRuWV(0l zL}`N({(AheeDT4X{JOs!TbbyH<+^W}vGvHOAQEEfyNl^Da3GCaHlwI8kNTNuSXwX= zQpn3IrbFj;WM-w2l$lOZgKQc%$mYPly;SVmM=+R3x4xYyDlDc!K_RBCF_e!!eR|Qp zZ7Z~BG=6HUYFM-SGyZzU8I(3Gp|r4wjHE>T#C({jLoeb6xM_|34{B>X_n4T*QDbWh zQ!KW9`w@Q`JcuQ$zUJ2-zNAO59z6Z(`yfa7?2|=wY}1sK^m?3oHo8K=iXWlR3yvBSa8oq3wvmahzhKT;Q32yaU&pH!be*yJW2$| z*V@}2cqa+Ajvxryw!JtrYz>wckO^EmOillW-u_e2bcXa@{y9Y(YjHM`>i zVIjiG4`1Po(?_x7%k_A^CJGCskMQ*DnH)Fh7}ox<9m{Y6LZbAiF1Mnk!M17$)f}Wc zVnrQZAcE*x(A8*NL2Yd%RW&u#Shl-1*@#_3sJeoRswxggB3Nidhk*#;P$kvX)l`PV zguJOwB7{RnsI02wNNt#iJ3f&x;ZOxNl@(Ofh6zVa-ytHQBh*w^QXL8ra@)gUYVe}2 zy?g(wt%85bzguD~9nlEUKX^yrZlVlBQC(ewXE;qyOXkqQ!+=96vUh(uDe3jmTA{?* zDQgr}71d6jSfA-=Eww^fHbEmoxTey1;ni;`3!D!oLr0ycW)j-6AafZ zg=@7F!0>}*Th6qs407scP;q!ak#HD*BUP0oBq!rI<~#XUW4n5f3MLk4k(nB#s_KZ7 z+Ds`hePm{3bLij^BH}DgNa{72|H;)0Hb3a%_JT z5f|_qXhS1dC=sl%MPiblgrLd(y?X&0Ln)ND9MEle1h+T~lW7u6OQxo#2FtRXcT+2p zQ!@!wR$;k)S#=~tQc^Oe(ulhNM~SW#h*BgZ1TnNk@1eBcS@caX3{5a43CoHQj#$_N z<%bUAPst!LB?+Garssp2U?M0LL8%C0 z#E8}Z5ph7E25mXM!DtL+6Hz{@2@($1kd~B8MP&_pwr}R9>u#jl@-ybLF`PK4J4@et zpZgwqnv;j0!37tcM_ztr-3MsL-&d(x3}s=6#x(sz3}-$mzM-G#knn}otI7WV#c-!$e-o1q|5HTEH*?_LXKw+7RFrdUjNeGnJPC+8B7q>*&V;qlj6O9TVWa)bg89eA% zrrhzU%g*VJeFc^k=D8=IuQ7s`x*(fdAoQ)FFwE1A~8* zSmLPP8C@B?0b`9)q|^Z{p_b1^=jiCtUC8?P?l z<7La4FzGfLHE&71v^11xLXD+K&e#NFuKeFztFGw^%+3r4Hd5rcB@vk9Zic7vKUTmx{M zn>1wV_;Gyl@h9AJ+XJZN`gHHq4xb2y7;fyW<7ID%lQqGqr;uJhgEgx^X62{fu9y3AU+aRiEzQ$r?Gm)QeJ%d4OV~t zC7U;G;p_`9XYp&V@y^1xm_PpwKKphD1N-*CublB=v$#B#JA$|DQ+JY@|s8#lwUYItPU-5uDvU~-$g!uU5C5)SR z16piCRR_3k{21oUeb&{+{A1#n1S3f85$?L>X8QH*&sEpmOjt~mKM}t_$o_r%2>MNq z9N5RNyUN+KuZkrfzE9PzZ`t|Nx9qFXtX}gapRHPfRa0A+Lr;U)HN5id!<;hoBzpGj z#qht5;Ju|Q328woo67R-+%)NW`t|F_xffi@w?FPgD@CaCAlFTpK=T@=QT!-K9fFu`Z0LWUwHC`H>s$#9e2Pws!5^hNI7Q=Kb0<>JJF?6XS#Ok z&t0>gWZ63lIq{^SeD&S;VA<4GRB-&j6FBSaOPq}?A$D!s%-}%-8TQvRS@YFqG_Yaq zYQ|l1HvRhdrT=lKvUc4Dst)XB(sdIVFrYu@UT_H;w(Y}K!lAuex#*$`=-syuBSxLW z*Xw@(e}I~*3T~M+nSuR};qC_>;Ydvg#A4UBpSgU@MfC2|o6E;dWaqvL=RL*a>r(^} zw*S15%P+Z<{{2tj`T1{PDIZ?se^hfOhO3ngv;4!?dHtoQNKH;ft3-DL;>EfPhxV8A z+UrZWY1$n;@$mf|{^fh-zws_Rckf}=z4tR_!VS!Q;sF|@n>_T`^F%^b+^pRbM<0Fyiy(6zdz_ocpU;cWKgXV$8W#k{Hf(>&f2Kq^eMKZ@V)+9_p;1N> zBhJ2rV|%pZ_Nh0p=))DX?%bEj*ImK058la>&%Vm7x8K3wV|ro`A;D05xoQnlrc9@P z<91wo{SBlVJ_?Eo$*z}+AqL|nO{8&YE>o|Y!0ZPfVc)?cQ4_946Tu>6*Rp!$$BZ3w z4bx`K=8`KerKC|SPCtDVg~3{`A2*I=tG{RL#A%e}C34lJm-6^CZ*crEy$J>a+%#nx z8FH9uH%#Qywd*4 zR%!wXDOogW+>ivrpmV=|^zYf8=@Twx!Jk@_@*Bir3 zptz)n^kjEBQx0I&N+WK01%rZiotbgVO}zKglT4g&4J*F>iT=l*#?9B9!;=rr#8JK}| z8a8Z5vfo6R0ZK}W$gZD?;ZLDuvqoejIZ&pcsDOgPTxXM%mP>KN7NqdUqi? zHQCXuDZmg61GH8oXEfxVd+y-Kj<31?+6l~C@D65b9{1lnjjvaI%+zUjFz~c6 z#pkbpj{K`P7AWfRLA}uKa#7998%+f>CST8;x8Fxa*kH$wN-RsGty<7w_V3xl;UhJOZ6e|)m{UxH(gxJ8mq930 z1A!puN*m4&XpIO!>mW< zVTCQ0EqaBsM_$A)zx>RsyKd&e$LCQmuLw~FHI_|HbuGJh@1e5FWlJy{Hz=%6X?_N~cl^TUpSDvkzX9K`|AueYe#@FKzQ<=M@CC_e zP(uCO94De$KtiLJoMCDnigl^QxUg^T`Rn*Vf*$isN{w;Y21w5ybRj6EoSlJx7qy5F2Y7KeR_2z zyM79%5B&=pzx|$HH*e+ZuQ$=TXLr&wv+35o8^8Xz4hdJXY4eY??bCyl%xwC1ZcF*b zFW9(#9pC*@&fvdZKzddN!;bGxb@^6){B;knzQ2wR-3O4DlS<=Oc_=Hy!2{uF8GnyL z@=y5>5;;n=)<+-ur;66Lh_*y@M6`~GEg}&S(RN70t`@N)qD92gBBHBg=TFNeue6nX z{nG)lMIl5-qkwMC=;Tx>jtlB`o3`(^VpNt=L*iSVSzbMRZ6+TViXGkl13|5s`4Mh;55# zEm}mvTEx~`w6??&E!wUXZAT>HR6?{^VmYlN+6s%me-19{&twrpxh_=MiUcc5##Cfua zHv)86L`TGS%kH$fC1N>0TGu*#XWP;75!PC2B`mhCcCHtvEY9zUXt$rjI#w6255x|O z*0D0!Vmo8g4vS@L326~q+s@b$%PFTF7F%nnv9*ZQMxQCRQwv*;Y6B}Q5$!x*yKSPi zEn)49W36jN>?)@%#fq!D7F%jXq(-#uwwv46B4M$jBVD5Jk}cw1T`Lh0iD-A6>5z!+ zbiCGK3Aw#2+8qqq644>i+IbH{;*3?XYDHTWV(Ch^ZN$BYQ=eKbV(VJ5?TAFQH@37> zUa>@^T5O3(t%zGA%NY+M&Tl&;T3gX}6A6jd&U2jqy`Hp1bd87(i>=+NSeA&kB;vNK zH;>q&Me7<7UE`Fg&b*@~6bi|@b?fBd!Gpj1vwZpT==uBi@0Z!LXN%}cIk4wz>CvKz zbnMVee%!TBe*FAx$w*6+M;9!S?dz9GQEq|U_Q>n9{_}UFSy@v#=h}OvR)GYoWzIZ>DEjqkYE-=mv z{ep3Fr23#dJ8POGr8kzBUVBv@dSH^|WTnfcmyeT0%RiU$h{*P@7E5+&iahxIyRvKj zGRdu%CNrO1A|YFg*yXb6v&E8~m?!gJUmyz>z95-NnKJk7_vJvvKDl(nagv_hTvmL! zMy6jqQgRDh%f~BM$Ty!ZmbBzznKS#P=lh@}xB>DM`hhe z?`_veetMQX|L#&bEF$aIE|ab$xzeyvQ@MD|SZUv}jbsd$Q4@-6RVYy?{<&vI~ zCeOU}o-BTOmefnHFHbI7CKY?uNm*f*Tr_cpgd+##&Pi8El1h-bR&S6>cTW3d>o&Rl zu9;%T&o`kRGXDG_GJeLxa!9;6!4i>QW%)<1$gs1nlS37?qHFib<9Cgho+q9uZ+y5+ zj_KV`j?~nM=-skz`F!c|mow$dPnJl#k}Uc7`yVAFmVEQoDj70puvnGf%PA)fl0{#y zml|!$zRh1r=lW^#*1~6{-GE{8{a?;aDOGzUoC5^1~T&}uuvSU6~3d6QA#iisk0${qC8nlhV2Sx(6Er{4CYz$0L zNzN`<3D~w1Y@!0743r9E>KZ;;{03zW8jzNnN^(jXDan~MZq}AnU#!Jaj_;EapPLE7 z@h-G%jnX!re;~?_G7JKM-}QZWvbQ-JI!hc)lcQ4zU}8GX@+2TC0XuBt_qee!T_U9D=ggU5$T>^SNf0n0=70(+n6n6&U@>C`b3lw3RzyU_ zRYBCnfEmO@5ET@aoYOE&I-$Gj{iCY;oN@Qwyy3@1kRl9uBxu^)Gs_wpiDNS z&NBJV+i6f-kD{X56c!g#qp&93d+kSAMxjK^^p8+D+Q-oW+A#5%I2(*1QCoA7Mw!^k z09^?lABF@l;!H7Tl5gQB7$ zii_%U!RRZf%xJR0i`=_{Fh87brvIrjbP@iHwcNi5fB7f8}TJgHnmNn2~>b96=i$N@QKs1O1c3_UR!t0GMoE0BXiz6cfk>mW3be_34YWf7$fin2rK+e?yO?-U5eFZ3 zBgta7MZFNl=8vxD6OobUc&~|D2Socra2(Hm14}%sp_yl`c|f0&QHuzV>m2XPX?@_St7z5?&dPGvnn~ z2~|phsD5Dy>lMBb+ib1zWY`j;%`6=edNn~nOuCSNM=PQcx)^h$#a8J;n|G(Rz_9`P z(gC3bj_cXM6W~Y@jSV+UwlbX*O}Y_hj%37{7ujn}{7|k52C##nZ*n|ytq8}m0M`xG zt96vPVQyef4z2~kt}E>`e82$mun$bmha{)pZTek!5-AF};_8W9di6ahVGb=q+wD(; z5^*L28Eq0sH3ApMf^X3HxNbaZzvntp8^Zaa?feN5k`(zufM!&OgHl*-7$Jm7Tp{{Z z^f~ZPq`Hbxt8NPh^zF>t`JXfO(Z^`wm5@;qDPksR%w}e4;%K4q9ARdna8Y)?2hxnP zSe|@Jcwj+E9Ie?~vWa*8I-BzC8(6Vv7Zb)EL;IFZY1gtL^Jc$DkCrugW9GBeYt)1; z?K<-1CktuTt|PbJFqX@%p2ROd|3c8E6Iw!`6^Y_T)G18z&g>UxRa8#5E{({Vj2|kM zL(kq_X;wF2%B>SP`p^TI_rcdRY2BW7ZQJrS4odq3+DAGL0)^w{#)o--5{V{Nv6;#D zKET?oRh&L{0E<5Rn08GYvHh1Xx$mhrx#rsIsMnxAy7F^gnlY0;Z5wdtf%`;80CZrc z7n(o?INGrX8Pib>8aAax>t-z7xSNjcI#a850eJOj(XavY-f91>I@aD+qM<}GR0rWw;7nnW%CG@kv-d}4K5(xY=Xyp3g$N%8r|3pu&} zN%ZK^i5H%JkPeL%->lj|T6zTG*m5kdp)&EpA`JbJuF)}fY<#c^_^qpwox9VgO(R}?>OPu}8_C?iyhnrP zUFp=U2^XAv5TAbf4hJ83Fl(2tBvDXAz1nfR2mQ7(v452R{l&m0ozo8dt+Rs#MnVmg zp-%aA*%@y2y+x7J7+>&{7UuVpyQCxN1&2;bCgX51L zgz%CCC|nUxT)#CJTyP%WEO>*9F1m>MAAU?qc_>$)M4UElyK&Q`8~E|-MO-=VI*J;% zDO%^CSCU@CfqcUpvq+GyV6H!hqQL_fw=ZT#4!E_vpY0s)}9+C z-b$DD&A4{_WsJONBy;D?p`yH;8PCt;!t>AL!AGB9(4mKN^xy#~>7faT3m=@A(Ps9m zXxO9!x7>0wPIf1kjr|k5Q-TK{ew^N&+R&~4AdWunNaoLbgP@=eH{W(E?VHr#(vg=i z_w5g8)1@PgY86JyYWV7MMSyk*@bH34=QfuDodyKP~=@5htI;(iIyx=bSS^ z)MmtKXHl|wC8wWy8t;Gh6*t{`FU2(*a@7^1*uCXPPCxZ@-dV7Wt8TcRT17>icJ3L} zty{>sXP(CWQ(xwyk)vo-SYVP2wQu+1-`)W9NBQ4bgi=cX?y@&QCEqV!#@4C=4j9;r zc=&n#I28ZJWV1j3-)F-3@pS03FQ=SyHi?jgROH{Ny1nREyC=TZxK#4pH{atY>(jMe zYozv(PDt7rUa!&qUOxTkV~U%0r%T6Hc*3{0G+W=VZ4%WUrE~jbbrR6rRr*)ghaW~3 zo9HtO0?`OEto!LZ#$9(Ok397p*&S=yvDc?dpYFs(-bO7$(lJ@>5n6}&Zh6nnmsheK zDt^^(Q9X2q4Xb}(_}OE5@S&;f*SiDAAnKFqu*JCcf^?c2t{+dAeg`pp#0XphW5tcs zDRN*>gP~EW)$ zxD(CiQm1(Ap@;cs>1v*S;t`5tPTrUcEt0ajwJfZ5K9(gPFzLMZL!{6V0q{IfmBYIB z>qZW*V*56h{;-~I{rgiG^Kc@-tIQ!FvOJqZMK!>it9cIK2|$e+{> zNhC3pYg8WI6nXC&OA}MAzV@>B=e^Cf*I&yUpMFfe8pXKLp&`Ge%66*+k#DW|dz;li zUca=~WV2a*{P9PcH*fxTzw_<4-*VuA2LiBb*Dhwwn#HKmV*rraWPBrB&=TJ!Hn^lw zIHYh%k|Dq)BP1~tj;cb-I0_f7z|kr8?A%P1@~{GWD6J_qJWG5 zML>a0Ap(a07wx(z4W7sv<^^F_W z1=7&Bm_Qzlt18gaMUlXviXf2qPMkOzNP~fhWVJMXhQd)9w1}C{q{bm-vYZ|h%Cn+ExO`&bS?LMs#I*UUFL=s;(WbFHO$bd4^oW73Z3yD_R ztlvVJcP|oTggKy_`R4;^v@XCG5+$sJDH#Y12W*v+xGs3%=LCR92G_R19@e9c$;`32 zbLY~uX;b?2>GKcg)F0*lZV3&3ixw@y4gZnv3jVD@p$@8eW%{G+Degs|fxV0^MEiy; zRSPreBdbJU{B5@4AvvexIUIk=$<(M@-^2;Y3}!IL&`MOpe>nzx4JvCE2rZE!K&w4W zd-@^j^&CRGwyjAz#vdpQ(G>_~_{aR++;i)Aj=K16+H`7VvKN()kg*6L`1TPlzqY7q zAV35GIG)uCwN6j#`ZAixfaOy|Is{g;QlKrLmo%v0&tz2t;NZ&uTVx|K)7gO7LNRAfdBzAM(u`m z89VM0TD5Fs`btZb5Rtlv)`6{rgRcSC*5eQD|^P2*|V<<4Ba!Na+#;!fXJ6 z4_@5F7m_!mBg`0B;N-Gv<4-*P=;Pee^I2js4@nTkn1yC-ZGk&7h6&N@vH?iD&~N2xaB2a_2p?7PuAuyesN5LN^TZ8gcUu5$tHy0mBfbyreUkOZ`y z52mgXLso3gIoA3d5V<&AnHz|arnEUN@LQBf!$H`XVdI9t4d;UP5JC_Wps_Kd;gvFp zX@Lf*DBHfCvFD$~dtdyBZ^0zeVdRBpQ0CS`$SgugJo40W>^w8iH$cFwk1=rE$ZqP| zB~QCW2*A@C(^)YP+FDgzkRA}=;UK~|XO{?&xhKg`B$fytgU<&+KE;5Xr(Z6S&xDIf%&od7{K=;}At>Mb6E~itEzMOp8NcL1z7*bK}ULq8TEUUj;#E_#8qfO@?Tz}hrRHZ5r znLXTd{q=Ne+k;#0xtndW@bM&!%vvQ+#D~Gm~uqgI!SjqV(A3^6%?djgDCzB>k6x8_z1E*^Vnp%wCTpBV<%9VDr5PVpK|o!$I`QVZ>IkFc`AH`@9$ySQ;*PZ;6Zfk z)|Xjx=8+YquS`CPMw4aRFH0CU88b7|J-bzUttIXh=6EBKQtCw@c;C^)I(uwmgy@qYOD-k-)o!5_Jzn-1x z)TI-bj=PGjC8hY8a;85ri2?ol(xGD)&OG}+e1`gPt z_U+nm(kZ92^yiIa(D<23o_zcv(Zdl9oKR-d%ui&q9{=$(5 z4xoFdjtn~FP(JwVOMD?gSMkxj*&KB6A#~}~juTHgo6V(Z1MmsiH;Jsqzu8h1&R~0p z`kUR-N^UxN6y&+Dg;r|~%BQeybME`|t9cd9i|(b(N{9~*#Xq&dyzZ|K{@RDcjnhCv~r``ro8&NjwP zN(0KJ0D*%@)MM6PKjEt-U-9*l&sn_qOO}4Mh)d5KVZe(;BVlx_s8%OUe%OW*=CBz0 z3=9`%jsTzV9#Lo7ZwiT)!g?w4V3|F)VqrJJFsdqHD2GfkM;MZm3yUyybR!~uvj)0^ zWbt7!;M;=Ke>0K7q`T!T?KV3vgl{VEexdgPX@FqFnrbh#VM!tA6k6wr#O2cJ{a=sx7|Q#X*uQPB}fF5?|P8( zy(y+X@i>kwARadcazVI|8+QE%?!KM<4?2*Ek6wiEGsHZBl!8mH9?$U8PNRMeMa_5> z6K=SkWI-VhPJNndZoGq8k6nil4r3=w;Dn*WX;P?p@tKEMxL`5&Pkw+e7A|1uh_hMv z@jRNu^Iebg!TU=%^Qf-eHfbUo zc2+WF%0tY5_dU)yX$UXQd7W=p{DcycY0p2)Pv0(O%H;d#(!DbUnG_|vc9YSD0Qr>D zPUoEQw@|mJ2HV&Fz$KSo#@VB;q(j>#OuFweYSwMYu*2K3;PcNo<*bW1?BM=1YTU?J z?L@TH0-9Z$Hc^$$N##tIBa?mZzV3f|jk?bK}H^NQoG(hRTvXlvSpvtV;2~O*gZ%G~mHU9^jpK z=5hMz=kmr&Q~2@Q#dyg&Jp23|tX%#z58gM0K3&_ij-6#F?eod}ztVs3 zQJgaL2wr;eWgdCx86Lg&QeJ-H1zvgk6DB|O5G5P8as71@D66WXFkTRW7h~=6DKFX1 z>+?Qf;=PZuPpbwrsO9nCgAcRp$IU$O(8GN3=^{=z;vnAq_(Mv|((K;3+hiGvN_Owq zN@?0h#y$G&H-O9Tno7e4ji?(d??4O9;$_RIQ@0WKOn!t^o#>N7L03m$Pu2oCHu5os&wZ!9E3#3~_ zQOyt(X|z@ZfsgCB6vsWP%1TH}GYbQoA{AQCasVk@(d?WJ|6=EaLZGY#+E`=_z|v8I zjrFwHu2Mo7IAD{WOxsMGt?fGM%|t;>;yRmWK{9fL<-2ziY7pnuju6HuVL}9?jXO{_ ziO+-{SP=Lt2(7KQt#o$u`-OkOg{c#f8#iy^P?MD+hK*$H8in?&9> zs>LQN5yf|;QdMZJDJd!WJNssMZ^Kb*0%2q>=A!!7h+Z5zvi61Ru+F8P+b_#%H>f_^ z^XG(!ga8cxYxwrH9Z^;}*?I#0S!q;%l>d9h{XLRFsu%ODKnoJJ8`7d_F*S9Dw?AFT zz(Gec=;$LT4g!`g{hn85JWcnT#*mT4wCmBIKCNrep`m2dm3OnVbT1hN(#cYlsbule z&D=ftE;@DV96crcQF+g8+p#Mjezln9UHUTQu)#QL3&Ja;ut8l~HLFdbPE%D@$%3WJ zS^fPoc5hwJ#&iSHS%Fe6#kK0tx@i%y@;xm3coBO_(meX)6Qs*Z*tK~JtJiFxdGEHS zso^PD2(<8U3gWcy-j_DD)4VXfGp&2}rr&-YIb{DnY+CgbCB2h;^Ya>RdtxTN8rP&> z=f-^S#w->s{f3lNi^2vi=&^4v_UqY@x88l9?In9@=^59JgQ4{(tlONXE$UNCE1r1r z4O+G9%*kh+M(y}sMyx%C_uhJoVTWCUa+9>{-k+Y`Iz(qmv&2|;jdl@1oLcqj(Y{kh zx;E0h_1+@-9CRQ}+!ES9KaVvlR?@D21Eh8kO46onTb`b?kWUwU$cUjs@I056t=seJ zD{s@|n`Im`iX^ z-(SS)4O`KrJK45*1EmU5@!GWM)RTUFdNBOhfy`O_J>~jjw1}}!mtOSk*By2Gv7C9$ zbCg#p6akJS5jwzE(6CJhy7%o(VZvkLt&gEod-(K|PdRzy7zQ3RkgdzVqgKppve8Tn z7k6ze6_rj6+V$y2?|qVFN`GeYl5e@_hP&9m`#$X7y(MqXe2n=EKQ}QwS{PDpWx@p{ z8Wl+5MRjP_yb(={ldS!65ubm$l&YeZtl#uA8#ivDG*gHlKZm>Sn}R~(5Exlt1%a$Z zt2RC8)4MP28Yh{5#*KXO#Scg&kss4&B0qjN+?uUS zq|kW@OBOT;BgtoIvaIV}I4B&WM@?YsXRb2R(gCmk8#&u!%H*!GyRckP`)BiHZL_>!IV30VfL5XnKJPzRxkU2`{pc1 zD-#o@kSJv=DCx2^=Uz01F8u~ltWr$WlGZJn{!JFLP#USssn=9RQKP7cz%DRJPf}U7 zmmn~~PenBnARwObD2lsOrcyR5+QjV$0R@QyQoc4sf|$+3aUttlx0DVjD=(q2FoEZq zXqjX(NmVKZLJ$a#tc>TK)kCmsO;p;5x`+KIUE_>MX^rDZ5^xK`3G=PCjb)n=J6l~zI$5JL$=-=b9&%C97uj3ETLahIZGoQldyq{tHJ z6u!=yXeezci=-zBgu>S*3pX1#vV14%%c*V&ab+g#~6% zP~Z`Z#i*!CfshEtL-=VPxn~k{zuL^?o3CQ^(goZ(XPI?11^6l;K;p$bJfT4cC*0N`Sqfm-a3Q>uidpKk?3PDFcIF8gJZNHf{;J32}X`Ks@5qb00 z#8~QFV!d@;hhW)!9x@IXm#L1h|9=e>{pafa_W{&8n;0^B^yq&WPap2DCiXR7;U;Hk zHJp|qObz43wY8xBt-kMnrpf+UAlB*#xpb6 zvZIvkJIiTUzad*zu4Kd7Eo|Jhm6F}t*{^SJTC{FS?FP*dN+8?>Et)rH?RU#rw|)!T z_Uxr|pU%8HZw?|=g6BC1N8rW`Nc?qC2$LA0OyWln_$Z|T2O$kHYjN$yG_O~SIZsb# z&6?G`_WDO`OL_F}(h)CILKSB7Q-N<53TfON0Z>#k$@(=b*|cFBYq#uX@Zf{^dF4{R zT)2=mzij2*_ZQN4{{a|TE~A@k`D3G=QXxT!P-qq42*Za*khOLMY+{AP@l3d~76DoY zY~HvQ*OT0E%gxlNQIoH}Sj3i18>!d05fdifN<})w+Km;KKTuG&PHh@Dtj&x+Kgqf^ z8+hf_ci5Xs)3$R5gwRM~qjIz%1y?G-{Tu!_Z8pTJa(-I2oV9D#Fk|-n6gBNc+ZHXU z6U(r3%UX7nR#CQh5Bv7$LgR*wsNJvyDJ2jXV(#z+E~N)bSyv2J-bxerS%lU|8OGQc zKwzvp+6J9FI5LKClXUCSfsba-W#ig){Jdr(-HHKy`_jE*b5^ff&f>2YvvqShWht}iCyNW%Te6)^t2eT4{Z1OR zY)^}JP55fTd&FIh5-!PvhxALBJNsqUY~6{nKuQRWqsrK@dIf9Ot>yg>zoM+NlHR>L z;l>hd+p?KGyY{kY*Dm_>>P_R8EvVVJDPiD}bX}yS7(#9NF{tX+}Z)aC&m3iBKiuvz<#DYaj08O@RE3dus0_(Q# z08)JW?KjMO@6+mY|G!Ye^-yaw7DB6y0nOGeEM1%6Wr&`&jStjXRr@pi2^oKExEF+g z!2U$CWDq47N&Ax*9B2D2+|-&zu-P*Dy|F5d6AHvojqH0=@9|4yzS zqGl>%88aW-xnrrZL|AW;Z(aNS%demP@6{!=Ea!hm2od!~eg_$vGTR@7->H7xf3M=z z?;{W<{_|J$`=k786d6vW-|OWop%JdfNh8iAyJs^epD>(zraVgDL4z24U_Zv3a}Fa% zj%M&t$8p-3XCPI8t5Q5NdS=;Id&+2o-vD4&%224 zzWRjYjy#SDx7J|_=5m6@-;#_6L*(ztFR7oK${Lx-Ni^cP+u z5GI*91P6AtCy;S`=^EpJ69?(x1co#j>5$I)6xM3YwO5U0<$}L5?D!!(`urU3dUP6H zS~W$=04*&~A~A$k#H0o%P8i?Pt#5x+x}1}bJCVEZf0RzWdNJ~%bGiBY>o{fD+0?Du zm{W$Ih!7r55D*VixB$RFKfm@=sH4+%7zw2DwM62WOhYGT!jS_&#O($T3eSMGpn|vO zzQVD`4&&4_FQRSdE*yS9UuL~9lOv8ekqgF*XW#(?=+H8WattYKag7>Wb@e#D`1k`x z3>(3W>96wOV^e6^wgnnNTxU!crZ(?Tiodg6*%P$NRPppol!f zlMzD>Va0b#S+e{mCf$A`e|g~k0`n zhNDvm4Zikltd)y$<0c*qjTDYGd3c<2-npoqYZ*4=IBvQ99!gRwM@k-6-3(5&7IReH2*$pHuUj}p z-J}IQI(6it)6Ze-_?y_1b$I55=UDdn#|%61ILWc*4<3ymv`UW~-W!B`QqDr+Z=hth(W(j0l*;q2R| z8y8=EA)`l*Va>YD=J1nE@%+ped42ACXf)|P+nI9z-K<)-9`O0(e=+Bb(5tVbDR zy^3FZui9-}{MT>i?bn^Pjc9{xkRKYWES<+xbWN z*D6BWBX2%c%x^gml(wn+Dua*-l(r(=+6ScB)9nH(b&5^DET-q-qxtK*@6)GU{TzoG zfeqA^WP^;M8V~|4T+4+e5JDPd5hpx*YZPe=g@qTn6pWaHLdP7G4v=ICi5{{lYvjLB z2tNaEA~MTZm0PP4;Na6$t4S|q2WUc$y1AJ2_>4DZLOBJIr z?w~McMg$p@4rcV zccwWTLZHyn#Yf>%iKYNQaPXWA8qc^Pg-=#HHiOhWUnvZ=1R~0L3*)|p(x9>^$209x zM%pSw&Vdw`=-FftO0ZNl0$=+$B4+9q#ssP~WhFmw!I(*mz4KxEwrYeU>{!Oo$7shT zK;RG{0%^yM0VX~gN7#HnmBmBh3lCoi;tG@$Xk~H*v%*2>07odYB8C(G9hWeJ&%`Tc zNvEnvr?NP%WYMC<+&uAaUVZ0H>L%lOK$zhyEn#aA#88fvxWh-Qy zr3n!?N-8rA`~jU7jeZoL_C;RSd~ z<4EkB^vRMip%N-1o zM!_e*LFh{M?ky!AOR#0r3dT)%oSUXhrDqev!KO4wEf8c)?45QHB7@0eHt^C|zic@C zf0-w6lwEHO02HcTA;t&9CINA+XhWl*_`pVn=q zR+HA$uUUx7nmOq?0tm>YtN3N@CK@$qPVM5N=t>beseikY4}e4X8K$4)b{q}5f@KT8 z;JLTH~97%|r)CXH%G7$}R?szrn6#Egqg1vri(lP=|f`=_vZ>n@v3W;mt# z4%na5PaQ@$S&TxPu#dN!xDXgVC&Q)ZTCf5V+yuEa6B9EAI&$*}?X&W`<;<8qlZtfO zDw)KnQCQ4Hqc5ao^Co!0Y>oyr8D2fJyeUGt5^XJCA(x1*psbizYGeuJ$Gc-y+4nSB3aWVLHz zu>jZAoPO%jWZeX4VSti-cM<`PhXBitZ(q6wth7@o3n#&Hs2M5-15(U09BHx(9W;h| zBF8p{c5p?2p?MHsrS-mC_zBNG`#fo-D9<`veCeh5CEK{|jwjetS`lsbu9x8C)6QVv zzCA1e6lfhL7Z}*@m@cuFB-iNm=4}UtJ1+(zuw%i_Fi-DoUf$%&QYSy#9vdDH?SU28?Nnzi3~&B7IOH>qZvDKG8Z4;j~gf5 z&!CgeXUM_5a7eM_^N%>;l#7`3;6t2shM{(m)y$K554WS##H5AV=3$N8{E84R$s+u> zHj~*TpBe&WggIskyM`MBfXS{l-*eIUpek7S=?Bbs;cYIsVifhGUNO>!XmgmAvKoGl z=7`8|!f#ZB7NA1HWrfP_W%jFc_7MSe2c-yo{n*<$&&ABvrk7(8GZ_N>eaT| zOt}&ENBP$*?yrMde``yi19panSy3WdWW!mTd%jD{eLAyZ`2xIH2*APdN zz)iPYYqnw;GZOMbkch_-!enylyoZWV4M79i1P&|m7qO7gGjFwv_F+-&UQu(Zy*}Gl z_2D_p?q9`B#;rZjqV|ZUD)mUz50Vhh~uIqB?9=Cq97vo&2JBe z`zvSQ(0M=Mdos&<HBf#ZX!q>Jvg+O0I{DuTt7~8$p+9 zgsbFj_bU3#6e+5ox zV){Ylnrr7#{=ffOtC&Qfvz5kL?Kmjy;RljH$7#{J1(#ob1qUBzu*$D!)FTj;1oJDISCU#S67byk4b}WDos=Zh9-hHFdYZb{AAf*7ELW?*78dvyK z`Yv%#BUB0@lQxDiKq~_0|df&EQA4vj;IDv zf4ibJM!GZL%~{X$=+x<)eaWAgI`whNQ)w=|;0yvFE}k(3o{!#u_%iqKV{+=-b8jQs&LN)onu>gS>$$|nxb*|{JDu^=aqLZi1 z4iuu0L{V*$HHt|l6Xwr?BndATT_52M0uTW?4lO|>Ae>)Q9T4a&Qn)z6F&V;yr%z?- z<4YWwq##+FWMMIhWFf`LB*lpW;!#3_2y;>GGsCv3Y8EidEM@yf*uId_h8$)Yiae+y zG1;mSj1nPpe-53A5KIuBm_0nFfMlYOf@A^7WRhe-f@C}%^?-=rQh0AuA4!gDERqM) zL>j%Ch~*69JPgD2!x*Npt=JXP*_kvvY>!u(*E6baHUab2s5;m2)A3S`VpxETQ-fsGt6_aY0^X?4tDj3u z+-2UkjVzxAoxu;P_~D12$YitjQi*hmh$rh(m@J}ZJWin_bL+(KScKM~vaI^%Gfp`C zU}_fE=CGk>Q|7xkPK?s+TbOdsy?pfXr)07jsRujO`Emkx|^o3yTbI%M{mty(1HD_RjVFt zJN9PE^f^>km9gUM_c&xgZyGje$UfZ$^4dpVvT5yl?!NtQK3lZRoOgm0H;*}=#tnP$ z!mQW%am^a;xqULrmi&N9Rq(=I(K6(coTkS*L+O;UC zS(kG!y_xm9%P`LWJcuPS?A`u72kzUJy0r@_D2U@G8Zmz2gFN@d{WNOch9_qHg`*Dc zPw#_|V0R|N=O4a-SJ04&lkQ>JXYbLzO>64atwZDHEx7xk=cq~x6Z@<|hz!fWnoqkX z^||);N7%7rBM0{CK)*r9Q(9iZ>hC`0)S*YytU-NRx9-Zlk3L65*8go4r|r8lHu^NF z$}QY@-!v|~{6@|>?Ia$Zcrgn;ewRJjtg*OjO*Rv-V%1OFGVvC=c5XvpfvO4u7A*Xf zDvFn`E8F9D2<0#B>#z zy_4Pngf3R40-%cRo7b~p$8MW{n|~@YRu2UTm0`=zKd@ojE-ROn z0|#N2p5sUxe<31Eghb;gWhA(w4LsU`O&)=UAY{9@@o*tLQaTSPYK;nfV_CD=bK5tp z4?2jfVrF3t z0i@mX1!4FKI?$0d5X=IH4keVFsEt}17iACxIajv`uL-NJ`TFCxnf&nMRDhu{&|yZd zAW#9C04X#QiOgfv4_&AslnVe~Wzg*9lTY90`4{IzM+~7=l&zaj)EfS%5LAT>9X7a8 z>(CdKV*czIJo(IYs%#%AZMfP3;h5liZN`8Z+9Apft?r>q2E+NM6*?$m{V!`NPi63x zX^qxSwV^2xMjkOl-dd3@-^s1lT*2EPeGzG$hC@MNEJ%?BG6?(KN2xSxe%Z*LlD*M) zqQe$>ha#=29Vq1mgndhFSN4xsmJMli2f472XXFS6Xn|5&TV^ewR>4)gwy#pRuv+hX8#0qPd zi^pHjYjdV?*r5j?vjMJW%^T((yc>VUYPz8o44*X2SBY* zfsYepDA3A;HwY8VA}AnRzL&8VjpUb2J9%>2Q(S!Ja2~n;VSd`QgG%`AjtqjF3twn< z?b^=z?P;2~?g~OsuYQus(w$TWHe>;ac^+q;cL4_;HW32=KMQ$NV5n=B7rG4YzNt&|09S;quZVH^3tr4x2rv z5a39(uHv5CZ{XF}-^PzBnFag3&~l=)6^uOV6yBcy0T~P0gbdvQI$9WnbP2VN&6734 z31ez9D3v9!3xH5QU`SDwBMktv-_vN)8hn8TmOerRmd+$}X&MkKgs~jWd;LYGJ^L&f zh$NW=85|K9@4FP%^{OJWWg#2_AxWc=jvIjz!_AdN5}>qsM}d~n=jbc}DvT5Yw29Hd zuKkK%gD8@N68DkI+7jV_ZC;lON@qQ?RKlo(_sQ zNU2TT15IEi7M`O(+BjCNjOMhpDhd&%76nMh0&$^8`IU^hcoZwX{SG07O(L-^*P#tp z5cnB9$Gm?bLPIj2FzbtKKmWO8K)1WO`{sT{q}s;ZQ8{8jaxZx z_}LtD{9%k6bviq@ZsmtxHZu5xlgO$xSB@LU!jC?~l`-p9wuc1apuHkmb?DB30X?Z- zuLhn{1VI*ua(-O7oGm-EjJbLe#|=4(BM$7wj!j!wwQ4mAft#p9w_ZINdB!jjekI$s z?IKP1K0+Yq;CMCY+^H*X&7Q-aO3fX2+)C$GO*r(ZA-pzwCj0N#i~a}gPfTT)`{FDX ze!hZw?b^`2XBR&H@LkTk_%bdWc?Dm8wus7#6q!sF*=!m|I0(l>Ix!UBEARuWE)u}@ z%^UgVn++`c{%6iP`vN9EG?{eSF1Bph`rB`8c>_@e8tEiZxM(erjtha2{!{hr9yqsJeF8EEF?Wy@%&spQa+gE@3aKVE)yG4+it2_R^`igyW`8BRf&2eAi|^`e-?IEkPU! zsT?(FG6Q>;;7LfNU$1VYY8qN3z}Krj=T7dYPw$@0JZ>CyReM~H7liq#%apd@Mq$guz-mHji`JQdO z_s$Yp0|ur2hj8@KlOWj0M<0L2)}0mjgCV;0>dTa4CX?#c*!11ktp4H)8d`&-<`iSMlH`#t`Uke8p&aVMNgda?_QFh6bD$fuvJroOeEqORSU zdhF5UWTeue6kv@Q%mBgmMxK81Zxj_|GIQFIxSe5^e)t8A&F%E<(~B`f2k_o|@36n2 zje;)SnLhJm5?v{D?Qsyf*(o^1q`9_&r5`P)x~7r70}f{F`0=E;Oxl{O`EdCsY};K! z*B)J%Jn?V>zGj|({#ia;`7u*xp2WcJomsj312$~lNm6z`Q>RR!Fe{m++P%EH^h3() zTFLL)ovsD>G}hH{!imSD6JYuK?~|C_m0(Ld&E94vPCbrfhXZ8MT@%t&x$RHsh z0gubY-km!M`NC}9x*dl{!;zfMsL_L2`quM&@W#8`d;3io&J@m>kQZwMx{juxzOLH3 zwhdV@bt}r6k(!Q6gRPr4(zmETRdr2hPL0&GBpbVIl}Kq04TotG2?eZ8o@wB)3#^nW zm_{S-z48jLzVbd7Tz4ObPZ)(}LQQo!-)!8;p`%ALeB`0@E=*?e^NVN;2DxOxLK3Bk z`)^->O3dbkCm-j-H(utgRh6K0oNhNEzn^xWiOZFQ=5kS1whdtdAyJ^2BqpWe@<6xF z{h2?19)(${1cD9*AJpBB7XEf-L4ZsU7ui`we$+9 zWpz5Jxa{#0&3-B9D1ouY%7(AjF=F&svUA;-5<&|`=vth^s*hgh>-T;9^utdy`Cg<~ z@hK!GCa~+r?-`gofU-UN!I4N-W(H}Ua(H9e`*@q1c;jzRvSv>`DIRxh`2J!4-KPEC z+(1$45tJgYq!$Mtb`%48mr}O#J1)BP3R=wsBJC}lfA$=lYO(N?jA8?L>M zJ@u`$Ha79*;@9zo!)Qt;ze{HZA9^JH`u4+Ys%6f(bJ$YWNT(Ey>#w<-uh;!VDAd5B zMSo*grI*suzGS7P+bL)j1rdU2a{pa-vuxQi`VQ<*qQ`|(wXx@?Z#n+zCp`)WKh0--Tcj-j8{6y|q za0g$1z7B6wHMigS06uY(ot4Hd*Wb*u&%aDa!3Xay;p?y0P+U^XPhWh%J@-6}4~?JJ zujkWMYX}7byuRoeD)+aNUtGYe&pyKZ1rHLEFuOOc<n&R*JHd`O9^evuwp`#AxBs2kzl-uYW?0bd zE)RYC4`A%*krbpS@a)qsaQ#j9keHIfx|JVr+1!h$ZVR&Y`whJG;wz+gDJ3U6pZ2;c z?!5VG8vQ|xU^`DeypXMxwS4l~mn?aEDMr|ewu<;z_r)hX`t)n$7I&qowt_k5%;BeP zJMf!=X$H}-_#-{;LZ!`R7dgo^ZyOz z`2ga4ErFEmuAF(=bgH*)VETkZIsW9?v>Q&#l~Z90o)A)q9SOqFtW>=T4#Ti0tAGem zNQDJHu#_^a`_Lss+152oJ!UeKrkz1~o0D_SKAQnOdocQt?tHxXX@(9S#+A1`Ot)Tr z7&)*H_szeOOXpm{iZ9mVkLdU!0d!4A#EP0FWLZ*}kKS=L!w#9ib1%J%&z(RR2VpIX z!GlIKd|+p;J%1*{hmGTvW#4k}*fI3$+XF+QsvU};VW4y!r_-vwmROm;0wT0El(TT* z!_@o2y!X!Q969AwZhPPfUVr9qoOSY9{O#3`NX_le#pg_;uBsMiMk(i=I)iklPIiii z`ih+_T=+06)@}l&gO*4^aUs&Wo3l@wgF7jYlHz=pzw}p*8h;eu?c4{NPDXwqXPhyU znl0s6F;^CK*p$ctY4hJjG~y5Yf69KBBC21SHDMNXEoI!e{$!W|UVZ2V z1`HX&rB_`n*Ca#OpHi~+=2pn_b8>Xuozvc(R3%JJ-c$`5hF;FAmLy; z{RbXQYhwjt4jawOpZ0Hp zPd<#pmCXDb=8>E1$7g7~wfId&_Bjp1)R{EpB&Lk(VeL<2crhEFi4YEj$V^Y6XK4wY zOMBur>sWa2-He)WELU86HHmr%Oq1&_oJ-fPJ?Yi653ZiYe6VUGdn;?vB4K*=IfyA! zkLQRX#hiHl0_vI#I;ARl_U%V)RVBkm4&%k!-k`;6VunMM^c%#CS(8aKgM9hcW;9(9 z2!~nv!6(eS@n(*iFqXDy;}|gVbUyv`OHP3E|<$V^3s6&kUR);j^z+amHCE z6EUFQfFYbR>r_Vc$z$$~iwKE@6BL{lgduD&e)4e~F?KL{i9yc&^XvTO>hpQ(uMaS2 z}2Chxzs1kDs8D4V{;9;c>N=;3fDGI&HEM)oMc6{#iSZ>O|RKTer7m1Gqr z;A^6^=RveJ*D+{tUzUHmin(WwM;Q@JrSth0pR;rOPR_jgFQmJ}j2tzbZ@>M4WBaG^ z$%;?8{)smj*RMCq^x+Tt(cDQ48ZwlzqX*Hje>X3^_BJ=&^%#>U^hG~yGLug@m$e(W zkgqu@F6qMb8B@vic<_~P<(7b#wcq{3!Ntk!+EdQJ0RuRD##A($HO8_C0l$~5;_l3x zbqeXu891(-$7i3dWa>$?&~+UV1DC@|w~`)|l~vGxz(77&zLF+i0C!pfy0SPPP1WIo z#4IjIsOTt;dR#M;8&am-=IJjRo9IpM09y^8}U2;fD zO=skxqv_wX5T$gKBbCCgJvd@?3(1<`!r~ycQiC>zP$^Ij!az!9CMDf_pedahr<}>5 zhx8;#g}DETXXyOsGpyUVm2s1%ao#1DQIelQpWXx6ytkQvIJx558O%9r7OwU^j5&N9 zMLB7trss0kJ$LZrqQ!W9E>hF;NJ`D&uyLcw%gUyppoqUd{U{GTyokLuEu4D#dCZx6 z8Hvsy#XScy_D~lYX~}p}oQxVbk}kPPq+($TJ6Nj}NHT>z`r|1)2uux=Fbabq!$&fC zdLu`S8;z#9Ir;Rn_+-s?1|Bw(PKhpbN#*{>o+baG=h(h$4~0ctnKb+evNLn&I%Nj) zudiimO@wY;yKu*Ycai(>Q&dzpGw6`f3_0{Dk`hyyf6t>7_Z-4UpRT0QuQ6zFKim$B zi2OIT7);xuJNwi5=im(*Jo3n63_WxL7o2+*iJDMUkWWfVl3hfoz>&g$!NVv>ONny= z9q4*0{rmMHC(!~WnT8;ygN*#{4C>blH#QnuCE#!>lomn~v+3KX54oAiI5a1-&p#I@ z1~0$zGKY*ljLR>(6psTo{kVw-A9{*@BS-Q6$9I$8Da#^LvLE6f!NC7+``w*Dv9~&+ zlr78-7*Jo=Oi@v(6@=1tx^*e!>(4(VY=qIAZcL>i%A~Ms4&jg=Unopig)vo-h-uOq zaFLy!i5q*TDs<#z?UamC4lcg*5?)*UIu~6yo3Z1ka@pDAts)CkvpDL^An&}oh{qPM zVB)yZR8`avG7SX5j2L!g0}Kh#*wl=cSjpzCS?Fej>#n_uf}AvTM?3{aN900DR31r4 zN=hOWj-YUmAfrfF+L>qI1O+13S338pDDdHv+%W+Mox z=~;9x%%!%v98(RmC;aH5Z#{nl(~bu@NK4PcEn)orHVg$2CLC_%@kbW2Wmgrw`jk>t z-%Mdq2-Ad!=|J!xN~bhGgXQgwgbV}IuAMb7@pyEcnn^emjX>HuyqXK;v|tFiow6{3 z?L>k;%FFiBW6~6Ki^T}1sadHsF>%wA>7)9d|4%K3Yvn-xBh=^`)e9 zVMm6`DnIa;p@ahv@CWgSBQ|E# zKs1M)L5ou6*zHyl1L0c^;=d0SrlEl|gK4K<%(T{hdKR)J-D^2m< zl9yxc@7`ww5B_xoC>sbOpyB4U^DpC1=Uc?>3SsfvFN4v>UAJ9FeM=Zj-QMPEj2btY z=igjvCyx~o)8g>cOp_5uPPH8!!I@pc3ya^h=wwX6R7n){ID`it9)^Waj?R{Xh{07i z+(J}NuIG^PJpRmh6jtG%8Rc$N>6|h9a!$M8Qc!mM@7HuY|E*@F?=^cQn4+V*J8{t! zH!|mP-BO3NBWl;&as%iZhS-Q74( zcoGQsd|;YHeC>Sx>2i*lemZl`na-L|ma+Ptw?NlONpKTru^cs*?jbun8)sn;&OQGe zJod}$)b$web2QMdL_@cAMq`zrK-jRRVwbMaBuqkb8V)7w*}k8m!THpdH&9*EN|%B> zD)yCGm=Gl>w-duIUWi6J1aK#~2>MzO!^-In=u^n*XI9hP;w357VEc|8)Phz3v+Jez%%OU;744R|L(d$AHCP zD~gEWK+`qyQ{C*^zLP$Edf~0AV0&3PMcsQ?4aI4tSCnRZ9abrWX+*#XvcGXZAx|oa ziD|eD6GzC8-(Sx+-)~~>jSn&6pj;YT77`AGtl}9v&8RSO=@$2yuE0>1iiZOS$~3Ja zRs)b|v4_HlR*71GDZ++Yu9qd`B!k%k;7TMNU?kAF8kebqLiX*=K@+=TbMZY1bTGN#{rfO zbki0j5~i}MmhO4kDBS3xlj4G4dkcnWq@?7KlakDLt3RgOiDS{4160>Fke8c|+TUi8 zhYPrr0(T;_FT0pC=iJDq4Y^F2brC6UCuTT+VS?`V*wwHG5Jn?_8H!*yBmB6lhT?(! zaUp1tc1*+1j=kk1=ah2o{2Qs=vzJdlcn@o{5x^htqPw$kXd%o{5Wh+w$>~B#gitVm zxDwEHoenDP|NG_5j8;IKb|H}Fh&fL2$xzW8(L4iDa&PM$*J6&9hQf$M2>E@yzvO*Z zeEnl=qo#la*K8!I6A1}^6kwW`MzwA+n8(`G@oL%(1eyj~v{=iME{t+u>Nbip{@@Pe zX_Ro^D(o?pbP!O*Fco6^BOQFK;`j5~3(vECpVw-;0Jtzy3Yj$J2un6l1czqdoo4Ak zTe|^`4l-|BB`SLUxG-+)PvyW+9e1GF1od_|caWb07D2hy*E(WxxJTcq-^3JX7T!|R ztm^#;I+|va-N$IX6r$VQ2yxuEQKEIx?cc>=0^=_c9c)Te$LDre30N|sL?4+2L{~96 z&p7&V72PZesE8F&{{_O<8uNe1#{Ku%e;^%fq8uK^j-SL!*WS$)b763wQf5t^!m_pZ zaP5Vc;WFCr1$8dG_#*UB8DVb=cinb7g&8`VH*e2cCb0Jv+BEc4!}FoPHMbZhMHGyLOV6;-PHn{2S=rZ!nL(cpLLCzk$97b?2NDj^)#DzGdE3mywm^ zq^91-^*7#XO_It)QvqwiQBmGEYobvCnlgCy$;a8bYbWi7ldQ~ix|SZq!B<|-W!K%! zRTrI4cBgC(A2*S+FT99ruDXg#F1(1GtZcgV?8TX9oJs@-3I{GAq}-rP+?vqu;93I`=HDyKFAqO1hEY_Hf?0 z=h3^QfRj%cO_!-592cQ(4F;r99+x=}w=b6qbCmlL^O6LX0qX-0)|1l~?h|-<~8T z!BYBgIUQ`?_&rx$a}DlrGfiy~P8&aoG?yYZNoUbZi#cxUbZYBf;EF3QLq&w3D3Y8y zd$(_9+T$Ou6pP(;93plrJ3y6j=Rn0s@kC1(WS;^=s$k$ zuf{*txCpRyrfAqcN{VGWZ*j+Hzj&th2hy=Ih&I&_iK%57#&627_=o*JXff^J-_J}i zLzv+Zdn)$P(r)0%$e?FY4&KIU_EpuPv;?yA3(3h!qGtD33_JWh9)0R%I_G(Cr=(C^ zSVWQz)iwLj-5xTsv(Umms;X*eYG}ccm`c~u5R}aZ!wp=|ap9H5EIk zuWupjOd&P96UBMCxK)7qx=L#Hw_=K$?EC`qvr=eos->!`nTTPMl9@$eVLpMDW?Fqd zvI+`u8V&3$Yow@i2?_Y9s;Z``Ie>veOH8IuNf8azyJ*wWC@d%-fe39)HPp8m

+o z6A4gVT~2+27f)g;d0o1a8#TpkD26?+K=A>wdToS#Q#qQGL zIawINM#}cJP}Hpl{`xAs5k+234t3>aBy`FmE!ji3-OIMJ2731@B|-O7SGSManr2K= zx%Rp{xc9Cb>D#x5t&?p}*~((WY-??ztgH+J7sZ7+ghGB=O*h5)xwvR26!21Bu^(T1 z1Wk96nw3pqisHDVj^LCVALE3h$D;e{Dc@I1n=gXqNu;=QXHq>1Bh*S|Wi8&8AdaLo zx|MWAf-RJlRS+_Catn*dNl&JxayR>1gD7VL-MSQ$;&Id7Tti)R8+lzyaj7s4<$y?t z*PnTWwPitWxa|g##bAGBErD>DyspKT7)$JN>}Ovx>(3WQv*}e!4w-$XJ9I;qFou53XG;HB9RbomxEBi zD)2C)^g^Op^dkyuv9``?|1B{IMNMo@No69+u;3?_n}&(gem?}=w8of#^*gb(mX(Qt z6V0wJjun82vLi}j>33_kF1y`ty3L$#m?lbhS@06E6?vl3Q8PLxLewF(+GfVNrB+PU zN=lfBX4q-x4o@iRj9a|0x|QZu5uyq}Vk=@R4s@LVt)?IxiLiS0=Zrt%2#6BL+wG4d zNJ2A}{p2(#cWjjjX`_12dWIf(DNC2HrhjRw{c>9*zhFtVSudR#3x6Ai!L}Wn3Hl@U zZ*&YaGP1HLDJrlcbLyALf~fF_ZVKofWWF(S=NR#^eWa~XB+8PL)0LvRc|YalO+zE9#1Ivew>iY3q}bSG!m*TrVC5loTZYXf%Ic><+{>>} zMC=qmR1G)!xq&IVb&N8ot*)Y`x(;mlHWP)@oj|{yrFJ!&Gj0O1j*qH-2q30m$wb-L zh$cfY4C^>eL$jCziAG1_Qy|tfXH{>TO0)aLdd^}?Vp(#7257py1e%2X?d;jLlVI2$ zTY#oCa#MmFanyJgJiCI4hYrIN{R}}x`M5MU7FkSmGL2hc?EceY|BsGQBQ`#xt&aW~ zKk?gje?+xX6n@HgZQ`xBm(eM=fHfPoQ`ICqaLW}m*6cwXiGXGox++S#my({GWTnz# z*RlwFtnm=9yrMu1e9e_S_2eR+f8#@*ePandy5!*|`kq*vnbvp;p^Jdw1WiMz4jUor;Z^J zqFUva6V^d1ZrDzsvOCGNm1vx%VL4-1vWP^VgB|-dZEjE9?09Em(Z;ysMbyNW*#wD; zsM+6*5z3pGG398(`dAs(wQwOe_E$G`8)s%y)2Qf(r{g`Bc-kUtiOl$DRNQA#IEfq> zm&86MdhWPS;-0P84v}U%tA_F<0+iFYD@ex-lE2|~n((A?Ba zR#vwC{@Ze^_PQ2*9#)Sy?H;h^&8V(X2YNfI^Anvfe%W%fV}+n&MT&Qh0X|IaPn3H;sD!IrqZX~_abu_zKvZ|DbRGnA9m ztP=im(>w~Z+;M}rBlNCfQ;A)%rWBEgj~_N{q@ke&u(W~=%}I}g`chI{7<(b2;vUh7 zEt)D31@n^?1EJ;9)1--O_Hr_d=UhlIogdx6s9 zrmLuP7VDtcUBN<#6=`H2>**S>&U$ir|105V?5%KC0H`SRE zBR%%D``NJm2bx;FRw~039J-s)qX#hW&-c==vbt@ng?}KPWVMy(H~SaYi1*G8aC(0BuLDzYKRf@geEZ*P(U(Tzco>D~ zmf4CB*<)P&$@ZbCcpvS5 zwCLSfl5D0W8FqkU+R@n^-4~5ab=cp%o*ek^C^erh9apg^Ff0`fP5rWm#2yp6Zbd<& zuY5Fqf8aAPK|%;lOm(1h`mek_|C>l)U0oe-zWF9|=FGA0@jypKz>WgOD2RPallHb28k^g! zB-B5=q*Vde0fe?f>>|Q<-+jlPy?Zc;O7lbqwMBgr1teQ{X|w46>{?2NY4^6!;_kW{Nm^5 z=LBeOZejr8KpwxpB*&6Tv z4+~mh5|IvGP*V&LBlgZ%{cbtV5vA-j_P;TD6@6uGUQ|P(#Kg*~2p7=BKqCS~P~sq> zoEVyJ^A!GP96)P>Z@~b}=p1C4v3DMObBcsegl!2z6*nIKckjr*+cZr(U=Gy8w4G}U zDHJiK!^y>xkTY$^R!k%I*i2K917`!^Ukl9qGwb=!KaUkd{bB!A_Mds`5ic)3c^^-_ z_%;Fl!D0&bgkY;FNJm1(G!2$7UBxd?n4v3Q3*0Bh7$o0fN69X~4JoEU2EdAtj z!f|N`rR->+JsC-)nH#UZfDcxEMVR>HkcQH9l;-%^ZZ!U`O#X+v{9jr8gwedeo>yLc zm2e=;>i6H^xtA8>k6tZG0R4|FD#Bn-PF4k*<>hQx{V5MFypQHcIHo;oo%X;TPD3+#PB7>&{Kh+A#gLOe*!URXxLAETgZMctu$6{ zWzKn*^7Rip2!LIhp?<%Rga`#&*;QFX2y6Uk z_NJf%pZWiSMNnc(>nUY9*(e|c1TmE&2t*`;!eT*)02VAN`Xqi!rISDG5BsJ4?wG(x z#6*`c)q6IvM;Yv{*hi;?1oE;H@wEqOZfyr3DJ_GfBoCU=PGh5&K+tkb+{r1VrKRF@ zx|w~+T(kr?1_ll@Kx0cAUY~)}>84YsEL&glhUIJm0Ae-MW|fy}II zoVp_DYo)oRiBLqL={ji{nIt86$nBiRpKrT~gcJ{L&HLH8y_WKdN;)MblADo8Bp9Tj z$%kPWq@<;jl$?xCfHtp>7HETX-LdiHSfMpSP8k_7I37Eh7U@q6b~V z_T4oxF z&LAxf``EpsiM{0&coN)XXQ$HI=*903B1(~!(+Rf@&5e!tf)QMvL^3imaB2!ogOCxy zj5&buuB4!d5cK(IYH25EKw4TVX^9&9>l+D%Kof(clvDzt5aDnDJu!vM%uL)EU<7Gs zY{DN1pc)&9m>QZ=w70YnHihK$bX@9}JJ+8FnE!6-SR@u?`rmKK3_IIk(C*#O)~%aq zZV6Ibv5ODhUV@(0mk~Xaxa{J&e6@Zn-Fo$)xuu@3)_%p@%dRCQGnNTJ` z&Td0kB8H!*9(sVAZukqYtXjjU;e&8!%8pj*L{-ccChbkNoHpwe*6#AMVdEw;6BI5L z0cA(O3ELQRhed#H7sZIu<4V{dN|p2P^0GSm#e_(JFTYsL-S^zjk6U+>o{`BJ=bXc= zKmCd96yb{%pYX_YAM^BM_o6ur9{KCzJhONyOW%E)qTCF-fa^aLk^RH|tL=Ap0(FN5 zroySik6(Yz!h76|8$FO?#&l=Fg8Qj$F)+;tW>Ow^-g*s*;YyC3egVZL2jOx;eM^|R zS6s@(aU;0r)?4X$$Pi|pHj9j5J!|i;&{1fVH>p6VvKqikF$bEO;MSE+I9lL8e{;av2J7WkEjIjK@ z57@J#o@vJ(N@-4jzuff%sVO-$*45Hw$PwId-6fg{LlPEfP3?ZMF z*5+1I}tTRq#?3khGLJZHPFmN~xHvRA;k38@w#hrUH`}nb( zeai8;O9qjgRl*%N&13VI%XsgjPpEEEWagCczymk2cgHp^zi2iuzrU1*`Wo)KVLm}u z7Tz|Kl=Mt)x%(De;TmqaZXQ)$C!Vy-_ctv; zc#JlldGrxJ{c;WN^iKHNd|Y|O94c$-dFTDFdHlhf+4;jdF23LjUie@Ixrq_Zo_Q=& zFZnZv4(P_6^Df1aT}oX;3q@UfaP!SKu=c&zcwpf|3I~p%d#{7J>WT|+$2mM=1Q3F} z@ycRedihP#atley>B66{y@VytJ;bt=Ye~(>Wq)HU=U;ve$BgUE-Pd2pH`{!4?wn6q zRV~N=={(M#HH-vhuwm_L?z^XjJ_naFW!fapo_Q9T={cn2WOB)sbNOlQ*Szt{Yb0hD zvcKNX$)}#e%$dg!CX7-plpVXUA~Fh;iINchwkGada2K2RR->onG3D4POc~mVGiIGl zX4gZAv{us+2$I*iD`v2T-Sr0dKDdx!UDH_l`U^bu>`SEQ7UBwcY4$}h1)hBPA@((U zx%tioI2?`+H%atZR5l(;rp3K?_F%T6*Mb%HKG1jlg~dm>E$oaSAs-)p@BtgQY{zKc zOTf_4H79w6T^KfU6k|pVqpoTWET`OVbUZz=cQu! zn|Sx#Lp2eGlf4VZ#~J zzc(&SYASZ|{zogQZfK=v?>-zoX)?(!gY7@A=d&-qqrSNrU3W6fY&vLw!hatm8(7VvXd!Mam%CzaEYF?Ipu!8FSZDi+UbMh$@&{PO9 zgctty9AA9#1(#lUKDE0yuzdMvw6sSk=u*Nl(~c)e6rQkwzonJCZ@-sbJqtN?#u2=> zcqu_gBIo^SGRxmv#?~Fx%sBIGG94k7zPp6IHD2_TG)|a$3?)VRaZ&ewgQF#aiHWHU zbR)!9A1~qd`=8*1b1&l7{=I3~x0S~peVmOutGVyi3(++b4JTS8#50Q)v0=+T-hAgB zI^|?o!_jt@EhpA?^8W)4;U8qt|Ai*Mx0xblpj!SiccxrC|8ChIibyD8$kOK?mUGTM zTPnS6Qrl1`Gfq51Zn}QHlx(tK_x?cgjgKj+5H`b<*w+O3+s?FD{%X6OTV#ssmvOM*Q;4@|R@Fv}sb_ z)GW=dO>*PB>t)u-r$}?iD<{vKDGTqtU%WoA`2G9kmRlFdrB~l7hUt?9x8EXXpEFxR zrYWWwdkEH0@KwnL$B&YQi{6m>kRjo4MBe?|eR9DC=SY>;EA{pJWcu+Z$}KltD|@yq zm$c3UWLsH{Z2$H{$?ZN$c2_q_#kMsvWcZQt&4$h5_czP)k1dc{XPheE?$|BIPM;>N zZM$X3TTe+*PLV8H@}>N+Ws8jHQzARdHp>k+Tq!qRbA@=@TBV_;Tn-sNN+^}X-7DXJzfO)EGfsAwl}mfu zetG4&zse!wj+dI6-E!7(L**~`KPFy(v#eV6flNE;Eb)5F8ft!&{s#|~SKnJMt==Z7+qOz39(AOAUsWs3&CSx#&>+FsQ#7of z*mE`PKSd(;Puxc$A`%f({K0_yxbX*RYHF0Grlw!~tX{o3*4_2>_44SWkBVuAMT|E2 z+x>r*?Bookdo38dHT_t z+$GQ_|$j zt8N!>uubl|{ycHHJ(8K8EJ-e1N)9?yzS^`$0wQ9>=2JsN0^+UTA=4)glY_eENI_bn zXpT;D%Y!e={kL8#9#6X5a^ItJhm;zP<9;y*EgPu1j{8-qLf# zM5%1_%4;t?B&9`Z(m6j{k`t2T^s5#~O~XE!dBiZ$64Iqp_mMJv)|pbXcb$wGIZ6hP zKVJNy8oB7yW2HDJSH9e|Rj$4C9LY>ck-}aFOKy*0^4ZrL>=7azYr?;1d-v>>JMUT` zhS@5iP>qZkIZE!m_hIpeqqBaq?BBOp4jC~)zW?EK`Eu3kGULS4<%%nBlF7%;l3f*b z5->%=hAD;_iH+fZQ}h0>ZOM`)vTohF|8Oh*u;1ED(;8`Cef5?62QYy)$CpxwBLUr^ zqZ<)+Z{JDJzJqWjCy}0!#^^%^v3=tPBx0bPDL6dIBqz8SG5jC`ZB4ZL{WfP@grJ0| zYG|i>&pvn(TqL+%@%31i**m~LoqHZ{yzwH}Ty-@Yf834{5dnLs-McG!@Uf?vbleGCe92t;cFspd0%*SiwN!v8 zh3AXIvQj|?SOqDrL|jfCj|S`4ZlJWZFZl(9BqzD(*QX~twrvN8PDFGx zcPa@9E=!5RjG&azQ6U21h=zd!-QmEYY3RC@9@SiK5pz zz~OM<)S#+t7d?6p;Qz39-tkow>;Hex?4FX|APFf1LMWjZ6%kMnu^}q<-o4jeQLi2B z_lj5%yLhGB5G;raC@O-|q)6`xB?QuwlXG_G_s8s>a}v;NLGSne%=3DoC+FP5D+KuAhb1)2>p()Y=ETML z@Oh>70D63wJ|D>`vG`+R35Zx?;$q2emO}N;ZS35>g^~)Ju7?gJE;fdw1Rs7=(~HF= zC6StviWedb3sJF|u2D^+@HKQ7>r7I|2q+Y`_;t~5f*{ppMZEdOTQtkb=j+8wm^*t0 zu^wHjVRF}-xc~ql07*naR2WFZ!1VY~p%BUzoOQv)tX{jC%l>u+re%|s(UN)JEadY~ zr_-^Zm9DSbe-cnZ3|rBowJ%+7Y)-$+&58j{hF00pXAsDD3xmgbHee@w8z4s`Snkfdj~Wbu-3 zczfc@2vMscu569;DQz1QNzj%Q?<^uMIhhe7{=u9tKjP5CyNBJ{2QA>v8F&JVs_F_> zZ{0(F+d}+?i%_9ROK(oI_!#!?+=-=ZzW(|vULQA(tFF14<}I4x5nu@0VQh*-i8e`- z{FxGV2dh5`B1Q+62!u2VRPMtgKzKYfOHXIXj$(~>XW48iDke2O17Vt2^))(wOnBJ0 zw;E}B@ffCF^reYV5}%={tkk%GLbw@Zj+@Bw4N0Nsf7}Ul=+TL<=6%n-_dm*O&)$yD zYa;ES-YkN(OnCVv^4j(0&Koah@$8Se`-M+Y9s}tysjscnxqYUW(3xRg>0~gYVPis;jmH;@DHY|r%OIf{6=k)Ql+}=wlt?Wa z+Bm4dYuR{YB#>G-kPse^K`>Ab=z#B*c{wcpaTaxTwZz35>?z$xYHF&pNoa6Z7Z4cd zt}yMB0KeY@RtRC+n)Sd11C#;!JYK9|tsa!NNn%neyLT?p5W=?2`mII8 zCN;z7kHNymMx*R2<)KH{wq(Qwm^kiDYJy(69o`MsW3}JPsv^XG*cQ#wnz3@%4xKt- z!{+TfNNL^zY4{LU0D(=&@Sq3+inR0$f^`+tRFxy*J(TaOB`z_Q^yFB2b}V4Zgb&!V zubN9Pzl>Y2yO~+Q;2~$@F=I(eNM_(M$MW!lcQ^{BBqk=7jo-}1BL$|DaT}hFLTGp# zVH1~_OrWxy+I^LX=5c_RgoH$@D@v)W3lQh?Qna%aX-HyYb+nf)!N$~3E5ZOg#QOc% zff8q)=*}^OKu873A}&6TU~M^-rB%pu4`utxsH_VR9~*;D*aU1VLT=!WZzNcf^yV2< ztk?*lAjbpTA}Fz zZ5JKDcA$ME!tkNY82v1}9>Z4H#GnjMl!EF)|2pfGgnG+Di5QfKrES}Ma?=x7yM7h> zD!WrzQ^S$n4<$CvL*GNXQ&&BmlJZ(EzUBssO9I?^%MD}~bm#5|N76G@Lt+`W#4t^S zl-SbLDN@Qt1r=T)@CIwyyQ6}D9m^2|jv+BAo^}Pf%v!LJy?giQN(nzmN&B`fNi-~K zD(i4lmh}26oP(C6X#IMwzv^bZ>20{@zB`DQkXqP@8w$H(*g^h&%_Z!qc%CaSJe#hE z4B*9AMqmrC!ziuesAaH<2X4NNIm@@w=jg#yR8>*$t;MdlQCQR~iES%{sz;bYE4-GI zH7vZ?c(J92JMX!d$45TM-M8LKUfbS`eC%!pAKv{xh5`I436~@B`(sHfx0>>YXih5B~lZpq;rqMIdxDUo_g$lg!vH15AKU8j4&xd7`Rsa7i=?4@|TrA z9U{g8kRIB!Z^xG(OyQlkX7k>Rx%3`%6bt8k%;Xne$ZNO>vjSjgvZP3EHyzvR;|zau6&g~eaa<;SHf*t&Z!m=a|`k3+ig z(OXk_``x+Boxhx;jvdIDQ6ri9<~Tl^{RPuL`ARE5KfBWC6w2tUlz@6$kk-5n1A2F5 z_yt3m_V(LcHT(%uTJ`3Lo?S7iMPX|e5@|V`puSlu3j;-q>~!XRI-QR{n#Tuo7IN&+ z!R*##k~LCM~r`OHsy5+ zTN#8bg~Cs4Y%Eqq2}{0Rz?$_%l+-AK0zyJ7g33%{$gzF-^!=9@{p6F(`C=LWp8OFQ zFD8Pv-FO zlM^}pv@=NbNcs=x$C#Ji0#7=J_3TOC4(Tjj@HxGX?1te_=k${X@%|f+^WqDy@cG;& zy#MhR1h6oK2}1L#gdm(9sdWpj#&qb|i=M4Bxb^&D%y@qWuS}guW=<;-Jr!L0w@aBc zc{+c; z#~g0Ea42uRGnF&`b{~0N`_ZXY9yw`}AC@koXkR4`3X{`|0%0c6x8DHvtoVX|Jv5SO zGr!=|c}qZe5X!a9Yb94Iv{g|GLWY+Xx$U`l$dTNC&3R0n@)jS={DwLeizy^eJ^Bzg z-+l-CLLuisC#b0^=b|%CV#cglgzO+Q-}yH!+xKSOjv8z%?z-t}9(d?Jsw|xyEtSR= z{ngeMVUU>GjF!#4lx$wg@}HlFOv=13KcWP1x6sX|CJHIGC%AU8U5Hx$^(OV5qv`&C zXY;q~hO?%)nsyz!GhynRygv3(e)x74Q$Lu4@Fn6E^=w(Ol-k-__SMz#7zYp{FW3bq%OQW-R;6ADXM#3Z#~%&RXm z?!{3o`sN!x`tS>CEl1J%4Jknf7VXWlgdd+7&(&ui!_4WE*tT~s3JBHL^77ahP_ap5 z=eI}Lio|9uxaf+@xc|=U89DrFR&Cr(Eku$*!eEXEtBy_5B>!2A`|rPh1pFTBU$jF; zM7|OY4_*y2%!H(U`;K_Lu`FM?f|S%m1|Hdm?mZ4+(f5m}sjg-C9d~eOw*qSSZRdqI z-lyB4eJI+to^m3fhvL-GUxHy5jT2v2fvHs;eqF?9gt+_&pjr z!?hj&ix(|s?w1SLU0TK!mtRizE`_u!XiHsPh$TxFliebVv(G*ckbL+3ckHXI=GYTX zC?M6d&??WyLJt^IoS*ydLkVqOg5|w$g>$uB{RwOA)XI zeftj}!RMv2DnR>AU1-rPm71D*GBR4wzHMuI_UJ}Zd>o6H{6L4!JsB}_1kDot1Z!(a zPEDa(x9*q{DywWdckV`Vd<;Qb(z8cTax&71Pe|dr`3s1TkD>Qrhj7fGV_3arBbzpE zwj;Ayd?Wlq$J!?ZF-eIuOV4D{q9q^%-Me>DT{I)@~?b^_sObZ=Oo` z?w!fb&Y(}9zO4LlBdgb}CO5kU{rmSLHz$vkD^_57O^zNkkiLEUv3AXmlyCoek_ zQz%lKH=|p(UMya`j6hu-xBcS|x_9kBa(p7~3p!9yS&VP#M%T`TSb=&{nl+cDQ+L|tu>pL`u9#K|w1@D{9Hl?@05Mc--TR zKw#T~*!V;aKjaWLZr;lBm8;0i%%DTNHdF^}diCr@j7L%%u<72d2T3sob+vV5WoOa3 zOIMCM>PVV3OJ%|0rR>;U%5f(SrAN2U*nt|Fw`f6OVWIO*K`EQ+swz5l?MX(nG(v$o z@FsB7QGJQ?3TmsX$Z6Gv{DO9Pg-&3xESu8OQj(IAqgJMf?B2bbyu3UBYHMp*xpF0k z9@-nj6GMLMR?PqYd!8Tr0^?pEhc6+M)6O`P+(dZg-%~kkz_GMznZl$g(lSpZv&3PAJLaQ_%FTOI7 zqfb1Y-aWgpdCL~YzcG&I$Gk#vN&;CqIgEevZHAmajJ}8WCRAO)xN)!X)U(fn@Nx5< z_i+5cUVQV}CoEX8g)`1NmE<@dV_zE2fD=!kTepsQ6b|E%c86B%+RAOW-%Ihn8fJYq zljoj&h2q`236>S}?3mZdZPkWXpLv4YZ@-J_AI%{%s}8-bTWBepmuU$=ctM*)Z(fRmPIbY3Nzzbtv=i`~5bLk})A#BAr^XBl> z=;v6sVGCKUS~2X*VcdJmE!=(caHdcHfQ+nGTz=_=bZ+0;!Lp3(1;0ni%gR`>VkLe1 z_Qxlk{{VA>Y6#%~I4 zz2jbvI%)vvX{kt;r@6tuKVR0aT}whj0$EvE|CQ%A$)6`e2)1wEevr6>8x*0nKjkuX zxR*Hpv;{ypr_5-#ZG?T*yD@BC;5^-^u)8u0qAbF#Qo@Ne(E&18(&0Z)wvHck zq@EBS$8n;Zw(2%UzKQD0NI(9hIB=;-->-y<^sUPRAzXJc4Hmt~^AGT32Uk$JZeJ03 z8_}ru(f7Fk6PncAqPTbiQ>M;h)~DYyZTfgjsW4o!_n&BIq`U+AZuLLqUh61Gj>}Xj zg>8o@+WI4N=6u1lSxb5Gg=a`li9-=`z>9U6ma@YqZRyZxMS8?lW^`)-hgK_6rKp5X z2aNl`ET8+gL_}Pf+T<2B?nSs{r5wf$haWlID@tkh6X~j4ve7ddK5hRo7S)fq^f^(u zjr$F`#`D=JOQ5aM4l7Axo{ykqVMvJ-4GN2DpEFNI1m@S}v~Jv@hHcsZ^MQUnzzPz+ zLMcVCzMeH}*N~grk^_m$7y?jQTFR6uQ@G};Yn%dt?ApDZlF~9lL4gqyM@~*IaiWGF zH*6z0Gne!@#rjRfBqui`w?#ULDt7PQM^Q-~?F!oyV}MXWgl%F8fi1M_TG+d}{*uf1 z@cUApfBtbYo2Sw&Ba`&>=6IFDs;y-Eu3{=H>%bRBW^OL2euI+Yjg;)IMByPOE|Kh< z7MQ`k{J3r#&02OKGdYopvfXSiE=DO2nOV(=i}kZ%?KZMowZ35jA6Mtoka}tldCe&_Wts0tk{* zQ^`zFY%VS*uVo%pd$+K!EJzR!$!Te{%+5mEL3R~wr=+ZkdecKe>(-coGPZ9oA`k+@ z^b(htLT*kL)R(bkb1_u`8zVNBf;O!Y^)(c2T~Bp|0vf50-AVdGltbOqs%Mx8JV0d6i9|wv3`}Td1y+2-8P;i%e2elQ5~Hy0V&` zrM2YcW@8u-3RJOn-8Qnavq?!#*74Z;=ePgqGGoRJva+(87(@O)7j^KtgQJ&e%TXR8 z%949UcyW%}B*cDYME_-C_!H^WA&+>k%jZfIyh2o?&4KOT#kkT8j1Z69S`&&bhnnD0}m>I%WYQN1*E0-b+xUaDIa?VU1y6;iS zt7`RqLXwo$oTr}}MVG?1Na=0V_QsR_7fgN?#iJU=4U4GUx-JI}fNA(-z3{y9%FB!$ z`yxsSOewH!Nz1%8y#4MZTz+P;Ul|7~Su$zj6h8lQ5qFOGr^8kte&VJBz4`y#_OJrz z{9g*#x2Kq!hu?)Sp&9=i^$2MxaoC{{ciehCbHDsn$GtiC3?6y{_uqRjF{ZD6qO^6_yw=C!43$LWQ($ZV4VPY$I^vTf-KC)jF zBXr|3qyIYa=sM8#|MB-IrA;UhvW|~tyvK+Uqj5XdMiP^l%G>X}O-5SMPt-`!xL)c2 z*ZtHt|LNDC?uAG@e)HxkO)@fa$!MO9B|I8nq;+XO;)yz?IcvlnC5gyO4sqKF21L2BfJR|wCki1 zehj^dNw1GK`5nRZHdv$M^4p*+8(|pOj@9xH^RPN>NjcWFp5j9d>oYw!20@x&fO*uH0K+wjT>N>uD_Z__PehxkU1Vn6X z^Des`y)m&T#rKZ zh8^8cKUJ7*+Y!nj=RMg-N16X=l6JSZ^&@O_FWcC7!tYBquG6n=Ya>fwbP4($DulAJ z5rl-^4D~zK@k%=P$q2viu$7O77m0?xruo>;fj@7jPFJNTMx)I>UEAP3)&$PSm~>QX!-WIq{?h8c;YgAK+)E zwVQb!^}F4`68Oi7QYy?HoSU0_z-t;?0w+(N%(YivtABLX2<4O|T+e}2`^}K(6;->g z_2*!18J~POoo&0zuraiyS=e;z-kGYp5W7lhIO(KgNQsZp%C?}I1vvZ$~ zj=ys)=~B4bP(#bDR?s3d4&9v^UBHme!m6Bn35R7T+@FnNJ4M6;1S--8G#=ImN5R^% zWebxhPv-X9Z+9N=D*igzOYK*`$gy14%~^qdB`5G7CAMuNgkZ*u8BN^5e*tM=2@ES| zzi}XjJ&rak{b(j1-2VV7#w0NznGOR7p=89Bcrzmw0C%fYV1r>a%nNiCK>?ckR{)li_hxvoQ5Z;_0Vr`67pJ_aW2HuVS6Ir; zzBD51j8ncBg)I!%5qEIKvQZ7{7k>0F(*l*y0MX&Dvz>a|VOL$W^YW*~NhopOlDj5~ zu&#QL&$q6-&&g2~F5iM<-xLCgm*{i0{{Mk(Q2#eXtFX!$yGpoV%=(|pz3``73Zh=1 z4s$TVO1ToY9@j!ORA~RlMLEzsmTh5}&RXIeG8~mEJii*KWA5@GBAdIrw0dKc8G7bL zG|Wy`sIcW&hChj@H6;8&IqQu+b%u|*Lg^!n?LHqgU2%BHa%nfEKGcek6W*dZdu8)Nsg>aG7En zDS*HIr2M-j+=hc>6KazG9Wj6ZDMU})`sx}MzyB@+dv&Fxtdu41zfXswjz*xc%?Oo{ zX}BARo&*Z@6MUl)I-`g?GTM^hEQ;ZUHhPjr4P*t|w{B+Z?h-op>P3ucgq1+oE+mx8 z6KuQuLRe1OQlQDc!`DQ|mV|&R=FMBc*1eMRhYi*fUAjOJ+9vt$7hj-z-y_NI)R9=x zIFjl&irZXMqY^4*6J4@uWZU}ra-tVT8P<*?>eJ6f4Mg87KnawL2Eq8x>f>(`5j7@6 z$oaCNg{v_Xh-(KsP@VR-7W`Q&vC`v?C_Z6=Xl2l`1pdYi?7*_W)#sPhQQxGM(g@9& zPy)j_e7V`eKW(XWwaNbt5km0x+izjI5K4|>VM~FH?W`S|+D<6pWUAZR+NN~Ou8u8s z4r)pwZGk1~bx$a%VP()fxVmRF+Mydm8sU>wL{Jc2J91P^vd{{-UXPvJU15W;9IH48 zTOT8AVWFgRs8%LYMIw83GcCPtV`?Q(=p(V^tg%vQ4O6e93aPBHWiWhHR}v*mXKq?f zxemsp(gz$NEF@q#Y#BmnvN+r62i?L@M3ED^bmg>9Dm^=taM+lYBusTDwC&tI?AyYb zVM;_DZhyzvaFn^JQ>QjEpg18gO5-V7(srJ!BJUh@o!#&RC3JgTtzFotKY5@QX~+D(asevRVWJWhu%REMUvJHJp0i-BeXp@WSIybL!G1_zO;h#{(d#7?rB?TW+y4D*|2USZ%qE2yKcV@zb|6diI^p{>j0q@ zA=kvNFLAbfAy~6&1)qMskak_WhLynRG8`>R|Lq(>r5mfEG{%`Bg@fzo;Hf$0ed?+h z`}|mjT{#><9V-?u;;AvO5wI;Tx%ztg_U=WDub!9R7|(-`KYDPc_5og%h-ht5%G)p5 z=^NEZMDG4&)rk79^T>wddtoX#bZpT1r=S4V%dzY@6r?a@Y=pKn(b z2Xpk54L(LcGupc6D&37TgaNrvCMi;s~g^z=5j@Qyn^1WaoUPq7VTPQH43c?5+{TaQ4pdIB~i_G#C@^ z^-&am&f!ETGcsh{*C7axnfdeQ|B7B{lK&sX{Iyz1W6yyA>_C7Qhu=oG!w=)uQKLyt zN}yMVc07IUHQfHyY^3RNZV-<0BmkSV7{%-JzUG9BFC#flGU@ekyf=L|uT7amyr-Ha z-_2+Hu4-({W=HWB0+xXbKrwN+*8E3YABOX3of@k^+zD5E~4@OV6=q@?1H z@z8Hzf4cSQi_h<)zOtNM`%1BeiQ(~+l#)uU&p@hrYO8B0tE?nsgYx*vNJ++L3d&1M zsR;y;hCy;tGh+NELRcUyzW#hZfjY&Jy?aqtR?Izj-N6yZo=HlQ$=&ykVCuV5IAUNQ zo*DlDo3;e#n&;D95#@$&5R>;?Wj`hUmo90)ZyWxpyZ3k8{}E4de={0f(Rd4u{_B9s z-a)R>FS+8U>)|L_2e|&ADb&CFz5|cdUtao8y`ld*;$o&26ttnS)*s2?6yZfs+u)RT z1u9U|RqGnLThURo`h6-6P9|ss^D?XzsA$a~8V?}si2T_x6;Xs$7*t%^3atVQbf}L0 zU6<@A8R1yR1Me04|Ka=@b!G~GR1Gf-8~LNpS7C+MsTYQ}Mk?oq=x%BF#1du2e*gd= z07*naR0ay^uYCiCVIrkLet!ObE?sSzlr+rZS7D7S9G|RQM27>_(Ye!hJuCX>aEXmi z7LD$6$6lCWM>vYI6?LGI4GlX2Sg~Touk48?`Ck{)RyrV5XUG0$g~VO5T-TbREEY_e zNL~3}4j*(3pVZV6lM=^KJq}^a=W|#x<3oB4J0mh!qbyCW3tLfEwvW1+TIy683+H{x z(&cMew0aZ$yCm_$lBHzj_oaMqF;6{qFMDcztlm_`o%amqxPjey_320X^vi{$wC>E{ z6HaFLnw3m{Ya*>Xb!OYv9UL)mFt-f9iRE)XW8CzQc=+k(nefD;%$@%YNx7}qvtu8p zpMNbZ-EPfF+fD=sC)C}-~1%b4}aLM|FwNM240zW8Vc-LF2w>4r!w z$?sMGo1{sawx3Tn5p zG$Tq@_#Ns}LPW3*iTdT&*0iCT>nh&nepe~ntnNtctZ;s8sN6PG-rW;~b}19NDM|r9 zP`yNWhZZ0svD3IA1I~j52e2PB$zMvOd*aiyLcdHQQRr+U0|*pt=exHiQg}pfns@I) zTuL(WiD_gVemL#>9Ky19-X&P7QPdkIp;`FT67YCTc9qnzV@nazZ*cCF7xBsLd03WW z>9WPN?T|xyRyrdedyFy9J;$&Uj^?wupHgcZ?A%q!si$AS=%=4%=!r*DvagIThxF(9 zv16F<+(^EhIgJfPJFzX{1W!X*StTc(aynz5dzR}j9m?BpO{LzpnfdlqimL>pUmeFY z&yFU+l+^6o!^#!QDB4@a{f|7#KSw=8VcYERq^S>9vv|#RTD9wep)A&{T2E4HD&CkF ze10!2nm1?7vL7)#iF7E)W##v?8`^xtAJ5RzBu&yJzel1sc|cjHni4+w_+wUW+6}56 zjSB!enynUO9Tv93uVEpmz$Qcp2!IpiCL#;s?-bjy!zpE>>{^z6_Z?$inMh@Qy~9BB z>-dr(vNlP_S|uIb#Ih}1@3>N6TNbum#kUI<^3j~dzu`&yOT;-|PuZ4LeDc9`iuRO6 z%HGfE;VR??V6kEOd|rR;Mb;JXBIKqBV}n)B#?`BsG;tc`fshla7_poEx=KdOAxddZ zZp*e@2;7K~(h)lp3Ol`(0t*XUC=d#vtf+D|G)}}4>xL!S(V8O4*5Lt~y3n~*Y06b) zS&m*ToeXXwu5qd3P$QVBjVjtCe>sui$?hgI*ax1*jZa~Qln{jFpUt6i%NCBi{Bo?M z1lo6OM}C_EtfWMSTy-Ve7B6DMg82w#han5Fb zbxXfz_2N|&@7_g+b~((PHJ9_xzmk(r9m=~CUdFDkq8_kC45mMk7@rTH83HM>r4OIq zL-U*@65~v&YHKm1p)-ILAUybD67c(dWM?H)S6f3>O^9uqw$gXdiTD!Z@%h1TD5Nsz zJK$K_w#(#t(sgb5Utl@kIGieRvg>e?#&aj_t!UJR5QGHzjq>hX9?Y+(}P_fT71 z{)fHDCTWr;`6I=RZ40q=%~H-e`vSgRw378}R?wk+N1lImDk@mTTazYH(58^2lr(O= z`F2Wn?Btp&uOg*c8u^7in7`=9hAz#6SUYX`3Gn7?uko)Z#%Kz;gHduA)(cPp7JfO4 zN$-A0os&w`-X$^Dd ze8Ix+m$0v@7Np@Ma%n~M&rU>XlK(rRvxB3o%D>Dq<-{t~*7MmbZ_v9>Us4JSsqlKJ zs;R_Ol3Kr?W?j0{y+?PZJ@o{43_1$wkBypjCLVtp-8#4Biw`FwWh_@+eIadgT96Y{ z&zs}lA}OO4nQ1<*Ip+Z`yX-Q~Jo_|e{Cfh+i+4B}SB5?{0n)Z1WaBfvPOybQn3|Hztl9TQ}l$7W$A9gz%A&mdQ(FNAcr|CERo0!)&d#xc7#? zVG8h>UNX~SDBHUY+wM;1uI-sH`y1-2Yp68?>@3;A&|^*m6<|+UC25&?f6!}ek|t@A zKTHImLfX>j9-0jU3zOJ55B>V}qeXTuJGQQ5^r)vu$>_jiqpqi*bvAQ9`;>Ry{)~~2 zJVsWl0t(t>N0gkfV&!C83zw1CMRRl@tCUW%a4lro9cya~l5mj-Btn2Rz?2YD5?dHR z2&pW<2M*rkfq~AQrz(XK+P$ss6DTPV%0eNjF5An$?zxLiWHNZz5PU*FunuVjFijb? z#%i~&n`DBJSdN=gYG*92bJPyEC&DbG!In)83xkS+lW~d@TDfw|35WP88xaa2kXS-u z2#|*EM};C}3k**z7L66;-)5E7NtKeiKrL^)_!Q4Q`!dH~dBss0$L+*rkxYM(*PeZXX|orRU(kUiOIGmcb7Se>BabgXpTW~(-lBbn z4lMq016SWPoMFcv%EE8v@#v$EQ`n^|OV<^1?u8d};c0{T;h!IMrXqPoO?2IVse9A z6&ol0oBFa++73Gt<@10P>@42Hu97kk9`MD|_N0@j+_srb@4XWadC)eqE~mm z|7->uOKK_TbQm(E7|<<`7vGpd-xDt&BQb?GSqUuqdJaFXT*vm38kCuUDI_7=MjATi z#l!=aa1w$w42^U$qOcT(^f&iIg;YKyvhNwBUC15lQM=}n`5_pbc7XdwY%(7I0_OuL5H#yrc*FOFy1j#7>p z*b6(bmmk+|;gF+-929p+lQc<_{5hf=tA4OzJ2zf>0RBJ$zYfjQ(iw8jHI&!;keJw2 zRebj0$86YKM0I5qm3#NGXu&+rKI06gfA}FAwr{1RqLf>&zm8jPyn`*pyCXIicR^HD zd^2+r?OJ6M8|&w=BL_44`xPi^`1Jkp9NxVPDG3Q=X6EzQ=+~*VZ7fyGrloT^y5C{M z`24hJ)tNgVdWm42g{^d)o)rQasAT%Mr|Hr@pJwT~+&OYIrL`786>(WAw54p@`laNh z$8y$%=d!c9nx`JTkId|RR&3b8Etj9mF+%e$%&ct9W;zJJ1VeDgOcJcoH$@0sj01baP&AT>MfM2V&PXG(7#t9$qC7v zdC@HtR|K(zi8Lg(qdyC~j<09E%ORaQk(1q-cR%`q0Gfx}KH)|Dd}{p3?Te(R--AM+?%_f#-?%tW#ax-$By$9VSPYnb)%`;^qw zpsqOI4Y`r8Hk_{P84{@OS$&dTBB zgjlw}_6k3ad!5kA<>VVC@4WC5gzRwoKT4sLplx9{uDJRtZoU2@(vnOB9(o>g5;xv* zBWDde8B_XrZtTl+?%IX--hPXEJIL|J9F0c^`VKgXc5MqVl!X$KBl;aq-~NYzZ6G{p z9CyMgWThpOk>84e0|pXf81(MfpY|O(pp+mrvw%~E9!G*l(r3V6-Wc~9ZvY$)1;>21ctk3E45hA1l! z@YEBdNR2UBw_-W9!4Ulh^=&e`H%XKH4~Zm5sBRy3-h3C6-usecPd$g8J-cGKmMAwH z7y(KW5+1tt8OVqS?&FvNhvHH7#H3_$ShHd=*Is`cyS8rS>Ps&p zfRC$gzKP?997}3a4AKq}6BElR!%pVNL-KiQ)FXVmVgqYeF6M7n-Aurr!TIN%%KXpX zz&b)(MX@W{S+o&vQVYzOIJ_~?rEL!1%$vvN9VK`Z(`nnL9YWM`{GcP)w!Mh0 zo3~T6V-NZ5J0PT&g8bH$Zr^~iswmoBLRMi*LO{p%t*9^E#foLi*s-UEUPlf_QO}{> zTSI**n|AErldo3NzT;tdgiUO+AE82&>)xNi zp6AC>Z)>nqLkMT!TN-HDkW?#0&*M(O1rpYoQ4&QEUqTvpjCdGjIlwW(q-C4#JaB(E zov4B!Jv*OU?zl?_$6{jHU`sgpv|&!Bm5n7OC!IP(!xJbQeChoC+FP)cjoBidf-c<& zDalEvof?h-$!XPv8?WzzQWiUk_h3snA?@;;@j#c}&a-u}ZJ5#t zXx+6nU3zq6#>d~#{%@yI(7rqOkLc+H-U64T1H;s;XL@n(*)Ol!UrFJP2)H+B_vA5(Y4QU+f5Fuzc)ma@L6hPNk7 zVo;$#)n3b6AJ1dex-A5q-9;(I`elpQu(gb5CQah30WApZx{s|zi=5<)|3v@z3q|O- zLuo5yFodve$35-D+o>Rd+6qjsM<-?|3%|!l`MzRm>VpW=gGU%h8~kxGSSmziZ7r4( z`2Btq9!$f7U0)5#B4`CLWAr}jF}0>yT~Uh_vhl}z!3<&~c(JG_7!0tttd_XAB!rY0 z9uGoF>grsVoJj;wrb+&avY!(8b1{J~$fW>;G&z0jEAVtcA3H4z4CxGffiO(Xqv!<2 zVtB!0BHa_P4MO;|>jE6!UXZ4A0+FRNfmEb;)5Nwkl#NCn6xfypLSZ-nwl;Q{22BVs zgf35^FbxQ*5K5yGNm*EU{#`B^q>*-2i0A=BP{llJ+|b&QD(7%o_<6VIXm zB*IAJ+Usv+!t6pr_!lg5B&V`9H~vxBu#RVMMg3`@kWuoh`}2niEg#&GnovuT@` zgs^I9*{%<<20B?zYP*$Q^%cR|8g>-##v7Bwo|4^Elvfc<@*<>xL}Ex2g&v?P zf2v7Q@owV%@nmN-C&pt?R$7W6i^`e`dEr>vw3Q^DT76$F(*%e-9T{02pv zx6&yii+y`4QN++JF^P_?GuX9rE0%)#sv0aCViOGKAmZ{IH>rSsRS7GBVSw_VV-Hb8 zOke_pN21J_FnFNloURc1E4}Esg*PnI7= zPi#g8`EA?s?Xq?3*;gL6wYuILp+G5v!k&lFrbQfg{_Pz4bT44~>}3>o?@On)d2DWx zLHXW&OquclkKb|{UD~HJdc@7F{;C&WFIz>uPzXb_Of?4b{(WObAO2m-nhFJYvk{Dzd~EyzysH(>p0lE1EmSEyf-6x@)|NNFpX z{zP?MfJYyHmb1>gf^*KjipT!-yk_2Tp;_E}B83sA(s47zTxJ~y#L`7#a$t{emrXm2 zdE}bhMWg4?U}8sqEr|xwRN)i3jTi7}!gwN_4g1H9h^S>wpaC}p%CTtT#M#Jj*Xq-# z5KU99Nt)z;O%x`061neR4{^(N=koQek9lL_2jsQwL~eFEC=(kSQw33YP|Cuqs`c!b zenP^7Ab@FEnha1A=i&y$pum@!!)xOwAnNvU@4XMOXw^pAbu2(C10@Zl2;j3q2u#P- z37vZN?w(p5^md zv#G2oM+glE<|?8JSi0l~?tb_gjy?G-Ey5}T)S_08AP zHYc7pUVe^Qv*&|IKq>Ipb%2R2v~|g_O)NZENKBysgS^6CyzuJN3Cs+=X?eaRz_KgF`uTe$r1*D&bFepr}j=3<2N<`+{wUV1T~BgmE1n(uEG<(_o`300w(Z$R|D%r}-sf>RQxD=` z5gtOqi$O44_N<(TZu~L!$e4Bum=;vcWe|S2w(`$qv{g zP4eFnr4+$nkTq-8kei!(z-yK-Urzu2{Q)Q~EoI7-DO`Q^)eZ%&Mt(zRmJr)H3>qrr zuxd!83ZWcNfq`=F(NHb60_v+-`u#k1@2f!x6Odp_a`Fo(?AQ*kXlO??2{{U*p<~yS z19c@Ob!A0NoA^30*#+z^F5-^+M{(W_BlzcCf5$KM`eg~n{j4ms3q=4Hfw~G7E%=VI z@>(!F*uo|#JhaMhN4NH^2@~Ea73K_xH104WkIdzukh#S57g@gtm{r0H+G6YIt36En4uyq`~!=Wrx2$xwU;;gcr*r*7Ds|w$1JMT?7 z?RE_#F1WP7c8m>r%hccN@fhW;a^4qCZ$zH4zs#61gRHD9diCn{>pP`M{%6GX_|Bg{ z-{B5+ELA_39eh9$f}OicSh;#Fmt1-waj`xE!2tE4deU2@Gwh5r`EuSI^0J!KEHw#j zCX2X!B?d}bdUDvB>d1D?e+Gh3po(#0pW^VdF5{?vN8k|$p!u;YS^Dh)UYPbhkKKP8 zUXQIIVoX!hc)J$3@akHNCH+VY7SEf>yfu5c;UBk?MD$wFC{VVM^4Z8R*!Y|Mu4+>K znxskomqmc^H26E>LNOy@9?oZ@(LGKs92I-_^6iAjD3YwMJ0I5I0heo3YVRG5*{fW#Ur{N(V^cK)s=g=|K2-U z@coYC*KWeiu}bO&8V-0Ex!S}}=kXXJCFUD17@pJz0xvv6DDh~X$UjoT{S(|^OT znFeJy?%znM4V>S|(r>v@q_@q?! z?A=GR)MUcLQ%CQD3Q|*5$+*{E=id`1vwPn@vT|~{^X~f?aP*Ow!l0^RAC{#YgPXQI zhEH)Qf@OOde)A2S^^d19yfEsa`aQJ$rEfGj}p*=!G2KDYGeNuSuGuN&XNq1f-;A^4_O&!0-{hk-L#}@JrVpL5qS8 z%>Q8}w(tWcwn9T!!GB<*lcY9p!KYt*4NknCEu2i*MpqupaJeRFk|z1TDW*QGXe;2R zO`E8ztHUr1Y}-akNlHoz&6_v>Nd>V!7(#d@wRJ&^SO-mCnAFu*Q}h4WJMTCts;uvS zZ&ioMIVYGIa?T2pBn!x5LNR9q6%`N=6%&dgi)+|*4VVKcMkI&<5mCVef&|Gk!!S9g z?yjo){!vxkJ%n|4pU3dL&iQ->y1J`woqOumy}x^+&xg+d&9Fe6KdKfGK78I%9$xe) z+xJ&;-=ZaCB*(C8$M-zG=pGv7d`1mA)r_E%8d_5$ufO#+8Ere#zh5tF3YC2I%}z?H zbjFStg0G>L*!U!#dG2{U)%nc4<6(LaAHnE;-BD#d8`r+W^Upm`NJJ8i!a;gQ7e);3 z&ujl&LXW>KBvh5CRwa@aYM~bT^OCfpf%os2y)mpwQ5u<4`pkJRWKrG|DRK@#&HVj}M^+g`t}sh=8QNtc1_L*v!J` zUZPiSE8GTj>e!yfl0!WI{41O`s6XH!j5^*~xr+B!ZRFXf{(`By)R9I#Uw^xkLBr1{ zDKZQPZmya#4G_qNG@>FSa42RV$j%)<^Z4IiV&UDhn6daR3GDDJ(xXY#+X0rtE(dvmUOMo<(2;yljLMyIh;}ht?h2lpPLY^;3X9+)V~xpY0U$ zKLvunHn8|L!O_2Jr>?G!<;$1qmd)U zWwhyVikXW_nn^mV%8FU^&=T5rKZSmsIv_nIta$THu9|)u(OJo;W>P79x+F6>7THu! zZEYjTQBjs3M$2xfg<9y(Oom|~gy6P0bNxUm*gSf&IZ^n5-m%|X!45%AStbZH)4v2R zwvDn%Gbeugn&1!3s|lNbhM}10WQ0UY1u4w5GK!-3HIB_@H%U-iX8uBxH(~L0e98q= z4h8}5vtZ345R^pA7KQ*nFZOkT02J$!uu{PMAJ~QGAI{_TK0Ylsb1DcZS{_uhGnZ+GPpt<>|~mP5>)a}WP~cs8oyK!l#aEx`t1TS_JK=ZjWcw{PF` z_$B*T@TXYcSl~ew7*YwEYyFw~f=tgrOxYi#!vv2UtN%0n0>A#5pIam`Zk zgT+7^GaEFkw&5P(*ASm*oeJciJeFVU=i@Guc990&m}=^Argq2KT00hxROZ;7-a;?L=s}VBg++=FOc!Ty%6$6d8e+1wmL+D)G@_eEiOO z+FX4WiZIYT^(=e)Q%0XLfk+h;Rb}?Pxvc#73zjTc#AAP7j8jo?BT$u4Qj?O{|MPYb z6OmdaFFy4oWkv#vW?xT;(}4jbWp`)A+bcm)XeiuHN&V|wJ8e2KG2!gqR*rDGiHr>M z*F`?wMY@GrsD=L2Bnd3UQb*GaRENu4G>B2zOqb_rxt2q?D%7y_x- zpu}b&ptbb-Fj@fCuzd_Mt2pTzI2|^?wZLew>MFQvC!#+J0JKP2@;1SCX?}x9lz|XZ{@QP@fOZH?-F9u+Hv8evrr`Xth`WjZ@H2B(tMUY`cJ&NHIXTy z^y|@{E$iQ-s!pS>ypE@y{3qq5g*M%X54%;>$mKnp{j@#Z@jXodSzxk5qo_U(*UVekaB{e}aB1n6_F=P-B5`JZp zl(wcQh!I3kg(tgCt?6HgUdi$omU88k*)(YZBP3G#=V1HzSidnpII(Z%zo&v7fMRPQ z%|Mc1Fc|>9cH)0CCu=QFKfZ(;XD_6t-UC)CJ;j!;jiIo+X_++z=u%<`g3PIZ5c2b6 zaVs@Iv%r@`x3C(*@XJ_{5(Uj~52a{x@?x{>&?{zDk$j=aOU` z;)bcyIDguF9=PdD?wvc6S5~Y+Muc&}l~afgb#nbh7qhRRn51_7$n4UCw4_-4MrOZt zG?36)3R^cL&1yr^Jkl+bvyc*D=m=Fspra#@LN#?cdL>)G|B6pG9i~ZxPzMO<1)*9# zf>`%B)-I@9JUFeO6^X;}Vc|v*!K2RR=2azgk}yA!Tu+7E)1JLrGp4KA|EMCt2A!Tz&1;jF~u|!n}Qa z_QkjK8aS2*AH0jq)JWcVZ5fA(>v(zjyQJo3k(JZhZ{CFfsH&^0Brop>nkI0EMUaw_ zPIRb?+VWzK7M0PYgDw;jQ&LDujK`%ac?tNn=?)M~iF8ZP$tF;ymhof|S%$ z^7rl{CNZ7Vv_xtuirJfAPDWY+!dFFUStGi15D^(kdS(V8hJi~p!ID#WC@n6du(*b{ zT{_~cuO$D_K_ZfKNlT8yq1TglxPY2k53cY?(las$4GA&%`yC$pzamrTXCUw*bsx_@ z{ump-+QOXM=dH4h@XN#}wc(a)$6+A2^6IPc$|h#adz^&$45nUrE+DC{DCUm2^Vt65UOJyT5FZfo zJIkO`?Xr<9;7(%QAUOtrj_2-WoCL51FfhSFm)3Wt8%Dqk;_rDgU>i)w{BY9qnv)%GCw1L2#W%mmKVjQ?eqlgRi6HY| ztE7-r{n}S?Y$MHFLhOzPIg+0Q2M7F}jli??Ut@89oaWfDl*P)wRiC<9AMNXrrY0lk zyyN;5#G}2)n$KMEo4?FHW7+r`f40=?Xky!)+GiK9mQ`B40t%%Z%T7Mg?-19le8=Z_Ve-c z9q=KOmSN0)&wum1`k#=gh4b>+>i3v4?;ds^IZCvu;qkf=NNOs|cxmZUA~L%(v2PS! zU9$1Z?>Teac;?T#0#Bolss;~NTzw6hxw$NT{%Mli_U#{n}tFA}$`VgUU z+&JfMZoTe2K6vYOZoA_lDttP+F6n#9X*~Yiv$Tno+&||QmaX0ddOa0&Ue204m47}w z)jtm?ikJNTyO?+DJl1Xg7U?r++om%Q{o_ea>DdvNlqi1LDl|1UvFM&#*qL9$KVMwN z!g=$kXl&&5H(uhVDOa)ea4oOB@-jDFIEkd5BYFMhzwydbe`EH8ukykx|K$6Rmhsw( z5Aim636D);{*ouTXk1rQ11NNmHN5%UQ_NlXGT$HC#{Mmza`ohExqRM2=Fhl{*Pnfq z1&_T>ZDkp%D~xMzxr>``xRg+biY5(|UwU_cLlT(2mPn1J`YIlO_ATyx@FB*H98T*9 zjrmJn;*zOTh;S<)8#r2!Pjyo$Q?8v(QWX63#afmweUYorAIE_MM|t{hFOi$-LMz+P zE34KqabPFjc;gLjd3+gzhIdCQPM&!B1H^UbaNUhFKseC6hgtXePZU*DB2@=t#*arD zO_Y|FkevP=(&;iazIrvUy}q1weNHDSy(1v0xTl~9#VY$IOmHUv#js2nHlJ=#Lg?5wix8*T zmI*kma}*UJOr9hHLmEiT#Wx{6o5c8N+|7HziB}eRf=_{C+3frOY-N(R6OIL%71b{7 zZTlfv-3okTeQ6Nvs(mbnlH-0j@o_Vqz{!{lXkTp@5deVASL0@~kb!Uh-H~-tfX4}B zeS${KbO+KO+1adR`7ihgYS_=V_5U$0@xPqLLfTKry07(x|H=F-K7xi|Kzt`U`$Vw# zUo$4{@gsxJ4jxy*?HSGQD-8_5ur>h_Vb2;{KJ+kU^*+|D-^iP9zJ%KeSQ}hLfaXw;iU7sM8s?uw_fMdbszG|vK6fVXe~Q` z{DGyft)@w{r)9h9u8XMXL>_tUKJ=PG#*P}#SKsF|=k|L@j*4aC#Bp49=_Pb*mrmav z9rRB@NThI4ux}UhXWmPnfy3DL;|?aDb3V^J^9JRW4S>Y)2XfO9m`jx+1w!i7RF#om z<|8e$J&M$bjtjxt*g&II=}PKNlok~d5}iS)D;z~J$jV6IryqAwSXP50B$m{K7z9mp z>fDZs@=6L0=TqBQPkdT3Iw2&)C(=+=ijHY2M{lG!uY@1BZ|9Or&ca^Gm)vs?o!j;# zAwGc%E*g(ebc%Lw=euvVGGWprTrLHN<$DOSPr*}V*VlpXib>$Q%-Y1lJ=FVb*0s=l-7}* z&%m&*Gccpy6#pwD{I@p{K?`VeFi5kblf7QHj!_!*96ofA`X=M}cBBDPL!g_^(n_EJ zyFDodK&t^5zkUU=>Fvx=1n!fvm58~*!RxgqR)Wha(E z^XD4S+F8q!F#Bm2nYZ$dGkhuEvtaAqF@b)Sq;RA2#Fyy z)Qu{AxHJQU2tuNw2y?ql?GgCLnl8ccG_vHbJLuNEHXxKumWo@okJ&=KBx_U}JPrN`jLY1ebXWml7y z-H!0EPz=ouS_sleN{C5FW#YJzRFxj4ZSTHx@7W!s!Nu3y%)Gfb6B*{B&!8Uos!MqF z#h2N+=LmlpKOUE-jGHgNnyx*1Gvn5~@HF|*d_Iie@rerq7eZQdv!#zRaIkm(0qPrd z)~;H?kYU4F_2I{)CdZ;H5}jsgum2DvgkgzlV?@Q_Qt%mG z49nY7^9kH8Ck|CblM06J1nENen3cNRZpE~8={{7f_0OSNN&zoFeEkL2&tAfmsWWJo z9%ELzl1`@0x|5GSS&Q4K<-XfyQd3jRl~ZpeDmAuZ8|V z^qcF~gEfxA&`ofoG+U8^5S9R8nk?+qSfE;pCwt*EQ@RKQx*oWP*_PFY1F9;k*t2^- zs-+nefG`ZxaS(x7oZU)`1L(SjAtk!~`!PEt6O$VFYOC1&(~mT1KK~@8TM>Pxf=^g4 zKF77;j~o*q@KRfGn1v56Ca;c>TVKwBLkFoxV)`eYXhc}x zN1CR7!vORq^7rrLU}0GhP%tN5P4k){O-h93C2!v@3M%UG36oD-Go>iOV-0lOPLClm zPNMaeNV8&t^dayfrG_TJD+$z*F|4HIQX`P~){?ibo8U&8f4Z)jVzUyl8isB)A*@Y` zG{?UHqpp^pckaX^4bz}6h53A?rTr4ZEWarAAemd62YXi|CDOi^mA0a(p^WW2f2JuI znHjnn32(hthMljDzz_{2vsKMN0dGAo{NrI(e)cU*-bNPApU0+eb|3{PmR78`qJp2c z|AZazs#*Q@gYF;`sQpPZ3=^PA18CsuuQssc(PsjDU_M99kZ8I@S}(b@w*bGk=0XVE z;i1IExhO9_#Nqq`ywVkL-7qxEx}ac4(@RYEcU7WDP*s=T0-*$Upn&=A*Oiv?&wsp3 zul_@M@zs|(W5h6|p&=9}Is%_C<4O_sCP*bEDG|jm*th#|?|6W$F`-m>Rda>)<^?bQy zGmQc^eDnb;-d=@AaWQ1{7?PuOmOk|qhwD_PU3(=5cmBwypM1kP7hcZNm!2guG8`1s z+ek&nQ&)vo55W}`gQ{0?XzxA@H4KkX&=m&>2?+=R?K^kpnde_(`P*;u$m5Ghh>pO_ zKKRE<+htm(0O2AwA)PiUVHE7$j#S)~meddx6HSCeK^Ov|M3b17ji@EI5j;t8D)E2a?m%NNb%*a$*ce4&|ZXrQk>b5s8^NfL*(Ga@PZY zW7^F(GyaUzaSI7T1JyxjbUZ!!_2b;L#`FF6-%;a(ORu?!-hBq(Yih*j_2BXN5JK_K z9p-XssStjn5_m22$D!ZB$-*9X28wD9I{!vd8h{UJXh><`^XZ@)V0aL!hG7|^456Cf zOaMmnV0Tquf=0{*O_u^qYhvxH_j%;OhcGmAI`Qcegb!h9l6-(>VD7%82i4&~QB;Jg zqDcY5hZ)LmEk43rz_x7on7OlVq1NNYXYt?=5_A(JXa?9-NKXEKnVJ?Iox-we8VoF5 zn}*a4yqeiVZ+$KI&!5BkjT`X-s47A?0hy_Xz+5QN0UtsLf64(<9=aKoC(LtoX={Nr zbDxkcQ9Hj9|9qt*_4stYJ6YgZwKZCp z34m>_cQ6nXmdxwxYk1ZK*CWK;Gh+YN5-qaWfpL&t>TW^w@}yAgq>GRs1nfp@)wF~ArG&Ad>dFn z0O%kz{FMWQK%%p2>qchGxP=Cv`6@}>Y!fsTOFJkP+x?9egV)ozMgn1CE z#86z;Cd+&;gwRbup*m584@3822w|q;_?62`NSs6^wBouOuA!#5km3CYFlfYIX!5Bz z@FIk%3DUGCgd+?g6jZ6B80M(Oseo)mvGckq!L=RCa@uC|*~g!7@uUm+c-@DD zI5jXNK0_cBa3IY42!T_=8E1^6Q^y3JSa=uhayzr@=R7NVIE3srt*I|R#Q1YBVaUj_ zWMpPAf8HEUJ*6L~o!Xb}Tff2O07bF2&*qr$c^jEEYd-Gi)+~SfExP2!v3Sw_)HeB8 zaL--bFnt!q)e2eJow(?%QB+lw(eLyLbn1{sa&iJu@o_x=!b@Co`L$FxHsM4EL#0>m zKIHA$#-&%^K&Re)NlA-h!pLEqckz{!HF|J4pi8eloO8i2wtn>`BZi+&uYRZS#N$sO zbRD(1S>g{x5(f@7~m##2k5XZC%6Wyr8$L^vE=I%zU1SAI-tdJb*UBe{G2 zJRW=MIeyrGlFxifF!iN8O`BTv1|`R9%&Dn6F0ubam6|9Fa*o_(H& zmpsOpF{3~>^3IAkNXg1Y^EUFyC+pd?=}T&BDtT_{v%L2Da-Mo-DGMKdgkdAc5+9$& z`Ik)QqAM=tqRTF)cb`7=?c0aMgjj4p+hA$|fqy=7{MHZMG*g-y!0*1>%IBYN!Y5($ z*l~2u&Ed-pAMx#X-xD62$k;O{l98N9T~!e)-g}25#kHueFoq5vNv|H=QKgT9g2Q~U zdL0$j_4Mi2pTPtA@$uSs`Ekc?!ef#dcjg3gGsAEgP3+sbodpXPkkPgclP{c1@xh;2 zv+i@sYCN1WXdtJZ(g#mn6`y_h9y|6Fp$R9Qx^-pbn9+nOUcUV7Bfi+O2gMP>pwmyM zPtUFhsdH%WAr?RQSHj{GxpmsL7NPd4I>m2;7Dn(b?Xm&y8d%CRL(o+Y+5Bp zvw8E^eDU@7M8zdCdfY@>rzha8tK_Y>-zUGY6dx*Gd-P@Gut9`4bm}Wh`S8Pa>^oRU zR-5*mHEtxkwr*j=rmyfA4hD}LL%*KgPz@iuw{B(0{eLAZJDbUqCK3}77CagNgNpJZ z-dgc4Mb!(Z68hxfv1cv-u06{SVR3>th2r*_Nc-FH7A|41q6ty(kT+(|@YfX~A_ zufD{#Z@=NJ@neWmnmABW!RaGM;;TQ(tIJk1dh}S*5<*zB_9M3MK7czsii<9oMBbr8 z96WfC^Cq2VDNKFT*A;Q=tb52Wsb#_9N61P~;pov~vNO}ref50(piT zLk(dY#uD$$1JmrUZf6d1nDXgYb*KUj+GYYq&^Uc>^uyNB? z8k)Q$XJ#;R^cb>I+$1C?k<&&q6UX}+`Qo!r`DW`j)W}3Gyyzmd@&kOZW z8bb#5M^ThtaX0HiN(bj(GKKW)j%@yJ2lY*j#HD00ux}TlLYugG)=YYx(v^hdXs(}r zJ?U+`S*mC^JqHbDRzxde!d$5SG%S`$+tSvmkx9Jp#!6PM{)F=K3Y_k6+IH=Z>Ik7< z|3S=~8%AQ7lgQi-%$Rd4JqGq8HYt_Y-hQ9WKkTKUG@p6*JxXL`3?32AxtCo@XhH_{ zN;CrokKm2>Ugy)#zNDh2iO{H6dUxr7Vi;zoe}9;rN?BziT?U@X#r+46m7K(q#rN~x zM_*AE3q$ zpqkH!*q^2gaZTn7i9Nc!- z0!ED-feXwHn57u$f7&3F@CbkABfq=MA4|Y3^c&K@Um5*>i3AGhReZhSV=kEX0GD5J z1sREMgi+73<;%G5uKSpN^HjEf^Eu03dzBYfyieWXgZ%T!=eX#Gnbha+V(#48JoECa zB*+SGnK_rxj7|*g(-Fn#LKA|Jut++0%3sT0p}?%2Ty5klKGIqcv0 zBiCPbDX+f&AyNq^HZGQ)15YD9Di*b|npp_Kf0S6=iI~G+ioXLc(`ZIeAI{T#+-E?syh;d1E(vLHaWTE@BNW`Zoh*^pLrJ4P-4?l=se_fS|`QgcDs%l z4H`aQ1JkD7N^E>Gqb7{OClypQbfJ^kz6-qvk0K{G9z$qE#YEFBB7#?6Sjx{ws+o7= z`RESF?cR%?eNH1aDW0D`d7F=ZDy09&5$N^RJoD^pbnbKt`@Y}G%)1|F_8oWQ@>Qca z6~6iI2iC0qkh3P8hawGB!^_SezUI>}x3hfpdOBuC;s83e>xe+|^@l6DW5FWMy7)5o z@7ToZb)WIlYp<|-`$m?&{5qFhJ&k?aKWEaUOZj;1N;+nRF#Fc|%qed?qcu-x6(dYVc|XVX;dHO{89aIIo)(>m&3u`TbXzJoh*C%EmI}w3a8hgQKW=6 z;&#;Xz~V(5sc|x9cu$^s;t4c8l5;2YM+hBF*FbR-5gAXHjuE{5`b+G|FJ-~JDJZH7 zMOgmBii+($t6-SsYT+O;HHCitPbDEW1HHbQyXMXzzfooM@F6_1a30_7I>hbMC-cG+ zk5DAjnK*VRYgfL*XP<56$;aojcmDy_to)p_Mi1cqx8LI7$6w@<%g)0Q5{knxxPQSS zqEj;IJ9rdMMMeG9*Dfo-$PvcCp`#f%bc|{GwaloB)VO8FObiqp=uDq}J+^1DaKv)j z&@<>i)bxF8D$C=+yJqv%PkHFLKnfIRC}YpPgsIm}X3F&)P2&cZ_8OgjrwyU+z|&2C z&gf3em^&YU(!*Ohcfv$`k?~Yld8za`=yzH#LR2TNxHK-hZ4rI#2k|Q$yo8`@9RS z5v5u(FzJs4QOsoBrYns=5e|eJ#<&URFm{6NzijsGoXHnpN4%%DYRfg(wZ}k3$LgC< z36D|e|T(Ls(qoH2F+XN;ZTuhxRi zhXC7gXyEBXO=|_gc^Cg!(ruyNmi!>FnOW>t)D9Zb08b-tyzmU?UwS3C%$ZJvQAa~f zG56iKhI<};j&sMIidtX5U(UIhk2Y&abN1LFi28jEiM&y~D19dBhtoV&ak* zH25@9LPOa3^?J5{{~b3x@ONS(bjF`KmQO$1%*7X+M|_AWZd1}ay57LUiyvds1($LC z4cAaxyo>eQico|k#3jhd$)U8gnC{&>^7@AFXt2zG9XfSm*pM#7NCW9BCp$ZfvWgn| z^zO-~ANQg;UCe)A33k~kfkYbBtX;F3iIcBl=1o^4kT|55f86&TmruEl3ogD0y=n*} z&Ya4sci&}5pF}(|l(7@eqjOdm6^D!2vGogjoSMtWo3`=z6OYlkOFL8vs%#`VEr~jx zPHeQ`y$wHcq^z0*LlB>w!hnIjNeOY|_Ad>>|Gy#xjWv~Y>d>C9T{@7Om4);aBZNZR zcG(OY+LcJ@LHAV9wtagl%S!3qqa!QUf6mMsF93&1`)*wrae8;6(AXnASh{9Y#zMiT zIPhvdLfsB>Tcy&o<4{5)LYXq<8m3LT1`Ts^l~Ph!R7gx>I?0)le)m*?4?}BW$zxA5 z>7uK+>YB@_FF%D#uDO@ZTXx_wnutlw;+%`mC8S{xt3JAf@4niIvo3)*RojnAj)>?|k?X2Mdl8rGyZl6wja`{YeZBW9Oz%_;KrxOkX^exG>3> zF(cTpej}F+YmXuX!^e%{^d70yH#G6XH@lfUvJWX~X*BqJNTUYt`kyE+Z^F0Ey46!sn7k5_S`;Ka~sS+!;@H_p3{3&syH$BX7c>K-yulj+i_ zEvf102-VW4{puEtKv^vjd?Xy$VGf}B1GG#Ny%Vh8q;4REilRp1a)nzC7*_C-qWIk& z?DmCyPfJ^)Kv0cZ1D89LVWWn!Bd>~9xe44n>P#-YU_4G?ny@9RKkUus1F&3f3{-~$ zoGzR~MO6%3iVL@*Sehfl3La8|fPypdtc3t83OOK^fIgwQ;a2#63shlt{mb(L=l=02 zP--;LJJtV51b2|&@euspn3~}eTpQG8pqb_y>E`ki{`QYOLj)Z*mvjsL*~tOT0pPDq zs!(WZY@)KfnvvbRngd@^@p|g1tg0cqb8kR`OOT$NL|J()A~p^c#d5~gi4F@z^XinA zR+5yQ>Ys>Iy^dW!ZsqO;i|N+84;A$q4NVRBa3FD5{(=CK!n}jjHr2Ch?*Ss6(0|AX zdUfw%#xg1{%lA+xJvp8o`x+@Yu$MVkT}*D@p|nbhrqO5M(XDt^p_&n?Ky6(WhV+ql za4$!kDv>FTfgC-2 zgeIS1!6vhKyAx0hAM01Y%QLUOPq$NtQhM+ZUM&F~vu>#X3_w3L3Q zoP{AJPNAVooucY`PESw5K;n*wAUPq9(t>NytQl@H&4Hw zE~ky-_NnLKR2&FHn)lEeS^MTPo_p_e`ki_z1qDaZr3+n`py~c#2&864McO{0LZS&B zO>r=2#2Ds#;DyH@;UAj99SiQIQ%)vGPz`Ib6bhk{(bU&e&{zjV*!*hv3=ap2DmX7C z8Ab6D8XiVWbPV|i50jIqU^ra(PzZBIk{lb2ueO}xqfKb4oA~53R0%>#^7rmx%9U5r ze&Fe3C5GYk`7jJ~MA+}4L{d>%fiB_jfxQ$6gXGrj=sm0lPKW6aYgmvWCMFuaxSGbw zLhhV%D=}$pNRHB}sH_2mrM*-9=AYWqV(O~u*?%aX+L}6&GFs8EeJA{pjzaR~nz#7J zD=X>U?=*@IAI0O7{-iMG(=*M%%`*Qw0oInsJp0|vTd$#mccP>4=#%L9+SXg)WongLM? zX3&x~$DL5iBb-FUwqnuWpEG0f9D(}AQW{plG5?KPsD)bS|8sI2nrAxjCU))5XW&K2sKP+%5=A%58VQFRp$Jk^ z6F7WeEncq==@96$k)M9rK|)SXZkl-;2lnn^*Y<6oOTsYlmLD-wBM61uPCbZ^+Q|9m zpG{_3GD1oWhf4AO1L%f8RTZ-syOf~&*tugD1%-t?f7iW4iCR8bxdv%yxZMg3^))or zH{fxoM8_o{kqkd$939%{;FKU01*gCQCsrbDR9ucQPU+m5o!h^o{+uypeMoC>`Q10$ z=sWZbuAO!r-+uT8Uq7}AMF<>1p}wXXUDwft;ImIQa@x>gTzTDezFqek|6H*J6)?OW zbfKUK7cQZK5<*5wGCytJfE;rwnow{EXq6hl&-?e&fADbX%S+f-Sj5GhE<-2^imF(Z z2SAZtbg7V0B9Gy}fh{5|8(p3J24|H8*B zo@euO8*vDgP=`uQRV6-M$B+VdY%KYCKj71JROvJgmWqNaG?Kqex`YW6#xwJ#sr>!v z=UBMlcEWUn5Zg>`sN{C+j?<{+%@>z4<=RV$P!uz6MTw+mhfEIryoW~b2MeDy*@l1A5AV7DJh8vJd8MFA|2Xf;5KxG>Oxc=zz_~=i8pXM1P*-Em*i1dRn47C zW)Y!Q^4a#I=+eODa?@B_hp$P)8=@1Jo<&%so8hB}F|=QAG^wMgP8`w<9C4_U?>7Iy z;NfR-<+WGv#p-2je0&v(KZ0DMBQS)(>(l*pW(7W?ToS#pk~&W#;cgcxF-g=FAEc_b zfw&0xaocXxkTBvB5tV|2?g17lFg z?S3k^ck9mnL&aQq{Q@o+KaB9yg#Z0{N=gjFVEy{_&B|#0A{lnXb^v}!Bo0evx^S2! z(a;gnj5$}W)Jr;MppX=1{y~9la;3si{l&3$|yYFS|<`1c;D5rD3 zA)J0{Z%Vg)ixjFgSY0Rz7+M`|d-kJqn~hAn_$qR;l4z5i%;2HJc;U^3+KhyJ z>Yxxp&+eUh{i%O2?Yis8>DZ3zr%ho%pHH}b&J2>$(us~tVCF41U|2Od6=@(0fq@gD z*VCj^Re*mJE)W4-1ERa zXi~+YM03`;lem5U{aiQYS|VbSm@sY(=Us9scQ1aD9Xo%fuB3p0g9k8t#6YU^zCjob zsM3ejLr|QdXoiajM>JPldM=9=-b+&JcBCezam_g+NJ>d&{vCIa9q-^sNf{1RC8NXba&%=0hc-Y4Fs zq^OWnyXDYxzyO|n{dsn5|AwOne)F?hXShNAT6s6iyyj& z#g9C}<}cTgoR~6`33e2D6TJw%0s;dZ*{(5*MmzVIv~`n985zk#e+wv3^t_9Qng287_$f&F>%>1UXJ z(~YF2=W_dv*E4$j5T;x)nN}HD96E5AxpQtLIXMD{qVWE^?^BY0fQqAsXxFPR*%{d! z$@?0iXb2^oOE0^ag%3Z*_nY3w84|)Z*IdoV@4ZQBNg);W8tpr_AtE9aL-(Pm&J#^H z|NT5=X_xEj>To*$gSM@3bVEpgPC)as9kFf7*p9FV1x138CP>tTnZr>P(x0M9O6jlp zYo_8<@n>0-!mLkgfk0^`#g~GUq+~MNkyiWWEdn}2i(_oBF}uD0DgBz@;`fMXt*fiU zFbtZSJoqEMf8~lB|4BdpTRsX33P?{+|F5oXq5qpCq%~S>jo`0Nre`q*8f7H~l$2D{ zs41joq>&aAK}qouN=vKILnFw{%pxW%6mNA61;xdr=j0G7YRN0CAT&0Gq;MB?HDweO z9HmiL36F`UReBnw`3I<|szX;?xFaKJo820R)<|K&LCPu{35kj&J0}}oZ81j*3TW`D zghWJ>+o~0Y*T<2(0@B;&;Gltu(jv;6+_cF|p|Z4)qT*6?si1^Jkd>85bf}Z!{QVSF z)nSB0(Jng+x7I-Z(GqIvJm7GWl9felL^uw^OkpE!mpDTr6c1&k#S|4);MKtu8BJ#E z)`ZD=@(c2)uJM7Q5)~CoW>z|~se*%tOr8^xlSqqJ$U9O6 zscgg@7EN|mCZR6Vq1jx-bacZ*-l4-(SJfk(p~R=AlO7+9)T%jfu!wq(K}>u+>2YrI z3ks;IsYg1)36D)6J3SfMRL%Ya1vD5638|@M#Ya~`7K;%a~}Q{R*p6;fPLLxTn(A>pK@XAmE%P*Pe*aY+>p zcLZtaS;RzyQd?0#VYQd^>}*1$hr{~{h>3|MJ|Pax+eBX8A*vg^DB+Q`%}k}XypWQz zI&>*fL&M0(%pxXK<>-+k94)U!hKA9xRR&J!BmZy#bqyX=my7hQR>Zh{{Jdu`DY;#U zbVFrT4fTzZ%(OVlOA9F~sz8?l5fVmLZX04$owAZb3Jc4SA>riYw#J3V(foX>Ydt8g z5Hho~i3)X_nkPd;_g0gCw2YdXCKN>w5*0^wMk=1#G7c10l9`@@Vltw zBPBkck3D<#keQiz!gIE7-_D>xW*|gaSsBZgEn~`*DHaHn&9rO6KbIXdxmmz3P`qoyYqm>d!N;J!f-`<@E8;wmT0L$;o0&j*0B#XDRU_MLKuc2e~+D%6<|+u^MsX% zS15Mv2ox&`v9u;f1-oXdFt3+ZEeT;pP$__rI(ALn;3NoUb%{XRDn3kCccr<1lb@`l z}d?Frn^h0UMIvyQMF=L6T7362{%xc@K>4Ncbkt0RRVIXR8=)MT(@#YA8-_WR}p zMbMcOwBAf+_IbzV)E8D?gD0Ng`mzDp*s+KKx!4smq_qf`8U<--GMe90T79+`G_#Z# zmJgcGulX?aCJyaCNNrt{snu1$XGmg_Qpn9nML`DjGdO0@;@tvh=F@ceM~;1kUAILA ztdwjRiVum3VrgE2WvQTVdxjwy$=fSGwO z&59>Ze~ZDR(jH}jjDvyt9SVkpCW4pEz}ON&*Vx~i=Ld~Xr2ieUpI^WXXqo%{Z9_0f zXjUiN;#67@p22mr1IeJRchi!E@Q)RNznY2Akwz&~CtpnJpo^G!!xe;MkHEm#w(rL= zdf42zMQF3&04(Dst_Si(4~ed6$F8zAcQr!EWwT`{GrT4NkQwZ<62u!6l5Ypx8)A@H26MErJz8X+ydY-6vj zp;VhARjaH=^R~c#w``#4hc5np+w-t#;y#nOw2^s-bHV)!{lGuu4*tq&b@zQK#*vIz%S5TI~#o69|RJ< z|Ni@=r>D1o!2i!F7zFzB1pZdh!Tx(-O+*Aw0s=cyDgfN1|7}u&0GWR`D{LSV-1xEW z+D8_c^Dm^oHPH5 zE{+^6#t^3eoNh?E^yp1)dI|_}Lhb_mD@dIF<@VUPxn>b}!kmNyW9WFE?F9vaAAp+c zTHtve*Pr7+k##RKm9Lf5!UBLn&@uQ~m`^`=%VGP72Kw7N+JX!Ri z|J>u+4er^$9#eKp$HK?sqZ|qPWWCE$B8cSttELm0(#8siI@wr00iWX7Cx2p2|M$q; z(FAl;5>=~V$IgSqrR0+K|JXb4I4O$lZ$H)DGqZWwU3SSCiITH`C@6?X6cdVqf&oQD zMFc@WxqyI56a-NL0~k>em8e$~^{QkAlpt{lo5Q5;s`roX2}>}%*KqyG@iXo)U0pex zI_aD4MhZ8UGH?ljz(fdz6fP_WmBCPc6fT=NR-iligyH*e8168np~DnLtwGx^Pa}k^ zZdWG??IYY1MI79FlwAjMX@7BRV%!1^oser!c$G!nLr#})M%2G0Z5wTIV~DGXVjywQ zObp?K^Vh;_NkpZ!liLiVZn&e$i)0^aMHmT5i~6O6Gg9P2``7pqmqZhfX6~c_6}Ij^ zOWn@K?}Z(D{;Kwzr++FLr`rzv9U_K@q0LlCLKrP8J2Q2JLR*N9<{|Oe5+Q8-%HMbC z2^>5JVq)Uxd-XLSL>O5%w9XA>~MZ(XY#|0Skws=hRFL3eSbEoNeTO@5NzRTY+*^o(BFToe-(u~K@t<|L+#%LgBP=Zj&?1a&Waf*=om-T=tVH-TLA2gk0LUQzpvk_22dQ4G z7A~P2JZvqp1OSi->7yt&ho7<}buOsv$dxI{)0Ma)MXV?z5fsnH2>u1@=#0(*ge0W4 zmkx%zP7oWv$4$g-M`1bg|Hv+-qW=Cv_J#BGmy;coz=6>EJ1~IYEO}*NnSOF|@{xq> z%+5~sq732rD!@-xb|w!z_$Vh%9^v~vTNyiH1_i}|-?^U7_9ZklU3Wr2gf=osL?Rig zr^&}3f5O-?kD*l5hW&RV5#fJ?5GWbI3KnoGCz~+HpU|Ao**yjNylKq!t~~21}(e+L1At#T2ONI*l|u} z?qc};_jCAUfIhwYa!Jeje70`4?)p3c03ZNKL_t&)Q>V_QMY~R1+2bnGQW8r@-jtLG z8AKz9hP0hTgzYw>l(g}tLvu&UsEexYSYj!g*$65PDeXQs13`R2>98UyqC!_13LQ)6 zNHoX!#bF|qva!^W_61qVFr#W(_Fg3&`J_@74!;Umn1N%Azke8QT3*Sq>^w|_gGX&) zDGSrVO}3Qa(BALqdT|GajeL{><;(!-;Ce?{v{+8tZKoG76?VOaZ8l?XFoyH_Yu1o$ z`eKJOGJQvRVg6M5^ty`6I(ML3*DDx4d^Ecb9LB=Or|aJ1+Wx~REb>us>M#>V-bcSd z!#J8#~D@8g3urCI|O?$+YQDQmB+8&pVSMM~x%CS73YP z1=+RhN2H}FD#~Z?{zI6i{C(Z~m9TALqSPG9kwJ!3V~S|TL$ZJW0k&-3`nMX7Um_uc z?B4PzQ=ghiF@!A&!461!u1(L9HmH5}$xQYgJc^}kJleBSgq=_z^Eq*3H;+x4NnSzm z+3TbPf+BW&y@7|uKS@CVG~>6*f-R6<4(;8>qmPWDcds7YK5ziGc!4Q^dvqlWcM3tzd}*S zp0C$&>kZe^t!o#C41buddyfJ^zTLQndj}1qSC8&od&2-;Td|HJ6c%2NAK1#M2kzsl ztFGeuTkhof*VZDX%a)l5+XfG-h_5%i$DscGx#s%*JiqL%@EX*F6RHLiM1WJ7`?;xS zHzrMy=}=|;~UeVH_MK7|1jg^o)pHh;dB-dEkgoabKQ$88(Ay3aLy z^5t%hAKb$ocihdx6Q&WAe)jMD5BCkanV!9`=GNikIdCH1nKmUa(0@KT7a1*xz{@+Y zzR8M}YZ>61M=g@) zc{)#jA{n-%Mmgaj{w%UUnG_a!$uB5I0;N(?iTAiD$j_#r*l))POHIM!(viUeva)mV znHrifh)*mM`@-^q`MkCNtcQL%I)zM?|%i%bGaQMyzziE%E9i;Bq0F92bX zkdj71jBQvgB`9Sflx?48Xn+~OA1o#(&xfTHiAhPsC&Z(IK60~8;xh%p{bXO5*btlbc(JL?@wC3W>1>xp}z=J(g05 zZiPgz6L0QOzT5pH`+hn?MuJYc zvKb&PaPrmwo+`FeEroHrawKKf6bgvT6(I}zx;DJL4~6(3mJO-?>Agv zqNJDU6CPvo^aYfzRt*)*!IA=@34-1N_8&OFsjOU7&3Kd$h`2Zc0WX-v2oyoXjaN#1 zmPM3BpHqMUB`GeWK(-hO8#?|i(T z=9OJ^x~L`DDuYHB*5<<%ZxaY6aC6T_*p6xzx+>>0olioaN@{8PI_IeUHd3nQX1D?UKgop1Omlm`%MDU zqA2SpHf;EmUbhxfJvqqdAAe5i3xnhoo@7w}>-k}S9@X1);K1hXpu72BV3s1P`2f-^ zV(OF6(SOKLnzn933?{CO1g1=&olq;6lgamFLFo*;#z{K&7kW{t;`T1ThY|xAc zM%+i?4_|Zh?L#QnuoZ#ad`gw8$>aYTkI-YtJh+d!PcNoo*;MYmxf7GejAZ)>owRb* z8F+m+YL|=Qk#SQ%bKx@~wPG#Cj~Z;pSrY=3752B&fP(xJ%$+)k{U>}Bm>_kH$QHO^{j-Y%JESx=;^`Cx2N_sNe_8cW9AqAm=e7^Pr=FOW&Lbhb2YEO^b#Mg+el18JO@sij2ksQ51$QI*ITY7&jh0V6~D7UG<0|m&>`iXbm`Lbb}yKxZ>IR`>& zpv4fMUYQ=(T+i_n$2n2(Z}#rljU-?Pe~!su`Kop7`Qiiax$Q1Ceene+wij~jgy4Z$ z6M68au5@bG5zF!+4Cz>(S-8zCR)6>*CkuRBb6t1hJwfK}{hrS^e#0$&dJyAM2w{Y6 z*mO;D{q5KB@s}I9@Af;W-sn;W-+dR!E{!QOW{~aED4!OGW+>9iRpOefyVK*!PJka% zCJ>WYiI?7amkO!zxJ@s$8aAdwuAifsr^q?+KA(T}6+JGiO8{uru@A4l_8b|SpRMbc zAvA?Blzr(GE`${5noewd3b9Fo&RsgwqjxVVq{U#ft(q;({|ih46(EJZ>k9;hMFkwo zHz`-CI_{8trij54=b>!8hd@>~Znt3j)-TBQ>r9+HiR4%}Qi0H1Af!%s5CRqSvuM^+#FVMYq$!V*q)V*g6AXLk3EKC#gWGTEMlk0mdSBh2<{d7fnl4F7 zDZ|7`Q%TZt7(8SwyZ2{OR@13ks~(R}8A*x;vE~s@oj5_?n@4ipRaX#i6*6)3Fk;ec zGHLQyT>fJ2x#Mm={dg5^F1-X9^ZNT6Xi_$w zfT=U-sp-VVCz0T>A+m&UHgzSDrk~sbAH8oH!p&EAWcA9AcxdEEZn(A;)91ZJQiaAm zG5HZJ|8WN2`7obs+D5M?8Lawn4P$1^r*8F1EPnANRY4%sFU6=boVtvt!>ey7lhP#?^N+{QmJA z%=YojjJwD=v6l~4z0dfkpQA#Vbf(XGfoap{u=s`PtY7^u8EK_$M+qS)I+e}LNl()C z=Am43T^~FuKz8OHW$z5iorMD&lNY{&9!}dQE=)cw+tLY zw|39#mk30H5=aYW`7wiDa`W>DYHsqCflCwIdFP$fZ{5n)VmS7=x)P4V zj)4)Qk(QE-ufU7$jwdc58HJ=llO~wBK}sH*K9zCf9%I~nckKQLs_y`xhpDqGcq~ux@pB?a!o2tqg<_gC{ngWLG|=OC^w- z=cSBWqI3h@rQuRRgy~00Fx)Z3#<-BVMI70`m-d4O5tEomQi7Ydjp}f4-yWKGyaeS0 zl#|L1T#WGX!-1dpXyayf_w0kNy!e9>w=j`P!_s5%#K)89apP8$kV>Hx!mSffE|ez) zJtl^F)hZzJj*^p|$*uz@x%>9v#3#lhVq7$>SChRz9_K_x08dO3spZOJ#Kz$92wciX zZq{KAW}afg)OpN!dMa+|r$U7qXlAg)CZPlNGgq?Agg zZ_mrQdf+3Bo;r*4^i+;-{hV*N?%;-j!-y3{C@H8_|3VCRJeA5NI%-P$V9UwQA^T)5 z?K)k7D=wBe1qXAFp}XU#)2udet{`>mlqJa>E)Ab0ZH=|& zMsw+CmWioQaTmWQ^-DY5a9}W8AHUS*RtoVFsRY8 z9kK6jVCe04adr0|^zG3Kzu_h*VlZ@r1UD4q9bnQE^VzcHTcq@pb-a*3aS)4YzT$jNWuBr+>x*dJ?qW85vx9;Y*d`%T z*?guD2wgbNRtB}})+JWASh;K&>4j}Le5!~Glt4)r3Gp5ZP95a)Z}(HJP9x%6?~#`1 z;;JjJBH;B?vteV5P?UlY?w_>P-k+@egm+eNWYEyNS@FgjEM2mM2Z!ImyonR|;Y5JP zCXOQ~w}1ynJxJy1Ynk)h+w3}UjP#5|r1uzW-g}44x>cxNBAPXC&ATbD z02&E#@uVijvu)?stoi73>Q+c0E;XG}2?p=HynwjwttjyNNl`(9fjqWu+sZA2ZY8mF zX=XqFG2d?AMXN^D!Y)_#=iGM1e-sHqF=7ogcOoP28_d$zm(!?4eQH*#MsdL@=FWVE z3bkufrS=8v{x%!UlS1qE7qej2B!)fw1o6o!bh)e*iMkfK)c>iiI8WyZjL_-zr(p*x zaK*%un3TZ2J>Q|z7JH1q&BFgCosDNp=s468SO!lAxb5*MFDxysd; z^4xRO%<$L~LDPuWEZc)n5S9eS#>F8F!I7W#Q>9WGU=S0VM9}Y}AiJ1yW!>Zz6jA68 zkerwh4h`Y#l1NND#IO-d&~GzKn(hLj;nHkXnyw%&&P9yJ;Mn1VRIiYX&mZ7qZULU8 z6#U*igbdhzi^9P6jC4XnYc3MYROacKQ`!05E}owLJi5rHRr@w}Xa*%g`q=vQXT0*} zD&BniZOW&5=ylCd6gryAji!Q_riqAi6PKJ!TyiPq&YMTgj97F{AvA+{PmE)Uq=#h3 z=t;?3(dBYJ+wd{hb?Zn{Tnqpk)@-EEXHlbaS;YQBl&e&o@iU+1o#&rn!pMhtYT*l% zP4(cxKIH#YbKLXvn@9>5MqC-jKQR$)%wtS_bR>lZUec;vNP1cVmX&X-^<)sVIHa<0 zQ-mfoFg%z-L&L}88hlewD{>xm`=M(%Qo{PHlL36z8HD#j7 zAW~`s5$H(TUv>#or;K31vb9Wm@;{vP!UdWKp(WG#imtr-(MG1sT*{K!kCS(3AB&bP z;`w>ANiJQ1*^3r&LB$M55*dkea(MqwJpAxf+H~s8*oouGh{@-Q^gAFej5I zCr#nIT|W}^#L(f2Yq_|6%P2eAP~HE022eOmzCs6~(d+uY6nG1Ha^g6Oy#W+1YF*fr z@sHh2a!Nc>)0}&CEDc+}Dv2hvKTQ&7 zNejahN6%}oW8l!SqKlG%9VYU4-pB<}zIL?sp@%-1#8o5+#L&K30CUhh_KP zLx$UfFY^H3Zr@GS>Qy-M!&Y|eIYq-Jt(Y@yDvypC#buZE;`s3_`rOnDB_tX_bm_=% zv`~N$Ct`tv_yHEW3KF{0N!++%(;0BhWsDqh4;hIjM~)n1)AoG~9(f_jRpO~!p)`-* zH=LUXT*o(Cc2g*lD3wu%-d#E{b>v_Q9~@77N_mo!Jap^ahVU*SaBlQ53>_q!#zy(3xBBxr@aw zE~j#Xi)mT6Hal0YK-V3_3dd&0G9f9W97p$WXZhmglq;Rie%iB{ZQFN{nqGr| z((x+~WlE=0bYwGcyt0%smCKTtkc2lsi%lCoqCvw31WU09R$!3(nOHJ&@qp3$Ji;jgv}@h zg8`)J+$4pCR2rI*!r+IV;EsnTBZP)j5LDpOg4{V`40nzgPf#ctSM0%wynI{g7|5pc zl|ATt$4D~w|3KTzdXrYBESBz}&1F6LW_wS(ni~U)N2kr=(di3tVpJiOmtdd}pVA4% z0R=|b%D>Z+t!pF{zg+8;h@!j@-hlZenUa$_4pJ9-18sEp+bA0G{T{YPU6E2Yphjhc1p z(Yj@8wr$Uvl}Sezf~qy^(5z`wwr$;tL}$dP(KN1K z8@J&iH7%WDQ_`w=bK*QYCOR#fH=_MTEjV=K1Uq+pM_jCj=FJ-;l!a~>w7a+ihOURz zr6Coi{Z~<3Y*DppHL8>^jWjKMQqiu{Ql&CK9XLqKmMyucT|0!7eEaQYii?YB z*}M^n@g4$}PMeEblbRH3OT08e>x(WTExjyTw`}2LRu)Z~x8SNPI^)tLTek0{)kT-` z!2S1=lHeieD<(A~gSz$VA^@*n(X?q3DwRp6Ld8mK`r-?$K#=B58WFIdUc)AoO-(}+ zk`}F6Q#zv@o4?&mm8#VlHEJZ~Gg2vAwj5?qQYtltisj2X>TnxjK_SV_&EkU(H?Vcb z54332nm)aHk&=`^%_^1oX7e@*d;u=Iyek*CZOhK>+t{{!CoNjGq|+tssamBX)v8os z%a(2UgBC4XwWfFXZYXK;?Y14{n)<0efwdiW?Q=^0cgR~F-}OU;g(_H))j z5&N=`0_p#E&4xm4gy!>a%O_NWbHC-JP);4gF46q#Tfa96A+RiqtgI}OlatSy=ER8; zRH;%0fa2m}cJACsi{{PIG=UHXI8q-QgTwBBO^Zbc-5x2;KnO5|v~AloHwYaeK$DQ4 zeS+I=yp|CUJ;KacGnqAW22VXTi#)GMhf6L-SD}5xi54duCQS%5B?+NV2q8Ik=qE1e zcm@BOI-NxeU!>Xv7jpM~_fV@!IW#l}mB+H>)|#8}h9LsvWF6%CYx**3^cZH$n!}74 z&oE=wLj0D&B^_GZ?2Th;p&@W1kZ2gfsev$@a6iIMr$EyLXtowc6T&ffu=`6X+k#gQ z!)h3I|DZ4g2;oKvBNDGxh0vgM(6sQ>F|Yvwv@mMSU&8Enrl7MtScLL?p$TJy7z9RgV2pG!#+Lvd}ewg@sF;9ym3+ zKThxSvmM=Mn6C3{#_HTDqVqdj`DYueGwW}UmOv`gmRdUiZ3;W6EGP`&;6E!ITTkiW zr=FdWD%r;+%RM_obgupiQPle(^8f)(*k9-EkQ(r`K0YIxfb+$5_KJt|j^I9@UWZ?# za0NmEg6(>p73S(^@~{zmq9OXkXoS@2R1OvtVbYLIFJ`<#i^wOotC|edok7x$gd-qdV6a?W$ zDIFm+GRl;pLisXho1te?)EGziNu)nyR6-H;`M*Iw{qz&dmM!Czzz=o_@~AS{JC;Yd!{1Nw(t*O)8*ZjTI>pFzD8ArU>(PCKmB;$wMfon{7kcs0V>|Klm79Vsj-{Ecsx9On=zW#bB$En69cJM=3kffSHm zSZL4RpXHUJ=d(rm@|92_#0(|y`HK1F`Cv0=6)IFkDO>ucoXd%63W^JhenlR?hE&ww z|62?oKpikx<)j9JIfx|2N zmaLQ@s2Lc_LI~Xn`vHXHhDt*T%lWrq+bRkL(O!Q@M;&mkLhW3Y6bOx^NNazikS+S#&s|EQ1Z2+CkXX)TOh4fb3tmYo6=uNx8?rTbq4}$#8XuB> zhIm5ZI2(o9Y_9{&QI&gNQ{|0VqvNnlo17O%egDsi!~C>d!-n5A*ltI}au1)(dV z<#dBV2n|SuE|St_dKH>;N3r45q_E*Eb*KB3IM+IkY>1)#!alUMaJZMqA+8+gNlK&# zg|6FU6FT_qEOiHdGb9DH!q?!l)+XF1T2!Ba6w%Cn=zGL-`j4RBbapBDEjT0R%3BCQ zW@aWC85t$B{|!u3zLL)4tEyelSxNj2haqwU!Uw!o> zy?b{-*U!Sqho3H)u0*YC5B z9XfP~H{N)I0Rsm7F8Te{6k-Ziu3Y(7SLHnY$y6d(^q+gsM^qaT2%hL8H}u^?1yAwv z(v`I6+>`1R%7pMDqS8ikivEq$(w*@}IGL?pQRK7f^G|4*UX#`h!6QV896&m^^vK3$ z3j_oLqvVDdRl10N9}__lyZ3z0s`o#mZ{IE`$HVT7{s{-7HLwo~8|PCwcoQnD%9B4+ zX32gyn=NJJTUaKA0@kkn2nAf;xeH#ImDq-7yA4XH)<$l2O$_gU1NKoM`f zxr*wI+tH|I6`Nr?XWOIm^b-tb^TzA%(WlRKXY`hBG`WgFgRdn9g%*~1pKA|@8W-#}5b&O2+1u;6sB>?smkx!{ zv1d6rM*jE_s(_UrtfoTMRy3$n0hb8HNQ{Qd5|Q;I&Ne5014I9dE%+5_o%ngWuA{k5 zUz|Tzlc*Kod<|>IBTt-^=ZY2i%cAG-%u~+TM~(Bj_P-DrXZ!*oa~GoQZ9}`ke|IYU z_G{Fc@BjB>AD!3lL7Ju^rNl6dh!p&H%KNV(r4)u?{Bpwc^nZ$+karG)pwu646QHmU zMHK}6fW!&a9RAJTj{Kl}fQ||l@%HOWIhB(|09*Zu41n^3w2*)ulqCq#3(AU;H3UJK zC~24DS70g2&fD^Xl9&jB0K#UkWaQ)rB6nn^EEEAC5H3UF{_6(5V9D}D#CUTvHQo2&ISoq z5lY$5?a0l3=b4?Cr2?Re0g2`0z4raL`SRauky7FVOe9D@Sa!@l3&$}-nf7=9UhMD| z$dJoHsFR98d4XU!KCRtTc0B^he%HbT6;Y#Eq2p7TnAjfN3J}tdP<}KSQojL0Qe1eF zw_bmVyuzYzJA#h%6{l{&&{R|*rB`TTT1clKG|fT^K>#}qmKQL?{c9H*K$%5I8N_m0 zVoHfJi&*{68~k+Wu&uzC_6VX(Ea}V-r9c*g=>_S`f1x1>I#Q&wNrDtg7P0odH`%s* zJAP%iPYUe5RY7~s0VXC;Y>%^&D5u>L&^<8>zVAM|_vqxz$$-5U!li^hmJ{bOG>G9@ zfD{_O;ym7cZ5g@QMfMsLU<%NbJ!&RkDFZ2etpDIW_8mNG_qDQ6n9l0QVPd3X)?mkV zbY`hDRsp2bqI2#}DyrVmT#PD_1Sx(dk0{c09ifScx-=>;W%^Ol4BG=M%R)TE(?+gR zc3VSxlT=nXl^Is?+k0Yk1455NW>a<=XZ1>nloHFb?0Tq3?}c*wtF=An>8~LzBms>6 z{GlWO>Bm=eipR%K;KGItXxh9bZ@#;MysQ&+Xx4yd7cC~>D`v{1NsN1ZI+hvW&`&?o z^NMS!U!y7O*RSW);k^tRa2t*4*XN4MujHGZ2e2$3uPt6ky#_5QSH2#TCQjn@#q(*@ zpea>r)TCjPM!fpQ`yiY@Q4J~lxVDw6S#V2@b z=F`+`+?x9Jo3ZBOHGKW`m$YkhG1aP6q)F2Y8990c?K)h{1vP7N|L{@d`GP26vg7NG zT-K!C%bnHEU9(N+kx|aw|tp6)=Csll19vCAr=JN;7$M%vk0>|0Y?P z$9d@f`>9*M9$hZ$%9r16BPcZ%%zm1Bb?Z^NWBWDTuG|1Y;i> zLA7eNsa3l^>(_nAiQ`8YI_yDe*S>%&y7gr9&RrnAEPZhyjq5d~YSpS-+^#L-$B(0V ztCrNdpeECwnu*VpC>7wf#fxa#ycrGa*JI|)`FM*ZLIw!;oqOGC+Eab zhTr!fwJ)f}WtVm3KbvfIpw(#}9Mp-~qC7a*;w&n3u(o z1BW<#B$EPf&@t@*;b6~3q<6O5t)$F7>W~k85vR%fR774UWD#rEtYqxOY51%Nb7x;P z9ma(y$z+Lsa`I58%M_#Lf((G=BM`Kia-k`tmCwre-sSao*Vq@5NHv{2PnS$abLNrj zZ^<^>Y}B5un^?T~c@Actz!VXlI(l|S%Zim%#LCweGyRDt$;`^b5(4FTFa?W`vwG!9 z=05u}0aGHw40;K!^jA@sX^w8Kvf=tH6$$bb(izz{

3a2&`(S5*bVKnXo;ePC;T zf}jZJsR_+y^i?rR*etJ!bI}xGaSBRkPKgR-1?>=#N})6zB{U~IjpFptIZyvQGNKKP z|BRb}1cc0I>D(vydQUD(mcLHs{@pw_?HL-^pUi?67xM6!8Thh~vVP-#n6=;q^w=WO zD^zC0!uhnUU4v9Bi=np;pk{}w8TrU4K3MS<)1I2o3r`Pc&+a{3+UrK{8gwHWt^!_J z_!JfDw&az`53_6Y=R7)X9<7@;p>DNgo|^L<9wVQZmc7lASKguN*c-6UVb5nv1QhF6 zyul}%w(|6IFHk8lhVtcN`25o?RIS;ZSKoM*)gQjYwCS^$yLc&y%E!R|1Ni95?sROF z!H~NK(QD8sx_7L{dn;D+^>+bu71}HnVXsi(XZx3Hnfu&JJTi4A^(v;36ffAcaRYCx z*~Bx8m!SJ{89QnuT1r_uH?7Y1J9aU9*-9#>3LYCZmL;#Pp#S9^cy;+w_8&b?sY)L9 z{kVrN*A8Uf-1)fTl3BUx13vrkb*4W(m-&lkb71cw2HZ7_&OLikCNYj#+rDAo?RPR{ z#Dm1dyV&;SMy5XTBok*YASEuqz4zQpjfSmhRWX5_yaHZ$^9?c*5=heA+B*eud zk!YG9zb}h#cI;=|v=?dLxFQuwn@oFh8t&98e6(&2@4o*&Gp9dE%jYJr|L|ctU2!!- z@4kU03!Y`!;+I+U=IfYQdl^1zJZ&!TLc+;CELr+8k3BVua`9dspR$lj)oRhHSv<-U z&$9R5rCwQ`w8Ubj{c9R}LIqZ@Uc(0;uIA~d=F;TFxwthADHVFiD_&WAv2G>vm%PQJ zPtW0kGKrK*cC-4!_xa%Soh)4XDl-2RBOZ7Nk(9#4wKCYTa}UpcxRDC+K^}i}B5$u+ z$KCx}5TBaL6ALEL<)S8}#}u&Qr58x9P?v?vpCCmPviY->%zb`26J|e4MhuL4coHtH zfEx$)L>YPsX-kA`>4?V@&#*D$7}&2D>9NIpx_UVePkxq}Gv`pYl$&XfPh~~9Qe1b_ zO&rbg^7O2k)T~~X7v|67-Ul9K$+J&j1oN?k#?ixv7<&64I`kXDgsHO-0WWc}F;QjO zmm;$`m!w(zIG4sfjUoTn3L%d4fq=fLGsM&r7eq zPWvXeVi_JDpFNM>9UGDwo6YARufr0tnCN)W&`b+W74q@t|3-K!u;J6$SkfdTEd{ey z9s2Y!F!Tt^9_k$t5{(HF_3zNbl3&H?&wmv~?}-wHpUi#V^3X%0nX;%p@xg<1yXFpV z8ul2Y2X|!tlhc{?%nRh2(EFyrJao?>#@ux)>of?G?Pb;YWr(I0Bb$TjPc1lkK7*K{+;h zj-<0>xSxSb#8j{lz&v|MoXjY0{1gWizmm^F&yFdb&zmSYDo= zJ%a-U9xlJ3KWS;nc8o<4q#*YwPd+(|1BFTS8+ap$#{Vx)ZzNE3Xuu>O{e`^0@_k~` zt8z()_81{NU}cAiI(F~?D?eCGcA=LJmt9Wt#tqT2@aCW7t+zko(D59awrWj>4()I& z6Dv@}yQ|*k`|tKqzfp58>DZAtkAV#O_+DBd_wHAbKrGl;~R2#vD{^`FsoAyZ5ANi$j8@*FsHgq>OeIoXBuxVAUdQxr{_9B1pUuN}!K z5b_j8f{^V0b{kEbwBh28?MRk>bdkl<#b3~*V^5m5Y>sZ`az&^1y!+l7E@^ZpxHQUE zsY=}{v0UA)Gany5N!hAhsZymnJ9i%-!&eFw^inn>fw$j!i{p8Dyz<7I$l^S#_(}wd zZCjy=RjX6EN;wixNC9yPNu;NzwcJ1Z%TW>{LMI6u0qs@;8Xj-;D@remk zs#2M%sj0Xv#eh2pI^*py(3*~>#Zs+CeX3PYgn~V+dTSX!7Nqd*@)s#AD8ikPh&Sj* z>26XoDp09<4LW!1$ZN}9p<1mPr0YqPPfy@PPBtr7e9VOn+i*#{cEpJ+F70qJAHB1J zPA&Q)j5v~0N>e&bq7`KE&Kt|wmzT_{*OyUPRE&sEA>cRh#2Dxyt%(Mh0d{@6g$|eZ z;Gzy~Nx_Ff7XSIr7qstw0}Y!rBhJdE`{iv|v*r_8*X)O`8&s-Pk$ROpbiTALKO8=Z z1Wc(&NQ$Lm=|qH8gp___OQlk|YDLlw9~+iG%SD%TqDA}Gq^cmp2J~goYcFu+ja{+O zog2S>$c4SM9q(GpRKzF7Q?7I}9@EFhHEU?su_x^>ZBHV8Zn?T6Z-2Ro?l<;Fk4dCb zrK;4bUzO`_>_gW9Q#h653x|XFVc!8P;b!o_{v^i55gln#prbhloF_hs7HwMc#M2XT z=^A(3dJFiy1kp%MODChW2RB}d3$j@-e*tUOzE8H-MUA>GK-V!`9uiBXl3F^67*%M) zV@cuswcQbvD~=0lR%QN{X-uCYxbuPGSZ+5p>NTZmohArPkBT0n9B*S=g()oyG!0D% zJAy#y0G83}KbwjEZ9844Kp!X@uR4g1sp$yaL%9m647~Lg+Fsn6Bm2K+=_{{Or$t9* z&zVkAVgj!(Th70~-OY-1pO8_dDoJUnVHKPvKu87BXR9%_B!sY4)&T`>ArZ<1dSZ-k^^AzNSN2Lhlahgm;e6{AEf z7CMG3#?oT(`vR6osq+a^1_PMR7fzHG8=hVG zA|I^(luthUg5}F!piFu)0?XbzLN+Maw@?d#&@^Ini54he{OE@{o?FE8FD>K#2Oh-G zU7$=966M&lX{W_a6ozdl6bSg8JD>&lu#^ld?{oy3Qdk0%uyE-X(hA^l8R$SD5VQ{` z&A?JJgfky0L)cCbnjw&ubR-xWC_9)&FzB(*`HlZ{{S?|-kQRJ?7kC>Py`4d z5qL0MF50%ai1$~2$VclxW$X6uxo^m=cnk;zt*|;tX%Zz&tdMu4gC#75j^%`uK-Wnw zmCS_6Q}}4@dOqFs1s|_pN37d}P#QtgkxLl10k*B=kmy2TSrSi741rK0Vc-u2k-A}@ z^Ol7&P1{q`&`3@z&A*tP1`w)2j(@cDdbA@qc>H>JcdbX&zFE!-|01F)n$rb@Tt!D)6g@VH#~e12O1Boy92 z0Jq1D$IuYMLaNZ%i_^mN2;4Cq1mKr|&~O=Uf`K4X*=nGGDbZcF&$vLMyWA*Kg0v+P zn!^m(W1}#Ge#cfQqQZ(UPe-8XvD`U)G%HuW$@iPT;<`S)@cO+-T}K5?JKT&2vh;-o ze1Gr+&%W?7GNgVLi`;uHIF(^Im)Hwcb}O+O%oM7qdU2R@GGcUEhxt zYd53CuuuexwwVPq=0IN%C0Le;%#UHZp?EQq#r8;*E zxtjw8MMNUUnf31Lv}@Cz?5r%ZtJY@3=m&82nDoLL`GsX{qgpVEPkzg$XGV!ZIgL|Qg(L~8j=>gKfLx8Hwf&a4k< z)20$w-PW8VQvqEYtk-9wKqJ*ieHn-O>2 zL+;T+qQysfYx?UnX_`Z3W(9ioyn@whHxU)vSkkp|;gRBeo|yO`wQAI(O^det@Z(Q^ zeFXXsE`7@He-@r^eTC&etfX>QCf&PqLOY>Si>(+Xbl;wxY~5SHy%Qhi?%_i?wMi|e zz4;ECwrpqNw?FXAbI)_v$XmF5U?1Lk?_-YVAK|&Do}~Za!Q6Q3EsPm6g1NJ2A>J{* zoHLg}!zVCs;H``rGKd+^J<6V)zwypzUo-svr?~z0J9zey(af3k7Ta?VFzLxx>Dv7g z?i?|UNe_T?b=D$ zitzSpuXEU|!uzkk#MYH_`EvgE5Kbp8DVZO?U(L_!e#281Ic;)yYsLrc*}ae41A8gR z-;Zq@p9l+Ixl$IIkZ(XySXvRrLn)6)aS4RdQQ;8bBty!sl#OMCLdIgGlIeIxTehs6!;DYArrU+rk)E7Juk*SvckUc^?b^qoydxAJKa4`~ zltw8x&d=GRQ61L&w1S`3tl@`sztZOP_H6xqBVW$@hQmjXvSZ6;k|YMMi=!Mv>x8gn z^Do?g@4Xxf-W>+f@RkISf%mQI*rwr<@-OeY2jKwtx@lAX=!AC|Fx{YEx#-9h&Y zE@H|2&-rTBY!-d@9j|@xHSIfeBrJs#AI)RYqJ^woyMZ^Sf54e%b|kZW*yLAPG-+I) zl#uY)V^8w)x(zH_wv1vQ2saQBk60wenxB6qDI=5KmtV%-?Z0v4coF3?Qu*}lH~4Ag z8V>B)O~mzZ(kfzwlLVY0cq1+nE2&H>}^hg@Z?q z6HVp001BWNkletA|##g~5 z=szxvnl-Jlw)SN*_|qC&p?b}2O*JOQR-D5J%yPP`_CYQ{Q`qn{Vr9 z<}PK?rtPV`@Z2LLg%m^YxSQPL`K(*LhNJlrCOq&64@|s|!o$0HXv_o}HfzC)Q=X$J ze?Nbj@G#qd-_GRwAEaF68a(yvbKH67a4J=-NGRk`p<*WYOc=wUt9tSF8?W>8#-04S zdO7!we}E>ZpTlF1J;a_Z8yI@aZR|RfkEbkLJVFXqFaCz7o|#I|t8U_nWvuzIta}QIeZf#tWs8+icNAk8I(WC4= zaFFZd8vX*`MB{V&w3mT8sO|wznA$~t_fQ74eQLn)%IF=^0VhG29 zgZZw{Wpq;h-Ng!&zCR@}#6MY4PCEUEk7LmFmviTBgXq=c0zUlUb9Vl=m&uPk!@!&S z(x^ov#*7`qtdBk>;-+%*ErWRTsr%`D`4z0$x{sIMm_c@$%T*Wmg8Mxa{()SUBrF zj^^i+crfOhvN-RGYq+t`MU1+oAD3KsIdi{Vg-S^wIW=ZdIVm`yR8qBtZKdK`X{1r9-+YIIn^)4k%XvIJ=_wjFtPz}S`Iad2u9zF5b%*o0Z|t2sKXE+W&%c1@U;T*o z9lLT{zdj7T=|+YOAH#s*t^-2;mV7-`0_q1T(le!g_WF+Wtk%swC2j|ZlGLpGM9Jn!E3Khr+J(9 zy!OVceDKQioZr0%WAA%}{DLC9q!g0V(+F#ikhmPlJ;c)Qmg7bQPe5?MN+mh$kfKTu z6-GJLxOLdwG_97zHJ9|_%05@IWcex}1IM-qr9_S5?t}=19UReUD;@2mlMLjvYtN{= zhVjtIpdjtjb;PFh9{Mhw20k6wM8%dY6lqE)*XI(!^0>QtcbCB3-vlFM2A z{g2p+c(|d1GRm11rbE|@x$o}Vd1m}bdYyj((`L-0YmW=)cU3oTy1p-W{bdrPCqB=G z=XSzYnowFQVaEc(C?}cZkf7`;T-CQ9OJ~1N*BUK${hb$$((xTdE7r{ zC=>6#gPU&~N$>0WGGO2>q}iF=b9+DLe(^DR$Bvn!L;px!Sq{p{xQBB(bY$@GQDkOUL)jI$y3b{7TRo4S=UvFVA1|bO ztrpxp_&V+#Ih^iYdvc@%s+6z5s_z$Y$z>OFO2_jlpH+o(Iy7egzHO{pwG!72z-P?y z@5Z%j*}Qct8pV+#NBL^bH{|CZLu=Ua`*zl?S&I&$^5YZGKNticF^=Z#X3hGY)NR^< zemCFDg+0z7#r8nEShm^tn5bqKrIM-Duq78>cpmke)W(q*q2zLO?{NX=pK}(K)6>ln zxL9U`=pzoST=+FZZy&*+A$PN8-9~cr@({}+=2}RoBAt3(%q5qdPkPv9>y|C7T)CEl zh~m<#ucJqgv&l*~8zgKCPh315A$oidD}G!-UU7tn@4uhnca0^clG(F+ACZ_FhpsUS zONekv7X7cil&$MlvTf@w7Jk2hZe6<(PO=z3=_%fP`8l$Zj5#}0KAWDsy3($76JvR| zLR76?hpVr=kdCeDb8OF64jwMR^TMPir_=4+o?LrrHxBIhm2JEBG4q3ux$(xESiflp zhYlSiqBW({eC-{r0c zp5n%SH*!&z*6jIhJzI7j#*-uhgwCbke}|o1i5qXdgBJp&@lrtDM z{(D{RiMUbmw0WM^u83D8;zs;_p~aP`L?Zdp`=U$amvujjt4$r3Xiq#H@!Q(uMaN1^ zTkDvJj*06<{BdH&n(Jxt#1qj)B5qV-!FxTwPkSW^J)lIyJsz*S5)tu4i`Eg*5=-c} zK_4>(ceR*)EJbD{`fVN+5s`>^;+58WP`^4NuGaoIGW8e<`hgquGw4q{T1%v)Sk|ps zE&2I}B|ks^uYMLSS`<&8mzO6~rc4p>3gp;Hdk$}tF?Zc0>6Vgl4^5Prvp<*j zXMHYnR&SL8FBq3vf@wi}5!tu?YiUuZqV&AvD#@zaO5XYWTPYS#Hm+YSKdf3ShjRDG zm0eDghNqq-dm?7eJa%xkoZ0SFIj`?9i4^aYVK-bU>B$vj#g2_K@S5JzD7%3y`DK?B zOR+5a@^z_~ktCO1akYH#>1>(#*_ZP6oMn=K?2yEAH_AKHUy`%WK3ghe)s@e`TOs3z zTrKtMG?aO(f01oJ&yh+MOuf&3_gTp(S3#zKy+V#2-zV2!aiLVLT3zPDPjc2N zEo9riL*lxJKmF$t5`}LI>pDh+w z$7JQAdD60Gw*0d8J2~h4i)7|EDUQD3_j$<6BHEpMJ~pvdNd@D{P--zf!J!YDk#N{mmXU|3K@P?m)w8c%zM<5ejv&%?GIP_{8v zC=byt4h|ZH)()0!-fw9!ZDiv|8wTWGRw=EmXt2cC+e8Q{-~Ut@M|RN`SSGU3^Z^GE zP2i5HF}{(Gtx(Dw?S~Y&p2D${2%;Np6?7+MI8jC6D3dj%EU=S(Z$}dy`Q7}l7(H$R zQP)`5G$HIznAhHZlNJqXgB1etZ~|M2O7;B&1xrkuh$v#NhZ8bK!CGs=wh!U0Ou1|o z1ji)d;GspZm2D^kRT!m|aUS=B^gIm~A!0@O3?Fg}Kd#$`rwq@A!sFbFd-LGE<4|G% zAj06kAlaO3nVg{TaK*y2lkij$Camxg@2_G?sOChk0AD|_kX;bn2MU{nPnTS^{+5|FK25ZiY zi4fvhDBG~TSU@!95(<^JyYkz>w0k)2&!WXLffgdB@7N)8UHhy)zCZDQ%;xh)Q&ouc z%xtdceI8>Un!;5VUqZFC5(*+3TVg=6-{(C)<546OpXbn8Y|COq-LI6iu@JX?3{C99PJv8hox zlOub6W9VHEaLom0lkv)XyfghR7R|50@q%Macb`I<;#uYv~*=KL1j>oZgZNBd_#fSQJ7M8Vi&O zjf`0g%AG;EqfPSbiU{B{9*_U%Wa5xQM|6_Z!vD*1yp(F z6^0M$Pve>uSo7;1Dm7?@ML=1Yc-r&-E6R)+|5=_FW8A1Qbic4CZBJ`MMyQb2UYkne z`t@1-<0c-TK8Z%v!qll(g?lI5$K^fGX3`TcGT@#kDW6@D-q&2kTdz)|hMmt#&%aEE zE`71W<>}n9J+D9aC{`Y1p&{7oOdY=kC9gaO_TAed#q?wCPIy?COlT z`3nAW--9%3-JBo3nL~{_^{HGwrIe~NSddQ2zoo<>V*WIs$N=eB0)@S^b$YT z3V2*?6?eBP&8v1fT8j%7#Olg@bDYU4jEmeIVGijN5s zYGTK0-BPBnmG%P_A2OC7)r&HHAm|aw3ZP4j`jixM{76~}h7>`FaN^vcEPvNgrq7l3 zf3b`YsQ8N6e|EML9F&v6?W0GLUb!kCeKwE0LwQ`*yALfI*ToJUr+Ld9s#HuNIkf^! zTQsF^)eICC%1NhU)ofZduSbeQg?=R{)fQ#xt~wfY>&nl=5`wb`H}%_?mNj zb)kCI3=}1_Iinq!4Kr3xw3Y|xfhUVW8^CQjzS;o}S*(T7o^?j|!;xPS6w zio%nqTDd%x>*es~j2S%s#1wYy+(+B?9XR{k9wb=-%uLx?;{QvmB&yYEM5szdk}z|P zcpgewRLCgLedEV*@5D*WoA)iZjGn-$jk2+c^7IQYF#g_0dGeVTxpDXe23>bK4lxGb zHJbc~Co*>21Dx0E3i{q~As(q*am}^l=H_w#y^}b#!#RwYcpkLG*!Apu!pq&Pq)gRN;C3n$P8GP%lreG>yXYj4Qm_RH`qKLAHDVvZ)@l+U3lsS!%2w6R`16qH%GE(k^ps^zBogLVQJSK{JU)EuL-riV!*j$?&jGb+RcFI5YgxH!BU|?s z@YOeSsavBWVKlaQc)`gEF_Z>vg%NE&d&N$ znIXI5iR3?=XAIC_dtX=yH+4UQfSuO+H zpX5}Tg(PtSNu7@#g9`OKI;jkXu|r*YkEEG_=7J;+U>0%+b6@b?B$ zy-NPNE=#S3_zT)m)~@@J_ugN`OH&{9>myh=`QzdFH#Ay>%eUVy;QQ}?rd!uD|LWaF z*;A09zMuddr650_wZG@m=G4}tI7T5hc`(YKCBgrRv`>I5Y^C`o`z_xD+7|Cm2Icv9KEQ>sXo zj_KgeL@Qt7bN=gdoH6bu`9UTgo|NENA6a$TH|vA}!c#OEg)qsV$Hgd>`xMThxi!%`Nl z%f(L4WWeA%xOKplIF`cG7Pf_<1H>`;1Q0=~2(iLE-h6oq%YOcqnBOc)LFdjLSo8CG zGHNvAg&7}FuX;rs!9W}-18!|F2t&9!hUL52V1=**LYPer$^&t6RLJyhWvB!#WfRdB zj-6znll-Z}5f^L+NFt^^EOE^Vhw=|?#b82uI5;YBJy3|R`~?b~iN&=+D=bS9!bNKZ zmP5>S35617GYK{?|9xwp78|83EKg(E7M_dW4!*&_H-6X_SmNS|!nPcgGTiXECP>7f zDVXvpWf^OtZQM6BF3JiS>%TTGKDO;+WlG3*)rtAr6cf0jtg!D^rBM>YQl;C}V7B>Z zJAj>(e_i>L8AE*Bc~J(}3lK5LbY>m%{N0@mxMsL&fx>Ovd(Q|)On#X&S~T^2ImEa6 zSaDrLdlBR3XS|mDZvrL7ELxszVPTowD)`ngGwF(U@pKH&?7;~8)uDZbQz@I^*crs% zqnaZxEiMW(I7NI5W?WZPD9b3W;s@qyEtGi1;^QP3;w;~SVxkSfKf^Ru9r4hZs4)r9 zW-(x}mWbIoD>E$$2C&$%ED&X&OHiN;Bdo=7R)0T-2WKqjy*H_qVfD`&Q=;lIIc;E=dyF_ZwwyPpAT28 zrbgw;Bx`f*7^n3T(`QZJboum+=NR?q8@%+x65G_m=%mmCZ{+;y^Jj zRpx@PPna+M@MG{6RrdQ6^K-(J%On4y?w?bTa?>juk>M7Jb1S>j$Gl*=9VJ&#uoGOIDb9B5-%1bQ^42pu$c($7O0- z8D&iQWvf)@6h8lc6R1#pArBUF<&RrSh09i~Qa}j{R{I(O)#{ahh z_Y235-iA=fiC2YLFaCShy2R&LzAJ9MFy!ghK>^pdrtNQeyN&QS-eRCGM2lA*=r7C@g zj-Yef9Kx~VjJ@-2HvP7ZdM(;A^v=7eTQ$iHDiv5>N|h0XBm1^6<)yb-{L^nVZ`FeP$J{}3IL54*AMweoFG$O(!_X0T)3Sag zlvr3|`8&g-d_MDIKKN__;j~PK47-DtIgJU+aaJr{&I_--&yk~1Ztvd{OGj9}bP-ov zdpC1$OSwrRybEapSdp$Oy&w=*?I8{EKfmToh%{paHB}znx|| zr*P$^UHoGeA%x3@pO?`0nj0x+y9^pSn$GQ85>_RwS-zZ?UVV+jg_>*n520uGj(CMf zdHMNAS+L|MD%WYw&=I3))vy9TEMCal(?4MEzWrQzNf%O5(^&AuEH2sn3vF6d<+cHr z5Q`jP@LF`MaAU*gm0Q>fmoE!}&bOS1BhM0E*;NA~detDn&7 zlumpy{cYM$9*b6XT(v+&iA0aHYuhf4?cK`6C!c5Vn0u*TtvrjC>n0@A001BWNkllT~tav%7QQ7WZRyDj2}0S`Cos|9mB@* z`ON9mudL{ESua9KsZ4xf2G76p0h7jD{MWlTlWRZNL0J0T*NhuKk%5CpQKLq6YSzeN z?aDPA*nfR5s&d#aA!0WH3YV(c^zxz(!d3O#+ zij{BeOIR*_tJ9nhX0Y+s&5V6;60vA8jum0S?9Z6~<_yN&b1!oiuH=q8NAu;(H}I4X z6fH46|L|iTdH50To%}Sb*KXjpp||tS2k((m@H@lr9Lm)`rbTI)seOY$iSOB=sBCrdiEQ zdUQF9?!9_4?St=l;GswP@U?L)S~#C*L>M>rFVwCQV%d+YXnSTS{xW(Lbt-w39N&)T zxzw*;k26l`!IY<`5-llW{DixC=jEyVv~DvK?j6qyFTKqDlV9NJNn^>blEtv0w{on= zWz4wysL`kuZE7ZyVhi_Ae1M8o>QkXy8vFO|CbfEfzctK(tmr7SXU!rtyE$XW+{xhU zd-L0E{mH49L8&imF$Dz&*|cFR>1h|RZOdjhY}-kLDh>H=(YJ)tGWm7wPdqyLA%>26 zh`rl?Naf31R>C`uVCU`a^{HEPuOpU%!n`4i<&_X*UNg)S&y_RLSnuHS?o z)~q8|Qbo;;FFCXkAYPV=crw)yA+&sSh%p<#QOWL2^j*h1{VE%UlIJk2g zwJX$MNB&WEZ2yr86_VM%Z!fO){=gjW8_z93Vl4e;0lja$i7Wf}B^?ikeAX#VX3gfb zY2T5Qq+}M(oy)lwT}ahXgc&bA&M&`ip^`q#?>lmN;H?QXsgaC!9cIi}PAG`p4J?6T z6sii9t8zT@3p=-Mq~}>3NJ)wE*{3tHGioz$;R=o&$YaaTKe7GbexgcYJ24`WgM2va z8!~I0%Bs~rBW@u_4j*9ij-9Ojau%m|I+yGE-9Y(p2s?Iw9h-h8oL+_Ijp|S_T*Rku ze@Nxp%^7juy=2-Rby9_iQ>W6q?=`q7)oI$gJsmopfn^EPUOWYfAIt-m##Ij0>bB(U zE*Vv^%o{=)HtiE+f5SRhl-bP5ICfc5L23C@qWLeFt(%-4vQtaTxRP^Xxx1 znD;+fK!YZY`EvH>SY8237B8VV2G}7sZ2XlYhYnCNDaxw#zmQY2Jy;fX8aJj!W)+e} zxc9NAF+ne$ADyfzEGS{lSBn@jWIQdK)u3~Smc04)CpV-HQ!&Ft+<8`M?4r1)X&3O8$7kK~qr5 zpG&DxA)O>Vl#UUL7L#A-(z<;&&g|S8O)(vNTu4sShRk_kD_M2xVL84NvZb+X@GKJ# zEILNf@ne+BstO?xE!4}-A{H&7$n|iQW6~;(B|gLm5a5BC08WL4!PZN%73EUG#3IGy z9z00Zx=rcOsT(QYQMz_Jhn$wRSiX2Zlb(8u!MFA!9NNvsb*n+ea4oQ`kPiW48E1Df z5tC>WWvVS3&v#PFD3?r3N+@tW3cV1go^~dUa+-4XIp=VFa(V3I$GCUgJ%qCx(5uVo ztXw>gXv{@y8&4_2v+Vax@o_3G6e2E46|rgK&n#KClCPIuLD+$UV@Ijcw3s^vUPOu& zEc-TKn_vq&l}=}N6Cp^ zPRdC+DJSKBL@e?7f-TGXQ_R{95Kb>oqgIXCxb_E{*2|(<^Bfv9YCy&G6jm--!s@NL z%y?@WAHDrD%YXV6k~2VD4(!@R-r)k$DpsLN^{V9V+D@~E^=Y2dl6np5kd&P4D^X$q zMwRUYI2(|JnClX@6v}g1yK*I`wK;_jojcR&)HZ}uQc!jhh@#-oQDT5jgrHCg@Mzq$ z5liRIC2#j0^78U2I3B@OVdGw_z;cYMcgPAEKRrKkvvKp5B!!b$Hh&)ZdHEbU9wFkG zAPOCK3^XEc3^y7jr&%MOefmj~(lc4Jc_*#fwxuY47fl=1qFJj`Xx!oyGLq9twPF+= z%SAgCXx_9T+c*74y?S-X$!SO9MlGnA9;Qc^Gg$xA3U+SU%ArF?DL5{qSE^3z$UgFR z?KRL)AF#c6G*pVN}`@~Px*-%R5M4e8YJOmbSb#!gByk$=IF znOHyyX=xQGIkcT42ljI?_Xw_5*j_Qm4;^4%ZXTa~wS=tf`ebFK(5y*Kii?lYta)=9 zHElsovqnhlIEDFnTy@nooYwJds?=$WrxoEO8_R*;H*IEL?qQ0fF28M9%dR~KaO1%T zg)CaMkUj&4vUt%#<}aAXlI6>&S4r{nPd^fK(jbygQBg55D-{dGU16= zY1;Y>vdX2?qIC}Wc?W1vqY^neEos!aAvLO$|EG<$lk(pwzCBM|#63c8?jDX6l>ku$ z?FU0?6eTDk1RGEj==fqS-Jdk3J9y!d`oqLIBK_}dw zSd7HGgH(UN2BhrM$~?>G$xXsX!N0G}b&cSat>4l+%KQ#cJBgb+5|hh`7veu!blG?RD^~7F z`BTLlM*hj>Y!ynP{~bfAUcqAUzN@M~`B+m{>q4PyRxE6`R7T5KFYz8EaDXOo2T znH4OQc2S`eZW%J1)r-F2hHLxr@RQGynqic{)7p1n<~#3FP#iJCR}u!T61rV+F_{@* zh7P!yf&B;Z)q-Wj>?9xpp5Tg0M7e~NLU|UJm4u^&DmCje>5<8N{??n^c=Z6Dc;-ba zR;v=!2q4CvNK6Fdl5b{l%Z>dRbn_iJ<*HD-X*+J{+n3Ps9o#gaFMa#n%#07dz#~MP zQ=74O&o(~!Vi7}!44`saF}K`&6W8^$THZo2w19=hvx1`HU$(g4puFu$z_88TutRg!Fj=I66r6c-+1 z;>1UIf971`*lo%|>=fcL+1mIBYAZ~a^Df|`E~hZ=?&0*gwjU2Z`8);3g%0h{pkUu- zZo1(*9(eF!tZ*7g7+ZrQ9=5GeRvN83bS6EP%T3o`$HR|2Ml=SEs#WBHQMc1?K!4`` zxQ&|!-$hok!-(PiS^d*uuD{_1ZW?$Si?P+(?b=YE-LU zl|ENr&i!M@aocSp*!0_Wrat*NU(K0stfPPw6|iXO3Oe>UkJ|O?QNMm8nlx(2WnEe_ zfBt+@%2lIEMVpzQ%_3%{#jz_ZR;oa^?w$DP>!ox*{~}Usp+ooXB;9Q)+guTe`Qheh0_1Wi*jiDYOe3wmjz4Ka^%2n#*Q7!;uY%vk8QuLXY8mE^zT1_ zX|KOcEK>jgeK&~?C%VkzPgD&5mfDwiRTB1(8l-?XUY^R$L;pfS z%=1w{eLTlM&?MtX1W0Kf{>E#Av}MxA3!shClb{hP(MaSFcMiFUN1mQWH0C9!Fr^A= z@T@=3Pye7U{^zB%di*%^pkhxjqKNohC!+i$o?@ud8N^3P?c`(x3%L_{Ao zytFzhI$*K%qK4;IL_E)M;6?+^T#1PmEiq5T^E?rWio^{2VJzStjYdR!p3i41KL2Y( z3=?ny$D`|s_6(D!7FS#m|2;APJ$^bdtdhZx77@=Y7SAp5%aKr~_If^}>)i>Zg4tRTg?qCTxW?fST zE#i415my^_Tkm+BXV=q)e>Ubu%5tpgfT7mUh9q#cicjO~2E4U~J6H$z>6nNY^>gT% zHui$zmL%4W&$X)!U#;kPIxQleE)wm3F!#nxy@?l)>&A1WwU(&3eyas}F&wy_c;b0l zN<5L6r+pr1H{PZtA`;VHyl1$<{hlkLwcjM3h%ONA78wpBM zB=7|Xr8j)TV)Ezb`=tEyMQbgQNJQ4IUHgZ;!GDW8I6freKT+AX;%%u=zMQ=L(Gpp; z=u62eUruhj`vEy};8(fi+|J^J(xhhH1~O*s82Ns|JgHitf|Re6B~4H7EQ{A|Fx=OY z(C6aMj+LEMf|)0Q-d6k9gE^^eA!DMWyX3B02TJ7zo#a4N`}3MVFK9RZ41WaqPt&EN z{)F--ruEs^{W<2ue0gRT*QJ+5N5nh2QQ9=9A{Y0)Q}Rnn=XzJ%_!tP@5ohq#!Ql7* z>ckoNUqcLc@FV_Q6_t{syJg6LYo&bE8gl8iH_O(&2Mss3Ut`)UmY=?#EuGr8kt(&D z$YU?QD2apG80w(^e;ZG&B98!v27VS-aVI}wc8vQR4QAJrJtFG~gdqXxh3 z#~&8+l;bm-_>@OJHkv`qH``{VOpOJQR3W8| z9n^CCpcBK(D{{h$1v3+Zne7Bh5n8)xDBgn4bm})hu$L(3ZH#SHSdv|PQ-gnD6UaYBD zttK7LI+Hq;QrNR?3qLGh%c1oIj!2zx@{|xEaRGEhLu85%)Z^*m^EuLE!%bAw9{L0 zV9U>ZxnMaxF1(CAzpfy!#NxE}XE6V>52@es49+;MCA)rI$DBp0=+yaiV#oHeX2Uk3 zo=vrywK=ED*;KF{l&wKr!V+QK%9SkpX$x1}a3#kNY-i!zZ)wz~BkkMf5IcH+Zx$?N zU+!UQ)NMffGdoc!HQDDB`qz@u!{8{|i!ky2M~O(7ufCYcM{mEuOD|1f^n`mTXIns& zV@D41_)}9Ec^2ctjh4gchI48FYdW_0{4s?!wcE98Q%Y5Hf`C# z7&^K4qbgHzAHm?#j7TI|_(hza*SKw9}UMvi-$ zXPq|*?>AeQli z3pv+)@l!UxD+n%>roMM9eb7yBqkZSaBS*z|YUrae#YAe0ngT z%O?QI`PyIEV-0gxBEW2^l4_c+Or8-#E)OWn0Ck(VB*$+T53CSnE7Cu9v4X=B^PS_f z8I+PCmBQx+u(t+*-v{0G3t$C}abmZRABzc|?Vt#Fi~}%UlS~JP#@h0Ea!r{N59kB~ zsvQTqRl(J=D)dSD*A#^Zx`g*%d!DiPJi(!uCP_*tcGI!MrRc~ZzMVUdCY>&$=^5$7 zw8!r|e&^|@o+SCMn<*|Sq%h_(?TuHdR;LAR&*(_qisk**H%E0sA-gyI#Q1y0QsO!s zca!LU``tV<{yG+X@gbweK1NB{p(Luvs#ceeW`9afHJbrfUBvgR_L5ntJlhT&<$^2v z(Qe9c)8j3LgUhD1%ebxIZTzxpKc1aVa&iVwO?#OudKh*gk$@hs1S@u!`$mtZ`_(t| zOzVlv`FIB7pZ<`}7hcCh6DF``e-WR~`jlzUJ%iL<#_W$@;^Vho;Qp8A^UixyS^UWh zy!+WAiXt{%EX24cp61T0+Z+FEOHewWC0~EZn8_c~x%b8F-mr=X?jFh2V<(f-uqwl@ zxs0uYw*@P?~!)xWgN^a;pw5nsG8|A^42SPdgfvV z^}UMQhK)yA77{r?gSu7l@Ng8=tXY>k$3DoSSs%0MSP3@ZgfqDIhC$fG5U-F%wXz}R z;)+B0?0VR40o#9F&xc=r%S*3LB`Yb6Bbd$UN%^;yQcIw}rpliL8B<0H^k0{Vv1J9$ zIASba@s(Jc!6zzE_QbdFX+zH=%3Py#F&4LwqsK}}E?0pRr<66(Li-AiBF^860?VRm zt)^71B^WZKQma?Y|39!yNuX4fnWFx>{(^S~lzD*#tZMa!RIP6L7OzspMw1vd>|6Tc zYzG0mWKhaL*$FsWRhcZ9kG_A(AK0D*i5uC1at11t^6SZbHp-R~0`d>@8P9*a?LR#s z5g8Ytc5`Lg&1{@+*Jih_#c)Ts*`7f;%6~EtC zP?gWko1luC8uhSIWhnndJn|3k#VJ=ACn<#_5}7j;#?PjNXe>%Wfk(v(m9SL6_FRhB zAGBH^aRnXizdb0|KWogD_NkNdUl55>cw`T+O#28st0s$Pe?fBYS~{I~z0blEFw<&8 zX~asS_l>tO?eUS=dOy!jdYVer8nS5R_teZRM<^H?!JMbTQmHgO?X3UD-h0PMQS9sg z@9LhJoz0PjU0}&M=b$7pfLRnXqQ{6?FrgyhfPfN21Qak3R4`yXMnF+O(vs7XVOhfF zyc4>+et%T=%-}iq`@6|-@8$D)@nUzjr@O1Vy6UOt6CPHq_?)7%r}+Ey1+4#h1Ex8Y zni`XUmdwiRHSAvVHII*Yif_ML#jzAWKmNFfd&bXT!V@odB-Bi$83la$ z$w%zmcYrDL7LlG7%dNwP^X1n+GPwT*#Jeq|Ed&QKq}OlFmHpbWb^9+Al$P@Ss`Yf} z+KXD5aXj|)^PDR4(Vzic;t@D z@y11m-uS=7NS1&USQ_-{FSnt(xQC4acSs!6q;^O zt5!1KtvN(-c@5sUR1#yoXq3>PK^D~&+0^&~h*&oPUnSpsvYL~HJ|4WV695URwMa~c z=x7&ISePNtjl?o4`QfWiIgww;b1%QDHu0tb!5ZFO_y*lC>QBq|&6OIK3^(Vz{ol0+ z#VYZK1cf@xktQQ_Q7wrj!g)?oI2lZKCY=b&B876wB$!q>>nfCCYg2uppj`}nRe4OA z@)Eg)#UUspun77~S@_mceqO&LbbnHs_L`|7afL`d=Q?3168=p@fRGT1Iyd55waa!f z8a0(1J9-4a)G#$SWyQtJnf@{dbI%ZT&TN?>U06#hu&Llnn7Nb@eIbwpYKl0Pdy;@a z$?b((g=LwFIkjw~m@YhTR4=R>e7y?iP_j z?E(wz!0Zr*;8g8(zH1+^p`WYyEFn-?!R(hNvh%NNK55{YF0JJ za&|It+I-4u0-?t(Y=&B5f?3L`+~ZXGf;L;J$_hE)(2{n>UgS_gjpu*seUzpFG6<$} zLmQ}n(iwNAs&^U00#p#WCC|y?%HDMO0Ruz05xN30q4&m_u7r-PENAqik8=I(_woL+k0?BK9McHcRT~6`)X_Z& z)T>>G1h>7)0r=@LpVK z#Ky&8`KwjnjwJ|G`ib$z<8^BUeHHkOAW~{nSJmKld2zd37{MAAzq^>_->qT7w5c?$ zSI73+D36V1xkA&tL?VM_e7)jhKKNoS)22SNk3k*}~{-PKsfq{jFX)lbH1(s!mSQAUrKv-xPxP)Qr zWD10)hpX_5$o15~G)g&oB!?O!h#AHSSf-zyyY_RopvnezCPG-4(o!Wtu;bvQfn}G0 z_*bQ*g+ohP0i>y3E-4&$kJ7r8Hb^uj{JQ3QMm{!z5?>7lVETRR&fZLEO;9Z-(n4su znkYeO>;fVrl`c_HleUn$J(*^&{hkREC*cFE2tT#JLerwuuHTLU6e8?eR{L=mM#NOB zu4kbMOKGRtESDnJOvQpqh0!(PLc@hFOe`Z9a@`BfWH?G&oo46$;~1s_Zz?`fgjigJsRon{nx#{M!v?;gYnkd8CG%!$j|$M7 zR5^QBVwozwGyl|SDt#7M0djV4CaLnjN=_0MiDs)unkn z|I{ds`myW(0l zZQg?=L7I|T6DBZw&a3#OK}~f9_doCe!~QmcvYG&4H{^NycbU+MO-!S9dLn0Y_jCB* zek_+4LnxJVAuNPu$LC66#|k)ak>kYFk(L7p&N(>%mHec1Bme*)07*naR0Vl_`}w!@ z>N|kh^XD<}qP_?#2&NyUer+O69bM>(u?8|T>S9?YJ2!8ktgxKYYD=+gdK5yJ_$rI3 z@N3l0Y($hMxPIt$toZa3KKS4x9=LlLUXPB@)CM*reQ0Sk>(PT&jWQVf^hl(;Ha&aw zz$*lM?+BB z8`mHerTG|!m)PWVFpAi}dnbnGAs{rQ?xAk|`Us$N*Ul_?|9#&7@MFe}e~OrBFHQ#W zUj_&YHLnS&0bY`7WzxJ}G6#2MBTdPf6U8JYClIgeVCe`FsoSVIzLH~(>29yIzB+S38NSsv@$pbLic(CA)U- z=HQ89e3nk19-XP57Dx7$o#f`_laN-6wq3iBnh=XSg3)qZa>CS*zG^o7vYs5bpkDn3 zbnDs$w>Oa+hF(pb%q$Gc&yHW$aXdE(tQHhE4@7o8L z*Q4B?(wW#T5JAdHirA99n}YIc8Z>Q2=Qb^f5*hB+^I8OPkMs*(SV~z_OoO60W^0E?K*d%enxE-xhL)N z5W)yQDGA4NcJk?`g5+o~oxAm*c8Z&ZEn9L$Oar_wjr=nw*zoHX0@9*!vzD}J(;Bzt zx^(Z}4PA3#+6%hN6U7zRTu*Ff3tT{DSuwwE*hFR7X-dm|SXK~CS`?f)%7#tZ z)c7nKG;c+Rwk;7@_$tfz>K{L_H>(yG^z2B3+DUBRx`jhWbMYpo(6wtzmK=3&BSuWG3}Mf#6`Ou$N2B}g8wfwi3e{&CeMz2jM2|d;@SZ{ z@M=0{bZw%eV?Yb2olq!S2{akF{j4nEs^wP6iH{Snv zC0F14DD$Vjz}BDFGIjLBjDPxJw5SB$T)dR)F7Fo#-Ox~*Mya`oP0L{L<%3x}c@CZW z4xwesX1I)MK798rwww|Sx#K>vYB%B0d#>lHNpEu5(A#NTFNwtJrgZ7lj<;q`X2s$K zlmwzkN=inLj_0~-1~cpJuXtrn4~AaRp9?y-;Et;=#^s5@rN@w*lt#Y+JsCdi5|(}O z9xax=jS-c^qhqG<{3ExhWWB#!3YCQ}Es$s)9Q0Nkih6WZ=$w0z#YSH;>Bl2(X?qBvN!Ky@@uaV zMLAO@jlqa-!J@Yop$VOq?Yc2!@CEkPLdA+(mVquMW=#=qFaCr&S?&1li%(gpxk#&1 zmm7v&O_H~YL&px0)uuDL+lje9KL?yQWiFLK5iS%hv_F6iG^^Q}{WE`ibTWPVUO;Mc zG&APB&73Ju@cPRWxcq)M4-LPZ1ABMy#{7@y*5)auOqf7yvpzI!(15D)vn=`iZQlCu z7cL#ppY7Y;qkfxSjCHnSFd#K-T?W%ZYfnYCyYS6p#5THY!8_UeHa<-rb8vFkqh z@s*$D!3SR?sa7pAGSis<#zH2KABju&89iYhgD<-bkE@WX&K<$hFfB=$FGx(Bi<;tM zUK;ZZQz{Yit7kKoEnmjPmt4(=d#_{JM<227 zm%a49s55CvUiRc1X7lcobZ*lMZ?p~~2u3k4j(LGnGoE(M68ZMW9o#ki3A~lNShMF8 z(`HVk{M137d}a)9FId3ZPu^tZ{sMaRy^Okbia2|yiczCR)4WSB0;MNexOf@!7A__; zUf3*V*g21MA#t(x*KDFZ9**qT!17O5@#@P@uzUM9=6m6$B*EzILpGf z-(~D8vuKf2!}tjkXx9BIQe&fO)}j>ZBqN=SXbDIQv-l{JCyZtKqK{~vX7ScrZ_}vL zCDf~v!0{7#R95>~zH}ichd;tKmkm&NCP5f}-k$vmZ7+YE`n3{xapWT$C<@TOdkeN_ zZ^m*pM+m4YFXP0CBLqr|Sorp0o}V(4t_@unQllc^p`t2?2$Zt&^RJow))!pZt2+mC z4zlLQwM-iO5L-5`XXf<9Tztg<-1s?h^e8jm{)pvE-yuFa4Wy*z>{(u)J)g&>zr!_` z55OxVy}NcKGtR@J_urxSzzeaYiNCarQ6rxw)|<==<6k5#AxgP0LxH!y|7-rg!laHM zivE}0#Ioj{IgxjoU{J#omqd$}t%%nvShDN`>NROiodk`Aix!fYUQfvhYN=d%+g-Hn zcRjV@Txd>xH!Ui}z?f(dTZg~Td!Ji!4pLQB11=9~buw|eQn>Pl;WX=XDUH$-$%?&@ zrJsFDoklH4OpN3C2@|-d+D%E`5pKPABuS}hSXvB&hTO*It$X6vqv_PHC36=o;?VJv zRQm!%MMu-TWmDW{5QGbaV%IeQ%S32VB-E~taK|$2_UlNEbE8YiOS9)w9&}MVUPoxL z414%VTJ*V+`Yk%(Mo_m&J7&GRh{MND6EF-kcN7^78WR(pz!NV_<&q%}Qah_D^)l0# zzj!G}bMr7PL3C^aSxuW0ml(}UbCz)HzQdH3RU_P9vYIx>E1VQ6XG{NAFo_gWc^srt zFzPjM5UKT=lUGpA&36o=Ws4?6Y4FU8FOrs-Npw^k4?O-9yZ7f%6%aIT(www-H=48< z{?Oxe8gQ8M3O`Rg@)!-9G(a;ddGf`VDfhWTYE`u|)6}wKQ_8)sx|X(q0129g?v7=| zlTTAnScW;n4+<$dy+Q!4fflZnvGczoe<`V9QcL?RFf}?*#;vI}k*miY0Hn z&IOlT$N0ZLg61#gyOrCJZWp)Sehc5M-^M*d2eNC+X0n>J#O>D5gwA!h3}ImBw$$Y9 zP_=!SwKMB8dh}zo$xNeNv(Fek<^`^} zt|wA+qvJwHaM=}CQdM0@w+p*7@TO-umV1gL2XjbCOXlVquOTBf375+$SE5=ZgaGO1 z*I&M8{pKC4_~J8C6C@Qy<^1}~8fs;v5FMAykQ;_juTDCeOXs+BQKxQQZn^yyYRAM- zoqH6Q6~vSRzu&~|ishk)A11c?EPeY7^+>AT^Hi#t4g5v!wdw(g0H53rSXx*Tz0eyG}iMa?JC%YEE+JJ!4tE^b4LCakV`lRB0K- zq-aR#;=bz%PVRw^z@=~fKG;Pq31>(}3o)|K?Ruoj_6SrJeDMlGq| zNHK#I1*aMH(1WbovJXS(n3{6T54(E=&p$ho9=*~duBraj&1z0&R&({pyczVlC<7rS zd55>tyVn2=cOt>+N<>U5125`|%jLoomqMqmDWOepTHQvZ)op|n76Lz|g?ZdO|H-J?y{P+qJEQBPFZ<7?MtA?)}m9lG#gk+i#XNZd4P*yQ}Xf8PG3xl|aH2xSGEmi%3b zcPStk@R6Ti%thC9Q;80iv==ltSKn|eAAdKF!s91cw{{c#Z+Q^itzlZ>u&9JEt zt5pkKSOfwlei_B^`yQoY);ykn;t{f%wc-9p9;9wsvg$b1B9JDz$Bt0#FJ;dBdBnI3 zG@@wSwj2HXbSFQzgt1ROK}O@&j2Ll0x^Q8cCQ@L_+c{Z!w$n)H2qAFCx=D(Up{lA1 zEQ8d9Sk440kiLBW{`?D^tA3RFG z0sZiL)E_O=i7(aJd+aow`n5sRbiCeZvNAI`v}Y%lbrqVX*uU_^WTGL_g-fXqyQ8U> z7EMj*8T8m_gtXAjN@h--#Lj~iG)j+R+nz&o9wbT0YROGE4B_?h6Y!>HaOeH^(xFW= zJVJrLP`s8qo(nJR&(^h@sc+UJE+LM(sd23NdIfL4_X#QW8gMFSE7a{~7k{xA9;qog zJk8*AQ3-J=8Kfn}0EjBWfZ!+yg2%Kri^=@Mww~2&=8sv5qsVp^zSh#)MOGWV--$!gQpb`DFV23@*#3W2`xnlD3H<>I%iw}6Dy+Dx1}mAtc+ z=-yb`bnHx@3ogJd!(buw4T)U`Mt$muj^eT_uAoiFo=8oz=N?Ie1{rj0+YxVaI#=Fs zBe5=ffk4=RR|~gIS_mOS`R(DmRsbcmZ^4eyjhK&Bms+6~EBI^&isO9joYfJmG*Fcq z{wm{EAcegs*=-NE$gzk_FPzE&8je$6IO9j!ail^qjD#XT?HF{2a3CTvP>2u+6{tG9 zp>C5A$PsLh%lYWP^Y*XJWm&3Tn#2C-`tQ3{FtPANd5BAhX2-7WTz5@xJi>)3bb=y= zzTw7;ukvG2$UQtGxOEiML^6~rSfw*C4mL6OAd8ME*eo#fM1cOxu~TD9u);)Itd z&O6KvLvN*4(^lL+YzQtQ7gL?u^%{UXijhx0L!;WN4wzd5U6?%j^plhp9W-OYpJY2Oan^>R4EF>#O?B+3608vv+Uk`fGKY-B{RX` z$fM&iEdyN_RF{|8g^e{5(~`mPQ=DIb-XN1xMTPji@uVds5@mxf%aRCuV1cDYhq4wW z2KBO1C@w3Zrn&~aDu~=bBO$piS6zGo^Ja`Cvsn{{+<7VtH_Yjt4 z;`94Bdg>%y`d$l~9YGa2)O3lQWBpR}hm@8_QRYTet|6mGZ?GUo+{A zkGY_21~p@+BQ?;X;<#z}eOz((&siczR#ZgGrO7bM{m- zI`-^GdW@Sn|M-%N23^L`+wNlJ@;CWp!$}ZoadPQVwhKlDVrQnMP*HT2yt5_5){n)d zxxmy2mX`3vC!h1;8y_>Edjlqne+`ML-Yd(*2$<-aBq1rDCJogwvXap^ZOZd@*jzP3a+p&jR?Z%C1+PEI8zyFo?t(z0Cn-HjC;_DyNxOEpY zlM>J^Nu$=Cc;TUknLBAb&prJdZ@e>~6t`M1Ecu(hKX3nJj#orlc4Cxc_WJ77gOs=; zmRHS*J%G?MuYT2pPIP=4!|r_;gbT;X>7+bFf`{KaKL5EeiXc9@4#Vz#7*!}fJQGD8 z83KYfFc5Zu{+QU>{O!JnLU-+yOtPzX+Qp0PVp8FW^xTsR)!uL!rid1wlU;VMJ2(8@ zf7M#&GY3#QW#yfg{Z$67N_11g0O9)z{Upvk_P3^mi;>yK|MT;8KKp-4gwHvcZa6@5H z5gGNVflznNF~Y} z%{y-|rb(KM{QP{}!X&j`Lwu!YnehBHn$=5Y_)Qma>#*UxIc)}ey0>BNhArH9*F7Z1 zrlL!UGz~Oe?G)dbHH!^<^O-$!D)F{EwQbLC#4T9L-^YxhUHw>oTECtKod*$=f~zm@ z!|O99QxcWNb4?l}WDrxj&_fHG$xXN3$fM6pV9KPI2$bd#L~`40*AXtAtX5N%!KUGj zP2ig^mT~&nPB#9$iq;)^(7JsWcC1|mK|fKkiL_|hiY1E{ajb1!4jwv8`-=o;@(X!? z(L&Yyl$%kHPG<77nLPaL6pkO=O5^%z?A)@6vt=$` z8}kq`9u28!7{Y_s8_(m9Kg6R?OyH@$iWMt}a;rGwaOrVH zyExhD;vAq8W`-ParP(ZvWtXl}bBE3I$^YQo`>zsY|BX{fp*BGZi`lhB1z5rgl`B%| z!FCP5|4@mrF!Lwu^C-emxo(}mMkoRN$IdMYW%-A)g5|%#Wc>-aMF@dmn0)!=SE}5K zW4~7d^Y7e7%Ti_8s;a8U%*_0KFLvJkQYK8(lz-$7z(RuMLs&KJ+OvnlhY#T=iiy)d zV$qw^=+Y*glSg-O-Cbju@akJ!+$jsUSOR;g%*=po;8m*&IDtKtfU~ z-MaT6B|gTUkW>Knum}k6=i4GxN$25DWAzBL@$#W6vQ1L6fNXWG?8_mz1agdw1<& z-=RF>Qc~&LyF0@4u`PQGr%o4=R<8k_x^^WYO0sMB0ixXTv~1ZBA*(oeAcy>NLHADW zak~I1k!BgE&lIqI#~vyx%XsI*)!cITC~h0v9?d9V%&0L`*Xqc)(GL{w> zos@Wu{Jaw!$g8Ah=hhURInI{tyQ!}7;fYJ8TlbzMcwybzpDC>j5SyGz_pV(@OG-e= z!P#{jh0Rk~K6dZe%Aw)_{rmSPK{u%>JHw_edpLEv2ycv=dd*wWsZC1?au2X^`w{wG zcmap@ZYH)~OPVyOi>NMP^XBd3=NBVfF6y;tMW>bxDLIqN=B<0EuB^r#mq@#=J!z7W z$l22;*tl^kHI|1S-8)b}BZ(c`c5?K{Nn#Vy=+dnRwNj!vk(bBW{0cgEYKJcToXkDO z?t`bfuvahQydFT+UIc@aCl0b}Zw?jJK@yYG=-9a%DM<;qrAf}N?U+$9G;G<57);LQ z9cR;~ZS=b6Qc@G+|4%xFq?81ML2`0(s9(SSzdUBwu3hx$(+7Zpf&!K=UrygXeQnhu z2q_TR^3<($H?TaE;w9TP1S2z1Im{ay@L7<$=7^h2zl?c&B^{*?Ps z;lF<`f(fT-s0?SjP&S}R-3GR{yVU6k@$YS?#HpucIRG;>SN!Ym{~7F6QBe`=*RSWQ ztF8)t_Iuaa{XN@hSt{0Q+xBg=ZQGVEUAp{k*E(;1zB%E4zyA6wLjDmIq9e@2LbrVE z*|L^>M^2HDlER8FzhmF=088ioo$6CNSn>5L4pq3BI(-sJfD0274MRCJ(4{jGn^;1} zLPNvC3RV*E`vDJVZY9bj1o2)kLP#{UaCC$X3{0C&*PP9qP!eYbswAgwmwqtpHHlT&#X`~}TheVTpYJ3$~rj8U*I4%>@ z<0i`O#v^4&E=fIKQ?VhoETI+ho|tOH*$bre3_}8dcIbh6hNj)?s^((YMQ3M0OBFU? z35jy5+hYVm&)}S>AF1MvY%LQUl@&{Zrb&ZzyxSGiEX{PIgOGc(VF!2jhI2?AZ`Od5ZHWSow2S6S{@cI`Prb zS(4*pLV>%QjJzLtPVkJHAT8W>9E#;EveHCguq}H#AAI;J0aKwHX<4MD*X54;?jgEP zIxagqEW9i`Kr7N^6jtjCyG30QP89op`&nrAoeEV(+m4mdal+E|2xt;+7ldTyRK@Fv z$yo~lHFY)3zB5N*!|o3~mNUiGtl#<_@iFntm^zWH+6jE}{dNujIm492oI6Y5J2kaRj)qDf%~*Xxm2vxDKo4ywqtPDs0u zcZ7UQ_|6?kKxaI=)K7v?pQ)HFLXwB7-7e*N3=dGnN=bnfo=~r-J`bwjg$vMBDH!22 zN?la}!t;LM|B6X_1FE}Rq4)H!X3yDa5dZ)n07*naR6>Zq=$)On^LF0;Y9^#5Whl$& zkI)R35>>oIq9OzVX<`aZ#l8s*goYKtR)pLsA{>0|xLg#DP^^i{bk#yju(VXU8wZS7 zG92t2x%jHs7z2shhHegkQ^zS*O^I%4O86&&)sqOzc3o(W`vuj8&>1Yd4FV~`GIL6Q z*9yUfNH>eqQU%c>r*!F*oed>mgzv;*-kj%X+H9ob4$>mdBG0*=4E1QhzM>o5QW?jl z6u6we&_ert=R_(yRyg#TiPI{}zAs_-qO>_J&6Eh;0Y;{+5#vIoV*ECy$~lt)Md6;X z`%Mbl6%}rE=-CSsq+)9=O)+|!4e}kARU{!JL%V}8PvVRRVW$>3M)43e)~a)Mf#_^aR93`hMn^Zzx{meXh<1mWyA4b7NPjB&^r+E zAVVhpjZY#!JNMh?ej{=o`D@UQ|0O2SQJ}$g$NMY!Y25}IG;2fStlC)iSO{ys=nmvo zn^b9n&@l-oT!_elhxn)8|KE-Iw+^v@06VtrVf&sV+;;m=TVM=A51hzh7Re#26Gy&B z&ZWY~igW)E+DL{y8|N^eBJvE5DHR{fRym4n?QauHoXxZPTjYI3-shh)z9N}GM}0`W zpAtv56rB5aG|Tmf^-6hO!0Cg(#(Q#}3H-ldkxZb5_+!AIV?qct%g3khzs2O&-o+1~ z>58n z`o#u54!n$<6cyxi08IENf#Yx!LMZt$3xsJ>Q&omPXxP)2&1%`T@B}jCArY9iyU;mO zAVd1L=VlCs=4(`(jAm=!iqHfju%yX9zWJ7Ua~IghDwnGaT}1&>^*zVQC_rimDeSXU zv2*8ECQg};)KsY&mxDWm<05xJyqz4UDF#g10MOyebTo9kuQW8fzbw#oOdK5q4IMq~ zHjMzQs{J}hi!&$oF#5%*oUL*kZ(0c92pcX68KD`i2`nMVJGh^RAH0XW@-pS^btt?@ zAD#WkRjCEl|B*2CUje0X4y8TaYX-_it;Wo;W5<~_b56tsbg;Kukvi0oFwZ_w#PcHJ zpVLa5eFYc>)isqiEOjX@Q_BXRk*5^cAYE5LFk*XhE~q^V*s74poZ_mh|uPgbk0tlpYqzdaTflAxvD87VC#PickUEx^{{ zj<_HD*;uxopbF>*Q%a-^B8@zjESSx66J}HDmr6>|R_Bp6NRbjulZa>HY|JxA2s4;Xfp z1V;@;+Iv0$=ZqaoVr!o}Z)fBi@&}u6<_4wzjkNGpR&wNE4m-AQW8eP$yDQBc{^`^u!RX72Tc9m15tvs{N(J(CgNHINF@jVR%B9ieOS?#DX0%C(cYUh*CIl zG7flC;6g}Yw>!v|&70W1b5}T#PCDRI3%A3GRdnv%t~G}Z&B{v3ICAJz#8hjAlWb+E zH4(S!01F4G*w8NoWCcPx*H_cMCLKrRZwkT6NWdfP$uUS#!D;^S-H%k6oNM;j31Pbk zCQ$&TMFnJU-a^2z&Vg{Dz^HIo;kk=#=*dTHGD3`v%U8^0EZ?s3z$OM5CIUX@~0&g=O*nw z$1>3D{I`e&^j3SCr$IDy~+OKCn!r35HbqC^@^gaMx|a`1G?c2%=^j zm&>rPqk&n2&`eD18AbX*D$REjwXy&6v67wGV@dlxF)%9fnK z7ZBTIpsfMxJP$C?Z5NLA8yGAiSZS5eV@j|zkG;z`K?XykD+~-#RZC{W9uzYI7N&_JS_S16uCm0&f0H&>fD+pj| zTExam0@ci)JA;wWJVWg|=`?HHm^bIl<(8Z8ps2V4Gib8%+kbH8)DeP#DyB|(iJYUk zbnMBcGB5)1~B zMh#zo^darrwkNA`OU6&0K|m5JO{caA0x(&>`WrIS(wI1T1_9IJ`_GnAKeH~Y*KOtL zM<3*>AvaQKn5_PCIUU-zCZ$e8ZW?wEGEjpI2B@s4q)pQ%T+r`g0z&faBlpuVJ(aAi zEXGfqK}|qlSSF@rF>TUIWTrG@`HC;uy7n9D*UjSduYcjh(S3C3+>>jD-i6Os&WFpE z(4k#xGU{b<-HmrqToDZ4y#0j!jFBaRH!jCqj5R42G8Tb^Y$m0%PEQqe+&?`G!3D< z05=|wD(SL)^D3rJf0MGRYD~?;j5+gZRZDW?)mM=()6wyhoY9D9$N!zqO;g#wZ6mX0 z&L+RSoC+(E`yYOiA(!^R1NJr|$^3>n1z$IbQnCEz7c4Njo{Rp``eqd*@i)Wr6N$~VOdS7-g zOP4I7adH(`-*6XE37I4$CGy&9W7)Pbn`KLuQ{(qx#bq#V;zT+$u8Ui9*h)=dIjT9G zcbEy|UgcQs8MJ6Gqn>{b%Q9KF@@uXcd=*6%HC!`vDEB>Z7tv-RGpD`EhV91))YQ*%;V3JoxP9f)KnfG{X7HvbVmZZ%A!CBKiR84X4JS@=<%7DRfY7t zKbU@ZwSvkb`w8+`2jD#yNdT0FQ8$1A^;v;11pFS5}j%$j(wgD+54&R zNrn!;i#u)`%DUxmF>UVK$hc%QS;N)0JjlIw4kcKT&%8NvS@-KkYJwKYjXN=E{Ae1a zC5Oi|D#KVBC2U-?hL>M|o2ozsRRIr%6_05eoIbXn=~E_iqNswRDvc|yx`7ApznLZT zUghlt^GV96hb7%yeC0LVea~GaYn8k+=S{x(aWhqc8ZN%>RshgIFTWmr@J@dIbO~c; zyoDCukc;~Fr+<@JvNvXP`;9k}n$eUO@4JV)ZyCaSzx+(Y^e9%mF_*7)SMcWaQGE8+ z9A>}&Bc6m*uD^C5*I(L$sncF3@8nsk{LpLgtvr7BASOKhAjRHRy!!HZ5?p{KIk9Ui zOP8(Sm3NkNQP=i(2y*k#tGQ$7oviriWA41~PJ%`a)rGlCp8Nx6eM!uk@gk{S7rOkH z6!-ra6C#KiEath9BU$|3w_G^*Dzu6`wjJGpumZR=K`>xoSvueW;h|B-4qVZ%J>7bA zVbg|eJaIAHaL3KmuUC&c$;lCsxdPperA*@bKe&@!e{g5A97segRLE-QanN5}dX^6uLU={xvF zF28I5KYYKAF^@e?|IMqZ6(5amzf77g!1VFuCm-<5ue(^hPeclY{|6gQ+VgS75weSL6nyJnX_;a(NP-9-hGGX$4=(MC38uwQ;%0?&j8C} z+MGpv`{PGAaL-ksFIS>|biCteuKMg99wOBbBk`Yl50b}XCUcHNp( z*Oah7x0Elx`Iu&P<1nfY^Zv5MJU(_RjWaTsGGhU+yfT}Gb0?#TNLRN+8r965_A)h| zbY6RR5(yp`(XnoR`O2bWx8BTnZ5H{5cX9v7(Oh!*r5xYz9mftGVdkuv1S*Spe9WsH zJzdS=AHE^?R3Y;gyh}n<6bbQuHm==_=__IU#5ojJ`Wg4))0CGSW9fSzaL>pwv~J#j zsWTTaeezTm%zloY`;K$RJ&$npkW28!#)b+thf0x{22~ZMG;Q6Hv6Els^!^Rpa{mN| z-f%VE>H~~=VJ7b^`G9sUGWq6{Wh{7O1`TJ<;ar@Xy!}ZA59q-KeFrhKd2iAZW9`Mw#Brbt0L$Xx#~oujz!%8U4Q-FgXOMYCnf!gT}Xw#;d9m=i|pPa{6_}7DMj=moa7Pqj=<5Hm%!0bV4cjLL7cmK`+;aV; z%>Q&9xp}8pxpFIg`wk>F&c*oYv+!9iQsdmDCMIAUIgJtUG5FfQfv_-z8&7NsV<%1~ zBhih=ETOWhl6^-{Q&dup-&e`ry+=v!+!zDFl~-KNGov3Qksv!(XCnldb|$~HG)yfD zSA0CRQe!BoC_~p=48MDX3ayP;rGA^p@&^qHgtXA4@`BX(tI02|Avrl6w;iV~1h~B} zV!a*$Rn=HR<8*#L)#c?}*tajH=CT=K^~}N{8j^q3emQUF?e{a6qqF;mxPl$CUB6OD zOv_^Jk82n=?F}kVAET_agr>c(MxqlmB{7Lfq}NWQbGv5jIi8PEUBtG{TUq?YZk~Vc zMZCcvE>ASR>ME@GX!MZ#NgyqQeYhvG;T8Ey5G;XVk6UPtp{hF<8%D#^% zR}BHvN3W}gfzYwEXi{p`CM{NS+x3H4`0-c@3W_K!JH#_Dyu_I!`>2v`1`ZpAv;WPBJm{7mr@~>lchv%I1cL;$c#_gGsg))B|4!tDJjVa(}%Eij6-eJ-AD^u(Fw$* zB+|NdW0K-yID0aenv>f|sMDNwJ-SlM<7d#oj(ocE9~9R3IFwh$qrLi&k`hbp)L7iQ z#Ps{vyCa8BzuCn1KW)cjR3TjH6qlBe)}uYOGMyMx+llG~3nK7U`*NlCPA*$7{ikFs(<`*votd3z3h2VRR#71H!lGkBm11doUp1SmRr zjI#wLbnM-a=2QnIpyT!?lb9SwyrJC1rf}npi6P$W#)pA4 zgM_Nk2|>^>KuQc;xDr!HNsdP^FXX`P{d~0PG++GVCp=~)o`i;!mRHifQ@4=zwnA|h zX24QOK0+gC+VN-@xV!=(OvNKm zFrk4NRIzxW_DHOd?yH7B7~brTX>3{&w$OcfWhD zkFUX*?g}TL=RD!_2_a^{3)hH0S8#!*Bd3pX$Bow!tk9B2AHJ7q@6F>>SiAI*V&G_l zC;^g^0;HOXNVu4YVPhx=CMToqFiLC>NZbvOP)-Ex2>FE(PzD{&y^x9(O3|f959+qK zkYLbFxDsW6a&wzS1-SW^UcCJ7Ox}3qRdyUI=B|r66GBKTU6!aeD3zAX#Fw9E+{7uo z`@#DxS+tA|U%o@s455?|jz&=u<(rkCFl^X(ZtK^Nh7Id7;+dh~7=C^{C6TZ@Mn$8n zAO;SRNFkz9Kv{^g$gWhK&p!Kv=Z22v{b{f8&fI0JUb%#()yu@%J#IPsR}QYk2wRKv zv`iY;%3|-%t=MuAmNHNh<ql~GI{hEK6T|XJ zC?i0*tO~sJ%=2_^Uk_7jw1QG)Gf^TQO1+ID09uogk;(Uacj4~!CK0W` zvPe!#p?>qGygKm(s#GoumV*kVl7IXtN;`pC&x zo%h)rRv;Ei8SywWLlX#q6OF{YV1bZH-sw{qC~OrZYPfI_0W*k!30kAXz*GTh)@{o3 zZ!M;JsvCcoloTQ(7>E7v0VskgDWqj2apdSel$_&2;HUtO3V8538iFP&5I`w|vK6!F z*{d6mjhsMgD1cy+nU=w(50f}`;v}x;&%jhcw3Wg+9nYgqt!yTY8ph}e<1tgxsZqB+ z!(W|8-SQ^Nv9S!BP|!vkg<%BT+-EC*pyOG%Xpkb59l`LT`2rZ2MgSZkH7%8*!jnWJ zVN?)ua*MEn$s}1ODM5qW(rhZsv$j{*>H8q3gt=jYE`?JZg zN)S<`rX-VW#8Of40#-@Q%)~GZ&YV7lK^4TYu*Ja8K{85}=aDCF;?8TYAb^cBHAxvk zmd`37;>XKLfSkNSDyIb5{Pk+S->{i!Gv^V?+ry)y-o`XQJA$D?ZpNXZF_LUhQIvL* z27)04D$1GMd{p^NYz2W}2xSB?tpM5s)DBufl2Vemt?%6oc=#_Q+l62yQ7X-4fYvck zX?J6~=z`X~Gyg;O?%q$ihILUYNB3zmLM>rR)EY#0QSO40w(yT~ahUE@L+h!y=#XRxoeQY@`2uz7051^!5foCvA11qPUhs09Sw8r;33|dF`q_FThLPcL-kCr z4Sh?$_1FFO2aBMvm5Ej%3{x2ODTWL(oHuaSiIQf_z3w^{**snEIccqb{tI8L^~S8{NsqF z6bfZpgi_MjvUVdUPxi(%;o$CFoNQQ&+^|71V3>lVeV7$@Q`d$?QhHS`IR9K;8}%sZ zk3EG7Ws+X5Ea#NZ#6^{J-(sRrR)}7`d-LLzw=i{LHO@cxTz)y6OW8(Es8XR8b+b&S zyfT&>?&wF}nIhVDXp45D6rVoE+f%2|sBuFkjh#sQju%t8YBoX3;NZT!oH&uknGy%X z5R{Sxyf}rKnod@Qa?E+_Rg!`!RL@GMLY+o@`^pd&yx)w{sTKu=whN`9d|WX=8I-Ty zfNEJ8yzumc+;#UooXB%%*`fvMX)$mRH(5ahGc}njd-vqIF+(YzWKgj}7NxT)U=zZO zVeokyl`^>P_M5or`s-M@U?DAAwB}3%I-TE=4i}xvBToz`yL=^T)u~MB@~IT7R7z)8 zV(9bF^3-Eb@al^%^5mdCRIOZ|7l#huo_p^kr!Y#pw#`V5_0VsZEkCWmL@5(Lsatua zvJ8_bNnCt!H_8rwnTgLn#$}gZ!Ndu#aqgv^shpZZkBgf!ZuGMl>RI;h*+W5*#;}sO zpz~$idf$`OuU?rJO`C8iC(PAXv}ft!1-vqEJyTwIo~mWiKolv-iZl87?AUpb^pp@e zCysOE$YIQI5n-)74DEP$yx=m?I97o3FYC(4DKmI`$`~%~(wW1ji@DcbDQY3m+x>?Dk|s$6_tM@EevPL*__QjG?j%soNx?&lM73R(Zv zIu&TCSogzrZtY*4)SRspiwSEFDbdh4Ml_b!U880;hxYB{^Q9|E z3TDu?eO;>8smz4o!+4lTk>}`G&sfRnbn4cPdj^lCL5&L3uTzKI5`%6R zG-AY)Pmz~gpJyKLPr7A*GO5|N9i6+J&%nO7GGM?!LP?6L)24AMSMf~GYY1svOIa|J zuH8G6Yz67}@IcCzewPb6Gy?=v{ij+uEX+_DhCV-*P)a6m&7490nN!qm)ShbDnJB9S zOgEF3Kq{gH(=K%FIZh^8Q*QtOAOJ~3K~%uy)7B-V83q9_&CH1fC};$mzm9a5&1`1&jFl`z<7utxo?(AEs4iT@V#~T!On?1F z>eXw;iqAghrkk!}`kT{;Mx#`!P?>6#vZ+zMCjB0~o591zGimf#(n3Rd?5-<$?9l-{ zIb;}j1bq{(uW@ozs2!mN16Qk+l+hpEe5Urg3@Kn z(XnM?%uot#&b@$gX~`&pWLKy}eWC~f?!5Ot%s?9Nygdy&kj71S+yT^zsbW5muTmlE zHgC_;g$sD;)z?|GYBl96)}ndywgin3W5x{Um1#2=_xwmIRH{L<77Ym)5Db{?*|(cD z>(+DerQNx&{~(f*N_b<&Tt>X`4v#-EgtW}kTzyj~3@e4E&0A8jRGLeI7D(aQ(Gz)Q z^eenQWg>U=>BE(sE@9B4dCXbxA>pXaHNCE&dgW{aB~dzE(2BH>MzBarugIw9pJ(dS zH+f;)SklW^r%9vwD3umJA$l=9%1Gwsdj=3HU6ZK3@3@e4!EgMrIE0eU+mH2e=M~r`A60g1X8lA7`$sKpzO0ofc?!TYZ%xuQL z_!5?a8+%_#sWgMm-LGM~Rhsu_&SUw~Pift;6LNWb(lSa>t#Vcj*HDx}l_o9dd*40m z-L{Q>*Imc{!^fF0ejG`b%{d(|AuTCHh3eG^mN*1agi^}WzFl+DgAUajw_@>!^O*d~ zn@kuto@#X))2U+{NDKXTM5C-s9(!&KZ@=+2FHV|(1TyG)#bt<@MDOcwBw(1#{Advc z(U0kL=_Q~vhB62Qf_yM@HUTq*apNb@q<(FJkz{VV^#)#^Gy&6z(x&yfq??LzRclbs zEG7gfWl+9uBOZFVKl9#ykMb32a&g-MjGr=<(G%a~`7sko%}D2}8?PZ?B~i0(W9%|n zuFb>{DxGhRFNd3v=>(4wxJ4SFz|_IsncLFAI+Oj zakQ9o&%Ka7clReNGZjmqdF$4c$}ESW0(8FoG6oGe%_oZ%(yCcq(vp)C#=?J|C>0>B zbT%Vin8b)lFX0kdy39Z(CG0(P09yqJQNp$zTU}L8G^jKN4IR!S&x~=E`0yEi-M*1i z`5K=FQ4FY1u_|4zxs$Ee+=jv;tX<&w05<&wKE}O|JVjI~8dtrX<2lE%jU?HoR zhzv+ZsT58fKg!zgekD|@A`jeiE2*YJ5#;sv=U{uZmY;m_6&OiGMWGc0G*qcxletS4 zBaVqOld(nd^3*B3JoR;=Vqhvi!(DUh0}pfS0|SZTX3tw_ZtL5R+xp%IMi9@3LQtZ7 zw{bICTzH!}mvG`}`uB_}pREcJFoP&7#QB$A&Zn1j0hNSpxZWW{1SMh4>(qq~m-KMs zy3sUi-G+mEx4MU7CyIZfRDZRG{waUTA1g|`NS85G{J2Z_j~t4w?iR!kGLDi2YMDCMB0y=^5Ij& z#5XvhZ7{5uJIMo;`KyIch%D8JVv z-fq}vuZ|`P<&=P7g0j5eJU8gs@qnP+$ST{bpYr075rr_%JsXQLj8^tc?^7N^3W<0@F(X@!l^!&#&8pu64(~ z&l2${Zam=c7~90zQG}uk81mS&M77DN31ecGUN`bD;$7!+E4y<<5yj=3HauIB&t+qH zC5dy)_@g3br}l6F-S$ponTex5s#xE~UFq(y@jvr#llXv$|Ickr5$`Zyc>Upz{(p7c z*4gs+Foyi}(@>-g!WrG35UH@5hHHckNGZK!e}9i1ys<%46qn``ra8khA92nd3X@ zcgu|||8^_3vb=V;==0!Xj2b@JRqjcQa`WTFd}l3qDB&F6wV7+WcIVflXRxgdI(F*D zkde>PqFz-OB_UyTh_eGJly=BHv4b0~y^U|SY)3q%CQPAS$98DoK-p%E0+eJJ`uciOeOq|Ye7qx4{?SK?=pM@LR{)YTuZ&1F&1TS`!LhZ$@R7XFDo}j>%UR(D2{R*x2=3MJ->3!t$r$o~L(bw3K06HN z_XhDlS6pSu|Ic4c;+t3;H%-MRI=D#@DyCfd;4}@g{JkNFb)#`n~DWOu7AOdYhy6#)uyVAzppsbclYqg4@UO z0CdwEM;fKHS8EG@)W!}XzH05Yjndwji23#7>V;2>=#MG!88%|$|35k7(IpK8pXkf~ z6o|3iMDf>@7=mOBv0Z~0WMtLhgU{A^Q_<}?H$K{h-!w>6s3mrRe~ayfYPuuFK@-Kqz!4W{`Yd9%vj(ph zo*=k~SHtn1?=lR<24igD^bTk$@o?fZLnY1-_uANuSN@UCFH8KWZFp_^?;2Ao2Evbr zaSJYftzU6}q{J0rCB$%0jaVH#^Izc;sV?%qM(8}1Q8UbxZ9AU6t445<1@PA1#8F3gd5g$5^# zySM}pOWdqHE(h<~eqFp0 zipJ*{^<(@LZlHc_|Bs1(t=H1NGUnF}#)hTezka>MZyU!OgDz0DiEqS= z+hruS@g`*XqHu&bT{L)B+k_2GY0uUgXI1f!4gT-?H=i1~>kmp?1=>5U#-Ijc{T}O8 zPuWT+%-@iI)Dn2|!{(? zL)_D&KmUA1(OZQ4qnSSzILpe4ODj10~uL&KjqF0!o|_Jzl@WvbxVVz}pYJ zl1sc6Dxnw%61&A{U1@ja&mH6ykrTt-f~N9rpsBR z$qDsK$c{hT=BE=kAHSGq|NSo#A1ipnh7DA%T=`E+;Qw+t%Mu8mU${sVHupgn(z?Q1~0D&8F|x zV*Dg15|y|e__Z;;_KSCt0uMVd-lMVchPR8wHk`!$!&AzM zlACjsC7*AiN3ULF1pFk9L<=&$N|4YpUdg?fBA;)>cU^n-#^1Qa&vwGaKE}1Yp$s=} zR#c4Y&+=TXZh2k$I0wMdDAPX@By47ImeS%|@|6EpfBgAMvTxr^jN}J*905vcR(SCndPqyc^uNDM5+tDZ~LB&juJ95-7BGFbsu~D58SyHQL5dQ8WP@WyO?U zg|7g5j5LBbz7s4^vG@BS3TKD(#}#{ir`(?6=QmPpeevgOme<+UQy3A+Hn1NE3 zJA*y+0awWo3;~e-NC)o<65gs1y%%ikpHNP@x?6R?ijcS?7vlmzfXMsjvKxZ z^(I1M$V{TRVM2bAof1JC0+=Xm#@ZZjj2hw|#~g3^8RA-6wKpdJuJS2`X_`c%5oXVx z<(1iA*W%7@_uu#^m-xs0=GT9_IF2``M5tW3^1r({f6Bj5tk~#HoVkDG=u`@^i&(vM zAv?lVxT<$g(o}o{SKc*o^~{K`ChE5ZjXReUZ8yH%Bd&t^^jHRqX3eK!{U+3E(wrdi z{X;7-6E+k7v?!iy%kX1bAbxs}ol^Y?u8?S$rAt1dYRikLU9&1l7%l}^ten2f?W{(L zJuklKD$jxwcPpH2N%GqX@ZuyzgvE=NaQt{KU3+x<%^Tv@2j3atQ@$zj*gX)Si2eI_ zux9lJZoQ><+@bAjZVLQ3N4FLUyvqq(wef||?-3hcW$=}*m|@c2486_YRjzcrb0p0E zJ=+-b;#4|Z-ix$=c0s|F8E+Bq#zdm>fEMK{b&ez>YQo!e#c+s*k8t1p!?^aIr@7>uI`J-2fN%Lye$Pun zef;_A2SE5XZTCB^3psJ(B&SZD!L|*OGD=aoLPb(T7CM^4?)|68u2PeXkiv=Nv2)Kp z(#upQyIh%A63ZVUgC2b}Zo%`$j8BEc! zkKdFvcIfeAP{Ghf>@<~lc2eT@ll!&r!QgkF`(Mfa{rj0cdo}|H4*ZQW{+}sYyL-># z#f$&lMfp?y#S%AY!GHhg_78{{zBNUNI|6WiiK7w*oKF-CN_v0&*I?1T)0-h5>KIkh(BiWC z+OY*+63t}p>ZQY8zgcK8FboTAN6-inR80MKH!+v^-DmrCVmnqCmoM2(A`!#F@vI6; zY_NUfK@@Zt5#`n2S5+O*F2`^L(@(h}ZifU#35qa|*H&Q<-w_ee1)w5m1z{lS#w8Hr z?GkdcweLl5*Pt897P5dIQCBjQ4QXzgvh5=Chn!~!ffZTf~6Cr_f##_eYmE(fwZ zrhKMm(XQ1MDM3p#L8W%Z58JerKUU&jx|@#ntRxyoS!gQ-2g?PrmI$K5UTwk9Zn%Vl zo2cZrsYa<(F6nYP*Wb{SfO1ee4BE!=#vO*q)-7N2^5lsWMnMz6G*jr)w-5E|WP2r! z0ui*1r%j+VE@!tp?xQGdKYmL)h-k0fU6-%cB`jaEfIIK)$LJR)GiAz)4C>dH7hjl6 zPEnYG{F6NT*yH@P?-aIuhM99e;_e5ZX7`?hC=}xOi7x*{#qDc78Q`S`6MJu?k_loUZL+sk$ zeP-h0f9HGuGq+7Vm$w2XCL#*0<#(_D$9{YpfEzYsV4y|0inB8Q#y#SBjtmS;Z>=B} zhN|$gbhSH99A(A~4dTs-f3%!_{r>y){D14mFyd|Sr~Ka%BW7>|MCMvbUYE{ogl=*!^~XArxD z;ZHn9^;(UoRHYG%7Jh`X9j@)!i;87x^5I9HFze0N82;4#7uXeC}mqbGtJE2s;3amo~G)T&3V zx(!+OxqK=>=`HXvRD2-~? zB|EDMvp)L7Q^?~%;1K1fbzgAqx$P;PU4h2U8nbBm3Ze*xggJWX5Iwqfqk8q4Jo@-k zC~@K#QhLY2KtM%RXO^Ml*lj2Xw#c z296#-9c!q75`NsYjXG6pQ>}J0_U+%#sHYyGa5j>}U}O5AEmXTW+Reg$mqy+dZ7gcVjOX&Y4BKR?VqUu{;C&-^1N^ z-^+qUt5LxIoxADKrVZQn?BJ|fsX&mY7uU|{Y4jrgotp>wJPQ*QC*i4`L z3e6ifpj`Q~oOj-Ne7kWI5lmhjJC>)P9zu!Z=8G#8CGXTxCXRoZ2M0dIzS<0qjim%z;FG1xdHJn5yfyPf+P7)$DmZ3hy2d|G5;w)TWeN-u5%-|2EboB&JC`Q>DA6d#HyWt3J?&znR2W+vqK1#vDER0B z|Gi?${|YN0{Cx+5KjnX?#DjqZHzDK?9s{l`&_;>I42IAsnzwGtthpbuWZrxH@Z~4W zTKF+`q>!I~+QO)prt#^b4>-KsH)+ZEuRBel}t( za0sM`)t}5}z>tXy89j-2-+hDf<V&s^~*m8E98VW=gGIinzW-MC8&BvcCBJcDmMhqW`;}o;(iw)d*_du3^ zzLZPPZy!_t{G2{?gp-H%P^o4UmahJWCkOQ9vB!t9_h=qR4s54W*V{O^^L5OdGZTIM z029ZJ<#g2Mh4C*EOfJo5%fI06yKW^Zq)0NOES@`!m!~gc!qhhz{@g$YKJqwQw;iBz zhi_+-?0Ac&q)soU$0%y)8i+w@Uz9VXK54I4>zopV^ccrmrgXL94!Jvm-n!dE~1Ox*^p z_t(rIIo3A&ZM6+%CHcFMvqE^-F@f0TIS#$Ln7SDNu$?wc##7nR9>Xa8r z2|_^UQ+#?q_YZiIUN`h%<>xCn^vgz;tyoUSOS`jiCW<%pEG^RaNd3UU4H!a1R9eX&Dyc*$BlfvWEKR9i5BPMU~qKbk32JCEVn%L z6tiZ&&-dS~<=J6lDAEpVe%MOKOS-XgdNYn99$NEM&{K z-(Zz(O8XXVNVft6tPm;X(zv3_MJ!+VG0L=1kuxluGm}YEmoVwYSEy7jgryP^ivB?H z4d!S8r-Y*8J9*;qL9G3LGbJS_`E=Q*>^^i9jl=2FhgtgRLT1iiz`E}@5Q&zsb<4Lb zm_L`riZTy@L=oyYvy?{W8ok5N!!$G-cgD1+i!aSMxziHh>D5~D1i zJ&h614d+nqnOMTw-!AFjAxZ%ewr^R_z`;XVu>5PB|Ki>_$dt|2&1>m%*Zq9((Q;Qw z_q`1gVfWVc3>-9=UB`-J-VxVV;`QvQOtBhQfQVLN49LM!32Lq*O*q|AWs|47y^$RwB`xS>zh52l;!|uJu zIDRI=Mqoo9;3@TKpPOBEJXkDiiAIw|G z!Q;nSHE#i1f7#C1v115?PqS^;Q4Z}t#`j-urhE5ZT-N0RGSOI^VE4~I^X-}ye6{u) z-gx&d8rH4MiEUrh;jgk8V<3dc4O4Wx7X{e8&}3R%g081U>EPUaV}?uUJh966L$ z%^MNYhe@6J4R&#u@4onolgAJ9{FsRtb`d!_x%|3oFV}YOM5_*$o(1EfwZaM}Q>jt~ z%BCg}J(iE5pi$E{G-+6$bSKQQJx7@F?mPUvV<#u}ALPK16ZjB7Nr5n%Hhssh+xIhR z(j*Kg%;6KceD}i-mT`tE7`f68T4VbL`*|9(r~h z4J($VYN-(I+I3{h_FaTk3gxn@(7bUAltehEb(j?&KTmPdO>Et@k8>`(h9onHi67pi z+>oka_e1~yAOJ~3K~#mP!=`V(=jxm8r1KS>DW!|4U#ljjl(2d8*R20xGhsr^pFNYq z`*xD`V^i+$cNsHYdx!kfd)V^JHmWshPik@s%5ktT5ec(@|9;+ne=a#E_i#KXhdl@O zk#1Os5uj4#OtQ=nI=mMUl!9G9|3vw$iuAm$C)uXS!}sLT|M5ZG+y5@YBvCoLGR>Mc zq<;4GEWc+cX9^1G)~h#Y?H)KKia5pOo<2o#Mp;ZN;AMom4Atl;wqyxSm#bK57v#ykrt_ z=Zeo3<#@1CW-Pqaai9IgI);v)&bYUxP`h$@Oe4yog)>>bBTA3^?2Q#V@?$58#pRAe`VP$gt*J3yFlK`t-9G>w#+Ex7&0 zo}?t^g6Sx`c5LE>DQ|J~beP-kxSKAWI}(sE1;-CDdcvD*-?NtU8S|G?xmq0_9QYTiRLUZN54$C?J^z1;W%Ez@`^7pt9#H+^ zmO#&ph1L$*wkbM!jJ~(rM8_U?F{JNvj2<(}O?nhJ(+mtSAQ%i_I4+U^|*nO33|G6qYhPKGP_*Yu91uu;FA?$imPjfy``l?h((E zV4mNj*TdTs4`sl1A=8J0+xk#yvd{;L}{Xt z;+UgaD^QjXePg-xG)%;fP_tGIhK!#?>14nRVI_qKnP+3(c|l0nVVl&{G_STE+Mt-2 zX2{)SOijR2h!zTq3h8p$Mcg}hC?O(kRmF35@xZQ%&jDplq{ZV{g> zT}sR5brBINRmkSaaT6(DDu5kTq$F9GmJ7vWJ9d20_x_C~V8mjDT$he%nS?A8B2l8@ z2!TMz%}Q4g2nGI8xEYp?LL4DlY;(hP*U|gdJ|rPT%oHk>OYw62jI%6f zfq;S5Q5czf(`40c#ITWLcyG$fM54CqN;4FZl0vi-<&sM}^Uz}t zVBDnXZve97H*BFQ8~75=AKkG2Af{2$?9uMjQtbMZgNVV_ZVi zt5c0sImOrOzGTbx{akm$eR14zj22#5D=W9W0kx#^xqXjG>({RU6K zktoV^H(3`nzzqb|UcV}>2nK=#yjZTJfQ3ZEUhI~I6$kow;pDm+ujp~#wSI$*{1W+2SHHHY0l44Hf<>J^HGn7htnKGmrnnuT2RU)ExiYrEz=H{>yDHCjxq((u&7f8m%@nyaqt#?wy?#z-p7 z&Ar<3_RAAlv348x-F*iyOqq^Vsu~0OT*mylvw45cLIyrMkT<5!XY9xcj2Zqguf8^w z>CV#2oXw2<>f|5K+>>?~9N}2*o{3;nZT2N+)4i|Od%TGV%i)E|WvvUuJj-J9M znX1(qkeQyw#!WwB6ChktLg{3Mp`(P0&hXXRuh{y_cHVmXU24>>Np^N=^73-2UZ)-z zWiu#WwiK2Mpp-|7>nYJjFi0ppjrCuxXX~%~IdtR%S=Fnu@rU*N^utf=+kcSak|G?5 zpbgMIW}mhxon4uvP#Wvju0te3xbP&UfL|i>S9WFR_Fvhxf3FLy5iKEPLaTO-`Si1oS-*Y@yLRs4$k9{S zflR8_XvpUuy~6GvzvBIQi%G9gg^Y6L`DWcZoJa}b@EJ1Ff&@%3brj2pBVZ*mc@WF; zRdI_43TzvNLG!llDLB55Pv6yWClGC5 z1(Imlp*@Q}S;pbR`w?A2N$w%igHg8q`~z>j{{d%;irrTWlq!=-QE?udH*VsGpSDpH zRTyRxhW4CD${@E;s8Y2KWlEK%T&Yw-rmJw-qA)_GY0|g_zi!*iuDyE^!z3?1myDzU z=d^7?PVOP*FZhU^yAQB)#~v~=GRZl9gpJ?*#4kH`kW{KHrOK9P@%+!&xpOzuK3Gio z+RbTHr#cp4S8)Wip-3;2Lf5MKflub>>#CEqx@v=0^ExiB6 z48Gg+Gd-{Ci83riB~#*9-1pFZT;25|`rdp!n}6L+RFtP|{xRb2kx|xv`58UCbf!s@ zrd)H|0~Fd8h7~05+scy<^yQpZ&1uo9EmvKA zE9=*WVFpAimOL?Sud zc;)3>(e)}e{&En@OyR(`pXh#J7g{!JP5;M7P@rM^rgdD`qZqFI@0=rp8T}y1g0`jP7aetJW1mQjp@|+ zMwWfG8IcH^*RSM;YkJbCSz}tZZpTAUJkQBO4|3f*lp{7v7kohH3(loMqZT~!?0CZZ zpLV_y9kwFqjeD^&Tx4D4vrP1GGM^t+}8VYy0ov#tFKRE>yG{W zylp=t#*gEsTe>mqvA)b(_!&7zb9w)rS=@I2qg>X#2Tu-qkndN13ifGMt@(yq9vQ(E z-LK-w2kv0S?3dZOYa{c%_<=`9zfJFJuHlvE?&teeAF}Jn2}Zs&lgoSE!gal`1N%?;zacRt&@lfs*+C|N3UOJFYdN^Wf(ZoFt5Du zJUx2d$kqdeyfkqHnOWr+HE9YTzV|xkw!fHHr_G{LRw+Q5`Nf@T_2)M^&4me!!#h6LH{A6X;ZHX_uP0r-MV&X&D!;#6poJInrec8MG#HL zE?v0(`l}c+@IfxPvd93;Kr_Fp zRGR^Rd62hW9K*33n;}Dnu=>OI=y6$R`t<3`j=g(9f*2AdV7NKm+KG5hmc+gYp{+Db zOA`dN4iGS0H&OLEP55xutGxHdIJ))d&hET00|pHy%{1u$=z}=nQ*^!TQts|QlzZ?!GrO{P96_ zzNib2KQ)T{qA<0aH0AyG-)G(%uhRLVPCWVSc&gQJ&()pUa^HW{Jm?WN zu9#1c%e%1VyN$d*cLCX@G6Li+gYC#gK>k(dFVU96Oam`DzU*Td6)Tjv2})^Jj2=$MYC4;291dIf*Efb2?o? zZdlW@c|&SdD2G9isO^@aQndzj>vAFeZoG<1I(22=fqkTArqi(bx%9fM19#ta6?fnB z5RpQMsNvdMD%Wq!U+%w?=N}uuHP_xia+xfie)d_COhrIxbTkTLfl3AimT1=ua3AM) zXvxUY<0&XCbm{s2AW?*g6dY#Mh)EncC4BJVXH0u#EXk(p&2Z}>E_;hIQGs->yzO2# zY+BFVclRbmN+?~vHp|zp=i|k5Xj-e9=koS9UmImww7TFDzFf7El}qN*s74j$&He~& zM<_g9NM5dD{*q-p^ThppzhWLsmVUv?<;!?+;&eK8y_Pj!d`g|{RE{1y?j>~rL@=FP z7Jf93cjqkTg=z0Ff9|_{|IO#TJ9Dv{a0c;MN3lpst-zu$*RXWy0vgt;M5USy>E8QB z+O%xWmEF3~s$ngHwh#8tX};g zP3l&`5EId<40_^m7Q8o!gFkI%@w~YdL`xVsbTkKY48Hu~7oK|fcILk~jd$lPb~Cn> z1}UKA^g#v>8bM0A`m9>_9mAjOPbfw^`p*#8+hG_c&0C&Bx2t-Qnihy1>|D`cggJU( z4@v3eNlr<^3M#5qD$Aw~8#r_-7nM<#3fbi_h|sioJx=DHRNmMLf zg~AhukZ?Z7Po1J%wF*Rm8dbB=XA0Q8eK)!J4t1KhMk`I-`js*C8IGJj$%d^5s9L=t zmK7kmbTXEq$<47n2g9Ecg8%0w8ns1h5fKrswRpe&VWLGuoDvaTD2`}x#1YXYBH9)$ zB2f{Eh$D^^ik2cN5fLq6(K_OlO^Zm8h%OY-+PhvvbXY_j(IVn_SNY#*De?Y_f97c0 zeTGvaVmlJmA|)cSd&e(w%_Zl{>AVxMyKK>-#TJpUh_*$vBaZ)UCnAovrO3NZbg^4L zr&uDQrAR~^DG_nbh)7f%+mRA25*0^87fIB8YP{r5iHI&1M{6n4B4N=YPDI3siq^Jh zomfXL5-k*MN5potguOD^+OKJ@Xekz3L_{K@b)jfoEMc*wMBM8|q9RVQ+x}Wh#IKhY zaU2otL`8H|Y!Pwni2FWmyX~U2h?KbFMvG`|i%5ZJUF5cz)?#ash^@uZVF`l1^L`rN&v~9b6roB6DN5Vw~^5d2*(zWaLa_Gbvv9&GY6pGkU z(T+&OE2HB?+_yVn5wEW9C@vPQBVvn4REucs*Tr^6k>mEAt)rqvi`I^aT_i>M2W9WR zALa5ZZjhBPXnDW5jFIutao3+}b!^kA}t8j+A&~IVw^2nYM^H zQ4z@(N5XEu+ELMtEsozkTHJQmMP5Hd#qr)9aYS^~Z5yrKw$oaBf0uau{`ZO2TEgM5 zY}v9!a&mHh_h!oF_+S0CLcR5rLmA#ujlFW=!^4h#r za^UAxQZ=iBjC^f@{Je3Q)T`T2ZW#Q6M4S@Q(cSXWut%j_)i$#8OtBP-NK|ZZEpfck zhed~v$%`Wf$^XaRdB;gnrR)EDs;avu=NX1!fB^={h+tOCi6D!ZGiF6y1Bf}GAc_HV z)-@}bGln&RIiZLMiog&Dm>j#i>b$={PE~gg;=Sv=t9SReynaSzx+|VKbo%2g9jl1{~?^3V(KNUQeWAE5SO zdR10PW$#|{;=3QptXWUVz{(y{+M`m=y!2XGxps}b_T+7nnO-i_?|N7oR(>VrnI&@c ziKol*hAQb@k}k)eHc4tcE%QHnK`JWx$f2j4FR#tMOR}=N$h5m2lI08ElOiWmPB`OI z*%SFMogGiI3f(;}ih(b1K1?#cVhxzlf#`d~we zi`J{U(K2IKPFtcQ8=m3Q&P?1zG$efx3dU(cp z8V7|^Hm)5e>e-}guoVa{C>t$dECf%xDCLVnDI#^W2v#Ayf1vJqUAQrK9C)>yV}yfDh-Fey6(;-JM>-t{y% zVLb7$m4i|?uf6yzPtAVK=L$4z{^@yz+;HP`ax)ZZn0zHu<{&<0T^MDXqJR+iG}abE zBtb77h{=J;?L?&++8pf>wrsRkh~@Z4PMY>CEZgM&g-!N7;2@$gIq()DMp)1Ys>FHg zl_$CDfyWuJ%UCjV(lHWTX#^^(A^%0ufEI;iIf!`JiG+TmMQmx$FIez(U&Rnz80}w$ zrR)UVIbMt_FS>-ER&V5hamTUkc7t)W$7A>3%{%YU!^JYH6XMXlaw{&qbTZjtzY1C@ zLKqn^lYpOL3R^6b&t}XJ9gzqGb zH1LGT?^F8vADTsaMh-by4%IbPtXf$`p@a=*AS&rZ>A>pk|1K7SgH|R*CGmbH{N$!h zS~sj>=8ZSgZ@0s_b@~NNn|dAdSH%$Va3zK-8Y~CL3H$k(itL* z{2$8Bq^;ov+-Mta$Yt5`YKCmL4_ylLX|LbFsU8asW{3uFCEG#CB-IthA}m3S^<$aSr7q6;Lpv22u>YZ3p)5}$P>PuSrhRYpp~o}&uoG}`Qfi#7l#Ru|Mki=(lN;LMNd)~Y_}fnO zpVZgO^6!IC7Bg;t5K%UP28%**?5SsP?5Pt7)KO&9v!q;7hsB<4 z8Gs^*{ZoJNL(#$Sn69gW%-fDAEGYPJ{I*t(xx+-ureGgG9W$}JW!Zj_Vvv&J7cHdB z(5c`_{gE;uDW+AJtip26oNz1?&c2GhwjE4X1X|o2LRJW@7@)9R^S*eVV2LRNLTqet zK@0`Cq?XM3ARA?qo|R8Uc_E*?_Zp|1@-s_U*U_ox5P$G+2&uFLNxH2B+p-xkas>Bv zxtyCWJBOPu)kJY99c+P0qkFef+Se^-)S(l(cJkSDec)NHoqP_rWM|M4Rows7^Yrc2 zB~gg$SsF{)Xs%wtgtIQDy20VDTdw8)yQXr;A!8{m?!pDiVr!jJ`?dhDSIefoe z$?HCl`|iGnI2kAvGw-Br#x}>c@hp{Kfv~VpX@wkp#9>@H<6cJZvpb>8GJ0(_fcIXz zmvc`$ow@ISj84m>rAd(+$w0Jg^3=sM3smvYUYLlL%U{nqlL>#llpe*!xX~!NT?R1W zv{PvMjNW~R^6r=Gd1A_O^vv@ZI^YFK>I4^uGFWiI;aA6_(rJ?&pH5>skZrL%O-&M+t(HV z03ZNKL_t($lXlsBFIPVBu~Gowe|6md?q`#IQt?&dXW|dVQnvo>oqo4zt*NQ0AvZU7v)`{@zn<>hy93bH z*2cnx3mLZUcA#tq3>nDw+YX^q=kE0CGmw#E#BYwVa(1|Sz6-i_7eGVWuzktk~dF9z z+M_~dPCk3>yF2MNhzhaGF1s>xNFNR!u@8N>-j?Az59R9xKT^?e2M+nmzEo~iN$1Yx z3>>;MhmIS=zI*OSm+~(3?!6WJ?|%S$>^_{*!aM?vCG&zR+S=pP)W;Y!WC*=0E9l*; zf^D`Q%6|LoM}B@jqehQntIA3S^{=F;q!U{Y+n(XO>_Ud^(4|KuJM6rJiQG8p?791H zt$jm8Xs{w;J=7jN_ zdeYHouN^C#$?)BFq-WQ18k^&6yTc9)9z1}7{rWI?&>#v6OW5at(Offi3cb1)Q`V`3 z{sRWmrJ|DI!*^lCetR--U@tm#E~EdTp^O=K2)pk*jLb;j>PU{Kzo%z4G&J!2_usS2 zF1rxSpGt(L<|q}Fed$+OfumiTnp){QXlu&L%NRDKA4^xPVfFfY&N+7?gZh@^*s$Af zyU^4eW%-J=oO;IDj2f{wVN2*cU?8DTm@mKlnvtUp6A4A=(W3_?h53B)+2`!M z+n$_s>aj#@he7?fqI2g?e79%`yX`xI2@_5uGX(i1`Sj>n$tR!Br+420oOb$2G0Tt_CI;Ww%EUsDWzDoY86VmV(5;<2P=PcOjrcbHQYMwa+b7q zX2x|_kjbV)y8&bnP$>la23PO-UM^o$TzlMh^~K~5*pY+A{e`FQyA?OBi18K|_X-6S0tJEw|qBFx~s^z_?Mv6Q{TQdq5dqr4@X!DTwu5 zEVJ#@8i5v4k3a@#4IIk z%ZxW79+t8JkH-3Hrd@X2M%U6&cp^Tq2s~lhm(ep5j`rdS&%AMp22mjMHhZpzV_SGiOq4`CQ*eVyc(y&y zHARdbVEJ5!N}-gM(7#nFW03YdY%6fv*=UX7s3dhh@H#BL{t>IHs^aOVpXP!KE=W2} z#Pg4<{CQ5y{VIhgacqpVpomHUP^AFR1KTly7JrgS%n?EAiPi~kdE#%|-^vd`2aA(|*M#MuY2Ukqk-BO@kA==WOAXd>@;VF+-pMQ}jpL~XC zcic@*ehFFW%J*sp0M@+RP0g*e8=^Wtq-O5R3w(SU<6ZPcM1#T46ATRl7;R)r&^k&> zTQgb&@u0k{jLeL%xlbh~M+`rFY<9%LOaMwH6A856$q>&c1{Uz!%WM^;VdFX;d+2XG z_1x<;G`7;UTThOea6TjV-<7;@h-dDd$!9B?xbnKGsQOwiz2bW6o1@IU=^Ao#a}wdl zEw;t}*`~Gj-)jI1Nlf&<3WcAW7kp;0kKw6v4E!=L} zWwD{Ao^}-J%A`LiC4`bJ&4BjP9s9okccu1#AMci zpA4g%fI=V9?W|d`jFnYYXdmQ>ozBMEM&cU6etvOcF{d<$X#)XlJA}eZdXh}yG>%Fc zn@|a`6*NLLIH(|{Csk$YAD{cgC#~)RD$SveAM;$|-icZ+X`0@KiJoWsGG`7QmBge4o zuu2|&^dY`qvYgJHD>(efqv%oI84nxRa|tOZ$WEgzBbTbGmCU~PUTPZah)al!++r@i z>>TEQ{uyt+{2Ep`%pM1fWuM))F^TYP^;~nw#gyb&OuhI-va>Tu%gV%3n!5FCcxLts z{Ia}?t%mNv!G|A0wiD;0_uk^&zkf(mt4n@SXAVE+D7u!H^2_{>`DFf54ms{P(rvJC zQ4;0n@4w~Qm)@eTT^Kof47=_)3=y+BbR@>IWy^T%;m0^-!f`D9X%RZ+^1?IEQ8{=R zg9rBUOALZXB!FkMg%ybM*tm8Tvz~gEH5=>bzwIs@IA$c-jz;1Qy!Of*-urwZ*@Y#X zaP(N(>(}z=Q_m5L2|MgKoDri(nxYjSnky$xPHqm$ad`XnS9$C8Ik;kjoz4LV9>D&4 z@5Z+u&*QZ@bBH+^j5+iuwi(ca+O^AhVfJi(UQtc=9^Du-W-PN_c#ETsI+)HSxh8)y zR>uv~r?Rpk%*@;FB0oQer9Um^+H0rK)^s+??g0c$keRwuvIf?A)R9{x=HKq950gK%H&OG+ivxwMeWs+b# zY&=YXk z3gx3Fdy}L6{t6>WQJ3jB1_i$dQf(HJxXw+^lK^@;<$9CAG59{nT(@sB|-A0aN*iPG#nOlezQuOQ9mEQdZ@yMgIm~q>^+;aU@xK2J zYui{Bv^3Ol+2vQU#~%AqT3kvr9;IKOo}6&}@z~j=0C;HMee3^NX0Wk==DL-fe){QT z<#u7uz4v6=l&kq=>Cap=@eF1^_#pQ^^f)I@yaFqdL&$LmMTDJq8b(8H3zH{bjLI%z z)SzqbXl*o)PxmT=L97jfE|XR>6~MkZZw zIWNEXAm4vKpXX;i&AFFMAtNh;jWxB*dhRv$8?i5?B?Ul?`sGV__0{*8@zl%oA3TsO z+oiI1IgzII+%o$a4mfBOPRPNDwQ$ZEXOodx%=ObRA}cG+_m-MMgJ9VFgV!!w>_5zc zNq+9!xqc`%2=yhW=_Jvz<=2gaq_t^0Q2o%yS2M!+_?V;-204Pa$vP&sTEpUruVnz~x9xpO)>mPKA}9#vIU z{=?o&L3M&`ct8qrW^vhq5C+e9WU zy!F9H3@FPZ-qy&~Q?8}5?;wsn;b?3X$5R>Pl=fu1q1*Vv>}EBYcuxK=wm{f}B@4fx zK{C1Rp@%4S;tVXya8}M&^od*+v(e@oS&Ah zB0gv^t^~O@{wfinv`YmUA{#+Z8fcS zJ_TI{vH$2%X5h!>i@7iR&mR!Qy0sfgi=s75$}4lI zYES2}r=KDtJz^++6p1{oEsnq~_D7gf3fs2XSX)EPb5WuUs8Ml~(jcbzDFJYlLW!50 zSjG3>s30J#{eS)Hdu86MO-s4VKdGL_l+XO|bW)8cHOJToX@1I#R@(O}1_f7M0>Ih< za7*z*DgT}cJX|TqCvp7b*^>EY_@56gA}Bd z+{X{C{-&plz!L~b&uZ$u{R7L#-^e#BDIi&0%&opMh9_z6O4lg*gOycS8h6U%25 zFyUw|UV`*I=~=W02(!#yR$^b1QsW{i;qRdJjD)EH>z3ftYvG6U75E_Chxi?Cbk(X= ziQ=d&_Mc%+Kx3h-|KdgXr<&<_!Ryf09;KnFm9mPSW;JOkN(-}SYFNvLnl|!_N^mUO zC~_$H;O)1VdH192IpRQ~_0`yJyE&|Ywp@SxYd)~?So-64oO1C^Ou7CB`gSg$X59iV zx%7I>R)D6X#wp`jpXL$5ek8LP}#iic(tE-Oqy*+{RkYKIIgg zF8$bNXiuzIJ=#n4b|gK+7NDaoJoe}_)Y%10J@+Is!>ue|x(prZNlOgUY>TreoJMJW z4y(n_VedZ(^rm{ctvEfsP@LEw;t}_ZH-QjTtj0L8+94IR5X+q`6=(|KIL);bOzckpKB&i^jQ@YgMGAa)SAcYb3ZMaSp7 z*+c!0o@;Q_mtTJQckH#r{(mqh2z&flxm6|{Y$KLUJlalHW;We=bmxnY-(!#M`{TB^ z@WZNVMt2>9likEOPkl&J-9boJCYDls@$p=SY(0qMPdu3w-+jn;_dIXbOO{JC+J^R5 z;Fj`mo13_4>NIvAF^=8#+!^9+G}Nx6p|Ob>=buT$t>x+07NC_yI6ap%%cXYhTH4Zc z30Wqo+p)uB<>wM_s%PW!4P=+)^5IttA-#Yur6nfgLn#x&u??M!Ev8VVzO{|K!a~9V zs0e-g4I=ZsWsDlJ2l)jB#L?trr1Sl{Dl)UOxapqTIsJlbc;SU19C^@wcq+7+7ThE! zL|Gsn(e^g-i#t=dZUuF#YstzB^Tyn-NiQs=U*%Tx>z>E_&);Xzz%GboQNMaM-+lQd zcTc^Op*{2Ye*QviOH8u67UFRiRM-@QC|LQ^0$zXf9j4wli`_u*N78*!Tvr#&RR>2B2PCOQ4eO()c1^J{o4v0l*p8@pgSIHZ%yv2a7rRcClTWdX6 z-SQAS?m3dYj5NX_oAiQWPCnsaI#~^zb?ON`{PeR7>RoPtU}DbO;u73q|6B{GZ)|0v z3juADBs@E2kz^JleqZ-Bl2L+I4vD&ez!IQH`}4W-`|a=OyZ&sQnCK-qe=6gfxwZg` z*ocvaOHeH&!^FQjb8wBpx0@7u1VtFXU5)Qo@ry#N0acil(mww4 z6r=;4RRY_YW=U?3opQgw_F!(_0xz-g_@;u*q(4}jM;*{{sbsPO+Jw$UVIph3S6V4M zQC+>o{{VAQm3NdKt_B?joGkpEck6d=uRa`m!PR^e&pVqcGeRkZNz5{n> zK)jAm=e)}~r=LPvQCD`~Z8!Ga{{W`WxSdJooKL*51}~#C3fQV|Pi~*}GW+at0G?Qc zB*qU5f8wKg^BJ^T374LCDOqW7{@F*;y=x~fIQ>j=vTdrXH;|E$NpWcbBX--Gt1dX3 zZsp}%Jo#u`m4+n_ox1kn(1S*D`B|rtS6aZjx)>KsyPa-@g@i4^(|!W5KNe>I@4xme zkG$|EcRunc#g0O$Oor{U2SZ+ekMsU|DrtpXDK4vE+LagJDTv}wR@s;7mrdmC)6S+- z@k3}Uj2n+{W{n?=DHa)7MRY4GW9Ibf+%o+<#vZUY7oRqsoT38O*0yuzq-*I~+=+W` zp3KZ!?_}=RpOBv0g;NgQi_w1>&5SEArJ}TmufF+_BX=A_B)fnfJ$m!%%Wt#G z3!29sdWh;ZYq(>^G{PZ^J@(p#(MO%Y{O>R1+zF=;$?HPj!NZtz*6~v|r%|8@p#Rbd7lCx@%AxrQ5VypuCdn@1$<(9qCG_n~`n^aRD3I;1=6r|0MInwK}oB2w;jvMVnak%W85vb)~!@ z3s;NpzcKu!0n56!Y%B@#zl`FGhr$Ua{|+i6|M+$N+Wdh>0Nuu_)wL{NTf??H3?<|P zMr9>=JAX6A`8#a$FeMn7%$K4yb=50bvUCOIeFo5_xG=F*5(xfTiAeukGjnBXQAH{U zH-#suyr+IR2z;s*571h06ex@mj`(5vMAdo9NN+4alSU{(L?OyCK@Q{q4MKhq;9(vIi4tgUG!KRcbQOo#f0cAA=+&L+H9c!nywwA)ud@OCTVcj~?a|+N}5Z5CwFCQZ$l3XvF@x?==m4^B# z&8;q_owLz#p{}lpc-$o;E1TThJS^pbZl%7ViRM;~wj4?da!?Ybwyqh^GoFjQ!UA&A z!!*{{(WWg*^D?QfsU;(?h*&PuAB0U@lgj4?gya-$DPq+UuPv9A+`()>V*F{tP!#s8#bs|^Y_6YkA z$mOK-F5{>P7jwiu+pyrvd0cVT)hw#2 zBxp|*c+$?JGp}XFZI3bS;U^fi=gx#ldMHyt;J@2DT(x2~Pd`1I$rql7(HsGDXAZ6e ztb5wI0TG=n=<#zlx9|l1XIMv`z)e2tqtQEk$~_9vw3;1ky6YWMt)ZBzhK)%-lRObMnll8VYhFex9^oIbljVbuvh721*L4F~5`QYj(P9#K0X%>(=7Tc}Wo zw6M`M))K}EE4p+_Pw!mZ=|`giT1eb z>*{)lWfpnn{k8q``}MJ6`GpNZ=J>yA@0Jcft5+=Jf(tKZ`O4LFDeb})S6@Tl0sZ}= z3>UP=tIs^kt#{o^yEyE*?;qvS5rm4P#K?4VI<@M9)T%3oFHS+cR zg`6{S3S$mBh>OlY4TWOCw+lG($YaRL$w%2~>^J&AuDW0Xvz~a2C!c(p>iQN+dJN*a zYp8gKPkv!{uDa$bhHg6uCsEV>uiD02?9Z?S2vmM<${#KmqCqLw zyzJPZoTOL@;M1jJE0d37NSJ*fph01we7XWG4=sjN+Ok5R6k20S|5J!u3Boy|{Uq;A zNQMQog2F6(6R8%0uh``?%SGcLPOGb|2(?U~&`1oJp+UfM)B&_4wIF0Z&z8 z$dlwcS^42u&uwPohBde9eBw&Mhh|fQjq;?L}g_GN> z6wWD26#gyxO=Y;uf^?X~)FgJoaiDx++n|at!4DQhixQ;OJ{(G!kyM9pNN`ad_8xpxkzlM;T+Lqz{e{05zBk>j)sE;ZlIYnfrJLE*1WFOM_&o;(SKg{QjyC0*zp@puM{W)^{ zc=}fq^4(XTGJE!mtXp4$la|Mb0}o=<$lbAYoZ3}Y-1Eqz{Iql#k(?s-+Iv3^J)pno zdCEdr8s)|K>hsTe;@KBzYV+7@-;o@6;3(28Ot?@5V_}?VTP^3GdlAh|QCw_LA@gJMOvbVV10FV(Qe%WQfaaFTKJWfB%4tydn-h z{BXA2W)LCkx4e%3$0i!12IJznEnIQw)%57upXoDh=JnYR^1vexbNRK?$#uXcMompM z4?p@W7hW-qZe>MWb>Sr5dT%F&5AMp;tFGqYQ!i%E?fWqOk_))$p2wMX$pk)m>lL1O zb`CABLz@m`wC+7(?J)-R>C2rD{tZz!p>P;%iyd~`gB^F@6YaHg%3r53d)5nFIr%iY z_3qDgH_aq1Ba?^ke2f=fdX+xg^e4wQWZeI9ZM(((RO}ZV_YeR=3rZ^)7u>{_w z;QWXIdcM{NN+na2t(47z88+c4O!+;Pl0p3Zo+Qu;h#wSzN`~1pMl9x`C5=cp$;|~F z2RTVxuOb^4Px%I^2>7Xpy8XH-(@CVkcS%>r} z#6?lt8e`#)KT@}D2)3t*X`3a>R?rfMczd+Na1=b`4I8U@W6oqX>Mxep@*N~#d-4>R%)^T&fD-yOD045SMb%hFR^-UGY9S0ACq|) zBQ2!);^Vm-KJF+QL+NDMnn&-ypBo>2o|BIpO`7is3KlRTu=J;&Xx_MyWh+;)p)H+$ zgDQFJwJPqq<2Jf>%_l1@n@8@upQBGZhP1X?WlBgBIRe)`y+!kJV?pd7DtvPt)U_SluLq7evo~cvL;-UK(Vza9B$QHE_(!BexJrzra{8d?+wjr$7)krs|S<_NBQ=u?_nHG7R7$L=G? za@etxu(juVLE^NvG?E?)(a_LDL0Ku`a0E}ebnn^;*NgMx_dl|F?M8;}uoGBNSXxAG zK|1SKZ{*WOzp(F^(L^kJ%lNRxfE3&l6o>rLW(tzxJoVrmOugw|;$So;%|-ZgsPT?@ z0V49rKDCeP3~;cJ1oOM%i3jfGwYT3Psy)8`^h4%-HJ?}_Mi@+~{<2cMl?0D7#D)-E<@p!M4U;m07gp6Mrdcns-;|Y^-Nk? z+KtSlwtNk$lv@w>^`D3Ki%zg2h%&1|&l7Cb&Wa^pam)#4Qd3vY>J>ln@|<^RiMk0u zVXiF*BL*tr4p8$v& znjK%0$lo>qIFh)>)Th+Z43IYP(FBLIBzet(cIyCll>aQm44NWd0O=x|hxR5o zPtrqYo`WBDL(r}Vx}62{KjHPi&m-n(YB#KmRx9vSK)K^Lu+}8y7Jt=ZTkM}`ia1TRD|zvyx9K%-DD%Ghig(_6j?9Rl zwTJE4h-hplglG-g;-JHh=Buy1;J6cy#qxxrqOQF8_xE}2F-A-`{?n z!F{@e69LOXi(qLNX{%+<>#wr0u8CuhK8BM{IML8-&HIM7m`?QffVMh4Bbzzzyu>ZH z-bhAP0sH@DEXSR262~5UB2Pa41Vuh6dJpKwv}-Qm z$it82)i>vwbO1ZdoEKhT%H>liFUch@7hENP#pfS=%7qt9rm?n)Ze5Cq2U^tsca6Bk z{za@qrM_iZe|%wxvJf3-?ed>kRbA(&)O!Ap`Cj{;DjPH5C8W_TWpp3?q5{D}`(BW> zE0(dLrUtD&zWeljKKW`PvEU9MuiL!FpLXH}LDjS*tKCKo${`3=m zSi0V1uSguF<0e-T&?UYl!ioi7&u7jXuhW*O?$w|n8qf`h28m-r>!w|emb*$2RS3!up9bDU zi34%}{uJUfJzGknl=gF=0(UPyLn9!r&*~2z7H*)&DlshWCbXYjd_9K_U00)&0kT?q z21F@*EoXDD0nKcnA>aX?@7+_PvBVr%lqu^m$=U5J`u0;^dg}wC?Jb;t)=B(*?x*G+ zOaq~GJOT0&8nI}UcG)zoJ~*ESA9Tl9^!<07eByX^-f0JpI_3!8oA(iMKX3E14?g6$ zBafh_xeh_|!TTRF{^YZ$t!qTIHk!}De_Ja3{`V#xv6gz;T7~qiVzLVg2uBolK;Dc| z$yFzKQmL^E|GkwsE%mFp=IU$6DDKIOnKLNsR7zHEDdWZ+LQzRMUCYbZbyz><%zm1e zU;cn@19xHgHWmEs&YPGt@p4vG*OQhOLQ4x;8*TEynGGI}qw!pS(WD%-)@Zk#`lfnx zIK<+genC0u9DV$WRQ9S!DIVGUGV%Y$l)sQPQK^iaJRIc`ZD|0liMPeD9UI3V+XaV= z%xv7YX0teTg{Fp93i9*GOm}c&t+=j6VN+XIOUSVag+rJU4nsn2X6`z)#^30 zx(>yi%jjAVVfoKXX=)Xm^bER{cO@$$ge97|r}1ouk%u2ii=9h*YYQuuE+XEpaBT-7 z5&HM3prv*l>(;CTJCmZ)GCCJ#Ah9N@e*S^)=6_3VQJ4W+m2%{fM_^~>p`@Mm_6Am0 zt)V_@k&{6!GX=uT_>TB_Hs#kDdhDlMZt-@&$Q zL@bmFv(=!jnON4J+zeqw)e;&SqNa^4hfZC)(K$bzpO-A6wH-p4*>vmLm8_6r-HM-B z@XZ&HkwvF2UD;>kD0bL=S0YXbPg+^Grka|XR!GaBTX{LT=??K|6DwD)p{X^F$!z z|LpU)Z0hYCG-5}hjdd*jVF7V3%7U+dWZJarIq%AA$;!*Y^3@Z(EhGCs&y+(>Q7Qd< z74rVq-!SKuS1C(tq&291Ncx!**j_82Gtie|Ls`ij&wy`Gkxsrb7QyDVT6iu~j`D)1; zy7%6SEXSsM_ud?O=ongCo9WV{KM`Buc^YMdjf*0R=e2Xk)SLMDn`KPB=P_FA*Rx)= z(Na^xl~ZSO>IIV+zD*^&@3SLMPP~!tmbY@rwKouPqAXwbGb*cuBgdb_D^EPkoA11j zXdx{lop>zDlAo5sj>9P~&S$|FAMnF>1E_0iLVF%r*@g7z){TXWs@QGMy%;vAKP~Mp zJ-6=fKZHO}`CrFxWoZjb+dw)wIi1;MNDsdJ=uNg6SjHD${y=G2XVPtlmCLIr%1@)B zXCGAK8kR3xMyG--<}X;m*rU#3t8OKPq>1-GoX7BOdh*gMuhW0vHe_amfjCM+#@S(k z;GwKI4UH{`I3Vq`$D_n`9LtN*)Z9wQaS$tlWm!aHZMfQFW6fGZmSq;*;^Dd)SH$FM zLJ|o6>oo5c`xEU?27$qv(|GojKnRcdpMS_z*WX2_PDRw$)>2V9l#4Gs1Keh&Typ~( z8|ul*@5KHGjHdH$gL&<>*IBh@Bg+;oWRC+6A=<;$!W*x@Mdy6zedfX3 zdfUAW+Fq_dmvKZ+}Xcic+eo)^gO*M{&rZBf0J7JNWXeZ>b!#4NHIgfnE0- z!I@{D#fR_A;mH@@=JtmkCN1nkBL%i4KpX4UY~ZRZt|y9xg-2Ukl&fyOgI=W>y!6BX ztw2)01Kd0NZF=_XOI}Vk=be8RUw!%spUiug)isU$vR3oxJ=1XGt{-Z3S^WLCOq%f| zvmU*h&pw{Z4?q4w{kj^Sd;L9T{_PPC+Ghuzne{XcjjjB!U@=FXd@2VYGLAME=Fa<+ zW$Wu1G3qZY`Qj7a{owE1_xO{1{^=*&c++i^bnQXS>eUS0c`yEY&S@-P_$B8~o=(rf zJJC}6GaH&M?zr##K19|wq`*`Ea zmGs@JlKpla$jYA<@V8e!Vd!={vD4PQ$lQGhmtHjkFOrYd-a?C)!Sv}@(zVED{0V1J zP*_S?w=#}BH5Oz?w1a!z_-D3Z^rA9-95aEncF28m<&6i!n zh3A}s*V;&7NpDK>GeN}=C0JeyV&$XpNb_2-1+YWJ9EA||-+L1IoaRJ;2wBBlIQ^W{ zx%1&y7`6XsV&bsfZX=C0Fvj~FL8Fv|i^BFicG-O&F1+Y09)EcrS6uV~4UH{W;S987 zu=~Dy^Xwb*xbm{8Ja+fZto?ZfPds!tx8HUnnK`-K_rTxie!w0klHtc(5R01C>$vN| zr)g}pm^k4iY+Oz{?kM)!eGlf&`-l~~F?8pB$;>Y0 z>~sH0eM2h~C!B`sYWfZw%ww~jrnsUU--Z9@c7p%TeCij$!479}-Stzs;;Jcp`q@Xs zy*Lvuy`1cjV#3799C7>+j2StSgAUw_D=(ag6;7vnMSl(%xer+pkH1bjkC``3=h1K) zX`u+0Uw8}|K`sbkQ-G*E#IjL%y!iZV-gx^xVy&&XRu)%WehHS_#zXhq!8hOiK)dG= zjcLv~?|kwy(z*Y>+xX(s&vCU)tUb_6DVH_!7#L_}*Xf1GI% ziHVM`mg_D)L5@4;8fk5-m&5iOCYRlCyEMkzB-&ml<3^5?dGEg_FTXlV4m)mwY-nnc z##mh9o)#Tz6whrJH`*#+zx|vXHU4zjsI^R;JW(Eae3rDh?Q+ZIC(ETb-z^(OBNYHtUH2a=bLM?5KQH*Zbn3OWEZX2n+-nopT`ZF( zpDz!*__3_`@e?^--i0ekBCE6$4rpM#^v(F12@QNXH1sXcwAzQ)pGJ-Bjn7> zX2{B_#nQh#Tb_M)uC%(YxUMT&$Hntn#f?@=b90sS8M>#u@bXJCf8Gnyd+7eMdi{Et zKksGPYwRhqz9A}Fw@6#VDj9#+VRG7pNm3j4L?kY*+aR9TChyFCLe4tpeAyU_%PHf> z%e(KqEpg8iPrLt*z4MNA-(sq*?Rjq^ZfppbMD#?%sRuoS8XO zo_WgWBmeK_-^tliPLzh0Ei!iGXu0c8_ej>u$;Op)KQ zlZ=^ooILp8Uu4nSPssQqPM0;?lHz%u_U1yzFv9dmHhQPcI=SbZo928t|TMbY?CCDO_E3?q%E12jPHxdwMt8}Ra$d7 z@%?6LO}0oXlNIqj5z``>Y>PA|Q<65}v+%|9jpTe0&kyHHPJAyVskUZmYipC8ZAnRF zvSPeO$)$HnvMnLLG2&%fCDFW9TGLtab1kxc)m%v@T4l|`+0v!9R?htH_0r~f;`>dK zPHmS|I&EiRu2oXWR%uNnq%oC}jOUAISHk?-OM2X-W7-e3OxMx=j-4v>0Q=&$US^ zv0V~vEz+7yNivhQtA)u(Hrpu4wkAom+5XLXMtqU{{P;Ah8unlM^FZNw*~>mGf+W=UOF|Y?4GvizIV7`&;9QF-b`!c1j|VuwzF=f`Y~P zzGN~P$!2rGoqfq=+a%G}D2ZfJ5}AyoeG%iQB$IBIM6ykq5=m*xWF%>P@gyVJY=b0| z+oh$oMVeD-$rvNP81W@5zGTJN6+}ctrcIkBbLPzX1bcG7{3|5X^WJ#l4e4MB6eAz6 z*+3MC6C^I!NV(RQR<>>2&S_)Df)gX6VQ75?t=rf0!TJX3`VA*mR79}@T6|V7p2KxF z{FdgN#_ZgTS3L{_A|jxyW5cKjQ74Xzp>^kWF8JOrm~z^e88f&S$>z1(a`PXU^WI{# zBw4m}JLyywN=-gN#nB3rwQ*IRmnPAiCR$QTQKvZCfw9B-K(?9n+Z!=%3CfA!I8a$z zN<8Y4%z20tp-4IH+@s(cW2t(4!^&0b=skQAG1o=K97c^8#Ps>gS-ZB8R0f8O8isKk z9FwKBaWgmk@)i~>UQDbw#+Gf{NM};GZduTuK^CJHaw3Rlc=W#e*_w5@^=H>n;uz+? z`YgY`<@Y2hCbNATo%U-C*Y5fdZQ`VI(0*;2B z^<7D|wvfwt7;LPjC&1tr6YURX(CgQp-#pN{|Fr+8j*DWL0dpw?UKxrIp z>s}mdZ{QGgRPeMzYipLes<0u3WHO70A|8$7;ZjrEi31Ov$dA5%2|vB|8pe$nNRjFY z@1)wj_RB{h5hAXG>k1eLw2cE)P7$T99ehfaP*M~yKNvwwoT#gD9cyVxY~R4Q&pm^g z^OxZ(7lH(((=WJ~tFHWCN{VAdj7PC!=^_=SxQ@n+Y0LT+DW=$ofpXZsb~#5Mb~sy8 zLdL|X?>meyPB|9Gu`bG3yaXc-h@f>5@wgLMi9MQjtmNFY&*Qy?tMG9UW$>Ib&i~f; zx%$%ci3p$!p0enGh@!YCP8hK(Dnhh8Mu<6}0h}T`uH#WG=Q(JxR>o+|wfLcca*Bu* z#R9gC_7+!{NTdSSF^IBIQ}U^fX>A{;Xp`=u(FhWa5DT;S1!5%;kbt$%Eh6S%+n$e8 zcTmKM7sqXgX%I(fZ(&ec5s5^|)6t=E+$hCv3{<=A+eC;)qC{0la2Uj&ipFtEh`5#p z)%TTUHgpJ}!t&r<`{ln>IzYsPFfkvSC~TsKV;3jS_lXz9DeF|q%2lgzkC+G|tZhtj zOl23kCWQ}{tOnmh92fAJ{^;XWb*<;RE3RVWd$YK4>Pt4vTKgD6$YYxon#-p79d z%R^7U!Bs!|Io&%&aY=FGjkhsk+`)Y9I~Otcg{OIN<~$4#RUVmKHdv6fRiurksI-i# za+l2;R>6b;q%%31(@9DzijlNUU@=&w%?;YDMB9V}RahS5rR9`XMET6=r*rPPXXE1I zXqQrFJNTC4GEAKiF@-Ez@u{uu#FF)!0Kv~CSh03J)pfmal!F`KJ%(a}ryoLIEA3)X zWQ~oGv(Sh(=}0?KVyh*I~3lvdujH!W(oQb`XR5^km7Z4~TcF@lJ9=&@7(96-F z42z3u=VW24FD}H9*1I20K8GyKj}H$Q1%)R-KMj~v!VFjqDxOy; zbntx$p_QLADr|R<4i)m41&(Q>op$J@pXNi11r9HS4is{}bwR_+pG+-KMHt%{EPDB% zc$Gi!wLi*+$%7%oQeHv@x*g&I+R5YXT4>v_HkPCy6dm$8+d-Ni-xhN0W8VMw%coLy zV+{G&vx6NMe2408y_kRBTWr{JF5kH5yIg+b9TewUShwSzAxfnsR<~{WXj`upgg4cDP-z{2bl- z4rOrvdM-Zi8=U;vBf0yodpY@xuhOr+79|-RH=M98zOl=}6A%BDhaY>MKi+c}(TDdE;_ESh9vAjyZux{^w$D{EdsG61?{Aa(;LJ4fN?-!6~Po$kji%jI+)-i%!ur zeR_1p0FOQVI0p>qK{}B{i9>05CnULpg>&Absyqhbf#1f@uDc3VR>ihW8=19z4TA^w zr{AEV%zoz`2EO_V>z6Dg>S|(2(WgfpQ}6yWTUwF~=+%d;C^EQ|mUiX(tA5DsH~)&p z#!W1KdluDQx-hh71*^Afv}>1ltu(&L*$qd+7(XR_001BWNkl8;G3GoQac zcn^+>B9g^%!#JyO3C@Q)+fYe2O2i5H51a@JLj;93*z9nkjG8!^p*O0RMH+IRPgFZ79CF4%YlG`J7#yO?vdB!FG>K;(dxB!8h`wDS9Cym+`N6e6 zVdu8>Y*@K~9W6-?Kkft?w=4#g!H7)|TE2V%U-{|}_{Fb(&!H2CgHpuHEBW3PKjsVP zTtxHEZ5)2kXqGIP!?Uj}D?)?+xMMW6j z$90^J@sa!G9}*EEl}zHeVaikf8w#6sA%C@SoY`IM7Va|ifC&_oo7Z0; zcTITL@Gd^0iWxHUpx~1r+04u0dwT*73TqJFH_q?_#uLubu>J~*W0?O%hlYfdWd*Lr zuKDO3w zn57-YMep+45codCW3@_Ipy-K^hl^_en_b3R;d5v|LJEHeV?vx=t}nz3w||Dd`Fri% zFaODsR|2)xfA6}FOgsaQF5{##zD6e6k8HA)&rSI<n#IE)xQ38!m^EINS53*_9D#`~B$8}xu zpp*M0F9lU+-#R8d6hH9b1Gu`Q;!%JWA_z+eHc}jGCkw4R!PQ0u)qPRndm7)mb%N~x@epO{+U>+H zxRCOb8G|1Y8R8x;>_(x7ZCl5#>&9J?$P97QT0FJw0{oqv9a z1m%Xc4;|_n^1$E(V@C&l-~m|+yscuv>ZpQW<`7&Q6pj>v1yJqVCj?xEbOeyLpBv=_ zo26J6U$FW4N)?_#ev=M+HV3$Qt4{b#eVqI~6&}Vq(c6tbY+WR4$869SVa*GSC++Pr zwxtr3MZTQf9^!wgnEbz)Oq!+3R?@RaPxjO~3l}bA^5n??G&D5u;DZlx<{4)O?$E-Z z2}{&@52*ytB(PNleIG($b)W_e;jucf-n3tWceOa~`q}Q%{?`FZFv{4`NPE30xKPx- z4UN#wUbt56enEaLN}z~Pm}j&bi-Dp?py>FjgI)3Ow5Yv&dIt2y^&5F|`ZO-Q@SAyq zpKWU}DB4vuRNwN}Q6>0RMGWEl2?6O*9aaN&E#>cj)_%McM%S)~pZuP=3!5pxi!Z)N z@7}!`GiJ<(>W}^M?JW_WTziiO@$g**Z>SBY~+oWCy{Z+nrSX4hZJK zDR-al5vpLJBOz4K3Ziy3%LhkWE#!Zr+I?PN?+DHI!GiT6y5+;F)*r?TzqhhGFuCQg z37IfDF6Fxx5q6Q00)@QEw|&oJB2;b#Xx!Pr4cGmQl}pwkM8NpySP3Vdb0(*pe5{2$ zkkE!wuv+A4tM;}162z_s|7nCj-+2d5J@OO~2W6o&;eqcoPWk9=%0PP zrBy-gCT}_{sD*L^XAbSh|!YIqr z5*`sD7&rL`)G=x1V{1mB2(*`I^ixUFw_iR+aj$>meE^IvIF7c+_iAsGc~7#p4X?ne z8nR&IvRR^TG_Z_#Xgow*jEW%Iw+CubHpn#uRc){Fw0|EiA`&j7*+3c8HoGkEc5wox z2ioo3)-|I7v%M&VGAi%>KtgwiwT+p)CGpd}qZW9Or5!b#b<-GJBnT*0Qc#(LAGQl$ z34@b^6REUQ)b?-^4f!qvq4T737<*_O-!q7KxC%CiaMR=O;fiOiAAw~pw6Lns&h>w4 z!QuBBF&dPID9>)ToyRfm8xzn5d|k-Symk5lY)p(jecR1EOg`E7?KfQ9ZT)>vez4g) zfP)G%kyWtOwO`LWr0lA^ksvsR*mo+M=gJN(jdosXODUKC+fv@`mwlCj>ryX7vfzH*3}46gCWMoRHT6VkB#tEIhS+%Y??pxA`hIFiQISv;cnDjFye zR=I8Owh8PP_{PJDS~|UW#37sUZ2yJC!0kjSLtT9hRYftDEM7v^iD6U}6^-C3Aui2i zl_pwL%%s7+c=NqwB(j=fJd!Ak6U9+3o-rR{`3qN4>sr$&RLo&y|2np{-9qoyp1q3pQCiR@YLWI;&e8&kgEB7UH+eg@l+wE^YvG_3ZC&@` z<2c}Z9!kXnlbztYmiyJq`9va7%PyuAN-I3y1et>SF8?io-g`=Dli={D#Y0@k=As{7 zi4IM)p_m*dxtS-PnN7cuhcU8WCsID>NQ|gs5WkJA=aZ8-I8ove2QRymjB$Y?oLH2& z)_Dcu!`UUY(XmUA-#KL$!jc+U^rBXpQv9WX68j0O}aDZR}@5r9V z@_yMbAD3vsNAN)h%AYD&cmDBL$1)11UW4&Hz))9LMtw~Mu6Sr|gO!aI3-zLXL>ol= z`Il+`xAOCr7av0=m!!HssDn6_#bJIbIngz$Y=HiNqot zHK9LcPS)npYt4j1MlfV>Ukks2bg0j#?`86Onkc~!T#TKoI`Ns$9!?}0u?n#Y6l296 z$_VLnga*-!7&+(vK!5A*DH_eN=47wPB^|nMCX-7*LC^a7mlE|t~+`uDA;zA}m;yU*=JSDHs3%P+f( zjcZnO_Lt6~TlZcJ9eoh*%vI;A;sO#{qm?)kfovwaj>aI)D7b9Zdb} z11ws$f}D0hr`fb|8PB}*8rguWe)0Qrxbwb;*wL1;7Su47@ZZ)nx?lcXMO$S`F!=Tr zTD#<*eC5xd9S5}-KXA1Qcp30bfESm>l?0AS;z$xj&br;m;7Afj5@<;y$^(_dkpzyk zp(Tw{IYd0GV2ZG0(K_CHXPyn3_cJ(>B4XNbO>5xF$)Y5UBMDqTjca_0<8j9Juc4D9 zaQrmN_jrHKVpcC-iSay?$>K=L*3Tr-lEy}fWzmwdbu?{gQV`V9-p3Nb+n8V0X}w`Jw>ZHVF#AxF3BQuG3)tP*|B9iN&*+K2e-pQ0`=jcnMrTi#8tGq;X9G$0YL4z>du%u1TOJi6Vn0W5+2u z?9A|~?^4bejvB$R`fAGY8Q!NWr+nrB>O03#zEAJ26&yUI3yz0_b4q;^MKkjnN09k9%A+XG%sj8{ql+#XS^tcIZTKhhC z-f<@bh9AUhGhgMh|NSN}&v=$uv)<+2dmrYp#~)z+c?%GW@oL{^1G9txIS`u=XM!3Q z?)fwr)OYDvu4G7?wtA~|2T@v_p=D>5S#K_2LyKX| zh=GhB)dhzXcu{7)^*)Q%?4+(o7siYj!1L2zq16;)T!&6&E~g$fj;b<)mvdOYVmq(S zUqwqcM{So1jvqgU>Q0Kr7Kc|~pUdio43*WL`NF~ds3;d!Z_M$+E6d2L9FrytWk`=w zToGP>XD#!WZziK1LelnpP!8u&4_*_3^?~l-dmUE={J{h@PxsP>{W~y&D-y-=ellCAiAt@Iwc4 z$RYihx3Z0z9_7q^Z5>NCY$0A=!r8}-;jtO>*_^QMQ-uz!jY2f)bJ(~64DVTvpeQjh zJ}@4x<1oB$6%&T{B2o++R_^4rxgSuZgz7TIMduvJhNR~1>GP?sEM@ZO!BkfYZB0JU zy)=i0oT5wT5{{fWoa#!Uv03r*%r}V(e09nw+A@a6XS`2CBE=CC$I`dfC6V%Z6!C5?&wLp@XRbWwb{)u?syzByf4d_ZD#hn%kXuKoZ7%K z69+SKXg4;zx(?+F%CvwFj3BE{95b^e81cICxXM$^oG=23od&5bNtv6g6gJzqKR zLVkJKsR*83c|9SM*vkF4-@=V|+($z~_`<1Y@uRCRr$=>p04beU<;b*dW!%t%*tnyW z)|^jHqI~C)Z}Pd%9>>?eb_qA#dLyHT_2UQM`W7=^dyCSp1G)K@TRF661j)4UlMBw| zhKsxK+uvP5zux7Xch0xjwxfyqL8JKT4Zq@xNA)5qN!BfXoyxK@CLDGQf0=q07oBtr zeno#Cnsz^T|NO^X`m1|*XTc)Ornk7{k}H|}{st<#^yIFGA7J7E{fPTMTH847ea&?K zC`EzANF|F>S;S=d<#o3ZFYd-KZo8eD@=_En+;{)|+(wq%mkt5&gn&0;!5H76W4 zk)BnhtoQBd?x81MV{IzR&YX*wN+Ob_G_E*!%pjJ{pUiMaWBoIkIqA)C5)dih=WHCX6}1) zIDXQ2RxV!83u`vgqeneQjvvg!vleo|h#@qsU&)Mli^#-lNu_)a8b6TgnBn)ioS{%t%&mO)+vvPtr||JTvPx zyl5v9*&MzRR<2I*>~k||QpI@0c<-GLSTVba?sb)nI$#`27A(SXgvQo3Ui;e{NNFdg z95eYpfzDIMD@ZbY4(co5Kl*_~s1KGCtJ>J={nQx}(ka!VQMVcob{Tti-I0;|# z*1Jn+P7A&`pdDQ0QCD8f>$4Yk~f{H{~xo!u;4;e~CuR|l$R+aPl$-`K%cr^=` zZ6WKFA<8KvndT+bDE72~|K}@#Kt7&ox6cVTwnCo&hoQ+*D84p(3E3zjZfWyy}jT9)FfnWr9mfa|XN9bdZeJ5*MdbIoU%JBU{CN@Av(&GuUx?KM;yeY34VhEBX1B4VzyMoB_4C=-=~=QvsSaQAxE2^ zU|>T7HC;R5W`)Got*qakCgqf4Ob*BOIbhTf#tyASa*%G!5jRH0B_!)&bF&hMn0Mel!A(1>r1?E27$A z@#0l9MJj1tx|-o*`_rwm0@q8DRxx&@T$1^{EX}C~n~V`a;V2QjoX5_z zp(&Xmwx)s4kM2doYKIEfW#O{Tv}7YREZM;L0rixZL|L(7Ij0>ugmk2gH{M&0<9H13 zTTNYUl>P%wz&H@`9EzeYqzix|?eo@DfO(??GN~-v6N;v669@Y~ol0V?TeFVgCyr)p zZZfaDH5bta?I_Zo(Bx^_V#PRG7&&qn6Gm1cfSYkBbp>BM8d|e#*y)jOX=CxS^>po0 z&Z3oD?U)MUOf5@?MvDa^GRELU;-r0-?db?!Q7KE;>|nxSed%26(zkb4)^FWLCMQIq z4!(Fc=1Cx;U}Uda-e0nk)!Q?;<)!S*8jKh^m$~%mUP1rUK1VXHC`HqGXNGl~8p!(4 zCNUavn&J{o@A@((^qfemhB8;t(x#}as-Vb?@%{(P*qAFL8ZD+sTMWhKOpJz91{D$d z)OF>h+4I@v716jM!9l}w4D4RT%A|`C*xq8;VjOTai&kz06$#l0akRq4;295e6fxlE zJkn___cb0yJdE#CQCdn>bth!SW?ZfCWKX-EvI@yRozS&kb`#0bv~?Zt&Rs_DLF2jb zk{^&>GL2jR_%ORG-5Q)SdJmbvnO`~$Et{G7c!o%P^4F~&y`0jCqEeD!=b%zc>`o_vDEOO}yY-AGFk&N%;DoN@e6 z{(Q@CPyukE7V8G~l3SVm_FHU8WV!jaKch*LPA6Htd^K6mpkwVbQe$Yhg3q3GB6r_< z3mZ3Y<)WWm!)J~=mQq)E{+Ve++%{hI5&-<-7eD8JFTawmHC1>Umx5c$h>1sY#+gSG zqnTOHP3O8_+(^@w22xoV7_G+7`4|yk{gP^4YlSd^Ujcjlk=CHoSXUY+yFrqMC2G0*bd5w>F4!$QA zdEWyumKsisPsE90d?A?%Vr`7U_yCTLzJ zjH9(>6>y!<;KiEtJNVNRZ!&IZSI#(bJkLEln{2X$x86V z^r`tjifqPmTscaS z^@J^(cCe+f2mO21(Ys3V>^ocWR2<_=kTLEDhh`y>P7{koakZdK7FP+L=i@7vWow&x z^@UeyiHp}vHYsL zi`iW#0n5kyUm$zUs0=<1_2UnJ&{afYaiUR8Te6kb))wMU%<9|dA@*wOsyk6+>T+wWq|O zM3o|nM^P+_7GcM>on*3xRMw+ZnE)`sV6q9sjo}oPqTM(b{NRU-9^MnJ0T}8isy_k5|XL;hWyP105U-FYtZY)MFv59mdO-V@% z&_v=9nwlH&42X6?N5C!S^sj!MF8zA(m%Hxgic2nJOPg@n#b3cO1|251@h?!H6c}Y= zLQy4@lyznDm_aO<`#Q&;a5$wA2PDIydGl$=C^~oVN#oXy3>-6=$A5eQ*In~tetOmQ zTzTyklodtnTI+=1{`*zI{qo6*2GCmJ8~+nvn=<%b3L!@>m!qarglII%g2g)+KD-P4 z>WUdNpex-vbz;ZXCf00fq@+t%Mh~oGU}r;*^1!|6%I z(3Z~8mPv5PL8BR1Tf|YL2Gh1R&5pJzhbyke&Rl%GEtJu&cG$cKa7(bXn)rw;$4kwXH(bAHjYjp)Bq*%Ln0giEq#$vp^ za3$S)*3hF$Q5DZoR_x-La3SybvRT)DK2g9ZlTTJL%DOhX)l^U(&9ZgP8eBg|Wkn@z zEor*f#TeYJ69cM>aeRZLJzT$$59DG2%c~4CRU&H z@i4r(cr|?n)pJ1aQhJwqbaoV4N7=kJMNw&-LH&EtDQc*%u0VM?(#aG~90vEPVsMvI zbk3)tsgVQ545PYOs4I_BRN2c=d)W34i)W`9Rpqv1zB!~uw4C&@geE+-OWBtZ$ zY+1jCi!Qv7zuY^OC!T$pDW{yt6Vs;g_!EzE%WZ!m=NI9pHLcC9L@PScvwJ7*yZKtq zIrE!5{>&@rqB6E^T*vfhUS#>YZ79b9r;PsndeOFi0q34Eh3{T|4Os>&h_+%yYa9EQ;1f^qKckTCh zW9D>j{?)H}^Yz!ccj{xDdEUhwcf#lB)29bu@RUnU_a6M}m)DWrw1^*Fb{&ZfING6o z+Rc7@{(ku+#kJlgWrNLi;I{mT3J(FF!%zo7;YM71C%PcPdc2OffXy8$*N+Ot!|;u z|5g=tU!jf5YiF&nYjcFMtsrX}r@ zQE}pKgtC$%lra{xRje)0bzCNl8-aEm-v3}7v*#}*=M?eevvc{}q!E1f`0;Gql41Ib zZ_%9b=s&WKgNF@9`!H|eI@axICF%LNC2N^*&;dlEngvUDuwmyi_OyItMbVJ)F$$8# zr_qZL#zi$HGo*~BOI})gq_3>9&*O11K6tg{*A(?}QhMg>0-$d8m^{n62 zKts-AMlM~kmI0Fn^4ZTH!aMVKuyscZYqvCz_BQY)>m15*eO-`8|%GG>ReP2e5qytl9DgJ9q5lBH0u?_tHYLJ5x-1{wyft?NCrlbd_ns4(_2vh> zwQvniq>L|o{$O@Arg(hDn>6`RDhzB-rO9X)BR*({veII-!e*>0gReF7mu)23(!%5e z`!jY-9}=y?3p3wk^|m%75+~_FLk2u?*x4pL`SLub96g4L&YMXzraM05!USX2FVrV* zC;1o2USa|R$e<7)T+4@B-vk%Y#eDzTtEueTl{@Zzk`FeuF!{)18Q7;D#dhlIyVJQO zf*UQTYqu_R>Ez%jKo=A5R6~9D&P0?Y_H)F~C#M8yb3`h;bKhgr`TphCG5zTmaLa2r zcJeqJqLg&1q({#xO0*$cR7P!&9#oc>(0|xaUVQm!etr7`q*G}YEZ=||EymZSoO<3j zn74EziB{o@C!bE&BEwC${E1~BETT(~0mK}ODJaHA1>ELBgqbaF)@-D)Wfh;Fath!6);W|`#JKwEE4lWDTUoqt5yu~Q z2oF8^EI<6-l|1|Gi%?X-(Z^1}i57ACSzl)P(v>_p^Br_)7qY%^?zb;yYeNfXa8|Z2Y6@|W#GtB+pz(nfjOiN0+WW_~DPQ;iOYfB&u48#Y(8DDnTiSs=6Lrb4hVha>C)e zl)Yc}%O@x5m|wjrN-KQhSx{P~_Yipg_e5+mNrzIQqa{Mnjzc<`Boc|*`ydv?HP7(j zbwH6f0mrR^fSS_-JWR0R6_$YDJg7pVa`J)SDugr0a}+5GglL8WiJ8VI9h~4LxW7Y) zb!e2upVJ|~BM>qIs61$aL&!vefS-3mDGOMv6qT_YCmlMJM`pZ1QsQ_9eC;C2#vW?p z7kEku3E+bkNk}s9fU+k?CDx+mOW$xKzS{cDY%%i=hWbx$gT5}%Mc1PK>W3Hl^p zb`JWwJHAfpoJRYZ}x`eSq zdh+Hgud_K5MRW|U9eh8C3Dkmeg23=x7Do&gx6iVX807@@^b7S=I;dxuC8~oyD6qm5 z`aF2<`Db0om=B+Sp5a7n5|ZS98!|!!4AsiI_f_Dk6&(`t*`h6cM_^GE3F>JrM`2%w z9L)-Y7TceuUF6Z%&E+Os=2p9mt>?HWsL;3uaaME~y9d)#S5?qCsN=gyrx z_~3(Fc;SV?ob1RlUf>V*^Yf+fd{n?DZPy+Na4EfH3okzVD62PZv-1%RL>YSESSC#x zPmIECBx*13cimR?uJ482(&zV976ie*dEGNuLZh&4 zrAC@I;pa4tb=t#cd#dG!DYu}m{AbJFpHC16p@hm3d$9TNyRIS#pUzAExhSWwh6V3~;|1+Q z{xOhfY2ptz-^z<`&c{;$pRkVbtxJByA(O`E=T-qh(8<>|gb@Ky;?vgB%8Z$_cz5|G z;<0khJo~GB^DAE<8n}2RUrwPORt$+mGdKV4M&6vW#9pNoqKo*>_kYCX38R8JZ6Huu zI`)Iw!(YxWeY&^n)b4HC!|(I84d^;QEsEdXW!F9~d}>9v`#*)}_%YXNzwDQN5%-T* zoJtrP9Lk4fv;4nw#`cr=!^Au|!7E4M93Iy1A1Uu26~#Zd5Vc?2qrllGA3?|(y0j-e_Q6utgcCmdHrC?+5 z8A^&H^J6ybn}42#b-(ecC=gDSbJOa zKHX6%y7e2(-`<{wQAO4}Acb`?44v5X!B10F)0MxyF$ZuFoIIyfN88dUs;gGjTw{)T4}dz$v(CQDmLWgOHDH4IeR3Qdr4Q7CH zV~&<|k)k@AxfS8I+VhF;>vbZ*3sAhj5jl>*d$n!7@mL~!J7Z|B6_t9u5z`&-Rpugf;!@@vFT+fv+U@ow z49>|B+LHKD@+EGMr=)$s^LIasb}XwN?1N&_dd(F-FTsCNB3qdGje?dFxd(7l!RWvj zA_uuESV=1GBkXTwej}{_d|!J>@#n}0qz?2!veZUATG;0_kt0OhKW<0(i;+;GO-xW5 zyTLgNZ0gKqb;#4X}vVT3DimNeuzfFJ4Em zXbA*(Gxgj0S%IjP-cRoYlj0RmzG?Dh-q})T+cdsXlugSrd3?A=U-d44K}}@-Y1g-& zxC8a{wx8(3gP-2m`6q<`H;BVeT^n0F94FLImEDp;1%~k(Op<`FJiPguBIjplh$c9q z9P%eI0woX9O091Ht*UmHexX$P&!5;ZA`rHA!H^q@03$7!P>voYj}S$0!QosE^Dllc z04}*`irwvXx5^eTC*xo|B8FpXbYi~>Ix1>oTY1%fqyr*UAw^&$7%2tOFzS|ydUQ1i znTV)h;$b$XY3Nu%XVuyEv$)DL%t=qH-OfJ1$MxNt4|IWfOQqFzX_5EwH-JOJfRLe{ zvFLEH55y*j!GXaFg>EGsS?7LLsO^e;shPU%%zssgfE8nP`yIp_rcQmsaHeI7haZ57 z*7Mb|azVuCLTcOZ+$Vdi4z0YltFDW+C=g`!eAp%wDApH6=e<`DMrRE}{iq_}&h7>5a%i5xRdG-dFFz169rFl!66B z#h~|NYn+GeoZe4PkGQET+H*{fL~pJRV&9z!J_Dd6EkRS+`-4KK_JcRnzssl{=42sk zk_&M25g5W!mv_l((}p6+osyh_cE6fzrhdOg#`SdaFIe)xA~|8)jQV@Hy8Sl=rCU13 z7v6fS&184cNMe?r)bl+AgY5uV12WCF$2}|B=Mkus^ti=BJ9bhTk64fM zcU#ifLax!sb`Y3MKkQ1J@n;9Vdhee28(dd%7+yzQG)mG6+O)~7)&v7`L)-foM7z5^ zI}8eT&wK24x94n^jh3lQUMwQrVMN8ki|;+&FI{`a1G}DdeNj^6VYxnMAs8%<_)dIx z|F;S#lx&{yY{2o|Qf9L=UmZU(IloZH%<*S0&0aJ6Hd$|1^!pXItgj%{DA-kpPp})F zZ+p_^H@fzjS@!MQWYt|$^Z5H%uiP$0sNe5wvDBBcT)Xe~5QUGN>zNNpRz{whnp3~k z5{}EP?_7qj?w#zf=X?I0pDz9`;Dr@%xU!yBg@nYt@=Y23v`szo+ahl%>DtxaQsrOV z`HKCxq~Xss_HeQp$Oz9jT|X$k+UUy~CzCPr$o`q@b=8sM-a8a;i&E|SDb{uShTZj7 zpD*TYQON)NDIj7POsAjQu4lSms6SA&?(RK-cvM14|2mZ33%|E~>sK0+*YO|c^5n9-T-hP*F)Jz8BH50}!7$hQ zvyCYkcWWwkZ3n{VSUmBfVH*$6vm|Sc?o9aY_jCrn>1#K_MpK@#m=)drY)<-kJ#7&Q z$V|73{{7Z%)8i!MF^Q&jqeXQjB`gM`<3^ZnbB5bnK4WbjH6177#!|k~R2RL5!%r28 zvhWP%yix)3`^jp|Y#!ghQ{}Rv9Hs5=7v;?6tMO`$nb|6FZWzSaVW`a@`y?^58FaEx zj4wZ;Cw~NC7{(!cuEGuoTl1_&e2`_VCZP?%25gpM@w({;OSL$8)flqt7hpb}JF+bZ zz0tpWYDkc%4UQJr$;iXEhbWoHEF*xpL6Jh77zQ0F;^u&O;Iri_@z));zcv$Szx14e zzuGv^zC9>Ef5GgJPtcPs#Y5^yIeaPlei-nQ$6X9v#{q^Sl>Tr;TfCUBci?V$Jr`A1 zN1B<=ke>wKVt!%C?_ddsF^Yt@6~l13o=?Zu%BH_=zB^ycCIEkW)nB*nIPJgC(XhOF zhr4ohT(Jer zcUs}r^4f#*U#&+eZ~u4z_=|Kq1G+u|q$tPe^*#VwJdYDDYwsqTg&bWSFCyc3#n#p# zw4Tw!14~lRM`yEZnvwsm-_PTF#=sJM;AXyWpgEp93jxC%b{<((6%xdkUlLeh?+5V@ z9d5S_Yy&N_8UykM6G13|1p)!8EYa#a8$H?&A{3Y~DmqwODEOJm!}AJdI-NCGW!F7+ zoAi&xZYSK|SyT&3&3;67C28?5_fM~fHf0&2cDLD{8Z;$d9b;&Ol;A>2Xj~9$NlHOU zB5jfio58*bNDs)b3x5JGs7X>11&5aAP~i&i>ifW5Y==1$?-8rP=AEZ0F(0h_uh|kn zK~poD33Q0O41p6|sx3kJXo--FjJ!aI)LeS+`L*q?^4wyH;r9g6%YlqHFunvo)`AVo z92p2GXdRh?NMiptCm#~y(EnCqkX~5K3goCx0RmyF0?XWnD4F`YDtJf{PGXF7kj~(~ z-kH+>4Nf&Di`#3|JI>D+Uvu zbs2#(0x~3=JS`O3q!YJ(RO?N(Nn!ZS5EaFc3Lou+1koZ-7fhyd`sc4N)A{ow2CpX^ zuH!`)lUkxIbhte455BstFSBG5#X3=Lu4dbDPTr0B$3BDMO&5syKyJJC%=)BKM!Pwo zZ4Hj7$iJqmF>b`hAh8UL%^Lw$kf0TP0RJ77xpe{dJM(-O9tSFk>;`)r2xSh8aY6G4 zlV5+GL3Gxi3VjyfFC4y%Je_1-L@VYS@Jqe}uu;J@Tks;&fNPIhG5haHZ4$KkV zmq>2|>*;W{+8rf)EO_M_g%gHi82&uIWgu&a0~LCw;dBVm!PQs6!YO+8+B!6ZsKC(7 zBalL={h?o)f@TE?;5P2(9}awnoq|NG@}-@V@eL$aY}AFbf7uJH5`dUr0M8^u6sME zWgZaX#`1q)7j7Cg(8`MjGWi7Bp^qvx%N2GLXzk($uv4jTcZGk03WIC3fAB8X>;w$l z4AYKPYvpO#VoP>eZAa{#?ssm?Z@2JnsTvT$tauESC6fm@V=xr1_j8r} z_Y~MATF0dc0RxWZ>ogD?+<-TSxlG`WbBPRx%VUU7Kvx8zn44$zN#yfyDt< z;S}h*9w|eC4k46XX^`Yt3WnRH&}9j`fGQbf<}xV(E9pZZkjZSl7#dxd<;fy<^MzRu zH#|f*n?M|I7R^7eS3Rd$5JJS> z8ZST)yV$gtH-oygHFJkP--`IArTs_7KoN5)lQrhXN}#Za%>}FJwsGdWjIglnJ1(&k z133D>pUvJ5=DciNM^sUy$k;TI^P+1}=)bft(oTAZVYNp$+Xrbv?JyP?LJAs=$phum z2BVq1vyb|+h%zhhJHQ6Nu#a8`*yWsfp79d8o;dAV9PqmR zk$do9lZAYv;XlBYo%3V)X18czpgUhNlEb>Tc~kBFLJD=p+hX;Z?~XaTYjC<}=|e9= zSs8vX-{sP&xWd7+pSanZnbu3E=i;|k!5OpoJ%8L$TFWk<^Xg$9&v-%6i2Qln@*KUL z-uT|(E%D(ox+h+>+4Mg@x75d-?|C+J>W;EeqY!R1h^7#$z;eN#Xm5O{u9*KjGyHIn zDv9yTvVc0cool+AmO0iPj^vBe_EA8NYQkd=uqv!ZOvE(Xi+@JNenH~Lq6(RZ3=0B} z+{+nK#wgWhbSy(R1sR3Sjk^*H3Ka$e5h}!Ps35@#?f2;I+JCs?^;iC-uGmkYDj}sp z8W$-@5%V~hrvnTvySrX&7vkn9*;%OBQmwXFTaO&?76>P&q!4To?zwML4semsBi?;)mIv+-2XKS!F6k~(tp+~B)Ro0`nIj`ECkk_s_ z9{i-4%;x1zm!x-XLuO{dTTXhHJp3%lMkk3 zS=(b_L^#Xv;n!<(X*NDfjL;kI>gr~T#L?%Ol~0Rd!DIfP7huZ|XrlKcfU0E9mGMAq zXLRczkF1#0wLCZs&pW*HnN=`@Vv_ zTU~KUk5G$ES@Z37?km)|c|F@~!K6S1tta+3Sg}{@o#20>m>zIv;gwbD9WK>qlnj)Z z&mFe?`HV};h-#SFYB$D@Yq%vQBuZv>35`q01C+7uGZ9xgO=34dSaV`gE;Yw?b z2UB$}xb1@{=gw>SQIa4EXf!S;0vO zHJdN{@^x`nTdl}l&Js0((B(PA*T15pC6_L{+4Eqlw)DmtI7MZwu*5m!aNoNYYf@Hq#rXSkfW z?S+sGVZO*^xwL|IHT?}&q3$KAE6=X}71QRdK>oor`Q~!&;qW!#Y`u|q-`NVNTGDgc z-Bp~oT-xsf79N#LOlO)@qgGQ;(H?r;;$A4Ur8;l9EHL{H7}^l^emjD1vRH_CYli80 zJr;Mp=9aS5#2Tc-og7OdU+Z$A7Y@@sjQDFckn&T4-1A8Dza`cmkj<7m2>Y%#Bw!|8 zml*}UXl!c#asP2%6kU-lv(hLuC z0$s0G5Zp3BPbma0Ik1^5RkN5fRyTUgILwG z9UL-M`pD1Zbe0r69+kmrh6oXh;&^swV2j206Da$U9r^d)UY8K`ojlXqwAQQd=Q9e* zA*16Vt@rC7S~eC$O*cw&qHXYeJb_3$YaWf!nNiZ;0kk}t?{EmbT%nTXi?t_E_APhf zb9NgM1IDX4vzNUQ8%TP~BiveQ$s*yd*Kv?i**wA37D_sL@CGXBV;oMv{?zB`nZSi}2{x;D#~l#BJoyt_)O$SRyBgcs*<(9RY{ z+kKLKBxK6Tossel-;uY+^HJW630C&4v2|E}MHQFGTliR$@2?;VnFy ztvRV#IZ|o8+zBsyU!l=7G4*tu^_Gk=WW2({%EYNGwwqnz1&UT0-SkfsJ-=sIF;BD- z6*Prm29Wlw2soTN#_NTiE_0~P{J16+tu(_hw;}Kf(&fxz@ z8iOrc6to_;+tOWc>q=74v3D=T@Qu%Xj52yeC4$&{99^#iILA{tK}V}J>TUj%jc7>0 z%tTRa2*%3`KPbtq)`%#1!q$8o!cX%JLQcBeYERk-c}d|a!vPbIVp6i3Ij;%#w{~<$ zDNtG#3n*Yq6Lw-kzMK!A4fT&Qenli`WaymzBeiY)_W+*d+Sg!>#=Kz(i6WMA$PE?i zwT_S~)W0M5eFQ$B2kF3u!*^)UZ_qaR>jprjVWJrP#g5rU2C)ftnxY_mx0F(P%UYn~N-(g@_(I8wJ@Ua7P)UqLF zue%|})3K`~WfRu>^+@~%k0}DU!j+Ish|cAS>q;_G?|89!gTd}^BPUA;4l0by*{Lh6 z=17x_}~_<-dO&K`#&#)P&o!Xw>STEkIiMlZ)|(-$O9b2wX1B_%CozF|Y~ zLvkwgHKnr8W)h!!9H4H09sb?^G`|gl!{8sMTC=-a+f8D^3aB8@BbcTj8LNA}8AOFS z@n%hBIQ2WV4}H88vXrvf{#rQKc9Zmq9H+)yuEOW_YAR9nE z2Y9-Wy{%vxC=f#Xdeou;Zy`RJZ~c+w=h8@OINILCo0chnmELa*2yjI;90`khP4N(m+0-jUp^J@NlR28DHLKdS(g@v4TTC4io^HR8<~ zGO9RSE&)5FblP_e2l=Q;@2R|J;o&m(H6Vr^o!MY14F-$nM`3~yf!O11Y{3ef9wNkN;W<1L8^iAP!l6^Ys*<`;(l=)3#QWfgq73* z9LHRUPnYXaMgJM_y?eqsMBJvw{>x#9CD)~@Q)O`k`lUp2Gdnb*@$q&Z-Te%I*mOM@ z?By3$!zwspHEAz&@#0GxH{+X;-GW=e(G?O24Kab3UP^L8VGV>UhGnZ$u;}l|K*}LC z@3m`!L+hOW`9dAyez7+*p9krcphDQIYv_Dy+DIx}XT0Nd(s z2Z)s&d*U2!S#n0!6suY+vAQQ0`&o0~UxdNP!^yvtBv5=cn=QoT4*ncZ`XCbb;7w^R zk5F(NMG|7iC#3W*lTzCU5`Z8{lf-LO(J5(t+XemZ^8sUJ$ z-v+-_3MGMDz(Xs1{1R1Ap|+xdc{2%)|qaXx;e0zr`UKA3H*l zgy2j>PBppw@Q{Uk36Y26NiY$1khD%|cj9bl@u_C5`2fgmi#_ZzA}AgkZnm;;vvs?|W{=I$^BX=eFtln_b%n+-QVnfLr=|yqsH%sF@t2cI&F>g3F~snL1(RxVP`n!3_ifhKuI= zMVhYXM2KlY#=4|Jg+I&!`O0v(?Y;doRm7CNs&TK%$LdxG;rv{l0%{H~o>1(O+ASEEa2thaH?BwyOdiZsz}?tHq+( zOp}^RUbUIA{D{o^pv5aVg}1~Z#WU?wuii^#Ft3*iS6_pVlR3{!KSI#aYJc|wzB{lD zHyiO*S702Tdve$nrmT_>4ut$+AxZTPQ_{#H9X3TbMeFA6r(>S9I~ipHMv) zSOXabnVDQV|M*(xgBW(5sl|%MwVq3c2+D}2i}|ec&_}>}mfi6c1fJ1FIe&bvO4M}s z%m`Tml@`-YgMsyWa~%J+FY|&apJZ9;4x{G~Ym@mxE;My4#8r3fr19yMFtA)aF+{85 zR!!W^?Bc7oyKby_B)BFt%xQvuAPCu-(dut&HGDHrQ6=&pA!=jhf;OI(jOL? zA@f8eW1j+u{2UsFY_>-`{mCI3xX4LzT)D163lE3(sr&Tv}~$lxFos8WqN*(~6dKJJ;k zC<8MQfBrFZWbYhq*79cXc+rW+9nUo@bJya`XL@E>$aL7@Jf4x&1I+pO22B^(^BV8& zQ-WP^#P9DgmzlEY`CgOJ0lmXv_&qUNHfQ7|s&H{XK=>bSA4Thxru5}{GpF+*29ZM6 z>A@9wK90{L<~%qLmzcqBJO65K{W zHC?YJ6oawLkagSVW4}65aJvLpg?SZKk8c)BESRQ&~e zZl#ovY5H!N+O@bbi@7rj~V(|xkq2lnRpXUjmGc-gvsFV{7CTO4w zgv-@d)dGEB=^9sPC!i1>7eY)D7m@^`eFO6G=&73Wi1cg+qx7o0TmKq6?FnOYu6)N-}@gC7m=fW?|;D}#F_m#=qv78KeefEqh(ve|&^?DEI$bVF=F(P*}s z>yZ5&8A-+A_(GC1V5m0D&J@?LTl#d|%BLe%x5#*G{en!mKHLR@i*_aaI} ze&L<^#@>7~E0rPojP|P898(-69)@@40uuK%X`;&0>-)r%`VNxvh%3fkH$OXf3^`h| zBH6xuXV)BXu92MoAvHg>oLfLc6C!AKt|x>BAb?bKVR7!2#zo1aDk&m@ut-ri{ebC_ zDs-rEDYbdU7gz|8ZdGc{8aw%~c_>2|qVrRPIb622F8M-NWPgX+5z(2`0hH16@g_#)mRNl2HW?hAfHUd^{Ut^#>J<}kuXg> zu3_IkHWrL<am@D*8=Zt9Y z(l!U_z(e&};pNy;l8ViO8ZWPiFItAK;-`-@KI=zr5deI}kn>JAf_o*L;|&fYn7^ba zt0S4tqSB%TpaYg0N`w(=_FP7Es&BU~>e2`&q@QlOs3R;@cP$p=IR0Wf1+d<3`%SxP zz@fQNtO60L_oRh%@NxCtec84m^r)yhQ-$5Ef`=J%V;10g&JFwg7Ll7ZI$L}*TJmde zSsE+BDBsf;k;u}9qI;_yz53y}vEz)MX;~dx;(tvFv){HPvkPJGth@gNH$#?)EfSX4 z_BjbFV)MhXf=kHYD`LT@h;+NLVpNGb(z(WC94QMDRw2P+SIYNnsV@={4LslHDe8n( z0@XIkx)HJGwy0`0*F{*QxFHDU>$v2zu2d<$NIt^%XZj1#tOA${MMaa242RF(( zk!R>hJvE8Og90IY?|lnH(0Lz~);oTkhI{9eVJ<>brTP9;>JBBqvyoL3K=k`%w? zEalaZQ9(l%FxuaAf|s$5dB(s>#`Rm&*cV4c<5bixAR#Fcw8@Oy36vyaqS}! zcR_%Nw;4B(`Ju9!HD~6x8~*`CGsh;~C+>X=&taXDhPz$*@8=IeGZN zg$97Phd>uJ_pyCq=q@q~F~Aa4rrb5r4oU3shpChN_u}doos!6pPOUkGT;uGtAIlRh zFHGORqsq2SJ&2%DixW6q;78{Lvb){tHo_i}#~FDtPw5lzoa1BHJY*8pz^#hJ%XdV< z!Z*)SP{BkkV2~O=8KCd`E!nOI5*67XBo!nW9B*DSr%4cUnji&H!JBC|R8ZoKjzp=m zU9w4+y`U2oQiU2OBC-(dZWJ3|XlZ%eZt**%T&Sq~`cbJts*2;&`VwvA&NQ_Mw z1vT}vF7;28n#BPbv|P?Uz;`o&!xGk1_j63oy_X$IEu%X__o^U?@! z?0MQ+LlTO=R!ces*VSw08ylVn_mgL?JLmFU>Az~dACYl!t<;CmBEVXJpbz?P+KT>e zT`v`J_yA`e_(&wFKY>-~z;mU;MWfa_8p(F=yMe!Vs`W>!Q*m1Sv3BWPZH6la54S^H zEbp|>2>}PIcbW6y*M4OFjWy0sLAOB84b2hIGLi9l09N(+q&2vd#dRMV&^al7C@7D8 zqqIA6YpqDoBuo~gi0G4+wF(Fij&H)o1l=2N`>`pLY*lta66VtX6*jn{JMLx3o3~HD z{*hcR-O`kP)q3iafRz$EQEo04*@vIiyNg#g#Tu7yArrAcv{VC*(sT{g84^xWYInq>urwRw%(i(moS3WGe6S&wz%XJ%VX?1 z;oY0m`#-51zCU{V*{|dxtcXP^jHAg46x`tl(ynTd@r%+oq9HJtnsxjkXeVqY9)l{{ z1j51U*avcO2yjmvd>jxFmk$#WAizNyOdD~Tz8Xq`a6=s235n@WqVT&34hcFy3CRY7 zB%HvjrJ8(jw6wYb`Y3HE18q+VJLadcFVYvc1J!W(&dOrG5;tE-mH0vC5c=~y)YE{H z%6@zS?KfSNq>-q=357vw2%`Anz<8H}ne1^O*<_~kPuOur)gzF&cn~M_;U^p1uHdMVTZ4o%?^Z^<`11_$eG_1K}vE9%ny8O)CZn6chAml zXddOm&AwN)5_vaH6+9y@w}K~gz6fy{CtgVv*v~-dt)EHq_Msc8zN>DFvI?DgaN;kG zBn!F#7(syxZK@wgS#60R{($VohlzK^n4lV*r4T5EJ<3Rf2&w@=pG**#gI9(3+U}+27la( zKRjrF}&zC zzA*VP$PKKK1pV}v58q&W`wJ?X-%U)40|LXZH`0O|Pq-eJHEs_3FeC;zHU=sb$q$6y zz96Oj7K?fT!voMNhUf0q7Q66ZH_An(9RFu4L7vp>>>CYtzOa08{)dh;QDZpjPp9o9 z32(~78&}imlrT@$DQQI((+jWRl1*LP9uvL($QT^-m-IOnU%YO6%iVetL(} zzjH~C$*(_;qV>Rh@dc+;E<-@bZ~zn4F0;4m>zDNQce;R-O^5UOv<^Fbe}nMH>!nGx zR%eJo+QU&HuujIu4T==>9cQjyAM7*Vz$3bg2uNK|M=*WQ=48yuM<^Shn8D^4q*93O zNc8mq#~b!}%LiMsRBip2zkmcsiy6d^dS1bsv73gr+Jll^ia4@lPYohYZkC zKE-a;b6k<(#8@ms(f^maZZ8wNcCYa{_4ZI%K5?m2;0W!?b?_hxczxyAvQ@OCdHDIM>}1i!uO6 z6GQ)nf|l#w4`%FGz#;u`NaTVlDxrwnaV&2h z41)|k2>S7B`_Gt*`Dpn$o#}iVW3p=KYMTXj^NhuyIDXIInF{sGMB?)pZALdNB+58hb3QC7FUf$nm%>4hn0CTN>T^7Xfx~_q@HEt3A ziH6AJJV1`fr4Sz^wObrY&|xwW%;A9k>jyWtD=$(D;v14x$uLXQw_A|LY%u?6jD?oh+Zj*nQSt+B|2?E-vgz+8PWv#2A%NWp#7tC0)urQYyOh}>V8O>nLz~nnqFfvkbUQ< zp+Bep#$l_b)p3wDE%7+{?jo77>3Tctysk44xpT!~4mPRX_@u%a;aj})@G($%J&LVrRpm!=c;zh_YI=9^9F?eY%x+_gN@-Zfj@fc zNcUPM#R zm(xEOp~hY&fcyl8@8^+384fK$v;bBhqTA-wQJS7iDdyqOFe)S^l%$|sl`9YL0cJ9> z$J?A__1BlzucyoN(yNkT=rB&-3ycF(`a{)Fji%60J^38h2AHQ&a9^Uf#@x z&4Xw^eV7fug%H+rzhXr>@m%){L7Wl^Imny6#AnFgL74Z)NIdmHdu}qv1Jbo7_9MUk zoyisS3oy@2+W-sAD8P8GK(WUx#936XhbOXl--%tJix$(yXJqg*d>11Z5BLE)3N zI(|{nA73SZZjlH0AB23-k=(8}b2cR^8Q_70eA>!!`P;j5>6e4xhzIkX$mj15=mR|8 z#3N~4qU#|Tl|b)1rZOOZT#i|24RBW9_KkF z*;I;?T7TmOyn*}(5NdW}q>v%AXtCJ|oq3|rXbGxO#w2gc*eU;w{@0l|_zg8r-6!N3 z17r3+dR`X2Y1?_k=Igb0G@08Op4i}s!X_1x5K2HeEn@XkBf;MfG%{oI z+^|P?8PTj+So~2-({AqOBgEG4Q}4ZEF?+`Ivqq$ z6LD06md#=l&>*y~(-JWssfuS|faRBT;FGcFF!64aBhaf+pAN^aHJY{i)p!vEPf63* zwJwQGYaRTn0{m8zlBC3B*6#)ggiEHs;Imq{J5x@FJ1I3`m=l)SLYqHehW(;&CtvVl zt1WQOE!J?V12#C>_`QXf#s^?S*QO6NSl5eLRh@n}uM9aTE~UzQOrJh6npJD~Aq@W? z#GUK)YIH)j=zR;WgcM|aYC>egpu|G4;sP28DY@EnrMrWPu+_MbYf6kYd|E7O8< z`3_4ITus(rqie;~y0?VvBEd)Axqe)OB4Es}+2Ye<1C_-b^ym-){Co+;$;O(kwqo5h{QTDI zl8~ow+F|!=&EG&lbnUU8YZ=DHWJze~BCES?;f0|qsU{eMwct||GDQpofq}*=4o7c!=B?NTBq0pA zR;gf=lvLFt4c?$$WE8L{Wj;bBv;S65)D0DO^s~+@W2kr|C-$f5PGj5k2%TsDlJP!K zjK$}Tke3R+)CZwb|2NP+ld#mpX-DUi7J)qM_3tsTO#r7re>P@YBIqI6{i@pyhPvk^ zlD=L{rTKevU6fL$HK6~-gJgV&0S2bv27I3}MfhKZ5)3dZDk@59 zYGPvI36cikmYnfIpFK|Uk?XKn6Tmxk2r8^_M4OyDCUIYRmGE~!e%lMm7-loV0K5c@ zvXV|--JH@Nw|dJxHhKy9Z@GZf`OCW$kfs4RaV|6xO@B&4oXUY;2xQ?v>kgDJQS{xz zODo$$Bltc8k7{~HY-y0}Z|0DLDdq{#HQE6gg#+F~vBCtL30%$0l;iXuHBi)9fei%B zR%UYrI$qn}?>2P3#z2i_GlwHKVPm7?hO0MK>R)SV-cLtZeD8+f=ufACePTwAavRH= zE;~6dC1cZtIyjtqGrDG3~b7NyYyVDnVAir&r+!Iex=$nXC+6FJ$)z>QdIxa;TqG@xTHElb_8N4I{HR&I+|hK6edR4cJ;uC?kPYf@%#VnxCn`#bULZw(@&r zF0$=RRnzs%K&58?G0zv_widvEQw1->p#iZ$M6O<*XXm8 z3=+(rJ3N)usQ=XYaPEZHjBMSZH=Bokg&}>gY{M8t?qT;Twe5Lt0^>*7AIY=r?m|fJ z)na^{qL>F+Pkry(h3 zO7zn;SJYJsKn*;e(!41%!Jj|PE+wf<8X_&Z`*%Eb!S5VhI3N_9tbrI!sfCnECz9AiT?l&|tbih# zdF94a4_omoEC*a<@@UhsEW7x`t#I8f?ndu-vEqkffOVhZ5ESf7{QM)ubhTDk9r{$6 zbY4_NPJY{dWC4x$CF+kKOujXB?Z+`@#lvI6M`72mCYS~miS^shxfX1kVY3v?ev4&R zecg3QHF*GlY*Ije+|a;Trs~hNE@CMO6knQmx$!((>q9OzF)pbV z=}!oyqVnV7p>Nymisdl)H$hKFa2?3k_4NM8pd$HP)Q5k4>R#KWj0GE=IsSEn+X0sfke5o3lcRg2F&=*P#zB4$+O0DsH7O~;H z_md0M&_2gy5TC9T1#88wuj9oxz`$4{tMO&9?Q4cvG(2^5*iZb2gln-f zMNp&NaOA05g0{RGy3l%5M$+&*7PjkiIZtw8I^XNrR^6W#)R@&=VnWPVltSLg##b10PDYRYy5AF9X|IFg?!+MWU`KK*<0V9ifh9ZS$JSf)0! z#mh~uJF46))*RJK`a;3Mw{rXN6uz@^VB~az&>zo? z)3l(10z-az8>-W^ts){L&Lm=Ep}z8*4qCQ6pitE>al!5*C*CyMA>iz-@){>Q&W`;3W zi(N?g4dida)kZITfLu<2cRPm+jw8Ju(fKCSmFJCy?bnF#rlSr#TaDg7=Az-dH8Cd(@!rT3^_aOCo{yF7(L%K5a?wk_fD9wCUY=0?e;{8ea0W-)hv!RmVbG}!4qKie zCP{6Te*BrNl@t3O_Z)5o{${%FxpJ4-3hu8QJF;&fT+P@GW&l^Np8&5!Oy3mpRFxbxY{$2q%?BbEx7z?bL4yh^xs~ZiNn))8PaGo87ihsaaFo z?Ni}wv3lsN0W3&xT4%h(D~~T(I(%=kU7E#qKG5>? z)EIE6z{i?HCYw1|Df?SSaXit4x?(vW+^*}94pY*EVzfs>#u~?F!>v!i;aCVSCaaZ* zlukfS7uaT_xy&*pl48VQE)ZNF)A?jRV4Ih#(f3l5?TTYG=b2w54=*RY|Jcx#FD8qn z(9trn7VThV@m^h-f`TG{HMPlhCE(+NhDvq3*muiwRWNMgmGs9Xn4vF7*Mcd(@nrKe z@r9=Wm}xkQll?O~TI^awg_2CQ-ee&hcKo>3VZnRvs}-COFVy=5YOY?!g^8M|(eC>@ zC#zMzKaN?VN+a%)`+2U(!fH6$H}`H#@=uLo8WkoKjrt9@AnG8$9+q%SGzr}GX8)q( z!fM+&5NK_8Zq=J}zSNQwik*bI;@dmY_$}Y6ru6t;A6c8a#f8 zo$xuuPS?6kc1zK3k64Z`yNH^tmNL4dWbHz~C~p}rHhZ#ox!D>mmmFKJI3;=mR_2R! zP0;9aXWnEt%C$T3eBK|6Tur$!D;y@XdgHsgh}K(91$=eke*9IXN@6DKtyUAaMI-7h zhP+#EdLzW}JHpw({~t}~7#?S|e*KseyRmIsO*3&C+h}atw(X>8)Yw)tVUxzTZNGEQ z`M)3M)66x`-ZOizd#&HXn=&lcIe+2N!( z_a2r-B^H+LjJE@~?;>bhDmA)KS_rtFPOB;je>IU{C)B9fxq{7csffplj5|EWlUAkX zMCs%Ly8DxZ>(P}FA0hn4Z2kRp(?$Y8F;5^&S+?E0J#`x9qq$Y|+~J@4IFr7! zBm#h1JPZQaJab7b5Ne8OT_Q&$;cB%QhpR4&Nc^Nd8cDX3!c8wNBw3t|i7Zf)Ooz@f zRO1lgCpuXo#a8Q|K5<}Ocz*ecYi{25A|qG#A3@mJj1Lw6a~|qYmZ+ff4`#SyFHP8v zZ-tmZNh3^Wa;rdy_#9X34k#=hSw1=w$2H~&F=Jp?Mm#{iEK8I!2b*TT(&8(Hnm{NrX{E_-xLa{$Bjt4w)BX>h?D>R&F-j-UkLR9jXJhXjW7u|rey!k z9(f(Dgbb~ZF&C5GxIS<65`njb5G>ZEtBKyrQnbL}zNX`kJ3H^sv-Tw@zOsrZ8^$Se z*fAIZ2Z|Ec9L90&FIQ>^JvQ7$c7J~%j2b{zn@;jbNua{>HjS4~)^0Q=VM76e+2tHh zM0yk^2PE9!Lwwu<_x7bA9v$e>1uzf6=o^`_$-pEsNyOLULolZdD;sCQ_=m(qu{B+1 z7$fov9~1mHz-$c>paOVa-L(*U!tNW-cT7_a(#p#XJgng9mn}9)`=temH45vKzxU;b z72D@4QYah!WbZ^_Pxnv#Zh>a&h2n2<0{?2~G7k+r=V6t;KxEe*${AZ9OnHQ8UufSI zaK&N(<(qh_;rY0(Qo_T~y<_w`j8K`gxhlLTv;S3pkI~__{#&cg+j6-S<1C(;Uf8Hd zE`a9>ZbhbtLV$rJokC>e@=QixGhq*{4T!`DLGKtT7?3FHFFlSch=esZCc7_>`ih8L z1ViHuAwv9#cyG;HsxkTUuSz{)rP=y#l}CX7KP?1apLuBMKx1PBlvsAIt7f6V!_!6} zIwZj3R%1XS3V)J`{QVkQa?uH(RjO7SYkvGoDjlbP3kfTh4?SJljU_$%l}bTW`NWL`3 z%C6&Fb>Lqx2haouVLyLW`Qu5)KW7adUrdq+zUvv5Hwg}gCK+Ei8+7PINkS^$_pflF z(>`>2BqKQeM-!XlfA9b(r#vN!lO5nMEN5l@bhg`ul*QtZVx8pFiBox~=qrSAWMq46 znY;?zm^o-m>Jc_ElMlgl+Y(C}nu(W19ewYr=bXz%D?x|bM!Dphg7y4QneGne%-$b3 z_>f%6_aOh#wgmooe*|oUPHZ~lprG*Bzkz-KSsUM912~FGZ_wvAf7k=EtB_BnN(ub8 zPaI>jB`{pGs3#}G`hiQ6$oc;W3e7v@RZH~6+JBL&AWlTKNl$i3#hwNR+mD z8^B({pA;>6sd33X_)a3q_q!Keg|wf4G{d)SYP1|A?>V@-&IN7ZPNH{zMw$|^NbSWW zwuyfE!=GK|+-#4bDKH^KBbPFWGzcvs@_xe61`aT?C;Gu~W7)41IU|gz!kLFBmD5|Qx!!M>5S*k3S>PEHt%G9V$VDlJKOT<5iqG=)g& ze|k^ulnCm_Ebp{O5w$`nV+&1xncG^_)#U(VLGM`i8=4Is2Tsw7<&FOR=ZNO@P`A>5 zL8?D}wK)Sdz3#S8QxfW|Z?%<1=fw6qbd;`*g#>m0jtIWeHBP|J8w<<6IMjkD)&1{| zQHQ-ifMg2DF4}!?8JrmtOh8-4MyTXvKX-jtIj^U`NWbj(47F;v7tipDo{@HUyQGlA zd)bm`w?$mK!1oGvt(8*<+P1hj$wGppUgEZ`n6`k<02#1EswW_Jr0Y`_e=`&(TF$pk>h)yZcKb(b`>`fxk> z;n7fJ8>)igP?!)Dw9PH)g_-!WCPBdRg!7TmH-K4x#0J@IAmna{uw6$^JOP$SU57#n zM}K&WhXr4OjaUDDXzzyyDY7fn&zD(|pH3;m)rLG7UNM@Te|1^#2e5KAHP4uzCK9$Y z=9FiR|IJOaxq-O4S-t;EaBgzrZiGI&Tmr(#3UI~)Oy?K!ykow{f420Q)=`1zO{P*W zwR_DoNK5vcwe+0K&_>?IJ~%DJr9MvXb)M@!$|g0N6rFZvP{TL91-;sbiI(cK%o!KI zV>)SVJJT`T_!t~CMDnG6=2!5a_3PGVVmZ>WOqk4~sq%Z(i-jmWzQ*rfEwu6C-_PEL z+QJJ$MSF{VYtv~#x3HB*%H)02e8?3z9PGGy6f&56cM589wqnN^QwXb{{0x%1(fK?; zCVBQ6ezHmQIQjP-jE2b$d2MliyF&HP?F_|~4tVI>sA;lV&w_r94--$`oVp6CGn=E} zXRLjy{#4lSH@*~x&xI;idJi%^WO)Jb(8w+UKAqM)?x2Y3C_4hs>kdqGP=2)O`G0w`7patt_NuUW)d)U@VLjt;0 z+iCA(Ts|!0BLDY&oz5yM;6})JF;F^%E4^5pfU- zQm!A7k?l#nc-K4JBlSu4 z%0hGoUWx={*mXXf2zUneIT=@N*mCtB+B+h&Dv{_Gzdh);@5+_V-_31^Dn(n=L1+d(z_%#0_K0c9OrV*kTy1o|f-&gw0xB0Yb-- zy!9$FsDkukoh3dzx_7^XkKOa?PuH|=gqvpzoT$weq0I9${lw0uo6me~x}bQVxfa5Scq^o+FfG4U&K+NcgVK!nT0O2GXY{ zxxyT9ulTM^&K##X8e6WDc5}AckWG5XRJ^o6TcuZqc^SYKZ#~b!Wk+M{>K%qf5>NzI z(8!RWKY%2RZ*0aLHLZxy#2$I@A?VHng+@J z3?!cApU#9^&X*74BUcq!C!mxmLNP%JDtEP9@MWKvx&#>wtQG#d38l_^jcb30!*hLjll{P7Sv36;J-tC7T~;a} z^ziTYj}h)%?`N{N8{tf$zhuwThox+q!bUqZfRrOumH?+RF=?thA^u=(9}_*8e$#gl z+%}dpusv`rEaW*21XU~+yY!y6Wg3dngEj@a*hV%Gc2A~weMmRFw<`2sdjLuY0$^A)H?V3W^FD{i`D4i)&X6}!R=vt;aB`48 zSv@vR!RpvN-)j%!mqx8@=aleLlMiWF#+1wSRSr-|;qau&;h?WS1xTjl8UMIRBxg}3 z&rn|R*RF3;?@uFtn;*)$fCo7 z65$uegFSZpu3hr@f@#TcB(1yCgeF_Pf-l^sR~HqkbPV&g8y*I}u^scAKzZirty70> zHG7fawhJpfZJP;J@q-47ZTW0o2l2@hH&4GcpS@Hh1Q@yrk!jOMVexOy0*ip|IAL1W zBDF+^o{#u~!|HDg5k^x4`CXQL+}3JkHVNWqLXO#q!8>oaLf3tHr4|}R`j1u1-Jb{y zY6H8EB0y^uW-yb9@xe}CGT}mBM!sqa?4g6_$XPTXm@HB1JrFHMka(;2rT_Dub5s-8%{q{pVh`7ib3^$OBX)cp2faEFnRcFBJfCT8nT98O<*vA4Jj zqq5!53*RFQp7YI-DpSL~gtYN2AyeD}f8L~N(bv?=o{!uDiz%93vKaLo_v_`>xh!7G zYQtoK|L+Chsi(H|JipHvV?n`4*6wgeKBg95RFG2Cr!i`*!0WFcsMKwz9}eot9{% zzVFP)2h%0q-VC32T_qK6us1@1E!h=lZ%$#tQM4q|KL7FBPUG0FA z%{+EikTrbg;-|&;9j|e{;0!F2 zOIK#6PIsVHB2z*{CE*_%E${{XGDrR~S4u-k>Wc(YGwTPxvG51Ya|x9W`rqy1U32nfb~`Yv{8kzhPppvWBh znX~wPp5O*1v3yUQ4Na_Z3>DA1p;sG=q*YEFJh<1@YPn@wbr(jU_A<+3I=HJ>{ikSy z{#QG1Cdia*LhIK;t=u|Nn$^lrnl$UhBIA@7SL^v$H;swTbtq_h-(4tl zb^HleczrfMVCvxR#lis=s!l_4*=5V7{4&qHJymlj5mr|%#92!izm|d$C9%%M}cram^Pu(N^RV4FohDRK}%E& z^FI}L!@2oiMmgLsgh1t3h8)+Omw&o*rF7yH^@N;L`5OZcyR{ju)_xHSkLBRG`sE>5rs_c0@F;DTJO-36$po4y z7d3>AA4`yGhX+RZ2&(A6O%SO{6O;1gqs#cbmiznqQps_rUbEca>nh|vAxr<5ToA1V z4HIf`nk|t@Sa8graFv=jh69e)qyHM#6n+(__)#fB3bV?j+nyCK9M1ORYCcnMXG74z zY&Lg2wD$6=ydH(ZN^7~n+_zXqIOo?mUgwt`ZHaIQ?SbJ&X{}B-QmGq&++uA%{e;xW zkki$SzXj_GNJ+J)#Qc_qjv8aQLYYELLe`6+j8>V(Ou6Da<+lK#sJ5Fl&#ib}r`WGA z`rLF-9*F1SiHVsSdDizfb4~W@3rvR7C;W{+by`RXABiY^2IT!Sh0=<1WB#2kg_%f; z>tS-A{HqYpV<6gS4C2;(xIGLuLn4rRs~yjw`3Pcgi5e`b@ z9K_M;dg86TSL^S?MKTwckRWO)@v()KS2IQ+hpo@llI3KYon?1up>zT`g2{RvQ#$fs z5}F1&Tk{2jQ8v`^k(Qt&z5E~qj>Q9D&^4rz2!MgC*tZTukyl;pyyevZ3%Gb1?xA17 zb1Eiz$Vl|~CbuM`?Jc1G8LyEJ!ZF#o2@x%@eb3c^@R4Ow_uto_=oS+Em_+d8a*m~n zgc#*4igrkPb?@XP^q3TQ9SW18XgE@bO4(j zeKtUnAX1De9O3A<^x%w>BNUrFRCyFN(PSZFP>roE4h0JhZl~G_I{#pdyUSvrZX}Ty zKaw#+YU+|Ay{s(L+)YdcU(44ofn|r>G)5;+BVs~z-4Bp8Cl#iZ=3bbA&wV_^IHGmH|LtfbSJp^_(xN zc1#?g;4JBa+YWSkaTD52(c-+QqX2v@MaUctR`b!8^{&TZTLujWvH4PGgw+uz zD5@cvnKla!Ra(EvDdE?pj#Dx(>K43<1kBlK8sXnQyvN5lUfaW(ZK>*g`_;Z2oU_aI z{wQF+p!sKi3HJVBQdau6b`BXTnu^XKC0y=b3udD)Zf9$5siqavb8YIX{#nn^c#1?| zd`hHTdwV9N@+`6@9@!ejbdou5s&i0fJ`{DK8e+0)l}e|qz-G@o7<^}YnB(AI+6OE) zpL@ZtZJeos#;?7>nA&016bV}wpWA|W#5U6`K5#~#k%=@GM2 zWn|1=vzv+dJ+pT$8-G(``lq4W`%(ijSO`^{t+{7au(J5=zIgG6>HPs!Xi1n@n0r5* z48%J07%jFCpKbW0HV~j#t&^qD7bKV-J_yUde0YFpGz(>&2?SbdM%R`(ml|zY1s{k? z3aLs@zfodT)N$HV+z|2K~XeW?Jz0 zRz`jq=4=*fibQavr`zYr`b3HAXeL5-e=bTLi5|MNY_Z&J_sc}~6C@t10aYh{12Rk+ zqlURrg}40Yg=x$A%6Q8=?H~H4N^lNN5UhGUZj_wy`^Hj6JYW%8UMF;36jR~v%q~k# z81fYy_c8%2ospv&B#BmgQ}S{=>RtbG9I$9hzV=A|+$<$#wpKS0#dhJ}B*(rJ z`&||z9K-iZtx7Hj?%4NzL(X=!IRZrx)ihn9?0e(4Hz6+yFTCmGygWH4D}-?*Fi1&6 zf7H8QuNPiP=UPl@!#5q7J*^lgbu3BPFN#d9NFxw-N0Ud$sY^F%)IMt2$7QfJmHE`eWs>wqY!wcJVz@@ zs}9{^@E1J^ISxHB{?PEVjfT=DyD3%+g(TA=o_O6p4`!!9oW38Ek7_as102{bvSc*M z`3WMvacgIDt`{qLMZBn%w-5UG8boM9&oI~F{oI-;W=C;@%N}PGi)fuu1vGv#8H&Qs ze%sDOWp6NqD4p`97zw7CnLl`#+a&}p{ogP;!J#RiMSDQ!K5om|N<^&OUiWlQF%ysG z{mJleU1{edR~}KtkKmM7p1&2~n5$uPN`|3tR`k9JzWXbRT21D+&3s{k_W^t)Sy?VI zEOxDiRQ!yje_6kA=~OM>kYd8^R_03G;X+;?wx16TC>Sdsj8lt4i*+~qyEtF?^8@z$ z!vWnv?tXQqS8kFB2>OQT=7nDYDnllfm{8jlFd0cO;!NiP9(%V+o5puX8SNkCoj?Bm zVx*K_i?td_*5*$+Bv6=%G=JJ_bQ;nbzB?C9B}mHyUwh}O3I^U<;%Ty2c*MtMj8+D{l>(AuKQ z7&S^#B@G_71!;kD7t^Wz^tn4-T!Gwt{ z6mni~+~wC{yXmiv_inH{n(B0h$Pj=~@I@hMvgzaz;WneXRD06-;#Ef$xz!i(M{DJS zLe`Rs@fWBvS9>dZBcz(3lc;QZL)v9i_kj-74qI0M$!-a^`?_-v=telT!!~jockn)V zubYoYXS zUF$O=n5gunFVoQsA0Wi1at?W2&uU2(Dmr&Zh8iL{a+D>AWR;kqBHb%emt*( z<9fA9)eK8%VVPh?42tyzQP6qWf_QrENo0`bndD;p94AHE5O(+`ytEZ8R?W2W2`Ir{ zo7_CpAFWI!G26{@4E+9+XqI&V0 zCfqck*tXxIx_m!#Fo29GWBvA^Pd`J#2H_Nwts^pFz-^RKNqktar^b*Gxr+xnztm)j zYp@1K*;aW)-~ZtsNxrX>(0h3NUJE%f0$o&MM}7g<8o4r(Im|T`;9aD6|I_vn#HL@_ z?`UPg+Ocp|WsDS^$$PDedp>4)*QN=K*YXhXS-jT1yjqtkqKLOepB*j@J8qT01A5#o zeMy?f3JLs*Ss@9hr*FMF@6%wwXrF@S>srPrS&1s`FD>7wso|G0m8rf%dsr?-xW={Zyg5 zH996rraX6Z7rnr03N6bz&*DTnSUKFu-4Zm>5~{tleIB4})gRrK) zwCyq>(YR_~Nxg0T`ci(E{oVeV*pF|Hm>2H~DX1)XB3B@u1+L@0g3Me&n}~Fr&AF!KeY<-yLFyyCQdt@hIL|`7UNsR2C~6g zcFmV#Q2{S?o=n;rL%VUW0b1~SPsm@lh2fAcJ3oX$Rby6R zqk_g7Z1RleAUEf+(Tkd zCxIWT5QQ;}owHuD!N9)V3W*=Z?PU!(6&^RQLy(k8M?UZh{k^7EK zhcKO^BoanZTw*csVP}YEq<(Q@*uy^689#gpg96 zjD$CC-fx;bP`ppD1KA)o^1xJe;}tj zN;6Hjvx5R>)fKu-DGUK8eJDCN<_d$7pROjo2!TvLaF1m2P^$Zq0Wb8&G55O0Ix1xO zenOfUCbWnYlU`IiTPOYiVp@aWBF3-9U((hlx%tpVA#cnMEHh$q)6HKI!Bg?Rw1;$Q zmDG)8=)fp)+fpXu(*t2D>I&6P`(^~L?O-a&>7Z?4n6G^R!!MH_x<15gdg1e@DPfo8 zYDaBC;xL}qP}rf!7gBALA|X~!g_M}92JIulLn~s z@4dpxPHA*RAh3aT>nzE)BS2aydepPcxJX9n<}b~W>f7d9b#eid?Gv;Z!Ld6^Nc|Xd zHwYkU=*N`kXIgHI1w-k_b+3$P#61sT_oUwkU zM1l$CRx>3+TjozWzDw(bdq?@_XQKWKVWbA3Wd6rky|mfmC>3cC!D)+@<}re{>8doMpQ> zw1;N^lY1lbt&*6b_^AbM_+y6gl3hyb?d!*Z^g6|FM4Y_ss8Ldj;g*mKH?lgu+MtkB zSlf+;964<%42U$w5j9{=SYv?6bF^D%VB(b$=C!thBqQLl;pLIHg0A}i?j8BZzsxoc z@VpK`tK=a#{%G!QnygF^tSFo&d;d(VgDITXz=>43g6;)koqr(!c>_3 zAMNaA(5rcoDKBHFK*QvTZ-u!~BHk_lmjjkUEiZdPc*!uXf>OPYYN~_^lCBsjMh)fQ zOLRBrMK`?+SAFe(;KUaX94K`p*%M`-47VY>h&aXQnc*GR!~ni3?V?kZleRyOy;Rri zaCWOrG&Cc7tp)x@H$#Z|Ay|`Quz!PYH&pzS|x0TLpEbdGxHHMHYSt9$o=){WxbYnI;2*c(DF$O8)D9M?6 zF1d1vi|=Ix%6ma38ILi6Y#815nZh_qf^9fUNq!?Lr#` ziaz((bCLO@X#*#XsG{Ht*#(~xGL;p*5R{L|g(CBM5!j)<_gmY*>Z(N_;5GQ?|#0sRJ03*rG;R$ZhSQ% z5TDvdeq-}u&~+y+G@i3q^V@_T`lE87nDZz4K8KF(JD2rJa_2>N0+Km4P1!^qcTNes z(oC5u<3*brdV&8HhID)`MYjs~h5sJ=uMA!`^+*CydGk|J!8U(K(d>Ce8ZDKtL`ZWi zW*e-xPk!4Rpz?C|x7t^*iyf0Ab^7U1)cmt(a4#eLXzuWfecQGU=8ins-fiiZ+3=+v zJ3>yH>79w^7&DE^fyjV0sdew>C=67~1d_d5ho0TF_Lw^Ywn&>=0$??Pq>KzAxXbXV9X{d7(&VIQR$Q^LnI8J~I;pEp1As>DD$wG7W$nE$MNNi>|F;jLp`z}99P3AlGvwI6sFa`UrSvr` zEm35spJz?+|7Z9r$Rwv&@87BOfVWYlGoP(Bb;u`vXIMlznk-tk@!T7;tlVr7j3ZP# zn8J8$u(~yNzGY#ze|zLQU5bEw_rBTpak$!!ApK53E!cXtwRCL?q%utS49pUpK0L{> zFLSAA8Ok0hxZ&bX;Ip65N{pt>_e>6Vv%zA61w|J}moU=^PYA2xlwx%%2pk6;SBPLxDq)aY5MY3H4Pf}z( zc;H&y9j^5My#Utw5wr!~vHH@i5bQufF#|>Rkh-4i?o-X%nY>nKcF~NS@XZ)(bFZuZ zh@XayaFD!HHKTpxLf5n7cNc%NmX=^TTu=J_S~rJ!;*h=k&j>@!BGE?T_V-(Ri%l^pKd($ zgnSfz<6_R?p;^GT)$566uj>+@4$@TR4^@X4bOW%LXYd8L*{`Piz zNhIPJZ5rWz`#eOTC+tes%s}IOc%HEJvtfa?B=F)tcSwvzUYC(obK;Xv{R4adD>BdPA!gEKJkd0i8E9&7P* z9b%ugc1vDIRAJhOZO1D?*h@5vs3-lM4!xj>_VGlJ#d`-z?lc3{>yDMbVN+@l@A|jJ z76tHvIb3eLM~_EBZ`vVnKNODjJ|@UsP%vI;8haas2lp1ubKe~;$34Ly8waVOf}Ap+ zjw5`Z_8;#^*aDHITV^|_jaUxT5`8}SZgK0%mUz%%mU_IfMip~ojRrr{2{ryF8P#!} zUiwEakO=8(P;v{Wz}+(_<3^0lY0NfmirGJp#-+L-E&FV7Y{ms7;7P}csf5=G!_5?H zXlKvM?^Z5~Z0k)43yi9VBB%^RbFYGZD7;pGI|#}(P2;a{i=Z!Htt$8F=s=^0uvRM_ z%y5=TnWbi_WmX}-Qj^4krIv@%=*Md%eJTyA;9?$f3+aCTPNU$a%mRN1bk)q^m0`Ib za~-g>38ZDd&wwc+-H{^b(Xk)jClkP;&T}mnBTK%!{)#GZJG&e%bGcnBs_TVL#3|3^ z!BMTBS*zl9f}P-#^$S2pO|Dp}V#M`yBLO9+bq62UDl5zNay{i^o$$B+6ISjts4Sh@ ziD(hF5(<2;nJx8)O;(oozw`miN(WWwv_YNy~hy)Vy0Or9MyX z%|<^Y)oRjZoVLx`03Gg^(G0>7%)|_()N?-#;G#n5ruZY0gP}(gl9JOwD|xScE)P)1 z0lIyohKj{5offI8Wud`%knrOOP8a_~aG4F|FU1G>T#wLEa=6T%U(WTWrpW1q(|+q^ zPJL0B2JX&m$fc&6{jHbtk(ax7`uo%0JQ)FlVX8=e`Kvq8 zlBCYCtAzuEEB?a8bWtc<`{;6oQATtM%HVH8=e;iWcujksd5>r*@eP z?-&Oi+Tj>Q(oplfXWNXW6wg-1;`4ltR$6K6Gecv#AVLvj#Mi@Xj_0f3g;y5$pFY;# zI4nhcRG6yUoP`8Wyf`o=Q-LW32NR}GeL4t(1L;uIc9@{DnPwkp&|Ky)qer8~vP$;+ zQ5} zy7U{I2Tj^(0;C#jGAeQD9eOXl4mF_jv)cPgWQlhg(w=!9gsw?c;1rB<@LdyCDRC(u zHq_t{8&$tD`*4f+^H2jmCMkNT3#KsokE6tDkVUmC&<9xqul$&U`mfyy0>~`*m zDI%|dyqnJuj66wg95PGp2=uP58N4F#P4rB3g^JA}wMvy7@3>XA@;l$$BpsOycF^cY zHq^88m0^~O$vo<*kcBS#^dH}9m#PD4$yspGQ|l53_K_>xd^4?#bvj6jt+r_JJQ4W> zw6}(`m}VK&sA!CgGjXjdt@K3v;3SVc6^w@=k{iaHhG>VBi2&^WZ=Fr{2063^p1H3D z_zL0(wwjdF5TQ)w3wwyMpKmT-ZTUf|a{W$#=xAAlv=z0=+}hR4V;n~KIY&CCiK2h> z#Twn&YPBj^2gCwb1DP2zit@9~yP>ck^Y&QJ3;#2jaFmmQ98*K1y>3c=uWKk;#oQ9- zFj=)qy|9&go!gzGdNoC*ZD$Qs9L9>%dkVYXc7UQp*&PI8Lk5%G$b=YjEfs)lQnC>` z60VAE#BVubYcq`^=Y4BHn>(LF@3p`+&64a6J`^<(c%!ReGR*Fl!<5e)vw~1LJVw5b z^jwqT2XPE#$c(rX*%}+gK+IMt&=a+~#z9G|BpOQ0e^Ez7!U7*@=NZeBb6oNZRrm(J z62M8|rz*u#1rx!E5Fk4kB|OBfIluj$AteL04o zm+d*yrhbn=7{lGw*YK%ej-yYEL+z8TA%6oxo6CWF5`i*|hYOxCp;3tf2#fAS(Y7H? zO38RrR$3eT+EAT|)=Fj0k!aUSnH>Kpq~k5H%RvPvW9jFsG=~$7WalQo@~koG zD2H#S=~0oh=Og1yIrG;gzP(9wG&z8-B?bAt@95gw!3^V`l<-NN5D3ZiV#dC98kl^F zune5FRvSXpi_O8PM!YuHZ6-mF%MyhQ1EcIrVDxR{*z~yNeS-pwB;+r1jjvGPPXMvVP5cev0XQ-o3uI;<42xCyRgmGQY6T_ta~OWDQvIChlE#wa&zrg&WzX*#Lr zQnLnDi4(cQuLu%A*N0Arn@xfk=5G_AtjzY#@~zn+ZeoUEEGA706eo{Z zb9UAnkEO`-GJh_gZ)WpqylS_-4WLqP-!p4W*mnDM-Vm^6;1?m>N4cRh*`=|fp*q``*HJ*R^Oii5CW>b5#gVKG51L;}t z^^WIVgH3-`7G;FSvv+51NGKGAeLhSSldlty zDCKu`ylcy?B84vJ-A++7A^Z#n||4oGkOx2Lr>a8Xea1C=#V~-nYpr2F^dU4=(*pR=d|rE3-U((CAN zh3E7B;_*y7E$`YBvVg}AcbyOT51r15dv{iQ-}5L@zf7{vO>dR!l5Vff zP0^%Ba+=h!>-in?w|zGuCda9z({-y%O}oOBi`vbEPy_7q!94BZxgER_Sh_6wd0f9V zIwe;E@C<#hd{B=@e<_KG7dd?mVG&C;y*villC29vp`M4IsI4zJ4 z4eoF@)N?0bpRQ1N&3}74F%7avus3tb7D1;Ksu=aPQHYoiTt4@?Fu=>b)FrgbsS29FKSLeQ(a?HHGssAbC~F9U`d6n^=NI+g5V9+%D#~7;8{8jG3q2|sOHm}OSl|SQCj5cj>$hz##M&>Fp+CHpf8Kvh1}t$z1a865 zr{3_rJ*j%`Mho)2Ho4$89+HhH@P+1FdL`dZ=Sr7539icuZnd$;3wsIR83u?R*6EEr z`9;(p7ApRb#)ui_-)`b;b3YJ%JFBik;IN`0;mAV7qS-p4nSuPqL~0BdmLALe@?E=t z&!ifD4QKF>G~iGBDc+2h;dtWr2*(NIl;gxhmm7Lowp+Z66gG^uT>G(n*x*f|owN=}BxnFnL8w+AQ7,+{EZ~ zTBT%lT*4UTc#q|5b9)Hsx*ZvRs^k*wJwS5bbm4QF|I<`5>N2N}_kFg7ab1esMYAvcK#0rONkalH;Q7(*MS^J{P_};ABy^ zs`)?r^fU9Fvd-|r{qIU$Ec;CzmGb11mENdIeko@nJJLQM_E6t6SCWjx)<}Qc_n)e^ zI`7=C@_aG8o9~g3-K)vYT+arvnF#(P(nKgEp0i>!=ezJuu@AtZ-M`1hX^H(D9a(C` z;#*t0ViT0pZjNs>DwSN{hX3YEPlUNPK<kwFfkfmV+Ye7CMhWBa0?4Y|4v02TI(Lmu) zI_j@!#llD=vg5ORI^l7+mHNW(zz(TLA2e+Z-A2LAmvV~qjM1KZWBcUWu@WbK-EJrG zijProqvAv|#8WmjRx{TX1PKKU1CIr9JYJ1lLC#9Nnl3lltqqRyC-!i!<~h8*wG@Wvdpl0qIAFD zE>dIMI#NrGDD70tscG0BCaTtL{Xd${fxEJ3>DqBRwrx8d+qP}nwmY_M+qT`Y*|Dwf z-22||51g^jSYy|!J!{r8_r>vz`UdbUW-YQsg3?VSN?~I!4mjb-*G2X^BQQwlskmRF zOEx8k4?Uz36m?N^sHM>zpk2wUB zR>)xM>&)YO%0(qRIvPP4A@6;}ykZHu;6{!_SO%xU&QQf*{6QMqE31Oa7P>`l7n^@& zd#nOu+VuDwz^Ewy_4@X7N@6I%abls9GGLM^@d1$sb`bUw#Tq|rF+4+2i(?_zg*Zn+ z4=m^$un5giz$l1vRvfqBiOC?Ai-Kr!4i)6XOu6L|4Mvr@7$!oC5FQ}YiL}cB#wA9J zKcot6suV#gStdv-mXFq;5#7#QtlYAPTEL58n^`W;Ieg%Vyn*;C$t*_F;B#QqGO?7w zDxFGKBp#RBH5^nEMO3q5RrB2U_nRBYL3||M-_bCls)yECpO$<$nVb=VDd-S&58&HW zmq0W~mL8oDCW9WInj?`PzHdT0QMH880#S{?SRMX#`$f*@@uGWfg##rbU@0igb0Anf<_8GMcW@GiWMZy zcN&uFeci+;W+sBnR^k8$$7M8Q#oNFjd8MQf6tWiKrexjt-Hwd>Or7T87kLcj;)23HC2h{ymaS};L>D_0Uyo@lP|3#lS9V)z!>aVwre^@T?U=<1E7u_YQ+FmYi=!7ON!J?;HpDEu&Vlr-#F=T9)|%-R7?k^qq6Yxw)Pg}oer4@`RO;MOrpFapCChh zE#YK?K~_`kCq$c?ulq3zz^Q)mHS|DjpDG||_ z!horSFro$;l=L@~S5+g5dXb5v2nn{kqeq_}qb>IOihnA|V<-Yr-}6;|DC$QXf&5!PQF1%m z@Oq-M70oOew))tKDRF*^arlc zvOn2iik(W93KQev(Ui{^)tTi41#!6C6zKjoN+~Xu;*H_{PF4|fn}?61{RKAWN_1Nz zl8u?%s3O_ANk=LpwP{>&iz=!)e;xAPtJy2}S1G%2aAKVp=yVT?s8EVBVf^7A0Y zQw~>t;o}t|kf`JjwYbg{^q3Yf42lVFkel&^>*Ss8)tcY4d~mwM#Bx5V)`%)h{G<@f z#X|i?m!dy$&8otta00Jgu|YwEi;u7Yja=(`&eEeTw&9dx(FRf#cNXX+X+AhLScFr} z>S;Ix@8<45^-cRtpLlSH!tBfWHRtB3mlu^4!euaWj1hyETg8G!=RcYD<@v-!`O0+h zN}A8Nc<*K72A{AkF~GJPsOt}tQEyS;Wr~~BAiU@n*iI@;gPJBFc_z+@K|vtizlGIY z@N~hV;X=*oOkpIZ;Pa84j-N@*qap^WCnD*L+?`(jbRLM zRIh*`pFd)LY?;ag6p?&gD(GtoDRy2C!vuDfr?wV4s_zHS!AJ2#-RRfpK1zkikPj`E zNS`efjnTJR!a=tEr~B#a`pWb8B4!yi85(#O_woPM|E&&6E^I4{cG0GSRQ}85*sera zBI(c*idREQh*#tA;k)bR_KAIW&zeFSG@*;M87O1kM121E4}@)bRfUPRENL)$2#n%& zzeO`td9}va%6VA*+(H>JH}s|0SW|uRNH|7Vhg0Uvm9?5bhYd{?1}=O6WlZGOZ_SN( z*58|}4}*XDO6W5RdRwFDQdA8!*vE)(v+?r&br%9d?WW)zX(N?18I0Kxp;H?7ByfZD z10}%b{k$=B|LlB#39`Z`yyoa?#DJ;Tu8YVDgPzT^m=NEZ3*{A57{7JTwckc%EVI6Y z1)A`>OJyK(O8p~?Rw*IF9UFJ9Y+`I~Y>d)2+mYkC3U-Qoj-n4LSMXOi2uB*v_4q~O z+;fby5*a{9x5Pn%iqcb1==KzQB`%zISYTD)+}h7_zh$+B3upN!z4@0GX}2A9R~-|u zMAVaYnsS~@=>B%SG1sXc48#75Xi&9;9`*Y8MW1&{)Fj<&z*~ZR>OuquG$XK9$y%c+ ziX};U{Gg;{v0)C&ieMt(7|Jc>zWXu7fZ|iXdS592TK)Gb|0(@Sx7y3m*8&L!`{`s* zWD=MkMtPYzx--`&#_}8<)KE$%1`n}zXdVy4n+5CL9$lFJII&i%(=+~ppEMb29o3Le z)?IbRz&8G^hi38#Bo1=h=6I9Ces{o4unyaZXmM4pY9H@HmX_*#BZz3Lhjvg`JP(jXpKrft~u>~4{OR?kTxPfD5NY5n&*3m zmL3r2_ru)hbApu#r2kp{lEBEWnEV7LY75?51IboMw>Om|ASHCQl^@C{Q4L82LL8Vk znojuWtaaOBHG$ll!_5u`i;jAMI1hR zi0fL^{FYVC;(V?LeKR|wUfe&WL|ouJME{KwBXMNf*1z=P+xvQ{jE!?~Ss#)+l6q(T zmS79hXo)x)Fi4@>m0DHXn|Pd}DlyE5I1d5>3UglK36rMpMYKz+Ez0HHNnQ12lM{@c zpu@Ng4f5a0`2+VMPH3-wbM+Z@D-I(Xyx z4fiLtc2rfUt{3!dqXks3F;`Stt+A&QLd0UVg~InEHR+TK*YmRB2%}Auw0};e$>xoV zO`T0aLuJ~o3vR^Gb~X`i4hxkprbRow&*XQDY*?*s7h^e(obnZU@0S<7|38)KfSv7s z+eIu7y_xdH)Ut+-OrT-#B?@n>DmABB9sXs?n_$B4DN9Y>-fGo4L!&WSk)HUVVb@}U zg81~nT=)0|4vZ$5l^Trp_?&)`ZX3D@mqh$y-+wDTG>%Kd@2+Uo8}(=?V1P+}{NkeAaPp+)p0ASZW;(k+ zV00bUt&yGU`?1vFEN*mQtQ145*%~r=&INGVW3gHwhC0r?P9#}Qg0;sQ9p97LY&8dx z6L2-tmCWV)p>hc|_GZ@geFm9u4bAs{oh>!NsAjP@x{Po!3ku{l5?6uKQcrh1RBUyp zn$oZlatX%qeVwgz@XkCvRckaP50Hc*ukz8P(vuyx8XI`ZyOidROszDQII(C~U05=6 zJ#w6YKnfzoPp~%ljBru6+K`b0=X9kd$bH!CwxZSLr|%DiDWW>BH(KIJr`3@n%C_x% zQPNyQ(ag|l*C*4Z{El#QI-)k@$(PFdTmdY9wdWXfAQ_PhvZ3qM4 zX_R&q!rfR+dm!eUyfKj9L}j?I06|l(!la_Ms$?)}HD#Q}|8|NXzow=v6pvd=NrjJ3 zo@jL&0-F~eFO${K7h%)0iCQfuN(1FA;_9TGXst)IJbee)v88J1Pme zf2OzRVtVu0fn&S~-qS@Ml}xVe&BvV8a4<@7wB_9EO3L ztv5q~gCXNFf&|b!)o(rD_q)=&d|0-_FU9jJA>LnbqwllIH`;S=(CH`?30=$8rQ#&8CMW!d|S_8C`$kH`CA?O?B3F+|5#~`NsKbHrX)Ab@B0Vc%z5P z{V|^siV2{j!C*XGR>tyvoM2^NW_h`=Uo);_YNm;LSZ|x^Fgvl8Su4tJ(|e=q^LghC zyK2Drqpmh@|L=Os;VQ-F^@H8xvq5~#cyQlFM?aAMy8o(eTc*^BtZnC=5`pi7c5=aH zQ)hsEm(KjwAWm?*vg2fO$|BW>tC_)MVPi&z{{cNLrDHnRmjbPY{_EqJY^4+wfa+`% z8PF}zzBe46 zwD-+l+ zMx(fG%|55!mE~|v*Bv>t4PqyLcTi}5fp04_nOhj)Lve6!~oA)#zTs z677WBA7-;G4qL%8o6IR!D0=KhsH2aVy6pk{k3BqmpL4V@xZRuP}|2d`WPE+)>Z7&wx&6eX8eVvh32+>o&AuK*8(yz&> zUdX;oZ0nAfld3zE64X?9fsy;OErdncmTHaG+|f+4_op+dhtw3G_dAN^6}G$e)rXF& zKuFBLW5F&cRqE9vCI_(pc2dQ!J2JY7!X1au$_kW!>$r}{0&p}o@9_U75P}8PN4)>j z3awcEa6TIY@6}2axdVmW^Ba(>QnBlJbbnrkbroxgL`QVr9q~HtfMZC+L=-PdX0Z8& z>A0$I3WC$$)A`1Rr#;}nh#Yrd{SLneX`RuZ+y98Y@&3O z-1979^LQi6E`hqi_;$lteyRY4e0=3xi%E&DZQHX;$LERG(n^PFX)c?*&X-4@S&WpC zxHsa}Xm}0(PkJ%!=PTOVM5Oq5>AROCS=+?hsV;Hb?pt!T_IFA2j(@gKt4~#NG(%SE zY(kG44mm)wCvuLT!^ zY}seZ>o|qaa2u3VT3<8y*t1XK^!Jk$lg}kj*=(Cka@VC=n(b1u%4A8b+@wvD%cE|> z_Y?c(dg11@xGzx3k&=vGr(Ml<&(3z8$yr>h*Lb>;M^I5yr`GBv`wI&qWRrSBD&O^7x_JZeHp;zl3EDn;I; zMc=;X;|U0X5tSkA^F3$EVD|I3w2_mn_brjZ2WXW zU>hG@S23iH<$B9ilEu$tsY%oUdr#c#e9J^nWc)J{ks+MPLZ8~BcYIsgJ(bLfSpKUr zB_GSD!T0&7Y?+#@Qmsp=+jT?k|9$JL$#bfU1;|U&Y-mvwVZI;EVV?v~)1|?&wldkc zQ#M_%QkPa{=s(uqyyQQG3(4zLHDJ{;oy3BSuZDnXr+c+>kKS6Nl%{`Nkl|9#){ zVEKP{a~`wt^oyP#;^qDEhu?F`gb8VmoHSQXstPq(g^E<-L@{ZSq@|r*YH2CCrIl4; z9N)XdmOsAS7g2sU}+5cQuQ0Yqc+Q6BO2c+@B6DZ zf6>nXff0#|ZX5jcSu=966GCJPLa~6+2axyVv<8y}=JQtf(J5nLUHqHthI{m~iMtkP6xg%_v_;_R85xmn$%xbC zI-~~}baNUZLtnsoB{rh0=11#%bIwMm?Uu`nugy+<7{JV_MyCt?U4W?rA|yA|ZZ@C4 zqheoGTDelz+=PQq<^{bJ(VqIaCUDw%Wl>pELNy*A0ZGau?94R;V28Iq#BLJh##QLa zI#;t}5h}ooZ8pX{Uq$^}FM_;Ssh&gsJVBRV%OFpWA0=B?ktPQ;>(#Ju$!^yIX^V0; z)oTKlj^ZKdaFo(fdOaHtW%j2D1LxP&l1+|FW?s)Yh7a~5ZCl>l7#%>Owo)998z4C{44-ymEdB^ROmEIu|5qH)+)(~q3OvnVQbgXs z-0Lft2NOb432mb@>-|GfAz|<&R``EfQR|i;pCo_8`xMMmU9qRvNu#G-hUm>4B(&~4F;rD#x^CF-c+nSP6D%sOSqpTr}RIANNRba`Y<~S#tfmo+d6XPD<*k{U{-K?l6 zRj`U;-cq*-4tTA%J&s2#*6bP_wgfqxPuA*fjiG#CP|E18V(hl1Ed~3J8r6o9v-Eq-E;lBI?oV=c9d8)-nch6Z zp)j#|9K3}~Owo}OY$+)z3+;dT!*f(?76rLTrc2-lcDP8kbw!5OznxS-5F9%4MsS4T&}Q^jc8&WF6Ya!G1eI2bIM2s4=;hKhhDgz zi;+C9<9N~doXOq<9*fU37GZ?J5Y(%6hi?>l2a8p;`?KpWEOvd4dmIt>5#IP4@|zD1 z(3JFc(xxL`h~p7|4QAEgVGI>h;V#6h6+2$^|2I8l+r%0^?)?$oy#9>h1IUQ_9eLvZ zU7S^;eZ$ExlaWoQy~dtzqh%f*Zu*_BRAvXmcRVjEs?)iy7=q4p{&{^N`n(T_u{Hye zwx|2v_J$UDwV&55FC6zFC{%Rx#098PbPv8 zB;?h4t_pV10^G?iw1@F`#vR|$C>-y@6`yZSeJn1YOwl{W9QHmBWDvHl;lV&Mne8-` z3=oq882?tPq8ai!{*2)hh{VNSaX#ixbbp`FY;if0`*x}ayj2vx+v)N*e)%e6 zZui&kbsRdEJw^tDmiJCw5$C3air|bA6z;sgBx%y@Ylz(kg>(Rn=kInN&!#)?$lu{G zWjyPiAOEd@_L;Hl`gKJl&GN({$noVs-oW0D9Cx|$$xm~owAzvQdbJ!5I+r@nzka2+ zx!`>vV9ItEgR1L#)4j~~W@Y~UV=0A$4GNPOoJ1 znjJ;y&1zx`sQY)Ya<76Iz2y?S^1)wW>2N4Vp4;XBKD0eio=neI0!37hLg zjgkAJd@sc8Qo|}ZI$33!Y|z{|ypDz9#T>dn&2>#;Vbj^os7rf=E~(tW!T#OGsfC%M@S|RQ<#g=pl*N2v*pZ?KHHK0 z>jhVOQx1>wt(*!SI!rzpXkrv%=l!aQ#KkUY@9cxXaPO8EbE%K6 z$LnS9N&hFTa)Cs%+X+SYS*cuu2%u}c{Uwoa^x5}%##)IHhUbobsB2I0HupS2Lt8Qd zyW+B0?+yb1|I@hfJ<|6g!n#}vYMgJGrWf7IiEugUnkBe!Z>FqD`T4P zfBx%c=xg}WxW(xCG4AnS@b0)IB@S{1pb2+=eNGAFA49A>p8w6;Irfz-!3K;0V7xDT zalCJO7+U`RZN8ZgbY|el13a2VdF@_jzl*O*< z=+;nMOlA{C+s)RorvsNWwb6dQcdLtYi=|c)^K4J_o-TJ%{{4oza^DDwD9KWv=Phqk6bjkW zW?^jz1gydQz~J(lDze=1!}#E``8s|3D!C*adX@YZ;c&TaOjZLRsImD{S)4F9Jdsnm zt9hpI#oQjOhD|*gE(79;6V#^|xXY&1+~^H=u+TUBy548+XMEl$jqU(p1pY+hIL>Gu zd1W1?!TRmzeCINFjU2dwa#`*7rwie<#b*zwxa*!NEWm%wt)jBpj2s9KZ`_;@bfLW( z1dxjFp*I)}4@@A^QkYJM+#R{y%5>Z8V9(eCq!~H`Vy~d*si)fTW;sILc*J6Ofv!A; zb!PIvK`~j(SbIL;@_TC&dc>}0N-*>VBzxump1^fKhI7hrI53BTL&%^5SB=ad(!vs7i-5?zVNfLKaF zt{kEh&Pz5U4sl#x(u(N9(%!)RuA7MvM`KHUrRnO6VDSI!eT2YV1gSVv&HJ&WaM(OA_(G_o>5U% z70qI^b$i=xcD+!WoSeLDwgCV0-^q@>)sO0{yL#WL*H3vT+0j#vk``sDYj;t7vBf|J&WJZEWvt@{bv04YS@Ylmp~W16wUD3 zOAWRrglTe02ny6+5!zji(PGDDF>|sy)IfV13E9n1>^ns<#A9U29I|CqF`G5{O~h8r zU}(<=5GaS{KZ1;64o&-dqKGjxz!1SC&?Pz`Oc9NCTJoN$tMdUxXdyiQ$djeuy)$o3 zN7e<*V&(p3C2PcFG1)fbK=W*rwJPaVn3XM5vJ%CB#r<;!{>bx+&>KF_xJ?58SnfQp zF!(pmVNjZf(k%%;S)_;*2pEvy1&EkG%t3CbYN+YeW;p~V4!Us)hw#mV7%1l*8_rJ6 zS7lJcQYjS*$8oIC7!fM6#CrS`%V8~gG$|=F%9?&+QwUJ0CS22|Fe%z1>(?5x$E;ki zGu*MG>CsQikvPb>n~sWFhQs-)VKQ73cNBAbshf6Y3VnPQ3;C!HPux1&-1gq|)r&Am^;cMzD| z;3)9xaM{e#PuARtfw4x)d7dxot&lfVa5Xh(wDY7$Wg< zK|~_`z$BvN2b!BH#Q_r>Z4~9o-DbN*TD89872j|oW-}GiwzWe`Ow4k?l~H?G54cmD z1V;-CAzAOHoMzyr_7{mF+U|1SJ$6^FGLraDSN0{p8FvTvtuYVj!vKrx+h*Tw@T9R%N@?=AdQvT1Ow zu77)E9JjQVJsjd`1#Zjb^p=9LRM!m&FV}7nSY*SowyMie@)UQfSHKt*H! z&J?P-13I=yMhVi^)`~@8JK@-n8Z=ap^ML2HG%f^V2O(8N3r5>BooweoM%JJifoq#Bl&`yPXTyv> z6j>Dt-}h-Wt`d4D!--T&Po2;HX6x{sw%fji2T_!RH)@Q z24b*D__*mSf6wJ!M#xpA5nY3`dbwH)SlAj7*47Rz@jkenv1 zVSJly5w^)dcg-ixZ;oJhG{G)m97`6CW1dP{KT9F>zYpMnjKH zR)LJBn*DOEkzj1RubcgZY;$MRny9$TUmfR_z+d(>QF&_-5V&rFi z&6{#4!SL8({l=Sc+e@of$)oocLL#kYG*0Xx&Rlw!NiCiTIvRd2wUe2W!7t;%!avp7q^U}pO(7c}Jk z;=y;hZRN zzX!R7zPhy^hXyqMp4r~D+EY5GC$_BSpg=V{5HuXDBuRc|Jn_U`HXzguOEJu%7zxT610RV zFu-l0fFeO)P{3^Vpq0gI=5NW2t;W^4`h?w$`T2UIEe#ctOg#COdE=jkCxvUCdhWO) z&`HoM4J;nuJJ4h%&FJcwH+-P2vvpF)x+9P*ytLEHF>X&LZJ>66c@gp?QeivZt5_H( znEXcnWz|&$ZGCyOGP=tlfhd>GglI~UW1?ZLXH~^t+hJ}vI926q8Uyb!SrTu7IsS=7 zEZLybO#)PmfQq7Gw=Ok$#G`)caGntLSQ`*})GhPu&SYuTYHun$0#RAnx|BUz@2Sl@ zDt|vhL2&!{P-plF#E+;HXkGFc-Iy*3HkLl$hly8Ys&@5D<+qgQ^Zv+@&flCnOAb9` zzH+caK~6Ao=nk4>CN|TcEy%FjHEMM<&dLq;^mp6OgTx1odYfbT#00vrzarQN9f+;R zfp=rT{r{)C_?v&+0QKkie`jOi@EuO`*1Fh{`&2 zMjx3#Cf*j0i47c@Rzfh;Yxo%i8`UqJ0wPF40P$5LM_b|5Mz1Mgs8t|0jKQ z*C*U8a+Z!qxj~N*CDwWhx@xFfCJTdN1ENn?e4olRP4BL$;DiuYA4&+$Y>)z}gf6@g z6E`S696=kcrXLJgi<$DSsh@{?5Sr$+6lkK}^^GUj|2%EEc*#)85EC_-@DVzckR;yW zGGy%9H{dkSKhTT>(+7U-Tre{o$*Yn6mx(QJROL2>bVHXvU<(o=aT$EA`Qdw z2{(RWC70#qoEz)-EEbfnZ6T}0%;bnO$4B>{buIhf{&WaR%YBT)F&c9PA(0)6AW2Sv z9k$#%XxA7%6-|(j+wPGbGNznV~@5RSTknx#M*~AvE=CgbUK+2{wE-- zngy+!J)|u(T^Z?<=NBEYA6%BveA0<-2L6Hq2Sh$`!vG&xsSg8OpDWG0Ts02XqG)Tu zR8Y%m`+il2iN9$@TRdI3U|1rW)QPa%i8+*7I;>J3YqvSUiqNKspI>$U#hbaFV29%C zLXeW{J+8Q@CO`}lcMAkNgms(077w3^YQbf(LlKaLBMgPY^^&_R>Jo*bg(_J0f@djy z1skR|izGpSpvEFK7ZWn(!$^d$j-UbaM>?TyL?)m@))0m%Y}C-aZ2$iADH7C2_Z3El z1{{v-&1#7X1x6>Sz%-1%9h(yZjyx$CdP=eO+>f9eK@TSDW{6Q{iUTeMlWq}>{5n}` z>;-bLTHu0PbbmJlv&RW9l_@xKiK{^E9&*WOI96k|WOXwA79{NNWd>s@8!)rPLKVGO ztQy@eMYJL8!1USIt66gYq00Ue@*Z=ULCL^V%5((laIk%&ZF7LbTyR+k@ug zHi+KGg^tn46;;#-VLy6%JQ&n?IS6iwV3wK4agri7LbzWr#KXApi?RwTx+f(8NT{Rn zKIgAm6GZ+{r-NcySX`mS^nas&0uls^Gx~h*$b8@7Pb;=G1m6!J=w5JT{c5Ij*V+h?(GV4puM>DF-(+``yYkk^E?Bs z%}XabzP|67DVen!%J>)ELDXj~XCQzb z{A4*v-f-Zcq!`SuRh2>@YgAnDJKV3Z6BimM+&3O@uqWUy&s6@S-1W^%dA!Q#6^kCV2WMchQg8^o%`!BW+!3=S)Ov6%Hd-{-ZM zyj&+}id@zl-)H>UX=a9S(0Pt$DC8^laP;D)puvl#&+A^2T#hT`>t!BZ`ufw#^O$6x$zCW zl_BnM-cBw$a9N&E#o~AaNZ@%h`@WBr7mYkF-0dCrUO@rdEQGaP`)olfC|N7CfV>QP z)4|s}z-k6=UGEn~kboP=`LjRS?SMCd<7@F@y5n=n=jVN%^K?S^!e!Z7w;8ba6<>DU z2?JQ>+xpw-Z52EJ-cHxe$vVY#QAbDOANtBpowv-@xH zCYLkpivhAzE~@a(PO}yJ>ce#7*kb@_=gsU|NRG=A0!~&kI`5#nsnl^*Siauy&}^3X z!e&%9eVj-ff2#7YwMM4_{urJ+Gu#svcB}o-yS3d>fFvZ-cfeQ1?+d$1>kCGsc7svR zXe{1T#iHl^?uw2 zJZaNoHt+FlFupsSj>C5vtcFuevAFHHB6$92cK;vx3_?j=-{0=rt_UADef%h61pQY{ zc4d`JlD4jJX?f0U#uPGU_XT6Or~Ljx)T%Rwal8{m;VgJv5;MYo1w~O$F*YmOq9ME+SBId$GPhO0;fb@${y7qmJQ(J&D z!j0qLD9`Ed977>%?#UE?_juX^`okW}oKkZ2Y2lRpiMs6puJ5?rw0>8{Zuc!TXeX)1 zSE#v%!*kD;+l_BK7eWb|rR4p%Fhc#yzdIfGu?14ZsQddy_*ferX()!?Ph@cdcUW;; zez?Pr;T}@GLOA}fb;)UtV~dSrPLBo3si=mlhtXzBgyB@L-J-fj+e4U=WBl`a{I!5@A?isY~Ns&)IK<$FIy!-|H_>BJ&@UQyX5B=bH{z(lSe_L0DNoc-U~zB z3b0@?wEC=Rpk=wkZ)G|Ci5>dPANymNJ?i$oulLp`v>HRk^8Dd;wMPJ()m{d@@0z^; zm3_|>+nnDk86LM=VY2|s>4UrH_20IRkHC+!>{G|*b@hi2_V0d2WrU;FP5WZ`Jp2H% zYx3%BHzbuq^y^MnbmO?J0Y~N0`w#Zr{aDSm`>frqF%o$`VZ@tZlsUcdi_w32TF@eo z(sXF^yFV*dP%Zy4x&u^^uJyQznJ*^%o*!tS@A)Y&5VE6q7#WTHw>nQJHV%#kFi}y* zgW9p6I*f)@z9LE*hN9JeL4ZL6Q0VV|i!f8xMa1Sz{affs&XeN~nz>MKtmy^T#}c8i zlwfb_E{vo?DVy(;rszy@6RFzDCIWoTOdjtAQ#k+dwmtkbxbNI4CVzbU^RqOO^$1WF zyv&0@^{69>6iYT3GKlkz)f$ZGH5dSkDhMLML`Aq1O91F&3dn>7A&-}{(+?lUW^U|A z%ieKbb3J`ux6td;a-JL4KBwAzc~B@6`7{XsY;A_0Sbzgf?}y&j(65HhxA5=oYQ>H`R{Guam@2lroh1YhKE1{QnZx<(dlsFUGJC4dNfK=+q;oSN5>9gB81S`*8eafzFr;i;1Q`1cPpwy z#0*}!HF>QgtJP?Uzv%f|EHt9=Piyy2WZQ&P?%xe3s5Bs_P^$^GRE&+bT5ea;+g?u=YwdixovmhfiD=8VThS*oS-10e>`ktRc09S1 z&vx6>txwixODzOv6}B2}h9u&Rawtf;fr4LN%A7>A&tKr62bIa$e3=95Eaqp6H7sZ} z6iaR1;x~S-1@3$zHJz>%%1vCA+!7>*%h*5XEaCO0$CrL#IYEXYNTdFU zese&y_RXRAho9edm;nWP{rNW8vR1T?PS-yh6lRuV=4he?&CP3*?1_ox5)A8};A*)E zXCxn6nuRDd2I&x$QL2aqA`0pH(WM;@Rn+Nz#b9w$G1BL#7@DdjQNPqsv@l%#s9>=; zqfTlz7_X`bIu2XAGCo&=Q{~4Q6;K&{L%ZMZHMSNcr*)e{WUJEdCztgZOCqOg4ru5` zz*uF;*hZ%=>SBv_{|-4wCMk8RM7L>di5RHV*szN(C@3h@{K>aeGbQ`QDl0f7;B0At zjf#; zs-&P1!p^p{VhKKjCj>%5`z?w!j>$sDY-X8qm0l{RrwH62iRReR^RI;Ok(hv3t)P9l zxP7hv@Q(RBmK%T&BTFjvmEH9t$>8&2t<>HhS=BQhSN&QjMmUQkr=kxE5T@CKXH`_e zD-I;8!4*?iAtkBBAO5uOJzmzFIE>pFZOfB8=$V60N?eJAW?J~Q)IU!~k2G+)WM2Py z3f}$nEM2|b9Ud;`Ho_|VSsJ+u)OMZ@b4(qZBSkGLD)FaB=_zk4nJpArO;OURS%b*8%nW2eKn;ZLoMS4El*jPkQ4|puQHuB8kvm1v;mDKMaY0^iyz}{3BKFg3 zNL1g&o$DlXwOl8RYQ^hhcD%sO%p#5NV(#zX#H#-WVR8tsAQXp<2b32EA zkwi0oQ`~AB8k%ccP_j2eb3A_S7Dd0gy4E*4KTWE{e*Z=caPTbG>tdV2nBG4n!_jE6 zL$UR8Jx(i;PUrVV;`e)jYdWPfJCb$Jx5VxpboTk#UIoCD5+Mn^Q^Kg|%5gFN^a~)_ z@kIRr5I645s~8$w{-URTHRf&w`M^#yKL&$LoU2~UOT&4&T}b&|gG0mkF4roDr%0#P zTV0_8g#CcR3X?ouaXr5T*CMvBeCTub%DH<{7|rJ?F*e&>QLnUFnM~Huzcecjul;&% z_PYVvBeg(q%Rt&~l*)y_z(-j7+F%y zH9{Yc=#-VQh^4xoG`5EtAk>+%R@oXQ+DE=?TtT+CjX*3csg&sFh>=mh# z1nwKtw|g`|1O;%! z!=nnVf0h*ro^&BKg%hhWLzSAH>D#&O5n5(6CR5bkhZBV=H_%MBT9}ctjK^d5#||e- zd;w+EcrH%!rdQ8n2rIQZ!H48d+!>xo3O3-jv6(_}8jS`k5(;Mdb+NLh*&3H$vPjdIMnD)M@lbGYs;&4Lbn=hOAT zqdfWTS9FHY?=NR^f0pp;?GI!snc@oVIh{(;siJk<#K1*u%d{~GMz|@Ks$Wp0L4}=y z*!k^_-Xxrj_K=>Qp(+)MIVCW?#xtWcHX99p^gzR$&P~X7XR;>}jK$ZR%qhGqndoUD z1f`QnEdGJR3e*cV2?0#eT59zAfR}8CVvItvb~}AXm#e|)dUZPEcUE2BXP_sb?_6pb z;_yC4l}@c8tdK%GU#SJ~<3235D=5TSV(%x8;y7F$39VOa2lW%@?u^4b-ZQh-8cu=a z=<{zyj3}|WUoI(1t>CnZTTCWDlGeH%$qp&}B%0{clzZf$d$^kSTbN#$UdrA+8=ZcS z#o`?w-33Q?pNOf|u7_Ek+i0~ULlXGJUv9ymV(9HRm$NDGPYQNmyrkl5SyJJ8*$FZCx-6$^qLZ8kN4qkTSVKZZmOwfD2-jQ^g z(PFikk9d4U$K|Y#lSJV+y7`9nTIVXST*5E};WP8$ifkK|H#ys|-2zY+UCtIW0Aulb z%NeCofav5HiPmvKRxEBo{{I6^L9@Q7gr2>6pkT0Z>t51Z zbs*lOv3LJby7uf&&E#riWgKGiN0Z1e@zeLp{l&s` z|B5O#8}Q2OuaFRBGUMY9`C!7wY}lQ_1CKmH_pTl3+_?)z(Rn`qYzhk(ub^(76jGa{ zSe{pc#-M^EA|{%WVjmw){D`BOr|H_UD@j#qa`N~|29Fp@qk1(dDL6-|^m51Tw-BL9 zcJ16jLQ))+t0wW?FN<^q^+-YHVJ=nu;~*(57uic5hnE z$5TEdBBmmJdS5};b}g9o%?!T!>RT=p`RLrS9lFot$kA-NckO`Ntpz(CfCLJe{q0vA zJndt}iWL+V74rDlvDB_rlbXp@sZueD3Ga_*`@Taw^yKsO>)DB%%p<(=@^gIt)ptZ! zsLV4jzC@G8jp^2|1q?iuKk4%Crze7la`Er;&Ec4qG{ct8LCmpC!bAW>8f=!Pfev#LIevIt)gAK z4%Dh%kyDvR*t+K+oxAnKtNQt6^#&5F)Fw5hp5@~<49=cCM_gRoMZcTE+QDIj5ypQK zeym{hU^y-7S40<9G)%R_R)%fBs@UYdrodEHOxx?BI8GKj)TQXfNa4X$T!EY- zRa(@9ah8xY30gP)HB~%`6kl5=_N|iH2tQEGiI1#U*uY1zrrHTKqrK z4?;o5WtRX*kj0q7gMk|29m3*Nl!k2(N_H*&o;N<8#w#CxPKD@bM*7%@0Re_B!xyq50~~%r!@xwfRWYO~Kyf6_?EFQk zBZU`TTGD@tEJeo+LZC^XwU(rcR9u+SUME6gI^`(R1X+TiXqYIt0+J_|7f@m#QLL~q zR^L%T4;1s8NYg}DGz6waKO;N=N*z`Dt-K3+4ur70jM7x?yk9>E-I@>K3g*%Iv$^@Y z;WX$riihsG6|c0Ye-w#LF=K#`7*fL&Dw>oCX^{s>#cgp#+UrBeQY#f!@!&_;jEsgw zY7IdTsPuu*@Y#=R)+f*aX?;EoXT3=)O#q>x3!BeUmSPIagtnL}eVDj0P;pU;iH2?q zQz}y8^Odr1{{d>$sBzJ6rm$j27-59*cj33HfG=k3Ii9=F*BA2wUdrezZvdL6$?4Ol z?G!wdzsUdury5ZzZV)Ppka+A{9>N2{Wf^rgmzaSEO>?8!#;!{`?^(A)Rj9Tes@o!= zRTWB$^Xbqwow(Q-Vq;^8i;W>BHj#Vo8;w*Wtm{h9q)mn*G!P!! z0xWSBH(>-qs5aA`ZBQzzZ78WAqEMuU2AHZF6l-6E2EuJ?9@}QB@Bpqrk1VffBnm1n zE9;C`UV5JRm>6PXqlt@+B{n9W^t6r?n{I@nSqc>P@mgRGJ)lG&uvAg35UUr|NDwNj zeY+Q6lPY_y_St6jefQl%Tx>jX(Xk}N#1R*rK!*-JkRlRrAtbnM2eoC{DE5q~fESIR ztes`qxDj{=6dKrVwMqtTPDrDe*I#~~goHR^qT+~&iY7WbhHgFklX>!tZ3)|Y$o85N ziYstF)t)be*IF0Ck!SXx31N+ma9i&yt^l89b_uK(O993++}pm?y9uIm4d6ks z&+DWfT&y4{j4;9oiCNhKu9Zj9$~A62rx`c)iUo?)6RGkBA`|lJT~a>`OS6*{xC!KH8G_h z#irMhGGGFgY3-llVF+oA83^E(Z=bL=b}!bO;EC*-)6k z$szW|z9vZ9115yPFf32BEg{UGwI;0(g^3i_gNAgBqVk0ySRS^&(ohIpLjg4$fhC!O zLz!Z!x2WPz`bY-GQR1k>Se4j*6ydh!K-%s;B$y_q(5we7+bFhlxb62HIY#Hf?XQ5e zt}R7SAKUq+xY)PEA3CL!0qx+hCoqgK!uX%Ur3yaEzYZ<>C~vqqe`}idhrEB6`kkGf z9lW>yZH04ET45aw3|ngL(rncV;I=9+?JWUw%8Hv^C>nG+TO8TeIb8J+stt^U#%)ZAx)r&U0XM@ecxf*0dcXLiv+WT)l28IbN>+x zE3vCw`<&a9b7Oa`A6f3_-$R)*Ny)Lj+qq`sNY3XKk#%@K8#ZmnP=3p&`RfzPGJndz z_WyR1g`dLQY`*(p0mVLNoPvgC@S0`kDA;Nl`1j{PfUWC{2wmq+{+aQoUhR@7H=Y4A zO0gHU?XhznIR3oLI-{*4C}Qiz4IIkMw!MNu{Mt7f3LQf);>~gIla-Z&s;K;xSUC45 zzWZ(#rG`UUZ7@ z(+SL)zXYGKJ&-o_NpL@h(7|ur5bYbN#EzaRg296ala`idn-113wY=@(Y?0WB|LFFa zg{8l0W-Q;E<#|&=#Frgnn6klYrzJXI zT;wKJ*8B;*cBmOi$k_vz5RgzgiBUJ*NMwYY)l23xYxZmk?W*e*}gZj)*ECpcTq5tt?H-L{ISo_(DQrIzYOV4rd}X0R=eW#|OBmB5%@ z`eR|*>n3zGgYCRX$L&@)G&qL+6S|8|nQ<=nZrSx^1lDcY?PcdGXtbAYhm$N2=%eE~ z4KL>IvahOqe;Mi^oIU&rs|_m$uGV*C7-(HHuY znVE@Vr3C)nU#|v27Bl&s*J)ZeozYLcfLU^m`Lk!zp?ya>b?nHDS&J~GL1E58Zol;= zQd_nrwM9B(o_T|F`946hV(B7w?%s(XKe^e582#{lG-{U4kZW$^LSbR>wiCD;=^Wa= zk%9d#C#6{$W5&KgQIQY5D3=!>8$+W8t$E><*EyYakgNLlrfH)F47++HyN{m55E{ZL z<>^Nrrb+#_O#JvWjN)wGePn=^6pH1d5qhVML6Kbk=qG;gzQzqiOSW+V{AUOl7sfO#^2tP169glogACId6uZPEyuS<&aGa38zXwq7DrgfX{Y}>t^ z+}v!&KJ_?FnlvJ3(T z&&yc6Yz;mMh$1$vTTcHzmy_1KC2zd?JWoFTH1B`<1Esp)?CF!-dff)^nK4yRQ8J#<{p;MP0%$dI&KX4)Y1b1FDh?eOsY1uTD zr=ED8bA?u3X2IE0{PV`!X`IrADN{aT=lZ4eA25gpP1|zK&9_tP%Vov#MfB|6h4yXR zF=^_zlt>lb&_S^udqV6#iA0(bq#wWU924JtgS51kbi1rSt2S?E!B1atS@-rdYLvo& z{#WqA3op>ILnk`4NoU3nizr5dQOufO7Sg*{SK78~%gnjU&;eiR1%?bA#ZL>CqXP)5 z%3lf@YGv9lf(CgQVT2LJ|8`u;7z}mZ{g$y<{=HDcFf%ig&6_u)DT-1y41BQ%{67(v zQ^E2yjJWY;?!NC)l4IO#-@Kf+#=pyhPdtUH7xLW8uMi)hkXql%Pm5OZ+MDl_oZ#ZU z@$d5TO9ebV_6aWJUZ9{b4-mZh#@poPmGJT8k5LpiUXRE2ZU~e>g1hAH*IuD>$1c2d z-R+c=`f+>R2+hSkk37uq;Uh_kkyMD%dFqMLL_|dK?!?b{{Mpx;{?4N)s>*$19%9gt zYp5D&Fk{MiR{XM=H{Kk_hIMNge(g;xS@a{-D`-{~YoPE!av|pwTQ_dvwaL>l3$l51 z^wZpU?<4&4u2DSm(g!SFvWaW@HsQq=Un29Ik9Wqu%fbZ<89C$%X8!mSdv@Cui#)hh)8*nveLbzXeR;%NKw+wVAE=%YcM1YC-rpMP0P zO08b3UcLlROa<00U&_LtX7m0>(=lBU)T$dt#@6FhtyhmPznn>O9GHb?cw)?GF1vgP zci-QHho2fp)rwJE)uR#f7q4W(M<3x;^11ikN4f6C>zOun3h%!2E;DD%=FYqCuqsTY z<2^G_L#uR}L_U)~`Hc1JwlZthY^48oW_~@Li4!LA!pq}1a`ZS4KJ*Y@%$UKh?YoGMie~aB zud#dGTHYM@7WJDqMmv9yr^k-vimPuTy?F|WaVpz)A7iDaR~hkL$B_Gp$MA_Dd@?x*0_l@^ZDkBPno@FC9l8v4v{hO)Tv#Q zFMs-sx^?UD@>`Gb{nUxfpTCIbUVoFUz3X`WjkoC7qdP|ruH~+OKElm+-9uWFCcOLF z`<5?QDAcG?o#?12`_mjo7-59*{|7FWFLl7VIRNS#i)T*68ylF6N>1x__>qD;r{fIIP*}8cb-%OoM(`W8QcU7Qq%MPT~@z9{M z!abwMaXK#_Me(94l0v6I5rO>Ju3JRC290IApo2U5_eVPlr9-$;$-ZRmS> zA2jVOrs^T4Qbp?4P9#E>PNaEewbzs2Ddf=6Q!JjhfWepDg|2x?NpDAbdZXZ!n`TH7 zp&-3g8$O!$73EES3el40tsjX>TGlF() zzolWr6xy^(p_Oxme2L%V%ykR5vJoi5BS~sKU+<6vJfGj!B!X>N8Es0{vC!Zqy1zb3Div359 zq7zBQDz#|UstqmcC$eb8dd}t-le>K@m1{I&2WYYguP2JHr+!0GZWjA9j*{Fk zo%jf^MbQ#Wp+pFio$J<+-uW`FzVUiuWht6@iXUhEOt-6UrBDB>(EQnKTf2ZSXZ}FL zf82n9ASE@OrZrrQ*wLMX8CjT8U|)SDibR##X5hLPF^UzWm}#2HyD`ox69#BTR%e(WINC zDm7@D+Jva#eL0d-O0zcUG_C38y{U7_J#&G*o7PafNe8aK<1P|~$-y-n*mE)q)g8l| zZ@*+w)dU7awLaHns`~?_BVmLQMi~Eb_@l*azh~54$}qgtapm97%F1H%=FK76!GHIo zwJGhCBN0g3l9&_}6cAOp5O*YO(? zcZ3%MrwW)5*Oo=UAykcjJU)izKQH9IM;>Cv^iE9qU<^Vi7`C%e=tYcw?L~gtn8Uai zA7$5urF<}JFVd8l2vlKJ8cWl_?=NN4t+&&%eP<$l1&n>sORbvKQN_iQ=7k+b6M#Xa z*MrYzk?*=)8ijeKn0`Ns>cSJ_MMvUxyNGaWk@VIyzki&_6<=emt--nNH(UT#VK2G#g(?i`+f;WgT{Xv2)DZ&M-Gs+?Br_UJ{$ z)U4l_2cCYJczG5Tg}5jaUqKc=sbDBBRK-PXbOb(sDWDMN(LgtCLqlRSX4@fBlj0&D z9lBh`L-*f-CW?7NJWWES8mwQk1c?HQMVIGwEBFi@i6ka60@JT!>N;_WN!<15)6|Xy z;WvnnQc=}xP^`6Lx!omxzfMGy*9vL8Y}uVni;g`oBsMRmWeEy<%@h|E z6CGQ_3VI4a6%^#>5nm-fpvj$>5J%pT0!&k&s4iPJ(I7fD8s904PFi)jE&3GzDN*c7 zY>U)Lr?fDi=%^}zuy0a@1pK8X=%$sWYnlcM7L|=-dI?OVX^?jzpNObvs{qHY05=R3 zMX_n%-7YLGW{Kw3&|Dh+QXjtJLL#GM0}oH8;YZ+b021<4rv%0Y>?}el?WftGIY^nk z!U!XbF#fY~F(dBx_WP~e!HXG=Sy@>D51^Ei#Kc60!S-*=q7i_mQn7Lp2X}7Z$e~P* zo;XA6PVLyVW*Nu#>|@84oy=dll3x9#fWsTdQ5B6LhC zi1tKKr%DtHfBJ#L8OJ%Ckwu};u&Q{=1g;D+j~}IR(X!ND(nwCO%E4XRIh>J2PF@j>QX8{){%nlm3uxX5 z3`N1^Re#gscaq$Zp*JguUkYLqlSxjD;`_-{IhK*ZcR#M+tUrPlO&g(N7kEe~Ko~SC zrG4j&iH+je!98RiJ;mY79J=-D!ron*S+{y6hYp=!{-UL{YTp)w=Gfx)nVhl##innu zLas*-?I$s*B5%L_4yMr9z3(W|@fGQoUYj@Hoj}dzooQ6NI(cVKk$2$&k3RYsy?XU! z?b@xx#3Y~;WwU?VMh@)DAijD7N=gdZzjYNZmqw9c5)l)RX_^Q}YeG6Qd*Bob1jC~C zJ2tnAP-00*X~gmU>&QNxiRO)`$k2$4iNw;@u(WrDlqga`kygQvkP?YXWMXA1CC0LE z<8r)i1zav7ViWB)NK7FuH4{%9HL6wNm-!3GJaK|UCr*)XdQc-1Xq(=cpXYr^UVc8V zhy)B%!Q)bq!XRj_N+%P6I*pogaQ9}mu3Amz(PLy}p2igsMbEz7nDE|5Y~8Yx1}W8$ ziZ%Yuda>w`R2rl{z#+tm7v+dc1&^Z91`j@z?C%wTo?A_A_tkX8QH+fmhQ} z)gX(cBC#I2gi4gx#i6a+$vmD-PWE|pGej~_QE8N##@4mV*u7yBd-v?-z0bcTtxInb zA|i=4@;P(z1Vu(@36un(BD`^2cKKy2n=_k(`wnpUSSDw4i!3sB6w32aTGQ;uP!yV^ zw`bqhUs$^EXO0~|&dJtF`DG|0(1!nCiy=k)pf-})vBBaAS@_>ab=s(#C8zQeDK$BX^#7=X^-6)IGqZQHhv zP=&C_2aTXC$zRwlgwPmx^>B*LW-(&OwY>H2N3`wMg>D_%a`&hkx$};@>Dsdo!>_x> zl85uq|)pH}VWp8FpnKEj2Gfe@A&#sl}=#>Tb3FzBiw-1(3DIeR|OGLodU z4I9e{oH%|w{rV1J>6B~L&1 z8a1m|MsvHl|Dng&uwn^Ah74!M_djvN9d}YWA%z`fRwWS#Q5p{iLT0{4?n=P_g`bc6$7~EpAT^?D;on1P5LakH31fH zq}3?DqJfYBr4#A+g`@&R(Xmq}t{c&ZM<02Repe3W$+0g|Q0hY})_hxI?Zw26OWKlh zLP5bKA|{CkA9{eLv%X;9l>@lx*1Oqr=oknuiZsxq&sLF(=H7q(lP$l@XUM>QeDujw z3QRAC8pF*uUCU*in{mgTcW~99t9gIIBuaHZhJr0&Cjc+l^IpGsIyc=gg6AH(pTSoR z;O%$bM@OSe@7`qRmf&%DNvTsKke?}?DrNzgDs8&=W$2ZCcKIf_dL-_Hh#rW}} zVgzUb)4TLy*ucI#{?EI)dDP9+Xx56`{`CMAqT{*eh9S)U_G@x4EqrX>yp~CyenV-gkK)2SrcHXEbz63!V{+`^ex7~#Ei$vu z{R!V!VT2Jz82=ggElQc+3L~F9d9sWLutJ3jv}w}@RaFs&F0EjzVtLD~{G-1zh+@;U zNNH*K;)Ilpz$<4jMV63tXdA8j-pRa0OG&MhV0F&^U)a^GPUSDCm_iANQ<$cSs#x`| z)=k;4+#y26wDo0Gbh}tZbA}FtLC_eo=wK`=Hxm?xzC$AL0~$yxPs)(e4y}q%Ux)3< zu{=AbqM=Hkb$b>Xs_pHPD0UsOX&Gd~VvEBb72!M)2!W73Oxvim^iwrVEG<_6QwaNv zjzy~3V``mG!Eg89k|L9KQHfJ^WZ2rZnjNo~LP19$3>~BRJUh3pV*Doyd3nMIRCY^L zTcO2LlW@ky3Ct^H=F6cgakQ5Ox@{OZMMHM?(LwqxEm)xjCF07!Z_lSYaCYpm64>XF zx;@sarP+)KjC(M=7?R&6bxdI?AzR+WQt}H+&`p6$l<>v$ANYCYcBXy$E^c9)C8BKW zLP>^HQ@6%N2&+#B!15NGSkcX6W?@l?W98>9Xh5?n)J#`L&vmLr&Wx=xtujZNN<8;YZWay4^{%K{$pYY7XlMS zN(?(C!}%0T8CDDlBaATq=WwZ9zR=f~D(Wx{BkLX9qGFQml4g(?IX{y+;IGs6k1 zT5wrk-bnoZ62^^tgHxxnEd$UrFolawow{(%h#`UVXjW#Db-0irXV(aYGelA-K~7(R zZM=w(zL@OXzKzenm`+hqDNf_!;u5*}=9{Qjua2$l>JI6<5)uNnw~CN4a3DhRorF86 z!78+X=7(hWqP0p93D zo_b;o(UESPn$ciQOXyeywSUXJE>}blJXQ<7mSAG?!|d;wJ8u!_rI;d;yYG1rml7Po z^5#MrqHaaAayO-EE0S1YQ7H{fvxsqTzRvF5M@VUwM&G{O5r)D1Ip4Bq@d|Y5aP&cJ zd?JrMKAM<_$bi01Pz$>3SO-Q!C_ydZ!2ZGY6&y7s8zz zdk@)_!U{qtq_=6ubvImVYhstFF$#{6a1neo2pQ{gpa1e}rp!BK`U8&gN?=|^`Ll%) zMi^oI??8Eam(cBhgfp=GHn-bNT3Q+#H*N&LFbpBXgpfSD>n59QYzii-=85=>K~AT7^>+lALId3Q=A!8YTh-iNy35;q&|Ps}V%H-4`h>|2O&*XlF=&qym(p z>pn_K70W*)Oav;X-9F3sy|^*<-*1fwdF{jJ_o3_78d6mkE|=>!`(Cy`Ay0btxr3{? zgpyJnzv;s5cB82Zis?u9=i%2)5MHdjNDWgcxV>I9A^sKv=ht&$``t|w@KIV)h#^(m zW2j;vFf@$_w>w}2mW4wJ9rDogH&$+hJ%M3_5yt-{e$NwFp33E7-aW^gr)kIg-<$eDF?-N*Lb z$7oQm4l$7te{oO32qTOz{&(QFDuMs#zQ2d6RjZPoo*wWBo;h=doSYmK6vcY#l~^~d zzoAlCNFUjmhuL%F1U_+TFQl|-Ov)UKv<)!96-^tdQ*Av5C8G zxru>;hp}eE7Avn)hBi-zw9yGP+P~$WWdJ$|ojXzHC)9`c#~?BM`5Zd9pCZ$=bNqtu zSyj;nGDI#-NCnWWkgSkoW$fmSH{YfRiE)Xm{8=yoAq0~rOk~%-z2p@Z^72bBlaX}_ zT{u)V5-F^_Q$tZPi}QHozJIW3*8z0FZ)ghpDJne2Lk~a6v16zI;+}*NMi^oIXXC$O zYn9(Ow1D@I@&*D_sZxdX^z=ZawU%R|c+J=iuGY;SN+9q=QOw%V{g z$!Y~$UdfRt|^$PSgS@4_?0iV z)`D8V2KhNhcznzwoH~EOmJ}>I2NG#>_BrcDV0|X7N!9&@oIZWZTHT_I(lSU(yI6*9 z!?e~4X2_g4*9-QytWtMi@DKv>a&svuEwTKb!t#(?p9iDtTnnoxBkxQ$rKXiKpc^G2 zeKbSbWgtyI=g$|S8%|&S1PZ1C`#CGd`IP@!jW{&G9^6`HQy5`{5yt;nI3eHv4jhl5 zW9wtBuzKkdUKWCOtx_3qc~|!A+0BAQOOV1%m!5q{ZPo~*=qx|Z znMcO)lNeH=Nz)ee?A?<{w?@r+wW&}s2^Eu)f^#fh^fTM{9V02ZI@gXIMuf*@-_o7X zsLAQ9qx?8$9+_wJNo$o(->wb8SHS!q=Wr@3lTPhh(zR`KW_mR^zPM(?roZ~@|V?Y+PWKWbQD(%98R^$31|UT3)_n%O^VK+;)n0P z;pmw>r0St%^Ol^?$tEKsg9c4na#`O##7B83DavEf;zexVb&$$6>oQ=#Kq|#VaP;6l z7A=@Zc3vsoh$wpZy@JLK>*9%tr(vV|cohX#X(8)ZuHcmy-k?e26ow7xLC*2R%vrdc z+=4ru;nrM~-El#v2hu`?hU4aBwdtv(L~lr3t!>L`R0;f(KX3qRYoXst!ZKp1@Y2TIz z)ut?x)&r7a6EYj7jwvOYrqZB6T_U|I7tWpH=bvVCFf$8W(RAw6jdtzZqDZWB7(V<( z1$;UEGtxU;hQ};so@d_t#q2wLg4o20jJn}kylxjr14XDI;}iTJf@u=Jn*|X@7-59* zzZiyL*fj?KJvfHo!i5V_6cIw=8hqsb%V2#`TOqJYHR{s3(`7WMQ;TE!xAU)mJxrb+ zNpZm$ZochKcJDvT*_>lM^3+TC)M%okTs;5e!%Ut$8J{UxGH(Ifc5KIw!L-SfcyHnq zDkRs&8xiTGvD?HISYA7!^TsQ$vvco0Qd_q~Qx$|T@JoZ_lvG-G?oORLbx{;Ikuk9} ztX-MeUryoKm&fD7gQ;j#Z8~+X~*6zmi7cgn!$2|AS2gJw6@beGf z^3U6DA=hWHa@h*L`RZG$)vU>xjNLpw=5aF5=aY9fn{U3JNrB&wP$iXX)TC9Hel$&K zf|+}oJ8!$4Jx5PbF-~FhV-K@p<4*jgxlH}^Gmf7sqIT_uM0z7p5tyb$-4o1))2Ljz zBCR@gphap+3eM#4{NrQryCSJrtp<@^4=&Y1!+Q0Qr6oM`_!FEj_Hq39NhZEKk+{m0 zaI2*}bmxsMTE2!I+jesAU3U?cRF%rf)hup6(+}<#nzrsh`*vx>sd>CLZXDCTUPMxb zM5ayrkmsKqOR+SV`o-5QUc8bzwd;})8^iwn`OZL&jj2bbF16eu5L<+_{ za0hdite`w?qcbV3bMJ$rIj5_jMG_ZZk;ZkZ zG2_Fxcz@F87>1v(rc7etvW+Cytj)TWOStd;$H>Y#hhcm4oVsCwL})I&QE@cy(3|x1 z*2G5|d_V0&#=bIv*u*3@tXav^Prg8juN1$umU^q<9PY0 zNBC*^Itu+h-XHfmuf92f*u-R9stZ-MJ+px#uF&e?U*~3CDpxa%Fv1Aq{{sGuv^~cV zv@*EMDlz?~5ZE0Mf|~Uk(xYb!;tW4ujenJvt=n_oBli$(6mUGdfC=xs!IKYlB`N^&caFTyD2WViUJxosY9<`skrmc z^WmI1Tz*AAs@14LoVy2~KJYgC4;>+?MeV>)nbqAdqdswn;CF4K-lD17Mam|&z=+XO1R&Cr&i4UsRsKu}m!*LJn$j}=e z;KZ48)KaamvME8A3N`A~qieUO#3T83!rOQv<9Pgu$Eg%kLVk(D%&%wCx!H~QO@+&^ zxSA`vHww;6NIHN3OsSAmxe8r6cOu^7;llpi=zc%_2MwZOofvVDJ!z-E|WMevJkxEf_KK8WhE3*|HVHS4?Kuh!ON? zpURT?KhS^32wFFc<-pd}Y}vJs0eySoxk$pOzf{sJwH1Sh4yC5Ih)HucFyi{*oNHa3 z*`uByE5}E}xF}MZG^61BNm?{dVfm_!+;`hx{KZA2wCv8v8?NQ%kpmbp;&%4z-%nyv zdm;j9e|C`AG>M6gr&EUp)K5x)a|d|w*{8X8+_zji@G^!D?8mLQ+|9wvEE?6TQ^t#B zaYLHas#~82AHAJQicXw6lBtv4WAM;^RIFT;I&~XSSXxZ|diB}6XAh0*RU|sXMg7{f zXxX9}QPEM%pY{>wvd_}4bsJ(`rBtt8oh{ol=#bV7)&497>Q%5zP}5#hrZkZP{H985 zVs)+=c_XsqG~3s&;O7;qXfmt|hGFo{^r;jP%Y=_VAu-Oyz^jLG)v%HHg=&8gg5G#! zAzRn(BfHaIb7po|U6y3ak}Nm5V`GZ3={@uo0wJOI(2F5J=$#M} z5-<<~gc=umLLh`d2qg)aVq;Tn+|_K!>Sf!^ocH&~%5 zoO5Q+cfN1=-gOP5N90kYdbt0AhnYBGG;h7Vm?su4Wb~L(!~laku#iorld=glDqvrS zl6r@1$cF6yf+?l`X)rf-xo>w{RR4tmRw!Uhezq>T3K5{C^^U;D6PWLR*@& z;|B3;n%4FnDr;(j_c11p8BIrXJ$Qn)B6#AL?j2QCfuz%<(heR5Q7O_+g8sC{u=28? z^sLYSgee3_nDU{y__Fhf;&93N7x9aE57VD?{VZeSX9Y(j#cvlr$i&#j9_rUb}1={l5)Hte$Mh&KNZC@ zSpc!7ej_8RYbh?sL!lW}Q%g_lCLiD_3nxgB36o(gWo7Fi0+yvSKw68S#6v4z{#oPF z-@TC=e{>ZuzW55Ce7=(2u3lW@Vvs5z)_z4mGJ`#Ra|=HBgWr!$y(p?c&Kte#tGj-OBq*Kc=C%m9!JYt15%h zep-jJBa9tUN=Ii$5T_VMvPm%26)KZWEyVl!=&aUqfG&Mc8nrBPE&I|Y0r@Ma=h9G!rCu_rnYVhbFaFDM<1WZYp=dU z!}@g;6&DhZCrG=7bi9YZz400c9eo1l{ctYd|Lzf}pyp0daUp%Zy?CBM+lmpR%BilM zz!_(s#YGpK%lT)0pRrZLg3=~3Fwazch9yiOP?=^0naW})C@dwA4nY0-2hc6bFUOH)2vywmf8t3Kg30N8wDLOjZXzMdvbjjtM_k+{fs&*t|QiO%P z{cARe@_grfq>z0M{toxwKaU+}OyYsNeu3i{1dS2}*hGs_1`UHE{JG-B<1Bt>F(;mNA!p6K zko^zX17#VMhM29vO(R~KR3gFJO}z{+uk>kkB^WebaBO7^crK~5gX0;BOG~I3IfB)n ze}Q;uy1F}Q?Kh07tRf0Q=5-iTDiBEBxt_sw()|6y&lo*^E4-e~y#CIIoO8vsTzv6G z>^N&Cwr7ai#T;_f2|W1V-PDvRo>=rd#*UkeWoeH1-f^6F;U%1Z?wRZ`y)Ml00TpP; zhytw<&&6?^Y~dZ{kD;%|0ho-Eb1=Se;boVR?rP<_xfhdk1lM&)BojE{7>Ea2Fvh`n znh9HNPfu$zZJS&097FxuM#haF$C%1|B3?J2tyoRU^Kf0)PsK?mNhW&zG#znBCwl2m zJHhlfq|#}S;J*K+A8Lne$cAjl{)eX2mJ@ToZd<4z^3NXQ>pru;=^slYf{qrk%U=8Q z;y^OdZehM;^#a@7%#9=UqgeNsx4H&cEnfbZR|Ls)yTdx`9!pniXHHthn_C?Bul{0tl`3xUcl3CaVL5$0<=G{fZre?a6!syx> z%7%|-&%O5Nrh699vgQkRoH2&o_TGg9B`Hd0YuM5M5YBffVczj*8^)_?vb zd(N54VaJ}twYT2O$}d(?SX@BeglU|A&Z*e8VO!j^U1*F6IwgO`vhZT24OmJa(Kul@0H{jRdTXvI;R+L;@XR6$Ix`nz0@CFT8^* zFTRye&(?GJ0efRbi?Af^Ya^>7hE+}CsBa(2tyj!t{Fvd?uW8`gn{H=(btM*Q zeBEV#>iSPHejKAAh9^-h9JGpJRFoKouU4${k&o6sQ>CyF9Yc98Q6Q-zXl=;Li!f)m zUHRp_pYhk%r?CEukEs|j6C3axhu2isgy;md=#Uq ztGM~fn;1KG6lZ+@0Dk)Od-=()o@T`df1$0don80dmoZf%(Z&UBXJEZT5s4I%>TTnO z%dbOvTG+HX&NbIwPtB+*zP0zx+;YQJOspHrvgOO!X8L57EPjtg&pbzdOtX4@6DJ&W zGW&dMHh+8THGX)}g^U_iLs>;7r=4*+W2-BJK2gDc{@6~OGM1;FdYY|f&cbLNWMPMC z82%%Sr=uwG@UThi7?l;}-22lTIQz6yS+r;o!z_niKlUgOEqsl?W2nwzMp9KmrXe4lGCyNC(Xwxb}wfVp!oX65qt zxcJ<2c5I z$(5T61aIZ=x_@j(M)ZvIWmguzo`W-Te-w!^)U2x|*)e zO*AxZLR3B#RimgXi_p6MLuT!B8V^3akTJsxuuDo9JEoR=%VJYwGm-o#B^4!T$D_G% zBb~i{*wK6@P8dfl63Hlh_=P?UjT=_b*_9xzV${@BQ#HH{lj>vrh7EKjgprlyj4Usp zzJ3$^y-8FwO5U&v#@ALss+YCvn~5hqDyv3NU0KfNmS$QvwUgFS%7<4_TT@L$88E&~ zn6C*8$^LHEuU}8yl<7q66zkSEP*_pRh~fg;+d6PvsH!T*GyT*z)YH@J63Z`S+}N?? zX`7DCt@I@0j2b%{TjH$W&_a3DX!7Z&eq$$9_Ot^%OHzn{&U z+ZZ!uG~y;%vvwUL#!g^Zo~EU71736()m4>PLMGXDfa7%%h{Do2KR#JUhaK(W5AeDVjGm)85&G$}48f=rNSUd^tChBlV{-IEfA# zH@48#lfu$b%BrduSvj1Dap~#ppsA^ebV@-q#+d3#Y#bUIn@AZ=q^N{(W5!Vwfn;9? z^-Y`TPkQ7Pl`wkrXbPecKgv!5$w38pX?l7#vY|E3*m09+-&jvYbrp_*j!m1HGAie8nLLMxv3dP6;L~J z1fG+kp`n@KwWBD=&nL2l^xz@IkRcngA^T6-|3o`DS209Hd=E+R-nMNl%ld~J!nuEk z@7vnizIhPnyJh`=cO@R8Be(*#F`&FaZ6I*dnI4)qe8Tqoox>}CdW&uA%7S>dAn_xk z7$S)AzbnQ8iL+`neFH%t*EI^FhCByMcHng&}=RFPfdTIWEYi49^sL?+)#!lha(3Fye@OgJW6n~XN5 zgUxLYCfn-CL^@yD>)@7NZDML()T zfJyxZ5xfQVA{a}cJf^+=CX%N*wG70?GWG^H{C+nyhaxOk8{I6PKMM=tkm%!x5vZBeSeL;f`EWocIekzN^*d}T6o_DHE7lq6qJ%HG%+K0n0Z@6~W=l!zu^ z?6?>i{UVryyZwU^J|)fy^0L`^wZqEz?CG$y>R1huG+eSfjHORMOh%Q|?3l-OBNPtg zoo>Q#6KWruBWKnuzH5gt_O7ShV@pI1^+Hj8+idw!EQg76gn{(-mv(z5x57v6rXCH` zZ*JBiPN4um0qhCC+h_6jvZZ0rbnK5L;*M-?EU(J$kK7w{=JcB}%Z)>NB&m$8!!D#S zw~VmvM_My^Z3qx+4`E;Bt4I-xz550ylq`30bNo$P_r?yNe%M;D#J>d}E}jNHr9g6j zmt$wo$9jEGERwcogtCncmG^((yWIOWSWt&CYsxP-gY@9w;JS-vk88KDKA-y|ChsZW z%+Z(dJAWIb9QGRQWFth)zdyT>;-N`*w;Mk{Q#DZLP}DW&AssDhLcXVnz9FS7c-NY~ z-pyHGUyLGP5NV{)Ew)*zIVj1(L4n`EvjLw!lHpHa3;p?oRHI{4B5(JbHR|&DmLS2-B(%gRLv=0Jf;p^fdvcoIt5ZZtLHo~pj)z~71Fc};E? zN_ST)nmFh~_4&e&9X~xfNk2_FINWcO@Zd4qBq2YtBvdGNsinZ^2Zdn~>H^i0z~{)o z9@-)<@G?P2cd#)*_%T@?GxF(pJSW%F(%pi}n;~#mfApHfs*4lR#f|xZ;Z&`EhjAl#<>ogAEd>I6fL;Gxw4cyBn7c99%t589_KZa zVf6Xw&IZ1F%48+JJi3YrK5qD7E506u*3QZ$&d0<6?Vz?t>kKR2>W=VR8C z5bj9}f?izb)L9x6>+N2!TaPM(ha4PMi`K$w^p7{R!)^rL3({kd8?II6fcn5~a2eM8 zBusdqk+ERPQp}6Y^2_QJdiTV%cmOawiej=AwWNM9n@Z6Cs^Wi9ae_`QgO{_S(baZ^ zMzl3&)~fKo$Lw=)V6@#!wk5;}2OcZMT7c~edLT~YtxZRa4)=(71ltE6qSDo~>umD9 zmt_K?9628A8HK3ONjCj)>_BNjT*%yS=)Sr3Ldq@~$M8ta%+aVx6ZaIzoajjt{lNld zyZ#Q!?$W?bJVsBeUo?K;bq0`Z4;dAkvCLT;21wQ$IL1PW8 zWD%BXhq-df&c5g(p5!U|veR+)!bgZwa=;Euy)f1V1dExWy4!*sPY|6d8p-t!9_0x8 z8N!mirkz)YTFawk-~v%(u|pAnLn=o(Wa_-$wSFE?=;dlK`R$=(lSVyLxXoN%dfZF$ z$BJhIq|T9WgpHu%`m6YpgTKFnk?5wS+Hf2qJhtH2N3uv2bY!#O4Gh>9)De9kWh;x9 zL_T}{*;=}ckvL_ffJBw|I%GZvn&SD@LZS^dmMG}-cwS<2Kn$tTbWBMeg`l25A!v5j zC0_x(q0cRX#AnHVWYxw~|9sp3HVK+oYgd4;4@psiQ3jnewMcmc#A%NVk zBFxz91wPDiwv{RyeUGMD^C#{(9Jvn8Qmuo75TT&`(`x$4VrF~W11<(WYh9%l-CF}V zSWsl|N3)$8EN9kYV}#nuhJ0n9K9ha(WlJ%@!D z(5LzYsHYPk5TL0OznUa1}BhV8~QN9>*r026Loq7*?+R7zK69!B8lhBN7Nkq+Efd zHvtzMKd8hv(k4u}B4?|$KW;~GbQ%x*7m}*L5y-(0P{D6i(Es96m`icCL&t@*UkbWz z=L&wEt+%5y6aIeZ)K*C)J#}>an5XLgSTeM=U?lX)bSO?N}O(cbh0-<;$QPP=ZMI zy5`~b>ICPITCKQrIWAT4MWorZES5=mWlt1vM5O0v@oo&*0`E>v^=BN~HmBd7dcpeO zJ2EIZF8KTdPrymDNf$kDFx38K1>LAw?bF@hvG;lEk7I>>*-~oka_KytAp&6E)^~6e zX6+HgA(fE9ru8`hMm~8254j?(ctU5>9#*Q+5V6VT1E2Tak1W?OS##6^eV>+A&p3&( zcFO_RuWpMRjJoZSR8wjD2ku0>{>Fl_x9m$vDw(I44`%(Xr2-vS(FoqBHC}R1W9bF* z`2hm2MX6`!2Wtu}JDbYAlyK$u%rtpCcA-JM(ZWR^V1m;QIVFa{hU?U&;Oj?>cgOzIHe}#$)b|}Vg#R69 z*}T`uk6MGQ?@_?KZoLIz?eJl7VM6*g9Jaj`3;NIn>?@5%ep)p2_C_T_LB--~iVCKJ z%r^*1nBc=x*{WGdT-2Jq9$#p2BDxD*!&B4Hm(XTAb|Bmtqt)Q|sZKA>DDq^{qNMTI z{CHc#>!nG-$h{|cFAao>4HANb1t;M#IBN}perI73;Nx*sXP8KZH9Oi5O4S$nAXedi zM~vVy@{@dBw$srP3Cn6kk47+ae|}h4S%J|Ey^EH&pOUtlNEv-((P1@=Ze6BU%Y&FJ zEpG<>Q^S(KCmN|J&exk9=)k)yx_dUGDR)VlLZzgm(3rmBH5ugQ77K-0tYV@t6xEXs zjGy@EH_Ku&+IsMsCXM@mXkF}imP(CM2T zsG^}MZD>L~Z``0If0Kimt;SYSrzs)Dj+QafxMWSc%@(R^h0C;Ls+@^|oP|YPODhNHEuzVpu-C{APtN_FUQEl1 z$7YO7Q$^NC3eR&^?J6R%@|gj z<@T)QaaeqUQuglR(8&ebTOfeH3xk%Es>A{l`-s9YCw^8KU9NB3+i;$BQX!^3Wn`vp zLmFTLu1go2Tv$~V)9W3r4FJbFwD{K=2IqS4xxgE|m|xIShOmNb8WyH;AW;2oiif3F zXJIgeX)7N?HyiV(wIi;1-}vxYovjdFFn#ogQT@-EpVINw#)CJm&OhZaN(zcG*H5j? z^jNU4h9;VR_Y_3{z0n0UDuq+5>GjU4sBmKrL&xqZUxqmZQHJ(RBk1|_b!nFOMRkwK@&5pXoMrfK{4OU z$vMZ)%+AZU{g-6rgBlT$Ie!#pQcdpo%B%+c&msg`rt#+>$?DW9CjG&S}n4t?(mY>Hn)qa3kg`3ich z%H}gg*kZ;XC&G}-<{KD^*aIGj1gc3CkHDYG4A z>=bw}&+Zjk(f8nsQex=Xk$HCh!sr{Y9!eT$Jv&PzblY>eXkEA84zmZdkS*=xJt(+leU6^u+YOblHhcw7 z-+Dl}@-ru!`@ADg3wUEQY>rH^a@(9)VRJcP&GY>bJL-CrtH&3 zS(+3?eshFLH}b|-iV~-f;j&xiQsDyNhoPl=#N`tDU!3N6?2&QS=}q{1eWt`0&m1e! zIkp4kpK`gP7r*nOH56hd(3TWY46xDUPtI@ig?3%HBefMoPt|p$K?oKkb20So4Bk7M z?;YT0@wAXu2A-{{y0>~Q%r8v|^#LO3xJm?pQ~8aR9U&ew2KEBJG_@UfrfVWT5$XVE zvL77BqLum9x3aaprHTUW#(Uy6p( z-m;!!L7NL`lMsMq(UOc-moU>qtfhY|@s!boWR>SHEJN%AS(f9?S=al5m@pH7|3hu2 zy|bo$r#rc#ns#)MjH29H|LXl#$?xS92Qx0WKQvRodH41mUCjIbP(-z_HIX9WUosJO ztnrr6^Wwt%%v)((4%;&|awZ2dq#?i-d`kEwlqAQUvkLfxI3-}u-1p>~v&?njv10?$ zaR+{Ae8VyFA=sx;EaMfKEYZrH!$|l{L%|6cEi3~lF;H_ zGg4g$Tk+%M`f~GpzI+FGy!+4+{_N82xE;-(-<$_6b@b=z_rwd0E|&t12zZa%KaeV#p+xNa!=JSRh+UY@6D1-yq60;ZoW zB(xIrUFP+DE_hJn`ic)uoJh!6x?dXIpJ<9{@-WA6(b&ibzJ_tpqNXZju9)tRMVJjL znjeZ6Oc#{yikjjR^98$A_!nz=9d%<@Xl{Fn<(`@+77<92`66;ibA{quPx8zT$`a<% zmz!xOB>Oh_pUr(9c8wIAx|P$IjOZ^D{n+!2s-{(F0>DhT27D+GN;@Rl9-jwF# z(DN1p4T*ny^K-L;-ab3u%dc-16O}D$Ux#|G2dZPTW&!$n9bcXucUc4_RG0D_peHsb zNVdIZW~I~fTkP$Pdtzy2lU8e+Q+cn)?y#BTdm4?A4!M6+N-<&INFL-DuJZ81gb(OD4jWz* zCP#3#NN*+8_H1MbC-6kj(2_BewW-F4JDV6^KBv$VcqT1Gx>aiPd5nJUeKr~cAy(b; zL#UX^Yu9O_ykj1oJtnENwkWL(oO_4gSEf>;I1a1OUG6GPa%$m#Qz+E%=IJIs+M$af9h@z$CzSLVI2_7e4X=AX{i=Lv$(%hkDg+2&J{ zl91eK)Yu4Dt-Hswtb$!OE`_Neh3U`3%m}AMhi5@WZlAq`5WC^w?1M}g$CMgRK1J?U z?(yBOzvJa=^R5>iE3yg!;%XgjPaK^f&?hMYxBV}V^W}-P7CVcX zEUvq&uIovjYh>i2=M*SUa8F6IsIkgahD=U>>Q||-6jKhXuFUTD<^0>;HkQ#@8Z{Mp zlf0RW%d$Pe`d_`0=mX-zzj-!gWLOk4*;5OHy9>S>psJ^;*FuozJb-MRR)wB#N8c6r zcH5IzEu`_Z(FC!`up8=?f|b)5kFxZL`_G-q>e|B0ftucV(Do@r6fA{ow~*&rOZR`X z`;G>}<}h5kGK5R<52^7`U()2FT2%gN`$%D?(n-hDjF&0;-e!}@ z3mZ&q=?uY^G`2&ZYQsKot;5&PU+FS{zopH*@>WJ!Xi#ej5|Ap`lhGzpjD>kajVNgx zHVcUKc6M}siR=a3@aF{IsmH~YavH0>32Ywe3y+0D^>f)kmI|{ieww7>p^DRf%eV`>zaD0$e2NOHjQC&mcr8- zC(Hd(Y|H5^3C6y_h9X}5}4=1|Z zo!DWouYcod$IflYw)&z(`aa3}y5GSUsKwMJ5W22gnIMWi5OcK@0f5*wxK!=Q5}`bE zdk3ufSbM_^>E8p)q*>`>k$1b2u_5s~n3%e;mD5&kG7LycOdk)E9h?qVqGi6aj~?h= z2BzAy0>P>2GB!~o(>0}c%X`XgxMkF|ebRZ+i6jk??KZ-1I~b)7JP}EauF=C5Z-3#s zpJz=yGdoxc&HlZS;=K7#m7} z_@+r29Z7Z?EP4Cc)hfk*S=da1{Oh}by@)T5Cg2V&Chvo3%>QdW1?M0Hm+`SKjOV(2 zKRy$p`v1f1?PmYn1)28CbNSxT>g_b`fty2KWKeM)93G;@N%!rc0~092U!tG^nHgJo zv;FE-xWbLWGuc@mVFO{|qu7al>lZllQ`hF`-7i3_JqEUI%U)VB?cv zIqjKj?d+@_Y$y{WDQLM{o7qhzp?)R9RY4XF7NfEx+XgLQYNm47n!~YtTs>FYo?2z+ zJ{PtY=0qja-1keM+)N_`?7XG}$8E+)WPB85N8jc60JpYi1Qt?gEJ!wef8~Mot`~!} zOxgI6V7K1U!ZNh<47X$%iC`S>##9({6(6!f8j#AXz-_U{utRvmU#W#kNs>++eSinH zc%ef<(5MC!EG>e);&B@bWAa3Yw$U!N_Cvch469#+C;3?67kCa+cj3qgRtPP@RIAI# z?la3rUTHWsvG;=u!1I_0Q;Mlswt(>Bm_{J)&+`0CB-(Gu^@3~zy%X&e^KJoI$NF-j zA0tO;)UoGDo`l@3t!e_Egz`4zqg19J*=;6fG-xKErcm18k=-%B2pE#Qv1z%M9Fb@Gv+VVdmpNX1XZ1mZ`{Sl}K*U}D2Myn0?4nCt z2<<>?s5|?Wgrx&Ul+=m+c8U@J4WYp)BA$JsA0@Ruw{* z&1ZDk-D#_T!E0-Z67SJ-#Ao-g?Vm@R0qu0c4w^}VMEuS`m($S_6pHgUOTgth%omD& z2ZL7a^oQ~PZjrk#Nlw277;J2>SRh5n5t|gszBDp2-0KJumvwa!jJZHxypzZws!l>P zBuwZjTkSd^_;{8X(9yO0v)S%xzkayS_}alNu1ntjI%NX9Z(z_a#Z&V8ya2maZL;My zyyhhQ&i_czF)>N66W8JlEOWnKXpVt^(@@2+VO(@t!*kn_iY6`)we`VI5HOf%9*3AMzUA^lZA19~h8!Cfs)6CQQZG=@`X<>2j znwrV;H&2VJ)D?=+-?kb^{%XSwGMCwM^|0sW8LSM;A?4blm?iej)|hPeL{inTL-aKD z=bn0O&+jm|Lkx90uU3Yo_Iuwi_^tE+U#st8%MEdqNX1a=5Egpn1>e`lReyXOY9%x* z&HAdQmGPb2^!$gMov-Hr0}mBuKJGxbkC&(X_jfx4RrK;>OLgr=C~12Qp!3s~2g+>6 zjSS&eQ9gTPX&M`rPwZq@_B+5;D1z7nf@qTtS;*UKG@-)eFKfhpZvZAu9vhAvHJ|&O z3u259WBWU^=cX@8Yp!q($DBZf(WWPbPY+S|Lm3Y(aUaq?{b;h2@K_{rQhU=`9k}X& zLZ6RK>|OA%UQA@`0B*BpFMmu)!~GN;!{j~-3sXTWx3q);Ol@j{1KnK@ud>h+Y*gMi zo%$0VjTI%6hk7-~UQ=end64()lPx*+dYeq?SOb?v?=4yE2=9WZ?W$kn0<9nf6}Cu{^0|F3Zyqr;9JDg(Ts%>lM)NLearm1@f%GbkjXELDnramo%3w+ z+&Q$uQRS=7suWKjOcDn^O_F5tnLsEhZT?I2i;hOX<><`{L)i$E8yaRC!sGCORyZ;k zbOPv%-3$u8VZfR4&y11uPGr3y-yww0UyHJDO%jQ8Bp=3zm;)D;QDd}4Lr>Q)r@4-a zhNx)#BMy%Zhc%O_Z~tK+SSw)Oeqg1es}mKN8joajZgMmJJY(ziJ#hIjS#w7gHYbV3 z(`UNRZ=zE#-RZpQyP5f~*&}ESm}wmbeinTWU5COEbub#YGkpm9)weJ*G;QMU(=CR-`@SsMQ3?GCFSpn9v+|BdL7Y=Y%4QcHaX$pO%=f98y<=hUZ#w;%Sw8(Ig|xb9V};!C!1?d&f}Us_763FXt_Li zC5R30g*=NCRJA2Y^!ekiI|;?DHhC3vHKl{xD%d<9Xpx1j14`%q#e=NZg2Uf_j>Z$r zHBWf_Gr2Xysx+pJrJ)oWVeYz?5}PhWY0nf9@Q(WSw$S~4 z^#nZ{y-=<%WGM~??1BYILr_)FE3NlEHT`(va{*v z=?Cuxb@lY{1UwmmOadvi?Egap5Pq)%m;qO}^O-Kw&$)@am0>9tPdTF`gRvMi3u3J# zPo1t{Sc;zQK1@4_sf)5>Cevtd=ha1&?9w=Vzhb;kmFt==i`6jEF^6Xo%OOasMi};j z8EB`FMdPj^r)dRnQ53AuTuUeQVb>%-p6D*yR-P1Warb}Udg%Ih@Zpp+*`lI5x-FK= zBBrEP^c^bz!sOxd0xm=iXX@-u?25y^88MkCUTPyF7O?Yh8L{M>=va3fLN9osYq{qh zOD-jYG&2ekG*l#1hY|Luz9DI0O+5CaV{>YZvIJH$BCL4SJBUO(i}Ljuf2rVTN`5pl z1Ngmh-6PSAJe37;un1`|rEkjuVdx|AW-$G@!L8vT4doc{KGXe{OL6}`GY zt$u~wvV~wtBu!9`jEod7+6aF>EdC#iEtV*{8|DVW&H0XQX7&cB;0D7{ux+`4MkhCxV!+K@0_nqE;vWkGk5=dUx>1+k6Xfl^O> zB4v?xNYxTQ2h+>v2nQMHrypR$P$J_-=l1U(=MxU9V2G;5Qo;4Y;0jP3;()h78HKI= zq!<>^?j!THl!##$=XrYud3_dfcmzZiBN`lXW^}6+0b?tt6(`o4*@*tw6C{~lA2^24 zVH*5}^td^nwqqw7LHCN6DTv2vr2;L`P7FpzXL$kQ23a#CyB9U@UMzm!E3(Mnrw=>9 zjkN5OKt5{CuAMmBqGvxwnHhwt%h#S~Emb0larkJJY0d?ACj)A=qA+~6Asgf}>H7_o z_;s2(6j(47kmtC+t?K(-RlJ~utiq6$z{s`f^giS*45)fg_V@5}JY&JD@?%U{RoqmC zR6Sczy=%N6ri1&@M?B8N8LP6B>BmxBhpP_NObuU z!N>!Fzzn)QLL%L{RwpftZM2TcI(D4r>kk3_&lh_cQqx2;c4Lu{IF?NUaok)bd@z+A z`aaPn7JJgEmw0C;sM8R~*}x<4x+4(PlXO0mP`%2jv^gdI9y+a%{ei)oEa+MNEsbITDDqt*pn(stslo)$~j#axj*G*2)Mn*(fz7&G|yW7NdG?*;p>Ubs_ z8!3J9auZ303I^}ZH0^18}$2}A%?tObF z(r3iZD}$igt-fdMN|@MbQ<02Cg|%6S5eh;~rz+^F=G1;lVJ53W4elH`k|^Yi=F~xJ zsn(kjsf&>FCFLe=D9G*YT6rQ3zIL1y@@0;nxeQSWTd}IFCNxfuqnc{|k>oA!+@KQV zmn%>n*HOSG7~Izm?J%$U=e75o;Ln~()I`0u`O2G^8D=oo$@!_pE=9rujyZXRxe~4W z`LB_f-4!h4Y`t^7%MXRse|RuODyC%U;20D*?hI@?s57EimKYGkg5sN}HxIP=s~8RS zKYl?L!8W^m^Rk59;ULNm(Uh`?Pv@hir-|V^kw_Jw=N{$K9>poUPZ6PM!IDUcyS+u& z;}>oxU_A~EI)9ymXAv|sX#@v9qV?cMFY5^y6 za2e!0xK;t=I(H-+?wnI3TcF(Co5I}Po9~n?-eo?GzJ7=+^C)df`TYdRS&5?T-3eEuyQ7KUwlxV2HTixTv;)Q7gDGG)rU)b2w4 z(YJV!S4rJBbidnOHAA0ErM=J`g>osvD-v;7b`9Mpx^I$f^?18)1aMq3GBR+2j zj6688pgV#5*^ihcE<0;Y#N{Bev??w@oqOvjluI|qB@$pfT zJdrH@=6~2rG8g%`{Pu9Lj&dX~BtiWH#wvCJ22|;YA6_d{cao^ddzV^y$Dhwz13z|X z!B9%{ZwU3jA%m-ig)9u1Vmmt)au(Wu7daMuTJtrshh%bLMW%IbU{75WbZ^yc4qQgo zeHVF=rW;ncTSJ&@{Mc7^k+4*&vyyK3KP~|JP6>N)fhzt!rT5*gQG@HqaWS}ZP>B+l zs2}o>I=r$~$1vkH?gb6qHd8rf-rcHFNicqJ+Tn^D28uH(ntuP1SR8X*=*Jj(zjgP{ZQc$tVS|D{q(JdHHaxy z8n&@TyBI8=Nv??)8j3?wo3jL|Iz)Mji@aN!wSQ?T|MFaDcF-N$jUXH?mRrQ-aTK)5^JGSf ztMM*u|H^y!el1B?g^fGcbX`6zWB1&^L>Bnqef#-7cm)rbHI^K$Q?(i zYfqCbOm{DgAgJpOk~3@FPb1luQ*fhzxoBcZ9{t;RT6*xw9x0puk2fcG_3;6Q^6y$lhzO!L2jNe5ta#V}z-`-f9$Tu5hsSh|a0pGF zw(Mk!wS&WPr(NBc66Ju~%hKk3hOi?vPL3B@1&|o{&~^OJrHm+((+6bF{!@TR$R$Su zMda(&K{2lpX`g!f05nyE&!D;;2npZH^Q4Z?o}3EsMuOt31*R0m^9LW*5(Dqv2rl}z zfr>foVO4d#nO9o?L8uy{TtdGSF~vNMu?d>o$O+_1iLyK39!kAIM8ejWz&nvM z>^{xxPEySA9v|{=-ygdT_NVN~B73l-%7k+|BD^3Q{cO49^Ea$mTvmhbm-VttE-NqU z?>PgxUY`&v?aiD#ZvTEqumUc$4ShbDwqD0@~feS5Uy`v~;M6#+oN5CI5lvb&lV>BorH z)%x+ftrf0+4b72d-o3v}@sym95 zNHD(pGP~~EFD_r;aeVQutn8v;KOiOLQ}|^r3XTRYmPAX9YS2V#JQ$dy7zv;8?I=)3 zRh11D^A}-w4#&4?Rz5GS-1`rg%1U1qug~u5Cg9WRT%S+$tT)QZtXi+fwYC{agQ3uce>yQc;Ct;v@2)ht z-Tws1=BL+c1XNS*m(T0i4jXi6@l2kk%WRfQDI5gyX0+~)6LWoo5m?TK-jE39$*d;` zn)3Iee@oEPBT!h7p@?uMrf&md3%ip+J|O$e0{e=cxl5@|y+(?>M_0hFV-`&voy>e1 zjJEa>CdV%jtvqPk2t2rfxL*VwiNMgc!zuv5t(R3*8bWJZFr11Y{dW8Sl=5_-*ZTng zF*0~S1tbMhO#Lcs)AHIq$rm zN^7iN$0XiYnPajFio=gAyD)d5dygyImM1q=+O0pKyf$1Aeyf0S@PYJ5B&MrtR2v)s z&ZVlAqcE+lgLEUDKW$n9rNV64YBs+SV|+<+XIakETsD75yzV^WOwcF#y&RS);)(?8 zjcrUM#zG)QF$+gh3#jJg&mfI34&H6 zDIMy|x$A+sDxCXUUzS8)KMdu$tQn+d#l3T3k6q zH0J#tukBLV!8HG|j(~+CM%@<-e_zkhg$5gPDw@@He-RENK=$jlpA;`oa>79%{{~wkv|d)GD&Glv`$Q^5`O`wVMB~x3I z^`>i{w;w#*#KeZrcF0GgIa*WM=7_IT&&2$OUno}bSN$%d_B}z}tWO@l4LG7syqUGG ztvVhpjcoA_?Kbd+Xs+iT*~tG9PiRggqWHkPw)08XcB!^V9TO7qY$fi(EMnF7ftQ_d zw?D7P{o-#B$+7=T-Y4F4E>A)Q%EoL=lM!{Fc0$h)_~+NBQ<_Z{7X9TOHmE)?MFxPG z(c}4HVPEj5v5(OB;X#KH8o*LpUZNmQl|fQ6woLpV$+BsO#dRB#tH+N824x(wiQM0q z`SVGRXG*SDQB1W{E4B-$Y6vnn_<*{#J!a@SP+`22qH6MVCH7msNvmGMvQ?HyiS(_0 zlAS&#{3vx}9l74X8NPo5=F*0~LWAStkinFt)M`zZ_;i@+89t%M`TkKJRq1NlNfD~g z_V#qDlhk}%L0Met4e%UtMmli(STLExs@PSeQ(KnC>+rDLddm0qrsudpt4DvXdN^&D-Xt^;G?lh{cfB z1-E^mwwLcdh0+GWX9 z%t&SoA4;bpevFErkr6)eYXFDisx`a(4Zz_@6d*GB5RLE7Rjp;?Z}RNsZ8obQ_`YF( z)g3?|Uh?P>XB=tEr6$Xv@Gq%1W@#$D@#i_5qz^Mx7@GY3_xcVgcHcH9v%$~gdJW+) zJ}SgY%);rka#8Y@^QAJ?edy4sgx@i251p+ul4snGa#hk3`fGgz*-!T7Mx)@|7jwH? zHWb!t^~mpMe-R!g;f0g4P6N9A< zS>^~Fp-7g(=27bHNfZ!E*?8l>()y%XH=0L%Dr_kO3ND#en0~Kej4%1chB#D~dw;o2 zguV=>gh3%QIRyvX1BW|El`f@)mzEj<2Z`aF0~>C!vlD32$w>gAa02Pg6j;rGPo$?c zdUhrksVNVCZ6LkjPT|n$c~pV3ZLvGY;B)@!+pkKyJ_@PfgEl89oEp1fkhGH$gSIFf7(6$;nL! zX!ZMjs10#Q$U*jBS#GOKs82}{9ys_O_F}1$Ba>L?I;~V8>oVJ-%d^`j|9Y9`dLPia zDoacipb!w#PjGsOXYI; zTfD!9P|A(U*m;9P|5ifYa{CO`DX_)LZ*c8`&t3w^KCNf;_|AIhDEU>E}%0O zo0$<{PdfY1Abqn4bU&bb`=vXzN}38T!CZ8S=iqbN!qdK2ndk>RwIYT5PPvC|MT_l! z%V#w6o;GILD;qb=KB@$mFj$2zF5_Z?4HL(eH%UJS>!rYq#}b9Cx?Ll1y8q-6;W$r> zs@4$+6}ak%lNWzKL8==ckuUb@i_vZ~#p}92pS9jj%}Q01MW!2#>q%9p?aGw=twNs3 z-%@FeIxrwkrhg@yn@_K*ok9j@ig9TB5To7=x%(fsb9qN;44|TUmg&FF2OkhAOpi(} zz!*FP7k(uF`pyAn0$u*&nNyR=V7hWCTW-5Cb@tfHVl^p@@za7&cvdu94cGz;2Nz*+_ryO%O5E z)dwnUV01=6R!PBP+Tp8!wCvZ%hADm?fd90w#?tQXyQlr8)UYNlT}7mEU~woIFLxvu z54Mtg{m@0071PVVc=KFhye2b@(MnsMI7>;fp+L-oj$ps^A5@<17mcX!HtrdFAZY@~k+k}IU7>NN;)6@mVQpm`mqbcgd+kj4HXjOSU+=WpU zW7K|h>dm<;#eoTm?%TI)`?bd8nbURFYDjdYkzOKSYryDgj$s-0HsFzurpaxBH!li} zj_knuFDtY#MNU$2nNyKv?jo-LChK=gbK?jHHHmuDSM&v*GPj!@@Mt20BzlVA-~-8T zLy3^Ef6ArtrvePdD<7CHHu9y;v1fFE_kP&G=1?MmXEk(?56HyZ<2o%%dTjTdE2E9u zK|k3uoJ7YGeW!(h*Y&=)C$j|fbCJ9}zCi0$iQ(oVU#}Mr19qM1(q!D<@@>K)`JF|S zZ3-5in4ySgvan+Ru_jqq*xuI!2$B+bJTHlL7z5W=p=S1-qZMks^46@dk0o(m8QjYtwFKVKc%-(qVZ75vz4kbp8SA` zvq9LJd^tW6e8r7Q<>7aBk+c zL|ktBcPR^S|Mrn6q}Q5X=OMB;-Hp#o42m~;jX_fj-jI%cKO!qJ-#X4`JFelOMUJ4G zp4*uy%eOr5#ZYahaTdzO8e%MiZyE!YTFiPt^kDk>mC z4lV;u-{X^sv)a^kX-7=(`OG(GwT7onKY;34UnF=QWF+wOLOUF>2UZM{LTy;)x)&t( z*K%#<9sZVFs=~)6NlTX)DoPIyvB6=3p14N{{d_ueSu~ccr4bzaTlY4aSlE02$4~dJ z$XzY{v3dsP60!RyL=qRFLy(}vrB1l}>-2ep(-Y!V=IKw5p4aHMNF4HI7KWm%`6PyN za)%j`#5>Afj8nSHjDy$w*I@02%ccb)?jKOr-|P2xq8>`Ogux+H$!W;x6i!4cH1b4I z)+kH`u&9i*FbgF1Hv?J-)@oh!V(RFy8M-ZElx9%qEfLeO ziMX6_5V@U3qMP^?h?k2oG7--ZwrzBhQ}6d&r+z_QReP^B=Nx0+Bm2^!L_r7Va3ua9j+>Fi^3Ktn zfbQsgw1VX|&f;vXl2njhUpfzh9*HC<0`Sro55u0X20+1L(p&5m0t2=XrR;ldbQpR} z(b#ixrKfS!wVnnwpRTtvzCr5?6?bDg3pEuv*B9r2l&rdPmt`?oj}BzdT;`QFT5N_J zs_Rd-3^E+21M|0>kJ06F*+NpYYcshIojAS$S+L%(2Pe#jYXLohJaHS3&!@Ky{_DOB z=bI6__JpHkxWgBo21sx3)rdO~g|4y|&Ry>1v}oarbNPfTHi$E2xL!@E zDDcVO84O?e<0l(#;EH^z@5w!G#V(BiZng9x$J1&zuKwlyc(+732208E`P{D6=PQ8e zO4v_Xz_1s4;zl*eKf!-!Uo4x^oXPv6X%9$nQ!xeZqt{iiH~6#3S^EJf=Rg7MVUg3v z*%I|l3M!+8>xF%|&Qd~?`tEFEP{_OUo_a^PvFT~!d&WK`H5>_=;e7nf_0;@$dUSvn zR-;}=-oRdfnS|ddMtAGr#n7lCxNmJWARYJY>jpC_6GBAhofquw){kao1O69jYM2T| zJTX&QIRY@O6<8z`l(O8&cdP5UAMWng9qo0th6ndYKiUQ_S(y+_0~<56jC5*6+6DMk zX*o`kh!GDt5nUKtf(gkTIzB5BjRLqE z%?vCOEB$4JIFTfhv|r^odq^CtLE3Q>t{jduE^x&l31twMml%m;PxS>yCglpsXs<&% zog!Wq)3_L_%auR-myT3}JSs71rU){!u$-C67*tzUWD#0;({^rPVEGboaQqUn0~$qH zcC!@O9uzDnZqY;_S*a{xac>Rsmk4%f7y<+YuqXxyaA;CsNxza&=>A^e@m;^FJ@nzP z{SFkn^k^bSHvKpwl=~5xF#QTcAnGSiXtR)_bIno^D=Il{garxhapn&ej_?v8u;R-E zCJ`DW;eom(9V8|y$n(Njv8@L@I=s~CiJ}HK;aF7HG!Z=8jD*=#6kzSI$WmUaonIKWEv(LXEAZtW+WWacXL&-*=N>o;X*pBEC ze-n*3$4LSYFILV!nLt9>>`;(O;Znt-#PG=3SGWHR1^@2E zYg@A_JRx_HJ?jVzO#sYMuBhLGGP z{k|@flgF}@;`0(F<`Z-U+81#@$M_2s?4Q;P6wDCCOZJO|$)u%VyBZi83k$3#Z9n9k zs#fv8#hM=k12WP1`n+BL{#3(Q#COI&ywa?yBB%Y0$@}>2nM?Fy2@kZL;yFOn zczf7k&$hUmWRm7yR)Q2h=jRwBjRZr@7q}PK^#okD8lHKK`KYS47T7DVZ(;3CU{t31 zng+ICNIvuQTDo8$RfKn4=9Uzy0<&MPhEvf(StUmMZ?;%x*?w1_8cCn~reoK|s5O~k z?{#GQIwo=GVt+$LFp%mgCCx0;zaGBt(|hXqAGT*x_`q#nedx8#1I@mbQ1`kIbM}z; zx%lY9Zz8_yjz=0LngbN&OAsRXaa&D7F%Kb|n+^hY!zy`;XbmkLX4MOIavwyY1-pWZ zgWx+bSlS6ZiB%S=*~9C4x8wRGENbJ@jQR_9p{)7G=uC*tQzfV$yIPOfAM7*1swAmU ze83A#_|+QY19JF(1B7+MXP6Oh(B6W+N0BR}#gEg5tX-SyqNITY1{ zlkF;Cj!;NQ(S`LWG{q6p@K<<0id~MJu&`x4YaIwZ*&--Rsfd+u4u&e;DGl3mX_vIs zKu)f1^?#yK(0_#m2=wlrC8jZfig_qt0)3!pgAj-Hd42c+r#cQEae3mH3NXBE2Bj~G z6p30G*^(XG>*5jnEu$cgN$vVrUvS90qR#Rb_qfyW8w|`9aTm2<)`*N0@_`3l{*j!J z(fZs}ks&n`z>l&Q#|o9#vV_;awdKjxlC%0&-pT*O?j%Q$fgwBz5yDEJL1)#|*F=Yv z5T-f@H4d;fCTe>6Ta+HYSVg9cRKIC#+yOM`hx4Gzs5f`Ppa2gRcDe2{SU>?XiR9_! zzN06h*@fM#z_x@Y(`fwe%o1-VaY~IbOMM&fSl#Lu2&?m`^s%cUQRIvXc$^7xUY%ewSI_@d0K29?HC$vbU#gFw$YQXf3iRaP z?b)g``~14=4Q78q58P1jV?dPePQ_-qGIjD{h?a?<^hU)W|ztp z|G-vN(Ymc9j0ywbe?0Sm-G047)Zs8EPxYuYDdL%Z-t-DEH+ZBXyI_=d7mXx`j(T$F zlO5SN5sbO~jrk;;fR(`YY@p@jjX5pI7gn~inli7a8k;^CAUM4{UKO;|DkUj6s=}^OK#2UKd=Zd7lErpnge#UK2%F#S~A#TIbc)LzpFrO^X!j`W0%EyT7~+tiESR(K0Y=J$|@8FE^wRVV$Q@Gnswq0g#*ek>p?lOo>gA&pDjQ zs&!`YZi0NtZhDT#zm#Uu>2=5HsOB41^HR>d+_<=4PI{}oca-Yk^D9`rLp}KUHw-T0 zRAD|2de4!;e~m@hi5mh161jLl|a>y$ObGLkyF77S(b%i=934KS98 zF3hFN&tcATz+iBjB+Wg0)psZoDVk`?avXi8(`j2!jK#c}ZyGo`@yHvoXacPwq|TiPd~9)a5eQ?f+@`)x5F#`l=4$U)7@tK0pKjIj zx{wanm&&+qyvRhP`+m9_C=mAlPxOF)tI)ch4cxuu3s(-kf6Y2IVp7ZWBJ}Go1Fbt* z$2={}1p$oY`^Nwvgr(n?@BZ^NwnbFq+yhVJDV@G+OyLGRsiy`xvcgdzOkk7=gruB; z8BiQyUJ;%~FRXejM=~RFnPLXg)X2qZ^E(i(j;|CWTmGb&h&U6?^*y56+T5v_cOy0H za5pa04!!pRommmsK8ta1H>(NVw_OqZqYsX9u=}ZZ1FEdpYd<&w|7-=CdICEMdjN}C zt4uF#%(jAwLHM9lZ1eRm=|=@z{X^Xntd3_&;rjmA_0wKyQHcCQg|Z*_Ym2Ph%4)$N zG7m1E-&qw{EKe#oy|>8m7HRub5z{v5j-&FVSWI^)60sfeWwa|QH(Fv76Kn0aL`I^< zFgf*tUI|8D^+)rR7OE=ggELQQTi%QEdK{)u1^(;>B%{I`?^8d%44Q`g$-*IZN1x)d zv}cbb185kgj>qb&jpkn*{luqh90d9Qkg&yvueLjrd~Wcj=O*h9t~(#85H9;|yqp9) zcAOwH;Jb6RXaC4$+5MvV`^WA)mySjpg_zO=(PP_-F(e{>Z+*R9iNL8JNs4TsVO*ds zK^k#;dT)~9`22K-to=8fq*uP^E@o8XuFw~>yZ2wjp7))Io_`m(Ja9VR z!2mc!)|0*u^~9v<#n&M=mnT)pZJwODL1PRWe;{E|4IALh%p6M)te+EFo-vy^g4Awz z!Q5Za%P)B65)C()7>Y_6=Sm7WOn3DZ;^#GCOra1Mn=8s-{TiJbkvN?3Lg0*M*I@@!GeWa1`k!Bx zKY!%BkDTI9Qh}2fwoJA>K0U+X{}-0#JL==WKl*s{{EN$i;*93t3505Ax@V#c^Q=Id$HsiEmx z+TePl6FVZ`8<8I*e3|B~K`g!x<)mf}so*UYtSaGHlHO`S~6;<_1mv<`K|;LY{^U}GoIrvm>^n7gUKg=HBfUFHuH79dn)S@ zr$j>uBPkv^N{Sj zz-d=5XC0jZ>topeglX{W2>z##?v#wvz=J+6oBjCXvi{&aOR?E<9cRFd+n4pnCcEu? zEEM{6vC3@H666n1s=TublD5XcfOt$4)!!(;Zf0*bzKUadUKfV9n1{0<}UodU=%}BZ?umhW5v+m#2bXqTmhQ<>XZl)Bl%B7EG zDz{u#_4yv3C5u@Gdvr7|>6I zCc8<4JQO3$2BYQrTq>%Q^YcZn1`9}3O8Mi1AWC@)f)0Iv8!zT#%F~0o2;chmKNm}8<%Y*d?>lPL+ka;(lB`WqGSU)7Y|OuH)<+YV4)>{D`x+1dpp;UxNe(E?E!iBAMSPpLk5&=U>@lgf4wPrW^%@_Q6?5cg1HhTq1 z6b94%;Ck&od(g#v&t&3321;V)q~ZZSKooR*?bg46KzSLJKylfHs5Jyhgj=)SZ#Wc? zWGlp7Nf{mWk!|Mi1c9v4e+6wLJdywFBZjX7CcdLzZ~8qi6b5!8t6esssE-U^wsf>fvOT57sJjL-M;5ZK|?@wVC(aUlnF^)a9WCu+{-yP zCoI;fqtfA#EEGF$cePk6$KbH5L~=RuQDzKJrYn)t4+Vi@r>4o`4HkQEZ?stE%A}DE zHx*#2Rv4IQ)M(2ZNeirFYhP`;Fj4F(p5K*&ki*v~v0QiO4*#}^n7giVcjda}^M2wf z2*P~c>tCroGAA?zB$)F(T=+a)uO?U!;LEO$+tujxA?vCad)JQS?w0U+#C9fMq|wEn zq6ZQqlLP~mrj{=MmQNX3=I+&DF`W7e4wv6>eq3vW!`h0$t?vzfFYtv9C$c4XGJgej z<*f&eyHKM%Gq2y5A_88N+HbS@Xf``^Fhx&$Jf6ip-)bZGS!FQ&{ML)lr!pE&E|7A3 z&}wu>H-bY+u3q%%7lL@X9Y+tD+0WQbN7m>lvKt==n}p_t-r}?(>18+@=sb0OGMO)@ zF_}GKr_*oF`PT%7@$-b5R*SMyqc2X~;Ts168I;W9(BvMsamDYM+4SH$W4Qq~*yxC2 zt<>)1ve9BMbBrdgCDV2-IPnp8zEqt)H2(!~7Km#%ps*`Ch{c%4{mw3BDw7|RanAFl z2#5Iv72{pOURcN^H*$}fyV%JN4eUUS+l4QIM4a4tb?~^}d9I0&JGNg^uQAtQB)T9H z*7N?&SE`<7i1{PePi1jE;u<|~&ToS@Xq%2;dXdWZSv+eZ~St-HuzaT zTl86&6x;D^{_%99kYoPLv}J7)CC*K)R=b`EsM3{Nz3sZ(>_;7T10wbFC$p!!&-})r zXu^{HAY>S?`{5`OH7a;E0hPa{bT+$vs0uKNIk`25mH6XHg);TLm;}iczkBHLWB@Te zc~Wf1r;vDJxOnXcyX8&;$2c@J85TzQp?a_`59~lvsk%%_&y@M?%yx^VN2=vLx&Qc2Uz-3HgsUjmn9oXI*j9lN}kY_IY+FPvO z5F*lc3N7%vJq9J;yv#Ns#Cd-%yBwxCCa@xNKUTE!GR63uO#?63&kj1?%jzD z+n>yib4q{SulP6Ec=b>Hq3at4gsGy+c9)Da7b(cegCeg36UivT9it~3WG9(Yh0`Xa z14%laQPfpLjxf+rkSXHl-n9n+`YGAOAP?qrqJ426@POlZ0=~5SiFB1(oiJ5mBv6$` zot(XWejO7!aVZ>$39N8W3Q@l!*H7_FD%zFB=?&?1a-JD!RCpL|m`{zT3S5tz`dk&wmmxmGv)n?5_RMFO8tK5UV!sO+UR zXjL7@(9N67u?4pXtHm3+DouGY?lLZ!#hf)65@af)AR{FVgiF{^cEEHfx!M7H@{M=& z@dZ|K@idwEO3-;=7-ykZ^NG*nY$H`?nY>z~W^Xyce=qo3lW4$bfTdr1o1t*ii@(!& zh{~LgCreFej0q$9VL?TVNQ?76l|PQ+AGQed3U%{;)9v?5s*FNJ zz-HkMY5mG5MbTN`XM?^UU)CFW^FfO?>Z2{d=we87%kwH$+jercx|$cXU@AIL)hPVl z&xb+K9(RM1^^VVG8O>jJ%B8wfCNzu<1rmoR7KwP{M34Oj{%>aJ*RvNw1_~T$)hnf{ zufVyRy_~4GeK|g(dI^g8q<@uf27@vft4aI?^8#K6ZT}l460Y@C?Z45s;-i-yee1)2 zRlqaRFD%eF9rPnKu{@4VP#4-|u&y^5k-uY)a<$wN#rW%sui9f;dZB8IXp9Ien4jD& z&R$AYsm0(#NkeT?;9-z~p;qeh2er~>II-|Xm}qyVO7x&0&bDL_>FG$^3Sctd#xSn` zxg^5IURRTmKVJLeXId~tNlBaY#oOj2TrZHjSi)<^>pH~d7H8Kwu{^fcodMu-P}4D# z88u5>ZT6;|z+cW4yXj`LIY?Ps6NRJB0U?*Y-&K=r$iYD7{5rFor z{l^r3^ntX+as?oslCzP+Ow@9^xrOq3rwlEj#S`qv+Pe#AgO}yHd~;u|wFTvEwk4-& zk2R@ZTCH}5NSMLs1FDsjyOQG$87MU1nhExE?-T5vk0n$xwMy|xcYW?=KS>mI>PqNn z3_ISr7Bk9=)v7S1W2#)Nx^_$C_>(Wzv$;BUNrY?TuZiU&v(qHMCM0nr(p*I+1A*t9 zR#JN9Ul}J0rN`K8_M1uG&(;?Y$j8t4O!7!w6R!(KA)e1+r`o;dsKeysWZ2}UcstYM zTX+hlCysah#0=d}EHeVHdN^!$(egmDV82t$o&Svy#9Lq{>XHF0HaxtG8IEUj$j&l& zGWzWC$-%xGtq#LB^?b5M%Ax8uoF8VG%727mSzBpV_1JR}4Sj-8AZM=m1GASe7t5XO zU|d)&H=5vUH(ZOPQ_8iZf=T2w%#qcrSBQm>FIQ_wXsc7-VKtO$z2$M(Y$mu*-7LNq z!c4CO<=hPf*58k%tb&)8INYis$GKX?jD#HNmsbr{oXAGFG>_{%2JGItF@Z1;-=4DmIO3w{GU?0 z4bYO(4Uf{h4cVeuom57Nd1>Px?3aFJ1^-iMc`m9P*4P#3CTZ5PC^Q zegF++Qi>#S7~iDM=moa^?&H&?Qn{K~QQ#TN%|?9~tWRfI=o=(NLpod)8SKSx+oZ+Z#)w&{MgfQpv3@WjgE7dUE%-;?KvqE{R{Ehm$! z5@KDK6PhYPK$32KA298&g|gFOKF?Xp9s-;}y5!Nai@N@;UO|<`vC$PMwCNadSY!N-&CM13)@%XG7zihE89Rm)zZx z>wH`%FyRO{v!bu^KzIr^E9sl{I1p7xr6GlSvyqOMd1>b$LPeWWX5OxSnI1bmArU9O zGF04A5c0aL_CrMGiUkr;Fe>%JF6DyGg5^L~Qb-&ysN`~VW~5AxVnCwOJnq*+q0k-= zM@v>*$T6(EEdckQec7y+#lwuQOD4-Tu(<;Mq>TgrtWAB7+_KKJ=ibh|tMw+9yw3p& zH*G)lVb=NLddndaNXTQ?YlVaijOb_HbWH`}{&M@J)8jO!%QpL9*7F-^CUqKDX42?y zn|caMa_7Tk(X8(+THhzY?v2N`Jls_PunmU)U$+v8Bs92R>Q&O#DjVwvwLx?f~C5zF`dWZv|0Qv5N&YDsi{L#+KS4(-slorp0p9H1;=%|_Q9cK z;RuA%O=wc`=|gs_@cVxuDH=)qU@_r)l6@R-C!X75j|XBLjxLxplFq!{(y9xC7iLM{ zxwH5l*VH&}xFw(~;X1EWXjX0e69xFazLV~Kb*dRScR6w|0m|DWV?cj#y#PhKl=FOl zl2(wK_v^*DY=Zo8i1l;F^9%A5E=z7ffd1qfuH=DMnv_&kwAsK!nc(At%`Fmi#xD)- zJl0vuu`V-M&(oOUDep&mYY2HTltGl--9E%ci0$c)s05{I8J6^_8A1Dwe9ruUbWB-U zsp{oS3-g(BVfL7WU9ST4%Z2w}JKbdK>vG<|KtvsKhQ^3{wOXCooAbT0X8qs7j}i&H z6957}M*EM>Cuv%es^IIDM-}OX12IHwHp4=L+nEIUK?ef8tQ9+K0+zVZuiwrrFSSJ` z1V0r@lhNN0u*)1A@4WWTW^=5&e_+e4k&JLM63R5bn4+~=`Rw}=QIsiUGO?US`p<@8Zx+5aO5CsnKvCBI0P!h zzLnrb_2)oXVs!YCu*Ti{rm&Kpvq*I#Odybox0=Q=MBz=$4NhXgvK_U3)zs=+vR-nG zBE+RDQE7Dqj&!qar@ZVv;MZdPOSP|1gY@M0sY5*OsCha@%6k-6xY?#RG2|m_M-U-4(}B> zPP2i>JZvI*CO!}>dEdJ6@U2e;>TQN&WrXz`(73S6dbeBJ1TCF?Wj<)_a5P|Bql>vV zSIzPUWsDJ;a9HcqTgc& z(Zv5J0QA`gpw9q?xFQY4!_j@asK47IsR%QJMu9Cp>iN`>QbomJYH{{8K1M8gJNC&i ziGRI&>klv-q|E*ywduwvEED_HiQxlDF)+w55J$?Gb@u85F0X|=oKS8LXZ%Y-q3$FoRP z>xCq(>fPimtTJn8F-SM}yRvf^OL`(n`_Rx|zlbmT(h9m(ZSDb6JMcxVKW$gKk|jAZ z6Z+o~gqbNz@I)1=uDSq@oEfEJl{B3JYOPE2(*|**Mc=SRv zjA+2>M3d({W2yv+_n%ZE=1LgRaJWL9v0&cuswm{<8zCbshOtMCg1bQN;UrNinAKK#7!a*C7iVRN9EEoNJp{Ihy_1uBh#Zs%*pzpdZ>_ZBJ*uglk zP(TK)=-(ad6@W5aWydg8tJFwq?gHQ|`$K9Jh=iE9u^|srr>V_>_>dw7P_a~Ro{by! zsIS2c$4R0qwi?qsJ8cBUTm>Hjlbneidb?U1W-dZmLZC!_B5IUC;^+F;9!X)~Jg&k5 z_+Pg()4i-|2l{@wPVqC=Z)yb9qr81G&&P4V;!+Qacay~>@kb11V+L+yIKfRO_vlPP6HGKExBDyEr;d&mDP zeHFg+t`19mF%BW{XV6cqDzggLZw_c*=9HN48DqOZh)L+yKjdtOQS2~0P6|4!kc7=< zB@>6;x(II44-2JKtuEH=Oq*5Am9F^5c#S=*im5yri!tlBV>?Qt%k!!rE;twXqf-Z-Yz~ux_>_>j3`iO z)8FTbpr3xkfxpyleWRHQI7t^S0^YnJ%l z>a`foKZAfCm}hrA)vMB9bvmRSj!ORL*n~X zUK*gbwMG&QuFl&isNml);m9tD83ey3);M?>=I%DG-K2aF__5&T-!tZcO1oF|ZX2B@ zS~NrD7_i(E z9;wx8JopKu+X&(GUz>hrg#t}QexCBA*gt!b=VLi0R=~jQE>Z-i0kn1u26>MV@A2go zcUeVALd4Y?bjN9$ryo0+s_n$|l_zR<_*RS(R}>oiv^=R-&wp!Ip8IaQZc>?qwT|-n zM&MTs{{D%T6YQ_}i^a^FrfX#F$uy?EqMqBNNOL8XIS7e}Doh;K&n6x=`(@rWHX7nH zvHRTnBC&blm2BM0LQ`Hp;In@k>~%2$;@e*{iwr)%@TYd`-bJR1}m@T-~ zqosII=RI)B?wgQr1geZl4Ngf(C+P5PUi1inHFGnmJmb^QBEVsw6@*m`aiRY?5f&A9 z{Z88q(Mo8`cs+~ryOI;{BlJOq!Gxkg<`-ea-4sW;_<_TV67;2~={Z64uYS9^Mf^UbjS+nN zF36?+Pl~R%p5+3ey#xEUi;Dub@xF9xS)GEtq1u$!d*$#Hcbb7lxZaf&vxe8KKPzsb zim27~K;b9`rYl9jqLHDZ8l&VLT^14V)aBwqRPsEgWKcrNt`o_5iTB)_LB1h4w=e%N zW6MGQnJOfX4iQ13rZswfnMTWye4<>SNN<)8SpC!oMfl;H7*WM{0@4lVc78)by}^l4 zQ6@*T`{+^bOC3Nbc>LkcWRPlnwh(z2hnfHOCg4Y$@>E1Z(79c?-y}1sI|kiATivABf@2_OTyW>97ZUi``VEGy0S1%FbM9#9 z|9b)K7C>vXx|boFaGut1*n)M@4!rL9h_LkecWfnD5!t2G?SF1>2;CZ472qFb9=xU96 z(nC)Ub(@uw8V0+yHY<8a#Us)|rFI275opJ=exqa>^$L^K=1O($G)HOR^PClzGe-&q zWe)MOW2j2($xtKYFnb)7P}27r?cRJ7Y%i=Jq-mYjBJszOBU6H3%NOuy=`acoE4l91 zIwh&1!Yj-Id7r>RsZ~!`^C1^e5Swjv7PCPmWaUeRliU`{)Z?au*@l%)IP<`BQ%Nn){ozpH{&lj?2Dygx;kM92P z0~Q@9isg7b_(Jr35Et%ZU)XBYQ+lrS0GQ~ZPW~BEw57Be6w%c|Drx%_<&~OE83m`% z5qaFjPCK{g80WX+)!|$|r_j2*jrn3}KZL9G@snDg2Iz%46N`)G>L?mU4Q`g}!976`Kxk-E96&B11x9 z)q3f4qm9p;s}ic;e-I|<#AbrI&2T2YxMC+QEiK9oQ#7&OW=6`3KtP=U)WMz3W$~Io z`@8$5X&|z5Pb$~*>7JeELhNR(elW^-%JRAWp1avfY9gU8UkQ`sXG#e09^|>7zJ&hM z6Zm!|SjKJJ8=7hL<+bTda2)KOP(tY{_%-5E#q))(u1zVxn4 z?VR%y7geA@^~yScz>sL5HPXK9@JAa%qKhGFp!o=c1B(j@At9APfvA*{vZpGEZ0z`~ ze0*y)dklDe{kim;eU3U^?(7xWFg2Ht`W#pF@9Qmt!Y860m())CwdoMSRULroZo4zq z+rA@8j=<~x6_#O$C%GDQicE+Z0}r*|!A%cYROM;^6eE|-hi_;LGAbi$m7X_nN6UC1 z#DuKw9_mz5VEpAE8QH{UDEFQ`C>i2y+)@sJf^-cZR4C; ztvcPR5JeulL?YqvP}(pt6>Byc+~v(|k)iAP=5JE3kM{eb3<3t>UP${+k=5v8q6(AA zh8oTh=HBD5Qs#D|`fkAJTEHI>5gmFA-!JYQ5Bzeo%{IRGGbvL&68V^HW8?u8^cuZ) zR7C!NZ1c?i{yGn&imF=lZ; z>bn1HEBMo^!~Fb69qWH0j*^m`#cT$H%TagOlE3Zw^f#cv_Z-I9UXYHO}zzKX$Sj^DUboy`fuzw6ix(Rx-KE5G+ zU(Qd-OqVEmXwqX-!Thy40!1Ma?=M1MqvBerC+eqd9ONk~3aQ7Xnc1c)M-^!`9&R>o zo%h2)GkIMIJa+g&cm?9kVoq7@HrRNcxl=-PS6o)NJ&;qhBYJTIPD-Q~&$cQMA=|zt zOiD%^N5CAOq&&}dP>A_x2v_#xZKO0x1A_K_VLD#Zo<~_0QiZ{vb$wCbyY!{8RJ|DyggAp!+JZ_-mh9 z=&{sr{%P8N;(x?DVbBrTT(VSAZN~CHtX+Bm>?_?xXn)y2pSquq#MXDIlGpr5{1ik0 zKBI;~s*K2_LPHPRA%HP>`ny~(&1Lpm9_{=v9LD3bI8^qHoE&;2I3#=DrelU5c)nyHDh3y7N zeI;+*d}aNzijPx4DZ_Vdh<(Q8R2^CU*JBT_jKbq~ZcU-bEP!#M1=2G3SHG|EzTX}J z?RE$ToXh0StCXyQBn%v|>MWeMBxYOty9!1)I^iwTvT6eVg>Y>&ep=V_`Z!8VRa(Ru zM?U)~t8nF|C@uw;+~)=LIDwLz8aa%`h4C+uy4ff-zc(O*wa;`s*Gz?i^_V79qlx) zheR}0Xp=Cw)nYODCna5Jk6zF&AFWIX8b{F{G>1K}obcjeL#c#iOmGi~#`Ri6B7LJT z261~qi&u)RjC=jz-o8E>A>R-H;wyF^iAN=cFVdHPBmDi#rcxBgkcjD+-T( zqnVyA6uQ$ati*c$vpOiIYeq0?G#kgm!*`5eH8rhLC3V7EoGZvr8fcH<=<+Y3P$jLU zI@~iNPfRz+$qgU%G=8FLccoHV7+8si4&M61O-yfXw*0pa;2MdyGi{?9x-~!~9ykOx z|1qBu+3QfwL(0y?BK&N}6m90iv&-V#kMFW{v5TXNBco@>r&XKy>&H7TKTA<47sR~R z&$-KRd=tPYl+#v=&HLaVsX6KSx_nCPPKj&|nu=1}e3m zFx6qbU!sxcJ+xXsI7oUkvT~yoTlS^{NrGdKV^;&KDD7;YO#D!l=PZ}P8cDy zmlAE5t`GyKUWiV8Ua6*rcls8EI`$-ngfS6MPQeftnyU7ZH=k342|uDNk-CO#t|b=b zNTEU8iv2lOl`_y}=hHB~JtVBuZlsT6z9IMRi-GGwaGV_cK?zRH!X-5A{(LESx!FzG)c+Z7I*yrl=Tr8VHhX8r zV~gkbO0<-A)kBfKZ>-Vo0u1&1=8hZuKK*qNWk4!WT*vZ6nMH+YkOnaJ|03bS29ZBW zpPqvU697H|{3ODA)R#fXKp5X0X!iI5vE76|Sy2Ez2+bb?ULc3MKyklq)4sxLk;1aJ z^CjCx2_zJ)F5M7KC*)c!`?x!$#LnmG@cKN#X_g*wj*K&=%WbhzvjP}*)vte|mG{i$ zgs5EMGkVj$J1)0}ghpo4bMJdIGCqzYt3Og#j1B%l*YUD7<6&v=b-vPv(b&Ye!&C?| zwIQxIv%#tKTE`ApB|DIXBCiM&(dcO{$yRR}UfCczUUsMV-!)$Cv zO8z$Q<6>~9*ec_I1GKYqv)5~0yLPKNc{QL-mRz(iEhkG(N162V*b)&=ao6K|qpRzE z=gG(ZMB$A=L?$#_Y|_W{RvM@e5ebVFd8R9rM@Enq) z3}si^&2jp%qhP3rkjggmAc$uAkQV2r+A3!F}ZsA?HagneP;n38Z=_0 z?6XX?=xoe;KuBS;m#C!1*Ar_av-HqN*+Pkn?2e}yTlI=-vBmA;yjG|PQif8DY=r($ ziX#8`iy9V!?I6#4pLpmhs=? z-QC^WrEwe{xARdYUm?oKx-ilB_;i{2=c46mBmKPqVN{e;E_0!vRpt56&`457fue!C z=m84qIK8FVV2`h{tzc{Og-T|IthEdu_j}y$-9qB?%GR^_GJNWLe`D0-FUJZv*(EJ@LV-v-{8v;MD zD~Cphll12@d;W=dyW5G!?ke_r!()3NA1~GCNS`Nx(tWrypCV$5$kcA+vOckVyq+2N zc#3P;%tCcol0j2byWY;HWu93sT%I_tr)kb}wF~@3^~q#C_4$C~iP*qC&vn`Hdb-@j zm4$L{x?Jd7v?3cKPfpF0ODT^VpPC?}Ck+dx2rFHl7;+e$@39haYes1_V-ug&SqSLQ zTB^?zKV8&O=A{iOJ%YnQM^gcaZrSWsa$i@r4-YsCm7=u&zO`U<+fOep9SRk6P?(hk zoN+OeQVJAP$;WH-3nbnl22BF$zgzmL-G@#K}@KC>$)bg6+D)_Md^Kr({vbabEKk)l>_h2KZ?sTFkL~cYGdzim3FcD*|uDoQAYgaBWJW}RpC<-Ru``GUr0O-nH?8R1546@&8Dww_r5g&kg}_F#m}DVd=g0U3HINol3K1QDbphL9430SOTarH3H}B!-~{ zq`RdA21c48{_{M~`n~JDKb*Dpm$T2>XPt9j*R}6`Ut!O%`l?fpy5@o`IHJD;4Ed2> z%oH!;sVo~j)(WusEBj|lTv9@?L)F)x#WbIqG>*x=O_Pc@2&)A&CZb*5>%Cv^E@uwI z(ms|5!%srEt@iTEL89lMejbH1RZ>c#^C;9L1V9gEl;I(7Rb7*&l!43)H4VQ=fac;p z2GMtosnC^_g6u4;Qiawo!#r0Z5tvVOXod6g-}nl>RFt?-(d~V&)Gt3HQ6CG9_oO2s zEC8ib$V<2wx%n;1BCE(C)9)*&&_1=8Utm%t4tSY#N7`x!DH6>z_mF$GIY|DX70X$? zVUp@;x1QFt_Q&1D;{9DS^@rw`E_7f`AaOE{nV}uA=dcPZYfRi}!~7W&MNq=ozWo~N zY&LvF^I;{IM@}bWuD+($=J0bJO(JyDF7N$Mvm+G%+6DEiR7w6~-6zo<44l$$MM4wt zAnvpk#E$qN0X?rjFQW)5*^1~inHy}z&mA4OpJ^>9(8m*B)jc6%-8gM>tz75;zt8}V zN`U9tK&0?B>;Yz0iW}XYvt*sk5shy0Jm6HPgo=yhdSyG31<_QrU2} zI#mu}!nbJPC8bQl#7tHkZ?S)r7^p12`_QkjzJ(gOKa{@tJ>#bDAcbyob{fK6BxuBq z)U8BUafR!;?#IvZZrgB_dB>gDkMf;n;THKkoBRcED?h0MU~g+D?* zmbvN4#~@RUmCL2br#(%iu2;Od?|YmF`yL99fn9BFes>93Q#+H87C%Hdso2cGxUS-J zB8bCh^JGggp-|*YN7K3-<%`T~TRT?fi^sWDWZ53YiDGTvN#LpvI|aB7GJ<)25;OJI z{Yn2ylDXyfK;-JCJ@6n#0kEg(#J9Fsh7>-wwPk;{iK4$Bz&*^8V1yp{t)0B3oq(Ts>>)r`T_A44)Zs^*PYI+cLhrn(xo3aW$!+eM$zZ?1){e)X+}RGG zJaeF@F_6{M+2xzgO!LkvHTxN08eTkCjUp@Ui|Y$GnYta$Qa#DT;Fl>;3e#@mWGY*k zet9!@_6zX&eu`=n?bpeO_b3AHHqBqO6oC&}v|T7XEJtRX^EZ5gcpBJ;DWKoV9uH6L z&nKN^R8UYzucO0bT76JnU14-ePIYuPa z%Bql1bbST$)t#pUYiguHw_Vkv5UzB3VyUEh%X9Dql_VLVOR9bbrnE9Z|GogxeL(?X zrQ{x_T>69Ap{%d@YcA$$NvM3aB4eS2-FTC{b^6r=uCk~XmHZ%K?xLZ~^k6+0!;Du6 za4oe$=V3*us~(@(`HVxobW`TtjE#+lQ&F!sve*o!lHY!9 z2OxhW|C16PJh(OQGon79RLu%#{!>Il5?|J!pV4FpEb%Bcj#CMK4PTl6o=(UPesq=X zSrfd=pq}#P6Qp=iQNa3o4HUJv)R;qV8DI)nQ2183n3yIbdzXdybu=rRD|<3#fo!q8 zPCrJw0{l5cYt5Crb8&~gGjxt{DhdA%ehWs(j9&N1+9Fl5ZT&_5}JCq>4Q;E_}o{t~O0 zBs3&SZ{elQkB$|#5?}%?+=-{sjHL=gF1jPs#}&{M)xS8S1=}jr=pY(VhiZ|-A|+bO zfxo_Z{%XLSy}~vX5z)MqfH~$U$_fYw3Oi0B0N*MqP>hW3ks8`jw0MIlNMtH+f2oRz z%U}vklcCfdIuoK*4o{!D{vjxx*?{sND##3xz$lml>T~8^ASr{yw~f(wn(-DzEd|zW z@R~*TkhA)*5zaU0Ht5|WhDLh504zI*^!iaG0n~(#>1cwe&B8#(#y~J8cYdDD#F$T7{?&mhc9{KXTcCJD zq3<;96I*KV$}>)Bl|5+{uJAtL$p6+mKP40r{Coj5l&rhkgvl-sM6bKjO(od(=k6?= zEjTDmDyA(+y zm|UwWl%pf!YFQGKX^d|^b1H^0T-bWy>X6&69 z^1Xq%4N~TlpG*`mXdE>|?*OPs{-#(s2S-scrKt}JWrBy)J z5ZT@&l(32&5?dQ1>aa~^N1VB+5^}xq)x)guZQ2-KD4|t{LgRCljhfI_*;Cmz%a#vi zpFg_}1}vO(fTm2G5-Gl0C>*x6#=lG681Bt43EqwIu&R&V>S^nZPos%6C406MB<*~L z?)$@Y#H8fJ)~%tf^=&zEv@jn`(_Nz=-{f{U>EMLI?Ddrg9j5lWjD<42whrbr;0lqX z7Ytkad849yb1}glA{#7scX(gdO{Q@7W)<#*;Zjct{j_=;7+s)pU^|uh!F9BW!H@Sx zf8s{F$XaPlE9O|!^cDeA$&j)R&L0VVZKGVre)>V`!C?>{9wnugs?g zFd=g}G-dnzA&uuyT+TtE?}yDqrcm-_;mhPqrSrs3U(YtD2-VZl4RZK@N|dR;Jsq#d zGCx-QYdUq?8tESMd<56m*KugU{0iBF-tVZ>?sDVZNI(nLw=;~ubindS$ED9Eo0^|cZ!m3<%Emk z^@{bUaP&Qk_H!z3bZee?RZ}b}VSab(h0@;(K5?dr!n?Q<1lxt(Y6AoFVe6FkpKBZL zGL;c3Zh34yp@)x{4I+!SAvpa;+0GDA(^VW|4W)gI+LOiA`j^S?Ojh4J(D~REQ$N46 z0GxMlTvSxiCar__4|zk@_v9+9Ya_q#Mwuhlo;BC;+bz{m&bA)#+xNEjkJ@i6U^_ls zN$s({{8RMi)b-!w8ZN8%!!s9OUMPF%I{5EZk^XmhxHH4;xww97kdnA!Ue7z+JWJ)2 z26E8|J6RjU7>FL~T{5>UC<)m91;_7rdLQ*^K8*%*0&$%MPwEsa`A&{r#(yR0R|e99 z-IBgUlIJvt?F>RgYMU6tUPb=>+!YZ;XmvZCy~S#WZFoLw`Di=jl0$5a0H4t04MCl5 z2w0BU6;tPG(O2C`Kr?RGH&Qt`ZREUaoB?k+7rE=bqvBRcCIf?1&_DU(Cf=fn^Kh7{ zapVq8R?ZY3;g(!1FiivG`#*IFGrQs*Nq!Tf(DK^A_n0V2E`X=VuTzghR5ppJJ#v5s zhy1~qXGejT#TZq0HJvCY8O{XWAq#G9+Ul&c0S&7VUe}$SI)MRh<#a?#AV8^V=_j(d z{a58P;V-Z7uHubz`3nP=mC--8gu*OZlFhzG_AK5vD5Ylsh!P7tdb+vs?O%d?EFb3NG-19 z;(P1yUTs~T%#zDCbSnbd!AUZh?0C*|*SyB#!6MmCPQP_sWm%gR_U-X)BMa zEWPH=I_`L@M8${8-fP9cf8$Ck_szTvv5ey7Cto4`AE!Lt?O1`2(0x~f^xm_6UkUH& zkMV#Xx^*C`IbJEw)MXf`17R&}%L4}iI2#L|o6(S?_)s-o<4Y`rH3rC+SR8}F5a&ue z5RE*(7D=N@ei^3=;UsyDL{93dkkYJupelQ}u0g3{(L7q?XR<^FLc;52avfW-?5eoIk$z>vWBExRlv{yUdFER}yr1zafagRJRWQ5{w=H zsv&K|tbjjAGXv(x#goZ!2_YKPP`|#vAhSm@{P@h{%A&vnARx+-5rqK0wwYlsqM~9@ zgBdno$1q^D`uz`<5*U}m?pnGO(W&`hSDJ#;9?Cy8Myc`FRjUJeEG6Snzq~h1B|CV79%u=VJFyJ!qGrIS z7a(5OlR86B#+WaM3=MF*WnmLYKyZdVNJ{JoVzOGrm7&mx7w`W(ly|2Tzk%}=7wQ`d;+v@b-pcTW5t3BFi z0l1rq_r(SyEFPl+NiR$Cv)!_}g3egnp;cx7O6( z9oF5{d*F0~god0>HW~|v2ilcF0uJW7+tLh^?*TjX-9jWxO$2C{nMQKE1!rC_*!6vP z{@aO~HgE8!SE^k6Ib}`w?OWMO=e(EQ-{VmNoe@xQD2~bAH`lVNH3kpguXfZ9QFY}hKwD_SDkEs^4GD#toD;9HaYT`))C6T z^dl-QP3#eVCWz9z5#m#h)q*6v8}Oh1QPJ#;hHX(>zMu0~XGluRdy&9#G&N_BId z?|P5eCX_L7wV2QKnQ<)h5kp!Q)lk)b&P;=!QnLMhk94Y{sbMaVY=&rxQYVy=f=f#A zqiv@35Nt#I;xa+YW2QC5araa$MEdc+apR`i8l|71_gVeBxpYEgj5!;KQsnm-=R=h0 zhl~uJ+a-mpqkS5up-;LdB2Td6bA={v*Hkoirhf2=HaKC2e@Fhr1`pe{pdBEb%bYsgQw-r%gc`wBLgc>e2GViOY6L+vJhj25QyHd z!eHraX>aw4=VCkK0u`3+sY}s9x2NiVZB0U9gc}^H41O%?YIKlVrk^p!eH# za>wZDSX1c5&+HTO=Q>y#+xcTwkvOL$L}_LQlJCP;ctBUcT>Xw_wN2ikRsyBsO=5nS zg<6>H9q26iOp_Pr)e%X5zw2Ad2&(M6gvs_7UtDIJMfJX=)w4>C)=%Tj)q6owhCM&Z zI^Pj@9#%JFV3+q_No-RvtKDQ&%$0yHpYDAPt{!(CFB2dmZ5D`G=vl&Z}&K74Wd zEm@%-X2ac?LtPEp7C03l& zkjZ8{jLc_}+7m;J8P$N|_x<_?zI9J26kCNXnX~aPr6_S`G=JP-1Ij`&y%ytA;<4kNEAI08Lw0akMK8|BLizK zkn}%CK2h^7!>fVF1JIZ6` zW2nBoc_$S@rbETkl|3wp{{(sGb1*eDoujPQ%a&c8T{e=stN}SJR+0@!O-K&hAUR^2 zp}yYrfypmuGs#k~hq6(4EqWGp5TqbU@f7~~*WEPd{?%Ctr{Ltkn{nCqBYcn;?H~Bf zG=|)-OX|VxJ_b)bj`|~H@{Y7f%@fx;pX<~+`MW>L>p#xQ%od*A?h*$FUU_1~BK`r) zG1(tGa78vpfT$$Xk_kc3G(8G**OXSz`da_Y)3`mzQ`V4A>2q9auhE`VTP% zUSY002RjdgIj0T?t#56FR}OFuT8S0H&#*SzTmL-)M#KKrM&SG)oBjXI({k7dA`JfD zE%Gi{cM0D7ZxnhF{Qr$~WjB^O|F;AW!WC}`M;v +#include +#include +#include #include PoseInstabilityDetector::PoseInstabilityDetector(const rclcpp::NodeOptions & options) : rclcpp::Node("pose_instability_detector", options), - threshold_diff_position_x_(this->declare_parameter("threshold_diff_position_x")), - threshold_diff_position_y_(this->declare_parameter("threshold_diff_position_y")), - threshold_diff_position_z_(this->declare_parameter("threshold_diff_position_z")), - threshold_diff_angle_x_(this->declare_parameter("threshold_diff_angle_x")), - threshold_diff_angle_y_(this->declare_parameter("threshold_diff_angle_y")), - threshold_diff_angle_z_(this->declare_parameter("threshold_diff_angle_z")) + timer_period_(this->declare_parameter("timer_period")), + heading_velocity_maximum_(this->declare_parameter("heading_velocity_maximum")), + heading_velocity_scale_factor_tolerance_( + this->declare_parameter("heading_velocity_scale_factor_tolerance")), + angular_velocity_maximum_(this->declare_parameter("angular_velocity_maximum")), + angular_velocity_scale_factor_tolerance_( + this->declare_parameter("angular_velocity_scale_factor_tolerance")), + angular_velocity_bias_tolerance_( + this->declare_parameter("angular_velocity_bias_tolerance")), + pose_estimator_longitudinal_tolerance_( + this->declare_parameter("pose_estimator_longitudinal_tolerance")), + pose_estimator_lateral_tolerance_( + this->declare_parameter("pose_estimator_lateral_tolerance")), + pose_estimator_vertical_tolerance_( + this->declare_parameter("pose_estimator_vertical_tolerance")), + pose_estimator_angular_tolerance_( + this->declare_parameter("pose_estimator_angular_tolerance")) { + // Define subscribers, publishers and a timer. odometry_sub_ = this->create_subscription( "~/input/odometry", 10, std::bind(&PoseInstabilityDetector::callback_odometry, this, std::placeholders::_1)); @@ -39,9 +54,8 @@ PoseInstabilityDetector::PoseInstabilityDetector(const rclcpp::NodeOptions & opt "~/input/twist", 10, std::bind(&PoseInstabilityDetector::callback_twist, this, std::placeholders::_1)); - const double interval_sec = this->declare_parameter("interval_sec"); timer_ = rclcpp::create_timer( - this, this->get_clock(), std::chrono::duration(interval_sec), + this, this->get_clock(), std::chrono::duration(timer_period_), std::bind(&PoseInstabilityDetector::callback_timer, this)); diff_pose_pub_ = this->create_publisher("~/debug/diff_pose", 10); @@ -61,6 +75,7 @@ void PoseInstabilityDetector::callback_twist( void PoseInstabilityDetector::callback_timer() { + // odometry callback and timer callback has to be called at least once if (latest_odometry_ == std::nullopt) { return; } @@ -69,6 +84,16 @@ void PoseInstabilityDetector::callback_timer() return; } + // twist callback has to be called at least once + if (twist_buffer_.empty()) { + return; + } + + // time variables + const rclcpp::Time latest_odometry_time = rclcpp::Time(latest_odometry_->header.stamp); + const rclcpp::Time prev_odometry_time = rclcpp::Time(prev_odometry_->header.stamp); + + // define lambda function to convert quaternion to rpy auto quat_to_rpy = [](const Quaternion & quat) { tf2::Quaternion tf2_quat(quat.x, quat.y, quat.z, quat.w); tf2::Matrix3x3 mat(tf2_quat); @@ -79,70 +104,48 @@ void PoseInstabilityDetector::callback_timer() return std::make_tuple(roll, pitch, yaw); }; - Pose pose = prev_odometry_->pose.pose; - rclcpp::Time prev_time = rclcpp::Time(prev_odometry_->header.stamp); - for (const TwistWithCovarianceStamped & twist_with_cov : twist_buffer_) { - const Twist twist = twist_with_cov.twist.twist; - - const rclcpp::Time curr_time = rclcpp::Time(twist_with_cov.header.stamp); - if (curr_time > latest_odometry_->header.stamp) { + // delete twist data older than prev_odometry_ (but preserve the one right before prev_odometry_) + while (twist_buffer_.size() > 1) { + if (rclcpp::Time(twist_buffer_[1].header.stamp) < prev_odometry_time) { + twist_buffer_.pop_front(); + } else { break; } + } - const rclcpp::Duration time_diff = curr_time - prev_time; - const double time_diff_sec = time_diff.seconds(); - if (time_diff_sec < 0.0) { - continue; - } - - // quat to rpy - auto [ang_x, ang_y, ang_z] = quat_to_rpy(pose.orientation); - - // rpy update - ang_x += twist.angular.x * time_diff_sec; - ang_y += twist.angular.y * time_diff_sec; - ang_z += twist.angular.z * time_diff_sec; - tf2::Quaternion quat; - quat.setRPY(ang_x, ang_y, ang_z); + // dead reckoning from prev_odometry_ to latest_odometry_ + PoseStamped::SharedPtr prev_pose = std::make_shared(); + prev_pose->header = prev_odometry_->header; + prev_pose->pose = prev_odometry_->pose.pose; - // Convert twist to world frame - tf2::Vector3 linear_velocity(twist.linear.x, twist.linear.y, twist.linear.z); - linear_velocity = tf2::quatRotate(quat, linear_velocity); - - // update - pose.position.x += linear_velocity.x() * time_diff_sec; - pose.position.y += linear_velocity.y() * time_diff_sec; - pose.position.z += linear_velocity.z() * time_diff_sec; - pose.orientation.x = quat.x(); - pose.orientation.y = quat.y(); - pose.orientation.z = quat.z(); - pose.orientation.w = quat.w(); - prev_time = curr_time; - } + Pose::SharedPtr DR_pose = std::make_shared(); + dead_reckon(prev_pose, latest_odometry_time, twist_buffer_, DR_pose); - // compare pose and latest_odometry_ + // compare dead reckoning pose and latest_odometry_ const Pose latest_ekf_pose = latest_odometry_->pose.pose; - const Pose ekf_to_odom = tier4_autoware_utils::inverseTransformPose(pose, latest_ekf_pose); - const geometry_msgs::msg::Point pos = ekf_to_odom.position; - const auto [ang_x, ang_y, ang_z] = quat_to_rpy(ekf_to_odom.orientation); + const Pose ekf_to_DR = tier4_autoware_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}; - const rclcpp::Time stamp = latest_odometry_->header.stamp; - // publish diff_pose for debug PoseStamped diff_pose; - diff_pose.header = latest_odometry_->header; - diff_pose.pose = ekf_to_odom; + diff_pose.header.stamp = latest_odometry_time; + diff_pose.header.frame_id = "base_link"; + diff_pose.pose = ekf_to_DR; diff_pose_pub_->publish(diff_pose); - const std::vector thresholds = {threshold_diff_position_x_, threshold_diff_position_y_, - threshold_diff_position_z_, threshold_diff_angle_x_, - threshold_diff_angle_y_, threshold_diff_angle_z_}; + // publish diagnostics + ThresholdValues threshold_values = + calculate_threshold((latest_odometry_time - prev_odometry_time).seconds()); + + const std::vector thresholds = {threshold_values.position_x, threshold_values.position_y, + threshold_values.position_z, threshold_values.angle_x, + threshold_values.angle_y, threshold_values.angle_z}; const std::vector labels = {"diff_position_x", "diff_position_y", "diff_position_z", "diff_angle_x", "diff_angle_y", "diff_angle_z"}; - // publish diagnostics DiagnosticStatus status; status.name = "localization: pose_instability_detector"; status.hardware_id = this->get_name(); @@ -166,13 +169,239 @@ void PoseInstabilityDetector::callback_timer() status.message = (all_ok ? "OK" : "WARN"); DiagnosticArray diagnostics; - diagnostics.header.stamp = stamp; + diagnostics.header.stamp = latest_odometry_time; diagnostics.status.emplace_back(status); diagnostics_pub_->publish(diagnostics); // prepare for next loop prev_odometry_ = latest_odometry_; - twist_buffer_.clear(); +} + +PoseInstabilityDetector::ThresholdValues PoseInstabilityDetector::calculate_threshold( + double interval_sec) +{ + // Calculate maximum longitudinal difference + const double longitudinal_difference = + heading_velocity_maximum_ * heading_velocity_scale_factor_tolerance_ * 0.01 * interval_sec; + + // Calculate maximum lateral and vertical difference + double lateral_difference = 0.0; + + const std::vector heading_velocity_signs = {1.0, -1.0, -1.0, 1.0}; + const std::vector angular_velocity_signs = {1.0, 1.0, -1.0, -1.0}; + + const double nominal_variation_x = heading_velocity_maximum_ / angular_velocity_maximum_ * + sin(angular_velocity_maximum_ * interval_sec); + const double nominal_variation_y = heading_velocity_maximum_ / angular_velocity_maximum_ * + (1 - cos(angular_velocity_maximum_ * interval_sec)); + + for (int i = 0; i < 4; i++) { + const double edge_heading_velocity = + heading_velocity_maximum_ * + (1 + heading_velocity_signs[i] * heading_velocity_scale_factor_tolerance_ * 0.01); + const double edge_angular_velocity = + angular_velocity_maximum_ * + (1 + angular_velocity_signs[i] * angular_velocity_scale_factor_tolerance_ * 0.01) + + angular_velocity_signs[i] * angular_velocity_bias_tolerance_; + + const double edge_variation_x = + edge_heading_velocity / edge_angular_velocity * sin(edge_angular_velocity * interval_sec); + const double edge_variation_y = edge_heading_velocity / edge_angular_velocity * + (1 - cos(edge_angular_velocity * interval_sec)); + + const double diff_variation_x = edge_variation_x - nominal_variation_x; + const double diff_variation_y = edge_variation_y - nominal_variation_y; + + const double lateral_difference_candidate = abs( + diff_variation_x * sin(angular_velocity_maximum_ * interval_sec) - + diff_variation_y * cos(angular_velocity_maximum_ * interval_sec)); + lateral_difference = std::max(lateral_difference, lateral_difference_candidate); + } + + const double vertical_difference = lateral_difference; + + // Calculate maximum angular difference + const double roll_difference = + (angular_velocity_maximum_ * angular_velocity_scale_factor_tolerance_ * 0.01 + + angular_velocity_bias_tolerance_) * + interval_sec; + const double pitch_difference = roll_difference; + const double yaw_difference = roll_difference; + + // Set thresholds + ThresholdValues result_values; + result_values.position_x = longitudinal_difference + pose_estimator_longitudinal_tolerance_; + result_values.position_y = lateral_difference + pose_estimator_lateral_tolerance_; + result_values.position_z = vertical_difference + pose_estimator_vertical_tolerance_; + result_values.angle_x = roll_difference + pose_estimator_angular_tolerance_; + result_values.angle_y = pitch_difference + pose_estimator_angular_tolerance_; + result_values.angle_z = yaw_difference + pose_estimator_angular_tolerance_; + + return result_values; +} + +void PoseInstabilityDetector::dead_reckon( + PoseStamped::SharedPtr & initial_pose, const rclcpp::Time & end_time, + const std::deque & twist_deque, Pose::SharedPtr & estimated_pose) +{ + // get start time + rclcpp::Time start_time = rclcpp::Time(initial_pose->header.stamp); + + // initialize estimated_pose + estimated_pose->position = initial_pose->pose.position; + estimated_pose->orientation = initial_pose->pose.orientation; + + // cut out necessary twist data + std::deque sliced_twist_deque = + clip_out_necessary_twist(twist_deque, start_time, end_time); + + // dead reckoning + rclcpp::Time prev_odometry_time = rclcpp::Time(sliced_twist_deque.front().header.stamp); + tf2::Quaternion prev_orientation; + tf2::fromMsg(estimated_pose->orientation, prev_orientation); + + for (size_t i = 1; i < sliced_twist_deque.size(); ++i) { + const rclcpp::Time curr_time = rclcpp::Time(sliced_twist_deque[i].header.stamp); + const double time_diff_sec = (curr_time - prev_odometry_time).seconds(); + + const Twist twist = sliced_twist_deque[i - 1].twist.twist; + + // variation of orientation (rpy update) + tf2::Quaternion delta_orientation; + tf2::Vector3 rotation_axis(twist.angular.x, twist.angular.y, twist.angular.z); + if (rotation_axis.length() > 0.0) { + delta_orientation.setRotation( + rotation_axis.normalized(), rotation_axis.length() * time_diff_sec); + } else { + delta_orientation.setValue(0.0, 0.0, 0.0, 1.0); + } + + tf2::Quaternion curr_orientation; + curr_orientation = prev_orientation * delta_orientation; + curr_orientation.normalize(); + + // average quaternion of two frames + tf2::Quaternion average_quat = prev_orientation.slerp(curr_orientation, 0.5); + + // Convert twist to world frame (take average of two frames) + tf2::Vector3 linear_velocity(twist.linear.x, twist.linear.y, twist.linear.z); + linear_velocity = tf2::quatRotate(average_quat, linear_velocity); + + // xyz update + estimated_pose->position.x += linear_velocity.x() * time_diff_sec; + estimated_pose->position.y += linear_velocity.y() * time_diff_sec; + estimated_pose->position.z += linear_velocity.z() * time_diff_sec; + + // update previous variables + prev_odometry_time = curr_time; + prev_orientation = curr_orientation; + } + estimated_pose->orientation.x = prev_orientation.x(); + estimated_pose->orientation.y = prev_orientation.y(); + estimated_pose->orientation.z = prev_orientation.z(); + estimated_pose->orientation.w = prev_orientation.w(); +} + +std::deque +PoseInstabilityDetector::clip_out_necessary_twist( + const std::deque & twist_buffer, const rclcpp::Time & start_time, + const rclcpp::Time & end_time) +{ + // If there is only one element in the twist_buffer, return a deque that has the same twist + // from the start till the end + if (twist_buffer.size() == 1) { + TwistWithCovarianceStamped twist = twist_buffer.front(); + std::deque simple_twist_deque; + + twist.header.stamp = start_time; + simple_twist_deque.push_back(twist); + + twist.header.stamp = end_time; + simple_twist_deque.push_back(twist); + + return simple_twist_deque; + } + + // get iterator to the element that is right before start_time (if it does not exist, start_it = + // twist_buffer.begin()) + auto start_it = twist_buffer.begin(); + + for (auto it = twist_buffer.begin(); it != twist_buffer.end(); ++it) { + if (rclcpp::Time(it->header.stamp) > start_time) { + break; + } + start_it = it; + } + + // get iterator to the element that is right after end_time (if it does not exist, end_it = + // twist_buffer.end()) + auto end_it = twist_buffer.end(); + end_it--; + for (auto it = end_it; it != twist_buffer.begin(); --it) { + if (rclcpp::Time(it->header.stamp) < end_time) { + break; + } + end_it = it; + } + + // Create result deque + std::deque result_deque(start_it, end_it); + + // If the first element is later than start_time, add the first element to the front of the + // result_deque + if (rclcpp::Time(result_deque.front().header.stamp) > start_time) { + TwistWithCovarianceStamped start_twist = *start_it; + start_twist.header.stamp = start_time; + result_deque.push_front(start_twist); + } else { + // If the first element is earlier than start_time, interpolate the first element + rclcpp::Time time0 = rclcpp::Time(result_deque[0].header.stamp); + rclcpp::Time time1 = rclcpp::Time(result_deque[1].header.stamp); + double ratio = (start_time - time0).seconds() / (time1 - time0).seconds(); + Twist twist0 = result_deque[0].twist.twist; + Twist twist1 = result_deque[1].twist.twist; + result_deque[0].twist.twist.linear.x = twist1.linear.x * ratio + twist0.linear.x * (1 - ratio); + result_deque[0].twist.twist.linear.y = twist1.linear.y * ratio + twist0.linear.y * (1 - ratio); + result_deque[0].twist.twist.linear.z = twist1.linear.z * ratio + twist0.linear.z * (1 - ratio); + result_deque[0].twist.twist.angular.x = + twist1.angular.x * ratio + twist0.angular.x * (1 - ratio); + result_deque[0].twist.twist.angular.y = + twist1.angular.y * ratio + twist0.angular.y * (1 - ratio); + result_deque[0].twist.twist.angular.z = + twist1.angular.z * ratio + twist0.angular.z * (1 - ratio); + + result_deque[0].header.stamp = start_time; + } + + // If the last element is earlier than end_time, add the last element to the back of the + // result_deque + if (rclcpp::Time(result_deque.back().header.stamp) < end_time) { + TwistWithCovarianceStamped end_twist = *end_it; + end_twist.header.stamp = end_time; + result_deque.push_back(end_twist); + } else { + // If the last element is later than end_time, interpolate the last element + rclcpp::Time time0 = rclcpp::Time(result_deque[result_deque.size() - 2].header.stamp); + rclcpp::Time time1 = rclcpp::Time(result_deque[result_deque.size() - 1].header.stamp); + double ratio = (end_time - time0).seconds() / (time1 - time0).seconds(); + Twist twist0 = result_deque[result_deque.size() - 2].twist.twist; + Twist twist1 = result_deque[result_deque.size() - 1].twist.twist; + result_deque[result_deque.size() - 1].twist.twist.linear.x = + twist1.linear.x * ratio + twist0.linear.x * (1 - ratio); + result_deque[result_deque.size() - 1].twist.twist.linear.y = + twist1.linear.y * ratio + twist0.linear.y * (1 - ratio); + result_deque[result_deque.size() - 1].twist.twist.linear.z = + twist1.linear.z * ratio + twist0.linear.z * (1 - ratio); + result_deque[result_deque.size() - 1].twist.twist.angular.x = + twist1.angular.x * ratio + twist0.angular.x * (1 - ratio); + result_deque[result_deque.size() - 1].twist.twist.angular.y = + twist1.angular.y * ratio + twist0.angular.y * (1 - ratio); + result_deque[result_deque.size() - 1].twist.twist.angular.z = + twist1.angular.z * ratio + twist0.angular.z * (1 - ratio); + + result_deque[result_deque.size() - 1].header.stamp = end_time; + } + return result_deque; } #include diff --git a/localization/pose_instability_detector/test/test.cpp b/localization/pose_instability_detector/test/test.cpp index 5ea03859d7731..9300984967d4b 100644 --- a/localization/pose_instability_detector/test/test.cpp +++ b/localization/pose_instability_detector/test/test.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "../src/pose_instability_detector.hpp" +#include "autoware/pose_instability_detector/pose_instability_detector.hpp" #include "test_message_helper_node.hpp" #include @@ -81,6 +81,11 @@ TEST_F(TestPoseInstabilityDetector, output_ok_when_twist_matches_odometry) // N timestamp.nanosec = 0; helper_->send_odometry_message(timestamp, 10.0, 0.0, 0.0); + // send the twist message1 (move 1m in x direction) + timestamp.sec = 0; + timestamp.nanosec = 5e8; + helper_->send_twist_message(timestamp, 2.0, 0.0, 0.0); + // process the above message (by timer_callback) helper_->received_diagnostic_array_flag = false; while (!helper_->received_diagnostic_array_flag) { @@ -88,11 +93,6 @@ TEST_F(TestPoseInstabilityDetector, output_ok_when_twist_matches_odometry) // N std::this_thread::sleep_for(std::chrono::milliseconds(10)); } - // send the twist message1 (move 1m in x direction) - timestamp.sec = 0; - timestamp.nanosec = 5e8; - helper_->send_twist_message(timestamp, 2.0, 0.0, 0.0); - // send the twist message2 (move 1m in x direction) timestamp.sec = 1; timestamp.nanosec = 0; @@ -101,7 +101,9 @@ TEST_F(TestPoseInstabilityDetector, output_ok_when_twist_matches_odometry) // N // send the second odometry message (finish x = 12) timestamp.sec = 2; timestamp.nanosec = 0; - helper_->send_odometry_message(timestamp, 12.0, 0.0, 0.0); + helper_->send_odometry_message(timestamp, 14.0, 0.0, 0.0); + + executor_.spin_some(); // process the above messages (by timer_callback) helper_->received_diagnostic_array_flag = false; @@ -124,6 +126,11 @@ TEST_F(TestPoseInstabilityDetector, output_warn_when_twist_is_too_small) // NOL timestamp.nanosec = 0; helper_->send_odometry_message(timestamp, 10.0, 0.0, 0.0); + // send the twist message1 (move 0.1m in x direction) + timestamp.sec = 0; + timestamp.nanosec = 5e8; + helper_->send_twist_message(timestamp, 0.2, 0.0, 0.0); + // process the above message (by timer_callback) helper_->received_diagnostic_array_flag = false; while (!helper_->received_diagnostic_array_flag) { @@ -131,11 +138,6 @@ TEST_F(TestPoseInstabilityDetector, output_warn_when_twist_is_too_small) // NOL std::this_thread::sleep_for(std::chrono::milliseconds(10)); } - // send the twist message1 (move 0.1m in x direction) - timestamp.sec = 0; - timestamp.nanosec = 5e8; - helper_->send_twist_message(timestamp, 0.2, 0.0, 0.0); - // send the twist message2 (move 0.1m in x direction) timestamp.sec = 1; timestamp.nanosec = 0; @@ -144,7 +146,9 @@ TEST_F(TestPoseInstabilityDetector, output_warn_when_twist_is_too_small) // NOL // send the second odometry message (finish x = 12) timestamp.sec = 2; timestamp.nanosec = 0; - helper_->send_odometry_message(timestamp, 12.0, 0.0, 0.0); + helper_->send_odometry_message(timestamp, 14.0, 0.0, 0.0); + + executor_.spin_some(); // process the above messages (by timer_callback) helper_->received_diagnostic_array_flag = false; From 4aeb69f94199b25168b864f1e115f38f72648004 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 7 Jun 2024 11:08:05 +0300 Subject: [PATCH 17/65] ci(clang-tidy-differential): split it out of build-and-test-differential (#7331) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../build-and-test-differential.yaml | 37 -------------- .../workflows/clang-tidy-differential.yaml | 51 +++++++++++++++++++ 2 files changed, 51 insertions(+), 37 deletions(-) create mode 100644 .github/workflows/clang-tidy-differential.yaml diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index fb98d321fde88..6745976aa543a 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -74,40 +74,3 @@ jobs: - name: Show disk space after the tasks run: df -h - - clang-tidy-differential: - runs-on: ubuntu-latest - container: ghcr.io/autowarefoundation/autoware:latest-prebuilt-cuda - steps: - - name: Check out repository - uses: actions/checkout@v4 - with: - fetch-depth: 0 - - - name: Show disk space before the tasks - run: df -h - - - name: Remove exec_depend - uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 - - - name: Get modified packages - id: get-modified-packages - uses: autowarefoundation/autoware-github-actions/get-modified-packages@v1 - - - name: Get modified files - id: get-modified-files - uses: tj-actions/changed-files@v35 - with: - files: | - **/*.cpp - **/*.hpp - - - name: Run clang-tidy - if: ${{ steps.get-modified-files.outputs.all_changed_files != '' }} - uses: autowarefoundation/autoware-github-actions/clang-tidy@v1 - with: - rosdistro: humble - target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} - target-files: ${{ steps.get-modified-files.outputs.all_changed_files }} - clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy - build-depends-repos: build_depends.repos diff --git a/.github/workflows/clang-tidy-differential.yaml b/.github/workflows/clang-tidy-differential.yaml new file mode 100644 index 0000000000000..f7ec81e3394e5 --- /dev/null +++ b/.github/workflows/clang-tidy-differential.yaml @@ -0,0 +1,51 @@ +name: clang-tidy-differential + +on: + pull_request: + types: + - opened + - synchronize + - labeled + +jobs: + prevent-no-label-execution: + uses: autowarefoundation/autoware-github-actions/.github/workflows/prevent-no-label-execution.yaml@v1 + with: + label: tag:run-clang-tidy-differential + + clang-tidy-differential: + runs-on: ubuntu-latest + container: ghcr.io/autowarefoundation/autoware:latest-prebuilt-cuda + steps: + - name: Check out repository + uses: actions/checkout@v4 + with: + fetch-depth: 0 + + - name: Show disk space before the tasks + run: df -h + + - name: Remove exec_depend + uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 + + - name: Get modified packages + id: get-modified-packages + uses: autowarefoundation/autoware-github-actions/get-modified-packages@v1 + + - name: Get modified files + id: get-modified-files + uses: tj-actions/changed-files@v35 + with: + files: | + **/*.cpp + **/*.hpp + + - name: Run clang-tidy + if: ${{ steps.get-modified-files.outputs.all_changed_files != '' }} + uses: autowarefoundation/autoware-github-actions/clang-tidy@v1 + with: + rosdistro: humble + target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} + target-files: ${{ steps.get-modified-files.outputs.all_changed_files }} + clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy + build-depends-repos: build_depends.repos From e6b56a42f8660235114857728ca2938cf5b725a5 Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Fri, 7 Jun 2024 17:10:23 +0900 Subject: [PATCH 18/65] feat(imu_corrector): componentize ImuCorrector and GyroBiasEstimator (#7129) * remove unusing main func file Signed-off-by: a-maumau * mod to componentize and use glog Signed-off-by: a-maumau * change log output from screen to both Signed-off-by: a-maumau * Update sensing/imu_corrector/CMakeLists.txt add namespace Co-authored-by: Yamato Ando Signed-off-by: a-maumau * Update sensing/imu_corrector/CMakeLists.txt add namespace Co-authored-by: Yamato Ando --------- Signed-off-by: a-maumau Co-authored-by: Yamato Ando --- sensing/imu_corrector/CMakeLists.txt | 25 +++++++++++------- .../launch/gyro_bias_estimator.launch.xml | 2 +- .../launch/imu_corrector.launch.xml | 2 +- .../imu_corrector/src/gyro_bias_estimator.cpp | 7 +++-- .../imu_corrector/src/gyro_bias_estimator.hpp | 2 +- .../src/gyro_bias_estimator_node.cpp | 26 ------------------- .../imu_corrector/src/imu_corrector_core.cpp | 8 ++++-- .../imu_corrector/src/imu_corrector_core.hpp | 2 +- .../imu_corrector/src/imu_corrector_node.cpp | 26 ------------------- 9 files changed, 30 insertions(+), 70 deletions(-) delete mode 100644 sensing/imu_corrector/src/gyro_bias_estimator_node.cpp delete mode 100644 sensing/imu_corrector/src/imu_corrector_node.cpp diff --git a/sensing/imu_corrector/CMakeLists.txt b/sensing/imu_corrector/CMakeLists.txt index ded596a8a9898..b3be5be12b75d 100644 --- a/sensing/imu_corrector/CMakeLists.txt +++ b/sensing/imu_corrector/CMakeLists.txt @@ -4,27 +4,32 @@ project(imu_corrector) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_library(gyro_bias_estimation_module SHARED - src/gyro_bias_estimation_module.cpp -) - -ament_auto_add_executable(imu_corrector +ament_auto_add_library(${PROJECT_NAME} SHARED src/imu_corrector_core.cpp - src/imu_corrector_node.cpp ) -ament_auto_add_executable(gyro_bias_estimator +ament_auto_add_library(gyro_bias_estimator SHARED src/gyro_bias_estimator.cpp - src/gyro_bias_estimator_node.cpp + src/gyro_bias_estimation_module.cpp ) -target_link_libraries(gyro_bias_estimator gyro_bias_estimation_module) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "imu_corrector::ImuCorrector" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR SingleThreadedExecutor +) + +rclcpp_components_register_node(gyro_bias_estimator + PLUGIN "imu_corrector::GyroBiasEstimator" + EXECUTABLE gyro_bias_estimator_node + EXECUTOR SingleThreadedExecutor +) function(add_testcase filepath) get_filename_component(filename ${filepath} NAME) string(REGEX REPLACE ".cpp" "" test_name ${filename}) ament_add_gmock(${test_name} ${filepath}) - target_link_libraries("${test_name}" gyro_bias_estimation_module) + target_link_libraries("${test_name}" gyro_bias_estimator) ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS}) endfunction() diff --git a/sensing/imu_corrector/launch/gyro_bias_estimator.launch.xml b/sensing/imu_corrector/launch/gyro_bias_estimator.launch.xml index e16ccef446aba..100168b17171a 100644 --- a/sensing/imu_corrector/launch/gyro_bias_estimator.launch.xml +++ b/sensing/imu_corrector/launch/gyro_bias_estimator.launch.xml @@ -6,7 +6,7 @@ - + diff --git a/sensing/imu_corrector/launch/imu_corrector.launch.xml b/sensing/imu_corrector/launch/imu_corrector.launch.xml index d87d6e77c110d..8430f2a50a85c 100755 --- a/sensing/imu_corrector/launch/imu_corrector.launch.xml +++ b/sensing/imu_corrector/launch/imu_corrector.launch.xml @@ -4,7 +4,7 @@ - + diff --git a/sensing/imu_corrector/src/gyro_bias_estimator.cpp b/sensing/imu_corrector/src/gyro_bias_estimator.cpp index e99667ed1c4a6..d79626f66801b 100644 --- a/sensing/imu_corrector/src/gyro_bias_estimator.cpp +++ b/sensing/imu_corrector/src/gyro_bias_estimator.cpp @@ -23,8 +23,8 @@ namespace imu_corrector { -GyroBiasEstimator::GyroBiasEstimator() -: Node("gyro_bias_validator"), +GyroBiasEstimator::GyroBiasEstimator(const rclcpp::NodeOptions & options) +: rclcpp::Node("gyro_bias_validator", options), gyro_bias_threshold_(declare_parameter("gyro_bias_threshold")), angular_velocity_offset_x_(declare_parameter("angular_velocity_offset_x")), angular_velocity_offset_y_(declare_parameter("angular_velocity_offset_y")), @@ -244,3 +244,6 @@ void GyroBiasEstimator::update_diagnostics(diagnostic_updater::DiagnosticStatusW } } // namespace imu_corrector + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(imu_corrector::GyroBiasEstimator) diff --git a/sensing/imu_corrector/src/gyro_bias_estimator.hpp b/sensing/imu_corrector/src/gyro_bias_estimator.hpp index 3592ff1f7d3b4..671c18de78f86 100644 --- a/sensing/imu_corrector/src/gyro_bias_estimator.hpp +++ b/sensing/imu_corrector/src/gyro_bias_estimator.hpp @@ -42,7 +42,7 @@ class GyroBiasEstimator : public rclcpp::Node using Odometry = nav_msgs::msg::Odometry; public: - GyroBiasEstimator(); + explicit GyroBiasEstimator(const rclcpp::NodeOptions & options); private: void update_diagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat); diff --git a/sensing/imu_corrector/src/gyro_bias_estimator_node.cpp b/sensing/imu_corrector/src/gyro_bias_estimator_node.cpp deleted file mode 100644 index a491957bbb57f..0000000000000 --- a/sensing/imu_corrector/src/gyro_bias_estimator_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 "gyro_bias_estimator.hpp" - -#include - -int main(int argc, char * argv[]) -{ - rclcpp::init(argc, argv); - auto node = std::make_shared(); - rclcpp::spin(node); - rclcpp::shutdown(); - return 0; -} diff --git a/sensing/imu_corrector/src/imu_corrector_core.cpp b/sensing/imu_corrector/src/imu_corrector_core.cpp index a26c64925729c..c8e7698cb4e37 100644 --- a/sensing/imu_corrector/src/imu_corrector_core.cpp +++ b/sensing/imu_corrector/src/imu_corrector_core.cpp @@ -53,8 +53,9 @@ geometry_msgs::msg::Vector3 transformVector3( namespace imu_corrector { -ImuCorrector::ImuCorrector() -: Node("imu_corrector"), output_frame_(declare_parameter("base_link", "base_link")) +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); @@ -123,3 +124,6 @@ void ImuCorrector::callbackImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_m } } // namespace imu_corrector + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(imu_corrector::ImuCorrector) diff --git a/sensing/imu_corrector/src/imu_corrector_core.hpp b/sensing/imu_corrector/src/imu_corrector_core.hpp index 7709c611ab714..4d5377274ae78 100644 --- a/sensing/imu_corrector/src/imu_corrector_core.hpp +++ b/sensing/imu_corrector/src/imu_corrector_core.hpp @@ -34,7 +34,7 @@ class ImuCorrector : public rclcpp::Node using COV_IDX = tier4_autoware_utils::xyz_covariance_index::XYZ_COV_IDX; public: - ImuCorrector(); + explicit ImuCorrector(const rclcpp::NodeOptions & options); private: void callbackImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr); diff --git a/sensing/imu_corrector/src/imu_corrector_node.cpp b/sensing/imu_corrector/src/imu_corrector_node.cpp deleted file mode 100644 index c1df5bee28439..0000000000000 --- a/sensing/imu_corrector/src/imu_corrector_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 "imu_corrector_core.hpp" - -#include - -int main(int argc, char * argv[]) -{ - rclcpp::init(argc, argv); - auto node = std::make_shared(); - rclcpp::spin(node); - rclcpp::shutdown(); - return 0; -} From 1f6c264c211f08d24421e610b0190d31399e15ac Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 7 Jun 2024 17:23:05 +0900 Subject: [PATCH 19/65] refactor(path_optimizer, velocity_smoother)!: prefix package and namespace with autoware (#7354) * chore(autoware_velocity_smoother): update namespace Signed-off-by: satoshi-ota * chore(autoware_path_optimizer): update namespace Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../motion_planning/motion_planning.launch.xml | 2 +- .../scenario_planning/scenario_planning.launch.xml | 2 +- .../autoware_behavior_velocity_planner/src/node.cpp | 2 +- .../planner_data.hpp | 2 +- .../src/utilization/trajectory_utils.cpp | 2 +- planning/autoware_path_optimizer/CMakeLists.txt | 2 +- .../include/autoware_path_optimizer/common_structs.hpp | 4 ++-- .../include/autoware_path_optimizer/debug_marker.hpp | 4 ++-- .../include/autoware_path_optimizer/mpt_optimizer.hpp | 4 ++-- .../include/autoware_path_optimizer/node.hpp | 4 ++-- .../include/autoware_path_optimizer/replan_checker.hpp | 4 ++-- .../state_equation_generator.hpp | 4 ++-- .../include/autoware_path_optimizer/type_alias.hpp | 4 ++-- .../autoware_path_optimizer/utils/geometry_utils.hpp | 8 ++++---- .../autoware_path_optimizer/utils/trajectory_utils.hpp | 10 +++++----- planning/autoware_path_optimizer/src/debug_marker.cpp | 4 ++-- planning/autoware_path_optimizer/src/mpt_optimizer.cpp | 4 ++-- planning/autoware_path_optimizer/src/node.cpp | 6 +++--- .../autoware_path_optimizer/src/replan_checker.cpp | 4 ++-- .../src/state_equation_generator.cpp | 4 ++-- .../src/utils/geometry_utils.cpp | 4 ++-- .../src/utils/trajectory_utils.cpp | 10 +++++----- .../test/test_path_optimizer_node_interface.cpp | 2 +- .../optimization_trajectory_based_centerline.cpp | 4 ++-- planning/autoware_velocity_smoother/CMakeLists.txt | 2 +- .../include/autoware_velocity_smoother/node.hpp | 4 ++-- .../include/autoware_velocity_smoother/resample.hpp | 4 ++-- .../analytical_jerk_constrained_smoother.hpp | 4 ++-- .../velocity_planning_utils.hpp | 4 ++-- .../smoother/jerk_filtered_smoother.hpp | 4 ++-- .../smoother/l2_pseudo_jerk_smoother.hpp | 4 ++-- .../smoother/linf_pseudo_jerk_smoother.hpp | 4 ++-- .../smoother/smoother_base.hpp | 4 ++-- .../autoware_velocity_smoother/trajectory_utils.hpp | 4 ++-- planning/autoware_velocity_smoother/src/node.cpp | 6 +++--- planning/autoware_velocity_smoother/src/resample.cpp | 4 ++-- .../analytical_jerk_constrained_smoother.cpp | 4 ++-- .../velocity_planning_utils.cpp | 4 ++-- .../src/smoother/jerk_filtered_smoother.cpp | 4 ++-- .../src/smoother/l2_pseudo_jerk_smoother.cpp | 4 ++-- .../src/smoother/linf_pseudo_jerk_smoother.cpp | 4 ++-- .../src/smoother/smoother_base.cpp | 4 ++-- .../src/trajectory_utils.cpp | 4 ++-- .../test/test_smoother_functions.cpp | 4 ++-- .../test/test_velocity_smoother_node_interface.cpp | 2 +- .../planner_data.hpp | 2 +- .../autoware_motion_velocity_planner_node/src/node.cpp | 4 ++-- 47 files changed, 94 insertions(+), 94 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index b5173d6a98b2e..4ed38df2d3f09 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -62,7 +62,7 @@ - + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 6a7e00154256a..f96cac4f017a6 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -27,7 +27,7 @@ - + diff --git a/planning/autoware_behavior_velocity_planner/src/node.cpp b/planning/autoware_behavior_velocity_planner/src/node.cpp index 59049ef7f07f3..3ff4e813b3266 100644 --- a/planning/autoware_behavior_velocity_planner/src/node.cpp +++ b/planning/autoware_behavior_velocity_planner/src/node.cpp @@ -310,7 +310,7 @@ void BehaviorVelocityPlannerNode::onParam() // constructed. It would be required if it was a callback. std::lock_guard // lock(mutex_); planner_data_.velocity_smoother_ = - std::make_unique(*this); + std::make_unique(*this); planner_data_.velocity_smoother_->setWheelBase(planner_data_.vehicle_info_.wheel_base_m); } diff --git a/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp index 907683998dd29..c69f23215a369 100644 --- a/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp +++ b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp @@ -88,7 +88,7 @@ struct PlannerData bool is_simulation = false; // velocity smoother - std::shared_ptr velocity_smoother_; + std::shared_ptr velocity_smoother_; // route handler std::shared_ptr route_handler_; // parameters diff --git a/planning/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp b/planning/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp index 4d2ef59886ba7..1dc448bea5b86 100644 --- a/planning/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp +++ b/planning/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp @@ -82,7 +82,7 @@ bool smoothPath( traj_smoothed.begin(), traj_resampled.begin(), traj_resampled.begin() + traj_resampled_closest); if (external_v_limit) { - autoware_velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( + autoware::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( traj_resampled_closest, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed); } out_path = motion_utils::convertToPathWithLaneId(traj_smoothed); diff --git a/planning/autoware_path_optimizer/CMakeLists.txt b/planning/autoware_path_optimizer/CMakeLists.txt index 3ceeae1022b10..78077e6c42720 100644 --- a/planning/autoware_path_optimizer/CMakeLists.txt +++ b/planning/autoware_path_optimizer/CMakeLists.txt @@ -41,7 +41,7 @@ target_include_directories(autoware_path_optimizer # register node rclcpp_components_register_node(autoware_path_optimizer - PLUGIN "autoware_path_optimizer::PathOptimizer" + PLUGIN "autoware::path_optimizer::PathOptimizer" EXECUTABLE path_optimizer_node ) 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 b27eff787ca5a..d2de8d201d9fa 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 @@ -25,7 +25,7 @@ #include #include -namespace autoware_path_optimizer +namespace autoware::path_optimizer { struct ReferencePoint; struct Bounds; @@ -153,6 +153,6 @@ struct EgoNearestParam double dist_threshold{0.0}; double yaw_threshold{0.0}; }; -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer #endif // AUTOWARE_PATH_OPTIMIZER__COMMON_STRUCTS_HPP_ diff --git a/planning/autoware_path_optimizer/include/autoware_path_optimizer/debug_marker.hpp b/planning/autoware_path_optimizer/include/autoware_path_optimizer/debug_marker.hpp index d1d2abaeaad61..edca8d706047b 100644 --- a/planning/autoware_path_optimizer/include/autoware_path_optimizer/debug_marker.hpp +++ b/planning/autoware_path_optimizer/include/autoware_path_optimizer/debug_marker.hpp @@ -25,11 +25,11 @@ #include #include -namespace autoware_path_optimizer +namespace autoware::path_optimizer { MarkerArray getDebugMarker( const DebugData & debug_data, const std::vector & optimized_points, const vehicle_info_util::VehicleInfo & vehicle_info, const bool publish_extra_marker); -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer #endif // AUTOWARE_PATH_OPTIMIZER__DEBUG_MARKER_HPP_ 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 33da339c62e40..8c207a9a3830f 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 @@ -34,7 +34,7 @@ #include #include -namespace autoware_path_optimizer +namespace autoware::path_optimizer { struct Bounds { @@ -308,5 +308,5 @@ class MPTOptimizer size_t getNumberOfSlackVariables() const; std::optional calcNormalizedAvoidanceCost(const ReferencePoint & ref_point) const; }; -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer #endif // AUTOWARE_PATH_OPTIMIZER__MPT_OPTIMIZER_HPP_ 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 a0e776628e3cb..30c95debe11cb 100644 --- a/planning/autoware_path_optimizer/include/autoware_path_optimizer/node.hpp +++ b/planning/autoware_path_optimizer/include/autoware_path_optimizer/node.hpp @@ -33,7 +33,7 @@ #include #include -namespace autoware_path_optimizer +namespace autoware::path_optimizer { class PathOptimizer : public rclcpp::Node { @@ -141,6 +141,6 @@ class PathOptimizer : public rclcpp::Node std::unique_ptr published_time_publisher_; }; -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer #endif // AUTOWARE_PATH_OPTIMIZER__NODE_HPP_ diff --git a/planning/autoware_path_optimizer/include/autoware_path_optimizer/replan_checker.hpp b/planning/autoware_path_optimizer/include/autoware_path_optimizer/replan_checker.hpp index 8270bb631e0ae..26d9599f07091 100644 --- a/planning/autoware_path_optimizer/include/autoware_path_optimizer/replan_checker.hpp +++ b/planning/autoware_path_optimizer/include/autoware_path_optimizer/replan_checker.hpp @@ -24,7 +24,7 @@ #include #include -namespace autoware_path_optimizer +namespace autoware::path_optimizer { class ReplanChecker { @@ -66,6 +66,6 @@ class ReplanChecker bool isPathGoalChanged( const PlannerData & planner_data, const std::vector & prev_traj_points) const; }; -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer #endif // AUTOWARE_PATH_OPTIMIZER__REPLAN_CHECKER_HPP_ diff --git a/planning/autoware_path_optimizer/include/autoware_path_optimizer/state_equation_generator.hpp b/planning/autoware_path_optimizer/include/autoware_path_optimizer/state_equation_generator.hpp index 6ee4fcb0ab7a5..0c41da0ee5f62 100644 --- a/planning/autoware_path_optimizer/include/autoware_path_optimizer/state_equation_generator.hpp +++ b/planning/autoware_path_optimizer/include/autoware_path_optimizer/state_equation_generator.hpp @@ -22,7 +22,7 @@ #include #include -namespace autoware_path_optimizer +namespace autoware::path_optimizer { struct ReferencePoint; @@ -58,5 +58,5 @@ class StateEquationGenerator std::unique_ptr vehicle_model_ptr_; mutable std::shared_ptr time_keeper_ptr_; }; -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer #endif // AUTOWARE_PATH_OPTIMIZER__STATE_EQUATION_GENERATOR_HPP_ diff --git a/planning/autoware_path_optimizer/include/autoware_path_optimizer/type_alias.hpp b/planning/autoware_path_optimizer/include/autoware_path_optimizer/type_alias.hpp index 755d0b2ace297..63a5840789a6b 100644 --- a/planning/autoware_path_optimizer/include/autoware_path_optimizer/type_alias.hpp +++ b/planning/autoware_path_optimizer/include/autoware_path_optimizer/type_alias.hpp @@ -28,7 +28,7 @@ #include "tier4_debug_msgs/msg/string_stamped.hpp" #include "visualization_msgs/msg/marker_array.hpp" -namespace autoware_path_optimizer +namespace autoware::path_optimizer { // std_msgs using std_msgs::msg::Header; @@ -45,6 +45,6 @@ using visualization_msgs::msg::MarkerArray; // debug using tier4_debug_msgs::msg::Float64Stamped; using tier4_debug_msgs::msg::StringStamped; -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer #endif // AUTOWARE_PATH_OPTIMIZER__TYPE_ALIAS_HPP_ 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 32ef8cd5941fc..588b68f52a094 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 @@ -39,13 +39,13 @@ namespace tier4_autoware_utils { template <> -geometry_msgs::msg::Point getPoint(const autoware_path_optimizer::ReferencePoint & p); +geometry_msgs::msg::Point getPoint(const autoware::path_optimizer::ReferencePoint & p); template <> -geometry_msgs::msg::Pose getPose(const autoware_path_optimizer::ReferencePoint & p); +geometry_msgs::msg::Pose getPose(const autoware::path_optimizer::ReferencePoint & p); } // namespace tier4_autoware_utils -namespace autoware_path_optimizer +namespace autoware::path_optimizer { namespace geometry_utils { @@ -68,5 +68,5 @@ bool isOutsideDrivableAreaFromRectangleFootprint( const vehicle_info_util::VehicleInfo & vehicle_info, const bool use_footprint_polygon_for_outside_drivable_area_check); } // namespace geometry_utils -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer #endif // AUTOWARE_PATH_OPTIMIZER__UTILS__GEOMETRY_UTILS_HPP_ 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 1056d80ef37aa..f3f528df2ec42 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 @@ -38,16 +38,16 @@ namespace tier4_autoware_utils { template <> -geometry_msgs::msg::Point getPoint(const autoware_path_optimizer::ReferencePoint & p); +geometry_msgs::msg::Point getPoint(const autoware::path_optimizer::ReferencePoint & p); template <> -geometry_msgs::msg::Pose getPose(const autoware_path_optimizer::ReferencePoint & p); +geometry_msgs::msg::Pose getPose(const autoware::path_optimizer::ReferencePoint & p); template <> -double getLongitudinalVelocity(const autoware_path_optimizer::ReferencePoint & p); +double getLongitudinalVelocity(const autoware::path_optimizer::ReferencePoint & p); } // namespace tier4_autoware_utils -namespace autoware_path_optimizer +namespace autoware::path_optimizer { namespace trajectory_utils { @@ -214,5 +214,5 @@ void insertStopPoint( std::vector & traj_points, const geometry_msgs::msg::Pose & input_stop_pose, const size_t stop_seg_idx); } // namespace trajectory_utils -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer #endif // AUTOWARE_PATH_OPTIMIZER__UTILS__TRAJECTORY_UTILS_HPP_ diff --git a/planning/autoware_path_optimizer/src/debug_marker.cpp b/planning/autoware_path_optimizer/src/debug_marker.cpp index 3127d521160c2..7c644f4448a0c 100644 --- a/planning/autoware_path_optimizer/src/debug_marker.cpp +++ b/planning/autoware_path_optimizer/src/debug_marker.cpp @@ -18,7 +18,7 @@ #include "visualization_msgs/msg/marker_array.hpp" -namespace autoware_path_optimizer +namespace autoware::path_optimizer { using tier4_autoware_utils::appendMarkerArray; using tier4_autoware_utils::createDefaultMarker; @@ -432,4 +432,4 @@ MarkerArray getDebugMarker( return marker_array; } -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer diff --git a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp index ece301e64c97e..2ab622c6b4b58 100644 --- a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp +++ b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp @@ -29,7 +29,7 @@ #include #include -namespace autoware_path_optimizer +namespace autoware::path_optimizer { namespace { @@ -1783,4 +1783,4 @@ std::optional MPTOptimizer::calcNormalizedAvoidanceCost( } return std::clamp(-negative_avoidance_cost / mpt_param_.max_avoidance_cost, 0.0, 1.0); } -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer diff --git a/planning/autoware_path_optimizer/src/node.cpp b/planning/autoware_path_optimizer/src/node.cpp index 49d41e6b07884..816c0d459d95f 100644 --- a/planning/autoware_path_optimizer/src/node.cpp +++ b/planning/autoware_path_optimizer/src/node.cpp @@ -25,7 +25,7 @@ #include #include -namespace autoware_path_optimizer +namespace autoware::path_optimizer { namespace { @@ -666,7 +666,7 @@ void PathOptimizer::publishDebugData(const Header & header) const time_keeper_ptr_->toc(__func__, " "); } -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer #include "rclcpp_components/register_node_macro.hpp" -RCLCPP_COMPONENTS_REGISTER_NODE(autoware_path_optimizer::PathOptimizer) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::path_optimizer::PathOptimizer) diff --git a/planning/autoware_path_optimizer/src/replan_checker.cpp b/planning/autoware_path_optimizer/src/replan_checker.cpp index 797041ee75416..6745872f50b02 100644 --- a/planning/autoware_path_optimizer/src/replan_checker.cpp +++ b/planning/autoware_path_optimizer/src/replan_checker.cpp @@ -21,7 +21,7 @@ #include -namespace autoware_path_optimizer +namespace autoware::path_optimizer { ReplanChecker::ReplanChecker(rclcpp::Node * node, const EgoNearestParam & ego_nearest_param) : ego_nearest_param_(ego_nearest_param), logger_(node->get_logger().get_child("replan_checker")) @@ -212,4 +212,4 @@ bool ReplanChecker::isPathGoalChanged( return true; } -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer diff --git a/planning/autoware_path_optimizer/src/state_equation_generator.cpp b/planning/autoware_path_optimizer/src/state_equation_generator.cpp index 7712fbbf6c3cf..ec6a9e575be95 100644 --- a/planning/autoware_path_optimizer/src/state_equation_generator.cpp +++ b/planning/autoware_path_optimizer/src/state_equation_generator.cpp @@ -16,7 +16,7 @@ #include "autoware_path_optimizer/mpt_optimizer.hpp" -namespace autoware_path_optimizer +namespace autoware::path_optimizer { // state equation: x = B u + W (u includes x_0) // NOTE: Originally, x_t+1 = Ad x_t + Bd u + Wd. @@ -69,4 +69,4 @@ Eigen::VectorXd StateEquationGenerator::predict( { return mat.B * U + mat.W; } -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer diff --git a/planning/autoware_path_optimizer/src/utils/geometry_utils.cpp b/planning/autoware_path_optimizer/src/utils/geometry_utils.cpp index 9d93cdc26a7ed..45302c0b729a9 100644 --- a/planning/autoware_path_optimizer/src/utils/geometry_utils.cpp +++ b/planning/autoware_path_optimizer/src/utils/geometry_utils.cpp @@ -36,7 +36,7 @@ #include #include -namespace autoware_path_optimizer +namespace autoware::path_optimizer { namespace bg = boost::geometry; using tier4_autoware_utils::LinearRing2d; @@ -207,4 +207,4 @@ bool isOutsideDrivableAreaFromRectangleFootprint( return false; } } // namespace geometry_utils -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer diff --git a/planning/autoware_path_optimizer/src/utils/trajectory_utils.cpp b/planning/autoware_path_optimizer/src/utils/trajectory_utils.cpp index 7983c5c2a3c2f..75e2b75b232e0 100644 --- a/planning/autoware_path_optimizer/src/utils/trajectory_utils.cpp +++ b/planning/autoware_path_optimizer/src/utils/trajectory_utils.cpp @@ -36,25 +36,25 @@ namespace tier4_autoware_utils { template <> -geometry_msgs::msg::Point getPoint(const autoware_path_optimizer::ReferencePoint & p) +geometry_msgs::msg::Point getPoint(const autoware::path_optimizer::ReferencePoint & p) { return p.pose.position; } template <> -geometry_msgs::msg::Pose getPose(const autoware_path_optimizer::ReferencePoint & p) +geometry_msgs::msg::Pose getPose(const autoware::path_optimizer::ReferencePoint & p) { return p.pose; } template <> -double getLongitudinalVelocity(const autoware_path_optimizer::ReferencePoint & p) +double getLongitudinalVelocity(const autoware::path_optimizer::ReferencePoint & p) { return p.longitudinal_velocity_mps; } } // namespace tier4_autoware_utils -namespace autoware_path_optimizer +namespace autoware::path_optimizer { namespace trajectory_utils { @@ -242,4 +242,4 @@ void insertStopPoint( traj_points.insert(traj_points.begin() + stop_seg_idx + 1, additional_traj_point); } } // namespace trajectory_utils -} // namespace autoware_path_optimizer +} // namespace autoware::path_optimizer diff --git a/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp b/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp index 8ef099ba09f24..4af88539597be 100644 --- a/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp +++ b/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp @@ -42,7 +42,7 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) planning_test_utils_dir + "/config/test_nearest_search.param.yaml", "--params-file", path_optimizer_dir + "/config/path_optimizer.param.yaml"}); - auto test_target_node = std::make_shared(node_options); + auto test_target_node = std::make_shared(node_options); // publish necessary topics from test_manager test_manager->publishOdometry(test_target_node, "path_optimizer/input/odometry"); 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 9eb9a2b432a21..0705f0b51ddd3 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 @@ -130,7 +130,7 @@ std::vector OptimizationTrajectoryBasedCenterline::optimize_tra const auto eb_path_smoother_ptr = path_smoother::ElasticBandSmoother(create_node_options()).getElasticBandSmoother(); const auto mpt_optimizer_ptr = - autoware_path_optimizer::PathOptimizer(create_node_options()).getMPTOptimizer(); + autoware::path_optimizer::PathOptimizer(create_node_options()).getMPTOptimizer(); // NOTE: The optimization is executed every valid_optimized_traj_points_num points. constexpr int valid_optimized_traj_points_num = 10; @@ -158,7 +158,7 @@ std::vector OptimizationTrajectoryBasedCenterline::optimize_tra // road collision avoidance by model predictive trajectory in the autoware_path_optimizer // package - const autoware_path_optimizer::PlannerData planner_data{ + const autoware::path_optimizer::PlannerData planner_data{ raw_path.header, smoothed_traj_points, raw_path.left_bound, raw_path.right_bound, virtual_ego_pose}; const auto optimized_traj_points = mpt_optimizer_ptr->optimizeTrajectory(planner_data); diff --git a/planning/autoware_velocity_smoother/CMakeLists.txt b/planning/autoware_velocity_smoother/CMakeLists.txt index fee13513a7a97..9dd0c62c4537e 100644 --- a/planning/autoware_velocity_smoother/CMakeLists.txt +++ b/planning/autoware_velocity_smoother/CMakeLists.txt @@ -41,7 +41,7 @@ target_link_libraries(${PROJECT_NAME}_node ) rclcpp_components_register_node(${PROJECT_NAME}_node - PLUGIN "autoware_velocity_smoother::VelocitySmootherNode" + PLUGIN "autoware::velocity_smoother::VelocitySmootherNode" EXECUTABLE velocity_smoother_node ) 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 aecfab342e7e0..8ab7acd5ec9b3 100644 --- a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/node.hpp +++ b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/node.hpp @@ -53,7 +53,7 @@ #include #include -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; @@ -275,6 +275,6 @@ class VelocitySmootherNode : public rclcpp::Node std::unique_ptr logger_configure_; std::unique_ptr published_time_publisher_; }; -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother #endif // AUTOWARE_VELOCITY_SMOOTHER__NODE_HPP_ diff --git a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/resample.hpp b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/resample.hpp index dc85c2b2f336f..24a20ca8a588f 100644 --- a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/resample.hpp +++ b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/resample.hpp @@ -20,7 +20,7 @@ #include -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { namespace resampling { @@ -48,6 +48,6 @@ TrajectoryPoints resampleTrajectory( const double nearest_dist_threshold, const double nearest_yaw_threshold, const ResampleParam & param, const double nominal_ds, const bool use_zoh_for_v = true); } // namespace resampling -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother #endif // AUTOWARE_VELOCITY_SMOOTHER__RESAMPLE_HPP_ diff --git a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp index e54a6e7b8afad..a5baa59f5d034 100644 --- a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp +++ b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp @@ -28,7 +28,7 @@ #include #include -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { class AnalyticalJerkConstrainedSmoother : public SmootherBase { @@ -113,7 +113,7 @@ class AnalyticalJerkConstrainedSmoother : public SmootherBase std::string strTimes(const std::vector & times) const; std::string strStartIndices(const std::vector & start_indices) const; }; -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother // clang-format off #endif // AUTOWARE_VELOCITY_SMOOTHER__SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER_HPP_ // NOLINT diff --git a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp index 3ab4fce11fd0b..0c18e102f6f66 100644 --- a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp +++ b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp @@ -25,7 +25,7 @@ #include #include -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { namespace analytical_velocity_planning_utils { @@ -51,7 +51,7 @@ double integ_x(double x0, double v0, double a0, double j0, double t); double integ_v(double v0, double a0, double j0, double t); double integ_a(double a0, double j0, double t); } // namespace analytical_velocity_planning_utils -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother // clang-format off #endif // AUTOWARE_VELOCITY_SMOOTHER__SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER__VELOCITY_PLANNING_UTILS_HPP_ // NOLINT diff --git a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/jerk_filtered_smoother.hpp b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/jerk_filtered_smoother.hpp index 09c1e7e96be7b..4e93fcd339140 100644 --- a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/jerk_filtered_smoother.hpp +++ b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/jerk_filtered_smoother.hpp @@ -26,7 +26,7 @@ #include -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { class JerkFilteredSmoother : public SmootherBase { @@ -69,6 +69,6 @@ class JerkFilteredSmoother : public SmootherBase const double v0, const double a0, const double a_min, const double j_min, const TrajectoryPoints & forward_filtered, const TrajectoryPoints & backward_filtered) const; }; -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother #endif // AUTOWARE_VELOCITY_SMOOTHER__SMOOTHER__JERK_FILTERED_SMOOTHER_HPP_ diff --git a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp index 066e0acef67f6..44fa263e71fb9 100644 --- a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp +++ b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp @@ -26,7 +26,7 @@ #include -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { class L2PseudoJerkSmoother : public SmootherBase { @@ -56,6 +56,6 @@ class L2PseudoJerkSmoother : public SmootherBase autoware::common::osqp::OSQPInterface qp_solver_; rclcpp::Logger logger_{rclcpp::get_logger("smoother").get_child("l2_pseudo_jerk_smoother")}; }; -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother #endif // AUTOWARE_VELOCITY_SMOOTHER__SMOOTHER__L2_PSEUDO_JERK_SMOOTHER_HPP_ diff --git a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp index b54de318e9702..f638e03658e05 100644 --- a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp +++ b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp @@ -26,7 +26,7 @@ #include -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { class LinfPseudoJerkSmoother : public SmootherBase { @@ -56,6 +56,6 @@ class LinfPseudoJerkSmoother : public SmootherBase autoware::common::osqp::OSQPInterface qp_solver_; rclcpp::Logger logger_{rclcpp::get_logger("smoother").get_child("linf_pseudo_jerk_smoother")}; }; -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother #endif // AUTOWARE_VELOCITY_SMOOTHER__SMOOTHER__LINF_PSEUDO_JERK_SMOOTHER_HPP_ diff --git a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/smoother_base.hpp b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/smoother_base.hpp index 43ccfcf193f14..0c17ef5bdbb9d 100644 --- a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/smoother_base.hpp +++ b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/smoother/smoother_base.hpp @@ -23,7 +23,7 @@ #include #include -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { using autoware_planning_msgs::msg::TrajectoryPoint; using TrajectoryPoints = std::vector; @@ -86,6 +86,6 @@ class SmootherBase protected: BaseParam base_param_; }; -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother #endif // AUTOWARE_VELOCITY_SMOOTHER__SMOOTHER__SMOOTHER_BASE_HPP_ diff --git a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/trajectory_utils.hpp b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/trajectory_utils.hpp index d35f80fb7fad8..f7999d1c8b04c 100644 --- a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/trajectory_utils.hpp +++ b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/trajectory_utils.hpp @@ -23,7 +23,7 @@ #include #include -namespace autoware_velocity_smoother::trajectory_utils +namespace autoware::velocity_smoother::trajectory_utils { using autoware_planning_msgs::msg::TrajectoryPoint; using TrajectoryPoints = std::vector; @@ -77,6 +77,6 @@ std::vector calcVelocityProfileWithConstantJerkAndAccelerationLimit( double calcStopDistance(const TrajectoryPoints & trajectory, const size_t closest); -} // namespace autoware_velocity_smoother::trajectory_utils +} // namespace autoware::velocity_smoother::trajectory_utils #endif // AUTOWARE_VELOCITY_SMOOTHER__TRAJECTORY_UTILS_HPP_ diff --git a/planning/autoware_velocity_smoother/src/node.cpp b/planning/autoware_velocity_smoother/src/node.cpp index 0ea10534eb126..0fd83871153f0 100644 --- a/planning/autoware_velocity_smoother/src/node.cpp +++ b/planning/autoware_velocity_smoother/src/node.cpp @@ -32,7 +32,7 @@ #include // clang-format on -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_options) : Node("velocity_smoother", node_options) @@ -1099,7 +1099,7 @@ TrajectoryPoint VelocitySmootherNode::calcProjectedTrajectoryPointFromEgo( return calcProjectedTrajectoryPoint(trajectory, current_odometry_ptr_->pose.pose); } -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother #include "rclcpp_components/register_node_macro.hpp" -RCLCPP_COMPONENTS_REGISTER_NODE(autoware_velocity_smoother::VelocitySmootherNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::velocity_smoother::VelocitySmootherNode) diff --git a/planning/autoware_velocity_smoother/src/resample.cpp b/planning/autoware_velocity_smoother/src/resample.cpp index 17ea1eb9fc9bd..af3b222a71ef9 100644 --- a/planning/autoware_velocity_smoother/src/resample.cpp +++ b/planning/autoware_velocity_smoother/src/resample.cpp @@ -22,7 +22,7 @@ #include #include -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { namespace resampling { @@ -264,4 +264,4 @@ TrajectoryPoints resampleTrajectory( } } // namespace resampling -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother 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 9cdfc515d51b7..dc5f4f19ce771 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 @@ -64,7 +64,7 @@ bool applyMaxVelocity( } // namespace -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { AnalyticalJerkConstrainedSmoother::AnalyticalJerkConstrainedSmoother(rclcpp::Node & node) : SmootherBase(node) @@ -658,4 +658,4 @@ std::string AnalyticalJerkConstrainedSmoother::strStartIndices( return ss.str(); } -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother 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 84ac29d14bdc5..e3edcfbbec681 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 @@ -19,7 +19,7 @@ #include #include -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { namespace analytical_velocity_planning_utils { @@ -353,4 +353,4 @@ double integ_a(double a0, double j0, double t) } } // namespace analytical_velocity_planning_utils -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother 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 d212cfc0bcedf..d759930eb4320 100644 --- a/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp @@ -27,7 +27,7 @@ #define VERBOSE_TRAJECTORY_VELOCITY false -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { JerkFilteredSmoother::JerkFilteredSmoother(rclcpp::Node & node) : SmootherBase(node) { @@ -480,4 +480,4 @@ TrajectoryPoints JerkFilteredSmoother::resampleTrajectory( smoother_param_.jerk_filter_ds); } -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother diff --git a/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp index 3c2872f2e58e3..fff1166567aee 100644 --- a/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp @@ -23,7 +23,7 @@ #include #include -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { L2PseudoJerkSmoother::L2PseudoJerkSmoother(rclcpp::Node & node) : SmootherBase(node) { @@ -242,4 +242,4 @@ TrajectoryPoints L2PseudoJerkSmoother::resampleTrajectory( base_param_.resample_param); } -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother diff --git a/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp index f434d8d4514ca..b00936f3092ad 100644 --- a/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp @@ -23,7 +23,7 @@ #include #include -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { LinfPseudoJerkSmoother::LinfPseudoJerkSmoother(rclcpp::Node & node) : SmootherBase(node) { @@ -254,4 +254,4 @@ TrajectoryPoints LinfPseudoJerkSmoother::resampleTrajectory( base_param_.resample_param); } -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother diff --git a/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp b/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp index 5704113067244..e1d72889203cc 100644 --- a/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp @@ -26,7 +26,7 @@ #include #include -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { namespace @@ -270,4 +270,4 @@ TrajectoryPoints SmootherBase::applySteeringRateLimit( return output; } -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother diff --git a/planning/autoware_velocity_smoother/src/trajectory_utils.cpp b/planning/autoware_velocity_smoother/src/trajectory_utils.cpp index aff1a0b0e3213..6ebf246748666 100644 --- a/planning/autoware_velocity_smoother/src/trajectory_utils.cpp +++ b/planning/autoware_velocity_smoother/src/trajectory_utils.cpp @@ -25,7 +25,7 @@ #include #include -namespace autoware_velocity_smoother +namespace autoware::velocity_smoother { using geometry_msgs::msg::Point; namespace trajectory_utils @@ -610,4 +610,4 @@ double calcStopDistance(const TrajectoryPoints & trajectory, const size_t closes } } // namespace trajectory_utils -} // namespace autoware_velocity_smoother +} // namespace autoware::velocity_smoother diff --git a/planning/autoware_velocity_smoother/test/test_smoother_functions.cpp b/planning/autoware_velocity_smoother/test/test_smoother_functions.cpp index 51ee84f535ca4..f1b7dbb197ea2 100644 --- a/planning/autoware_velocity_smoother/test/test_smoother_functions.cpp +++ b/planning/autoware_velocity_smoother/test/test_smoother_functions.cpp @@ -18,8 +18,8 @@ #include +using autoware::velocity_smoother::trajectory_utils::TrajectoryPoints; using autoware_planning_msgs::msg::TrajectoryPoint; -using autoware_velocity_smoother::trajectory_utils::TrajectoryPoints; TrajectoryPoints genStraightTrajectory(const size_t size) { @@ -48,7 +48,7 @@ TEST(TestTrajectoryUtils, CalcTrajectoryCurvatureFrom3Points) const auto checkOutputSize = [](const size_t trajectory_size, const size_t idx_dist) { const auto trajectory_points = genStraightTrajectory(trajectory_size); const auto curvatures = - autoware_velocity_smoother::trajectory_utils::calcTrajectoryCurvatureFrom3Points( + autoware::velocity_smoother::trajectory_utils::calcTrajectoryCurvatureFrom3Points( trajectory_points, idx_dist); EXPECT_EQ(curvatures.size(), trajectory_size) << ", idx_dist = " << idx_dist; }; diff --git a/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp b/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp index f0145ea5a32a7..30a64955366e4 100644 --- a/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp +++ b/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp @@ -22,7 +22,7 @@ #include -using autoware_velocity_smoother::VelocitySmootherNode; +using autoware::velocity_smoother::VelocitySmootherNode; using planning_test_utils::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp index add6b5ef392ea..87aa4ac483feb 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp @@ -81,7 +81,7 @@ struct PlannerData tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr virtual_traffic_light_states; // velocity smoother - std::shared_ptr velocity_smoother_{}; + std::shared_ptr velocity_smoother_{}; // parameters vehicle_info_util::VehicleInfo vehicle_info_; 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 4d152afa250b7..262c32fe1ea47 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 @@ -241,7 +241,7 @@ void MotionVelocityPlannerNode::on_acceleration( void MotionVelocityPlannerNode::set_velocity_smoother_params() { planner_data_.velocity_smoother_ = - std::make_shared(*this); + std::make_shared(*this); } void MotionVelocityPlannerNode::on_lanelet_map( @@ -399,7 +399,7 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s traj_smoothed.begin(), traj_resampled.begin(), traj_resampled.begin() + traj_resampled_closest); if (external_v_limit) { - autoware_velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( + autoware::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( traj_resampled_closest, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed); } return traj_smoothed; From fbe57b183f9be2cd56cf0c895df3ddfb5d84eb6a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 7 Jun 2024 17:34:49 +0900 Subject: [PATCH 20/65] refactor(costmap_generator)!: add autoware prefix (#7329) refactor(costmap_generator): add autoware prefix Signed-off-by: kosuke55 --- .github/CODEOWNERS | 2 +- .../launch/scenario_planning/parking.launch.xml | 2 +- launch/tier4_planning_launch/package.xml | 2 +- .../README.md | 2 +- .../CMakeLists.txt | 12 ++++++------ .../README.md | 0 .../config/costmap_generator.param.yaml | 0 .../costmap_generator.hpp | 13 ++++++++----- .../object_map_utils.hpp | 6 +++--- .../objects_to_costmap.hpp | 10 ++++++---- .../points_to_costmap.hpp | 10 +++++++--- .../launch/costmap_generator.launch.xml | 4 ++-- .../costmap_generator_node.cpp | 9 ++++++--- .../object_map_utils.cpp | 2 +- .../objects_to_costmap.cpp | 5 ++++- .../points_to_costmap.cpp | 7 ++++++- .../package.xml | 4 ++-- .../schema/costmap_generator.schema.json | 0 .../test/test_objects_to_costmap.cpp | 5 ++++- .../test/test_points_to_costmap.cpp | 6 +++++- 20 files changed, 64 insertions(+), 37 deletions(-) rename planning/{costmap_generator => autoware_costmap_generator}/CMakeLists.txt (80%) rename planning/{costmap_generator => autoware_costmap_generator}/README.md (100%) rename planning/{costmap_generator => autoware_costmap_generator}/config/costmap_generator.param.yaml (100%) rename planning/{costmap_generator/include/costmap_generator => autoware_costmap_generator/include/autoware_costmap_generator}/costmap_generator.hpp (94%) rename planning/{costmap_generator/include/costmap_generator => autoware_costmap_generator/include/autoware_costmap_generator}/object_map_utils.hpp (95%) rename planning/{costmap_generator/include/costmap_generator => autoware_costmap_generator/include/autoware_costmap_generator}/objects_to_costmap.hpp (95%) rename planning/{costmap_generator/include/costmap_generator => autoware_costmap_generator/include/autoware_costmap_generator}/points_to_costmap.hpp (95%) rename planning/{costmap_generator => autoware_costmap_generator}/launch/costmap_generator.launch.xml (84%) rename planning/{costmap_generator/nodes/costmap_generator => autoware_costmap_generator/nodes/autoware_costmap_generator}/costmap_generator_node.cpp (98%) rename planning/{costmap_generator/nodes/costmap_generator => autoware_costmap_generator/nodes/autoware_costmap_generator}/object_map_utils.cpp (98%) rename planning/{costmap_generator/nodes/costmap_generator => autoware_costmap_generator/nodes/autoware_costmap_generator}/objects_to_costmap.cpp (98%) rename planning/{costmap_generator/nodes/costmap_generator => autoware_costmap_generator/nodes/autoware_costmap_generator}/points_to_costmap.cpp (97%) rename planning/{costmap_generator => autoware_costmap_generator}/package.xml (92%) rename planning/{costmap_generator => autoware_costmap_generator}/schema/costmap_generator.schema.json (100%) rename planning/{costmap_generator => autoware_costmap_generator}/test/test_objects_to_costmap.cpp (97%) rename planning/{costmap_generator => autoware_costmap_generator}/test/test_points_to_costmap.cpp (98%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 7a0c8f8893a39..2eefee5606ab2 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -153,6 +153,7 @@ planning/autoware_behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp m planning/autoware_behavior_velocity_template_module/** daniel.sanchez@tier4.jp planning/autoware_behavior_velocity_virtual_traffic_light_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/autoware_behavior_velocity_walkway_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp +planning/autoware_costmap_generator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/autoware_external_velocity_limit_selector/** satoshi.ota@tier4.jp shinnosuke.hirakawa@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/autoware_path_optimizer/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/autoware_planning_test_manager/** kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp @@ -183,7 +184,6 @@ planning/autoware_behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp m planning/behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_stop_line_module/** fumiya.watanabe@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp zhe.shen@tier4.jp planning/behavior_velocity_traffic_light_module/** mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -planning/costmap_generator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/freespace_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/freespace_planning_algorithms/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/mission_planner/** isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp ryohsuke.mitsudome@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp diff --git a/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml index 98315919b540a..db5a9a0093e7c 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml @@ -4,7 +4,7 @@ - + diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 0a585bce673b6..e5def4c7aed0c 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -58,6 +58,7 @@ autoware_cmake autoware_behavior_velocity_planner + autoware_costmap_generator autoware_external_velocity_limit_selector autoware_path_optimizer autoware_planning_topic_converter @@ -66,7 +67,6 @@ autoware_surround_obstacle_checker autoware_velocity_smoother behavior_path_planner - costmap_generator external_cmd_selector freespace_planner glog_component diff --git a/planning/autoware_behavior_path_start_planner_module/README.md b/planning/autoware_behavior_path_start_planner_module/README.md index 71aa0a1abe704..bcb3b1bec1fd9 100644 --- a/planning/autoware_behavior_path_start_planner_module/README.md +++ b/planning/autoware_behavior_path_start_planner_module/README.md @@ -526,7 +526,7 @@ If a safe path cannot be generated from the current position, search backwards f ### **freespace pull out** If the vehicle gets stuck with pull out along lanes, execute freespace pull out. -To run this feature, you need to set `parking_lot` to the map, `activate_by_scenario` of [costmap_generator](../costmap_generator/README.md) to `false` and `enable_freespace_planner` to `true` +To run this feature, you need to set `parking_lot` to the map, `activate_by_scenario` of [costmap_generator](../autoware_costmap_generator/README.md) to `false` and `enable_freespace_planner` to `true` diff --git a/planning/costmap_generator/CMakeLists.txt b/planning/autoware_costmap_generator/CMakeLists.txt similarity index 80% rename from planning/costmap_generator/CMakeLists.txt rename to planning/autoware_costmap_generator/CMakeLists.txt index 620a997990001..b8b15a7312324 100644 --- a/planning/costmap_generator/CMakeLists.txt +++ b/planning/autoware_costmap_generator/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(costmap_generator) +project(autoware_costmap_generator) find_package(autoware_cmake REQUIRED) autoware_package() @@ -16,9 +16,9 @@ include_directories( ) ament_auto_add_library(costmap_generator_lib SHARED - nodes/costmap_generator/points_to_costmap.cpp - nodes/costmap_generator/objects_to_costmap.cpp - nodes/costmap_generator/object_map_utils.cpp + nodes/autoware_costmap_generator/points_to_costmap.cpp + nodes/autoware_costmap_generator/objects_to_costmap.cpp + nodes/autoware_costmap_generator/object_map_utils.cpp ) target_link_libraries(costmap_generator_lib ${PCL_LIBRARIES} @@ -33,7 +33,7 @@ if(${PCL_VERSION} GREATER_EQUAL 1.12.1) endif() ament_auto_add_library(costmap_generator_node SHARED - nodes/costmap_generator/costmap_generator_node.cpp + nodes/autoware_costmap_generator/costmap_generator_node.cpp ) target_link_libraries(costmap_generator_node ${PCL_LIBRARIES} @@ -41,7 +41,7 @@ target_link_libraries(costmap_generator_node ) rclcpp_components_register_node(costmap_generator_node - PLUGIN "CostmapGenerator" + PLUGIN "autoware::costmap_generator::CostmapGenerator" EXECUTABLE costmap_generator ) diff --git a/planning/costmap_generator/README.md b/planning/autoware_costmap_generator/README.md similarity index 100% rename from planning/costmap_generator/README.md rename to planning/autoware_costmap_generator/README.md diff --git a/planning/costmap_generator/config/costmap_generator.param.yaml b/planning/autoware_costmap_generator/config/costmap_generator.param.yaml similarity index 100% rename from planning/costmap_generator/config/costmap_generator.param.yaml rename to planning/autoware_costmap_generator/config/costmap_generator.param.yaml diff --git a/planning/costmap_generator/include/costmap_generator/costmap_generator.hpp b/planning/autoware_costmap_generator/include/autoware_costmap_generator/costmap_generator.hpp similarity index 94% rename from planning/costmap_generator/include/costmap_generator/costmap_generator.hpp rename to planning/autoware_costmap_generator/include/autoware_costmap_generator/costmap_generator.hpp index 31c8a05cc3c60..093c88541e9c8 100644 --- a/planning/costmap_generator/include/costmap_generator/costmap_generator.hpp +++ b/planning/autoware_costmap_generator/include/autoware_costmap_generator/costmap_generator.hpp @@ -42,11 +42,11 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ********************/ -#ifndef COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_ -#define COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_ +#ifndef AUTOWARE_COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_ +#define AUTOWARE_COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_ -#include "costmap_generator/objects_to_costmap.hpp" -#include "costmap_generator/points_to_costmap.hpp" +#include "autoware_costmap_generator/objects_to_costmap.hpp" +#include "autoware_costmap_generator/points_to_costmap.hpp" #include #include @@ -72,6 +72,8 @@ #include #include +namespace autoware::costmap_generator +{ class CostmapGenerator : public rclcpp::Node { public: @@ -197,5 +199,6 @@ class CostmapGenerator : public rclcpp::Node /// \brief calculate cost for final output grid_map::Matrix generateCombinedCostmap(); }; +} // namespace autoware::costmap_generator -#endif // COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_ +#endif // AUTOWARE_COSTMAP_GENERATOR__COSTMAP_GENERATOR_HPP_ diff --git a/planning/costmap_generator/include/costmap_generator/object_map_utils.hpp b/planning/autoware_costmap_generator/include/autoware_costmap_generator/object_map_utils.hpp similarity index 95% rename from planning/costmap_generator/include/costmap_generator/object_map_utils.hpp rename to planning/autoware_costmap_generator/include/autoware_costmap_generator/object_map_utils.hpp index 282bd6dcc1beb..f4911cc428d36 100644 --- a/planning/costmap_generator/include/costmap_generator/object_map_utils.hpp +++ b/planning/autoware_costmap_generator/include/autoware_costmap_generator/object_map_utils.hpp @@ -30,8 +30,8 @@ * */ -#ifndef COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_ -#define COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_ +#ifndef AUTOWARE_COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_ +#define AUTOWARE_COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_ #include #include @@ -98,4 +98,4 @@ void FillPolygonAreas( } // namespace object_map -#endif // COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_ +#endif // AUTOWARE_COSTMAP_GENERATOR__OBJECT_MAP_UTILS_HPP_ diff --git a/planning/costmap_generator/include/costmap_generator/objects_to_costmap.hpp b/planning/autoware_costmap_generator/include/autoware_costmap_generator/objects_to_costmap.hpp similarity index 95% rename from planning/costmap_generator/include/costmap_generator/objects_to_costmap.hpp rename to planning/autoware_costmap_generator/include/autoware_costmap_generator/objects_to_costmap.hpp index a88bb97a623e2..aa11a98830dc3 100644 --- a/planning/costmap_generator/include/costmap_generator/objects_to_costmap.hpp +++ b/planning/autoware_costmap_generator/include/autoware_costmap_generator/objects_to_costmap.hpp @@ -42,8 +42,8 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ********************/ -#ifndef COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_ -#define COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_ +#ifndef AUTOWARE_COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_ +#define AUTOWARE_COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_ #include @@ -57,6 +57,8 @@ #include +namespace autoware::costmap_generator +{ class ObjectsToCostmap { public: @@ -123,5 +125,5 @@ class ObjectsToCostmap const grid_map::Polygon & polygon, const std::string & gridmap_layer_name, const float score, grid_map::GridMap & objects_costmap); }; - -#endif // COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_ +} // namespace autoware::costmap_generator +#endif // AUTOWARE_COSTMAP_GENERATOR__OBJECTS_TO_COSTMAP_HPP_ diff --git a/planning/costmap_generator/include/costmap_generator/points_to_costmap.hpp b/planning/autoware_costmap_generator/include/autoware_costmap_generator/points_to_costmap.hpp similarity index 95% rename from planning/costmap_generator/include/costmap_generator/points_to_costmap.hpp rename to planning/autoware_costmap_generator/include/autoware_costmap_generator/points_to_costmap.hpp index 3b179d63f1d2a..0e3abbd69ec20 100644 --- a/planning/costmap_generator/include/costmap_generator/points_to_costmap.hpp +++ b/planning/autoware_costmap_generator/include/autoware_costmap_generator/points_to_costmap.hpp @@ -42,8 +42,8 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ********************/ -#ifndef COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_ -#define COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_ +#ifndef AUTOWARE_COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_ +#define AUTOWARE_COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_ #include @@ -52,6 +52,9 @@ #include #include +namespace autoware::costmap_generator + +{ class PointsToCostmap { public: @@ -115,5 +118,6 @@ class PointsToCostmap const std::string & gridmap_layer_name, const std::vector>> grid_vec); }; +} // namespace autoware::costmap_generator -#endif // COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_ +#endif // AUTOWARE_COSTMAP_GENERATOR__POINTS_TO_COSTMAP_HPP_ diff --git a/planning/costmap_generator/launch/costmap_generator.launch.xml b/planning/autoware_costmap_generator/launch/costmap_generator.launch.xml similarity index 84% rename from planning/costmap_generator/launch/costmap_generator.launch.xml rename to planning/autoware_costmap_generator/launch/costmap_generator.launch.xml index ba8a71f5f428a..e7c378565dd0f 100644 --- a/planning/costmap_generator/launch/costmap_generator.launch.xml +++ b/planning/autoware_costmap_generator/launch/costmap_generator.launch.xml @@ -6,9 +6,9 @@ - + - + diff --git a/planning/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp b/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/costmap_generator_node.cpp similarity index 98% rename from planning/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp rename to planning/autoware_costmap_generator/nodes/autoware_costmap_generator/costmap_generator_node.cpp index 777dfc7a50a6e..4302ac6ada645 100644 --- a/planning/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp +++ b/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/costmap_generator_node.cpp @@ -42,8 +42,8 @@ * OF private_node SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ********************/ -#include "costmap_generator/costmap_generator.hpp" -#include "costmap_generator/object_map_utils.hpp" +#include "autoware_costmap_generator/costmap_generator.hpp" +#include "autoware_costmap_generator/object_map_utils.hpp" #include #include @@ -157,6 +157,8 @@ pcl::PointCloud getTransformedPointCloud( } // namespace +namespace autoware::costmap_generator +{ CostmapGenerator::CostmapGenerator(const rclcpp::NodeOptions & node_options) : Node("costmap_generator", node_options), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { @@ -476,6 +478,7 @@ void CostmapGenerator::publishCostmap(const grid_map::GridMap & costmap) out_gridmap_msg->header = header; pub_costmap_->publish(*out_gridmap_msg); } +} // namespace autoware::costmap_generator #include -RCLCPP_COMPONENTS_REGISTER_NODE(CostmapGenerator) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::costmap_generator::CostmapGenerator) diff --git a/planning/costmap_generator/nodes/costmap_generator/object_map_utils.cpp b/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/object_map_utils.cpp similarity index 98% rename from planning/costmap_generator/nodes/costmap_generator/object_map_utils.cpp rename to planning/autoware_costmap_generator/nodes/autoware_costmap_generator/object_map_utils.cpp index 6955798be3e8a..4ce452814008c 100644 --- a/planning/costmap_generator/nodes/costmap_generator/object_map_utils.cpp +++ b/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/object_map_utils.cpp @@ -30,7 +30,7 @@ * */ -#include "costmap_generator/object_map_utils.hpp" +#include "autoware_costmap_generator/object_map_utils.hpp" #include #include diff --git a/planning/costmap_generator/nodes/costmap_generator/objects_to_costmap.cpp b/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/objects_to_costmap.cpp similarity index 98% rename from planning/costmap_generator/nodes/costmap_generator/objects_to_costmap.cpp rename to planning/autoware_costmap_generator/nodes/autoware_costmap_generator/objects_to_costmap.cpp index f6f024fb92a4e..afb2dbb9874c9 100644 --- a/planning/costmap_generator/nodes/costmap_generator/objects_to_costmap.cpp +++ b/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/objects_to_costmap.cpp @@ -42,13 +42,15 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ********************/ -#include "costmap_generator/objects_to_costmap.hpp" +#include "autoware_costmap_generator/objects_to_costmap.hpp" #include #include #include +namespace autoware::costmap_generator +{ // Constructor ObjectsToCostmap::ObjectsToCostmap() : NUMBER_OF_POINTS(4), @@ -196,3 +198,4 @@ grid_map::Matrix ObjectsToCostmap::makeCostmapFromObjects( return objects_costmap[OBJECTS_COSTMAP_LAYER_]; } +} // namespace autoware::costmap_generator diff --git a/planning/costmap_generator/nodes/costmap_generator/points_to_costmap.cpp b/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/points_to_costmap.cpp similarity index 97% rename from planning/costmap_generator/nodes/costmap_generator/points_to_costmap.cpp rename to planning/autoware_costmap_generator/nodes/autoware_costmap_generator/points_to_costmap.cpp index e875f68973a12..723c27201ac8a 100644 --- a/planning/costmap_generator/nodes/costmap_generator/points_to_costmap.cpp +++ b/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/points_to_costmap.cpp @@ -42,11 +42,14 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ********************/ -#include "costmap_generator/points_to_costmap.hpp" +#include "autoware_costmap_generator/points_to_costmap.hpp" #include #include +namespace autoware::costmap_generator +{ + void PointsToCostmap::initGridmapParam(const grid_map::GridMap & gridmap) { grid_length_x_ = gridmap.getLength().x(); @@ -140,3 +143,5 @@ grid_map::Matrix PointsToCostmap::makeCostmapFromPoints( gridmap_layer_name, grid_vec); return costmap; } + +} // namespace autoware::costmap_generator diff --git a/planning/costmap_generator/package.xml b/planning/autoware_costmap_generator/package.xml similarity index 92% rename from planning/costmap_generator/package.xml rename to planning/autoware_costmap_generator/package.xml index dc94d74dce8ae..aa1ae80eaf953 100644 --- a/planning/costmap_generator/package.xml +++ b/planning/autoware_costmap_generator/package.xml @@ -1,9 +1,9 @@ - costmap_generator + autoware_costmap_generator 0.1.0 - The costmap_generator package + The autoware_costmap_generator package Kosuke Takeuchi Takamasa Horibe Takayuki Murooka diff --git a/planning/costmap_generator/schema/costmap_generator.schema.json b/planning/autoware_costmap_generator/schema/costmap_generator.schema.json similarity index 100% rename from planning/costmap_generator/schema/costmap_generator.schema.json rename to planning/autoware_costmap_generator/schema/costmap_generator.schema.json diff --git a/planning/costmap_generator/test/test_objects_to_costmap.cpp b/planning/autoware_costmap_generator/test/test_objects_to_costmap.cpp similarity index 97% rename from planning/costmap_generator/test/test_objects_to_costmap.cpp rename to planning/autoware_costmap_generator/test/test_objects_to_costmap.cpp index 15b853d0782aa..8d437865b8793 100644 --- a/planning/costmap_generator/test/test_objects_to_costmap.cpp +++ b/planning/autoware_costmap_generator/test/test_objects_to_costmap.cpp @@ -12,11 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include #include +namespace autoware::costmap_generator +{ using LABEL = autoware_perception_msgs::msg::ObjectClassification; class ObjectsToCostMapTest : public ::testing::Test @@ -134,3 +136,4 @@ TEST_F(ObjectsToCostMapTest, TestMakeCostmapFromObjects) } } } +} // namespace autoware::costmap_generator diff --git a/planning/costmap_generator/test/test_points_to_costmap.cpp b/planning/autoware_costmap_generator/test/test_points_to_costmap.cpp similarity index 98% rename from planning/costmap_generator/test/test_points_to_costmap.cpp rename to planning/autoware_costmap_generator/test/test_points_to_costmap.cpp index 2366dffc7fc6f..6c52e2dc6ce9d 100644 --- a/planning/costmap_generator/test/test_points_to_costmap.cpp +++ b/planning/autoware_costmap_generator/test/test_points_to_costmap.cpp @@ -12,9 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include + +namespace autoware::costmap_generator +{ using pointcloud = pcl::PointCloud; class PointsToCostmapTest : public ::testing::Test { @@ -216,3 +219,4 @@ TEST_F(PointsToCostmapTest, TestMakeCostmapFromPoints_invalidPoints_outOfGrid) EXPECT_EQ(nonempty_grid_cell_num, 0); } +} // namespace autoware::costmap_generator From 2b0de17b1602b5afcf7ad9ddfd69f25c7cc2d722 Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Fri, 7 Jun 2024 17:47:22 +0900 Subject: [PATCH 21/65] refactor(gyro_odometer): apply static analysis (#7360) * refactor based on linter Signed-off-by: a-maumau * style(pre-commit): autofix --------- Signed-off-by: a-maumau Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../gyro_odometer/diagnostics_module.hpp | 16 ++-- .../gyro_odometer/gyro_odometer_core.hpp | 9 +- .../gyro_odometer/src/diagnostics_module.cpp | 16 ++-- .../gyro_odometer/src/gyro_odometer_core.cpp | 91 +++++++++---------- .../test/test_gyro_odometer_helper.cpp | 6 +- .../test/test_gyro_odometer_helper.hpp | 9 +- .../test/test_gyro_odometer_pubsub.cpp | 41 +++++---- 7 files changed, 92 insertions(+), 96 deletions(-) diff --git a/localization/gyro_odometer/include/gyro_odometer/diagnostics_module.hpp b/localization/gyro_odometer/include/gyro_odometer/diagnostics_module.hpp index 49b881900b997..c5b7b7a592013 100644 --- a/localization/gyro_odometer/include/gyro_odometer/diagnostics_module.hpp +++ b/localization/gyro_odometer/include/gyro_odometer/diagnostics_module.hpp @@ -30,14 +30,14 @@ class DiagnosticsModule public: DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name); void clear(); - void addKeyValue(const diagnostic_msgs::msg::KeyValue & key_value_msg); + void add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg); template - void addKeyValue(const std::string & key, const T & value); - void updateLevelAndMessage(const int8_t level, const std::string & message); + void add_key_value(const std::string & key, const T & value); + void update_level_and_message(const int8_t level, const std::string & message); void publish(const rclcpp::Time & publish_time_stamp); private: - diagnostic_msgs::msg::DiagnosticArray createDiagnosticsArray( + [[nodiscard]] diagnostic_msgs::msg::DiagnosticArray create_diagnostics_array( const rclcpp::Time & publish_time_stamp) const; rclcpp::Clock::SharedPtr clock_; @@ -47,18 +47,18 @@ class DiagnosticsModule }; template -void DiagnosticsModule::addKeyValue(const std::string & key, const T & value) +void DiagnosticsModule::add_key_value(const std::string & key, const T & value) { diagnostic_msgs::msg::KeyValue key_value; key_value.key = key; key_value.value = std::to_string(value); - addKeyValue(key_value); + add_key_value(key_value); } template <> -void DiagnosticsModule::addKeyValue(const std::string & key, const std::string & value); +void DiagnosticsModule::add_key_value(const std::string & key, const std::string & value); template <> -void DiagnosticsModule::addKeyValue(const std::string & key, const bool & value); +void DiagnosticsModule::add_key_value(const std::string & key, const bool & value); } // namespace autoware::gyro_odometer 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 3b2da504f938a..f85640ab2c523 100644 --- a/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp +++ b/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp @@ -47,14 +47,13 @@ class GyroOdometerNode : public rclcpp::Node public: explicit GyroOdometerNode(const rclcpp::NodeOptions & node_options); - ~GyroOdometerNode(); private: - void callbackVehicleTwist( + void callback_vehicle_twist( const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr vehicle_twist_msg_ptr); - void callbackImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr); - void concatGyroAndOdometer(); - void publishData(const geometry_msgs::msg::TwistWithCovarianceStamped & twist_with_cov_raw); + void callback_imu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr); + void concat_gyro_and_odometer(); + void publish_data(const geometry_msgs::msg::TwistWithCovarianceStamped & twist_with_cov_raw); rclcpp::Subscription::SharedPtr vehicle_twist_sub_; diff --git a/localization/gyro_odometer/src/diagnostics_module.cpp b/localization/gyro_odometer/src/diagnostics_module.cpp index 9d88d8e6833ed..5d687943cef53 100644 --- a/localization/gyro_odometer/src/diagnostics_module.cpp +++ b/localization/gyro_odometer/src/diagnostics_module.cpp @@ -44,7 +44,7 @@ void DiagnosticsModule::clear() diagnostics_status_msg_.message = ""; } -void DiagnosticsModule::addKeyValue(const diagnostic_msgs::msg::KeyValue & key_value_msg) +void DiagnosticsModule::add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg) { auto it = std::find_if( std::begin(diagnostics_status_msg_.values), std::end(diagnostics_status_msg_.values), @@ -58,24 +58,24 @@ void DiagnosticsModule::addKeyValue(const diagnostic_msgs::msg::KeyValue & key_v } template <> -void DiagnosticsModule::addKeyValue(const std::string & key, const std::string & value) +void DiagnosticsModule::add_key_value(const std::string & key, const std::string & value) { diagnostic_msgs::msg::KeyValue key_value; key_value.key = key; key_value.value = value; - addKeyValue(key_value); + add_key_value(key_value); } template <> -void DiagnosticsModule::addKeyValue(const std::string & key, const bool & value) +void DiagnosticsModule::add_key_value(const std::string & key, const bool & value) { diagnostic_msgs::msg::KeyValue key_value; key_value.key = key; key_value.value = value ? "True" : "False"; - addKeyValue(key_value); + add_key_value(key_value); } -void DiagnosticsModule::updateLevelAndMessage(const int8_t level, const std::string & message) +void DiagnosticsModule::update_level_and_message(const int8_t level, const std::string & message) { if ((level > diagnostic_msgs::msg::DiagnosticStatus::OK)) { if (!diagnostics_status_msg_.message.empty()) { @@ -90,10 +90,10 @@ void DiagnosticsModule::updateLevelAndMessage(const int8_t level, const std::str void DiagnosticsModule::publish(const rclcpp::Time & publish_time_stamp) { - diagnostics_pub_->publish(createDiagnosticsArray(publish_time_stamp)); + diagnostics_pub_->publish(create_diagnostics_array(publish_time_stamp)); } -diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::createDiagnosticsArray( +diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::create_diagnostics_array( const rclcpp::Time & publish_time_stamp) const { diagnostic_msgs::msg::DiagnosticArray diagnostics_msg; diff --git a/localization/gyro_odometer/src/gyro_odometer_core.cpp b/localization/gyro_odometer/src/gyro_odometer_core.cpp index 1852d70bced71..0ec479770740f 100644 --- a/localization/gyro_odometer/src/gyro_odometer_core.cpp +++ b/localization/gyro_odometer/src/gyro_odometer_core.cpp @@ -31,13 +31,13 @@ namespace autoware::gyro_odometer { -std::array transformCovariance(const std::array & cov) +std::array transform_covariance(const std::array & cov) { using COV_IDX = tier4_autoware_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]}); - std::array cov_transformed; + std::array cov_transformed = {}; cov_transformed.fill(0.); cov_transformed[COV_IDX::X_X] = max_cov; cov_transformed[COV_IDX::Y_Y] = max_cov; @@ -57,11 +57,11 @@ GyroOdometerNode::GyroOdometerNode(const rclcpp::NodeOptions & node_options) vehicle_twist_sub_ = create_subscription( "vehicle/twist_with_covariance", rclcpp::QoS{100}, - std::bind(&GyroOdometerNode::callbackVehicleTwist, this, std::placeholders::_1)); + std::bind(&GyroOdometerNode::callback_vehicle_twist, this, std::placeholders::_1)); imu_sub_ = create_subscription( "imu", rclcpp::QoS{100}, - std::bind(&GyroOdometerNode::callbackImu, this, std::placeholders::_1)); + std::bind(&GyroOdometerNode::callback_imu, this, std::placeholders::_1)); twist_raw_pub_ = create_publisher("twist_raw", rclcpp::QoS{10}); twist_with_covariance_raw_pub_ = create_publisher( @@ -76,49 +76,46 @@ GyroOdometerNode::GyroOdometerNode(const rclcpp::NodeOptions & node_options) // TODO(YamatoAndo) createTimer } -GyroOdometerNode::~GyroOdometerNode() -{ -} - -void GyroOdometerNode::callbackVehicleTwist( - const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr vehicle_twist_ptr) +void GyroOdometerNode::callback_vehicle_twist( + const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr vehicle_twist_msg_ptr) { diagnostics_->clear(); - diagnostics_->addKeyValue( - "topic_time_stamp", static_cast(vehicle_twist_ptr->header.stamp).nanoseconds()); + diagnostics_->add_key_value( + "topic_time_stamp", + static_cast(vehicle_twist_msg_ptr->header.stamp).nanoseconds()); vehicle_twist_arrived_ = true; - latest_vehicle_twist_ros_time_ = vehicle_twist_ptr->header.stamp; - vehicle_twist_queue_.push_back(*vehicle_twist_ptr); - concatGyroAndOdometer(); + latest_vehicle_twist_ros_time_ = vehicle_twist_msg_ptr->header.stamp; + vehicle_twist_queue_.push_back(*vehicle_twist_msg_ptr); + concat_gyro_and_odometer(); - diagnostics_->publish(vehicle_twist_ptr->header.stamp); + diagnostics_->publish(vehicle_twist_msg_ptr->header.stamp); } -void GyroOdometerNode::callbackImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr) +void GyroOdometerNode::callback_imu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr) { diagnostics_->clear(); - diagnostics_->addKeyValue( + diagnostics_->add_key_value( "topic_time_stamp", static_cast(imu_msg_ptr->header.stamp).nanoseconds()); imu_arrived_ = true; latest_imu_ros_time_ = imu_msg_ptr->header.stamp; gyro_queue_.push_back(*imu_msg_ptr); - concatGyroAndOdometer(); + concat_gyro_and_odometer(); diagnostics_->publish(imu_msg_ptr->header.stamp); } -void GyroOdometerNode::concatGyroAndOdometer() +void GyroOdometerNode::concat_gyro_and_odometer() { // check arrive first topic - diagnostics_->addKeyValue("is_arrived_first_vehicle_twist", vehicle_twist_arrived_); - diagnostics_->addKeyValue("is_arrived_first_imu", imu_arrived_); + diagnostics_->add_key_value("is_arrived_first_vehicle_twist", vehicle_twist_arrived_); + diagnostics_->add_key_value("is_arrived_first_imu", imu_arrived_); if (!vehicle_twist_arrived_) { std::stringstream message; message << "Twist msg is not subscribed"; RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); - diagnostics_->updateLevelAndMessage( + diagnostics_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); vehicle_twist_queue_.clear(); @@ -129,7 +126,7 @@ void GyroOdometerNode::concatGyroAndOdometer() std::stringstream message; message << "Imu msg is not subscribed"; RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); - diagnostics_->updateLevelAndMessage( + diagnostics_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); vehicle_twist_queue_.clear(); @@ -141,14 +138,14 @@ void GyroOdometerNode::concatGyroAndOdometer() const double vehicle_twist_dt = std::abs((this->now() - latest_vehicle_twist_ros_time_).seconds()); const double imu_dt = std::abs((this->now() - latest_imu_ros_time_).seconds()); - diagnostics_->addKeyValue("vehicle_twist_time_stamp_dt", vehicle_twist_dt); - diagnostics_->addKeyValue("imu_time_stamp_dt", imu_dt); + diagnostics_->add_key_value("vehicle_twist_time_stamp_dt", vehicle_twist_dt); + diagnostics_->add_key_value("imu_time_stamp_dt", imu_dt); if (vehicle_twist_dt > message_timeout_sec_) { const std::string message = fmt::format( "Vehicle twist msg is timeout. vehicle_twist_dt: {}[sec], tolerance {}[sec]", vehicle_twist_dt, message_timeout_sec_); RCLCPP_ERROR_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message); - diagnostics_->updateLevelAndMessage(diagnostic_msgs::msg::DiagnosticStatus::ERROR, message); + diagnostics_->update_level_and_message(diagnostic_msgs::msg::DiagnosticStatus::ERROR, message); vehicle_twist_queue_.clear(); gyro_queue_.clear(); @@ -158,7 +155,7 @@ void GyroOdometerNode::concatGyroAndOdometer() const std::string message = fmt::format( "Imu msg is timeout. imu_dt: {}[sec], tolerance {}[sec]", imu_dt, message_timeout_sec_); RCLCPP_ERROR_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message); - diagnostics_->updateLevelAndMessage(diagnostic_msgs::msg::DiagnosticStatus::ERROR, message); + diagnostics_->update_level_and_message(diagnostic_msgs::msg::DiagnosticStatus::ERROR, message); vehicle_twist_queue_.clear(); gyro_queue_.clear(); @@ -166,8 +163,8 @@ void GyroOdometerNode::concatGyroAndOdometer() } // check queue size - diagnostics_->addKeyValue("vehicle_twist_queue_size", vehicle_twist_queue_.size()); - diagnostics_->addKeyValue("imu_queue_size", gyro_queue_.size()); + diagnostics_->add_key_value("vehicle_twist_queue_size", vehicle_twist_queue_.size()); + diagnostics_->add_key_value("imu_queue_size", gyro_queue_.size()); if (vehicle_twist_queue_.empty()) { // not output error and clear queue return; @@ -182,13 +179,13 @@ void GyroOdometerNode::concatGyroAndOdometer() transform_listener_->getLatestTransform(gyro_queue_.front().header.frame_id, output_frame_); const bool is_succeed_transform_imu = (tf_imu2base_ptr != nullptr); - diagnostics_->addKeyValue("is_succeed_transform_imu", is_succeed_transform_imu); + diagnostics_->add_key_value("is_succeed_transform_imu", is_succeed_transform_imu); if (!is_succeed_transform_imu) { std::stringstream message; message << "Please publish TF " << output_frame_ << " to " << gyro_queue_.front().header.frame_id; RCLCPP_ERROR_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); - diagnostics_->updateLevelAndMessage( + diagnostics_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); vehicle_twist_queue_.clear(); @@ -208,7 +205,7 @@ void GyroOdometerNode::concatGyroAndOdometer() gyro.header.frame_id = output_frame_; gyro.angular_velocity = transformed_angular_velocity.vector; - gyro.angular_velocity_covariance = transformCovariance(gyro.angular_velocity_covariance); + gyro.angular_velocity_covariance = transform_covariance(gyro.angular_velocity_covariance); } using COV_IDX_XYZ = tier4_autoware_utils::xyz_covariance_index::XYZ_COV_IDX; @@ -223,8 +220,8 @@ void GyroOdometerNode::concatGyroAndOdometer() vx_mean += vehicle_twist.twist.twist.linear.x; vx_covariance_original += vehicle_twist.twist.covariance[0 * 6 + 0]; } - vx_mean /= vehicle_twist_queue_.size(); - vx_covariance_original /= vehicle_twist_queue_.size(); + vx_mean /= static_cast(vehicle_twist_queue_.size()); + vx_covariance_original /= static_cast(vehicle_twist_queue_.size()); for (const auto & gyro : gyro_queue_) { gyro_mean.x += gyro.angular_velocity.x; @@ -234,12 +231,12 @@ void GyroOdometerNode::concatGyroAndOdometer() gyro_covariance_original.y += gyro.angular_velocity_covariance[COV_IDX_XYZ::Y_Y]; gyro_covariance_original.z += gyro.angular_velocity_covariance[COV_IDX_XYZ::Z_Z]; } - gyro_mean.x /= gyro_queue_.size(); - gyro_mean.y /= gyro_queue_.size(); - gyro_mean.z /= gyro_queue_.size(); - gyro_covariance_original.x /= gyro_queue_.size(); - gyro_covariance_original.y /= gyro_queue_.size(); - gyro_covariance_original.z /= gyro_queue_.size(); + gyro_mean.x /= static_cast(gyro_queue_.size()); + gyro_mean.y /= static_cast(gyro_queue_.size()); + gyro_mean.z /= static_cast(gyro_queue_.size()); + gyro_covariance_original.x /= static_cast(gyro_queue_.size()); + gyro_covariance_original.y /= static_cast(gyro_queue_.size()); + gyro_covariance_original.z /= static_cast(gyro_queue_.size()); // concat geometry_msgs::msg::TwistWithCovarianceStamped twist_with_cov; @@ -257,23 +254,23 @@ void GyroOdometerNode::concatGyroAndOdometer() // From a statistical point of view, here we reduce the covariances according to the number of // observed data twist_with_cov.twist.covariance[COV_IDX_XYZRPY::X_X] = - vx_covariance_original / vehicle_twist_queue_.size(); + vx_covariance_original / static_cast(vehicle_twist_queue_.size()); twist_with_cov.twist.covariance[COV_IDX_XYZRPY::Y_Y] = 100000.0; twist_with_cov.twist.covariance[COV_IDX_XYZRPY::Z_Z] = 100000.0; twist_with_cov.twist.covariance[COV_IDX_XYZRPY::ROLL_ROLL] = - gyro_covariance_original.x / gyro_queue_.size(); + gyro_covariance_original.x / static_cast(gyro_queue_.size()); twist_with_cov.twist.covariance[COV_IDX_XYZRPY::PITCH_PITCH] = - gyro_covariance_original.y / gyro_queue_.size(); + gyro_covariance_original.y / static_cast(gyro_queue_.size()); twist_with_cov.twist.covariance[COV_IDX_XYZRPY::YAW_YAW] = - gyro_covariance_original.z / gyro_queue_.size(); + gyro_covariance_original.z / static_cast(gyro_queue_.size()); - publishData(twist_with_cov); + publish_data(twist_with_cov); vehicle_twist_queue_.clear(); gyro_queue_.clear(); } -void GyroOdometerNode::publishData( +void GyroOdometerNode::publish_data( const geometry_msgs::msg::TwistWithCovarianceStamped & twist_with_cov_raw) { geometry_msgs::msg::TwistStamped twist_raw; diff --git a/localization/gyro_odometer/test/test_gyro_odometer_helper.cpp b/localization/gyro_odometer/test/test_gyro_odometer_helper.cpp index 54e1d320319d3..f55278998f5f0 100644 --- a/localization/gyro_odometer/test/test_gyro_odometer_helper.cpp +++ b/localization/gyro_odometer/test/test_gyro_odometer_helper.cpp @@ -17,7 +17,7 @@ using geometry_msgs::msg::TwistWithCovarianceStamped; using sensor_msgs::msg::Imu; -Imu generateSampleImu() +Imu generate_sample_imu() { Imu imu; imu.header.frame_id = "base_link"; @@ -27,7 +27,7 @@ Imu generateSampleImu() return imu; } -TwistWithCovarianceStamped generateSampleVelocity() +TwistWithCovarianceStamped generate_sample_velocity() { TwistWithCovarianceStamped twist; twist.header.frame_id = "base_link"; @@ -35,7 +35,7 @@ TwistWithCovarianceStamped generateSampleVelocity() return twist; } -rclcpp::NodeOptions getNodeOptionsWithDefaultParams() +rclcpp::NodeOptions get_node_options_with_default_params() { rclcpp::NodeOptions node_options; diff --git a/localization/gyro_odometer/test/test_gyro_odometer_helper.hpp b/localization/gyro_odometer/test/test_gyro_odometer_helper.hpp index 6e3aff0b841a9..9da344e410e61 100644 --- a/localization/gyro_odometer/test/test_gyro_odometer_helper.hpp +++ b/localization/gyro_odometer/test/test_gyro_odometer_helper.hpp @@ -20,11 +20,8 @@ #include #include -using geometry_msgs::msg::TwistWithCovarianceStamped; -using sensor_msgs::msg::Imu; - -Imu generateSampleImu(); -TwistWithCovarianceStamped generateSampleVelocity(); -rclcpp::NodeOptions getNodeOptionsWithDefaultParams(); +sensor_msgs::msg::Imu generate_sample_imu(); +geometry_msgs::msg::TwistWithCovarianceStamped generate_sample_velocity(); +rclcpp::NodeOptions get_node_options_with_default_params(); #endif // TEST_GYRO_ODOMETER_HELPER_HPP_ diff --git a/localization/gyro_odometer/test/test_gyro_odometer_pubsub.cpp b/localization/gyro_odometer/test/test_gyro_odometer_pubsub.cpp index b7849ef03bfc5..fc331a638a1dd 100644 --- a/localization/gyro_odometer/test/test_gyro_odometer_pubsub.cpp +++ b/localization/gyro_odometer/test/test_gyro_odometer_pubsub.cpp @@ -50,19 +50,22 @@ class VelocityGenerator : public rclcpp::Node class GyroOdometerValidator : public rclcpp::Node { public: - GyroOdometerValidator() : Node("gyro_odometer_validator"), received_latest_twist_ptr(nullptr) - { - twist_sub = create_subscription( - "/twist_with_covariance", 1, [this](const TwistWithCovarianceStamped::ConstSharedPtr msg) { + GyroOdometerValidator() + : Node("gyro_odometer_validator"), + twist_sub(create_subscription( + "/twist_with_covariance", 1, + [this](const TwistWithCovarianceStamped::ConstSharedPtr msg) { received_latest_twist_ptr = msg; - }); + })), + received_latest_twist_ptr(nullptr) + { } rclcpp::Subscription::SharedPtr twist_sub; TwistWithCovarianceStamped::ConstSharedPtr received_latest_twist_ptr; }; -void spinSome(rclcpp::Node::SharedPtr node_ptr) +void wait_spin_some(rclcpp::Node::SharedPtr node_ptr) { for (int i = 0; i < 50; ++i) { rclcpp::spin_some(node_ptr); @@ -70,7 +73,7 @@ void spinSome(rclcpp::Node::SharedPtr node_ptr) } } -bool isTwistValid( +bool is_twist_valid( const TwistWithCovarianceStamped & twist, const TwistWithCovarianceStamped & twist_ground_truth) { if (twist.twist.twist.linear.x != twist_ground_truth.twist.twist.linear.x) { @@ -99,8 +102,8 @@ bool isTwistValid( // velocity data are provided TEST(GyroOdometer, TestGyroOdometerWithImuAndVelocity) { - Imu input_imu = generateSampleImu(); - TwistWithCovarianceStamped input_velocity = generateSampleVelocity(); + Imu input_imu = generate_sample_imu(); + TwistWithCovarianceStamped input_velocity = generate_sample_velocity(); TwistWithCovarianceStamped expected_output_twist; expected_output_twist.twist.twist.linear.x = input_velocity.twist.twist.linear.x; @@ -108,8 +111,8 @@ TEST(GyroOdometer, TestGyroOdometerWithImuAndVelocity) expected_output_twist.twist.twist.angular.y = input_imu.angular_velocity.y; expected_output_twist.twist.twist.angular.z = input_imu.angular_velocity.z; - auto gyro_odometer_node = - std::make_shared(getNodeOptionsWithDefaultParams()); + auto gyro_odometer_node = std::make_shared( + get_node_options_with_default_params()); auto imu_generator = std::make_shared(); auto velocity_generator = std::make_shared(); auto gyro_odometer_validator_node = std::make_shared(); @@ -120,13 +123,13 @@ TEST(GyroOdometer, TestGyroOdometerWithImuAndVelocity) velocity_generator->vehicle_velocity_pub->publish(input_velocity); // gyro_odometer receives IMU and velocity, and publishes the fused twist data. - spinSome(gyro_odometer_node); + wait_spin_some(gyro_odometer_node); // validator node receives the fused twist data and store in "received_latest_twist_ptr". - spinSome(gyro_odometer_validator_node); + wait_spin_some(gyro_odometer_validator_node); EXPECT_FALSE(gyro_odometer_validator_node->received_latest_twist_ptr == nullptr); - EXPECT_TRUE(isTwistValid( + EXPECT_TRUE(is_twist_valid( *(gyro_odometer_validator_node->received_latest_twist_ptr), expected_output_twist)); } @@ -134,20 +137,20 @@ TEST(GyroOdometer, TestGyroOdometerWithImuAndVelocity) // Verify that the gyro_odometer does NOT publish any outputs when only IMU is provided TEST(GyroOdometer, TestGyroOdometerImuOnly) { - Imu input_imu = generateSampleImu(); + Imu input_imu = generate_sample_imu(); - auto gyro_odometer_node = - std::make_shared(getNodeOptionsWithDefaultParams()); + auto gyro_odometer_node = std::make_shared( + get_node_options_with_default_params()); auto imu_generator = std::make_shared(); auto gyro_odometer_validator_node = std::make_shared(); imu_generator->imu_pub->publish(input_imu); // gyro_odometer receives IMU - spinSome(gyro_odometer_node); + wait_spin_some(gyro_odometer_node); // validator node waits for the output fused twist from gyro_odometer - spinSome(gyro_odometer_validator_node); + wait_spin_some(gyro_odometer_validator_node); EXPECT_TRUE(gyro_odometer_validator_node->received_latest_twist_ptr == nullptr); } From 565589c8757b09250b1c14276a8f725f312b94d9 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 7 Jun 2024 17:58:18 +0900 Subject: [PATCH 22/65] feat(obstacle_cruise)!: type specified stop deccel limit and enabling abandon to stop (#7121) * add abandon function Signed-off-by: Yuki Takagi --- .../config/obstacle_cruise_planner.param.yaml | 12 + .../common_structs.hpp | 8 +- .../include/obstacle_cruise_planner/node.hpp | 3 +- .../planner_interface.hpp | 84 ++++++- .../include/obstacle_cruise_planner/utils.hpp | 3 +- planning/obstacle_cruise_planner/src/node.cpp | 70 +++--- .../src/planner_interface.cpp | 216 +++++++++++------- .../obstacle_cruise_planner/src/utils.cpp | 19 +- 8 files changed, 271 insertions(+), 144 deletions(-) diff --git a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml index 08cee3d58152e..8b338e9d0cd9a 100644 --- a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml +++ b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml @@ -218,3 +218,15 @@ lpf_gain_slow_down_vel: 0.99 # low-pass filter gain for slow down velocity lpf_gain_lat_dist: 0.999 # low-pass filter gain for lateral distance from obstacle to ego's path lpf_gain_dist_to_slow_down: 0.7 # low-pass filter gain for distance to slow down start + stop: + type_specified_params: + labels: # For the listed types, the node try to read the following type specified values + - "default" + - "unknown" + # default: For the default type, which denotes the other types listed above, the following param is defined implicitly, and the other type-specified parameters are not defined. + # limit_min_acc: common_param.yaml/limit.min_acc + unknown: + limit_min_acc: -1.2 # overwrite the deceleration limit, in usually, common_param.yaml/limit.min_acc is referred. + sudden_object_acc_threshold: -1.1 # If a stop can be achieved by a deceleration smaller than this value, it is not considered as “sudden stop". + sudden_object_dist_threshold: 1000.0 # If a stop distance is longer than this value, it is not considered as “sudden stop". + abandon_to_stop: false # If true, the planner gives up to stop when it cannot avoid to run over while maintaining the deceleration limit. diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp index 052e7bb721592..34ae20980d3fd 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp @@ -113,14 +113,15 @@ struct StopObstacle : public TargetObstacleInterface { StopObstacle( const std::string & arg_uuid, const rclcpp::Time & arg_stamp, - const geometry_msgs::msg::Pose & arg_pose, const Shape & arg_shape, - const double arg_lon_velocity, const double arg_lat_velocity, + const ObjectClassification & object_classification, const geometry_msgs::msg::Pose & arg_pose, + const Shape & arg_shape, const double arg_lon_velocity, const double arg_lat_velocity, const geometry_msgs::msg::Point arg_collision_point, const double arg_dist_to_collide_on_decimated_traj) : TargetObstacleInterface(arg_uuid, arg_stamp, arg_pose, arg_lon_velocity, arg_lat_velocity), shape(arg_shape), collision_point(arg_collision_point), - dist_to_collide_on_decimated_traj(arg_dist_to_collide_on_decimated_traj) + dist_to_collide_on_decimated_traj(arg_dist_to_collide_on_decimated_traj), + classification(object_classification) { } Shape shape; @@ -129,6 +130,7 @@ struct StopObstacle : public TargetObstacleInterface // calculateMarginFromObstacleOnCurve() and should be removed as it can be // replaced by ”dist_to_collide_on_decimated_traj” double dist_to_collide_on_decimated_traj; + ObjectClassification classification; }; struct CruiseObstacle : public TargetObstacleInterface diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp index fd65446408db1..3aea741e3b2f4 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp @@ -272,8 +272,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node bool is_driving_forward_{true}; bool enable_slow_down_planning_{false}; - // previous closest obstacle - std::shared_ptr prev_closest_stop_obstacle_ptr_{nullptr}; + std::vector prev_closest_stop_obstacles_{}; std::unique_ptr logger_configure_; diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp index 416c36b116059..7a060657e16af 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp @@ -23,6 +23,8 @@ #include "tier4_autoware_utils/ros/update_param.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" +#include +#include #include #include #include @@ -42,7 +44,8 @@ class PlannerInterface vehicle_info_(vehicle_info), ego_nearest_param_(ego_nearest_param), debug_data_ptr_(debug_data_ptr), - slow_down_param_(SlowDownParam(node)) + slow_down_param_(SlowDownParam(node)), + stop_param_(StopParam(node, longitudinal_info)) { stop_reasons_pub_ = node.create_publisher("~/output/stop_reasons", 1); velocity_factors_pub_ = @@ -91,6 +94,7 @@ class PlannerInterface updateCommonParam(parameters); updateCruiseParam(parameters); slow_down_param_.onParam(parameters); + stop_param_.onParam(parameters, longitudinal_info_); } Float32MultiArrayStamped getStopPlanningDebugMessage(const rclcpp::Time & current_time) const @@ -333,6 +337,84 @@ class PlannerInterface double lpf_gain_dist_to_slow_down; }; SlowDownParam slow_down_param_; + struct StopParam + { + struct ObstacleSpecificParams + { + double limit_min_acc; + double sudden_object_acc_threshold; + double sudden_object_dist_threshold; + bool abandon_to_stop; + }; + const std::unordered_map types_maps = { + {ObjectClassification::UNKNOWN, "unknown"}, {ObjectClassification::CAR, "car"}, + {ObjectClassification::TRUCK, "truck"}, {ObjectClassification::BUS, "bus"}, + {ObjectClassification::TRAILER, "trailer"}, {ObjectClassification::MOTORCYCLE, "motorcycle"}, + {ObjectClassification::BICYCLE, "bicycle"}, {ObjectClassification::PEDESTRIAN, "pedestrian"}}; + std::unordered_map type_specified_param_list; + explicit StopParam(rclcpp::Node & node, const LongitudinalInfo & longitudinal_info) + { + const std::string param_prefix = "stop.type_specified_params."; + std::vector obstacle_labels{"default"}; + obstacle_labels = + node.declare_parameter>(param_prefix + "labels", obstacle_labels); + + for (const auto & type_str : obstacle_labels) { + if (type_str != "default") { + ObstacleSpecificParams param{ + node.declare_parameter(param_prefix + type_str + ".limit_min_acc"), + node.declare_parameter( + param_prefix + type_str + ".sudden_object_acc_threshold"), + node.declare_parameter( + param_prefix + type_str + ".sudden_object_dist_threshold"), + node.declare_parameter(param_prefix + type_str + ".abandon_to_stop")}; + + param.sudden_object_acc_threshold = + std::min(param.sudden_object_acc_threshold, longitudinal_info.limit_min_accel); + param.limit_min_acc = std::min(param.limit_min_acc, param.sudden_object_acc_threshold); + + type_specified_param_list.emplace(type_str, param); + } + } + } + void onParam( + const std::vector & parameters, const LongitudinalInfo & longitudinal_info) + { + const std::string param_prefix = "stop.type_specified_params."; + for (auto & [type_str, param] : type_specified_param_list) { + if (type_str == "default") { + continue; + } + tier4_autoware_utils::updateParam( + parameters, param_prefix + type_str + ".limit_min_acc", param.limit_min_acc); + tier4_autoware_utils::updateParam( + parameters, param_prefix + type_str + ".sudden_object_acc_threshold", + param.sudden_object_acc_threshold); + tier4_autoware_utils::updateParam( + parameters, param_prefix + type_str + ".sudden_object_dist_threshold", + param.sudden_object_dist_threshold); + tier4_autoware_utils::updateParam( + parameters, param_prefix + type_str + ".abandon_to_stop", param.abandon_to_stop); + + param.sudden_object_acc_threshold = + std::min(param.sudden_object_acc_threshold, longitudinal_info.limit_min_accel); + param.limit_min_acc = std::min(param.limit_min_acc, param.sudden_object_acc_threshold); + } + } + std::string getParamType(const ObjectClassification label) + { + const auto type_str = types_maps.at(label.label); + if (type_specified_param_list.count(type_str) == 0) { + return "default"; + } + return type_str; + } + ObstacleSpecificParams getParam(const ObjectClassification label) + { + return type_specified_param_list.at(getParamType(label)); + } + }; + StopParam stop_param_; double moving_object_speed_threshold; double moving_object_hysteresis_range; std::vector prev_slow_down_output_; diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/utils.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/utils.hpp index 3b4ab577c2988..48bab514cbf77 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/utils.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/utils.hpp @@ -36,8 +36,7 @@ PoseWithStamp getCurrentObjectPose( const PredictedObject & predicted_object, const rclcpp::Time & obj_base_time, const rclcpp::Time & current_time, const bool use_prediction); -std::optional getClosestStopObstacle( - const std::vector & stop_obstacles); +std::vector getClosestStopObstacles(const std::vector & stop_obstacles); template size_t getIndexWithLongitudinalOffset( diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index c5f0c73a13b78..41ae29b7d470f 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -1253,9 +1253,9 @@ std::optional ObstacleCruisePlannerNode::createStopObstacle( } const auto [tangent_vel, normal_vel] = projectObstacleVelocityToTrajectory(traj_points, obstacle); - return StopObstacle{ - obstacle.uuid, obstacle.stamp, obstacle.pose, obstacle.shape, - tangent_vel, normal_vel, collision_point->first, collision_point->second}; + return StopObstacle{obstacle.uuid, obstacle.stamp, obstacle.classification, + obstacle.pose, obstacle.shape, tangent_vel, + normal_vel, collision_point->first, collision_point->second}; } std::optional ObstacleCruisePlannerNode::createSlowDownObstacle( @@ -1386,50 +1386,36 @@ void ObstacleCruisePlannerNode::checkConsistency( const rclcpp::Time & current_time, const PredictedObjects & predicted_objects, std::vector & stop_obstacles) { - const auto current_closest_stop_obstacle = - obstacle_cruise_utils::getClosestStopObstacle(stop_obstacles); - - if (!prev_closest_stop_obstacle_ptr_) { - if (current_closest_stop_obstacle) { - prev_closest_stop_obstacle_ptr_ = - std::make_shared(*current_closest_stop_obstacle); + for (const auto & prev_closest_stop_obstacle : prev_closest_stop_obstacles_) { + const auto predicted_object_itr = std::find_if( + predicted_objects.objects.begin(), predicted_objects.objects.end(), + [&prev_closest_stop_obstacle](const PredictedObject & po) { + return tier4_autoware_utils::toHexString(po.object_id) == prev_closest_stop_obstacle.uuid; + }); + // If previous closest obstacle disappear from the perception result, do nothing anymore. + if (predicted_object_itr == predicted_objects.objects.end()) { + continue; } - return; - } - const auto predicted_object_itr = std::find_if( - predicted_objects.objects.begin(), predicted_objects.objects.end(), - [&](PredictedObject predicted_object) { - return tier4_autoware_utils::toHexString(predicted_object.object_id) == - prev_closest_stop_obstacle_ptr_->uuid; - }); - // If previous closest obstacle disappear from the perception result, do nothing anymore. - if (predicted_object_itr == predicted_objects.objects.end()) { - return; - } - - const auto is_disappeared_from_stop_obstacle = std::none_of( - stop_obstacles.begin(), stop_obstacles.end(), - [&](const auto & obstacle) { return obstacle.uuid == prev_closest_stop_obstacle_ptr_->uuid; }); - if (is_disappeared_from_stop_obstacle) { - // re-evaluate as a stop candidate, and overwrite the current decision if "maintain stop" - // condition is satisfied - const double elapsed_time = (current_time - prev_closest_stop_obstacle_ptr_->stamp).seconds(); - if ( - predicted_object_itr->kinematics.initial_twist_with_covariance.twist.linear.x < - behavior_determination_param_.obstacle_velocity_threshold_from_stop_to_cruise && - elapsed_time < behavior_determination_param_.stop_obstacle_hold_time_threshold) { - stop_obstacles.push_back(*prev_closest_stop_obstacle_ptr_); - return; + const auto is_disappeared_from_stop_obstacle = std::none_of( + stop_obstacles.begin(), stop_obstacles.end(), + [&prev_closest_stop_obstacle](const StopObstacle & so) { + return so.uuid == prev_closest_stop_obstacle.uuid; + }); + if (is_disappeared_from_stop_obstacle) { + // re-evaluate as a stop candidate, and overwrite the current decision if "maintain stop" + // condition is satisfied + const double elapsed_time = (current_time - prev_closest_stop_obstacle.stamp).seconds(); + if ( + predicted_object_itr->kinematics.initial_twist_with_covariance.twist.linear.x < + behavior_determination_param_.obstacle_velocity_threshold_from_stop_to_cruise && + elapsed_time < behavior_determination_param_.stop_obstacle_hold_time_threshold) { + stop_obstacles.push_back(prev_closest_stop_obstacle); + } } } - if (current_closest_stop_obstacle) { - prev_closest_stop_obstacle_ptr_ = - std::make_shared(*current_closest_stop_obstacle); - } else { - prev_closest_stop_obstacle_ptr_ = nullptr; - } + prev_closest_stop_obstacles_ = obstacle_cruise_utils::getClosestStopObstacles(stop_obstacles); } bool ObstacleCruisePlannerNode::isObstacleCrossing( diff --git a/planning/obstacle_cruise_planner/src/planner_interface.cpp b/planning/obstacle_cruise_planner/src/planner_interface.cpp index f7ce218cf3ccf..6e1de97378d16 100644 --- a/planning/obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/obstacle_cruise_planner/src/planner_interface.cpp @@ -259,129 +259,171 @@ std::vector PlannerInterface::generateStopTrajectory( rclcpp::get_logger("ObstacleCruisePlanner::PIDBasedPlanner"), enable_debug_info_, "stop planning"); - // Get Closest Stop Obstacle - const auto closest_stop_obstacle = obstacle_cruise_utils::getClosestStopObstacle(stop_obstacles); - if (!closest_stop_obstacle) { - // delete marker - const auto markers = - motion_utils::createDeletedStopVirtualWallMarker(planner_data.current_time, 0); - tier4_autoware_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); - - prev_stop_distance_info_ = std::nullopt; - return planner_data.traj_points; - } - - const auto ego_segment_idx = - ego_nearest_param_.findSegmentIndex(planner_data.traj_points, planner_data.ego_pose); - const double dist_to_collide_on_ref_traj = - motion_utils::calcSignedArcLength(planner_data.traj_points, 0, ego_segment_idx) + - closest_stop_obstacle->dist_to_collide_on_decimated_traj; - - const double margin_from_obstacle_considering_behavior_module = [&]() { - const double margin_from_obstacle = - calculateMarginFromObstacleOnCurve(planner_data, *closest_stop_obstacle); - // Use terminal margin (terminal_safe_distance_margin) for obstacle stop - const auto ref_traj_length = motion_utils::calcSignedArcLength( - planner_data.traj_points, 0, planner_data.traj_points.size() - 1); - if (dist_to_collide_on_ref_traj > ref_traj_length) { - return longitudinal_info_.terminal_safe_distance_margin; - } - - // If behavior stop point is ahead of the closest_obstacle_stop point within a certain margin - // we set closest_obstacle_stop_distance to closest_behavior_stop_distance - const auto closest_behavior_stop_idx = - motion_utils::searchZeroVelocityIndex(planner_data.traj_points, ego_segment_idx + 1); - if (closest_behavior_stop_idx) { - const double closest_behavior_stop_dist_on_ref_traj = - motion_utils::calcSignedArcLength(planner_data.traj_points, 0, *closest_behavior_stop_idx); - const double stop_dist_diff = closest_behavior_stop_dist_on_ref_traj - - (dist_to_collide_on_ref_traj - margin_from_obstacle); - if (0.0 < stop_dist_diff && stop_dist_diff < margin_from_obstacle) { - return min_behavior_stop_margin_; + std::optional determined_stop_obstacle{}; + std::optional determined_zero_vel_dist{}; + std::optional determined_desired_margin{}; + + const auto closest_stop_obstacles = + obstacle_cruise_utils::getClosestStopObstacles(stop_obstacles); + for (const auto & stop_obstacle : closest_stop_obstacles) { + const auto ego_segment_idx = + ego_nearest_param_.findSegmentIndex(planner_data.traj_points, planner_data.ego_pose); + const double dist_to_collide_on_ref_traj = + motion_utils::calcSignedArcLength(planner_data.traj_points, 0, ego_segment_idx) + + 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 = 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; } - } - return margin_from_obstacle; - }(); - // Generate Output Trajectory - const auto [zero_vel_dist, will_collide_with_obstacle] = [&]() { - double candidate_zero_vel_dist = - std::max(0.0, dist_to_collide_on_ref_traj - margin_from_obstacle_considering_behavior_module); + // If behavior stop point is ahead of the closest_obstacle_stop point within a certain + // margin we set closest_obstacle_stop_distance to closest_behavior_stop_distance + const auto closest_behavior_stop_idx = + motion_utils::searchZeroVelocityIndex(planner_data.traj_points, ego_segment_idx + 1); + if (closest_behavior_stop_idx) { + const double closest_behavior_stop_dist_on_ref_traj = motion_utils::calcSignedArcLength( + planner_data.traj_points, 0, *closest_behavior_stop_idx); + const double stop_dist_diff = closest_behavior_stop_dist_on_ref_traj - + (dist_to_collide_on_ref_traj - margin_from_obstacle); + if (0.0 < stop_dist_diff && stop_dist_diff < margin_from_obstacle) { + return min_behavior_stop_margin_; + } + } + return margin_from_obstacle; + }(); - // Check feasibility to stop + // calc stop point against the obstacle + double candidate_zero_vel_dist = std::max(0.0, dist_to_collide_on_ref_traj - desired_margin); if (suppress_sudden_obstacle_stop_) { - // Calculate feasible stop margin (Check the feasibility) - const double feasible_stop_dist = - calcMinimumDistanceToStop( - planner_data.ego_vel, longitudinal_info_.limit_max_accel, - longitudinal_info_.limit_min_accel) + - motion_utils::calcSignedArcLength( - planner_data.traj_points, 0, planner_data.ego_pose.position); + const auto acceptable_stop_acc = [&]() -> std::optional { + if (stop_param_.getParamType(stop_obstacle.classification) == "default") { + return longitudinal_info_.limit_min_accel; + } + const double distance_to_judge_suddenness = std::min( + calcMinimumDistanceToStop( + planner_data.ego_vel, longitudinal_info_.limit_max_accel, + stop_param_.getParam(stop_obstacle.classification).sudden_object_acc_threshold), + stop_param_.getParam(stop_obstacle.classification).sudden_object_dist_threshold); + if (candidate_zero_vel_dist > distance_to_judge_suddenness) { + return longitudinal_info_.limit_min_accel; + } + if (stop_param_.getParam(stop_obstacle.classification).abandon_to_stop) { + RCLCPP_WARN( + rclcpp::get_logger("ObstacleCruisePlanner::StopPlanner"), + "[Cruise] abandon to stop against %s object", + stop_param_.types_maps.at(stop_obstacle.classification.label).c_str()); + return std::nullopt; + } else { + return stop_param_.getParam(stop_obstacle.classification).limit_min_acc; + } + }(); + if (!acceptable_stop_acc) { + continue; + } - if (candidate_zero_vel_dist < feasible_stop_dist) { - candidate_zero_vel_dist = feasible_stop_dist; - return std::make_pair(candidate_zero_vel_dist, true); + const double acceptable_stop_pos = + 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()); + if (acceptable_stop_pos > candidate_zero_vel_dist) { + candidate_zero_vel_dist = acceptable_stop_pos; } } - // Hold previous stop distance if necessary - if ( - std::abs(planner_data.ego_vel) < longitudinal_info_.hold_stop_velocity_threshold && - prev_stop_distance_info_) { - // NOTE: We assume that the current trajectory's front point is ahead of the previous - // trajectory's front point. - const size_t traj_front_point_prev_seg_idx = - motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - prev_stop_distance_info_->first, planner_data.traj_points.front().pose); - const double diff_dist_front_points = motion_utils::calcSignedArcLength( - prev_stop_distance_info_->first, 0, planner_data.traj_points.front().pose.position, - traj_front_point_prev_seg_idx); - - const double prev_zero_vel_dist = prev_stop_distance_info_->second - diff_dist_front_points; + if (determined_stop_obstacle) { + const bool is_same_param_types = + (stop_obstacle.classification.label == determined_stop_obstacle->classification.label); if ( - std::abs(prev_zero_vel_dist - candidate_zero_vel_dist) < - longitudinal_info_.hold_stop_distance_threshold) { - candidate_zero_vel_dist = prev_zero_vel_dist; + (is_same_param_types && stop_obstacle.dist_to_collide_on_decimated_traj > + determined_stop_obstacle->dist_to_collide_on_decimated_traj) || + (!is_same_param_types && candidate_zero_vel_dist > determined_zero_vel_dist)) { + continue; } } - return std::make_pair(candidate_zero_vel_dist, false); - }(); + determined_zero_vel_dist = candidate_zero_vel_dist; + determined_stop_obstacle = stop_obstacle; + determined_desired_margin = desired_margin; + } + + if (!determined_zero_vel_dist) { + // delete marker + const auto markers = + motion_utils::createDeletedStopVirtualWallMarker(planner_data.current_time, 0); + tier4_autoware_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); + + prev_stop_distance_info_ = std::nullopt; + return planner_data.traj_points; + } + + // Hold previous stop distance if necessary + if ( + std::abs(planner_data.ego_vel) < longitudinal_info_.hold_stop_velocity_threshold && + prev_stop_distance_info_) { + // NOTE: We assume that the current trajectory's front point is ahead of the previous + // trajectory's front point. + const size_t traj_front_point_prev_seg_idx = + motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + prev_stop_distance_info_->first, planner_data.traj_points.front().pose); + const double diff_dist_front_points = motion_utils::calcSignedArcLength( + prev_stop_distance_info_->first, 0, planner_data.traj_points.front().pose.position, + traj_front_point_prev_seg_idx); + + const double prev_zero_vel_dist = prev_stop_distance_info_->second - diff_dist_front_points; + if ( + std::abs(prev_zero_vel_dist - determined_zero_vel_dist.value()) < + longitudinal_info_.hold_stop_distance_threshold) { + determined_zero_vel_dist.value() = prev_zero_vel_dist; + } + } // Insert stop point auto output_traj_points = planner_data.traj_points; - const auto zero_vel_idx = motion_utils::insertStopPoint(0, zero_vel_dist, output_traj_points); + const auto zero_vel_idx = + motion_utils::insertStopPoint(0, *determined_zero_vel_dist, output_traj_points); if (zero_vel_idx) { // virtual wall marker for stop obstacle const auto markers = motion_utils::createStopVirtualWallMarker( output_traj_points.at(*zero_vel_idx).pose, "obstacle stop", planner_data.current_time, 0, abs_ego_offset, "", planner_data.is_driving_forward); tier4_autoware_utils::appendMarkerArray(markers, &debug_data_ptr_->stop_wall_marker); - debug_data_ptr_->obstacles_to_stop.push_back(*closest_stop_obstacle); + debug_data_ptr_->obstacles_to_stop.push_back(*determined_stop_obstacle); // Publish Stop Reason const auto stop_pose = output_traj_points.at(*zero_vel_idx).pose; const auto stop_reasons_msg = - makeStopReasonArray(planner_data, stop_pose, *closest_stop_obstacle); + makeStopReasonArray(planner_data, stop_pose, *determined_stop_obstacle); stop_reasons_pub_->publish(stop_reasons_msg); velocity_factors_pub_->publish(makeVelocityFactorArray(planner_data.current_time, stop_pose)); - // Publish if ego vehicle collides with the obstacle with a limit acceleration + // 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() > + 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; const auto stop_speed_exceeded_msg = - createStopSpeedExceededMsg(planner_data.current_time, will_collide_with_obstacle); + createStopSpeedExceededMsg(planner_data.current_time, will_over_run); stop_speed_exceeded_pub_->publish(stop_speed_exceeded_msg); - prev_stop_distance_info_ = std::make_pair(output_traj_points, zero_vel_dist); + prev_stop_distance_info_ = std::make_pair(output_traj_points, determined_zero_vel_dist.value()); } stop_planning_debug_info_.set( StopPlanningDebugInfo::TYPE::STOP_CURRENT_OBSTACLE_DISTANCE, - closest_stop_obstacle->dist_to_collide_on_decimated_traj); + determined_stop_obstacle->dist_to_collide_on_decimated_traj); stop_planning_debug_info_.set( - StopPlanningDebugInfo::TYPE::STOP_CURRENT_OBSTACLE_VELOCITY, closest_stop_obstacle->velocity); - + StopPlanningDebugInfo::TYPE::STOP_CURRENT_OBSTACLE_VELOCITY, + determined_stop_obstacle->velocity); stop_planning_debug_info_.set( - StopPlanningDebugInfo::TYPE::STOP_TARGET_OBSTACLE_DISTANCE, - margin_from_obstacle_considering_behavior_module); + StopPlanningDebugInfo::TYPE::STOP_TARGET_OBSTACLE_DISTANCE, determined_desired_margin.value()); stop_planning_debug_info_.set(StopPlanningDebugInfo::TYPE::STOP_TARGET_VELOCITY, 0.0); stop_planning_debug_info_.set(StopPlanningDebugInfo::TYPE::STOP_TARGET_ACCELERATION, 0.0); diff --git a/planning/obstacle_cruise_planner/src/utils.cpp b/planning/obstacle_cruise_planner/src/utils.cpp index 6b32ccafc7f42..6c1b3999e40c1 100644 --- a/planning/obstacle_cruise_planner/src/utils.cpp +++ b/planning/obstacle_cruise_planner/src/utils.cpp @@ -95,16 +95,21 @@ PoseWithStamp getCurrentObjectPose( return PoseWithStamp{obj_base_time, *interpolated_pose}; } -std::optional getClosestStopObstacle(const std::vector & stop_obstacles) +std::vector getClosestStopObstacles(const std::vector & stop_obstacles) { - std::optional candidate_obstacle = std::nullopt; + std::vector candidates{}; for (const auto & stop_obstacle : stop_obstacles) { - if ( - !candidate_obstacle || stop_obstacle.dist_to_collide_on_decimated_traj < - candidate_obstacle->dist_to_collide_on_decimated_traj) { - candidate_obstacle = stop_obstacle; + const auto itr = + std::find_if(candidates.begin(), candidates.end(), [&stop_obstacle](const StopObstacle & co) { + return co.classification.label == stop_obstacle.classification.label; + }); + if (itr == candidates.end()) { + candidates.emplace_back(stop_obstacle); + } else if ( + stop_obstacle.dist_to_collide_on_decimated_traj < itr->dist_to_collide_on_decimated_traj) { + *itr = stop_obstacle; } } - return candidate_obstacle; + return candidates; } } // namespace obstacle_cruise_utils From 457771919d907aebd1ffe66c4d6a8b3588b0b458 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 7 Jun 2024 18:23:21 +0900 Subject: [PATCH 23/65] fix(perception_online_evaluator): add metric_value not only stat (#7100)(#7118) (revert of revert) (#7167) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Revert "fix(perception_online_evaluator): revert "add metric_value not only s…" This reverts commit d827b1bd1f4bbacf0333eb14a62ef42e56caef25. * Update evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp * Update evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp * use emplace back Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> --- .../metrics/metric.hpp | 5 +++ .../metrics_calculator.hpp | 4 +- .../perception_online_evaluator_node.hpp | 2 + .../src/metrics_calculator.cpp | 16 ++++---- .../src/perception_online_evaluator_node.cpp | 39 +++++++++++++++---- .../test_perception_online_evaluator_node.cpp | 14 ++++++- 6 files changed, 61 insertions(+), 19 deletions(-) diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp index 926fbb7435f3a..eaa07f2317940 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp +++ b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp @@ -20,6 +20,7 @@ #include #include #include +#include #include namespace perception_diagnostics @@ -36,7 +37,11 @@ enum class Metric { SIZE, }; +// Each metric has a different return type. (statistic or just a one value etc). +// To handle them all in the MetricsCalculator::calculate function, define MetricsMap as a variant using MetricStatMap = std::unordered_map>; +using MetricValueMap = std::unordered_map; +using MetricsMap = std::variant; struct PredictedPathDeviationMetrics { diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp index ec435b0a5e17f..a9b1388281ce8 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp +++ b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp @@ -96,7 +96,7 @@ class MetricsCalculator * @param [in] metric Metric enum value * @return map of string describing the requested metric and the calculated value */ - std::optional calculate(const Metric & metric) const; + std::optional calculate(const Metric & metric) const; /** * @brief set the dynamic objects used to calculate obstacle metrics @@ -143,7 +143,7 @@ class MetricsCalculator PredictedPathDeviationMetrics calcPredictedPathDeviationMetrics( const PredictedObjects & objects, const double time_horizon) const; MetricStatMap calcYawRateMetrics(const ClassObjectsMap & class_objects_map) const; - MetricStatMap calcObjectsCountMetrics() const; + MetricValueMap calcObjectsCountMetrics() const; bool hasPassedTime(const rclcpp::Time stamp) const; bool hasPassedTime(const std::string uuid, const rclcpp::Time stamp) const; diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp index daaea56178873..1bc427e667a2a 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp +++ b/evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp @@ -61,6 +61,8 @@ class PerceptionOnlineEvaluatorNode : public rclcpp::Node DiagnosticStatus generateDiagnosticStatus( const std::string metric, const Stat & metric_stat) const; + DiagnosticStatus generateDiagnosticStatus( + const std::string & metric, const double metric_value) const; private: // Subscribers and publishers diff --git a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp index 9c1e0667e4fef..cc455445ca9f8 100644 --- a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp +++ b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp @@ -26,7 +26,7 @@ namespace perception_diagnostics using object_recognition_utils::convertLabelToString; using tier4_autoware_utils::inverseTransformPoint; -std::optional MetricsCalculator::calculate(const Metric & metric) const +std::optional MetricsCalculator::calculate(const Metric & metric) const { // clang-format off const bool use_past_objects = metric == Metric::lateral_deviation || @@ -455,15 +455,14 @@ MetricStatMap MetricsCalculator::calcYawRateMetrics(const ClassObjectsMap & clas return metric_stat_map; } -MetricStatMap MetricsCalculator::calcObjectsCountMetrics() const +MetricValueMap MetricsCalculator::calcObjectsCountMetrics() const { - MetricStatMap metric_stat_map; + MetricValueMap metric_stat_map; // calculate the average number of objects in the detection area in all past frames const auto overall_average_count = detection_counter_.getOverallAverageCount(); for (const auto & [label, range_and_count] : overall_average_count) { for (const auto & [range, count] : range_and_count) { - metric_stat_map["average_objects_count_" + convertLabelToString(label) + "_" + range].add( - count); + metric_stat_map["average_objects_count_" + convertLabelToString(label) + "_" + range] = count; } } // calculate the average number of objects in the detection area in the past @@ -472,8 +471,8 @@ MetricStatMap MetricsCalculator::calcObjectsCountMetrics() const detection_counter_.getAverageCount(parameters_->objects_count_window_seconds); for (const auto & [label, range_and_count] : average_count) { for (const auto & [range, count] : range_and_count) { - metric_stat_map["interval_average_objects_count_" + convertLabelToString(label) + "_" + range] - .add(count); + metric_stat_map + ["interval_average_objects_count_" + convertLabelToString(label) + "_" + range] = count; } } @@ -481,8 +480,7 @@ MetricStatMap MetricsCalculator::calcObjectsCountMetrics() const const auto total_count = detection_counter_.getTotalCount(); for (const auto & [label, range_and_count] : total_count) { for (const auto & [range, count] : range_and_count) { - metric_stat_map["total_objects_count_" + convertLabelToString(label) + "_" + range].add( - count); + metric_stat_map["total_objects_count_" + convertLabelToString(label) + "_" + range] = count; } } 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 0fcdd77f4d515..2933afdab3d08 100644 --- a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp @@ -69,16 +69,25 @@ void PerceptionOnlineEvaluatorNode::publishMetrics() // calculate metrics for (const Metric & metric : parameters_->metrics) { - const auto metric_stat_map = metrics_calculator_.calculate(Metric(metric)); - if (!metric_stat_map.has_value()) { + const auto metric_result = metrics_calculator_.calculate(Metric(metric)); + if (!metric_result.has_value()) { continue; } - for (const auto & [metric, stat] : metric_stat_map.value()) { - if (stat.count() > 0) { - metrics_msg.status.push_back(generateDiagnosticStatus(metric, stat)); - } - } + std::visit( + [&metrics_msg, this](auto && arg) { + using T = std::decay_t; + for (const auto & [metric, value] : arg) { + if constexpr (std::is_same_v) { + if (value.count() > 0) { + metrics_msg.status.emplace_back(generateDiagnosticStatus(metric, value)); + } + } else if constexpr (std::is_same_v) { + metrics_msg.status.emplace_back(generateDiagnosticStatus(metric, value)); + } + } + }, + metric_result.value()); } // publish metrics @@ -111,6 +120,22 @@ DiagnosticStatus PerceptionOnlineEvaluatorNode::generateDiagnosticStatus( return status; } +DiagnosticStatus PerceptionOnlineEvaluatorNode::generateDiagnosticStatus( + const std::string & metric, const double value) const +{ + DiagnosticStatus status; + + status.level = status.OK; + status.name = metric; + + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = "metric_value"; + key_value.value = std::to_string(value); + status.values.push_back(key_value); + + return status; +} + void PerceptionOnlineEvaluatorNode::onObjects(const PredictedObjects::ConstSharedPtr objects_msg) { metrics_calculator_.setPredictedObjects(*objects_msg, *tf_buffer_); 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 a408821466fb9..3db487f3167ae 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 @@ -141,7 +141,19 @@ class EvalTest : public ::testing::Test [=](const DiagnosticArray::ConstSharedPtr msg) { const auto it = std::find_if(msg->status.begin(), msg->status.end(), is_target_metric); if (it != msg->status.end()) { - metric_value_ = boost::lexical_cast(it->values[2].value); + const auto mean_it = std::find_if( + it->values.begin(), it->values.end(), + [](const auto & key_value) { return key_value.key == "mean"; }); + if (mean_it != it->values.end()) { + metric_value_ = boost::lexical_cast(mean_it->value); + } else { + const auto metric_value_it = std::find_if( + it->values.begin(), it->values.end(), + [](const auto & key_value) { return key_value.key == "metric_value"; }); + if (metric_value_it != it->values.end()) { + metric_value_ = boost::lexical_cast(metric_value_it->value); + } + } metric_updated_ = true; } }); From 2f6cd2b322bed1f431ccac0c7edd43a1ee0ca170 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 7 Jun 2024 19:17:34 +0900 Subject: [PATCH 24/65] chore(lane_departure_checker): add maintainer (#7366) add maintainer Signed-off-by: Zulfaqar Azmi --- control/lane_departure_checker/package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/control/lane_departure_checker/package.xml b/control/lane_departure_checker/package.xml index 73955613d21a9..3b1c1c6f6d54b 100644 --- a/control/lane_departure_checker/package.xml +++ b/control/lane_departure_checker/package.xml @@ -6,6 +6,8 @@ The lane_departure_checker package Kyoichi Sugahara Makoto Kurihara + Zulfaqar Azmi + Apache License 2.0 ament_cmake_auto From f03323f59a5e52c349b6bd4d63b75b086a94fbfb Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Fri, 7 Jun 2024 19:35:15 +0900 Subject: [PATCH 25/65] refactor(lane_departure_checker)!: prefix package and namespace with autoware (#7325) * add prefix autoware_ to lane_departure_checker package Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .github/CODEOWNERS | 2 +- control/lane_departure_checker/CMakeLists.txt | 8 ++++---- .../lane_departure_checker.hpp | 10 +++++----- .../lane_departure_checker_node.hpp | 12 ++++++------ .../util/create_vehicle_footprint.hpp | 6 +++--- .../launch/lane_departure_checker.launch.xml | 4 ++-- control/lane_departure_checker/package.xml | 4 ++-- .../lane_departure_checker.cpp | 8 ++++---- .../lane_departure_checker_node.cpp | 8 ++++---- .../tier4_control_launch/control_launch.drawio.svg | 6 +++--- launch/tier4_control_launch/launch/control.launch.py | 4 ++-- launch/tier4_control_launch/package.xml | 2 +- .../parking_departure/geometric_parallel_parking.hpp | 8 +++++--- .../package.xml | 2 +- .../parking_departure/geometric_parallel_parking.cpp | 6 ++++-- .../geometric_pull_out.hpp | 7 ++++--- .../shift_pull_out.hpp | 4 ++-- .../start_planner_module.hpp | 4 ++-- .../src/geometric_pull_out.cpp | 3 ++- .../src/start_planner_module.cpp | 2 +- .../geometric_pull_over.hpp | 4 ++-- .../goal_planner_module.hpp | 4 ++-- .../shift_pull_over.hpp | 4 ++-- .../behavior_path_goal_planner_module/util.hpp | 2 +- .../src/goal_searcher.cpp | 2 +- planning/behavior_path_planner/package.xml | 2 +- 26 files changed, 67 insertions(+), 61 deletions(-) rename control/lane_departure_checker/include/{lane_departure_checker => autoware_lane_departure_checker}/lane_departure_checker.hpp (95%) rename control/lane_departure_checker/include/{lane_departure_checker => autoware_lane_departure_checker}/lane_departure_checker_node.hpp (93%) rename control/lane_departure_checker/include/{lane_departure_checker => autoware_lane_departure_checker}/util/create_vehicle_footprint.hpp (91%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 2eefee5606ab2..c0eb60e5a1316 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -49,7 +49,7 @@ control/control_performance_analysis/** berkay@leodrive.ai fumiya.watanabe@tier4 control/control_validator/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/external_cmd_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/joy_controller/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -control/lane_departure_checker/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp +control/autoware_lane_departure_checker/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp control/mpc_lateral_controller/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/obstacle_collision_checker/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/operation_mode_transition_manager/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp diff --git a/control/lane_departure_checker/CMakeLists.txt b/control/lane_departure_checker/CMakeLists.txt index 874670c478240..d545e1cbb5ad1 100644 --- a/control/lane_departure_checker/CMakeLists.txt +++ b/control/lane_departure_checker/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(lane_departure_checker) +project(autoware_lane_departure_checker) find_package(autoware_cmake REQUIRED) autoware_package() @@ -10,13 +10,13 @@ include_directories( ${EIGEN3_INCLUDE_DIRS} ) -ament_auto_add_library(lane_departure_checker SHARED +ament_auto_add_library(autoware_lane_departure_checker SHARED src/lane_departure_checker_node/lane_departure_checker.cpp src/lane_departure_checker_node/lane_departure_checker_node.cpp ) -rclcpp_components_register_node(lane_departure_checker - PLUGIN "lane_departure_checker::LaneDepartureCheckerNode" +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::lane_departure_checker::LaneDepartureCheckerNode" EXECUTABLE lane_departure_checker_node ) diff --git a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp b/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker.hpp similarity index 95% rename from control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp rename to control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker.hpp index 967cb65c8efa8..d90dbc9474fd8 100644 --- a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp +++ b/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_ -#define LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_ +#ifndef AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_ +#define AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_ #include #include @@ -45,7 +45,7 @@ #include #include -namespace lane_departure_checker +namespace autoware::lane_departure_checker { using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::Trajectory; @@ -170,6 +170,6 @@ class LaneDepartureChecker const std::vector & vehicle_footprints, const SegmentRtree & uncrossable_segments); }; -} // namespace lane_departure_checker +} // namespace autoware::lane_departure_checker -#endif // LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_ +#endif // AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_ diff --git a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker_node.hpp b/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker_node.hpp similarity index 93% rename from control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker_node.hpp rename to control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker_node.hpp index 0f0e15d0a4f62..be7126944f767 100644 --- a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker_node.hpp +++ b/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker_node.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_NODE_HPP_ -#define LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_NODE_HPP_ +#ifndef AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_NODE_HPP_ +#define AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_NODE_HPP_ -#include "lane_departure_checker/lane_departure_checker.hpp" +#include "autoware_lane_departure_checker/lane_departure_checker.hpp" #include #include @@ -40,7 +40,7 @@ #include #include -namespace lane_departure_checker +namespace autoware::lane_departure_checker { using autoware_map_msgs::msg::LaneletMapBin; @@ -149,6 +149,6 @@ class LaneDepartureCheckerNode : public rclcpp::Node lanelet::Lanelets getRightOppositeLanelets(const lanelet::ConstLanelet & lanelet); }; -} // namespace lane_departure_checker +} // namespace autoware::lane_departure_checker -#endif // LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_NODE_HPP_ +#endif // AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_NODE_HPP_ diff --git a/control/lane_departure_checker/include/lane_departure_checker/util/create_vehicle_footprint.hpp b/control/lane_departure_checker/include/autoware_lane_departure_checker/util/create_vehicle_footprint.hpp similarity index 91% rename from control/lane_departure_checker/include/lane_departure_checker/util/create_vehicle_footprint.hpp rename to control/lane_departure_checker/include/autoware_lane_departure_checker/util/create_vehicle_footprint.hpp index edc62cd6659fd..917317361d702 100644 --- a/control/lane_departure_checker/include/lane_departure_checker/util/create_vehicle_footprint.hpp +++ b/control/lane_departure_checker/include/autoware_lane_departure_checker/util/create_vehicle_footprint.hpp @@ -25,8 +25,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LANE_DEPARTURE_CHECKER__UTIL__CREATE_VEHICLE_FOOTPRINT_HPP_ -#define LANE_DEPARTURE_CHECKER__UTIL__CREATE_VEHICLE_FOOTPRINT_HPP_ +#ifndef AUTOWARE_LANE_DEPARTURE_CHECKER__UTIL__CREATE_VEHICLE_FOOTPRINT_HPP_ +#define AUTOWARE_LANE_DEPARTURE_CHECKER__UTIL__CREATE_VEHICLE_FOOTPRINT_HPP_ #include #include @@ -63,4 +63,4 @@ inline FootprintMargin calcFootprintMargin( return FootprintMargin{Cov_xy_vehicle(0, 0) * scale, Cov_xy_vehicle(1, 1) * scale}; } -#endif // LANE_DEPARTURE_CHECKER__UTIL__CREATE_VEHICLE_FOOTPRINT_HPP_ +#endif // AUTOWARE_LANE_DEPARTURE_CHECKER__UTIL__CREATE_VEHICLE_FOOTPRINT_HPP_ diff --git a/control/lane_departure_checker/launch/lane_departure_checker.launch.xml b/control/lane_departure_checker/launch/lane_departure_checker.launch.xml index 62799c1187651..7ea2e8b2de60a 100644 --- a/control/lane_departure_checker/launch/lane_departure_checker.launch.xml +++ b/control/lane_departure_checker/launch/lane_departure_checker.launch.xml @@ -4,12 +4,12 @@ - + - + diff --git a/control/lane_departure_checker/package.xml b/control/lane_departure_checker/package.xml index 3b1c1c6f6d54b..466dc7351cd9e 100644 --- a/control/lane_departure_checker/package.xml +++ b/control/lane_departure_checker/package.xml @@ -1,9 +1,9 @@ - lane_departure_checker + autoware_lane_departure_checker 0.1.0 - The lane_departure_checker package + The autoware_lane_departure_checker package Kyoichi Sugahara Makoto Kurihara Zulfaqar Azmi diff --git a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp index eb5d674705aaa..5e90df6773b87 100644 --- a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp +++ b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "lane_departure_checker/lane_departure_checker.hpp" +#include "autoware_lane_departure_checker/lane_departure_checker.hpp" -#include "lane_departure_checker/util/create_vehicle_footprint.hpp" +#include "autoware_lane_departure_checker/util/create_vehicle_footprint.hpp" #include #include @@ -96,7 +96,7 @@ lanelet::ConstLanelets getCandidateLanelets( } // namespace -namespace lane_departure_checker +namespace autoware::lane_departure_checker { Output LaneDepartureChecker::update(const Input & input) { @@ -460,4 +460,4 @@ bool LaneDepartureChecker::willCrossBoundary( return false; } -} // namespace lane_departure_checker +} // namespace autoware::lane_departure_checker diff --git a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index c3fd1d314e371..2b919f89e6e95 100644 --- a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "lane_departure_checker/lane_departure_checker_node.hpp" +#include "autoware_lane_departure_checker/lane_departure_checker_node.hpp" #include #include @@ -120,7 +120,7 @@ void update_param( } // namespace -namespace lane_departure_checker +namespace autoware::lane_departure_checker { LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & options) : Node("lane_departure_checker_node", options) @@ -759,7 +759,7 @@ lanelet::Lanelets LaneDepartureCheckerNode::getRightOppositeLanelets( return opposite_lanelets; } -} // namespace lane_departure_checker +} // namespace autoware::lane_departure_checker #include -RCLCPP_COMPONENTS_REGISTER_NODE(lane_departure_checker::LaneDepartureCheckerNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::lane_departure_checker::LaneDepartureCheckerNode) diff --git a/launch/tier4_control_launch/control_launch.drawio.svg b/launch/tier4_control_launch/control_launch.drawio.svg index 5d13b84a0b34b..21d97ba08c0b3 100644 --- a/launch/tier4_control_launch/control_launch.drawio.svg +++ b/launch/tier4_control_launch/control_launch.drawio.svg @@ -259,17 +259,17 @@ >
- lane_departure_checker_node + autoware_lane_departure_checker_node

- package: lane_departure_checker_node + package: autoware_lane_departure_checker_node
- lane_departure_checker_node... + autoware_lane_departure_checker_node... diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index 77140b0e0f630..239a65f8260bf 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -102,8 +102,8 @@ def launch_setup(context, *args, **kwargs): # lane departure checker lane_departure_component = ComposableNode( - package="lane_departure_checker", - plugin="lane_departure_checker::LaneDepartureCheckerNode", + package="autoware_lane_departure_checker", + plugin="autoware::lane_departure_checker::LaneDepartureCheckerNode", name="lane_departure_checker_node", namespace="trajectory_follower", remappings=[ diff --git a/launch/tier4_control_launch/package.xml b/launch/tier4_control_launch/package.xml index 801fa274dd086..fda612f05436c 100644 --- a/launch/tier4_control_launch/package.xml +++ b/launch/tier4_control_launch/package.xml @@ -11,10 +11,10 @@ ament_cmake_auto autoware_cmake + autoware_lane_departure_checker control_evaluator external_cmd_converter external_cmd_selector - lane_departure_checker shift_decider trajectory_follower_node vehicle_cmd_gate diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp index 867e76f0db614..fe8dc4c25869a 100644 --- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp +++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp @@ -18,7 +18,7 @@ #include "autoware_behavior_path_planner_common/data_manager.hpp" #include "autoware_behavior_path_planner_common/parameters.hpp" -#include +#include #include #include @@ -75,7 +75,8 @@ class GeometricParallelParking bool planPullOut( const Pose & start_pose, const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes, const bool left_side_start, - const std::shared_ptr lane_departure_checker); + const std::shared_ptr + autoware_lane_departure_checker); void setParameters(const ParallelParkingParameters & parameters) { parameters_ = parameters; } void setPlannerData(const std::shared_ptr & planner_data) { @@ -119,7 +120,8 @@ class GeometricParallelParking const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes, const bool is_forward, const bool left_side_parking, const double end_pose_offset, const double lane_departure_margin, const double arc_path_interval, - const std::shared_ptr lane_departure_checker); + const std::shared_ptr + autoware_lane_departure_checker); PathWithLaneId generateArcPath( const Pose & center, const double radius, const double start_yaw, double end_yaw, const double arc_path_interval, const bool is_left_turn, const bool is_forward); diff --git a/planning/autoware_behavior_path_planner_common/package.xml b/planning/autoware_behavior_path_planner_common/package.xml index 21da8dcef1c2d..24d369e475e61 100644 --- a/planning/autoware_behavior_path_planner_common/package.xml +++ b/planning/autoware_behavior_path_planner_common/package.xml @@ -43,12 +43,12 @@ autoware_cmake autoware_adapi_v1_msgs + autoware_lane_departure_checker autoware_perception_msgs autoware_planning_msgs freespace_planning_algorithms geometry_msgs interpolation - lane_departure_checker lanelet2_extension magic_enum motion_utils diff --git a/planning/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp b/planning/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp index 26c089ee0ba09..73f513c9e65eb 100644 --- a/planning/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp +++ b/planning/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp @@ -223,7 +223,8 @@ bool GeometricParallelParking::planPullOver( bool GeometricParallelParking::planPullOut( const Pose & start_pose, const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes, const bool left_side_start, - const std::shared_ptr lane_departure_checker) + const std::shared_ptr + lane_departure_checker) { constexpr bool is_forward = false; // parking backward means pull_out forward constexpr double start_pose_offset = 0.0; // start_pose is current_pose @@ -364,7 +365,8 @@ std::vector GeometricParallelParking::planOneTrial( const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes, const bool is_forward, const bool left_side_parking, const double end_pose_offset, const double lane_departure_margin, const double arc_path_interval, - const std::shared_ptr lane_departure_checker) + const std::shared_ptr + lane_departure_checker) { clearPaths(); diff --git a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/geometric_pull_out.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/geometric_pull_out.hpp index 5edde96ea4abf..510fee8fe3dc6 100644 --- a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/geometric_pull_out.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/geometric_pull_out.hpp @@ -19,7 +19,7 @@ #include "autoware_behavior_path_start_planner_module/pull_out_path.hpp" #include "autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp" -#include +#include #include @@ -32,14 +32,15 @@ class GeometricPullOut : public PullOutPlannerBase public: explicit GeometricPullOut( rclcpp::Node & node, const StartPlannerParameters & parameters, - const std::shared_ptr lane_departure_checker); + const std::shared_ptr + lane_departure_checker); PlannerType getPlannerType() const override { return PlannerType::GEOMETRIC; }; std::optional plan(const Pose & start_pose, const Pose & goal_pose) override; GeometricParallelParking planner_; ParallelParkingParameters parallel_parking_parameters_; - std::shared_ptr lane_departure_checker_; + std::shared_ptr lane_departure_checker_; }; } // namespace behavior_path_planner diff --git a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/shift_pull_out.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/shift_pull_out.hpp index 3092ca4f80e3f..29a74ce0e14ef 100644 --- a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/shift_pull_out.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/shift_pull_out.hpp @@ -18,7 +18,7 @@ #include "autoware_behavior_path_start_planner_module/pull_out_path.hpp" #include "autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp" -#include +#include #include @@ -27,7 +27,7 @@ namespace behavior_path_planner { -using lane_departure_checker::LaneDepartureChecker; +using autoware::lane_departure_checker::LaneDepartureChecker; class ShiftPullOut : public PullOutPlannerBase { diff --git a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/start_planner_module.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/start_planner_module.hpp index 1883e10af3c62..7a98a43efec5b 100644 --- a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/start_planner_module.hpp @@ -27,7 +27,7 @@ #include "autoware_behavior_path_start_planner_module/pull_out_path.hpp" #include "autoware_behavior_path_start_planner_module/shift_pull_out.hpp" -#include +#include #include #include @@ -46,13 +46,13 @@ namespace behavior_path_planner { +using autoware::lane_departure_checker::LaneDepartureChecker; using behavior_path_planner::utils::path_safety_checker::EgoPredictedPathParams; using behavior_path_planner::utils::path_safety_checker::ObjectsFilteringParams; using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; using behavior_path_planner::utils::path_safety_checker::SafetyCheckParams; using behavior_path_planner::utils::path_safety_checker::TargetObjectsOnLane; using geometry_msgs::msg::PoseArray; -using lane_departure_checker::LaneDepartureChecker; using PriorityOrder = std::vector>>; struct PullOutStatus diff --git a/planning/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp b/planning/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp index 86d7de246c312..d299b3f4799b2 100644 --- a/planning/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp +++ b/planning/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp @@ -32,7 +32,8 @@ using start_planner_utils::getPullOutLanes; GeometricPullOut::GeometricPullOut( rclcpp::Node & node, const StartPlannerParameters & parameters, - const std::shared_ptr lane_departure_checker) + const std::shared_ptr + lane_departure_checker) : PullOutPlannerBase{node, parameters}, parallel_parking_parameters_{parameters.parallel_parking_parameters}, lane_departure_checker_(lane_departure_checker) diff --git a/planning/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index c13afdf2b86df..b30af17eaa898 100644 --- a/planning/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -65,7 +65,7 @@ StartPlannerModule::StartPlannerModule( { lane_departure_checker_ = std::make_shared(); lane_departure_checker_->setVehicleInfo(vehicle_info_); - lane_departure_checker::Param lane_departure_checker_params; + autoware::lane_departure_checker::Param lane_departure_checker_params; lane_departure_checker_params.footprint_extra_margin = parameters->lane_departure_check_expansion_margin; diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp index 0009fbccdb5d8..903655b64e347 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp @@ -18,7 +18,7 @@ #include "autoware_behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" -#include +#include #include @@ -27,7 +27,7 @@ namespace behavior_path_planner { -using lane_departure_checker::LaneDepartureChecker; +using autoware::lane_departure_checker::LaneDepartureChecker; class GeometricPullOver : public PullOverPlannerBase { public: diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp index 8938e48e0ceb5..b7c4a24e52974 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -28,9 +28,9 @@ #include "behavior_path_goal_planner_module/goal_searcher.hpp" #include "behavior_path_goal_planner_module/shift_pull_over.hpp" +#include #include #include -#include #include #include @@ -50,9 +50,9 @@ namespace behavior_path_planner { +using autoware::lane_departure_checker::LaneDepartureChecker; using autoware_vehicle_msgs::msg::HazardLightsCommand; using geometry_msgs::msg::PoseArray; -using lane_departure_checker::LaneDepartureChecker; using nav_msgs::msg::OccupancyGrid; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp index 635816f17497f..e7b297548083a 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp @@ -17,7 +17,7 @@ #include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" -#include +#include #include @@ -26,7 +26,7 @@ namespace behavior_path_planner { -using lane_departure_checker::LaneDepartureChecker; +using autoware::lane_departure_checker::LaneDepartureChecker; class ShiftPullOver : public PullOverPlannerBase { diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp index 83e817a8d5a45..d6c9215e495ae 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp @@ -18,7 +18,7 @@ #include "behavior_path_goal_planner_module/goal_searcher_base.hpp" #include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" -#include +#include #include "visualization_msgs/msg/detail/marker_array__struct.hpp" #include diff --git a/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp index efd9eda322585..b56ae44dcf476 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp @@ -32,7 +32,7 @@ namespace behavior_path_planner { -using lane_departure_checker::LaneDepartureChecker; +using autoware::lane_departure_checker::LaneDepartureChecker; using lanelet::autoware::NoParkingArea; using lanelet::autoware::NoStoppingArea; using tier4_autoware_utils::calcOffsetPose; diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index a646621e5b089..f51fa99578d7b 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -39,6 +39,7 @@ autoware_adapi_v1_msgs autoware_behavior_path_planner_common autoware_frenet_planner + autoware_lane_departure_checker autoware_path_sampler autoware_perception_msgs autoware_planning_msgs @@ -48,7 +49,6 @@ freespace_planning_algorithms geometry_msgs interpolation - lane_departure_checker lanelet2_extension libboost-dev libopencv-dev From dfa31a60b1bc0dfab3014d17bdbe148beffa57a3 Mon Sep 17 00:00:00 2001 From: Autumn60 <37181352+Autumn60@users.noreply.github.com> Date: Fri, 7 Jun 2024 20:01:26 +0900 Subject: [PATCH 26/65] fix(mrm_handler): fix stop judgement (#7362) fix stop judgement Signed-off-by: Autumn60 Co-authored-by: Autumn60 --- 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 44407c40c6787..326fbb392fd35 100644 --- a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp +++ b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp @@ -520,7 +520,7 @@ bool MrmHandler::isStopped() auto odom = sub_odom_.takeData(); if (odom == nullptr) return false; constexpr auto th_stopped_velocity = 0.001; - return (std::abs(odom->twist.twist.linear.x < th_stopped_velocity) < th_stopped_velocity); + return (std::abs(odom->twist.twist.linear.x) < th_stopped_velocity); } bool MrmHandler::isDrivingBackwards() From ed038d8c1462d19232e7270479ceb01ebea7b382 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Fri, 7 Jun 2024 21:06:36 +0900 Subject: [PATCH 27/65] chore(smart_mpc_trajectory_follower): add prefix autoware_ to smart_mpc_trajectory_follower (#7367) * add prefix Signed-off-by: Go Sakayori * fix pre-commit Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori --- .github/CODEOWNERS | 2 +- .../.gitignore | 0 .../CMakeLists.txt | 4 +- .../README.md | 66 +++++++++--------- .../.gitignore | 0 .../__init__.py | 0 .../clear_pycache.py | 4 +- .../param/mpc_param.yaml | 0 .../param/nominal_param.yaml | 0 .../param/trained_model_param.yaml | 0 .../python_simulator/.gitignore | 0 .../python_simulator/accel_map.csv | 0 .../plot_auto_test_result.ipynb | 0 .../python_simulator/python_simulator.py | 4 +- .../python_simulator/run_python_simulator.py | 2 +- .../python_simulator/run_sim.py | 2 +- .../python_simulator/slalom_course_data.csv | 0 .../scripts/.gitignore | 0 .../scripts/__init__.py | 0 .../scripts/drive_GP.py | 2 +- .../scripts/drive_NN.py | 4 +- .../scripts/drive_controller.py | 10 +-- .../scripts/drive_functions.py | 8 ++- .../scripts/drive_iLQR.py | 2 +- .../scripts/drive_mppi.py | 2 +- .../scripts/proxima_calc.cpp | 0 .../scripts/pympc_trajectory_follower.py | 4 +- .../training_and_data_check/.gitignore | 0 .../training_and_data_check/__init__.py | 0 .../add_training_data_from_csv.py | 4 +- .../data_checker.ipynb | 0 .../execute_train_drive_NN_model.ipynb | 0 .../training_and_data_check/rosbag2.bash | 0 .../train_drive_GP_model.py | 0 .../train_drive_NN_model.py | 8 ++- .../images/autoware_smart_mpc.png | Bin .../images/lateral_error_nominal_model.png | Bin .../images/lateral_error_trained_model.png | Bin .../images/proxima_logo.png | Bin ...python_sim_lateral_error_nominal_model.png | Bin ...python_sim_lateral_error_trained_model.png | Bin .../images/test_route.png | Bin .../package.xml | 2 +- .../setup.py | 14 ++-- .../launch/control.launch.py | 2 +- 45 files changed, 75 insertions(+), 71 deletions(-) rename control/{smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower}/.gitignore (100%) rename control/{smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower}/CMakeLists.txt (60%) rename control/{smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower}/README.md (85%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/.gitignore (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/__init__.py (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/clear_pycache.py (88%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/param/mpc_param.yaml (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/param/nominal_param.yaml (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/param/trained_model_param.yaml (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/python_simulator/.gitignore (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/python_simulator/accel_map.csv (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/python_simulator/plot_auto_test_result.ipynb (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/python_simulator/python_simulator.py (99%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/python_simulator/run_python_simulator.py (92%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/python_simulator/run_sim.py (99%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/python_simulator/slalom_course_data.csv (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/scripts/.gitignore (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/scripts/__init__.py (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/scripts/drive_GP.py (98%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/scripts/drive_NN.py (98%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/scripts/drive_controller.py (99%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/scripts/drive_functions.py (99%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/scripts/drive_iLQR.py (99%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/scripts/drive_mppi.py (98%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/scripts/proxima_calc.cpp (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/scripts/pympc_trajectory_follower.py (99%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/training_and_data_check/.gitignore (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/training_and_data_check/__init__.py (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/training_and_data_check/add_training_data_from_csv.py (98%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/training_and_data_check/data_checker.ipynb (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/training_and_data_check/execute_train_drive_NN_model.ipynb (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/training_and_data_check/rosbag2.bash (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/training_and_data_check/train_drive_GP_model.py (100%) rename control/{smart_mpc_trajectory_follower/smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower}/training_and_data_check/train_drive_NN_model.py (99%) rename control/{smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower}/images/autoware_smart_mpc.png (100%) rename control/{smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower}/images/lateral_error_nominal_model.png (100%) rename control/{smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower}/images/lateral_error_trained_model.png (100%) rename control/{smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower}/images/proxima_logo.png (100%) rename control/{smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower}/images/python_sim_lateral_error_nominal_model.png (100%) rename control/{smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower}/images/python_sim_lateral_error_trained_model.png (100%) rename control/{smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower}/images/test_route.png (100%) rename control/{smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower}/package.xml (96%) rename control/{smart_mpc_trajectory_follower => autoware_smart_mpc_trajectory_follower}/setup.py (60%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index c0eb60e5a1316..cbab68f91f512 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -57,7 +57,7 @@ control/pid_longitudinal_controller/** mamoru.sobue@tier4.jp takamasa.horibe@tie control/predicted_path_checker/** berkay@leodrive.ai control/pure_pursuit/** takamasa.horibe@tier4.jp control/shift_decider/** takamasa.horibe@tier4.jp -control/smart_mpc_trajectory_follower/** masayuki.aino@proxima-ai-tech.com +control/autoware_smart_mpc_trajectory_follower/** masayuki.aino@proxima-ai-tech.com control/trajectory_follower_base/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/trajectory_follower_node/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/vehicle_cmd_gate/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp diff --git a/control/smart_mpc_trajectory_follower/.gitignore b/control/autoware_smart_mpc_trajectory_follower/.gitignore similarity index 100% rename from control/smart_mpc_trajectory_follower/.gitignore rename to control/autoware_smart_mpc_trajectory_follower/.gitignore diff --git a/control/smart_mpc_trajectory_follower/CMakeLists.txt b/control/autoware_smart_mpc_trajectory_follower/CMakeLists.txt similarity index 60% rename from control/smart_mpc_trajectory_follower/CMakeLists.txt rename to control/autoware_smart_mpc_trajectory_follower/CMakeLists.txt index 7aecab2597dcd..57e7b596790c2 100644 --- a/control/smart_mpc_trajectory_follower/CMakeLists.txt +++ b/control/autoware_smart_mpc_trajectory_follower/CMakeLists.txt @@ -1,11 +1,11 @@ cmake_minimum_required(VERSION 3.14) -project(smart_mpc_trajectory_follower) +project(autoware_smart_mpc_trajectory_follower) find_package(autoware_cmake REQUIRED) autoware_package() install(PROGRAMS - smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py + autoware_smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py DESTINATION lib/${PROJECT_NAME} ) ament_auto_package( diff --git a/control/smart_mpc_trajectory_follower/README.md b/control/autoware_smart_mpc_trajectory_follower/README.md similarity index 85% rename from control/smart_mpc_trajectory_follower/README.md rename to control/autoware_smart_mpc_trajectory_follower/README.md index 8fcc13142d68b..fd135319ff900 100644 --- a/control/smart_mpc_trajectory_follower/README.md +++ b/control/autoware_smart_mpc_trajectory_follower/README.md @@ -19,7 +19,7 @@ This technology makes it relatively easy to operate model predictive control, wh ## Setup -After building autoware, move to `control/smart_mpc_trajectory_follower` and run the following command: +After building autoware, move to `control/autoware_smart_mpc_trajectory_follower` and run the following command: ```bash pip3 install . @@ -37,7 +37,7 @@ This package provides smart MPC logic for path-following control as well as mech ### Trajectory following control based on iLQR/MPPI -The control mode can be selected from "ilqr", "mppi", or "mppi_ilqr", and can be set as `mpc_parameter:system:mode` in [mpc_param.yaml](./smart_mpc_trajectory_follower/param/mpc_param.yaml). +The control mode can be selected from "ilqr", "mppi", or "mppi_ilqr", and can be set as `mpc_parameter:system:mode` in [mpc_param.yaml](./autoware_smart_mpc_trajectory_follower/param/mpc_param.yaml). In "mppi_ilqr" mode, the initial value of iLQR is given by the MPPI solution. > [!NOTE] @@ -50,7 +50,7 @@ ros2 launch autoware_launch planning_simulator.launch.xml map_path:=$HOME/autowa ``` > [!NOTE] -> When running with the nominal model set in [nominal_param.yaml](./smart_mpc_trajectory_follower/param/nominal_param.yaml), set `trained_model_parameter:control_application:use_trained_model` to `false` in [trained_model_param.yaml](./smart_mpc_trajectory_follower/param/trained_model_param.yaml). To run using the trained model, set `trained_model_parameter:control_application:use_trained_model` to `true`, but the trained model must have been generated according to the following procedure. +> When running with the nominal model set in [nominal_param.yaml](./autoware_smart_mpc_trajectory_follower/param/nominal_param.yaml), set `trained_model_parameter:control_application:use_trained_model` to `false` in [trained_model_param.yaml](./autoware_smart_mpc_trajectory_follower/param/trained_model_param.yaml). To run using the trained model, set `trained_model_parameter:control_application:use_trained_model` to `true`, but the trained model must have been generated according to the following procedure. ### Training of model and reflection in control @@ -60,7 +60,7 @@ To obtain training data, start autoware, perform a drive, and record rosbag data ros2 bag record /localization/kinematic_state /localization/acceleration /vehicle/status/steering_status /control/command/control_cmd /control/trajectory_follower/control_cmd /control/trajectory_follower/lane_departure_checker_node/debug/deviation/lateral /control/trajectory_follower/lane_departure_checker_node/debug/deviation/yaw /system/operation_mode/state /vehicle/status/control_mode /sensing/imu/imu_data /debug_mpc_x_des /debug_mpc_y_des /debug_mpc_v_des /debug_mpc_yaw_des /debug_mpc_acc_des /debug_mpc_steer_des /debug_mpc_X_des_converted /debug_mpc_x_current /debug_mpc_error_prediction /debug_mpc_max_trajectory_err /debug_mpc_emergency_stop_mode /debug_mpc_goal_stop_mode /debug_mpc_total_ctrl_time /debug_mpc_calc_u_opt_time ``` -Move [rosbag2.bash](./smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash) to the rosbag directory recorded above and execute the following command on the directory +Move [rosbag2.bash](./autoware_smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash) to the rosbag directory recorded above and execute the following command on the directory ```bash bash rosbag2.bash @@ -75,7 +75,7 @@ This converts rosbag data into CSV format for training models. Instead, the same result can be obtained by executing the following command in a python environment: ```python -from smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model +from autoware_smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model model_trainer = train_drive_NN_model.train_drive_NN_model() model_trainer.transform_rosbag_to_csv(rosbag_dir) ``` @@ -86,7 +86,7 @@ At this time, all CSV files in `rosbag_dir` are automatically deleted first. The paths of the rosbag directories used for training, `dir_0`, `dir_1`, `dir_2`,... and the directory `save_dir` where you save the models, the model can be saved in the python environment as follows: ```python -from smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model +from autoware_smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model model_trainer = train_drive_NN_model.train_drive_NN_model() model_trainer.add_data_from_csv(dir_0) model_trainer.add_data_from_csv(dir_1) @@ -112,12 +112,12 @@ If only polynomial regression is performed and no NN model is used, run the foll model_trainer.get_trained_model(use_polynomial_reg=True,force_NN_model_to_zero=True) ``` -Move `model_for_test_drive.pth` and `polynomial_reg_info.npz` saved in `save_dir` to the home directory and set `trained_model_parameter:control_application:use_trained_model` in [trained_model_param.yaml](./smart_mpc_trajectory_follower/param/trained_model_param.yaml) to `true` to reflect the trained model in the control. +Move `model_for_test_drive.pth` and `polynomial_reg_info.npz` saved in `save_dir` to the home directory and set `trained_model_parameter:control_application:use_trained_model` in [trained_model_param.yaml](./autoware_smart_mpc_trajectory_follower/param/trained_model_param.yaml) to `true` to reflect the trained model in the control. ### Performance evaluation Here, as an example, we describe the verification of the adaptive performance when the wheel base of the sample_vehicle is 2.79 m, but an incorrect value of 2.0 m is given to the controller side. -To give the controller 2.0 m as the wheel base, set the value of `nominal_parameter:vehicle_info:wheel_base` in [nominal_param.yaml](./smart_mpc_trajectory_follower/param/nominal_param.yaml) to 2.0, and run the following command: +To give the controller 2.0 m as the wheel base, set the value of `nominal_parameter:vehicle_info:wheel_base` in [nominal_param.yaml](./autoware_smart_mpc_trajectory_follower/param/nominal_param.yaml) to 2.0, and run the following command: ```bash python3 -m smart_mpc_trajectory_follower.clear_pycache @@ -125,7 +125,7 @@ python3 -m smart_mpc_trajectory_follower.clear_pycache #### Test on autoware -To perform a control test on autoware with the nominal model before training, make sure that `trained_model_parameter:control_application:use_trained_model` in [trained_model_param.yaml](./smart_mpc_trajectory_follower/param/trained_model_param.yaml) is `false` and launch autoware in the manner described in "Trajectory following control based on iLQR/MPPI". This time, the following route will be used for the test: +To perform a control test on autoware with the nominal model before training, make sure that `trained_model_parameter:control_application:use_trained_model` in [trained_model_param.yaml](./autoware_smart_mpc_trajectory_follower/param/trained_model_param.yaml) is `false` and launch autoware in the manner described in "Trajectory following control based on iLQR/MPPI". This time, the following route will be used for the test:

@@ -136,7 +136,7 @@ Record rosbag and train the model in the manner described in "Training of model To control using the trained model obtained here, set `trained_model_parameter:control_application:use_trained_model` to `true`, start autoware in the same way, and drive the same route recording rosbag. After the driving is complete, convert the rosbag file to CSV format using the method described in "Training of model and reflection in control". -A plot of the lateral deviation is obtained by running the `lateral_error_visualize` function in `control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/data_checker.ipynb` for the nominal and training model rosbag files `rosbag_nominal` and `rosbag_trained`, respectively, as follows: +A plot of the lateral deviation is obtained by running the `lateral_error_visualize` function in `control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/data_checker.ipynb` for the nominal and training model rosbag files `rosbag_nominal` and `rosbag_trained`, respectively, as follows: ```python lateral_error_visualize(dir_name=rosbag_nominal,ylim=[-1.2,1.2]) @@ -152,7 +152,7 @@ The following results were obtained. #### Test on python simulator -First, to give wheel base 2.79 m in the python simulator, create the following file and save it in `control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator` with the name `sim_setting.json`: +First, to give wheel base 2.79 m in the python simulator, create the following file and save it in `control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator` with the name `sim_setting.json`: ```json { "wheel_base": 2.79 } @@ -162,7 +162,7 @@ Next, run the following commands to test the slalom driving on the python simula ```python import python_simulator -from smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model +from autoware_smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model initial_error = [0.0, 0.03, 0.01, -0.01, 0.0, 0.0] save_dir = "test_python_sim" python_simulator.slalom_drive(save_dir=save_dir,use_trained_model=False,initial_error=initial_error) @@ -172,7 +172,7 @@ Here, `initial_error` is the initial error from the target trajectory, in the or and `save_dir` is the directory where the driving test results are saved. > [!NOTE] -> The value of `use_trained_model` given as the argument of `python_simulator.slalom_drive` takes precedence over the value of `trained_model_parameter:control_application:use_trained_model` in [trained_model_param.yaml](./smart_mpc_trajectory_follower/param/trained_model_param.yaml). +> The value of `use_trained_model` given as the argument of `python_simulator.slalom_drive` takes precedence over the value of `trained_model_parameter:control_application:use_trained_model` in [trained_model_param.yaml](./autoware_smart_mpc_trajectory_follower/param/trained_model_param.yaml). Run the following commands to perform training using driving data of the nominal model. @@ -211,21 +211,21 @@ It can be seen that the lateral deviation has improved significantly. Here we have described wheel base, but the parameters that can be passed to the python simulator are as follows. -| Parameter | Type | Description | -| ------------------------ | ----------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| steer_bias | float | steer bias [rad] | -| steer_rate_lim | float | steer rate limit [rad/s] | -| vel_rate_lim | float | acceleration limit [m/s^2] | -| wheel_base | float | wheel base [m] | -| steer_dead_band | float | steer dead band [rad] | -| adaptive_gear_ratio_coef | list[float] | List of floats of length 6 specifying information on speed-dependent gear ratios from tire angle to steering wheel angle. | -| acc_time_delay | float | acceleration time delay [s] | -| steer_time_delay | float | steer time delay [s] | -| acc_time_constant | float | acceleration time constant [s] | -| steer_time_constant | float | steer time constant [s] | -| accel_map_scale | float | Parameter that magnifies the corresponding distortion from acceleration input values to actual acceleration realizations.
Correspondence information is kept in `control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/accel_map.csv`. | -| acc_scaling | float | acceleration scaling | -| steer_scaling | float | steer scaling | +| Parameter | Type | Description | +| ------------------------ | ----------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| steer_bias | float | steer bias [rad] | +| steer_rate_lim | float | steer rate limit [rad/s] | +| vel_rate_lim | float | acceleration limit [m/s^2] | +| wheel_base | float | wheel base [m] | +| steer_dead_band | float | steer dead band [rad] | +| adaptive_gear_ratio_coef | list[float] | List of floats of length 6 specifying information on speed-dependent gear ratios from tire angle to steering wheel angle. | +| acc_time_delay | float | acceleration time delay [s] | +| steer_time_delay | float | steer time delay [s] | +| acc_time_constant | float | acceleration time constant [s] | +| steer_time_constant | float | steer time constant [s] | +| accel_map_scale | float | Parameter that magnifies the corresponding distortion from acceleration input values to actual acceleration realizations.
Correspondence information is kept in `control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/accel_map.csv`. | +| acc_scaling | float | acceleration scaling | +| steer_scaling | float | steer scaling | For example, to give the simulation side 0.01 [rad] of steer bias and 0.001 [rad] of steer dead band, edit the `sim_setting.json` as follows. @@ -237,13 +237,13 @@ For example, to give the simulation side 0.01 [rad] of steer bias and 0.001 [rad Here, we describe a method for testing adaptive performance by giving the simulation side a predefined range of model parameters while the control side is given constant model parameters. -First, to restore nominal model settings to default values, set the value of `nominal_parameter:vehicle_info:wheel_base` in [nominal_param.yaml](./smart_mpc_trajectory_follower/param/nominal_param.yaml) to 2.79, and run the following command: +First, to restore nominal model settings to default values, set the value of `nominal_parameter:vehicle_info:wheel_base` in [nominal_param.yaml](./autoware_smart_mpc_trajectory_follower/param/nominal_param.yaml) to 2.79, and run the following command: ```bash python3 -m smart_mpc_trajectory_follower.clear_pycache ``` -To run a driving experiment within the parameter change range set in [run_sim.py](./smart_mpc_trajectory_follower/python_simulator/run_sim.py), for example, move to `control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator` and run the following command: +To run a driving experiment within the parameter change range set in [run_sim.py](./autoware_smart_mpc_trajectory_follower/python_simulator/run_sim.py), for example, move to `control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator` and run the following command: ```bash python3 run_sim.py --param_name steer_bias @@ -270,11 +270,11 @@ In `run_sim.py`, the following parameters can be set: | USE_INTERCEPT | bool | When a polynomial regression including bias is performed, whether to use or discard the resulting bias information.
It is meaningful only if FIT_INTERCEPT is True.
If it is False, discard the bias in the polynomial regression in the hope that the NN model can remove the bias term, even if the polynomial regression is performed with the bias included. | > [!NOTE] -> When `run_sim.py` is run, the `use_trained_model_diff` set in `run_sim.py` takes precedence over the `trained_model_parameter:control_application:use_trained_model_diff` set in [trained_model_param.yaml](./smart_mpc_trajectory_follower/param/trained_model_param.yaml). +> When `run_sim.py` is run, the `use_trained_model_diff` set in `run_sim.py` takes precedence over the `trained_model_parameter:control_application:use_trained_model_diff` set in [trained_model_param.yaml](./autoware_smart_mpc_trajectory_follower/param/trained_model_param.yaml). ## Change of nominal parameters and their reloading -The nominal parameters of vehicle model can be changed by editing the file [nominal_param.yaml](./smart_mpc_trajectory_follower/param/nominal_param.yaml). +The nominal parameters of vehicle model can be changed by editing the file [nominal_param.yaml](./autoware_smart_mpc_trajectory_follower/param/nominal_param.yaml). After changing the nominal parameters, the cache must be deleted by running the following command: ```bash @@ -293,7 +293,7 @@ The nominal parameters include the following: ## Change of control parameters and their reloading -The control parameters can be changed by editing files [mpc_param.yaml](./smart_mpc_trajectory_follower/param/mpc_param.yaml) and [trained_model_param.yaml](./smart_mpc_trajectory_follower/param/trained_model_param.yaml). +The control parameters can be changed by editing files [mpc_param.yaml](./smart_mpc_trajectory_follower/param/mpc_param.yaml) and [trained_model_param.yaml](./autoware_smart_mpc_trajectory_follower/param/trained_model_param.yaml). Although it is possible to reflect parameter changes by restarting autoware, the following command allows us to do so without leaving autoware running: ```bash diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/.gitignore b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/.gitignore similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/.gitignore rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/.gitignore diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/__init__.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/__init__.py similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/__init__.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/__init__.py diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/clear_pycache.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/clear_pycache.py similarity index 88% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/clear_pycache.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/clear_pycache.py index fafcb5bdecf05..2458de3a80f99 100644 --- a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/clear_pycache.py +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/clear_pycache.py @@ -16,10 +16,10 @@ from pathlib import Path import shutil -import smart_mpc_trajectory_follower +import autoware_smart_mpc_trajectory_follower if __name__ == "__main__": - package_dir = str(Path(smart_mpc_trajectory_follower.__file__).parent) + package_dir = str(Path(autoware_smart_mpc_trajectory_follower.__file__).parent) remove_dirs = [ package_dir + "/__pycache__", diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/mpc_param.yaml b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/param/mpc_param.yaml similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/mpc_param.yaml rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/param/mpc_param.yaml diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/nominal_param.yaml b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/param/nominal_param.yaml similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/nominal_param.yaml rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/param/nominal_param.yaml diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/trained_model_param.yaml b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/param/trained_model_param.yaml similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/trained_model_param.yaml rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/param/trained_model_param.yaml diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/.gitignore b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/.gitignore similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/.gitignore rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/.gitignore diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/accel_map.csv b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/accel_map.csv similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/accel_map.csv rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/accel_map.csv diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/plot_auto_test_result.ipynb b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/plot_auto_test_result.ipynb similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/plot_auto_test_result.ipynb rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/plot_auto_test_result.ipynb diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/python_simulator.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/python_simulator.py similarity index 99% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/python_simulator.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/python_simulator.py index d706c342f04ec..0eaa6ce1c0fbf 100644 --- a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/python_simulator.py +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/python_simulator.py @@ -18,14 +18,14 @@ import datetime import os +from autoware_smart_mpc_trajectory_follower.scripts import drive_controller +from autoware_smart_mpc_trajectory_follower.scripts import drive_functions import matplotlib.pyplot as plt from numba import njit import numpy as np import pandas as pd import scipy.interpolate import simplejson as json -from smart_mpc_trajectory_follower.scripts import drive_controller -from smart_mpc_trajectory_follower.scripts import drive_functions print("\n\n### import python_simulator.py ###") diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/run_python_simulator.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/run_python_simulator.py similarity index 92% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/run_python_simulator.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/run_python_simulator.py index 6b477bb804ac9..68d8a9f64e73f 100644 --- a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/run_python_simulator.py +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/run_python_simulator.py @@ -12,9 +12,9 @@ # See the License for the specific language governing permissions and # limitations under the License. +from autoware_smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model import numpy as np import python_simulator -from smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model initial_error = np.array( [0.001, 0.03, 0.01, -0.001, 0, 2 * python_simulator.measurement_steer_bias] diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/run_sim.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/run_sim.py similarity index 99% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/run_sim.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/run_sim.py index 3125719556559..d2bb4ea26f0a6 100644 --- a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/run_sim.py +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/run_sim.py @@ -23,9 +23,9 @@ import traceback from typing import Dict +from autoware_smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model import numpy as np import python_simulator -from smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model parser = argparse.ArgumentParser() parser.add_argument("--param_name", default=None) diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/slalom_course_data.csv b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/slalom_course_data.csv similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/slalom_course_data.csv rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/slalom_course_data.csv diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/.gitignore b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/.gitignore similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/.gitignore rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/.gitignore diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/__init__.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/__init__.py similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/__init__.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/__init__.py diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_GP.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_GP.py similarity index 98% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_GP.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_GP.py index e75eedcb4bf65..4d36afd3d4324 100644 --- a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_GP.py +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_GP.py @@ -16,9 +16,9 @@ from functools import partial +from autoware_smart_mpc_trajectory_follower.scripts import drive_functions from numba import njit import numpy as np -from smart_mpc_trajectory_follower.scripts import drive_functions sqrt_mpc_time_step = np.sqrt(drive_functions.mpc_time_step) diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_NN.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_NN.py similarity index 98% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_NN.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_NN.py index f35789ee39fd3..f13aa07b0f795 100644 --- a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_NN.py +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_NN.py @@ -13,9 +13,9 @@ # limitations under the License. +from autoware_smart_mpc_trajectory_follower.scripts import drive_functions +from autoware_smart_mpc_trajectory_follower.scripts import proxima_calc import numpy as np -from smart_mpc_trajectory_follower.scripts import drive_functions -from smart_mpc_trajectory_follower.scripts import proxima_calc import torch from torch import nn diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_controller.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_controller.py similarity index 99% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_controller.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_controller.py index b21fcf72da931..228b0c37c5e7b 100644 --- a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_controller.py +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_controller.py @@ -21,14 +21,14 @@ import threading import time +from autoware_smart_mpc_trajectory_follower.scripts import drive_GP +from autoware_smart_mpc_trajectory_follower.scripts import drive_NN +from autoware_smart_mpc_trajectory_follower.scripts import drive_functions +from autoware_smart_mpc_trajectory_follower.scripts import drive_iLQR +from autoware_smart_mpc_trajectory_follower.scripts import drive_mppi import numpy as np import scipy.interpolate # type: ignore from sklearn.preprocessing import PolynomialFeatures -from smart_mpc_trajectory_follower.scripts import drive_GP -from smart_mpc_trajectory_follower.scripts import drive_NN -from smart_mpc_trajectory_follower.scripts import drive_functions -from smart_mpc_trajectory_follower.scripts import drive_iLQR -from smart_mpc_trajectory_follower.scripts import drive_mppi import torch ctrl_index_for_polynomial_reg = np.concatenate( diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_functions.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_functions.py similarity index 99% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_functions.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_functions.py index c11b5c886b49a..fb96e134f7746 100644 --- a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_functions.py +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_functions.py @@ -31,7 +31,9 @@ with open(package_path_json, "r") as file: package_path = json.load(file) -mpc_param_path = package_path["path"] + "/smart_mpc_trajectory_follower/param/mpc_param.yaml" +mpc_param_path = ( + package_path["path"] + "/autoware_smart_mpc_trajectory_follower/param/mpc_param.yaml" +) with open(mpc_param_path, "r") as yml: mpc_param = yaml.safe_load(yml) @@ -101,7 +103,7 @@ cap_pred_error = np.array(mpc_param["mpc_parameter"]["preprocessing"]["cap_pred_error"]) nominal_param_path = ( - package_path["path"] + "/smart_mpc_trajectory_follower/param/nominal_param.yaml" + package_path["path"] + "/autoware_smart_mpc_trajectory_follower/param/nominal_param.yaml" ) with open(nominal_param_path, "r") as yml: nominal_param = yaml.safe_load(yml) @@ -172,7 +174,7 @@ mpc_param["mpc_parameter"]["preprocessing"]["sg_window_size_for_nominal_inputs"] ) trained_model_param_path = ( - package_path["path"] + "/smart_mpc_trajectory_follower/param/trained_model_param.yaml" + package_path["path"] + "/autoware_smart_mpc_trajectory_follower/param/trained_model_param.yaml" ) with open(trained_model_param_path, "r") as yml: trained_model_param = yaml.safe_load(yml) diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_iLQR.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_iLQR.py similarity index 99% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_iLQR.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_iLQR.py index 261a72e680778..2307586f23552 100644 --- a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_iLQR.py +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_iLQR.py @@ -21,9 +21,9 @@ import time from typing import Callable +from autoware_smart_mpc_trajectory_follower.scripts import drive_functions from numba import njit import numpy as np -from smart_mpc_trajectory_follower.scripts import drive_functions index_cost = np.concatenate( ( diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_mppi.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_mppi.py similarity index 98% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_mppi.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_mppi.py index ca6e6f15f42ef..5e88c79172097 100644 --- a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_mppi.py +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_mppi.py @@ -16,9 +16,9 @@ from typing import Callable +from autoware_smart_mpc_trajectory_follower.scripts import drive_functions from numba import njit import numpy as np -from smart_mpc_trajectory_follower.scripts import drive_functions index_cost = np.concatenate( ( diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/proxima_calc.cpp b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/proxima_calc.cpp similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/proxima_calc.cpp rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/proxima_calc.cpp diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py similarity index 99% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py index 992a5fd53a10c..78a120fe601f2 100755 --- a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py @@ -22,6 +22,8 @@ from autoware_control_msgs.msg import Control from autoware_planning_msgs.msg import Trajectory from autoware_planning_msgs.msg import TrajectoryPoint +from autoware_smart_mpc_trajectory_follower.scripts import drive_controller +from autoware_smart_mpc_trajectory_follower.scripts import drive_functions from autoware_vehicle_msgs.msg import SteeringReport from builtin_interfaces.msg import Duration from geometry_msgs.msg import AccelWithCovarianceStamped @@ -34,8 +36,6 @@ import scipy.interpolate from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Slerp -from smart_mpc_trajectory_follower.scripts import drive_controller -from smart_mpc_trajectory_follower.scripts import drive_functions from std_msgs.msg import String from tier4_debug_msgs.msg import BoolStamped from tier4_debug_msgs.msg import Float32MultiArrayStamped diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/.gitignore b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/.gitignore similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/.gitignore rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/.gitignore diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/__init__.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/__init__.py similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/__init__.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/__init__.py diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/add_training_data_from_csv.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/add_training_data_from_csv.py similarity index 98% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/add_training_data_from_csv.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/add_training_data_from_csv.py index 3f6ef7a9f78d1..5338f3cbaddce 100644 --- a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/add_training_data_from_csv.py +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/add_training_data_from_csv.py @@ -23,11 +23,11 @@ import os from pathlib import Path +from autoware_smart_mpc_trajectory_follower.scripts import drive_functions import numpy as np import scipy.interpolate from scipy.ndimage import gaussian_filter from scipy.spatial.transform import Rotation -from smart_mpc_trajectory_follower.scripts import drive_functions def data_smoothing(data: np.ndarray, sigma: float) -> np.ndarray: @@ -76,7 +76,7 @@ def transform_rosbag_to_csv(self, dir_name: str, delete_csv_first: bool = True) os.system( "cp " + package_path["path"] - + "/smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash " + + "/autoware_smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash " + dir_name ) os.chdir(dir_name) diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/data_checker.ipynb b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/data_checker.ipynb similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/data_checker.ipynb rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/data_checker.ipynb diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/execute_train_drive_NN_model.ipynb b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/execute_train_drive_NN_model.ipynb similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/execute_train_drive_NN_model.ipynb rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/execute_train_drive_NN_model.ipynb diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/train_drive_GP_model.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/train_drive_GP_model.py similarity index 100% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/train_drive_GP_model.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/train_drive_GP_model.py diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/train_drive_NN_model.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/train_drive_NN_model.py similarity index 99% rename from control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/train_drive_NN_model.py rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/train_drive_NN_model.py index 269b577f83c25..449ddda45f460 100644 --- a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/train_drive_NN_model.py +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/train_drive_NN_model.py @@ -15,13 +15,15 @@ # cspell: ignore optim savez suptitle """Class for training neural nets from driving data.""" +from autoware_smart_mpc_trajectory_follower.scripts import drive_NN +from autoware_smart_mpc_trajectory_follower.scripts import drive_functions +from autoware_smart_mpc_trajectory_follower.training_and_data_check import ( + add_training_data_from_csv, +) import matplotlib.pyplot as plt import numpy as np from sklearn import linear_model from sklearn.preprocessing import PolynomialFeatures -from smart_mpc_trajectory_follower.scripts import drive_NN -from smart_mpc_trajectory_follower.scripts import drive_functions -from smart_mpc_trajectory_follower.training_and_data_check import add_training_data_from_csv import torch from torch import nn from torch.utils.data import DataLoader diff --git a/control/smart_mpc_trajectory_follower/images/autoware_smart_mpc.png b/control/autoware_smart_mpc_trajectory_follower/images/autoware_smart_mpc.png similarity index 100% rename from control/smart_mpc_trajectory_follower/images/autoware_smart_mpc.png rename to control/autoware_smart_mpc_trajectory_follower/images/autoware_smart_mpc.png diff --git a/control/smart_mpc_trajectory_follower/images/lateral_error_nominal_model.png b/control/autoware_smart_mpc_trajectory_follower/images/lateral_error_nominal_model.png similarity index 100% rename from control/smart_mpc_trajectory_follower/images/lateral_error_nominal_model.png rename to control/autoware_smart_mpc_trajectory_follower/images/lateral_error_nominal_model.png diff --git a/control/smart_mpc_trajectory_follower/images/lateral_error_trained_model.png b/control/autoware_smart_mpc_trajectory_follower/images/lateral_error_trained_model.png similarity index 100% rename from control/smart_mpc_trajectory_follower/images/lateral_error_trained_model.png rename to control/autoware_smart_mpc_trajectory_follower/images/lateral_error_trained_model.png diff --git a/control/smart_mpc_trajectory_follower/images/proxima_logo.png b/control/autoware_smart_mpc_trajectory_follower/images/proxima_logo.png similarity index 100% rename from control/smart_mpc_trajectory_follower/images/proxima_logo.png rename to control/autoware_smart_mpc_trajectory_follower/images/proxima_logo.png diff --git a/control/smart_mpc_trajectory_follower/images/python_sim_lateral_error_nominal_model.png b/control/autoware_smart_mpc_trajectory_follower/images/python_sim_lateral_error_nominal_model.png similarity index 100% rename from control/smart_mpc_trajectory_follower/images/python_sim_lateral_error_nominal_model.png rename to control/autoware_smart_mpc_trajectory_follower/images/python_sim_lateral_error_nominal_model.png diff --git a/control/smart_mpc_trajectory_follower/images/python_sim_lateral_error_trained_model.png b/control/autoware_smart_mpc_trajectory_follower/images/python_sim_lateral_error_trained_model.png similarity index 100% rename from control/smart_mpc_trajectory_follower/images/python_sim_lateral_error_trained_model.png rename to control/autoware_smart_mpc_trajectory_follower/images/python_sim_lateral_error_trained_model.png diff --git a/control/smart_mpc_trajectory_follower/images/test_route.png b/control/autoware_smart_mpc_trajectory_follower/images/test_route.png similarity index 100% rename from control/smart_mpc_trajectory_follower/images/test_route.png rename to control/autoware_smart_mpc_trajectory_follower/images/test_route.png diff --git a/control/smart_mpc_trajectory_follower/package.xml b/control/autoware_smart_mpc_trajectory_follower/package.xml similarity index 96% rename from control/smart_mpc_trajectory_follower/package.xml rename to control/autoware_smart_mpc_trajectory_follower/package.xml index b25a7e2ce8dd6..a05f06cd865ff 100644 --- a/control/smart_mpc_trajectory_follower/package.xml +++ b/control/autoware_smart_mpc_trajectory_follower/package.xml @@ -1,7 +1,7 @@ - smart_mpc_trajectory_follower + autoware_smart_mpc_trajectory_follower 1.0.0 Nodes to follow a trajectory by generating control commands using smart mpc diff --git a/control/smart_mpc_trajectory_follower/setup.py b/control/autoware_smart_mpc_trajectory_follower/setup.py similarity index 60% rename from control/smart_mpc_trajectory_follower/setup.py rename to control/autoware_smart_mpc_trajectory_follower/setup.py index 4dca4d72929a8..fee1d04e826c0 100644 --- a/control/smart_mpc_trajectory_follower/setup.py +++ b/control/autoware_smart_mpc_trajectory_follower/setup.py @@ -13,25 +13,25 @@ os.system("pip3 install torch") package_path = {} package_path["path"] = str(Path(__file__).parent) -with open("smart_mpc_trajectory_follower/package_path.json", "w") as f: +with open("autoware_smart_mpc_trajectory_follower/package_path.json", "w") as f: json.dump(package_path, f) build_cpp_command = "g++ -Ofast -Wall -shared -std=c++11 -fPIC $(python3 -m pybind11 --includes) " -build_cpp_command += "smart_mpc_trajectory_follower/scripts/proxima_calc.cpp " -build_cpp_command += ( - "-o smart_mpc_trajectory_follower/scripts/proxima_calc$(python3-config --extension-suffix) " -) +build_cpp_command += "autoware_smart_mpc_trajectory_follower/scripts/proxima_calc.cpp " +build_cpp_command += "-o autoware_smart_mpc_trajectory_follower/scripts/proxima_calc$(python3-config --extension-suffix) " build_cpp_command += "-lrt -I/usr/include/eigen3" os.system(build_cpp_command) so_path = ( "scripts/" - + glob.glob("smart_mpc_trajectory_follower/scripts/proxima_calc.*.so")[0].split("/")[-1] + + glob.glob("autoware_smart_mpc_trajectory_follower/scripts/proxima_calc.*.so")[0].split("/")[ + -1 + ] ) setup( name="smart_mpc_trajectory_follower", version="1.0.0", packages=find_packages(), package_data={ - "smart_mpc_trajectory_follower": ["package_path.json", so_path], + "autoware_smart_mpc_trajectory_follower": ["package_path.json", so_path], }, ) diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index 239a65f8260bf..d9e6e3e6757d6 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -432,7 +432,7 @@ def launch_setup(context, *args, **kwargs): ) smart_mpc_trajectory_follower = Node( - package="smart_mpc_trajectory_follower", + package="autoware_smart_mpc_trajectory_follower", executable="pympc_trajectory_follower.py", name="pympc_trajectory_follower", ) From b1749afb95dca78db2537f682f4bd971cc74a933 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Fri, 7 Jun 2024 22:18:06 +0900 Subject: [PATCH 28/65] feat(autonomous_emergency_braking): prefix package and namespace with autoware_ (#7294) * change package name Signed-off-by: Daniel Sanchez * add the prefix Signed-off-by: Daniel Sanchez * change option Signed-off-by: Daniel Sanchez * change back node name Signed-off-by: Daniel Sanchez * eliminate some prefixes that are not required Signed-off-by: Daniel Sanchez * fix node name Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .github/CODEOWNERS | 2 +- .../CMakeLists.txt | 2 +- .../README.md | 0 .../config/autonomous_emergency_braking.param.yaml | 0 .../image/obstacle_filtering_1.drawio.svg | 0 .../image/obstacle_filtering_2.drawio.svg | 0 .../image/range.drawio.svg | 0 .../image/rss_check.drawio.svg | 0 .../include/autoware_autonomous_emergency_braking}/node.hpp | 6 +++--- .../autoware_autonomous_emergency_braking.launch.xml} | 4 ++-- .../package.xml | 2 +- .../src/node.cpp | 2 +- launch/tier4_control_launch/launch/control.launch.py | 2 +- .../config/diagnostic_aggregator/control.param.yaml | 2 +- .../config/system_error_monitor.param.yaml | 4 ++-- .../system_error_monitor.planning_simulation.param.yaml | 4 ++-- 16 files changed, 15 insertions(+), 15 deletions(-) rename control/{autonomous_emergency_braking => autoware_autonomous_emergency_braking}/CMakeLists.txt (92%) rename control/{autonomous_emergency_braking => autoware_autonomous_emergency_braking}/README.md (100%) rename control/{autonomous_emergency_braking => autoware_autonomous_emergency_braking}/config/autonomous_emergency_braking.param.yaml (100%) rename control/{autonomous_emergency_braking => autoware_autonomous_emergency_braking}/image/obstacle_filtering_1.drawio.svg (100%) rename control/{autonomous_emergency_braking => autoware_autonomous_emergency_braking}/image/obstacle_filtering_2.drawio.svg (100%) rename control/{autonomous_emergency_braking => autoware_autonomous_emergency_braking}/image/range.drawio.svg (100%) rename control/{autonomous_emergency_braking => autoware_autonomous_emergency_braking}/image/rss_check.drawio.svg (100%) rename control/{autonomous_emergency_braking/include/autonomous_emergency_braking => autoware_autonomous_emergency_braking/include/autoware_autonomous_emergency_braking}/node.hpp (98%) rename control/{autonomous_emergency_braking/launch/autonomous_emergency_braking.launch.xml => autoware_autonomous_emergency_braking/launch/autoware_autonomous_emergency_braking.launch.xml} (74%) rename control/{autonomous_emergency_braking => autoware_autonomous_emergency_braking}/package.xml (96%) rename control/{autonomous_emergency_braking => autoware_autonomous_emergency_braking}/src/node.cpp (99%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index cbab68f91f512..be202d123cd62 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -44,7 +44,7 @@ common/time_utils/** christopherj.ho@gmail.com shumpei.wakabayashi@tier4.jp tomo common/traffic_light_recognition_marker_publisher/** shumpei.wakabayashi@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp common/traffic_light_utils/** kotaro.uetake@tier4.jp satoshi.ota@tier4.jp shunsuke.miura@tier4.jp common/tvm_utility/** ambroise.vincent@arm.com xinyu.wang@tier4.jp -control/autonomous_emergency_braking/** daniel.sanchez@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp +control/autoware_autonomous_emergency_braking/** daniel.sanchez@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp control/control_performance_analysis/** berkay@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/control_validator/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/external_cmd_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp diff --git a/control/autonomous_emergency_braking/CMakeLists.txt b/control/autoware_autonomous_emergency_braking/CMakeLists.txt similarity index 92% rename from control/autonomous_emergency_braking/CMakeLists.txt rename to control/autoware_autonomous_emergency_braking/CMakeLists.txt index 53a629fafa0cc..7f38e4387b452 100644 --- a/control/autonomous_emergency_braking/CMakeLists.txt +++ b/control/autoware_autonomous_emergency_braking/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(autonomous_emergency_braking) +project(autoware_autonomous_emergency_braking) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/control/autonomous_emergency_braking/README.md b/control/autoware_autonomous_emergency_braking/README.md similarity index 100% rename from control/autonomous_emergency_braking/README.md rename to control/autoware_autonomous_emergency_braking/README.md diff --git a/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml b/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml similarity index 100% rename from control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml rename to control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml diff --git a/control/autonomous_emergency_braking/image/obstacle_filtering_1.drawio.svg b/control/autoware_autonomous_emergency_braking/image/obstacle_filtering_1.drawio.svg similarity index 100% rename from control/autonomous_emergency_braking/image/obstacle_filtering_1.drawio.svg rename to control/autoware_autonomous_emergency_braking/image/obstacle_filtering_1.drawio.svg diff --git a/control/autonomous_emergency_braking/image/obstacle_filtering_2.drawio.svg b/control/autoware_autonomous_emergency_braking/image/obstacle_filtering_2.drawio.svg similarity index 100% rename from control/autonomous_emergency_braking/image/obstacle_filtering_2.drawio.svg rename to control/autoware_autonomous_emergency_braking/image/obstacle_filtering_2.drawio.svg diff --git a/control/autonomous_emergency_braking/image/range.drawio.svg b/control/autoware_autonomous_emergency_braking/image/range.drawio.svg similarity index 100% rename from control/autonomous_emergency_braking/image/range.drawio.svg rename to control/autoware_autonomous_emergency_braking/image/range.drawio.svg diff --git a/control/autonomous_emergency_braking/image/rss_check.drawio.svg b/control/autoware_autonomous_emergency_braking/image/rss_check.drawio.svg similarity index 100% rename from control/autonomous_emergency_braking/image/rss_check.drawio.svg rename to control/autoware_autonomous_emergency_braking/image/rss_check.drawio.svg diff --git a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp b/control/autoware_autonomous_emergency_braking/include/autoware_autonomous_emergency_braking/node.hpp similarity index 98% rename from control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp rename to control/autoware_autonomous_emergency_braking/include/autoware_autonomous_emergency_braking/node.hpp index 81ab2ecff790b..b87f421de7c8c 100644 --- a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp +++ b/control/autoware_autonomous_emergency_braking/include/autoware_autonomous_emergency_braking/node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_ -#define AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_ +#ifndef AUTOWARE_AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_ +#define AUTOWARE_AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_ #include #include @@ -340,4 +340,4 @@ class AEB : public rclcpp::Node }; } // namespace autoware::motion::control::autonomous_emergency_braking -#endif // AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_ +#endif // AUTOWARE_AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_ diff --git a/control/autonomous_emergency_braking/launch/autonomous_emergency_braking.launch.xml b/control/autoware_autonomous_emergency_braking/launch/autoware_autonomous_emergency_braking.launch.xml similarity index 74% rename from control/autonomous_emergency_braking/launch/autonomous_emergency_braking.launch.xml rename to control/autoware_autonomous_emergency_braking/launch/autoware_autonomous_emergency_braking.launch.xml index cf6640ec6be52..75b1a9dcf822d 100644 --- a/control/autonomous_emergency_braking/launch/autonomous_emergency_braking.launch.xml +++ b/control/autoware_autonomous_emergency_braking/launch/autoware_autonomous_emergency_braking.launch.xml @@ -1,12 +1,12 @@ - + - + diff --git a/control/autonomous_emergency_braking/package.xml b/control/autoware_autonomous_emergency_braking/package.xml similarity index 96% rename from control/autonomous_emergency_braking/package.xml rename to control/autoware_autonomous_emergency_braking/package.xml index bf27e6b7e1575..221fc2c000826 100644 --- a/control/autonomous_emergency_braking/package.xml +++ b/control/autoware_autonomous_emergency_braking/package.xml @@ -1,7 +1,7 @@ - autonomous_emergency_braking + autoware_autonomous_emergency_braking 0.1.0 Autonomous Emergency Braking package as a ROS 2 node Takamasa Horibe diff --git a/control/autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp similarity index 99% rename from control/autonomous_emergency_braking/src/node.cpp rename to control/autoware_autonomous_emergency_braking/src/node.cpp index 71eb92a4e95fb..3ec8cc68df9b1 100644 --- a/control/autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autonomous_emergency_braking/node.hpp" +#include "autoware_autonomous_emergency_braking/node.hpp" #include #include diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index d9e6e3e6757d6..a4f896048739f 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -139,7 +139,7 @@ def launch_setup(context, *args, **kwargs): # autonomous emergency braking autonomous_emergency_braking = ComposableNode( - package="autonomous_emergency_braking", + package="autoware_autonomous_emergency_braking", plugin="autoware::motion::control::autonomous_emergency_braking::AEB", name="autonomous_emergency_braking", remappings=[ diff --git a/system/system_error_monitor/config/diagnostic_aggregator/control.param.yaml b/system/system_error_monitor/config/diagnostic_aggregator/control.param.yaml index a1ebddee73e2a..3c8a5c77b2e44 100644 --- a/system/system_error_monitor/config/diagnostic_aggregator/control.param.yaml +++ b/system/system_error_monitor/config/diagnostic_aggregator/control.param.yaml @@ -6,7 +6,7 @@ analyzers: autonomous_emergency_braking: type: diagnostic_aggregator/AnalyzerGroup - path: autonomous_emergency_braking + path: autoware_autonomous_emergency_braking analyzers: performance_monitoring: type: diagnostic_aggregator/AnalyzerGroup diff --git a/system/system_error_monitor/config/system_error_monitor.param.yaml b/system/system_error_monitor/config/system_error_monitor.param.yaml index d3fc221bac768..63fdbd0081af6 100644 --- a/system/system_error_monitor/config/system_error_monitor.param.yaml +++ b/system/system_error_monitor/config/system_error_monitor.param.yaml @@ -20,7 +20,7 @@ /autoware/control/autonomous_driving/node_alive_monitoring: default /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default /autoware/control/control_command_gate/node_alive_monitoring: default - /autoware/control/autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error", auto_recovery: "false"} + /autoware/control/autoware_autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error", auto_recovery: "false"} /autoware/localization/node_alive_monitoring: default /autoware/localization/performance_monitoring/scan_matching_status: { sf_at: "warn", lf_at: "none", spf_at: "none" } @@ -45,7 +45,7 @@ external_control: /autoware/control/control_command_gate/node_alive_monitoring: default - /autoware/control/autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error", auto_recovery: "false"} + /autoware/control/autoware_autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error", auto_recovery: "false"} /autoware/control/external_control/external_command_selector/node_alive_monitoring: default /autoware/system/node_alive_monitoring: default diff --git a/system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml b/system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml index 43e8c56353a36..c9ab89a8fce96 100644 --- a/system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml +++ b/system/system_error_monitor/config/system_error_monitor.planning_simulation.param.yaml @@ -20,7 +20,7 @@ /autoware/control/autonomous_driving/node_alive_monitoring: default /autoware/control/autonomous_driving/performance_monitoring/lane_departure: default /autoware/control/control_command_gate/node_alive_monitoring: default - /autoware/control/autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error", auto_recovery: "false"} + /autoware/control/autoware_autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error", auto_recovery: "false"} /autoware/localization/node_alive_monitoring: default # /autoware/localization/performance_monitoring/scan_matching_status: { sf_at: "warn", lf_at: "none", spf_at: "none" } @@ -46,7 +46,7 @@ external_control: /autoware/control/control_command_gate/node_alive_monitoring: default - /autoware/control/autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error", auto_recovery: "false"} + /autoware/control/autoware_autonomous_emergency_braking/performance_monitoring/emergency_stop: { sf_at: "none", lf_at: "warn", spf_at: "error", auto_recovery: "false"} /autoware/control/external_control/external_command_selector/node_alive_monitoring: default /autoware/system/node_alive_monitoring: default From f93e5b3e671d865662dafa14bc2a585c1cecf47b Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Fri, 7 Jun 2024 22:54:15 +0900 Subject: [PATCH 29/65] refactor(rtc_interface)!: prefix package and namespace with autoware (#7321) refactor(rtc_interface): add autoware prefix Signed-off-by: Fumiya Watanabe --- planning/.pages | 2 +- .../package.xml | 2 +- .../interface/scene_module_interface.hpp | 4 ++-- .../package.xml | 2 +- .../package.xml | 2 +- .../package.xml | 2 +- .../package.xml | 2 +- .../scene_module_interface.hpp | 4 ++-- .../package.xml | 2 +- .../CMakeLists.txt | 4 ++-- .../README.md | 18 +++++++++--------- .../autoware_rtc_interface}/rtc_interface.hpp | 10 +++++----- .../package.xml | 4 ++-- .../src/rtc_interface.cpp | 6 +++--- .../package.xml | 2 +- .../package.xml | 2 +- .../package.xml | 2 +- 17 files changed, 35 insertions(+), 35 deletions(-) rename planning/{rtc_interface => autoware_rtc_interface}/CMakeLists.txt (85%) rename planning/{rtc_interface => autoware_rtc_interface}/README.md (79%) rename planning/{rtc_interface/include/rtc_interface => autoware_rtc_interface/include/autoware_rtc_interface}/rtc_interface.hpp (94%) rename planning/{rtc_interface => autoware_rtc_interface}/package.xml (88%) rename planning/{rtc_interface => autoware_rtc_interface}/src/rtc_interface.cpp (98%) diff --git a/planning/.pages b/planning/.pages index 6e3c6d5d49104..2decfad30e0da 100644 --- a/planning/.pages +++ b/planning/.pages @@ -77,7 +77,7 @@ nav: - 'External Velocity Limit Selector': planning/autoware_external_velocity_limit_selector - 'Objects of Interest Marker Interface': planning/objects_of_interest_marker_interface - 'Route Handler': planning/route_handler - - 'RTC Interface': planning/rtc_interface + - 'RTC Interface': planning/autoware_rtc_interface - 'Additional Tools': - 'Remaining Distance Time Calculator': planning/autoware_remaining_distance_time_calculator - 'RTC Replayer': planning/rtc_replayer diff --git a/planning/autoware_behavior_path_external_request_lane_change_module/package.xml b/planning/autoware_behavior_path_external_request_lane_change_module/package.xml index 26b78f5cf8cf1..9410be5a0011c 100644 --- a/planning/autoware_behavior_path_external_request_lane_change_module/package.xml +++ b/planning/autoware_behavior_path_external_request_lane_change_module/package.xml @@ -19,12 +19,12 @@ eigen3_cmake_module autoware_behavior_path_planner_common + autoware_rtc_interface behavior_path_lane_change_module behavior_path_planner motion_utils pluginlib rclcpp - rtc_interface tier4_autoware_utils tier4_planning_msgs visualization_msgs diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/interface/scene_module_interface.hpp index 97f249e0e7d6e..ebbb795a699b5 100644 --- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/interface/scene_module_interface.hpp @@ -22,6 +22,7 @@ #include #include +#include #include #include #include @@ -29,7 +30,6 @@ #include #include #include -#include #include #include #include @@ -56,11 +56,11 @@ namespace behavior_path_planner { +using autoware::rtc_interface::RTCInterface; using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::SteeringFactor; using objects_of_interest_marker_interface::ColorName; using objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; -using rtc_interface::RTCInterface; using steering_factor_interface::SteeringFactorInterface; using tier4_autoware_utils::calcOffsetPose; using tier4_autoware_utils::generateUUID; diff --git a/planning/autoware_behavior_path_planner_common/package.xml b/planning/autoware_behavior_path_planner_common/package.xml index 24d369e475e61..b6fb6a352e91e 100644 --- a/planning/autoware_behavior_path_planner_common/package.xml +++ b/planning/autoware_behavior_path_planner_common/package.xml @@ -46,6 +46,7 @@ autoware_lane_departure_checker autoware_perception_msgs autoware_planning_msgs + autoware_rtc_interface freespace_planning_algorithms geometry_msgs interpolation @@ -56,7 +57,6 @@ objects_of_interest_marker_interface rclcpp route_handler - rtc_interface tf2 tier4_autoware_utils tier4_planning_msgs diff --git a/planning/autoware_behavior_path_start_planner_module/package.xml b/planning/autoware_behavior_path_start_planner_module/package.xml index 8504241c908ce..e4d6de4324bfe 100644 --- a/planning/autoware_behavior_path_start_planner_module/package.xml +++ b/planning/autoware_behavior_path_start_planner_module/package.xml @@ -21,11 +21,11 @@ eigen3_cmake_module autoware_behavior_path_planner_common + autoware_rtc_interface behavior_path_planner motion_utils pluginlib rclcpp - rtc_interface tier4_autoware_utils tier4_planning_msgs visualization_msgs diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/package.xml b/planning/autoware_behavior_path_static_obstacle_avoidance_module/package.xml index a36a5c73729cb..e3699306df1f3 100644 --- a/planning/autoware_behavior_path_static_obstacle_avoidance_module/package.xml +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/package.xml @@ -23,6 +23,7 @@ autoware_behavior_path_planner_common autoware_perception_msgs + autoware_rtc_interface behavior_path_planner geometry_msgs lanelet2_extension @@ -32,7 +33,6 @@ pluginlib rclcpp route_handler - rtc_interface sensor_msgs signal_processing tf2 diff --git a/planning/autoware_behavior_velocity_intersection_module/package.xml b/planning/autoware_behavior_velocity_intersection_module/package.xml index 401e53586c649..0655867951ed8 100644 --- a/planning/autoware_behavior_velocity_intersection_module/package.xml +++ b/planning/autoware_behavior_velocity_intersection_module/package.xml @@ -21,6 +21,7 @@ autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs + autoware_rtc_interface fmt geometry_msgs interpolation @@ -32,7 +33,6 @@ pluginlib rclcpp route_handler - rtc_interface tf2_geometry_msgs tier4_autoware_utils tier4_planning_msgs diff --git a/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/scene_module_interface.hpp b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/scene_module_interface.hpp index 53b6e064d73b4..a97346297c9ac 100644 --- a/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/scene_module_interface.hpp @@ -16,11 +16,11 @@ #define AUTOWARE_BEHAVIOR_VELOCITY_PLANNER_COMMON__SCENE_MODULE_INTERFACE_HPP_ #include +#include #include #include #include #include -#include #include #include @@ -48,12 +48,12 @@ namespace autoware::behavior_velocity_planner { +using autoware::rtc_interface::RTCInterface; using builtin_interfaces::msg::Time; using motion_utils::PlanningBehavior; using motion_utils::VelocityFactor; using objects_of_interest_marker_interface::ColorName; using objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; -using rtc_interface::RTCInterface; using tier4_autoware_utils::DebugPublisher; using tier4_autoware_utils::getOrDeclareParameter; using tier4_debug_msgs::msg::Float64Stamped; diff --git a/planning/autoware_behavior_velocity_planner_common/package.xml b/planning/autoware_behavior_velocity_planner_common/package.xml index 524387034e4b6..7ab991a247a63 100644 --- a/planning/autoware_behavior_velocity_planner_common/package.xml +++ b/planning/autoware_behavior_velocity_planner_common/package.xml @@ -23,6 +23,7 @@ autoware_map_msgs autoware_perception_msgs autoware_planning_msgs + autoware_rtc_interface autoware_velocity_smoother diagnostic_msgs eigen @@ -36,7 +37,6 @@ rclcpp rclcpp_components route_handler - rtc_interface sensor_msgs tf2 tf2_eigen diff --git a/planning/rtc_interface/CMakeLists.txt b/planning/autoware_rtc_interface/CMakeLists.txt similarity index 85% rename from planning/rtc_interface/CMakeLists.txt rename to planning/autoware_rtc_interface/CMakeLists.txt index fda6025b84e86..cd36121e6aee8 100644 --- a/planning/rtc_interface/CMakeLists.txt +++ b/planning/autoware_rtc_interface/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(rtc_interface) +project(autoware_rtc_interface) ### Compile options if(NOT CMAKE_CXX_STANDARD) @@ -12,7 +12,7 @@ endif() find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() -ament_auto_add_library(rtc_interface SHARED +ament_auto_add_library(autoware_rtc_interface SHARED src/rtc_interface.cpp ) diff --git a/planning/rtc_interface/README.md b/planning/autoware_rtc_interface/README.md similarity index 79% rename from planning/rtc_interface/README.md rename to planning/autoware_rtc_interface/README.md index 7f8f73edcc6b2..19d200592bcf3 100644 --- a/planning/rtc_interface/README.md +++ b/planning/autoware_rtc_interface/README.md @@ -10,7 +10,7 @@ RTC Interface is an interface to publish the decision status of behavior plannin ```c++ // Generate instance (in this example, "intersection" is selected) -rtc_interface::RTCInterface rtc_interface(node, "intersection"); +autoware::rtc_interface::RTCInterface rtc_interface(node, "intersection"); // Generate UUID const unique_identifier_msgs::msg::UUID uuid = generateUUID(getModuleId()); @@ -51,12 +51,12 @@ rtc_interface.removeCooperateStatus(uuid); ### RTCInterface (Constructor) ```c++ -rtc_interface::RTCInterface(rclcpp::Node & node, const std::string & name); +autoware::rtc_interface::RTCInterface(rclcpp::Node & node, const std::string & name); ``` #### Description -A constructor for `rtc_interface::RTCInterface`. +A constructor for `autoware::rtc_interface::RTCInterface`. #### Input @@ -72,7 +72,7 @@ An instance of `RTCInterface` ### publishCooperateStatus ```c++ -rtc_interface::publishCooperateStatus(const rclcpp::Time & stamp) +autoware::rtc_interface::publishCooperateStatus(const rclcpp::Time & stamp) ``` #### Description @@ -90,7 +90,7 @@ Nothing ### updateCooperateStatus ```c++ -rtc_interface::updateCooperateStatus(const unique_identifier_msgs::msg::UUID & uuid, const bool safe, const double start_distance, const double finish_distance, const rclcpp::Time & stamp) +autoware::rtc_interface::updateCooperateStatus(const unique_identifier_msgs::msg::UUID & uuid, const bool safe, const double start_distance, const double finish_distance, const rclcpp::Time & stamp) ``` #### Description @@ -113,7 +113,7 @@ Nothing ### removeCooperateStatus ```c++ -rtc_interface::removeCooperateStatus(const unique_identifier_msgs::msg::UUID & uuid) +autoware::rtc_interface::removeCooperateStatus(const unique_identifier_msgs::msg::UUID & uuid) ``` #### Description @@ -131,7 +131,7 @@ Nothing ### clearCooperateStatus ```c++ -rtc_interface::clearCooperateStatus() +autoware::rtc_interface::clearCooperateStatus() ``` #### Description @@ -149,7 +149,7 @@ Nothing ### isActivated ```c++ -rtc_interface::isActivated(const unique_identifier_msgs::msg::UUID & uuid) +autoware::rtc_interface::isActivated(const unique_identifier_msgs::msg::UUID & uuid) ``` #### Description @@ -169,7 +169,7 @@ If not, return `false`. ### isRegistered ```c++ -rtc_interface::isRegistered(const unique_identifier_msgs::msg::UUID & uuid) +autoware::rtc_interface::isRegistered(const unique_identifier_msgs::msg::UUID & uuid) ``` #### Description diff --git a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp b/planning/autoware_rtc_interface/include/autoware_rtc_interface/rtc_interface.hpp similarity index 94% rename from planning/rtc_interface/include/rtc_interface/rtc_interface.hpp rename to planning/autoware_rtc_interface/include/autoware_rtc_interface/rtc_interface.hpp index 7ab796321e041..8b435a6f8ed51 100644 --- a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp +++ b/planning/autoware_rtc_interface/include/autoware_rtc_interface/rtc_interface.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef RTC_INTERFACE__RTC_INTERFACE_HPP_ -#define RTC_INTERFACE__RTC_INTERFACE_HPP_ +#ifndef AUTOWARE_RTC_INTERFACE__RTC_INTERFACE_HPP_ +#define AUTOWARE_RTC_INTERFACE__RTC_INTERFACE_HPP_ #include "rclcpp/rclcpp.hpp" @@ -33,7 +33,7 @@ #include #include -namespace rtc_interface +namespace autoware::rtc_interface { using tier4_rtc_msgs::msg::AutoModeStatus; using tier4_rtc_msgs::msg::Command; @@ -101,6 +101,6 @@ class RTCInterface mutable std::mutex mutex_; }; -} // namespace rtc_interface +} // namespace autoware::rtc_interface -#endif // RTC_INTERFACE__RTC_INTERFACE_HPP_ +#endif // AUTOWARE_RTC_INTERFACE__RTC_INTERFACE_HPP_ diff --git a/planning/rtc_interface/package.xml b/planning/autoware_rtc_interface/package.xml similarity index 88% rename from planning/rtc_interface/package.xml rename to planning/autoware_rtc_interface/package.xml index 753e4df13908e..d08467d8f15a9 100644 --- a/planning/rtc_interface/package.xml +++ b/planning/autoware_rtc_interface/package.xml @@ -1,8 +1,8 @@ - rtc_interface + autoware_rtc_interface 0.1.0 - The rtc_interface package + The autoware_rtc_interface package Fumiya Watanabe Taiki Tanaka diff --git a/planning/rtc_interface/src/rtc_interface.cpp b/planning/autoware_rtc_interface/src/rtc_interface.cpp similarity index 98% rename from planning/rtc_interface/src/rtc_interface.cpp rename to planning/autoware_rtc_interface/src/rtc_interface.cpp index 77fe29b41d893..3389d08b9015e 100644 --- a/planning/rtc_interface/src/rtc_interface.cpp +++ b/planning/autoware_rtc_interface/src/rtc_interface.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "rtc_interface/rtc_interface.hpp" +#include "autoware_rtc_interface/rtc_interface.hpp" #include @@ -78,7 +78,7 @@ Module getModuleType(const std::string & module_name) } // namespace -namespace rtc_interface +namespace autoware::rtc_interface { RTCInterface::RTCInterface(rclcpp::Node * node, const std::string & name, const bool enable_rtc) : clock_{node->get_clock()}, @@ -363,4 +363,4 @@ bool RTCInterface::isLocked() const return is_locked_; } -} // namespace rtc_interface +} // namespace autoware::rtc_interface diff --git a/planning/behavior_path_avoidance_by_lane_change_module/package.xml b/planning/behavior_path_avoidance_by_lane_change_module/package.xml index 1b11b6d8d445d..57e30bd628e08 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/package.xml +++ b/planning/behavior_path_avoidance_by_lane_change_module/package.xml @@ -20,13 +20,13 @@ autoware_behavior_path_planner_common autoware_behavior_path_static_obstacle_avoidance_module + autoware_rtc_interface behavior_path_lane_change_module behavior_path_planner lanelet2_extension motion_utils pluginlib rclcpp - rtc_interface tier4_autoware_utils tier4_planning_msgs visualization_msgs diff --git a/planning/behavior_path_goal_planner_module/package.xml b/planning/behavior_path_goal_planner_module/package.xml index c5201c1d2d9a2..75ca5c264b523 100644 --- a/planning/behavior_path_goal_planner_module/package.xml +++ b/planning/behavior_path_goal_planner_module/package.xml @@ -21,11 +21,11 @@ eigen3_cmake_module autoware_behavior_path_planner_common + autoware_rtc_interface behavior_path_planner motion_utils pluginlib rclcpp - rtc_interface tier4_autoware_utils tier4_planning_msgs visualization_msgs diff --git a/planning/behavior_path_lane_change_module/package.xml b/planning/behavior_path_lane_change_module/package.xml index ee4089375376f..23fc8f61af2f3 100644 --- a/planning/behavior_path_lane_change_module/package.xml +++ b/planning/behavior_path_lane_change_module/package.xml @@ -20,11 +20,11 @@ eigen3_cmake_module autoware_behavior_path_planner_common + autoware_rtc_interface behavior_path_planner motion_utils pluginlib rclcpp - rtc_interface tier4_autoware_utils tier4_planning_msgs visualization_msgs From d891ef7b70cf5cf292e9a5f49d1289555aad3bb3 Mon Sep 17 00:00:00 2001 From: Amadeusz Szymko Date: Sat, 8 Jun 2024 00:04:57 +0900 Subject: [PATCH 30/65] feat(lidar_transfusion): add lidar_transfusion 3D detection package (#6890) * feat(lidar_transfusion): add lidar_transfusion 3D detection package Signed-off-by: amadeuszsz * style(pre-commit): autofix * style(lidar_transfusion): cpplint Signed-off-by: amadeuszsz * style(lidar_transfusion): cspell Signed-off-by: Amadeusz Szymko * fix(lidar_transfusion): CUDA mem allocation & inference input Signed-off-by: amadeuszsz * style(pre-commit): autofix * fix(lidar_transfusion): arrays size Signed-off-by: amadeuszsz * style(pre-commit): autofix * chore(lidar_transfusion): update maintainers Co-authored-by: Satoshi Tanaka <16330533+scepter914@users.noreply.github.com> Signed-off-by: amadeuszsz * fix(lidar_transfusion): array size & grid idx Signed-off-by: amadeuszsz * chore(lidar_transfusion): update maintainer email Signed-off-by: amadeuszsz * chore: added transfusion to the respective launchers Signed-off-by: Kenzo Lobos-Tsunekawa * refactor(lidar_transfusion): rename config Signed-off-by: amadeuszsz * refactor(lidar_transfusion): callback access specifier Signed-off-by: amadeuszsz * refactor(lidar_transfusion): pointers initialziation Signed-off-by: amadeuszsz * refactor(lidar_transfusion): change macros for constexpr Signed-off-by: amadeuszsz * refactor(lidar_transfusion): consts & uniform initialization Signed-off-by: amadeuszsz * refactor(lidar_transfusion): change to unique ptr & uniform initialization Signed-off-by: amadeuszsz * style(pre-commit): autofix * refactor(lidar_transfusion): use of config params Signed-off-by: amadeuszsz * refactor(lidar_transfusion): remove unnecessary condition Signed-off-by: amadeuszsz * style(lidar_transfusion): switch naming (CPU to HOST) Signed-off-by: amadeuszsz * refactor(lidar_transfusion): remove redundant device sync Signed-off-by: amadeuszsz * style(lidar_transfusion): intensity naming Signed-off-by: amadeuszsz * feat(lidar_transfusion): full network shape validation Signed-off-by: amadeuszsz * feat(lidar_transfusion): validate objects' orientation in host processing Signed-off-by: amadeuszsz * feat(lidar_transfusion): add json schema Signed-off-by: amadeuszsz * style(pre-commit): autofix * style(lidar_transfusion): affine matrix naming Signed-off-by: amadeuszsz * style(lidar_transfusion): transformed point naming Signed-off-by: amadeuszsz * refactor(lidar_transfusion): add param descriptor & arrays size check Signed-off-by: amadeuszsz * style(lidar_transfusion): affine matrix naming Signed-off-by: amadeuszsz * feat(lidar_transfusion): caching cloud input as device ptr Signed-off-by: amadeuszsz * fix(lidar_transfusion): logging Signed-off-by: amadeuszsz * chore(tier4_perception_launch): revert to centerpoint Signed-off-by: amadeuszsz * fix(lidar_transfusion): typo Signed-off-by: amadeuszsz * docs(lidar_transfusion): use hook for param description Signed-off-by: amadeuszsz * fix(lidar_transfusion): interpret eigen matrix as col major Signed-off-by: amadeuszsz * feat(lidar_transfusion): update to autware_msgs Signed-off-by: amadeuszsz --------- Signed-off-by: Amadeusz Szymko Signed-off-by: Kenzo Lobos-Tsunekawa Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kenzo Lobos Tsunekawa --- .../detection/detection.launch.xml | 2 +- .../detector/lidar_dnn_detector.launch.xml | 29 +- .../launch/perception.launch.xml | 2 +- perception/lidar_transfusion/CMakeLists.txt | 156 ++++++++ perception/lidar_transfusion/README.md | 113 ++++++ .../detection_class_remapper.param.yaml | 38 ++ .../config/transfusion.param.yaml | 20 ++ .../include/lidar_transfusion/cuda_utils.hpp | 126 +++++++ .../detection_class_remapper.hpp | 47 +++ .../lidar_transfusion_node.hpp | 73 ++++ .../lidar_transfusion/network/network_trt.hpp | 87 +++++ .../postprocess/circle_nms_kernel.hpp | 32 ++ .../postprocess/non_maximum_suppression.hpp | 80 +++++ .../postprocess/postprocess_kernel.hpp | 50 +++ .../preprocess/pointcloud_densification.hpp | 101 ++++++ .../preprocess/preprocess_kernel.hpp | 77 ++++ .../preprocess/voxel_generator.hpp | 70 ++++ .../include/lidar_transfusion/ros_utils.hpp | 39 ++ .../lidar_transfusion/transfusion_config.hpp | 161 +++++++++ .../lidar_transfusion/transfusion_trt.hpp | 114 ++++++ .../include/lidar_transfusion/utils.hpp | 103 ++++++ .../lidar_transfusion/visibility_control.hpp | 37 ++ .../launch/lidar_transfusion.launch.xml | 39 ++ .../lib/detection_class_remapper.cpp | 71 ++++ .../lib/network/network_trt.cpp | 332 ++++++++++++++++++ .../lib/postprocess/circle_nms_kernel.cu | 144 ++++++++ .../postprocess/non_maximum_suppression.cpp | 104 ++++++ .../lib/postprocess/postprocess_kernel.cu | 145 ++++++++ .../preprocess/pointcloud_densification.cpp | 117 ++++++ .../lib/preprocess/preprocess_kernel.cu | 208 +++++++++++ .../lib/preprocess/voxel_generator.cpp | 142 ++++++++ .../lidar_transfusion/lib/ros_utils.cpp | 83 +++++ .../lidar_transfusion/lib/transfusion_trt.cpp | 205 +++++++++++ perception/lidar_transfusion/package.xml | 34 ++ .../detection_class_remapper.schema.json | 72 ++++ .../schema/transfusion.schema.json | 160 +++++++++ .../src/lidar_transfusion_node.cpp | 178 ++++++++++ 37 files changed, 3587 insertions(+), 4 deletions(-) create mode 100644 perception/lidar_transfusion/CMakeLists.txt create mode 100644 perception/lidar_transfusion/README.md create mode 100644 perception/lidar_transfusion/config/detection_class_remapper.param.yaml create mode 100644 perception/lidar_transfusion/config/transfusion.param.yaml create mode 100644 perception/lidar_transfusion/include/lidar_transfusion/cuda_utils.hpp create mode 100644 perception/lidar_transfusion/include/lidar_transfusion/detection_class_remapper.hpp create mode 100644 perception/lidar_transfusion/include/lidar_transfusion/lidar_transfusion_node.hpp create mode 100644 perception/lidar_transfusion/include/lidar_transfusion/network/network_trt.hpp create mode 100644 perception/lidar_transfusion/include/lidar_transfusion/postprocess/circle_nms_kernel.hpp create mode 100644 perception/lidar_transfusion/include/lidar_transfusion/postprocess/non_maximum_suppression.hpp create mode 100644 perception/lidar_transfusion/include/lidar_transfusion/postprocess/postprocess_kernel.hpp create mode 100644 perception/lidar_transfusion/include/lidar_transfusion/preprocess/pointcloud_densification.hpp create mode 100644 perception/lidar_transfusion/include/lidar_transfusion/preprocess/preprocess_kernel.hpp create mode 100644 perception/lidar_transfusion/include/lidar_transfusion/preprocess/voxel_generator.hpp create mode 100644 perception/lidar_transfusion/include/lidar_transfusion/ros_utils.hpp create mode 100644 perception/lidar_transfusion/include/lidar_transfusion/transfusion_config.hpp create mode 100644 perception/lidar_transfusion/include/lidar_transfusion/transfusion_trt.hpp create mode 100644 perception/lidar_transfusion/include/lidar_transfusion/utils.hpp create mode 100644 perception/lidar_transfusion/include/lidar_transfusion/visibility_control.hpp create mode 100644 perception/lidar_transfusion/launch/lidar_transfusion.launch.xml create mode 100644 perception/lidar_transfusion/lib/detection_class_remapper.cpp create mode 100644 perception/lidar_transfusion/lib/network/network_trt.cpp create mode 100644 perception/lidar_transfusion/lib/postprocess/circle_nms_kernel.cu create mode 100644 perception/lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp create mode 100644 perception/lidar_transfusion/lib/postprocess/postprocess_kernel.cu create mode 100644 perception/lidar_transfusion/lib/preprocess/pointcloud_densification.cpp create mode 100644 perception/lidar_transfusion/lib/preprocess/preprocess_kernel.cu create mode 100644 perception/lidar_transfusion/lib/preprocess/voxel_generator.cpp create mode 100644 perception/lidar_transfusion/lib/ros_utils.cpp create mode 100644 perception/lidar_transfusion/lib/transfusion_trt.cpp create mode 100644 perception/lidar_transfusion/package.xml create mode 100644 perception/lidar_transfusion/schema/detection_class_remapper.schema.json create mode 100644 perception/lidar_transfusion/schema/transfusion.schema.json create mode 100644 perception/lidar_transfusion/src/lidar_transfusion_node.cpp diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml index 9c3e815e8abb4..7e389f5790051 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -5,7 +5,7 @@ - + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml index f941bc8d771b1..274b39be681b8 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml @@ -2,16 +2,41 @@ - + - + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index e1a2260f3ee6d..3ce78e3b29f29 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -47,7 +47,7 @@ - + diff --git a/perception/lidar_transfusion/CMakeLists.txt b/perception/lidar_transfusion/CMakeLists.txt new file mode 100644 index 0000000000000..c0e2d85f27e62 --- /dev/null +++ b/perception/lidar_transfusion/CMakeLists.txt @@ -0,0 +1,156 @@ +cmake_minimum_required(VERSION 3.14) +project(lidar_transfusion) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +add_compile_options(-Wno-deprecated-declarations) + +option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) + +# set flags for CUDA availability +option(CUDA_AVAIL "CUDA available" OFF) +find_package(CUDA) +if(CUDA_FOUND) + find_library(CUBLAS_LIBRARIES cublas HINTS + ${CUDA_TOOLKIT_ROOT_DIR}/lib64 + ${CUDA_TOOLKIT_ROOT_DIR}/lib + ) + if(CUDA_VERBOSE) + message("CUDA is available!") + message("CUDA Libs: ${CUDA_LIBRARIES}") + message("CUDA Headers: ${CUDA_INCLUDE_DIRS}") + endif() + # Note: cublas_device was depreciated in CUDA version 9.2 + # https://forums.developer.nvidia.com/t/where-can-i-find-libcublas-device-so-or-libcublas-device-a/67251/4 + # In LibTorch, CUDA_cublas_device_LIBRARY is used. + unset(CUDA_cublas_device_LIBRARY CACHE) + set(CUDA_AVAIL ON) +else() + message("CUDA NOT FOUND") + set(CUDA_AVAIL OFF) +endif() + +# set flags for TensorRT availability +option(TRT_AVAIL "TensorRT available" OFF) +# try to find the tensorRT modules +find_library(NVINFER nvinfer) +find_library(NVONNXPARSER nvonnxparser) +if(NVINFER AND NVONNXPARSER) + if(CUDA_VERBOSE) + message("TensorRT is available!") + message("NVINFER: ${NVINFER}") + message("NVONNXPARSER: ${NVONNXPARSER}") + endif() + set(TRT_AVAIL ON) +else() + message("TensorRT is NOT Available") + set(TRT_AVAIL OFF) +endif() + +# set flags for CUDNN availability +option(CUDNN_AVAIL "CUDNN available" OFF) +# try to find the CUDNN module +find_library(CUDNN_LIBRARY +NAMES libcudnn.so${__cudnn_ver_suffix} libcudnn${__cudnn_ver_suffix}.dylib ${__cudnn_lib_win_name} +PATHS $ENV{LD_LIBRARY_PATH} ${__libpath_cudart} ${CUDNN_ROOT_DIR} ${PC_CUDNN_LIBRARY_DIRS} ${CMAKE_INSTALL_PREFIX} +PATH_SUFFIXES lib lib64 bin +DOC "CUDNN library." +) +if(CUDNN_LIBRARY) + if(CUDA_VERBOSE) + message(STATUS "CUDNN is available!") + message(STATUS "CUDNN_LIBRARY: ${CUDNN_LIBRARY}") + endif() + set(CUDNN_AVAIL ON) +else() + message("CUDNN is NOT Available") + set(CUDNN_AVAIL OFF) +endif() + +if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) + find_package(ament_cmake_auto REQUIRED) + ament_auto_find_build_dependencies() + + include_directories( + include + ${CUDA_INCLUDE_DIRS} + ) + + if(CMAKE_BUILD_TYPE STREQUAL "Debug") + set(CMAKE_CUDA_FLAGS ${CMAKE_CUDA_FLAGS} "-g -G") + set(CUDA_NVCC_FLAGS "-g -G") + endif() + + ament_auto_add_library(transfusion_lib SHARED + lib/detection_class_remapper.cpp + lib/network/network_trt.cpp + lib/postprocess/non_maximum_suppression.cpp + lib/preprocess/voxel_generator.cpp + lib/preprocess/pointcloud_densification.cpp + lib/ros_utils.cpp + lib/transfusion_trt.cpp + ) + + cuda_add_library(transfusion_cuda_lib SHARED + lib/postprocess/circle_nms_kernel.cu + lib/postprocess/postprocess_kernel.cu + lib/preprocess/preprocess_kernel.cu + ) + + target_link_libraries(transfusion_lib + ${NVINFER} + ${NVONNXPARSER} + ${CUDA_LIBRARIES} + ${CUBLAS_LIBRARIES} + ${CUDA_curand_LIBRARY} + ${CUDNN_LIBRARY} + transfusion_cuda_lib + ) + + target_include_directories(transfusion_lib + PUBLIC + $ + $ + ) + + # To suppress unknown-pragmas error. The root-cause is CUB library in CUDA 11.6. + # This issue was fixed by https://github.com/NVIDIA/cub/commit/7d608bf1dc14553e2fb219eabeed80b76621b6fe + target_include_directories(transfusion_lib + SYSTEM PUBLIC + ${CUDA_INCLUDE_DIRS} + ) + + ament_auto_add_library(lidar_transfusion_component SHARED + src/lidar_transfusion_node.cpp + ) + + target_link_libraries(lidar_transfusion_component + transfusion_lib + ) + + rclcpp_components_register_node(lidar_transfusion_component + PLUGIN "lidar_transfusion::LidarTransfusionNode" + EXECUTABLE lidar_transfusion_node + ) + + if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + endif() + + ament_auto_package( + INSTALL_TO_SHARE + launch + config + ) + +else() + find_package(ament_cmake_auto REQUIRED) + ament_auto_find_build_dependencies() + + ament_auto_package( + INSTALL_TO_SHARE + launch + ) +endif() diff --git a/perception/lidar_transfusion/README.md b/perception/lidar_transfusion/README.md new file mode 100644 index 0000000000000..7974714720c32 --- /dev/null +++ b/perception/lidar_transfusion/README.md @@ -0,0 +1,113 @@ +# lidar_transfusion + +## Purpose + +The `lidar_transfusion` package is used for 3D object detection based on lidar data (x, y, z, intensity). + +## Inner-workings / Algorithms + +The implementation bases on TransFusion [1] work. It uses TensorRT library for data process and network inference. + +We trained the models using . + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| -------------------- | ------------------------------- | ----------------- | +| `~/input/pointcloud` | `sensor_msgs::msg::PointCloud2` | Input pointcloud. | + +### Output + +| Name | Type | Description | +| -------------------------------------- | ------------------------------------------------ | --------------------------- | +| `~/output/objects` | `autoware_perception_msgs::msg::DetectedObjects` | Detected objects. | +| `debug/cyclic_time_ms` | `tier4_debug_msgs::msg::Float64Stamped` | Cyclic time (ms). | +| `debug/pipeline_latency_ms` | `tier4_debug_msgs::msg::Float64Stamped` | Pipeline latency time (ms). | +| `debug/processing_time/preprocess_ms` | `tier4_debug_msgs::msg::Float64Stamped` | Preprocess (ms). | +| `debug/processing_time/inference_ms` | `tier4_debug_msgs::msg::Float64Stamped` | Inference time (ms). | +| `debug/processing_time/postprocess_ms` | `tier4_debug_msgs::msg::Float64Stamped` | Postprocess time (ms). | +| `debug/processing_time/total_ms` | `tier4_debug_msgs::msg::Float64Stamped` | Total processing time (ms). | + +## Parameters + +### TransFusion + +{{ json_to_markdown("perception/lidar_transfusion/schema/transfusion.schema.json") }} + +### Detection class remapper + +{{ json_to_markdown("perception/lidar_transfusion/schema/detection_class_remapper.schema.json") }} + +### The `build_only` option + +The `lidar_transfusion` node has `build_only` option to build the TensorRT engine file from the ONNX file. +Although it is preferred to move all the ROS parameters in `.param.yaml` file in Autoware Universe, the `build_only` option is not moved to the `.param.yaml` file for now, because it may be used as a flag to execute the build as a pre-task. You can execute with the following command: + +```bash +ros2 launch lidar_transfusion lidar_transfusion.launch.xml build_only:=true +``` + +### The `log_level` option + +The default logging severity level for `lidar_transfusion` is `info`. For debugging purposes, the developer may decrease severity level using `log_level` parameter: + +```bash +ros2 launch lidar_transfusion lidar_transfusion.launch.xml log_level:=debug +``` + +## Assumptions / Known limits + +## Trained Models + +You can download the onnx format of trained models by clicking on the links below. + +- TransFusion: [transfusion.onnx](https://awf.ml.dev.web.auto/perception/models/transfusion/v1/transfusion.onnx) + +The model was trained in TIER IV's internal database (~11k lidar frames) for 20 epochs. + +### Changelog + +## (Optional) Error detection and handling + + + +## (Optional) Performance characterization + + + +## References/External links + +[1] Xuyang Bai, Zeyu Hu, Xinge Zhu, Qingqiu Huang, Yilun Chen, Hongbo Fu and Chiew-Lan Tai. "TransFusion: Robust LiDAR-Camera Fusion for 3D Object Detection with Transformers." arXiv preprint arXiv:2203.11496 (2022). + +[2] + +[3] + +[4] + +[5] + +## (Optional) Future extensions / Unimplemented parts + + diff --git a/perception/lidar_transfusion/config/detection_class_remapper.param.yaml b/perception/lidar_transfusion/config/detection_class_remapper.param.yaml new file mode 100644 index 0000000000000..baea087c96bca --- /dev/null +++ b/perception/lidar_transfusion/config/detection_class_remapper.param.yaml @@ -0,0 +1,38 @@ +/**: + ros__parameters: + allow_remapping_by_area_matrix: + # NOTE(kl): We turn all vehicles into trailers if they go over 3x12 [m^2]. + # NOTE(kl): We turn cars into trucks if they have an area between 2.2 x 5.5 and 3.0 * 12.0 [m^2] + # row: original class. column: class to remap to + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN + [0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN + 0, 0, 1, 0, 1, 0, 0, 0, #CAR + 0, 0, 0, 0, 1, 0, 0, 0, #TRUCK + 0, 0, 0, 0, 1, 0, 0, 0, #BUS + 0, 0, 0, 0, 0, 0, 0, 0, #TRAILER + 0, 0, 0, 0, 0, 0, 0, 0, #MOTORBIKE + 0, 0, 0, 0, 0, 0, 0, 0, #BICYCLE + 0, 0, 0, 0, 0, 0, 0, 0] #PEDESTRIAN + + min_area_matrix: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN + 0.000, 0.000, 12.100, 0.000, 36.000, 0.000, 0.000, 0.000, #CAR + 0.000, 0.000, 0.000, 0.000, 36.000, 0.000, 0.000, 0.000, #TRUCK + 0.000, 0.000, 0.000, 0.000, 36.000, 0.000, 0.000, 0.000, #BUS + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000] #PEDESTRIAN + + + max_area_matrix: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN + 0.000, 0.000, 36.000, 0.000, 999.999, 0.000, 0.000, 0.000, #CAR + 0.000, 0.000, 0.000, 0.000, 999.999, 0.000, 0.000, 0.000, #TRUCK + 0.000, 0.000, 0.000, 0.000, 999.999, 0.000, 0.000, 0.000, #BUS + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000] #PEDESTRIAN diff --git a/perception/lidar_transfusion/config/transfusion.param.yaml b/perception/lidar_transfusion/config/transfusion.param.yaml new file mode 100644 index 0000000000000..feabe359caf1f --- /dev/null +++ b/perception/lidar_transfusion/config/transfusion.param.yaml @@ -0,0 +1,20 @@ +/**: + ros__parameters: + # network + class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] + trt_precision: fp16 + voxels_num: [5000, 30000, 60000] # [min, opt, max] + point_cloud_range: [-76.8, -76.8, -3.0, 76.8, 76.8, 5.0] # [x_min, y_min, z_min, x_max, y_max, z_max] + voxel_size: [0.3, 0.3, 8.0] # [x, y, z] + onnx_path: "$(var model_path)/transfusion.onnx" + engine_path: "$(var model_path)/transfusion.engine" + # pre-process params + densification_num_past_frames: 1 + densification_world_frame_id: map + # post-process params + circle_nms_dist_threshold: 0.5 + iou_nms_target_class_names: ["CAR"] + iou_nms_search_distance_2d: 10.0 + iou_nms_threshold: 0.1 + yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] # refers to the class_names + score_threshold: 0.2 diff --git a/perception/lidar_transfusion/include/lidar_transfusion/cuda_utils.hpp b/perception/lidar_transfusion/include/lidar_transfusion/cuda_utils.hpp new file mode 100644 index 0000000000000..5c25a936d5392 --- /dev/null +++ b/perception/lidar_transfusion/include/lidar_transfusion/cuda_utils.hpp @@ -0,0 +1,126 @@ +// 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. +/* + * Copyright (c) 2020, NVIDIA CORPORATION. All rights reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +/* + * This code is licensed under CC0 1.0 Universal (Public Domain). + * You can use this without any limitation. + * https://creativecommons.org/publicdomain/zero/1.0/deed.en + */ + +#ifndef LIDAR_TRANSFUSION__CUDA_UTILS_HPP_ +#define LIDAR_TRANSFUSION__CUDA_UTILS_HPP_ + +#include + +#include +#include +#include +#include + +#define CHECK_CUDA_ERROR(e) (cuda::check_error(e, __FILE__, __LINE__)) + +namespace cuda +{ +inline void check_error(const ::cudaError_t e, const char * f, int n) +{ + if (e != ::cudaSuccess) { + ::std::stringstream s; + s << ::cudaGetErrorName(e) << " (" << e << ")@" << f << "#L" << n << ": " + << ::cudaGetErrorString(e); + throw ::std::runtime_error{s.str()}; + } +} + +struct deleter +{ + void operator()(void * p) const { CHECK_CUDA_ERROR(::cudaFree(p)); } +}; + +template +using unique_ptr = ::std::unique_ptr; + +template +typename ::std::enable_if<::std::is_array::value, cuda::unique_ptr>::type make_unique( + const ::std::size_t n) +{ + using U = typename ::std::remove_extent::type; + U * p; + CHECK_CUDA_ERROR(::cudaMalloc(reinterpret_cast(&p), sizeof(U) * n)); + return cuda::unique_ptr{p}; +} + +template +cuda::unique_ptr make_unique() +{ + T * p; + CHECK_CUDA_ERROR(::cudaMalloc(reinterpret_cast(&p), sizeof(T))); + return cuda::unique_ptr{p}; +} + +constexpr size_t CUDA_ALIGN = 256; + +template +inline size_t get_size_aligned(size_t num_elem) +{ + size_t size = num_elem * sizeof(T); + size_t extra_align = 0; + if (size % CUDA_ALIGN != 0) { + extra_align = CUDA_ALIGN - size % CUDA_ALIGN; + } + return size + extra_align; +} + +template +inline T * get_next_ptr(size_t num_elem, void *& workspace, size_t & workspace_size) +{ + size_t size = get_size_aligned(num_elem); + if (size > workspace_size) { + throw ::std::runtime_error("Workspace is too small!"); + } + workspace_size -= size; + T * ptr = reinterpret_cast(workspace); + workspace = reinterpret_cast(reinterpret_cast(workspace) + size); + return ptr; +} + +template +void clear_async(T * ptr, size_t num_elem, cudaStream_t stream) +{ + CHECK_CUDA_ERROR(::cudaMemsetAsync(ptr, 0, sizeof(T) * num_elem, stream)); +} + +} // namespace cuda + +#endif // LIDAR_TRANSFUSION__CUDA_UTILS_HPP_ diff --git a/perception/lidar_transfusion/include/lidar_transfusion/detection_class_remapper.hpp b/perception/lidar_transfusion/include/lidar_transfusion/detection_class_remapper.hpp new file mode 100644 index 0000000000000..ace7dc5ff3405 --- /dev/null +++ b/perception/lidar_transfusion/include/lidar_transfusion/detection_class_remapper.hpp @@ -0,0 +1,47 @@ +// 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 LIDAR_TRANSFUSION__DETECTION_CLASS_REMAPPER_HPP_ +#define LIDAR_TRANSFUSION__DETECTION_CLASS_REMAPPER_HPP_ + +#include + +#include +#include +#include +#include + +#include + +namespace lidar_transfusion +{ + +class DetectionClassRemapper +{ +public: + void setParameters( + const std::vector & allow_remapping_by_area_matrix, + const std::vector & min_area_matrix, const std::vector & max_area_matrix); + void mapClasses(autoware_perception_msgs::msg::DetectedObjects & msg); + +protected: + Eigen::Matrix allow_remapping_by_area_matrix_; + Eigen::MatrixXd min_area_matrix_; + Eigen::MatrixXd max_area_matrix_; + int num_labels_; +}; + +} // namespace lidar_transfusion + +#endif // LIDAR_TRANSFUSION__DETECTION_CLASS_REMAPPER_HPP_ diff --git a/perception/lidar_transfusion/include/lidar_transfusion/lidar_transfusion_node.hpp b/perception/lidar_transfusion/include/lidar_transfusion/lidar_transfusion_node.hpp new file mode 100644 index 0000000000000..86303618d7877 --- /dev/null +++ b/perception/lidar_transfusion/include/lidar_transfusion/lidar_transfusion_node.hpp @@ -0,0 +1,73 @@ +// 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 LIDAR_TRANSFUSION__LIDAR_TRANSFUSION_NODE_HPP_ +#define LIDAR_TRANSFUSION__LIDAR_TRANSFUSION_NODE_HPP_ + +#include "lidar_transfusion/detection_class_remapper.hpp" +#include "lidar_transfusion/postprocess/non_maximum_suppression.hpp" +#include "lidar_transfusion/preprocess/pointcloud_densification.hpp" +#include "lidar_transfusion/transfusion_trt.hpp" +#include "lidar_transfusion/visibility_control.hpp" + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +namespace lidar_transfusion +{ + +class LIDAR_TRANSFUSION_PUBLIC LidarTransfusionNode : public rclcpp::Node +{ +public: + explicit LidarTransfusionNode(const rclcpp::NodeOptions & options); + +private: + void cloudCallback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg); + + rclcpp::Subscription::ConstSharedPtr cloud_sub_{nullptr}; + rclcpp::Publisher::SharedPtr objects_pub_{ + nullptr}; + + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_{tf_buffer_}; + + DetectionClassRemapper detection_class_remapper_; + float score_threshold_{0.0}; + std::vector class_names_; + + NonMaximumSuppression iou_bev_nms_; + + std::unique_ptr detector_ptr_{nullptr}; + + // debugger + std::unique_ptr> stop_watch_ptr_{ + nullptr}; + std::unique_ptr debug_publisher_ptr_{nullptr}; + std::unique_ptr published_time_pub_{nullptr}; +}; +} // namespace lidar_transfusion + +#endif // LIDAR_TRANSFUSION__LIDAR_TRANSFUSION_NODE_HPP_ diff --git a/perception/lidar_transfusion/include/lidar_transfusion/network/network_trt.hpp b/perception/lidar_transfusion/include/lidar_transfusion/network/network_trt.hpp new file mode 100644 index 0000000000000..3f8f32e346b0a --- /dev/null +++ b/perception/lidar_transfusion/include/lidar_transfusion/network/network_trt.hpp @@ -0,0 +1,87 @@ +// 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 LIDAR_TRANSFUSION__NETWORK__NETWORK_TRT_HPP_ +#define LIDAR_TRANSFUSION__NETWORK__NETWORK_TRT_HPP_ + +#include "lidar_transfusion/transfusion_config.hpp" +#include "lidar_transfusion/utils.hpp" + +#include + +#include + +#include +#include +#include +#include +#include +#include + +namespace lidar_transfusion +{ + +struct ProfileDimension +{ + nvinfer1::Dims min; + nvinfer1::Dims opt; + nvinfer1::Dims max; + + bool operator!=(const ProfileDimension & rhs) const + { + return min.nbDims != rhs.min.nbDims || opt.nbDims != rhs.opt.nbDims || + max.nbDims != rhs.max.nbDims || !std::equal(min.d, min.d + min.nbDims, rhs.min.d) || + !std::equal(opt.d, opt.d + opt.nbDims, rhs.opt.d) || + !std::equal(max.d, max.d + max.nbDims, rhs.max.d); + } +}; + +class NetworkTRT +{ +public: + explicit NetworkTRT(const TransfusionConfig & config); + ~NetworkTRT(); + + bool init( + const std::string & onnx_path, const std::string & engine_path, const std::string & precision); + const char * getTensorName(NetworkIO name); + + tensorrt_common::TrtUniquePtr engine{nullptr}; + tensorrt_common::TrtUniquePtr context{nullptr}; + +private: + bool parseONNX( + const std::string & onnx_path, const std::string & engine_path, const std::string & precision, + size_t workspace_size = (1ULL << 30)); + bool saveEngine(const std::string & engine_path); + bool loadEngine(const std::string & engine_path); + bool createContext(); + bool setProfile( + nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, + nvinfer1::IBuilderConfig & config); + bool validateNetworkIO(); + nvinfer1::Dims validateTensorShape(NetworkIO name, const std::vector shape); + + tensorrt_common::TrtUniquePtr runtime_{nullptr}; + tensorrt_common::TrtUniquePtr plan_{nullptr}; + tensorrt_common::Logger logger_; + TransfusionConfig config_; + std::vector tensors_names_; + + std::array in_profile_dims_; +}; + +} // namespace lidar_transfusion + +#endif // LIDAR_TRANSFUSION__NETWORK__NETWORK_TRT_HPP_ diff --git a/perception/lidar_transfusion/include/lidar_transfusion/postprocess/circle_nms_kernel.hpp b/perception/lidar_transfusion/include/lidar_transfusion/postprocess/circle_nms_kernel.hpp new file mode 100644 index 0000000000000..e231482652b98 --- /dev/null +++ b/perception/lidar_transfusion/include/lidar_transfusion/postprocess/circle_nms_kernel.hpp @@ -0,0 +1,32 @@ +// 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 LIDAR_TRANSFUSION__POSTPROCESS__CIRCLE_NMS_KERNEL_HPP_ +#define LIDAR_TRANSFUSION__POSTPROCESS__CIRCLE_NMS_KERNEL_HPP_ + +#include "lidar_transfusion/utils.hpp" + +#include + +namespace lidar_transfusion +{ +// Non-maximum suppression (NMS) uses the distance on the xy plane instead of +// intersection over union (IoU) to suppress overlapped objects. +std::size_t circleNMS( + thrust::device_vector & boxes3d, const float distance_threshold, + thrust::device_vector & keep_mask, cudaStream_t stream); + +} // namespace lidar_transfusion + +#endif // LIDAR_TRANSFUSION__POSTPROCESS__CIRCLE_NMS_KERNEL_HPP_ diff --git a/perception/lidar_transfusion/include/lidar_transfusion/postprocess/non_maximum_suppression.hpp b/perception/lidar_transfusion/include/lidar_transfusion/postprocess/non_maximum_suppression.hpp new file mode 100644 index 0000000000000..daf2cc7c1fac1 --- /dev/null +++ b/perception/lidar_transfusion/include/lidar_transfusion/postprocess/non_maximum_suppression.hpp @@ -0,0 +1,80 @@ +// 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 LIDAR_TRANSFUSION__POSTPROCESS__NON_MAXIMUM_SUPPRESSION_HPP_ +#define LIDAR_TRANSFUSION__POSTPROCESS__NON_MAXIMUM_SUPPRESSION_HPP_ + +#include "lidar_transfusion/ros_utils.hpp" + +#include + +#include + +#include +#include + +namespace lidar_transfusion +{ +using autoware_perception_msgs::msg::DetectedObject; + +enum class NMS_TYPE { + IoU_BEV + // IoU_3D + // Distance_2D + // Distance_3D +}; + +struct NMSParams +{ + NMS_TYPE nms_type_{}; + std::vector target_class_names_{}; + double search_distance_2d_{}; + double iou_threshold_{}; + // double distance_threshold_{}; +}; + +std::vector classNamesToBooleanMask(const std::vector & class_names) +{ + std::vector mask; + constexpr std::size_t num_object_classification = 8; + mask.resize(num_object_classification); + for (const auto & class_name : class_names) { + const auto semantic_type = getSemanticType(class_name); + mask.at(semantic_type) = true; + } + + return mask; +} + +class NonMaximumSuppression +{ +public: + void setParameters(const NMSParams &); + + std::vector apply(const std::vector &); + +private: + bool isTargetLabel(const std::uint8_t); + + bool isTargetPairObject(const DetectedObject &, const DetectedObject &); + + Eigen::MatrixXd generateIoUMatrix(const std::vector &); + + NMSParams params_{}; + std::vector target_class_mask_{}; +}; + +} // namespace lidar_transfusion + +#endif // LIDAR_TRANSFUSION__POSTPROCESS__NON_MAXIMUM_SUPPRESSION_HPP_ diff --git a/perception/lidar_transfusion/include/lidar_transfusion/postprocess/postprocess_kernel.hpp b/perception/lidar_transfusion/include/lidar_transfusion/postprocess/postprocess_kernel.hpp new file mode 100644 index 0000000000000..01435424aa248 --- /dev/null +++ b/perception/lidar_transfusion/include/lidar_transfusion/postprocess/postprocess_kernel.hpp @@ -0,0 +1,50 @@ +// 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 LIDAR_TRANSFUSION__POSTPROCESS__POSTPROCESS_KERNEL_HPP_ +#define LIDAR_TRANSFUSION__POSTPROCESS__POSTPROCESS_KERNEL_HPP_ + +#include "lidar_transfusion/transfusion_config.hpp" +#include "lidar_transfusion/utils.hpp" + +#include +#include +#include + +#include + +namespace lidar_transfusion +{ + +class PostprocessCuda +{ +public: + explicit PostprocessCuda(const TransfusionConfig & config, cudaStream_t & stream); + + cudaError_t generateDetectedBoxes3D_launch( + const float * cls_output, const float * box_output, const float * dir_cls_output, + std::vector & det_boxes3d, cudaStream_t stream); + +private: + TransfusionConfig config_; + cudaStream_t stream_; + cudaStream_t stream_event_; + cudaEvent_t start_, stop_; + thrust::device_vector boxes3d_d_; + thrust::device_vector yaw_norm_thresholds_d_; +}; + +} // namespace lidar_transfusion + +#endif // LIDAR_TRANSFUSION__POSTPROCESS__POSTPROCESS_KERNEL_HPP_ diff --git a/perception/lidar_transfusion/include/lidar_transfusion/preprocess/pointcloud_densification.hpp b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/pointcloud_densification.hpp new file mode 100644 index 0000000000000..25095f4dc9c0b --- /dev/null +++ b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/pointcloud_densification.hpp @@ -0,0 +1,101 @@ +// 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 LIDAR_TRANSFUSION__PREPROCESS__POINTCLOUD_DENSIFICATION_HPP_ +#define LIDAR_TRANSFUSION__PREPROCESS__POINTCLOUD_DENSIFICATION_HPP_ + +#include "lidar_transfusion/cuda_utils.hpp" + +#include +#include +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +#include +#include +#include + +namespace lidar_transfusion +{ + +class DensificationParam +{ +public: + DensificationParam(const std::string & world_frame_id, const unsigned int num_past_frames) + : world_frame_id_(std::move(world_frame_id)), + pointcloud_cache_size_(num_past_frames + /*current frame*/ 1) + { + } + + std::string world_frame_id() const { return world_frame_id_; } + unsigned int pointcloud_cache_size() const { return pointcloud_cache_size_; } + +private: + std::string world_frame_id_; + unsigned int pointcloud_cache_size_{1}; +}; + +struct PointCloudWithTransform +{ + cuda::unique_ptr points_d{nullptr}; + std_msgs::msg::Header header; + size_t num_points{0}; + Eigen::Affine3f affine_past2world; +}; + +class PointCloudDensification +{ +public: + explicit PointCloudDensification(const DensificationParam & param, cudaStream_t & stream); + + bool enqueuePointCloud( + const sensor_msgs::msg::PointCloud2 & 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(); + } + size_t getIdx(std::list::iterator iter) + { + return std::distance(pointcloud_cache_.begin(), iter); + } + size_t getCacheSize() + { + return std::distance(pointcloud_cache_.begin(), 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(); + + DensificationParam param_; + double current_timestamp_{0.0}; + Eigen::Affine3f affine_world2current_; + std::list pointcloud_cache_; + cudaStream_t stream_; +}; + +} // namespace lidar_transfusion + +#endif // LIDAR_TRANSFUSION__PREPROCESS__POINTCLOUD_DENSIFICATION_HPP_ diff --git a/perception/lidar_transfusion/include/lidar_transfusion/preprocess/preprocess_kernel.hpp b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/preprocess_kernel.hpp new file mode 100644 index 0000000000000..c571990d84b51 --- /dev/null +++ b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/preprocess_kernel.hpp @@ -0,0 +1,77 @@ +// 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. +/* + * SPDX-FileCopyrightText: Copyright (c) 2021 NVIDIA CORPORATION & AFFILIATES. + * All rights reserved. SPDX-License-Identifier: Apache-2.0 + * + * 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 LIDAR_TRANSFUSION__PREPROCESS__PREPROCESS_KERNEL_HPP_ +#define LIDAR_TRANSFUSION__PREPROCESS__PREPROCESS_KERNEL_HPP_ + +#include "lidar_transfusion/cuda_utils.hpp" +#include "lidar_transfusion/transfusion_config.hpp" +#include "lidar_transfusion/utils.hpp" + +#include + +namespace lidar_transfusion +{ + +class PreprocessCuda +{ +public: + PreprocessCuda(const TransfusionConfig & config, cudaStream_t & stream); + + void generateVoxels( + float * points, unsigned int points_size, unsigned int * pillar_num, float * voxel_features, + unsigned int * voxel_num, unsigned int * voxel_idxs); + + cudaError_t generateVoxels_random_launch( + float * points, unsigned int points_size, unsigned int * mask, float * voxels); + + cudaError_t generateBaseFeatures_launch( + unsigned int * mask, float * voxels, unsigned int * pillar_num, float * voxel_features, + unsigned int * voxel_num, unsigned int * voxel_idxs); + + // cudaError_t generateVoxelsInput_launch( + // uint8_t * cloud_data, CloudInfo & cloud_info, unsigned int points_agg, unsigned int + // points_size, float time_lag, float * affine_transform, float * points); + + cudaError_t generateSweepPoints_launch( + const float * input_points, size_t points_size, int input_point_step, float time_lag, + const float * transform, float * output_points); + +private: + TransfusionConfig config_; + cudaStream_t stream_; + cuda::unique_ptr mask_{nullptr}; + cuda::unique_ptr voxels_{nullptr}; + unsigned int mask_size_; + unsigned int voxels_size_; +}; +} // namespace lidar_transfusion + +#endif // LIDAR_TRANSFUSION__PREPROCESS__PREPROCESS_KERNEL_HPP_ diff --git a/perception/lidar_transfusion/include/lidar_transfusion/preprocess/voxel_generator.hpp b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/voxel_generator.hpp new file mode 100644 index 0000000000000..3e3660e238473 --- /dev/null +++ b/perception/lidar_transfusion/include/lidar_transfusion/preprocess/voxel_generator.hpp @@ -0,0 +1,70 @@ +// 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 LIDAR_TRANSFUSION__PREPROCESS__VOXEL_GENERATOR_HPP_ +#define LIDAR_TRANSFUSION__PREPROCESS__VOXEL_GENERATOR_HPP_ + +#include "lidar_transfusion/cuda_utils.hpp" +#include "lidar_transfusion/preprocess/pointcloud_densification.hpp" +#include "lidar_transfusion/preprocess/preprocess_kernel.hpp" +#include "lidar_transfusion/transfusion_config.hpp" +#include "lidar_transfusion/utils.hpp" + +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +#include + +#include +#include +#include +#include + +namespace lidar_transfusion +{ +constexpr size_t AFF_MAT_SIZE = 16; // 4x4 matrix +constexpr size_t MAX_CLOUD_STEP_SIZE = 35; // PointXYZIRCADT + +class VoxelGenerator +{ +public: + explicit VoxelGenerator( + const DensificationParam & densification_param, const TransfusionConfig & config, + cudaStream_t & stream); + std::size_t generateSweepPoints( + const sensor_msgs::msg::PointCloud2 & msg, cuda::unique_ptr & points_d); + bool enqueuePointCloud( + const sensor_msgs::msg::PointCloud2 & msg, const tf2_ros::Buffer & tf_buffer); + void initCloudInfo(const sensor_msgs::msg::PointCloud2 & msg); + std::tuple getFieldInfo( + const sensor_msgs::msg::PointCloud2 & msg, const std::string & field_name); + +private: + std::unique_ptr pd_ptr_{nullptr}; + std::unique_ptr pre_ptr_{nullptr}; + TransfusionConfig config_; + cuda::unique_ptr cloud_data_d_{nullptr}; + cuda::unique_ptr affine_past2current_d_{nullptr}; + std::vector points_; + cudaStream_t stream_; + CloudInfo cloud_info_; + bool is_initialized_{false}; +}; + +} // namespace lidar_transfusion + +#endif // LIDAR_TRANSFUSION__PREPROCESS__VOXEL_GENERATOR_HPP_ diff --git a/perception/lidar_transfusion/include/lidar_transfusion/ros_utils.hpp b/perception/lidar_transfusion/include/lidar_transfusion/ros_utils.hpp new file mode 100644 index 0000000000000..f013a02404a29 --- /dev/null +++ b/perception/lidar_transfusion/include/lidar_transfusion/ros_utils.hpp @@ -0,0 +1,39 @@ +// 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 LIDAR_TRANSFUSION__ROS_UTILS_HPP_ +#define LIDAR_TRANSFUSION__ROS_UTILS_HPP_ + +#include "lidar_transfusion/utils.hpp" + +#include +#include +#include +#include + +#include +#include + +namespace lidar_transfusion +{ + +void box3DToDetectedObject( + const Box3D & box3d, const std::vector & class_names, + autoware_perception_msgs::msg::DetectedObject & obj); + +uint8_t getSemanticType(const std::string & class_name); + +} // namespace lidar_transfusion + +#endif // LIDAR_TRANSFUSION__ROS_UTILS_HPP_ diff --git a/perception/lidar_transfusion/include/lidar_transfusion/transfusion_config.hpp b/perception/lidar_transfusion/include/lidar_transfusion/transfusion_config.hpp new file mode 100644 index 0000000000000..31976de56a9da --- /dev/null +++ b/perception/lidar_transfusion/include/lidar_transfusion/transfusion_config.hpp @@ -0,0 +1,161 @@ +// 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 LIDAR_TRANSFUSION__TRANSFUSION_CONFIG_HPP_ +#define LIDAR_TRANSFUSION__TRANSFUSION_CONFIG_HPP_ + +#include +#include + +namespace lidar_transfusion +{ + +class TransfusionConfig +{ +public: + TransfusionConfig( + const std::vector & voxels_num, const std::vector & point_cloud_range, + const std::vector & voxel_size, const float circle_nms_dist_threshold, + const std::vector & yaw_norm_thresholds, const float score_threshold) + { + if (voxels_num.size() == 3) { + max_voxels_ = voxels_num[2]; + + voxels_num_[0] = voxels_num[0]; + voxels_num_[1] = voxels_num[1]; + voxels_num_[2] = voxels_num[2]; + + min_voxel_size_ = voxels_num[0]; + opt_voxel_size_ = voxels_num[1]; + max_voxel_size_ = voxels_num[2]; + + min_points_size_ = voxels_num[0]; + opt_points_size_ = voxels_num[1]; + max_points_size_ = voxels_num[2]; + + min_coors_size_ = voxels_num[0]; + opt_coors_size_ = voxels_num[1]; + max_coors_size_ = voxels_num[2]; + } + if (point_cloud_range.size() == 6) { + min_x_range_ = static_cast(point_cloud_range[0]); + min_y_range_ = static_cast(point_cloud_range[1]); + min_z_range_ = static_cast(point_cloud_range[2]); + max_x_range_ = static_cast(point_cloud_range[3]); + max_y_range_ = static_cast(point_cloud_range[4]); + max_z_range_ = static_cast(point_cloud_range[5]); + } + if (voxel_size.size() == 3) { + voxel_x_size_ = static_cast(voxel_size[0]); + voxel_y_size_ = static_cast(voxel_size[1]); + voxel_z_size_ = static_cast(voxel_size[2]); + } + if (score_threshold > 0.0) { + score_threshold_ = score_threshold; + } + if (circle_nms_dist_threshold > 0.0) { + circle_nms_dist_threshold_ = circle_nms_dist_threshold; + } + yaw_norm_thresholds_ = + std::vector(yaw_norm_thresholds.begin(), yaw_norm_thresholds.end()); + for (auto & yaw_norm_threshold : yaw_norm_thresholds_) { + yaw_norm_threshold = + (yaw_norm_threshold >= 0.0 && yaw_norm_threshold < 1.0) ? yaw_norm_threshold : 0.0; + } + grid_x_size_ = static_cast((max_x_range_ - min_x_range_) / voxel_x_size_); + grid_y_size_ = static_cast((max_y_range_ - min_y_range_) / voxel_y_size_); + grid_z_size_ = static_cast((max_z_range_ - min_z_range_) / voxel_z_size_); + } + + ///// INPUT PARAMETERS ///// + const std::size_t cloud_capacity_{1000000}; + ///// KERNEL PARAMETERS ///// + const std::size_t threads_for_voxel_{256}; // threads number for a block + const std::size_t points_per_voxel_{20}; + const std::size_t warp_size_{32}; // one warp(32 threads) for one pillar + const std::size_t pillars_per_block_{64}; // one thread deals with one pillar + // and a block has pillars_per_block threads + const std::size_t pillar_feature_size_{64}; + std::size_t max_voxels_{60000}; + + ///// NETWORK PARAMETERS ///// + const std::size_t batch_size_{1}; + const std::size_t num_classes_{5}; + const std::size_t num_point_feature_size_{5}; // x, y, z, intensity, lag + // the dimension of the input cloud + float min_x_range_{-76.8}; + float max_x_range_{76.8}; + float min_y_range_{-76.8}; + float max_y_range_{76.8}; + float min_z_range_{-3.0}; + float max_z_range_{5.0}; + // the size of a pillar + float voxel_x_size_{0.3}; + float voxel_y_size_{0.3}; + float voxel_z_size_{8.0}; + const std::size_t out_size_factor_{4}; + const std::size_t max_num_points_per_pillar_{points_per_voxel_}; + const std::size_t num_point_values_{4}; + const std::size_t num_proposals_{200}; + // the number of feature maps for pillar scatter + const std::size_t num_feature_scatter_{pillar_feature_size_}; + // the score threshold for classification + float score_threshold_{0.2}; + float circle_nms_dist_threshold_{0.5}; + std::vector yaw_norm_thresholds_{0.3, 0.3, 0.3, 0.3, 0.0}; + std::size_t max_num_pillars_{max_voxels_}; + const std::size_t pillar_points_bev_{max_num_points_per_pillar_ * max_num_pillars_}; + // the detected boxes result decode by (x, y, z, w, l, h, yaw) + const std::size_t num_box_values_{8}; + // the input size of the 2D backbone network + std::size_t grid_x_size_{512}; + std::size_t grid_y_size_{512}; + std::size_t grid_z_size_{1}; + // the output size of the 2D backbone network + std::size_t feature_x_size_{grid_x_size_ / out_size_factor_}; + std::size_t feature_y_size_{grid_y_size_ / out_size_factor_}; + + ///// RUNTIME DIMENSIONS ///// + std::vector voxels_num_{5000, 30000, 60000}; + // voxels + std::size_t min_voxel_size_{voxels_num_[0]}; + std::size_t opt_voxel_size_{voxels_num_[1]}; + std::size_t max_voxel_size_{voxels_num_[2]}; + + std::size_t min_point_in_voxel_size_{points_per_voxel_}; + std::size_t opt_point_in_voxel_size_{points_per_voxel_}; + std::size_t max_point_in_voxel_size_{points_per_voxel_}; + + std::size_t min_network_feature_size_{num_point_feature_size_}; + std::size_t opt_network_feature_size_{num_point_feature_size_}; + std::size_t max_network_feature_size_{num_point_feature_size_}; + + // num_points + std::size_t min_points_size_{voxels_num_[0]}; + std::size_t opt_points_size_{voxels_num_[1]}; + std::size_t max_points_size_{voxels_num_[2]}; + + // coors + std::size_t min_coors_size_{voxels_num_[0]}; + std::size_t opt_coors_size_{voxels_num_[1]}; + std::size_t max_coors_size_{voxels_num_[2]}; + + std::size_t min_coors_dim_size_{num_point_values_}; + std::size_t opt_coors_dim_size_{num_point_values_}; + std::size_t max_coors_dim_size_{num_point_values_}; +}; + +} // namespace lidar_transfusion + +#endif // LIDAR_TRANSFUSION__TRANSFUSION_CONFIG_HPP_ diff --git a/perception/lidar_transfusion/include/lidar_transfusion/transfusion_trt.hpp b/perception/lidar_transfusion/include/lidar_transfusion/transfusion_trt.hpp new file mode 100644 index 0000000000000..a94c3c1871136 --- /dev/null +++ b/perception/lidar_transfusion/include/lidar_transfusion/transfusion_trt.hpp @@ -0,0 +1,114 @@ +// 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 LIDAR_TRANSFUSION__TRANSFUSION_TRT_HPP_ +#define LIDAR_TRANSFUSION__TRANSFUSION_TRT_HPP_ + +#include "lidar_transfusion/cuda_utils.hpp" +#include "lidar_transfusion/network/network_trt.hpp" +#include "lidar_transfusion/postprocess/postprocess_kernel.hpp" +#include "lidar_transfusion/preprocess/pointcloud_densification.hpp" +#include "lidar_transfusion/preprocess/preprocess_kernel.hpp" +#include "lidar_transfusion/preprocess/voxel_generator.hpp" +#include "lidar_transfusion/utils.hpp" +#include "lidar_transfusion/visibility_control.hpp" + +#include + +#include + +#include +#include + +#include +#include +#include +#include +#include + +namespace lidar_transfusion +{ + +class NetworkParam +{ +public: + NetworkParam(std::string onnx_path, std::string engine_path, std::string trt_precision) + : onnx_path_(std::move(onnx_path)), + engine_path_(std::move(engine_path)), + trt_precision_(std::move(trt_precision)) + { + } + + std::string onnx_path() const { return onnx_path_; } + std::string engine_path() const { return engine_path_; } + std::string trt_precision() const { return trt_precision_; } + +private: + std::string onnx_path_; + std::string engine_path_; + std::string trt_precision_; +}; + +class LIDAR_TRANSFUSION_PUBLIC TransfusionTRT +{ +public: + explicit TransfusionTRT( + const NetworkParam & network_param, const DensificationParam & densification_param, + const TransfusionConfig & config); + virtual ~TransfusionTRT(); + + bool detect( + const sensor_msgs::msg::PointCloud2 & msg, const tf2_ros::Buffer & tf_buffer, + std::vector & det_boxes3d, std::unordered_map & proc_timing); + +protected: + void initPtr(); + + bool preprocess(const sensor_msgs::msg::PointCloud2 & msg, const tf2_ros::Buffer & tf_buffer); + + bool inference(); + + bool postprocess(std::vector & det_boxes3d); + + std::unique_ptr network_trt_ptr_{nullptr}; + std::unique_ptr vg_ptr_{nullptr}; + std::unique_ptr> stop_watch_ptr_{ + nullptr}; + std::unique_ptr pre_ptr_{nullptr}; + std::unique_ptr post_ptr_{nullptr}; + cudaStream_t stream_{nullptr}; + + TransfusionConfig config_; + + // input of pre-process + + unsigned int voxel_features_size_{0}; + unsigned int voxel_num_size_{0}; + unsigned int voxel_idxs_size_{0}; + unsigned int cls_size_{0}; + unsigned int box_size_{0}; + unsigned int dir_cls_size_{0}; + cuda::unique_ptr points_d_{nullptr}; + cuda::unique_ptr params_input_d_{nullptr}; + cuda::unique_ptr voxel_features_d_{nullptr}; + cuda::unique_ptr voxel_num_d_{nullptr}; + cuda::unique_ptr voxel_idxs_d_{nullptr}; + cuda::unique_ptr cls_output_d_{nullptr}; + cuda::unique_ptr box_output_d_{nullptr}; + cuda::unique_ptr dir_cls_output_d_{nullptr}; +}; + +} // namespace lidar_transfusion + +#endif // LIDAR_TRANSFUSION__TRANSFUSION_TRT_HPP_ diff --git a/perception/lidar_transfusion/include/lidar_transfusion/utils.hpp b/perception/lidar_transfusion/include/lidar_transfusion/utils.hpp new file mode 100644 index 0000000000000..e73fe7f055953 --- /dev/null +++ b/perception/lidar_transfusion/include/lidar_transfusion/utils.hpp @@ -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. + +#ifndef LIDAR_TRANSFUSION__UTILS_HPP_ +#define LIDAR_TRANSFUSION__UTILS_HPP_ + +#include +#include +#include +#include + +namespace lidar_transfusion +{ + +struct Box3D +{ + int label; + float score; + float x; + float y; + float z; + float width; + float length; + float height; + float yaw; +}; + +struct CloudInfo +{ + uint32_t x_offset; + uint32_t y_offset; + uint32_t z_offset; + uint32_t intensity_offset; + uint8_t x_datatype; + uint8_t y_datatype; + uint8_t z_datatype; + uint8_t intensity_datatype; + uint8_t x_count; + uint8_t y_count; + uint8_t z_count; + uint8_t intensity_count; + uint32_t point_step; + bool is_bigendian; + + CloudInfo() + : x_offset(0), + y_offset(4), + z_offset(8), + intensity_offset(12), + x_datatype(7), + y_datatype(7), + z_datatype(7), + intensity_datatype(7), + x_count(1), + y_count(1), + z_count(1), + intensity_count(1), + point_step(16), + is_bigendian(false) + { + } + + bool operator!=(const CloudInfo & rhs) const + { + return x_offset != rhs.x_offset || y_offset != rhs.y_offset || z_offset != rhs.z_offset || + intensity_offset != rhs.intensity_offset || x_datatype != rhs.x_datatype || + y_datatype != rhs.y_datatype || z_datatype != rhs.z_datatype || + intensity_datatype != rhs.intensity_datatype || x_count != rhs.x_count || + y_count != rhs.y_count || z_count != rhs.z_count || + intensity_count != rhs.intensity_count || is_bigendian != rhs.is_bigendian; + } +}; + +enum NetworkIO { voxels = 0, num_points, coors, cls_score, dir_pred, bbox_pred, ENUM_SIZE }; + +// cspell: ignore divup +template +unsigned int divup(const T1 a, const T2 b) +{ + if (a == 0) { + throw std::runtime_error("A dividend of divup isn't positive."); + } + if (b == 0) { + throw std::runtime_error("A divisor of divup isn't positive."); + } + + return (a + b - 1) / b; +} + +} // namespace lidar_transfusion + +#endif // LIDAR_TRANSFUSION__UTILS_HPP_ diff --git a/perception/lidar_transfusion/include/lidar_transfusion/visibility_control.hpp b/perception/lidar_transfusion/include/lidar_transfusion/visibility_control.hpp new file mode 100644 index 0000000000000..aeab20906628a --- /dev/null +++ b/perception/lidar_transfusion/include/lidar_transfusion/visibility_control.hpp @@ -0,0 +1,37 @@ +// 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 LIDAR_TRANSFUSION__VISIBILITY_CONTROL_HPP_ +#define LIDAR_TRANSFUSION__VISIBILITY_CONTROL_HPP_ + +//////////////////////////////////////////////////////////////////////////////// +#if defined(__WIN32) +#if defined(LIDAR_TRANSFUSION_BUILDING_DLL) || defined(LIDAR_TRANSFUSION_EXPORTS) +#define LIDAR_TRANSFUSION_PUBLIC __declspec(dllexport) +#define LIDAR_TRANSFUSION_LOCAL +#else // defined(LIDAR_TRANSFUSION_BUILDING_DLL) || defined(LIDAR_TRANSFUSION_EXPORTS) +#define LIDAR_TRANSFUSION_PUBLIC __declspec(dllimport) +#define LIDAR_TRANSFUSION_LOCAL +#endif // defined(LIDAR_TRANSFUSION_BUILDING_DLL) || defined(LIDAR_TRANSFUSION_EXPORTS) +#elif defined(__linux__) +#define LIDAR_TRANSFUSION_PUBLIC __attribute__((visibility("default"))) +#define LIDAR_TRANSFUSION_LOCAL __attribute__((visibility("hidden"))) +#elif defined(__APPLE__) +#define LIDAR_TRANSFUSION_PUBLIC __attribute__((visibility("default"))) +#define LIDAR_TRANSFUSION_LOCAL __attribute__((visibility("hidden"))) +#else +#error "Unsupported Build Configuration" +#endif + +#endif // LIDAR_TRANSFUSION__VISIBILITY_CONTROL_HPP_ diff --git a/perception/lidar_transfusion/launch/lidar_transfusion.launch.xml b/perception/lidar_transfusion/launch/lidar_transfusion.launch.xml new file mode 100644 index 0000000000000..492eb8c4d59b7 --- /dev/null +++ b/perception/lidar_transfusion/launch/lidar_transfusion.launch.xml @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/lidar_transfusion/lib/detection_class_remapper.cpp b/perception/lidar_transfusion/lib/detection_class_remapper.cpp new file mode 100644 index 0000000000000..e093637402448 --- /dev/null +++ b/perception/lidar_transfusion/lib/detection_class_remapper.cpp @@ -0,0 +1,71 @@ +// 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 lidar_transfusion +{ + +void DetectionClassRemapper::setParameters( + const std::vector & allow_remapping_by_area_matrix, + const std::vector & min_area_matrix, const std::vector & max_area_matrix) +{ + assert(allow_remapping_by_area_matrix.size() == min_area_matrix.size()); + assert(allow_remapping_by_area_matrix.size() == max_area_matrix.size()); + assert( + std::pow(static_cast(std::sqrt(min_area_matrix.size())), 2) == min_area_matrix.size()); + + num_labels_ = static_cast(std::sqrt(min_area_matrix.size())); + + Eigen::Map> + allow_remapping_by_area_matrix_tmp( + allow_remapping_by_area_matrix.data(), num_labels_, num_labels_); + allow_remapping_by_area_matrix_ = allow_remapping_by_area_matrix_tmp.transpose() + .cast(); // Eigen is column major by default + + Eigen::Map min_area_matrix_tmp( + min_area_matrix.data(), num_labels_, num_labels_); + min_area_matrix_ = min_area_matrix_tmp.transpose(); // Eigen is column major by default + + Eigen::Map max_area_matrix_tmp( + max_area_matrix.data(), num_labels_, num_labels_); + max_area_matrix_ = max_area_matrix_tmp.transpose(); // Eigen is column major by default + + min_area_matrix_ = min_area_matrix_.unaryExpr( + [](double v) { return std::isfinite(v) ? v : std::numeric_limits::max(); }); + max_area_matrix_ = max_area_matrix_.unaryExpr( + [](double v) { return std::isfinite(v) ? v : std::numeric_limits::max(); }); +} + +void DetectionClassRemapper::mapClasses(autoware_perception_msgs::msg::DetectedObjects & msg) +{ + for (auto & object : msg.objects) { + const float bev_area = object.shape.dimensions.x * object.shape.dimensions.y; + + for (auto & classification : object.classification) { + auto & label = classification.label; + + for (int i = 0; i < num_labels_; ++i) { + if ( + allow_remapping_by_area_matrix_(label, i) && bev_area >= min_area_matrix_(label, i) && + bev_area <= max_area_matrix_(label, i)) { + label = i; + break; + } + } + } + } +} + +} // namespace lidar_transfusion diff --git a/perception/lidar_transfusion/lib/network/network_trt.cpp b/perception/lidar_transfusion/lib/network/network_trt.cpp new file mode 100644 index 0000000000000..a36890facceec --- /dev/null +++ b/perception/lidar_transfusion/lib/network/network_trt.cpp @@ -0,0 +1,332 @@ +// 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 "lidar_transfusion/network/network_trt.hpp" + +#include + +#include +#include +#include + +namespace lidar_transfusion +{ + +std::ostream & operator<<(std::ostream & os, const ProfileDimension & profile) +{ + std::string delim = ""; + os << "min->["; + for (int i = 0; i < profile.min.nbDims; ++i) { + os << delim << profile.min.d[i]; + delim = ", "; + } + os << "], opt->["; + delim = ""; + for (int i = 0; i < profile.opt.nbDims; ++i) { + os << delim << profile.opt.d[i]; + delim = ", "; + } + os << "], max->["; + delim = ""; + for (int i = 0; i < profile.max.nbDims; ++i) { + os << delim << profile.max.d[i]; + delim = ", "; + } + os << "]"; + return os; +} + +NetworkTRT::NetworkTRT(const TransfusionConfig & config) : config_(config) +{ + ProfileDimension voxels_dims = { + nvinfer1::Dims3( + config_.min_voxel_size_, config_.min_point_in_voxel_size_, config_.min_network_feature_size_), + nvinfer1::Dims3( + config_.opt_voxel_size_, config_.opt_point_in_voxel_size_, config_.opt_network_feature_size_), + nvinfer1::Dims3( + config_.max_voxel_size_, config_.max_point_in_voxel_size_, + config_.max_network_feature_size_)}; + ProfileDimension num_points_dims = { + nvinfer1::Dims{1, {static_cast(config_.min_points_size_)}}, + nvinfer1::Dims{1, {static_cast(config_.opt_points_size_)}}, + nvinfer1::Dims{1, {static_cast(config_.max_points_size_)}}}; + ProfileDimension coors_dims = { + nvinfer1::Dims2(config_.min_coors_size_, config_.min_coors_dim_size_), + nvinfer1::Dims2(config_.opt_coors_size_, config_.opt_coors_dim_size_), + nvinfer1::Dims2(config_.max_coors_size_, config_.max_coors_dim_size_)}; + in_profile_dims_ = {voxels_dims, num_points_dims, coors_dims}; +} + +NetworkTRT::~NetworkTRT() +{ + context.reset(); + runtime_.reset(); + plan_.reset(); + engine.reset(); +} + +bool NetworkTRT::init( + const std::string & onnx_path, const std::string & engine_path, const std::string & precision) +{ + runtime_ = + tensorrt_common::TrtUniquePtr(nvinfer1::createInferRuntime(logger_)); + if (!runtime_) { + tensorrt_common::LOG_ERROR(logger_) << "Failed to create runtime" << std::endl; + return false; + } + + bool success; + std::ifstream engine_file(engine_path); + if (engine_file.is_open()) { + success = loadEngine(engine_path); + } else { + auto log_thread = logger_.log_throttle( + nvinfer1::ILogger::Severity::kINFO, + "Applying optimizations and building TRT CUDA engine. Please wait a minutes...", 5); + success = parseONNX(onnx_path, engine_path, precision); + logger_.stop_throttle(log_thread); + } + success &= createContext(); + + return success; +} + +bool NetworkTRT::setProfile( + nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, + nvinfer1::IBuilderConfig & config) +{ + auto profile = builder.createOptimizationProfile(); + + auto voxels_name = network.getInput(NetworkIO::voxels)->getName(); + auto num_points_name = network.getInput(NetworkIO::num_points)->getName(); + auto coors_name = network.getInput(NetworkIO::coors)->getName(); + + profile->setDimensions( + voxels_name, nvinfer1::OptProfileSelector::kMIN, in_profile_dims_[NetworkIO::voxels].min); + profile->setDimensions( + voxels_name, nvinfer1::OptProfileSelector::kOPT, in_profile_dims_[NetworkIO::voxels].opt); + profile->setDimensions( + voxels_name, nvinfer1::OptProfileSelector::kMAX, in_profile_dims_[NetworkIO::voxels].max); + + profile->setDimensions( + num_points_name, nvinfer1::OptProfileSelector::kMIN, + in_profile_dims_[NetworkIO::num_points].min); + profile->setDimensions( + num_points_name, nvinfer1::OptProfileSelector::kOPT, + in_profile_dims_[NetworkIO::num_points].opt); + profile->setDimensions( + num_points_name, nvinfer1::OptProfileSelector::kMAX, + in_profile_dims_[NetworkIO::num_points].max); + + profile->setDimensions( + coors_name, nvinfer1::OptProfileSelector::kMIN, in_profile_dims_[NetworkIO::coors].min); + profile->setDimensions( + coors_name, nvinfer1::OptProfileSelector::kOPT, in_profile_dims_[NetworkIO::coors].opt); + profile->setDimensions( + coors_name, nvinfer1::OptProfileSelector::kMAX, in_profile_dims_[NetworkIO::coors].max); + + config.addOptimizationProfile(profile); + return true; +} + +bool NetworkTRT::createContext() +{ + if (!engine) { + tensorrt_common::LOG_ERROR(logger_) + << "Failed to create context: Engine was not created" << std::endl; + return false; + } + + context = + tensorrt_common::TrtUniquePtr(engine->createExecutionContext()); + if (!context) { + tensorrt_common::LOG_ERROR(logger_) << "Failed to create context" << std::endl; + return false; + } + + return true; +} + +bool NetworkTRT::parseONNX( + const std::string & onnx_path, const std::string & engine_path, const std::string & precision, + const size_t workspace_size) +{ + auto builder = + tensorrt_common::TrtUniquePtr(nvinfer1::createInferBuilder(logger_)); + if (!builder) { + tensorrt_common::LOG_ERROR(logger_) << "Failed to create builder" << std::endl; + return false; + } + + auto config = + tensorrt_common::TrtUniquePtr(builder->createBuilderConfig()); + if (!config) { + tensorrt_common::LOG_ERROR(logger_) << "Failed to create config" << std::endl; + return false; + } +#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 + config->setMemoryPoolLimit(nvinfer1::MemoryPoolType::kWORKSPACE, workspace_size); +#else + config->setMaxWorkspaceSize(workspace_size); +#endif + if (precision == "fp16") { + if (builder->platformHasFastFp16()) { + tensorrt_common::LOG_INFO(logger_) << "Using TensorRT FP16 Inference" << std::endl; + config->setFlag(nvinfer1::BuilderFlag::kFP16); + } else { + tensorrt_common::LOG_INFO(logger_) + << "TensorRT FP16 Inference isn't supported in this environment" << std::endl; + } + } + + const auto flag = + 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); + auto network = + tensorrt_common::TrtUniquePtr(builder->createNetworkV2(flag)); + if (!network) { + tensorrt_common::LOG_ERROR(logger_) << "Failed to create network" << std::endl; + return false; + } + + auto parser = tensorrt_common::TrtUniquePtr( + nvonnxparser::createParser(*network, logger_)); + parser->parseFromFile(onnx_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR)); + + if (!setProfile(*builder, *network, *config)) { + tensorrt_common::LOG_ERROR(logger_) << "Failed to set profile" << std::endl; + return false; + } + + plan_ = tensorrt_common::TrtUniquePtr( + builder->buildSerializedNetwork(*network, *config)); + if (!plan_) { + tensorrt_common::LOG_ERROR(logger_) << "Failed to create serialized network" << std::endl; + return false; + } + engine = tensorrt_common::TrtUniquePtr( + runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); + if (!engine) { + tensorrt_common::LOG_ERROR(logger_) << "Failed to create engine" << std::endl; + return false; + } + + return saveEngine(engine_path); +} + +bool NetworkTRT::saveEngine(const std::string & engine_path) +{ + tensorrt_common::LOG_INFO(logger_) << "Writing to " << engine_path << std::endl; + std::ofstream file(engine_path, std::ios::out | std::ios::binary); + file.write(reinterpret_cast(plan_->data()), plan_->size()); + return validateNetworkIO(); +} + +bool NetworkTRT::loadEngine(const std::string & engine_path) +{ + std::ifstream engine_file(engine_path); + std::stringstream engine_buffer; + engine_buffer << engine_file.rdbuf(); + std::string engine_str = engine_buffer.str(); + engine = tensorrt_common::TrtUniquePtr(runtime_->deserializeCudaEngine( + reinterpret_cast(engine_str.data()), engine_str.size())); + tensorrt_common::LOG_INFO(logger_) << "Loaded engine from " << engine_path << std::endl; + return validateNetworkIO(); +} + +bool NetworkTRT::validateNetworkIO() +{ + // Whether the number of IO match the expected size + if (engine->getNbIOTensors() != NetworkIO::ENUM_SIZE) { + tensorrt_common::LOG_ERROR(logger_) + << "Invalid network IO. Expected size: " << NetworkIO::ENUM_SIZE + << ". Actual size: " << engine->getNbIOTensors() << "." << std::endl; + throw std::runtime_error("Failed to initialize TRT network."); + } + for (int i = 0; i < NetworkIO::ENUM_SIZE; ++i) { + tensors_names_.push_back(engine->getIOTensorName(i)); + } + + // Log the network IO + std::string tensors = std::accumulate( + tensors_names_.begin(), tensors_names_.end(), std::string(), + [](const std::string & a, const std::string & b) -> std::string { return a + b + " "; }); + tensorrt_common::LOG_INFO(logger_) << "Network IO: " << tensors << std::endl; + + // Whether the current engine input profile match the config input profile + for (int i = 0; i <= NetworkIO::coors; ++i) { + ProfileDimension engine_dims{ + engine->getProfileShape(tensors_names_[i], 0, nvinfer1::OptProfileSelector::kMIN), + engine->getProfileShape(tensors_names_[i], 0, nvinfer1::OptProfileSelector::kOPT), + engine->getProfileShape(tensors_names_[i], 0, nvinfer1::OptProfileSelector::kMAX)}; + + tensorrt_common::LOG_INFO(logger_) + << "Profile for " << tensors_names_[i] << ": " << engine_dims << std::endl; + + if (engine_dims != in_profile_dims_[i]) { + tensorrt_common::LOG_ERROR(logger_) + << "Invalid network input dimension. Config: " << in_profile_dims_[i] + << ". Please change the input profile or delete the engine file and build engine again." + << std::endl; + throw std::runtime_error("Failed to initialize TRT network."); + } + } + + // Whether the IO tensor shapes match the network config, -1 for dynamic size + validateTensorShape( + NetworkIO::voxels, {-1, static_cast(config_.points_per_voxel_), + static_cast(config_.num_point_feature_size_)}); + validateTensorShape(NetworkIO::num_points, {-1}); + validateTensorShape(NetworkIO::coors, {-1, static_cast(config_.num_point_values_)}); + auto cls_score = validateTensorShape( + NetworkIO::cls_score, + {static_cast(config_.batch_size_), static_cast(config_.num_classes_), + static_cast(config_.num_proposals_)}); + tensorrt_common::LOG_INFO(logger_) << "Network num classes: " << cls_score.d[1] << std::endl; + validateTensorShape( + NetworkIO::dir_pred, + {static_cast(config_.batch_size_), 2, static_cast(config_.num_proposals_)}); // x, y + validateTensorShape( + NetworkIO::bbox_pred, + {static_cast(config_.batch_size_), static_cast(config_.num_box_values_), + static_cast(config_.num_proposals_)}); + + return true; +} + +const char * NetworkTRT::getTensorName(NetworkIO name) +{ + return tensors_names_.at(name); +} + +nvinfer1::Dims NetworkTRT::validateTensorShape(NetworkIO name, const std::vector shape) +{ + auto tensor_shape = engine->getTensorShape(tensors_names_[name]); + if (tensor_shape.nbDims != static_cast(shape.size())) { + tensorrt_common::LOG_ERROR(logger_) + << "Invalid tensor shape for " << tensors_names_[name] << ". Expected size: " << shape.size() + << ". Actual size: " << tensor_shape.nbDims << "." << std::endl; + throw std::runtime_error("Failed to initialize TRT network."); + } + for (int i = 0; i < tensor_shape.nbDims; ++i) { + if (tensor_shape.d[i] != static_cast(shape[i])) { + tensorrt_common::LOG_ERROR(logger_) + << "Invalid tensor shape for " << tensors_names_[name] << ". Expected: " << shape[i] + << ". Actual: " << tensor_shape.d[i] << "." << std::endl; + throw std::runtime_error("Failed to initialize TRT network."); + } + } + return tensor_shape; +} + +} // namespace lidar_transfusion diff --git a/perception/lidar_transfusion/lib/postprocess/circle_nms_kernel.cu b/perception/lidar_transfusion/lib/postprocess/circle_nms_kernel.cu new file mode 100644 index 0000000000000..dcb60831825bb --- /dev/null +++ b/perception/lidar_transfusion/lib/postprocess/circle_nms_kernel.cu @@ -0,0 +1,144 @@ +// 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. + +// Modified from +// https://github.com/open-mmlab/OpenPCDet/blob/master/pcdet/ops/iou3d_nms/src/iou3d_nms_kernel.cu + +/* +3D IoU Calculation and Rotated NMS(modified from 2D NMS written by others) +Written by Shaoshuai Shi +All Rights Reserved 2019-2020. +*/ + +#include "lidar_transfusion/cuda_utils.hpp" +#include "lidar_transfusion/postprocess/circle_nms_kernel.hpp" +#include "lidar_transfusion/utils.hpp" + +#include + +namespace +{ +const std::size_t THREADS_PER_BLOCK_NMS = 16; +} // namespace + +namespace lidar_transfusion +{ + +__device__ inline float dist2dPow(const Box3D * a, const Box3D * b) +{ + return powf(a->x - b->x, 2) + powf(a->y - b->y, 2); +} + +// cspell: ignore divup +__global__ void circleNMS_Kernel( + const Box3D * boxes, const std::size_t num_boxes3d, const std::size_t col_blocks, + const float dist2d_pow_threshold, std::uint64_t * mask) +{ + // params: boxes (N,) + // params: mask (N, divup(N/THREADS_PER_BLOCK_NMS)) + + const auto row_start = blockIdx.y; + const auto col_start = blockIdx.x; + + if (row_start > col_start) return; + + const std::size_t row_size = + fminf(num_boxes3d - row_start * THREADS_PER_BLOCK_NMS, THREADS_PER_BLOCK_NMS); + const std::size_t col_size = + fminf(num_boxes3d - col_start * THREADS_PER_BLOCK_NMS, THREADS_PER_BLOCK_NMS); + + __shared__ Box3D block_boxes[THREADS_PER_BLOCK_NMS]; + + if (threadIdx.x < col_size) { + block_boxes[threadIdx.x] = boxes[THREADS_PER_BLOCK_NMS * col_start + threadIdx.x]; + } + __syncthreads(); + + if (threadIdx.x < row_size) { + const std::size_t cur_box_idx = THREADS_PER_BLOCK_NMS * row_start + threadIdx.x; + const Box3D * cur_box = boxes + cur_box_idx; + + std::uint64_t t = 0; + std::size_t start = 0; + if (row_start == col_start) { + start = threadIdx.x + 1; + } + for (std::size_t i = start; i < col_size; i++) { + if (dist2dPow(cur_box, block_boxes + i) < dist2d_pow_threshold) { + t |= 1ULL << i; + } + } + mask[cur_box_idx * col_blocks + col_start] = t; + } +} + +cudaError_t circleNMS_launch( + const thrust::device_vector & boxes3d, const std::size_t num_boxes3d, + std::size_t col_blocks, const float distance_threshold, + thrust::device_vector & mask, cudaStream_t stream) +{ + const float dist2d_pow_thres = powf(distance_threshold, 2); + + dim3 blocks(col_blocks, col_blocks); + dim3 threads(THREADS_PER_BLOCK_NMS); + circleNMS_Kernel<<>>( + thrust::raw_pointer_cast(boxes3d.data()), num_boxes3d, col_blocks, dist2d_pow_thres, + thrust::raw_pointer_cast(mask.data())); + + return cudaGetLastError(); +} + +std::size_t circleNMS( + thrust::device_vector & boxes3d, const float distance_threshold, + thrust::device_vector & keep_mask, cudaStream_t stream) +{ + const auto num_boxes3d = boxes3d.size(); + const auto col_blocks = divup(num_boxes3d, THREADS_PER_BLOCK_NMS); + thrust::device_vector mask_d(num_boxes3d * col_blocks); + + CHECK_CUDA_ERROR( + circleNMS_launch(boxes3d, num_boxes3d, col_blocks, distance_threshold, mask_d, stream)); + + // memcpy device to host + thrust::host_vector mask_h(mask_d.size()); + thrust::copy(mask_d.begin(), mask_d.end(), mask_h.begin()); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream)); + + // generate keep_mask + std::vector remv_h(col_blocks); + thrust::host_vector keep_mask_h(keep_mask.size()); + std::size_t num_to_keep = 0; + for (std::size_t i = 0; i < num_boxes3d; i++) { + auto nblock = i / THREADS_PER_BLOCK_NMS; + auto inblock = i % THREADS_PER_BLOCK_NMS; + + if (!(remv_h[nblock] & (1ULL << inblock))) { + keep_mask_h[i] = true; + num_to_keep++; + std::uint64_t * p = &mask_h[0] + i * col_blocks; + for (std::size_t j = nblock; j < col_blocks; j++) { + remv_h[j] |= p[j]; + } + } else { + keep_mask_h[i] = false; + } + } + + // memcpy host to device + keep_mask = keep_mask_h; + + return num_to_keep; +} + +} // namespace lidar_transfusion diff --git a/perception/lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp b/perception/lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp new file mode 100644 index 0000000000000..c1179a3f6673d --- /dev/null +++ b/perception/lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp @@ -0,0 +1,104 @@ +// 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 "lidar_transfusion/postprocess/non_maximum_suppression.hpp" + +#include +#include +#include + +namespace lidar_transfusion +{ + +void NonMaximumSuppression::setParameters(const NMSParams & params) +{ + assert(params.search_distance_2d_ >= 0.0); + assert(params.iou_threshold_ >= 0.0 && params.iou_threshold_ <= 1.0); + + params_ = params; + target_class_mask_ = classNamesToBooleanMask(params.target_class_names_); +} + +bool NonMaximumSuppression::isTargetLabel(const uint8_t label) +{ + if (label >= target_class_mask_.size()) { + return false; + } + return target_class_mask_.at(label); +} + +bool NonMaximumSuppression::isTargetPairObject( + const DetectedObject & object1, const DetectedObject & object2) +{ + const auto label1 = object_recognition_utils::getHighestProbLabel(object1.classification); + const auto label2 = object_recognition_utils::getHighestProbLabel(object2.classification); + + if (isTargetLabel(label1) && isTargetLabel(label2)) { + return true; + } + + const auto search_sqr_dist_2d = params_.search_distance_2d_ * params_.search_distance_2d_; + const auto sqr_dist_2d = tier4_autoware_utils::calcSquaredDistance2d( + object_recognition_utils::getPose(object1), object_recognition_utils::getPose(object2)); + return sqr_dist_2d <= search_sqr_dist_2d; +} + +Eigen::MatrixXd NonMaximumSuppression::generateIoUMatrix( + const std::vector & input_objects) +{ + // NOTE: row = target objects to be suppressed, col = source objects to be compared + Eigen::MatrixXd triangular_matrix = + Eigen::MatrixXd::Zero(input_objects.size(), input_objects.size()); + for (std::size_t target_i = 0; target_i < input_objects.size(); ++target_i) { + for (std::size_t source_i = 0; source_i < target_i; ++source_i) { + const auto & target_obj = input_objects.at(target_i); + const auto & source_obj = input_objects.at(source_i); + if (!isTargetPairObject(target_obj, source_obj)) { + continue; + } + + if (params_.nms_type_ == NMS_TYPE::IoU_BEV) { + const double iou = object_recognition_utils::get2dIoU(target_obj, source_obj); + triangular_matrix(target_i, source_i) = iou; + // NOTE: If the target object has any objects with iou > iou_threshold, it + // will be suppressed regardless of later results. + if (iou > params_.iou_threshold_) { + break; + } + } + } + } + + return triangular_matrix; +} + +std::vector NonMaximumSuppression::apply( + const std::vector & input_objects) +{ + Eigen::MatrixXd iou_matrix = generateIoUMatrix(input_objects); + + std::vector output_objects; + output_objects.reserve(input_objects.size()); + for (std::size_t i = 0; i < input_objects.size(); ++i) { + const auto value = iou_matrix.row(i).maxCoeff(); + if (params_.nms_type_ == NMS_TYPE::IoU_BEV) { + if (value <= params_.iou_threshold_) { + output_objects.emplace_back(input_objects.at(i)); + } + } + } + + return output_objects; +} +} // namespace lidar_transfusion diff --git a/perception/lidar_transfusion/lib/postprocess/postprocess_kernel.cu b/perception/lidar_transfusion/lib/postprocess/postprocess_kernel.cu new file mode 100644 index 0000000000000..bca23e9961b40 --- /dev/null +++ b/perception/lidar_transfusion/lib/postprocess/postprocess_kernel.cu @@ -0,0 +1,145 @@ +// 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 "lidar_transfusion/postprocess/circle_nms_kernel.hpp" +#include "lidar_transfusion/postprocess/postprocess_kernel.hpp" + +#include +#include +#include + +namespace lidar_transfusion +{ +const size_t THREADS_PER_BLOCK = 256; + +struct is_score_greater +{ + is_score_greater(float t) : t_(t) {} + + __device__ bool operator()(const Box3D & b) { return b.score > t_; } + +private: + float t_{0.0}; +}; + +struct is_kept +{ + __device__ bool operator()(const bool keep) { return keep; } +}; + +struct score_greater +{ + __device__ bool operator()(const Box3D & lb, const Box3D & rb) { return lb.score > rb.score; } +}; + +__device__ inline float sigmoid(float x) +{ + return 1.0f / (1.0f + expf(-x)); +} + +__global__ void generateBoxes3D_kernel( + const float * __restrict__ cls_output, const float * __restrict__ box_output, + const float * __restrict__ dir_cls_output, const float voxel_size_x, const float voxel_size_y, + const float min_x_range, const float min_y_range, const int num_proposals, const int num_classes, + const int num_point_values, const float * __restrict__ yaw_norm_thresholds, + Box3D * __restrict__ det_boxes3d) +{ + int point_idx = blockIdx.x * blockDim.x + threadIdx.x; + if (point_idx >= num_proposals) { + return; + } + + int class_id = 0; + float max_score = cls_output[point_idx]; + +#pragma unroll + for (int i = 1; i < num_classes; i++) { + float score = cls_output[i * num_proposals + point_idx]; + if (score > max_score) { + max_score = score; + class_id = i; + } + } + + // yaw validation + const float yaw_sin = dir_cls_output[point_idx]; + const float yaw_cos = dir_cls_output[point_idx + num_proposals]; + const float yaw_norm = sqrtf(yaw_sin * yaw_sin + yaw_cos * yaw_cos); + + det_boxes3d[point_idx].label = class_id; + det_boxes3d[point_idx].score = yaw_norm >= yaw_norm_thresholds[class_id] ? max_score : 0.f; + det_boxes3d[point_idx].x = box_output[point_idx] * num_point_values * voxel_size_x + min_x_range; + det_boxes3d[point_idx].y = + box_output[point_idx + num_proposals] * num_point_values * voxel_size_y + min_y_range; + det_boxes3d[point_idx].z = box_output[point_idx + 2 * num_proposals]; + det_boxes3d[point_idx].width = expf(box_output[point_idx + 3 * num_proposals]); + det_boxes3d[point_idx].length = expf(box_output[point_idx + 4 * num_proposals]); + det_boxes3d[point_idx].height = expf(box_output[point_idx + 5 * num_proposals]); + det_boxes3d[point_idx].yaw = + atan2f(dir_cls_output[point_idx], dir_cls_output[point_idx + num_proposals]); +} + +PostprocessCuda::PostprocessCuda(const TransfusionConfig & config, cudaStream_t & stream) +: config_(config), stream_(stream) +{ + boxes3d_d_ = thrust::device_vector(config_.num_proposals_); + yaw_norm_thresholds_d_ = thrust::device_vector( + config_.yaw_norm_thresholds_.begin(), config_.yaw_norm_thresholds_.end()); +} + +// cspell: ignore divup +cudaError_t PostprocessCuda::generateDetectedBoxes3D_launch( + const float * cls_output, const float * box_output, const float * dir_cls_output, + std::vector & det_boxes3d, cudaStream_t stream) +{ + dim3 threads = {THREADS_PER_BLOCK}; + dim3 blocks = {divup(config_.num_proposals_, threads.x)}; + + generateBoxes3D_kernel<<>>( + cls_output, box_output, dir_cls_output, config_.voxel_x_size_, config_.voxel_y_size_, + config_.min_x_range_, config_.min_y_range_, config_.num_proposals_, config_.num_classes_, + config_.num_point_values_, thrust::raw_pointer_cast(yaw_norm_thresholds_d_.data()), + thrust::raw_pointer_cast(boxes3d_d_.data())); + + // suppress by score + const auto num_det_boxes3d = thrust::count_if( + thrust::device, boxes3d_d_.begin(), boxes3d_d_.end(), + is_score_greater(config_.score_threshold_)); + if (num_det_boxes3d == 0) { + return cudaGetLastError(); + } + thrust::device_vector det_boxes3d_d(num_det_boxes3d); + thrust::copy_if( + thrust::device, boxes3d_d_.begin(), boxes3d_d_.end(), det_boxes3d_d.begin(), + is_score_greater(config_.score_threshold_)); + + // sort by score + thrust::sort(det_boxes3d_d.begin(), det_boxes3d_d.end(), score_greater()); + + // supress by NMS + thrust::device_vector final_keep_mask_d(num_det_boxes3d); + const auto num_final_det_boxes3d = + circleNMS(det_boxes3d_d, config_.circle_nms_dist_threshold_, final_keep_mask_d, stream); + thrust::device_vector final_det_boxes3d_d(num_final_det_boxes3d); + thrust::copy_if( + thrust::device, det_boxes3d_d.begin(), det_boxes3d_d.end(), final_keep_mask_d.begin(), + final_det_boxes3d_d.begin(), is_kept()); + + // memcpy device to host + det_boxes3d.resize(num_final_det_boxes3d); + thrust::copy(final_det_boxes3d_d.begin(), final_det_boxes3d_d.end(), det_boxes3d.begin()); + return cudaGetLastError(); +} + +} // namespace lidar_transfusion diff --git a/perception/lidar_transfusion/lib/preprocess/pointcloud_densification.cpp b/perception/lidar_transfusion/lib/preprocess/pointcloud_densification.cpp new file mode 100644 index 0000000000000..774b3a05d71c1 --- /dev/null +++ b/perception/lidar_transfusion/lib/preprocess/pointcloud_densification.cpp @@ -0,0 +1,117 @@ +// 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 "lidar_transfusion/preprocess/pointcloud_densification.hpp" + +#include + +#include +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +#include + +#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_transfusion"), 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 lidar_transfusion +{ + +PointCloudDensification::PointCloudDensification( + const DensificationParam & param, cudaStream_t & stream) +: param_(param), stream_(stream) +{ +} + +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(); + + assert(sizeof(uint8_t) * msg.width * msg.height * msg.point_step % sizeof(float) == 1); + 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, affine_world2current.inverse()}; + + pointcloud_cache_.push_front(std::move(pointcloud)); +} + +void PointCloudDensification::dequeue() +{ + if (pointcloud_cache_.size() > param_.pointcloud_cache_size()) { + pointcloud_cache_.pop_back(); + } +} + +} // namespace lidar_transfusion diff --git a/perception/lidar_transfusion/lib/preprocess/preprocess_kernel.cu b/perception/lidar_transfusion/lib/preprocess/preprocess_kernel.cu new file mode 100644 index 0000000000000..b8f9ae998fd4f --- /dev/null +++ b/perception/lidar_transfusion/lib/preprocess/preprocess_kernel.cu @@ -0,0 +1,208 @@ +// 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. +/* + * SPDX-FileCopyrightText: Copyright (c) 2021 NVIDIA CORPORATION & AFFILIATES. + * All rights reserved. SPDX-License-Identifier: Apache-2.0 + * + * 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 "lidar_transfusion/cuda_utils.hpp" +#include "lidar_transfusion/preprocess/preprocess_kernel.hpp" + +namespace lidar_transfusion +{ + +PreprocessCuda::PreprocessCuda(const TransfusionConfig & config, cudaStream_t & stream) +: stream_(stream), config_(config) +{ + mask_size_ = config_.grid_z_size_ * config_.grid_y_size_ * config_.grid_x_size_; + voxels_size_ = config_.grid_z_size_ * config_.grid_y_size_ * config_.grid_x_size_ * + config_.max_num_points_per_pillar_ * config_.num_point_feature_size_ + + 1; + mask_ = cuda::make_unique(mask_size_); + voxels_ = cuda::make_unique(voxels_size_); +} + +void PreprocessCuda::generateVoxels( + float * points, unsigned int points_size, unsigned int * pillar_num, float * voxel_features, + unsigned int * voxel_num, unsigned int * voxel_idxs) +{ + cuda::clear_async(mask_.get(), mask_size_, stream_); + cuda::clear_async(voxels_.get(), voxels_size_, stream_); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + + CHECK_CUDA_ERROR(generateVoxels_random_launch(points, points_size, mask_.get(), voxels_.get())); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + + CHECK_CUDA_ERROR(generateBaseFeatures_launch( + mask_.get(), voxels_.get(), pillar_num, voxel_features, voxel_num, voxel_idxs)); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); +} + +__global__ void generateVoxels_random_kernel( + float * points, unsigned int 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, + float pillar_z_size, int grid_y_size, int grid_x_size, int points_per_voxel, unsigned int * mask, + float * voxels) +{ + int point_idx = blockIdx.x * blockDim.x + threadIdx.x; + if (point_idx >= points_size) return; + + float x = points[point_idx * 5]; + float y = points[point_idx * 5 + 1]; + float z = points[point_idx * 5 + 2]; + float i = points[point_idx * 5 + 3]; + float t = points[point_idx * 5 + 4]; + + if ( + x <= min_x_range || x >= max_x_range || y <= min_y_range || y >= max_y_range || + z <= min_z_range || z >= max_z_range) + return; + + int voxel_idx = floorf((x - min_x_range) / pillar_x_size); + int voxel_idy = floorf((y - min_y_range) / pillar_y_size); + unsigned int voxel_index = voxel_idy * grid_x_size + voxel_idx; + + unsigned int point_id = atomicAdd(&(mask[voxel_index]), 1); + + if (point_id >= points_per_voxel) return; + float * address = voxels + (voxel_index * points_per_voxel + point_id) * 5; + atomicExch(address + 0, x); + atomicExch(address + 1, y); + atomicExch(address + 2, z); + atomicExch(address + 3, i); + atomicExch(address + 4, t); +} + +cudaError_t PreprocessCuda::generateVoxels_random_launch( + float * points, unsigned int points_size, unsigned int * mask, float * voxels) +{ + int threadNum = config_.threads_for_voxel_; + dim3 blocks((points_size + threadNum - 1) / threadNum); + dim3 threads(threadNum); + generateVoxels_random_kernel<<>>( + points, points_size, config_.min_x_range_, config_.max_x_range_, config_.min_y_range_, + config_.max_y_range_, config_.min_z_range_, config_.max_z_range_, config_.voxel_x_size_, + config_.voxel_y_size_, config_.voxel_z_size_, config_.grid_y_size_, config_.grid_x_size_, + config_.points_per_voxel_, mask, voxels); + cudaError_t err = cudaGetLastError(); + return err; +} + +__global__ void generateBaseFeatures_kernel( + unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, float points_per_voxel, + float max_voxels, unsigned int * pillar_num, float * voxel_features, unsigned int * voxel_num, + unsigned int * voxel_idxs) +{ + unsigned int voxel_idx = blockIdx.x * blockDim.x + threadIdx.x; + unsigned int voxel_idy = blockIdx.y * blockDim.y + threadIdx.y; + + if (voxel_idx >= grid_x_size || voxel_idy >= grid_y_size) return; + + unsigned int voxel_index = voxel_idy * grid_x_size + voxel_idx; + unsigned int count = mask[voxel_index]; + if (!(count > 0)) return; + count = count < points_per_voxel ? count : points_per_voxel; + + unsigned int current_pillarId = 0; + current_pillarId = atomicAdd(pillar_num, 1); + if (current_pillarId >= max_voxels) return; + + voxel_num[current_pillarId] = count; + + uint4 idx = {0, 0, voxel_idy, voxel_idx}; + ((uint4 *)voxel_idxs)[current_pillarId] = idx; + + for (int i = 0; i < count; i++) { + int inIndex = voxel_index * points_per_voxel + i; + int outIndex = current_pillarId * points_per_voxel + i; + voxel_features[outIndex * 5] = voxels[inIndex * 5]; + voxel_features[outIndex * 5 + 1] = voxels[inIndex * 5 + 1]; + voxel_features[outIndex * 5 + 2] = voxels[inIndex * 5 + 2]; + voxel_features[outIndex * 5 + 3] = voxels[inIndex * 5 + 3]; + voxel_features[outIndex * 5 + 4] = voxels[inIndex * 5 + 4]; + } + + // clear buffer for next infer + atomicExch(mask + voxel_index, 0); +} + +// create 4 channels +cudaError_t PreprocessCuda::generateBaseFeatures_launch( + unsigned int * mask, float * voxels, unsigned int * pillar_num, float * voxel_features, + unsigned int * voxel_num, unsigned int * voxel_idxs) +{ + dim3 threads = {32, 32}; + dim3 blocks = {divup(config_.grid_x_size_, threads.x), divup(config_.grid_y_size_, threads.y)}; + + generateBaseFeatures_kernel<<>>( + mask, voxels, config_.grid_y_size_, config_.grid_x_size_, config_.points_per_voxel_, + config_.max_voxels_, pillar_num, voxel_features, voxel_num, voxel_idxs); + cudaError_t err = cudaGetLastError(); + return err; +} + +__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]; + const float intensity = input_points[point_idx * input_point_step + 3]; + + output_points[point_idx * num_features] = 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] = intensity; + output_points[point_idx * num_features + 4] = time_lag; +} + +cudaError_t PreprocessCuda::generateSweepPoints_launch( + const float * input_points, size_t points_size, int input_point_step, float time_lag, + const float * transform_array, float * output_points) +{ + int threadNum = config_.threads_for_voxel_; + dim3 blocks((points_size + threadNum - 1) / threadNum); + dim3 threads(threadNum); + + generateSweepPoints_kernel<<>>( + input_points, points_size, input_point_step, time_lag, transform_array, + config_.num_point_feature_size_, output_points); + + cudaError_t err = cudaGetLastError(); + return err; +} + +} // namespace lidar_transfusion diff --git a/perception/lidar_transfusion/lib/preprocess/voxel_generator.cpp b/perception/lidar_transfusion/lib/preprocess/voxel_generator.cpp new file mode 100644 index 0000000000000..7072e8491af66 --- /dev/null +++ b/perception/lidar_transfusion/lib/preprocess/voxel_generator.cpp @@ -0,0 +1,142 @@ +// 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 "lidar_transfusion/preprocess/voxel_generator.hpp" + +#include "lidar_transfusion/preprocess/preprocess_kernel.hpp" + +#include + +#include + +namespace lidar_transfusion +{ + +std::ostream & operator<<(std::ostream & os, const CloudInfo & info) +{ + os << "x_offset: " << static_cast(info.x_offset) << std::endl; + os << "y_offset: " << static_cast(info.y_offset) << std::endl; + os << "z_offset: " << static_cast(info.z_offset) << std::endl; + os << "intensity_offset: " << static_cast(info.intensity_offset) << std::endl; + os << "x_datatype: " << static_cast(info.x_datatype) << std::endl; + os << "y_datatype: " << static_cast(info.y_datatype) << std::endl; + os << "z_datatype: " << static_cast(info.z_datatype) << std::endl; + os << "intensity_datatype: " << static_cast(info.intensity_datatype) << std::endl; + os << "x_count: " << static_cast(info.x_count) << std::endl; + os << "y_count: " << static_cast(info.y_count) << std::endl; + os << "z_count: " << static_cast(info.z_count) << std::endl; + os << "intensity_count: " << static_cast(info.intensity_count) << std::endl; + os << "point_step: " << static_cast(info.point_step) << std::endl; + os << "is_bigendian: " << static_cast(info.is_bigendian) << std::endl; + return os; +} + +VoxelGenerator::VoxelGenerator( + const DensificationParam & densification_param, const TransfusionConfig & config, + cudaStream_t & stream) +: config_(config), stream_(stream) +{ + pd_ptr_ = std::make_unique(densification_param, stream_); + pre_ptr_ = std::make_unique(config_, stream_); + cloud_data_d_ = cuda::make_unique(config_.cloud_capacity_ * MAX_CLOUD_STEP_SIZE); + affine_past2current_d_ = cuda::make_unique(AFF_MAT_SIZE); +} + +bool VoxelGenerator::enqueuePointCloud( + const sensor_msgs::msg::PointCloud2 & msg, const tf2_ros::Buffer & tf_buffer) +{ + return pd_ptr_->enqueuePointCloud(msg, tf_buffer); +} + +std::size_t VoxelGenerator::generateSweepPoints( + const sensor_msgs::msg::PointCloud2 & msg, cuda::unique_ptr & points_d) +{ + if (!is_initialized_) { + initCloudInfo(msg); + std::stringstream ss; + ss << "Input point cloud information: " << std::endl << cloud_info_; + RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lidar_transfusion"), ss.str()); + + CloudInfo default_cloud_info; + if (cloud_info_ != default_cloud_info) { + ss << "Expected point cloud information: " << std::endl << default_cloud_info; + RCLCPP_ERROR_STREAM(rclcpp::get_logger("lidar_transfusion"), ss.str()); + throw std::runtime_error("Input point cloud has unsupported format"); + } + is_initialized_ = true; + } + + size_t point_counter{0}; + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + + for (auto pc_cache_iter = pd_ptr_->getPointCloudCacheIter(); !pd_ptr_->isCacheEnd(pc_cache_iter); + pc_cache_iter++) { + auto sweep_num_points = pc_cache_iter->num_points; + if (point_counter + sweep_num_points >= config_.cloud_capacity_) { + RCLCPP_WARN_STREAM( + rclcpp::get_logger("lidar_transfusion"), "Exceeding cloud capacity. Used " + << pd_ptr_->getIdx(pc_cache_iter) << " out of " + << pd_ptr_->getCacheSize() << " sweep(s)"); + break; + } + auto shift = point_counter * config_.num_point_feature_size_; + + auto affine_past2current = + pd_ptr_->getAffineWorldToCurrent() * pc_cache_iter->affine_past2world; + static_assert(std::is_same::value); + static_assert(!Eigen::Matrix4f::IsRowMajor, "matrices should be col-major."); + + float time_lag = static_cast( + pd_ptr_->getCurrentTimestamp() - rclcpp::Time(pc_cache_iter->header.stamp).seconds()); + + CHECK_CUDA_ERROR(cudaMemcpyAsync( + affine_past2current_d_.get(), affine_past2current.data(), AFF_MAT_SIZE * sizeof(float), + cudaMemcpyHostToDevice, stream_)); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + + pre_ptr_->generateSweepPoints_launch( + pc_cache_iter->points_d.get(), sweep_num_points, cloud_info_.point_step / sizeof(float), + time_lag, affine_past2current_d_.get(), points_d.get() + shift); + point_counter += sweep_num_points; + } + + return point_counter; +} + +void VoxelGenerator::initCloudInfo(const sensor_msgs::msg::PointCloud2 & msg) +{ + std::tie(cloud_info_.x_offset, cloud_info_.x_datatype, cloud_info_.x_count) = + getFieldInfo(msg, "x"); + std::tie(cloud_info_.y_offset, cloud_info_.y_datatype, cloud_info_.y_count) = + getFieldInfo(msg, "y"); + std::tie(cloud_info_.z_offset, cloud_info_.z_datatype, cloud_info_.z_count) = + getFieldInfo(msg, "z"); + std::tie( + cloud_info_.intensity_offset, cloud_info_.intensity_datatype, cloud_info_.intensity_count) = + getFieldInfo(msg, "intensity"); + cloud_info_.point_step = msg.point_step; + cloud_info_.is_bigendian = msg.is_bigendian; +} + +std::tuple VoxelGenerator::getFieldInfo( + const sensor_msgs::msg::PointCloud2 & msg, const std::string & field_name) +{ + for (const auto & field : msg.fields) { + if (field.name == field_name) { + return std::make_tuple(field.offset, field.datatype, field.count); + } + } + throw std::runtime_error("Missing field: " + field_name); +} +} // namespace lidar_transfusion diff --git a/perception/lidar_transfusion/lib/ros_utils.cpp b/perception/lidar_transfusion/lib/ros_utils.cpp new file mode 100644 index 0000000000000..0ecb34faf732d --- /dev/null +++ b/perception/lidar_transfusion/lib/ros_utils.cpp @@ -0,0 +1,83 @@ +// 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 "lidar_transfusion/ros_utils.hpp" + +#include +#include +#include + +namespace lidar_transfusion +{ + +using Label = autoware_perception_msgs::msg::ObjectClassification; + +void box3DToDetectedObject( + const Box3D & box3d, const std::vector & class_names, + autoware_perception_msgs::msg::DetectedObject & obj) +{ + obj.existence_probability = box3d.score; + + // classification + autoware_perception_msgs::msg::ObjectClassification classification; + classification.probability = 1.0f; + if (box3d.label >= 0 && static_cast(box3d.label) < class_names.size()) { + classification.label = getSemanticType(class_names[box3d.label]); + } else { + classification.label = Label::UNKNOWN; + RCLCPP_WARN_STREAM( + rclcpp::get_logger("lidar_transfusion"), "Unexpected label: UNKNOWN is set."); + } + + if (object_recognition_utils::isCarLikeVehicle(classification.label)) { + obj.kinematics.orientation_availability = + autoware_perception_msgs::msg::DetectedObjectKinematics::SIGN_UNKNOWN; + } + + obj.classification.emplace_back(classification); + + // pose and shape + // mmdet3d yaw format to ros yaw format + float yaw = box3d.yaw + tier4_autoware_utils::pi / 2; + obj.kinematics.pose_with_covariance.pose.position = + tier4_autoware_utils::createPoint(box3d.x, box3d.y, box3d.z); + obj.kinematics.pose_with_covariance.pose.orientation = + tier4_autoware_utils::createQuaternionFromYaw(yaw); + obj.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; + obj.shape.dimensions = + tier4_autoware_utils::createTranslation(box3d.length, box3d.width, box3d.height); +} + +uint8_t getSemanticType(const std::string & class_name) +{ + if (class_name == "CAR") { + return Label::CAR; + } else if (class_name == "TRUCK") { + return Label::TRUCK; + } else if (class_name == "BUS") { + return Label::BUS; + } else if (class_name == "TRAILER") { + return Label::TRAILER; + } else if (class_name == "MOTORCYCLE") { + return Label::MOTORCYCLE; + } else if (class_name == "BICYCLE") { + return Label::BICYCLE; + } else if (class_name == "PEDESTRIAN") { + return Label::PEDESTRIAN; + } else { // CONSTRUCTION_VEHICLE, BARRIER, TRAFFIC_CONE + return Label::UNKNOWN; + } +} + +} // namespace lidar_transfusion diff --git a/perception/lidar_transfusion/lib/transfusion_trt.cpp b/perception/lidar_transfusion/lib/transfusion_trt.cpp new file mode 100644 index 0000000000000..c876c0906162b --- /dev/null +++ b/perception/lidar_transfusion/lib/transfusion_trt.cpp @@ -0,0 +1,205 @@ +// 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 "lidar_transfusion/transfusion_trt.hpp" + +#include "lidar_transfusion/preprocess/preprocess_kernel.hpp" +#include "lidar_transfusion/transfusion_config.hpp" + +#include + +#include +#include +#include +#include + +namespace lidar_transfusion +{ + +TransfusionTRT::TransfusionTRT( + const NetworkParam & network_param, const DensificationParam & densification_param, + const TransfusionConfig & config) +: config_(config) +{ + network_trt_ptr_ = std::make_unique(config_); + + network_trt_ptr_->init( + 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>(); + stop_watch_ptr_->tic("processing/inner"); + initPtr(); + + CHECK_CUDA_ERROR(cudaStreamCreate(&stream_)); +} + +TransfusionTRT::~TransfusionTRT() +{ + if (stream_) { + cudaStreamSynchronize(stream_); + cudaStreamDestroy(stream_); + } +} + +void TransfusionTRT::initPtr() +{ + // point cloud to voxels + voxel_features_size_ = + config_.max_voxels_ * config_.max_num_points_per_pillar_ * config_.num_point_feature_size_; + voxel_num_size_ = config_.max_voxels_; + voxel_idxs_size_ = config_.max_voxels_ * config_.num_point_values_; + + // output of TRT -- input of post-process + cls_size_ = config_.num_proposals_ * config_.num_classes_; + box_size_ = config_.num_proposals_ * config_.num_box_values_; + dir_cls_size_ = config_.num_proposals_ * 2; // x, y + cls_output_d_ = cuda::make_unique(cls_size_); + box_output_d_ = cuda::make_unique(box_size_); + dir_cls_output_d_ = cuda::make_unique(dir_cls_size_); + + params_input_d_ = cuda::make_unique(); + voxel_features_d_ = cuda::make_unique(voxel_features_size_); + voxel_num_d_ = cuda::make_unique(voxel_num_size_); + voxel_idxs_d_ = cuda::make_unique(voxel_idxs_size_); + points_d_ = cuda::make_unique(config_.cloud_capacity_ * config_.num_point_feature_size_); + pre_ptr_ = std::make_unique(config_, stream_); + post_ptr_ = std::make_unique(config_, stream_); +} + +bool TransfusionTRT::detect( + const sensor_msgs::msg::PointCloud2 & msg, const tf2_ros::Buffer & tf_buffer, + std::vector & det_boxes3d, std::unordered_map & proc_timing) +{ + stop_watch_ptr_->toc("processing/inner", true); + if (!preprocess(msg, tf_buffer)) { + RCLCPP_WARN_STREAM( + rclcpp::get_logger("lidar_transfusion"), "Fail to preprocess and skip to detect."); + return false; + } + proc_timing.emplace( + "debug/processing_time/preprocess_ms", stop_watch_ptr_->toc("processing/inner", true)); + + if (!inference()) { + RCLCPP_WARN_STREAM( + rclcpp::get_logger("lidar_transfusion"), "Fail to inference and skip to detect."); + return false; + } + proc_timing.emplace( + "debug/processing_time/inference_ms", stop_watch_ptr_->toc("processing/inner", true)); + + if (!postprocess(det_boxes3d)) { + RCLCPP_WARN_STREAM( + rclcpp::get_logger("lidar_transfusion"), "Fail to postprocess and skip to detect."); + return false; + } + proc_timing.emplace( + "debug/processing_time/postprocess_ms", stop_watch_ptr_->toc("processing/inner", true)); + + return true; +} + +bool TransfusionTRT::preprocess( + const sensor_msgs::msg::PointCloud2 & msg, const tf2_ros::Buffer & tf_buffer) +{ + if (!vg_ptr_->enqueuePointCloud(msg, tf_buffer)) { + return false; + } + + cuda::clear_async(cls_output_d_.get(), cls_size_, stream_); + cuda::clear_async(box_output_d_.get(), box_size_, stream_); + cuda::clear_async(dir_cls_output_d_.get(), dir_cls_size_, stream_); + cuda::clear_async(voxel_features_d_.get(), voxel_features_size_, stream_); + cuda::clear_async(voxel_num_d_.get(), voxel_num_size_, stream_); + cuda::clear_async(voxel_idxs_d_.get(), voxel_idxs_size_, stream_); + cuda::clear_async(params_input_d_.get(), 1, stream_); + cuda::clear_async( + points_d_.get(), config_.cloud_capacity_ * config_.num_point_feature_size_, stream_); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + + const auto count = vg_ptr_->generateSweepPoints(msg, points_d_); + RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lidar_transfusion"), "Generated sweep points: " << count); + + pre_ptr_->generateVoxels( + points_d_.get(), count, params_input_d_.get(), voxel_features_d_.get(), voxel_num_d_.get(), + voxel_idxs_d_.get()); + unsigned int params_input; + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + + CHECK_CUDA_ERROR(cudaMemcpyAsync( + ¶ms_input, params_input_d_.get(), sizeof(unsigned int), cudaMemcpyDeviceToHost, stream_)); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + + if (params_input < config_.min_voxel_size_) { + RCLCPP_WARN_STREAM( + rclcpp::get_logger("lidar_transfusion"), + "Too few voxels (" << params_input << ") for actual optimization profile (" + << config_.min_voxel_size_ << ")"); + return false; + } + + if (params_input > config_.max_voxels_) { + params_input = config_.max_voxels_; + } + RCLCPP_DEBUG_STREAM( + rclcpp::get_logger("lidar_transfusion"), "Generated input voxels: " << params_input); + + network_trt_ptr_->context->setTensorAddress( + network_trt_ptr_->getTensorName(NetworkIO::voxels), voxel_features_d_.get()); + network_trt_ptr_->context->setInputShape( + network_trt_ptr_->getTensorName(NetworkIO::voxels), + nvinfer1::Dims3{ + static_cast(params_input), static_cast(config_.max_num_points_per_pillar_), + static_cast(config_.num_point_feature_size_)}); + network_trt_ptr_->context->setTensorAddress( + network_trt_ptr_->getTensorName(NetworkIO::num_points), voxel_num_d_.get()); + network_trt_ptr_->context->setInputShape( + network_trt_ptr_->getTensorName(NetworkIO::num_points), + nvinfer1::Dims{1, {static_cast(params_input)}}); + network_trt_ptr_->context->setTensorAddress( + network_trt_ptr_->getTensorName(NetworkIO::coors), voxel_idxs_d_.get()); + network_trt_ptr_->context->setInputShape( + network_trt_ptr_->getTensorName(NetworkIO::coors), + nvinfer1::Dims2{ + static_cast(params_input), static_cast(config_.num_point_values_)}); + network_trt_ptr_->context->setTensorAddress( + network_trt_ptr_->getTensorName(NetworkIO::cls_score), cls_output_d_.get()); + network_trt_ptr_->context->setTensorAddress( + network_trt_ptr_->getTensorName(NetworkIO::bbox_pred), box_output_d_.get()); + network_trt_ptr_->context->setTensorAddress( + network_trt_ptr_->getTensorName(NetworkIO::dir_pred), dir_cls_output_d_.get()); + return true; +} + +bool TransfusionTRT::inference() +{ + auto status = network_trt_ptr_->context->enqueueV3(stream_); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + + if (!status) { + RCLCPP_WARN_STREAM( + rclcpp::get_logger("lidar_transfusion"), "Fail to enqueue and skip to detect."); + return false; + } + return true; +} + +bool TransfusionTRT::postprocess(std::vector & det_boxes3d) +{ + CHECK_CUDA_ERROR(post_ptr_->generateDetectedBoxes3D_launch( + cls_output_d_.get(), box_output_d_.get(), dir_cls_output_d_.get(), det_boxes3d, stream_)); + CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + return true; +} + +} // namespace lidar_transfusion diff --git a/perception/lidar_transfusion/package.xml b/perception/lidar_transfusion/package.xml new file mode 100644 index 0000000000000..29643d0957eb1 --- /dev/null +++ b/perception/lidar_transfusion/package.xml @@ -0,0 +1,34 @@ + + + + lidar_transfusion + 1.0.0 + The lidar_transfusion package + Amadeusz Szymko + Kenzo Lobos-Tsunekawa + Satoshi Tanaka + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + autoware_perception_msgs + launch_ros + object_recognition_utils + pcl_ros + rclcpp + rclcpp_components + tensorrt_common + tf2_eigen + tf2_geometry_msgs + tf2_sensor_msgs + tier4_autoware_utils + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/perception/lidar_transfusion/schema/detection_class_remapper.schema.json b/perception/lidar_transfusion/schema/detection_class_remapper.schema.json new file mode 100644 index 0000000000000..8aaefa295fcc0 --- /dev/null +++ b/perception/lidar_transfusion/schema/detection_class_remapper.schema.json @@ -0,0 +1,72 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Detection Class Remapper", + "type": "object", + "definitions": { + "detection_class_remapper": { + "type": "object", + "properties": { + "allow_remapping_by_area_matrix": { + "type": "array", + "items": { + "type": "integer" + }, + "description": "Whether to allow remapping of classes. The order of 8x8 matrix classes comes from ObjectClassification msg.", + "default": [ + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 1, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0 + ], + "minItems": 64, + "maxItems": 64 + }, + "min_area_matrix": { + "type": "array", + "items": { + "type": "number" + }, + "description": "Minimum area for specific class to consider class remapping.", + "default": [ + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 12.1, 0.0, 36.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 36.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 36.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 + ], + "minItems": 64, + "maxItems": 64 + }, + "max_area_matrix": { + "type": "array", + "items": { + "type": "number" + }, + "description": "Maximum area for specific class to consider class remapping.", + "default": [ + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 36.0, 0.0, 999.999, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 999.999, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 + ], + "minItems": 64, + "maxItems": 64 + } + }, + "required": ["allow_remapping_by_area_matrix", "min_area_matrix", "max_area_matrix"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/detection_class_remapper" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/lidar_transfusion/schema/transfusion.schema.json b/perception/lidar_transfusion/schema/transfusion.schema.json new file mode 100644 index 0000000000000..41d8d887236a8 --- /dev/null +++ b/perception/lidar_transfusion/schema/transfusion.schema.json @@ -0,0 +1,160 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for LiDAR TransFusion Node", + "type": "object", + "definitions": { + "transfusion": { + "type": "object", + "properties": { + "class_names": { + "type": "array", + "items": { + "type": "string" + }, + "description": "An array of class names will be predicted.", + "default": ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"], + "uniqueItems": true + }, + "trt_precision": { + "type": "string", + "description": "A precision of TensorRT engine.", + "default": "fp16", + "enum": ["fp16", "fp32"] + }, + "voxels_num": { + "type": "array", + "items": { + "type": "integer" + }, + "description": "A maximum number of voxels [min, opt, max].", + "default": [5000, 30000, 60000] + }, + "point_cloud_range": { + "type": "array", + "items": { + "type": "number" + }, + "description": "An array of distance ranges of each class.", + "default": [-76.8, -76.8, -3.0, 76.8, 76.8, 5.0], + "minItems": 6, + "maxItems": 6 + }, + "voxel_size": { + "type": "array", + "items": { + "type": "number" + }, + "description": "Voxels size [x, y, z].", + "default": [0.3, 0.3, 8.0], + "minItems": 3, + "maxItems": 3 + }, + "onnx_path": { + "type": "string", + "description": "A path to ONNX model file.", + "default": "$(var model_path)/transfusion.onnx", + "pattern": "\\.onnx$" + }, + "engine_path": { + "type": "string", + "description": "A path to TensorRT engine file.", + "default": "$(var model_path)/transfusion.engine", + "pattern": "\\.engine$" + }, + "down_sample_factor": { + "type": "integer", + "description": "A scale factor of downsampling points", + "default": 1, + "minimum": 1 + }, + "densification_num_past_frames": { + "type": "integer", + "description": "A number of past frames to be considered as same input frame.", + "default": 1, + "minimum": 0 + }, + "densification_world_frame_id": { + "type": "string", + "description": "A name of frame id where world coordinates system is defined with respect to.", + "default": "map" + }, + "circle_nms_dist_threshold": { + "type": "number", + "description": "A distance threshold between detections in NMS.", + "default": 0.5, + "minimum": 0.0 + }, + "iou_nms_target_class_names": { + "type": "array", + "items": { + "type": "string" + }, + "description": "An array of class names to be target in NMS.", + "default": ["CAR"], + "uniqueItems": true + }, + "iou_nms_search_distance_2d": { + "type": "number", + "description": "A maximum distance value to search the nearest objects.", + "default": 10.0, + "minimum": 0.0 + }, + "iou_nms_threshold": { + "type": "number", + "description": "A threshold value of NMS using IoU score.", + "default": 0.1, + "minimum": 0.0, + "maximum": 1.0 + }, + "yaw_norm_thresholds": { + "type": "array", + "items": { + "type": "number", + "minimum": 0.0, + "maximum": 1.0 + }, + "description": "A thresholds array of direction vectors norm, all of objects with vector norm less than this threshold are ignored.", + "default": [0.3, 0.3, 0.3, 0.3, 0.0] + }, + "score_threshold": { + "type": "number", + "description": "A threshold value of confidence score, all of objects with score less than this threshold are ignored.", + "default": 0.2, + "minimum": 0.0 + } + }, + "required": [ + "class_names", + "trt_precision", + "voxels_num", + "point_cloud_range", + "voxel_size", + "onnx_path", + "engine_path", + "densification_num_past_frames", + "densification_world_frame_id", + "circle_nms_dist_threshold", + "iou_nms_target_class_names", + "iou_nms_search_distance_2d", + "iou_nms_threshold", + "yaw_norm_thresholds", + "score_threshold" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/transfusion" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/lidar_transfusion/src/lidar_transfusion_node.cpp b/perception/lidar_transfusion/src/lidar_transfusion_node.cpp new file mode 100644 index 0000000000000..9313015002973 --- /dev/null +++ b/perception/lidar_transfusion/src/lidar_transfusion_node.cpp @@ -0,0 +1,178 @@ +// 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 "lidar_transfusion/lidar_transfusion_node.hpp" + +#include "lidar_transfusion/utils.hpp" + +namespace lidar_transfusion +{ + +LidarTransfusionNode::LidarTransfusionNode(const rclcpp::NodeOptions & options) +: Node("lidar_transfusion", options), tf_buffer_(this->get_clock()) +{ + auto descriptor = rcl_interfaces::msg::ParameterDescriptor{}.set__read_only(true); + // network + class_names_ = this->declare_parameter>("class_names", descriptor); + const std::string trt_precision = + this->declare_parameter("trt_precision", descriptor); + const auto voxels_num = this->declare_parameter>("voxels_num", descriptor); + const auto point_cloud_range = + this->declare_parameter>("point_cloud_range", descriptor); + const auto voxel_size = this->declare_parameter>("voxel_size", descriptor); + const std::string onnx_path = this->declare_parameter("onnx_path", descriptor); + const std::string engine_path = this->declare_parameter("engine_path", descriptor); + + if (point_cloud_range.size() != 6) { + RCLCPP_WARN_STREAM( + rclcpp::get_logger("lidar_transfusion"), + "The size of point_cloud_range != 6: use the default parameters."); + } + if (voxel_size.size() != 3) { + RCLCPP_WARN_STREAM( + rclcpp::get_logger("lidar_transfusion"), + "The size of voxel_size != 3: use the default parameters."); + } + + // pre-process + const std::string densification_world_frame_id = + this->declare_parameter("densification_world_frame_id", descriptor); + const int densification_num_past_frames = + this->declare_parameter("densification_num_past_frames", descriptor); + + // post-process + const float circle_nms_dist_threshold = + static_cast(this->declare_parameter("circle_nms_dist_threshold", descriptor)); + { // IoU NMS + NMSParams p; + p.nms_type_ = NMS_TYPE::IoU_BEV; + p.target_class_names_ = + this->declare_parameter>("iou_nms_target_class_names", descriptor); + p.search_distance_2d_ = + this->declare_parameter("iou_nms_search_distance_2d", descriptor); + p.iou_threshold_ = this->declare_parameter("iou_nms_threshold", descriptor); + iou_bev_nms_.setParameters(p); + } + const auto yaw_norm_thresholds = + this->declare_parameter>("yaw_norm_thresholds", descriptor); + const float score_threshold = + static_cast(this->declare_parameter("score_threshold", descriptor)); + + NetworkParam network_param(onnx_path, engine_path, trt_precision); + DensificationParam densification_param( + densification_world_frame_id, densification_num_past_frames); + TransfusionConfig config( + voxels_num, point_cloud_range, voxel_size, circle_nms_dist_threshold, yaw_norm_thresholds, + score_threshold); + + const auto allow_remapping_by_area_matrix = + this->declare_parameter>("allow_remapping_by_area_matrix", descriptor); + const auto min_area_matrix = + this->declare_parameter>("min_area_matrix", descriptor); + const auto max_area_matrix = + this->declare_parameter>("max_area_matrix", descriptor); + detection_class_remapper_.setParameters( + allow_remapping_by_area_matrix, min_area_matrix, max_area_matrix); + + detector_ptr_ = std::make_unique(network_param, densification_param, config); + + cloud_sub_ = this->create_subscription( + "~/input/pointcloud", rclcpp::SensorDataQoS{}.keep_last(1), + std::bind(&LidarTransfusionNode::cloudCallback, this, std::placeholders::_1)); + + objects_pub_ = this->create_publisher( + "~/output/objects", rclcpp::QoS(1)); + + published_time_pub_ = std::make_unique(this); + + // initialize debug tool + { + using tier4_autoware_utils::DebugPublisher; + using tier4_autoware_utils::StopWatch; + stop_watch_ptr_ = std::make_unique>(); + debug_publisher_ptr_ = std::make_unique(this, this->get_name()); + stop_watch_ptr_->tic("cyclic"); + stop_watch_ptr_->tic("processing/total"); + } + + if (this->declare_parameter("build_only", false, descriptor)) { + RCLCPP_INFO(this->get_logger(), "TensorRT engine is built and shutdown node."); + rclcpp::shutdown(); + } +} + +void LidarTransfusionNode::cloudCallback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg) +{ + const auto objects_sub_count = + objects_pub_->get_subscription_count() + objects_pub_->get_intra_process_subscription_count(); + if (objects_sub_count < 1) { + return; + } + + if (stop_watch_ptr_) { + stop_watch_ptr_->toc("processing/total", true); + } + + std::vector det_boxes3d; + std::unordered_map proc_timing; + bool is_success = detector_ptr_->detect(*msg, tf_buffer_, det_boxes3d, proc_timing); + if (!is_success) { + return; + } + + std::vector raw_objects; + raw_objects.reserve(det_boxes3d.size()); + for (const auto & box3d : det_boxes3d) { + autoware_perception_msgs::msg::DetectedObject obj; + box3DToDetectedObject(box3d, class_names_, obj); + raw_objects.emplace_back(obj); + } + + autoware_perception_msgs::msg::DetectedObjects output_msg; + output_msg.header = msg->header; + output_msg.objects = iou_bev_nms_.apply(raw_objects); + + detection_class_remapper_.mapClasses(output_msg); + + if (objects_sub_count > 0) { + objects_pub_->publish(output_msg); + published_time_pub_->publish_if_subscribed(objects_pub_, output_msg.header.stamp); + } + + // add processing time for debug + if (debug_publisher_ptr_ && stop_watch_ptr_) { + const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic", true); + const double processing_time_ms = stop_watch_ptr_->toc("processing/total", true); + const double pipeline_latency_ms = + std::chrono::duration( + std::chrono::nanoseconds( + (this->get_clock()->now() - output_msg.header.stamp).nanoseconds())) + .count(); + debug_publisher_ptr_->publish( + "debug/cyclic_time_ms", cyclic_time_ms); + debug_publisher_ptr_->publish( + "debug/pipeline_latency_ms", pipeline_latency_ms); + debug_publisher_ptr_->publish( + "debug/processing_time/total_ms", processing_time_ms); + for (const auto & [topic, time_ms] : proc_timing) { + debug_publisher_ptr_->publish(topic, time_ms); + } + } +} + +} // namespace lidar_transfusion + +#include "rclcpp_components/register_node_macro.hpp" + +RCLCPP_COMPONENTS_REGISTER_NODE(lidar_transfusion::LidarTransfusionNode) From f328a157b637e10fc3304d18992b52de9f4803a6 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Sat, 8 Jun 2024 01:49:59 +0900 Subject: [PATCH 31/65] fix(autoware_planning_validator): revert node name change (#7371) revert node name change Signed-off-by: kyoichi-sugahara --- .../planning_validator/launch/planning_validator.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/planning_validator/launch/planning_validator.launch.xml b/planning/planning_validator/launch/planning_validator.launch.xml index fa1475a0787e4..aeb9c37d67cda 100644 --- a/planning/planning_validator/launch/planning_validator.launch.xml +++ b/planning/planning_validator/launch/planning_validator.launch.xml @@ -3,7 +3,7 @@ - + From 57786a719c27fb7f5082f627ddbbee17c87f83f3 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Sat, 8 Jun 2024 01:41:26 +0200 Subject: [PATCH 32/65] refactor(behavior_path_avoidance_by_lane_change_module)!: prefix package and namespace with autoware_ (#6638) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * build(behavior_path_avoidance_by_lane_change_module): prefix package and namespace with autoware_ Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * build(autoware_behavior_path_avoidance_by_lane_change_module): fix namespaces Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * fix(autoware_behavior_path_avoidance_by_lane_change_module): fix clang-tidy issues Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * fix(autoware_behavior_path_avoidance_by_lane_change_module): fix tests Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * fix(autoware_behavior_path_avoidance_by_lane_change_module): fix clang-tidy issues Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * build(autoware_behavior_path_avoidance_by_lane_change_module): revert clang-tidy fixes for naming functions Signed-off-by: Esteve Fernandez * build(autoware_behavior_path_avoidance_by_lane_change_module): revert clang-tidy fixes for naming functions Signed-off-by: Esteve Fernandez * build(autoware_behavior_path_external_request_lane_change_module): revert performance-related clang-tidy fixes Signed-off-by: Esteve Fernandez * build(autoware_behavior_path_avoidance_by_lane_change_module): revert clang-tidy fixes for naming functions Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * refactor(autoware_behavior_path_avoidance_by_lane_change_module): update CODEOWNERS and .pages files Signed-off-by: Esteve Fernandez * refactor(autoware_behavior_path_avoidance_by_lane_change_module): move headers files to src Signed-off-by: Esteve Fernandez * refactor(autoware_behavior_path_avoidance_by_lane_change_module): fix include paths Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * Update planning/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp Co-authored-by: M. Fatih Cırıt Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * build: fix missing using clauses Signed-off-by: Esteve Fernandez --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: M. Fatih Cırıt --- .github/CODEOWNERS | 2 +- planning/.pages | 2 +- .../CMakeLists.txt | 2 +- .../README.md | 0 .../avoidance_by_lane_change.param.yaml | 0 .../images/avoidance_by_lane_change.svg | 0 .../images/avoidance_by_lc_trigger_1.svg | 0 .../images/avoidance_by_lc_trigger_2.svg | 0 .../package.xml | 2 +- .../plugins.xml | 3 ++ .../src}/data_structs.hpp | 12 ++++---- .../src/interface.cpp | 9 ++++-- .../src}/interface.hpp | 18 ++++++----- .../src/manager.cpp | 14 +++++---- .../src}/manager.hpp | 19 +++++++----- .../src/scene.cpp | 14 ++++++--- .../src}/scene.hpp | 21 ++++++++----- ...t_behavior_path_planner_node_interface.cpp | 30 +++++++++---------- .../plugins.xml | 3 -- 19 files changed, 89 insertions(+), 62 deletions(-) rename planning/{behavior_path_avoidance_by_lane_change_module => autoware_behavior_path_avoidance_by_lane_change_module}/CMakeLists.txt (90%) rename planning/{behavior_path_avoidance_by_lane_change_module => autoware_behavior_path_avoidance_by_lane_change_module}/README.md (100%) rename planning/{behavior_path_avoidance_by_lane_change_module => autoware_behavior_path_avoidance_by_lane_change_module}/config/avoidance_by_lane_change.param.yaml (100%) rename planning/{behavior_path_avoidance_by_lane_change_module => autoware_behavior_path_avoidance_by_lane_change_module}/images/avoidance_by_lane_change.svg (100%) rename planning/{behavior_path_avoidance_by_lane_change_module => autoware_behavior_path_avoidance_by_lane_change_module}/images/avoidance_by_lc_trigger_1.svg (100%) rename planning/{behavior_path_avoidance_by_lane_change_module => autoware_behavior_path_avoidance_by_lane_change_module}/images/avoidance_by_lc_trigger_2.svg (100%) rename planning/{behavior_path_avoidance_by_lane_change_module => autoware_behavior_path_avoidance_by_lane_change_module}/package.xml (95%) create mode 100644 planning/autoware_behavior_path_avoidance_by_lane_change_module/plugins.xml rename planning/{behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module => autoware_behavior_path_avoidance_by_lane_change_module/src}/data_structs.hpp (79%) rename planning/{behavior_path_avoidance_by_lane_change_module => autoware_behavior_path_avoidance_by_lane_change_module}/src/interface.cpp (92%) rename planning/{behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module => autoware_behavior_path_avoidance_by_lane_change_module/src}/interface.hpp (77%) rename planning/{behavior_path_avoidance_by_lane_change_module => autoware_behavior_path_avoidance_by_lane_change_module}/src/manager.cpp (96%) rename planning/{behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module => autoware_behavior_path_avoidance_by_lane_change_module/src}/manager.hpp (73%) rename planning/{behavior_path_avoidance_by_lane_change_module => autoware_behavior_path_avoidance_by_lane_change_module}/src/scene.cpp (96%) rename planning/{behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module => autoware_behavior_path_avoidance_by_lane_change_module/src}/scene.hpp (76%) rename planning/{behavior_path_avoidance_by_lane_change_module => autoware_behavior_path_avoidance_by_lane_change_module}/test/test_behavior_path_planner_node_interface.cpp (79%) delete mode 100644 planning/behavior_path_avoidance_by_lane_change_module/plugins.xml diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index be202d123cd62..297ce75c5c176 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -144,6 +144,7 @@ perception/traffic_light_map_based_detector/** shunsuke.miura@tier4.jp tao.zhong perception/traffic_light_multi_camera_fusion/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/traffic_light_occlusion_predictor/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/traffic_light_visualization/** tao.zhong@tier4.jp yukihiro.saito@tier4.jp +planning/autoware_behavior_path_avoidance_by_lane_change_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp planning/autoware_behavior_path_external_request_lane_change_module/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/autoware_behavior_path_planner_common/** daniel.sanchez@tier4.jp fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp @@ -161,7 +162,6 @@ planning/autoware_planning_topic_converter/** kosuke.takeuchi@tier4.jp satoshi.o planning/autoware_remaining_distance_time_calculator/** ahmed.ebrahim@leodrive.ai planning/autoware_static_centerline_generator/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp planning/autoware_velocity_smoother/** fumiya.watanabe@tier4.jp makoto.kurihara@tier4.jp satoshi.ota@tier4.jp takamasa.horibe@tier4.jp -planning/behavior_path_avoidance_by_lane_change_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_goal_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_path_lane_change_module/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_planner/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp diff --git a/planning/.pages b/planning/.pages index 2decfad30e0da..be6bf0af9b2a9 100644 --- a/planning/.pages +++ b/planning/.pages @@ -10,7 +10,7 @@ nav: - '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 - 'Scene Module': - - 'Avoidance by Lane Change': planning/behavior_path_avoidance_by_lane_change_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/behavior_path_goal_planner_module - 'Lane Change': planning/behavior_path_lane_change_module diff --git a/planning/behavior_path_avoidance_by_lane_change_module/CMakeLists.txt b/planning/autoware_behavior_path_avoidance_by_lane_change_module/CMakeLists.txt similarity index 90% rename from planning/behavior_path_avoidance_by_lane_change_module/CMakeLists.txt rename to planning/autoware_behavior_path_avoidance_by_lane_change_module/CMakeLists.txt index bca909c7cef7e..2ab88e04f96e5 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/CMakeLists.txt +++ b/planning/autoware_behavior_path_avoidance_by_lane_change_module/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(behavior_path_avoidance_by_lane_change_module) +project(autoware_behavior_path_avoidance_by_lane_change_module) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/planning/behavior_path_avoidance_by_lane_change_module/README.md b/planning/autoware_behavior_path_avoidance_by_lane_change_module/README.md similarity index 100% rename from planning/behavior_path_avoidance_by_lane_change_module/README.md rename to planning/autoware_behavior_path_avoidance_by_lane_change_module/README.md diff --git a/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lane_change.param.yaml b/planning/autoware_behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lane_change.param.yaml similarity index 100% rename from planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lane_change.param.yaml rename to planning/autoware_behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lane_change.param.yaml diff --git a/planning/behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lane_change.svg b/planning/autoware_behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lane_change.svg similarity index 100% rename from planning/behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lane_change.svg rename to planning/autoware_behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lane_change.svg diff --git a/planning/behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lc_trigger_1.svg b/planning/autoware_behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lc_trigger_1.svg similarity index 100% rename from planning/behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lc_trigger_1.svg rename to planning/autoware_behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lc_trigger_1.svg diff --git a/planning/behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lc_trigger_2.svg b/planning/autoware_behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lc_trigger_2.svg similarity index 100% rename from planning/behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lc_trigger_2.svg rename to planning/autoware_behavior_path_avoidance_by_lane_change_module/images/avoidance_by_lc_trigger_2.svg diff --git a/planning/behavior_path_avoidance_by_lane_change_module/package.xml b/planning/autoware_behavior_path_avoidance_by_lane_change_module/package.xml similarity index 95% rename from planning/behavior_path_avoidance_by_lane_change_module/package.xml rename to planning/autoware_behavior_path_avoidance_by_lane_change_module/package.xml index 57e30bd628e08..3a75849931228 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/package.xml +++ b/planning/autoware_behavior_path_avoidance_by_lane_change_module/package.xml @@ -1,7 +1,7 @@ - behavior_path_avoidance_by_lane_change_module + autoware_behavior_path_avoidance_by_lane_change_module 0.1.0 The behavior_path_avoidance_by_lane_change_module package diff --git a/planning/autoware_behavior_path_avoidance_by_lane_change_module/plugins.xml b/planning/autoware_behavior_path_avoidance_by_lane_change_module/plugins.xml new file mode 100644 index 0000000000000..848d978329866 --- /dev/null +++ b/planning/autoware_behavior_path_avoidance_by_lane_change_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp b/planning/autoware_behavior_path_avoidance_by_lane_change_module/src/data_structs.hpp similarity index 79% rename from planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp rename to planning/autoware_behavior_path_avoidance_by_lane_change_module/src/data_structs.hpp index d7fd8b82bd71e..01f2fd7f1ee52 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp +++ b/planning/autoware_behavior_path_avoidance_by_lane_change_module/src/data_structs.hpp @@ -11,13 +11,15 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__DATA_STRUCTS_HPP_ -#define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__DATA_STRUCTS_HPP_ +#ifndef DATA_STRUCTS_HPP_ +#define DATA_STRUCTS_HPP_ #include "autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp" -namespace behavior_path_planner +namespace autoware::behavior_path_planner { +using ::behavior_path_planner::AvoidanceParameters; + struct AvoidanceByLCParameters : public AvoidanceParameters { // execute only when the target object longitudinal distance is larger than this param. @@ -30,6 +32,6 @@ struct AvoidanceByLCParameters : public AvoidanceParameters { } }; -} // namespace behavior_path_planner +} // namespace autoware::behavior_path_planner -#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__DATA_STRUCTS_HPP_ +#endif // DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp b/planning/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp similarity index 92% rename from planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp rename to planning/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp index bae9112e6d840..c5070540152de 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp +++ b/planning/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_avoidance_by_lane_change_module/interface.hpp" +#include "interface.hpp" #include "autoware_behavior_path_planner_common/interface/scene_module_interface.hpp" #include "autoware_behavior_path_planner_common/interface/scene_module_visitor.hpp" @@ -20,8 +20,11 @@ #include #include -namespace behavior_path_planner +namespace autoware::behavior_path_planner { +using ::behavior_path_planner::State; +using ::route_handler::Direction; + AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface( const std::string & name, rclcpp::Node & node, const std::shared_ptr & parameters, @@ -63,4 +66,4 @@ void AvoidanceByLaneChangeInterface::updateRTCStatus( uuid_map_.at(direction), isExecutionReady(), state, start_distance, finish_distance, clock_->now()); } -} // namespace behavior_path_planner +} // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp b/planning/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp similarity index 77% rename from planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp rename to planning/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp index 897956a392008..75413c4dccfa6 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/interface.hpp +++ b/planning/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__INTERFACE_HPP_ -#define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__INTERFACE_HPP_ +#ifndef INTERFACE_HPP_ +#define INTERFACE_HPP_ -#include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" -#include "behavior_path_avoidance_by_lane_change_module/scene.hpp" #include "behavior_path_lane_change_module/interface.hpp" +#include "data_structs.hpp" +#include "scene.hpp" #include @@ -25,8 +25,12 @@ #include #include -namespace behavior_path_planner +namespace autoware::behavior_path_planner { +using ::behavior_path_planner::LaneChangeInterface; +using ::behavior_path_planner::ObjectsOfInterestMarkerInterface; +using ::behavior_path_planner::RTCInterface; + class AvoidanceByLaneChangeInterface : public LaneChangeInterface { public: @@ -45,6 +49,6 @@ class AvoidanceByLaneChangeInterface : public LaneChangeInterface protected: void updateRTCStatus(const double start_distance, const double finish_distance) override; }; -} // namespace behavior_path_planner +} // namespace autoware::behavior_path_planner -#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__INTERFACE_HPP_ +#endif // INTERFACE_HPP_ diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp b/planning/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp similarity index 96% rename from planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp rename to planning/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp index 868b2585170f9..792f0e93ac1b7 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp +++ b/planning/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_avoidance_by_lane_change_module/manager.hpp" +#include "manager.hpp" #include "autoware_behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp" -#include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" +#include "data_structs.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" @@ -25,8 +25,10 @@ #include #include -namespace behavior_path_planner +namespace autoware::behavior_path_planner { +using ::behavior_path_planner::getParameter; +using ::behavior_path_planner::ObjectParameter; void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) { @@ -191,9 +193,9 @@ AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance() objects_of_interest_marker_interface_ptr_map_); } -} // namespace behavior_path_planner +} // namespace autoware::behavior_path_planner #include PLUGINLIB_EXPORT_CLASS( - behavior_path_planner::AvoidanceByLaneChangeModuleManager, - behavior_path_planner::SceneModuleManagerInterface) + autoware::behavior_path_planner::AvoidanceByLaneChangeModuleManager, + ::behavior_path_planner::SceneModuleManagerInterface) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp b/planning/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.hpp similarity index 73% rename from planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp rename to planning/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.hpp index 75fa67e7fe1a3..f921aa4d7e31c 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp +++ b/planning/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__MANAGER_HPP_ -#define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__MANAGER_HPP_ +#ifndef MANAGER_HPP_ +#define MANAGER_HPP_ -#include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" -#include "behavior_path_avoidance_by_lane_change_module/interface.hpp" #include "behavior_path_lane_change_module/manager.hpp" +#include "data_structs.hpp" +#include "interface.hpp" #include @@ -26,9 +26,12 @@ #include #include -namespace behavior_path_planner +namespace autoware::behavior_path_planner { -using route_handler::Direction; +using ::behavior_path_planner::LaneChangeModuleManager; +using ::behavior_path_planner::LaneChangeModuleType; +using ::behavior_path_planner::SceneModuleInterface; +using ::route_handler::Direction; class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager { @@ -47,6 +50,6 @@ class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager private: std::shared_ptr avoidance_parameters_; }; -} // namespace behavior_path_planner +} // namespace autoware::behavior_path_planner -#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__MANAGER_HPP_ +#endif // MANAGER_HPP_ diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp similarity index 96% rename from planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp rename to planning/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp index e0ebeebba955c..0647147dff0d0 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_avoidance_by_lane_change_module/scene.hpp" +#include "scene.hpp" #include "autoware_behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "autoware_behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" @@ -28,13 +28,19 @@ #include #include +#include #include #include #include -namespace behavior_path_planner +namespace autoware::behavior_path_planner { -using behavior_path_planner::utils::lane_change::debug::createExecutionArea; +using ::behavior_path_planner::Direction; +using ::behavior_path_planner::LaneChangeModuleType; +using ::behavior_path_planner::ObjectInfo; +using ::behavior_path_planner::Point2d; +using ::behavior_path_planner::utils::lane_change::debug::createExecutionArea; +namespace utils = ::behavior_path_planner::utils; AvoidanceByLaneChange::AvoidanceByLaneChange( const std::shared_ptr & parameters, @@ -293,4 +299,4 @@ double AvoidanceByLaneChange::calcLateralOffset() const } return additional_lat_offset; } -} // namespace behavior_path_planner +} // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp b/planning/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.hpp similarity index 76% rename from planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp rename to planning/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.hpp index 4ef4c0673c0c5..6b39340da172a 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp +++ b/planning/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.hpp @@ -12,19 +12,26 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_ -#define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_ +#ifndef SCENE_HPP_ +#define SCENE_HPP_ #include "autoware_behavior_path_static_obstacle_avoidance_module/helper.hpp" -#include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" #include "behavior_path_lane_change_module/scene.hpp" +#include "data_structs.hpp" #include -namespace behavior_path_planner +namespace autoware::behavior_path_planner { +using ::behavior_path_planner::DebugData; using AvoidanceDebugData = DebugData; -using helper::static_obstacle_avoidance::AvoidanceHelper; +using ::behavior_path_planner::AvoidancePlanningData; +using ::behavior_path_planner::LaneChangeParameters; +using ::behavior_path_planner::NormalLaneChange; +using ::behavior_path_planner::ObjectData; +using ::behavior_path_planner::ObjectDataArray; +using ::behavior_path_planner::PredictedObject; +using ::behavior_path_planner::helper::static_obstacle_avoidance::AvoidanceHelper; class AvoidanceByLaneChange : public NormalLaneChange { @@ -59,6 +66,6 @@ class AvoidanceByLaneChange : public NormalLaneChange double calcMinimumLaneChangeLength() const; double calcLateralOffset() const; }; -} // namespace behavior_path_planner +} // namespace autoware::behavior_path_planner -#endif // BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_ +#endif // SCENE_HPP_ diff --git a/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp similarity index 79% rename from planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp rename to planning/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 69ce87aabc7b4..ea7979958e49e 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -23,7 +23,7 @@ #include #include -using behavior_path_planner::BehaviorPathPlannerNode; +using ::behavior_path_planner::BehaviorPathPlannerNode; using planning_test_utils::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() @@ -52,26 +52,26 @@ std::shared_ptr generateNode() ament_index_cpp::get_package_share_directory("behavior_path_lane_change_module"); std::vector module_names; - module_names.emplace_back("behavior_path_planner::AvoidanceByLaneChangeModuleManager"); + module_names.emplace_back("autoware::behavior_path_planner::AvoidanceByLaneChangeModuleManager"); std::vector params; params.emplace_back("launch_modules", module_names); node_options.parameter_overrides(params); test_utils::updateNodeOptions( - node_options, - {planning_test_utils_dir + "/config/test_common.param.yaml", - planning_test_utils_dir + "/config/test_nearest_search.param.yaml", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", - behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", - behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", - behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - behavior_path_lane_change_module_dir + "/config/lane_change.param.yaml", - ament_index_cpp::get_package_share_directory( - "autoware_behavior_path_static_obstacle_avoidance_module") + - "/config/static_obstacle_avoidance.param.yaml", - ament_index_cpp::get_package_share_directory("behavior_path_avoidance_by_lane_change_module") + - "/config/avoidance_by_lane_change.param.yaml"}); + node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", + planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", + behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", + behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", + behavior_path_lane_change_module_dir + "/config/lane_change.param.yaml", + ament_index_cpp::get_package_share_directory( + "autoware_behavior_path_static_obstacle_avoidance_module") + + "/config/static_obstacle_avoidance.param.yaml", + ament_index_cpp::get_package_share_directory( + "autoware_behavior_path_avoidance_by_lane_change_module") + + "/config/avoidance_by_lane_change.param.yaml"}); return std::make_shared(node_options); } diff --git a/planning/behavior_path_avoidance_by_lane_change_module/plugins.xml b/planning/behavior_path_avoidance_by_lane_change_module/plugins.xml deleted file mode 100644 index 092d54c096ae9..0000000000000 --- a/planning/behavior_path_avoidance_by_lane_change_module/plugins.xml +++ /dev/null @@ -1,3 +0,0 @@ - - - From 7d12dcf51966c9c0217e8f26b7a7d9d816cbe81b Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 8 Jun 2024 23:09:04 +0900 Subject: [PATCH 33/65] fix(tier4_planning_launch): unexpected modules were registered (#7377) Signed-off-by: Takayuki Murooka --- .../behavior_planning/behavior_planning.launch.xml | 2 +- .../motion_planning/motion_planning.launch.xml | 12 ++++++------ 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 779ee5c7af34a..fdb6bc1d90643 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -92,7 +92,7 @@ /> diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 4ed38df2d3f09..0b82057144f0e 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -3,7 +3,7 @@ - + @@ -13,11 +13,11 @@ value="$(eval "'$(var motion_velocity_planner_launch_modules)' + 'autoware::motion_velocity_planner::OutOfLaneModule, '")" if="$(var launch_motion_out_of_lane_module)" /> - + + + + + From 3b036b156b2389a6e1794ba629d2ea80e456e22d Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 9 Jun 2024 00:15:27 +0900 Subject: [PATCH 34/65] feat(autoware_velocity_smoother): use polling subscriber (#7216) feat(motion_velocity_smoother): use polling subscriber Signed-off-by: Takayuki Murooka --- .../autoware_velocity_smoother/node.hpp | 17 +++++----- .../autoware_velocity_smoother/src/node.cpp | 32 ++++++------------- 2 files changed, 18 insertions(+), 31 deletions(-) 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 8ab7acd5ec9b3..160ee183d8a0a 100644 --- a/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/node.hpp +++ b/planning/autoware_velocity_smoother/include/autoware_velocity_smoother/node.hpp @@ -31,6 +31,7 @@ #include "tier4_autoware_utils/geometry/geometry.hpp" #include "tier4_autoware_utils/math/unit_conversion.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" +#include "tier4_autoware_utils/ros/polling_subscriber.hpp" #include "tier4_autoware_utils/ros/self_pose_listener.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" @@ -86,11 +87,15 @@ class VelocitySmootherNode : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_trajectory_; rclcpp::Publisher::SharedPtr pub_virtual_wall_; rclcpp::Publisher::SharedPtr pub_over_stop_velocity_; - rclcpp::Subscription::SharedPtr sub_current_odometry_; - rclcpp::Subscription::SharedPtr sub_current_acceleration_; rclcpp::Subscription::SharedPtr sub_current_trajectory_; - rclcpp::Subscription::SharedPtr sub_external_velocity_limit_; - rclcpp::Subscription::SharedPtr sub_operation_mode_; + tier4_autoware_utils::InterProcessPollingSubscriber sub_current_odometry_{ + this, "/localization/kinematic_state"}; + tier4_autoware_utils::InterProcessPollingSubscriber + sub_current_acceleration_{this, "~/input/acceleration"}; + tier4_autoware_utils::InterProcessPollingSubscriber sub_external_velocity_limit_{ + this, "~/input/external_velocity_limit_mps"}; + tier4_autoware_utils::InterProcessPollingSubscriber sub_operation_mode_{ + this, "~/input/operation_mode_state"}; Odometry::ConstSharedPtr current_odometry_ptr_; // current odometry AccelWithCovarianceStamped::ConstSharedPtr current_acceleration_ptr_; @@ -180,12 +185,8 @@ class VelocitySmootherNode : public rclcpp::Node const std::vector & parameters); // topic callback - void onCurrentOdometry(const Odometry::ConstSharedPtr msg); - void onCurrentTrajectory(const Trajectory::ConstSharedPtr msg); - void onExternalVelocityLimit(const VelocityLimit::ConstSharedPtr msg); - void calcExternalVelocityLimit(); // publish methods diff --git a/planning/autoware_velocity_smoother/src/node.cpp b/planning/autoware_velocity_smoother/src/node.cpp index 0fd83871153f0..1541b19d70a1c 100644 --- a/planning/autoware_velocity_smoother/src/node.cpp +++ b/planning/autoware_velocity_smoother/src/node.cpp @@ -58,19 +58,6 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti pub_over_stop_velocity_ = create_publisher("~/stop_speed_exceeded", 1); sub_current_trajectory_ = create_subscription( "~/input/trajectory", 1, std::bind(&VelocitySmootherNode::onCurrentTrajectory, this, _1)); - sub_current_odometry_ = create_subscription( - "/localization/kinematic_state", 1, - std::bind(&VelocitySmootherNode::onCurrentOdometry, this, _1)); - sub_external_velocity_limit_ = create_subscription( - "~/input/external_velocity_limit_mps", 1, - std::bind(&VelocitySmootherNode::onExternalVelocityLimit, this, _1)); - sub_current_acceleration_ = create_subscription( - "~/input/acceleration", 1, [this](const AccelWithCovarianceStamped::ConstSharedPtr msg) { - current_acceleration_ptr_ = msg; - }); - sub_operation_mode_ = create_subscription( - "~/input/operation_mode_state", 1, - [this](const OperationModeState::ConstSharedPtr msg) { operation_mode_ = *msg; }); // parameter update set_param_res_ = @@ -319,16 +306,6 @@ void VelocitySmootherNode::publishTrajectory(const TrajectoryPoints & trajectory pub_trajectory_, publishing_trajectory.header.stamp); } -void VelocitySmootherNode::onCurrentOdometry(const Odometry::ConstSharedPtr msg) -{ - current_odometry_ptr_ = msg; -} - -void VelocitySmootherNode::onExternalVelocityLimit(const VelocityLimit::ConstSharedPtr msg) -{ - external_velocity_limit_ptr_ = msg; -} - void VelocitySmootherNode::calcExternalVelocityLimit() { if (!external_velocity_limit_ptr_) { @@ -441,6 +418,15 @@ void VelocitySmootherNode::onCurrentTrajectory(const Trajectory::ConstSharedPtr base_traj_raw_ptr_ = msg; + // receive data + current_odometry_ptr_ = sub_current_odometry_.takeData(); + current_acceleration_ptr_ = sub_current_acceleration_.takeData(); + external_velocity_limit_ptr_ = sub_external_velocity_limit_.takeData(); + const auto operation_mode_ptr = sub_operation_mode_.takeData(); + if (operation_mode_ptr) { + operation_mode_ = *operation_mode_ptr; + } + // guard if (!checkData()) { return; From 14c75e6b3f5f8129cfa633b4ec370cf65c9106f4 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 9 Jun 2024 02:08:14 +0900 Subject: [PATCH 35/65] feat(joy_controller): use polling subscriber (#7286) Signed-off-by: Takayuki Murooka --- .../include/joy_controller/joy_controller.hpp | 12 +++++---- control/joy_controller/package.xml | 1 + .../joy_controller/joy_controller_node.cpp | 27 +++++++++---------- 3 files changed, 20 insertions(+), 20 deletions(-) diff --git a/control/joy_controller/include/joy_controller/joy_controller.hpp b/control/joy_controller/include/joy_controller/joy_controller.hpp index e88f7bcb3904e..136637f0f1fd3 100644 --- a/control/joy_controller/include/joy_controller/joy_controller.hpp +++ b/control/joy_controller/include/joy_controller/joy_controller.hpp @@ -18,6 +18,7 @@ #include "joy_controller/joy_converter/joy_converter_base.hpp" #include +#include #include #include @@ -66,19 +67,20 @@ class AutowareJoyControllerNode : public rclcpp::Node double backward_accel_ratio_; // CallbackGroups - rclcpp::CallbackGroup::SharedPtr callback_group_subscribers_; rclcpp::CallbackGroup::SharedPtr callback_group_services_; // Subscriber - rclcpp::Subscription::SharedPtr sub_joy_; - rclcpp::Subscription::SharedPtr sub_odom_; + tier4_autoware_utils::InterProcessPollingSubscriber sub_joy_{ + this, "input/joy"}; + tier4_autoware_utils::InterProcessPollingSubscriber sub_odom_{ + this, "input/odometry"}; rclcpp::Time last_joy_received_time_; std::shared_ptr joy_; geometry_msgs::msg::TwistStamped::ConstSharedPtr twist_; - void onJoy(const sensor_msgs::msg::Joy::ConstSharedPtr msg); - void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg); + void onJoy(); + void onOdometry(); // Publisher rclcpp::Publisher::SharedPtr pub_control_command_; diff --git a/control/joy_controller/package.xml b/control/joy_controller/package.xml index f7a5ed805b8ad..f160d561057e8 100644 --- a/control/joy_controller/package.xml +++ b/control/joy_controller/package.xml @@ -26,6 +26,7 @@ sensor_msgs std_srvs tier4_api_utils + tier4_autoware_utils tier4_control_msgs tier4_external_api_msgs diff --git a/control/joy_controller/src/joy_controller/joy_controller_node.cpp b/control/joy_controller/src/joy_controller/joy_controller_node.cpp index 39198825f9c4e..313d4498395b8 100644 --- a/control/joy_controller/src/joy_controller/joy_controller_node.cpp +++ b/control/joy_controller/src/joy_controller/joy_controller_node.cpp @@ -148,8 +148,9 @@ double calcMapping(const double input, const double sensitivity) namespace joy_controller { -void AutowareJoyControllerNode::onJoy(const sensor_msgs::msg::Joy::ConstSharedPtr msg) +void AutowareJoyControllerNode::onJoy() { + const auto msg = sub_joy_.takeData(); last_joy_received_time_ = msg->header.stamp; if (joy_type_ == "G29") { joy_ = std::make_shared(*msg); @@ -190,8 +191,13 @@ void AutowareJoyControllerNode::onJoy(const sensor_msgs::msg::Joy::ConstSharedPt } } -void AutowareJoyControllerNode::onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg) +void AutowareJoyControllerNode::onOdometry() { + if (raw_control_) { + return; + } + + const auto msg = sub_odom_.takeData(); auto twist = std::make_shared(); twist->header = msg->header; twist->twist = msg->twist.twist; @@ -243,6 +249,9 @@ bool AutowareJoyControllerNode::isDataReady() void AutowareJoyControllerNode::onTimer() { + onOdometry(); + onJoy(); + if (!isDataReady()) { return; } @@ -470,23 +479,11 @@ AutowareJoyControllerNode::AutowareJoyControllerNode(const rclcpp::NodeOptions & RCLCPP_INFO(get_logger(), "Joy type: %s", joy_type_.c_str()); // Callback Groups - callback_group_subscribers_ = - this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); callback_group_services_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - auto subscriber_option = rclcpp::SubscriptionOptions(); - subscriber_option.callback_group = callback_group_subscribers_; // Subscriber - sub_joy_ = this->create_subscription( - "input/joy", 1, std::bind(&AutowareJoyControllerNode::onJoy, this, std::placeholders::_1), - subscriber_option); - if (!raw_control_) { - sub_odom_ = this->create_subscription( - "input/odometry", 1, - std::bind(&AutowareJoyControllerNode::onOdometry, this, std::placeholders::_1), - subscriber_option); - } else { + if (raw_control_) { twist_ = std::make_shared(); } From af9db8c22ee26fa0b713bab6a0f85c427edde32c Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 9 Jun 2024 03:16:39 +0900 Subject: [PATCH 36/65] refactor(joy_controller)!: prefix package and namespace with autoware (#7382) * add prefix Signed-off-by: Takayuki Murooka * fix codeowner Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .github/CODEOWNERS | 2 +- .../autoware_joy_controller/CMakeLists.txt | 20 ++++++++++++++++ .../README.md | 10 ++++---- .../config/joy_controller_ds4.param.yaml | 0 .../config/joy_controller_g29.param.yaml | 0 .../config/joy_controller_p65.param.yaml | 0 .../config/joy_controller_xbox.param.yaml | 0 .../joy_controller.hpp | 12 +++++----- .../joy_converter/ds4_joy_converter.hpp | 12 +++++----- .../joy_converter/g29_joy_converter.hpp | 12 +++++----- .../joy_converter/joy_converter_base.hpp | 10 ++++---- .../joy_converter/p65_joy_converter.hpp | 12 +++++----- .../joy_converter/xbox_joy_converter.hpp | 12 +++++----- .../launch/joy_controller.launch.xml | 4 ++-- .../joy_controller_param_selection.launch.xml | 7 ++++++ .../package.xml | 4 ++-- .../schema/joy_controller.schema.json | 4 ++-- .../src}/joy_controller_node.cpp | 24 +++++++++---------- control/joy_controller/CMakeLists.txt | 20 ---------------- .../joy_controller_param_selection.launch.xml | 7 ------ 20 files changed, 86 insertions(+), 86 deletions(-) create mode 100644 control/autoware_joy_controller/CMakeLists.txt rename control/{joy_controller => autoware_joy_controller}/README.md (94%) rename control/{joy_controller => autoware_joy_controller}/config/joy_controller_ds4.param.yaml (100%) rename control/{joy_controller => autoware_joy_controller}/config/joy_controller_g29.param.yaml (100%) rename control/{joy_controller => autoware_joy_controller}/config/joy_controller_p65.param.yaml (100%) rename control/{joy_controller => autoware_joy_controller}/config/joy_controller_xbox.param.yaml (100%) rename control/{joy_controller/include/joy_controller => autoware_joy_controller/include/autoware_joy_controller}/joy_controller.hpp (93%) rename control/{joy_controller/include/joy_controller => autoware_joy_controller/include/autoware_joy_controller}/joy_converter/ds4_joy_converter.hpp (89%) rename control/{joy_controller/include/joy_controller => autoware_joy_controller/include/autoware_joy_controller}/joy_converter/g29_joy_converter.hpp (88%) rename control/{joy_controller/include/joy_controller => autoware_joy_controller/include/autoware_joy_controller}/joy_converter/joy_converter_base.hpp (82%) rename control/{joy_controller/include/joy_controller => autoware_joy_controller/include/autoware_joy_controller}/joy_converter/p65_joy_converter.hpp (88%) rename control/{joy_controller/include/joy_controller => autoware_joy_controller/include/autoware_joy_controller}/joy_converter/xbox_joy_converter.hpp (88%) rename control/{joy_controller => autoware_joy_controller}/launch/joy_controller.launch.xml (89%) create mode 100644 control/autoware_joy_controller/launch/joy_controller_param_selection.launch.xml rename control/{joy_controller => autoware_joy_controller}/package.xml (93%) rename control/{joy_controller => autoware_joy_controller}/schema/joy_controller.schema.json (97%) rename control/{joy_controller/src/joy_controller => autoware_joy_controller/src}/joy_controller_node.cpp (95%) delete mode 100644 control/joy_controller/CMakeLists.txt delete mode 100644 control/joy_controller/launch/joy_controller_param_selection.launch.xml diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 297ce75c5c176..838194e44583c 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -48,7 +48,7 @@ control/autoware_autonomous_emergency_braking/** daniel.sanchez@tier4.jp mamoru. control/control_performance_analysis/** berkay@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/control_validator/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/external_cmd_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -control/joy_controller/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp +control/autoware_joy_controller/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/autoware_lane_departure_checker/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp control/mpc_lateral_controller/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/obstacle_collision_checker/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp diff --git a/control/autoware_joy_controller/CMakeLists.txt b/control/autoware_joy_controller/CMakeLists.txt new file mode 100644 index 0000000000000..9c7d8b3ad475a --- /dev/null +++ b/control/autoware_joy_controller/CMakeLists.txt @@ -0,0 +1,20 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_joy_controller) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(autoware_joy_controller_node SHARED + DIRECTORY src +) + +rclcpp_components_register_node(autoware_joy_controller_node + PLUGIN "autoware::joy_controller::AutowareJoyControllerNode" + EXECUTABLE autoware_joy_controller +) + +ament_auto_package( + INSTALL_TO_SHARE + launch + config +) diff --git a/control/joy_controller/README.md b/control/autoware_joy_controller/README.md similarity index 94% rename from control/joy_controller/README.md rename to control/autoware_joy_controller/README.md index 73e3644df49ac..a6919356f3dbc 100644 --- a/control/joy_controller/README.md +++ b/control/autoware_joy_controller/README.md @@ -1,8 +1,8 @@ -# joy_controller +# autoware_joy_controller ## Role -`joy_controller` is the package to convert a joy msg to autoware commands (e.g. steering wheel, shift, turn signal, engage) for a vehicle. +`autoware_joy_controller` is the package to convert a joy msg to autoware commands (e.g. steering wheel, shift, turn signal, engage) for a vehicle. ## Usage @@ -10,13 +10,13 @@ ```bash # With default config (ds4) -ros2 launch joy_controller joy_controller.launch.xml +ros2 launch autoware_joy_controller joy_controller.launch.xml # Default config but select from the existing parameter files -ros2 launch joy_controller joy_controller_param_selection.launch.xml joy_type:=ds4 # or g29, p65, xbox +ros2 launch autoware_joy_controller joy_controller_param_selection.launch.xml joy_type:=ds4 # or g29, p65, xbox # Override the param file -ros2 launch joy_controller joy_controller.launch.xml config_file:=/path/to/your/param.yaml +ros2 launch autoware_joy_controller joy_controller.launch.xml config_file:=/path/to/your/param.yaml ``` ## Input / Output diff --git a/control/joy_controller/config/joy_controller_ds4.param.yaml b/control/autoware_joy_controller/config/joy_controller_ds4.param.yaml similarity index 100% rename from control/joy_controller/config/joy_controller_ds4.param.yaml rename to control/autoware_joy_controller/config/joy_controller_ds4.param.yaml diff --git a/control/joy_controller/config/joy_controller_g29.param.yaml b/control/autoware_joy_controller/config/joy_controller_g29.param.yaml similarity index 100% rename from control/joy_controller/config/joy_controller_g29.param.yaml rename to control/autoware_joy_controller/config/joy_controller_g29.param.yaml diff --git a/control/joy_controller/config/joy_controller_p65.param.yaml b/control/autoware_joy_controller/config/joy_controller_p65.param.yaml similarity index 100% rename from control/joy_controller/config/joy_controller_p65.param.yaml rename to control/autoware_joy_controller/config/joy_controller_p65.param.yaml diff --git a/control/joy_controller/config/joy_controller_xbox.param.yaml b/control/autoware_joy_controller/config/joy_controller_xbox.param.yaml similarity index 100% rename from control/joy_controller/config/joy_controller_xbox.param.yaml rename to control/autoware_joy_controller/config/joy_controller_xbox.param.yaml diff --git a/control/joy_controller/include/joy_controller/joy_controller.hpp b/control/autoware_joy_controller/include/autoware_joy_controller/joy_controller.hpp similarity index 93% rename from control/joy_controller/include/joy_controller/joy_controller.hpp rename to control/autoware_joy_controller/include/autoware_joy_controller/joy_controller.hpp index 136637f0f1fd3..88371455def62 100644 --- a/control/joy_controller/include/joy_controller/joy_controller.hpp +++ b/control/autoware_joy_controller/include/autoware_joy_controller/joy_controller.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef JOY_CONTROLLER__JOY_CONTROLLER_HPP_ -#define JOY_CONTROLLER__JOY_CONTROLLER_HPP_ +#ifndef AUTOWARE_JOY_CONTROLLER__JOY_CONTROLLER_HPP_ +#define AUTOWARE_JOY_CONTROLLER__JOY_CONTROLLER_HPP_ -#include "joy_controller/joy_converter/joy_converter_base.hpp" +#include "autoware_joy_controller/joy_converter/joy_converter_base.hpp" #include #include @@ -37,7 +37,7 @@ #include #include -namespace joy_controller +namespace autoware::joy_controller { using GearShiftType = tier4_external_api_msgs::msg::GearShift::_data_type; using TurnSignalType = tier4_external_api_msgs::msg::TurnSignal::_data_type; @@ -120,6 +120,6 @@ class AutowareJoyControllerNode : public rclcpp::Node bool isDataReady(); void onTimer(); }; -} // namespace joy_controller +} // namespace autoware::joy_controller -#endif // JOY_CONTROLLER__JOY_CONTROLLER_HPP_ +#endif // AUTOWARE_JOY_CONTROLLER__JOY_CONTROLLER_HPP_ diff --git a/control/joy_controller/include/joy_controller/joy_converter/ds4_joy_converter.hpp b/control/autoware_joy_controller/include/autoware_joy_controller/joy_converter/ds4_joy_converter.hpp similarity index 89% rename from control/joy_controller/include/joy_controller/joy_converter/ds4_joy_converter.hpp rename to control/autoware_joy_controller/include/autoware_joy_controller/joy_converter/ds4_joy_converter.hpp index faa920d493478..7cfac1af8662b 100644 --- a/control/joy_controller/include/joy_controller/joy_converter/ds4_joy_converter.hpp +++ b/control/autoware_joy_controller/include/autoware_joy_controller/joy_converter/ds4_joy_converter.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef JOY_CONTROLLER__JOY_CONVERTER__DS4_JOY_CONVERTER_HPP_ -#define JOY_CONTROLLER__JOY_CONVERTER__DS4_JOY_CONVERTER_HPP_ +#ifndef AUTOWARE_JOY_CONTROLLER__JOY_CONVERTER__DS4_JOY_CONVERTER_HPP_ +#define AUTOWARE_JOY_CONTROLLER__JOY_CONVERTER__DS4_JOY_CONVERTER_HPP_ -#include "joy_controller/joy_converter/joy_converter_base.hpp" +#include "autoware_joy_controller/joy_converter/joy_converter_base.hpp" #include -namespace joy_controller +namespace autoware::joy_controller { class DS4JoyConverter : public JoyConverterBase { @@ -90,6 +90,6 @@ class DS4JoyConverter : public JoyConverterBase bool reverse() const { return Share(); } }; -} // namespace joy_controller +} // namespace autoware::joy_controller -#endif // JOY_CONTROLLER__JOY_CONVERTER__DS4_JOY_CONVERTER_HPP_ +#endif // AUTOWARE_JOY_CONTROLLER__JOY_CONVERTER__DS4_JOY_CONVERTER_HPP_ diff --git a/control/joy_controller/include/joy_controller/joy_converter/g29_joy_converter.hpp b/control/autoware_joy_controller/include/autoware_joy_controller/joy_converter/g29_joy_converter.hpp similarity index 88% rename from control/joy_controller/include/joy_controller/joy_converter/g29_joy_converter.hpp rename to control/autoware_joy_controller/include/autoware_joy_controller/joy_converter/g29_joy_converter.hpp index 7ba062fe10d19..a36ad3a580287 100644 --- a/control/joy_controller/include/joy_controller/joy_converter/g29_joy_converter.hpp +++ b/control/autoware_joy_controller/include/autoware_joy_controller/joy_converter/g29_joy_converter.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef JOY_CONTROLLER__JOY_CONVERTER__G29_JOY_CONVERTER_HPP_ -#define JOY_CONTROLLER__JOY_CONVERTER__G29_JOY_CONVERTER_HPP_ +#ifndef AUTOWARE_JOY_CONTROLLER__JOY_CONVERTER__G29_JOY_CONVERTER_HPP_ +#define AUTOWARE_JOY_CONTROLLER__JOY_CONVERTER__G29_JOY_CONVERTER_HPP_ -#include "joy_controller/joy_converter/joy_converter_base.hpp" +#include "autoware_joy_controller/joy_converter/joy_converter_base.hpp" -namespace joy_controller +namespace autoware::joy_controller { class G29JoyConverter : public JoyConverterBase { @@ -88,6 +88,6 @@ class G29JoyConverter : public JoyConverterBase bool reverse() const { return Share(); } }; -} // namespace joy_controller +} // namespace autoware::joy_controller -#endif // JOY_CONTROLLER__JOY_CONVERTER__G29_JOY_CONVERTER_HPP_ +#endif // AUTOWARE_JOY_CONTROLLER__JOY_CONVERTER__G29_JOY_CONVERTER_HPP_ diff --git a/control/joy_controller/include/joy_controller/joy_converter/joy_converter_base.hpp b/control/autoware_joy_controller/include/autoware_joy_controller/joy_converter/joy_converter_base.hpp similarity index 82% rename from control/joy_controller/include/joy_controller/joy_converter/joy_converter_base.hpp rename to control/autoware_joy_controller/include/autoware_joy_controller/joy_converter/joy_converter_base.hpp index 94587b88e22f5..98a8b799d71a9 100644 --- a/control/joy_controller/include/joy_controller/joy_converter/joy_converter_base.hpp +++ b/control/autoware_joy_controller/include/autoware_joy_controller/joy_converter/joy_converter_base.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef JOY_CONTROLLER__JOY_CONVERTER__JOY_CONVERTER_BASE_HPP_ -#define JOY_CONTROLLER__JOY_CONVERTER__JOY_CONVERTER_BASE_HPP_ +#ifndef AUTOWARE_JOY_CONTROLLER__JOY_CONVERTER__JOY_CONVERTER_BASE_HPP_ +#define AUTOWARE_JOY_CONTROLLER__JOY_CONVERTER__JOY_CONVERTER_BASE_HPP_ #include #include -namespace joy_controller +namespace autoware::joy_controller { class JoyConverterBase { @@ -50,6 +50,6 @@ class JoyConverterBase virtual bool vehicle_engage() const = 0; virtual bool vehicle_disengage() const = 0; }; -} // namespace joy_controller +} // namespace autoware::joy_controller -#endif // JOY_CONTROLLER__JOY_CONVERTER__JOY_CONVERTER_BASE_HPP_ +#endif // AUTOWARE_JOY_CONTROLLER__JOY_CONVERTER__JOY_CONVERTER_BASE_HPP_ diff --git a/control/joy_controller/include/joy_controller/joy_converter/p65_joy_converter.hpp b/control/autoware_joy_controller/include/autoware_joy_controller/joy_converter/p65_joy_converter.hpp similarity index 88% rename from control/joy_controller/include/joy_controller/joy_converter/p65_joy_converter.hpp rename to control/autoware_joy_controller/include/autoware_joy_controller/joy_converter/p65_joy_converter.hpp index e4cb822846fef..a6f51cb95b44d 100644 --- a/control/joy_controller/include/joy_controller/joy_converter/p65_joy_converter.hpp +++ b/control/autoware_joy_controller/include/autoware_joy_controller/joy_converter/p65_joy_converter.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef JOY_CONTROLLER__JOY_CONVERTER__P65_JOY_CONVERTER_HPP_ -#define JOY_CONTROLLER__JOY_CONVERTER__P65_JOY_CONVERTER_HPP_ +#ifndef AUTOWARE_JOY_CONTROLLER__JOY_CONVERTER__P65_JOY_CONVERTER_HPP_ +#define AUTOWARE_JOY_CONTROLLER__JOY_CONVERTER__P65_JOY_CONVERTER_HPP_ -#include "joy_controller/joy_converter/joy_converter_base.hpp" +#include "autoware_joy_controller/joy_converter/joy_converter_base.hpp" #include -namespace joy_controller +namespace autoware::joy_controller { class P65JoyConverter : public JoyConverterBase { @@ -76,6 +76,6 @@ class P65JoyConverter : public JoyConverterBase const sensor_msgs::msg::Joy j_; }; -} // namespace joy_controller +} // namespace autoware::joy_controller -#endif // JOY_CONTROLLER__JOY_CONVERTER__P65_JOY_CONVERTER_HPP_ +#endif // AUTOWARE_JOY_CONTROLLER__JOY_CONVERTER__P65_JOY_CONVERTER_HPP_ diff --git a/control/joy_controller/include/joy_controller/joy_converter/xbox_joy_converter.hpp b/control/autoware_joy_controller/include/autoware_joy_controller/joy_converter/xbox_joy_converter.hpp similarity index 88% rename from control/joy_controller/include/joy_controller/joy_converter/xbox_joy_converter.hpp rename to control/autoware_joy_controller/include/autoware_joy_controller/joy_converter/xbox_joy_converter.hpp index a009ee1e12975..776b0c98b7835 100644 --- a/control/joy_controller/include/joy_controller/joy_converter/xbox_joy_converter.hpp +++ b/control/autoware_joy_controller/include/autoware_joy_controller/joy_converter/xbox_joy_converter.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef JOY_CONTROLLER__JOY_CONVERTER__XBOX_JOY_CONVERTER_HPP_ -#define JOY_CONTROLLER__JOY_CONVERTER__XBOX_JOY_CONVERTER_HPP_ +#ifndef AUTOWARE_JOY_CONTROLLER__JOY_CONVERTER__XBOX_JOY_CONVERTER_HPP_ +#define AUTOWARE_JOY_CONTROLLER__JOY_CONVERTER__XBOX_JOY_CONVERTER_HPP_ -#include "joy_controller/joy_converter/joy_converter_base.hpp" +#include "autoware_joy_controller/joy_converter/joy_converter_base.hpp" #include -namespace joy_controller +namespace autoware::joy_controller { class XBOXJoyConverter : public JoyConverterBase { @@ -76,6 +76,6 @@ class XBOXJoyConverter : public JoyConverterBase const sensor_msgs::msg::Joy j_; }; -} // namespace joy_controller +} // namespace autoware::joy_controller -#endif // JOY_CONTROLLER__JOY_CONVERTER__XBOX_JOY_CONVERTER_HPP_ +#endif // AUTOWARE_JOY_CONTROLLER__JOY_CONVERTER__XBOX_JOY_CONVERTER_HPP_ diff --git a/control/joy_controller/launch/joy_controller.launch.xml b/control/autoware_joy_controller/launch/joy_controller.launch.xml similarity index 89% rename from control/joy_controller/launch/joy_controller.launch.xml rename to control/autoware_joy_controller/launch/joy_controller.launch.xml index 5236077680d0d..02220f0026cea 100644 --- a/control/joy_controller/launch/joy_controller.launch.xml +++ b/control/autoware_joy_controller/launch/joy_controller.launch.xml @@ -12,9 +12,9 @@ - + - + diff --git a/control/autoware_joy_controller/launch/joy_controller_param_selection.launch.xml b/control/autoware_joy_controller/launch/joy_controller_param_selection.launch.xml new file mode 100644 index 0000000000000..3d0aae9a45c4a --- /dev/null +++ b/control/autoware_joy_controller/launch/joy_controller_param_selection.launch.xml @@ -0,0 +1,7 @@ + + + + + + + diff --git a/control/joy_controller/package.xml b/control/autoware_joy_controller/package.xml similarity index 93% rename from control/joy_controller/package.xml rename to control/autoware_joy_controller/package.xml index f160d561057e8..10e33d5d6564a 100644 --- a/control/joy_controller/package.xml +++ b/control/autoware_joy_controller/package.xml @@ -1,9 +1,9 @@ - joy_controller + autoware_joy_controller 0.1.0 - The joy_controller package + The autoware_joy_controller package Taiki Tanaka Tomoya Kimura Shumpei Wakabayashi diff --git a/control/joy_controller/schema/joy_controller.schema.json b/control/autoware_joy_controller/schema/joy_controller.schema.json similarity index 97% rename from control/joy_controller/schema/joy_controller.schema.json rename to control/autoware_joy_controller/schema/joy_controller.schema.json index d4c6351324935..4c95057aec46d 100644 --- a/control/joy_controller/schema/joy_controller.schema.json +++ b/control/autoware_joy_controller/schema/joy_controller.schema.json @@ -3,7 +3,7 @@ "title": "Parameters for Joy Controller node", "type": "object", "definitions": { - "joy_controller": { + "autoware_joy_controller": { "type": "object", "properties": { "joy_type": { @@ -112,7 +112,7 @@ "type": "object", "properties": { "ros__parameters": { - "$ref": "#/definitions/joy_controller" + "$ref": "#/definitions/autoware_joy_controller" } }, "required": ["ros__parameters"], diff --git a/control/joy_controller/src/joy_controller/joy_controller_node.cpp b/control/autoware_joy_controller/src/joy_controller_node.cpp similarity index 95% rename from control/joy_controller/src/joy_controller/joy_controller_node.cpp rename to control/autoware_joy_controller/src/joy_controller_node.cpp index 313d4498395b8..2491893a2806c 100644 --- a/control/joy_controller/src/joy_controller/joy_controller_node.cpp +++ b/control/autoware_joy_controller/src/joy_controller_node.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "joy_controller/joy_controller.hpp" -#include "joy_controller/joy_converter/ds4_joy_converter.hpp" -#include "joy_controller/joy_converter/g29_joy_converter.hpp" -#include "joy_controller/joy_converter/p65_joy_converter.hpp" -#include "joy_controller/joy_converter/xbox_joy_converter.hpp" +#include "autoware_joy_controller/joy_controller.hpp" +#include "autoware_joy_controller/joy_converter/ds4_joy_converter.hpp" +#include "autoware_joy_controller/joy_converter/g29_joy_converter.hpp" +#include "autoware_joy_controller/joy_converter/p65_joy_converter.hpp" +#include "autoware_joy_controller/joy_converter/xbox_joy_converter.hpp" #include @@ -27,9 +27,9 @@ namespace { -using joy_controller::GateModeType; -using joy_controller::GearShiftType; -using joy_controller::TurnSignalType; +using autoware::joy_controller::GateModeType; +using autoware::joy_controller::GearShiftType; +using autoware::joy_controller::TurnSignalType; using GearShift = tier4_external_api_msgs::msg::GearShift; using TurnSignal = tier4_external_api_msgs::msg::TurnSignal; using GateMode = tier4_control_msgs::msg::GateMode; @@ -146,7 +146,7 @@ double calcMapping(const double input, const double sensitivity) } // namespace -namespace joy_controller +namespace autoware::joy_controller { void AutowareJoyControllerNode::onJoy() { @@ -459,7 +459,7 @@ void AutowareJoyControllerNode::initTimer(double period_s) } AutowareJoyControllerNode::AutowareJoyControllerNode(const rclcpp::NodeOptions & node_options) -: Node("joy_controller", node_options) +: Node("autoware_joy_controller", node_options) { // Parameter joy_type_ = declare_parameter("joy_type"); @@ -521,7 +521,7 @@ AutowareJoyControllerNode::AutowareJoyControllerNode(const rclcpp::NodeOptions & // Timer initTimer(1.0 / update_rate_); } -} // namespace joy_controller +} // namespace autoware::joy_controller #include -RCLCPP_COMPONENTS_REGISTER_NODE(joy_controller::AutowareJoyControllerNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::joy_controller::AutowareJoyControllerNode) diff --git a/control/joy_controller/CMakeLists.txt b/control/joy_controller/CMakeLists.txt deleted file mode 100644 index f000c8c0909f4..0000000000000 --- a/control/joy_controller/CMakeLists.txt +++ /dev/null @@ -1,20 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(joy_controller) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_add_library(joy_controller_node SHARED - src/joy_controller/joy_controller_node.cpp -) - -rclcpp_components_register_node(joy_controller_node - PLUGIN "joy_controller::AutowareJoyControllerNode" - EXECUTABLE joy_controller -) - -ament_auto_package( - INSTALL_TO_SHARE - launch - config -) diff --git a/control/joy_controller/launch/joy_controller_param_selection.launch.xml b/control/joy_controller/launch/joy_controller_param_selection.launch.xml deleted file mode 100644 index d8e3d0bfe8b25..0000000000000 --- a/control/joy_controller/launch/joy_controller_param_selection.launch.xml +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - From a6ef8bb9ac20cf774ba42d6b0fde49f5efbc0966 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 9 Jun 2024 03:23:32 +0900 Subject: [PATCH 37/65] feat(tier4_autoware_utils): suppress too many warning of TF transform failure (#7378) Signed-off-by: Takayuki Murooka --- .../tier4_autoware_utils/ros/transform_listener.hpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/transform_listener.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/transform_listener.hpp index ffc845575a76f..96b1cc6ea6ccc 100644 --- a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/transform_listener.hpp +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/transform_listener.hpp @@ -48,8 +48,9 @@ class TransformListener try { tf = tf_buffer_->lookupTransform(from, to, tf2::TimePointZero); } catch (tf2::TransformException & ex) { - RCLCPP_WARN( - logger_, "failed to get transform from %s to %s: %s", from.c_str(), to.c_str(), ex.what()); + RCLCPP_WARN_THROTTLE( + logger_, *clock_, 5000, "failed to get transform from %s to %s: %s", from.c_str(), + to.c_str(), ex.what()); return {}; } @@ -64,8 +65,9 @@ class TransformListener try { tf = tf_buffer_->lookupTransform(from, to, time, duration); } catch (tf2::TransformException & ex) { - RCLCPP_WARN( - logger_, "failed to get transform from %s to %s: %s", from.c_str(), to.c_str(), ex.what()); + RCLCPP_WARN_THROTTLE( + logger_, *clock_, 5000, "failed to get transform from %s to %s: %s", from.c_str(), + to.c_str(), ex.what()); return {}; } From a082e6400a565149270ff11ad30ae7234ca3c102 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 9 Jun 2024 03:43:01 +0900 Subject: [PATCH 38/65] refactor(pid_longitudinal_controller)!: prefix package and namespace with autoware (#7383) * add prefix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix trajectory follower node param Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .github/CODEOWNERS | 2 +- .../CMakeLists.txt | 7 ++----- .../README.md | 0 .../debug_values.hpp | 7 ++++--- .../longitudinal_controller_utils.hpp | 6 +++--- .../lowpass_filter.hpp | 6 +++--- .../pid.hpp | 6 +++--- .../pid_longitudinal_controller.hpp | 18 +++++++++--------- .../smooth_stop.hpp | 6 +++--- .../media/BrakeKeeping.drawio.svg | 0 .../LongitudinalControllerDiagram.drawio.svg | 0 ...tudinalControllerStateTransition.drawio.svg | 0 .../media/slope_definition.drawio.svg | 0 .../package.xml | 2 +- ...longitudinal_controller_defaults.param.yaml | 0 .../src/longitudinal_controller_utils.cpp | 2 +- .../src/pid.cpp | 2 +- .../src/pid_longitudinal_controller.cpp | 4 ++-- .../src/smooth_stop.cpp | 2 +- .../test_longitudinal_controller_utils.cpp | 2 +- .../test/test_pid.cpp | 2 +- .../test/test_smooth_stop.cpp | 2 +- control/trajectory_follower_node/package.xml | 2 +- .../param/longitudinal/pid.param.yaml | 5 +++-- .../src/controller_node.cpp | 2 +- .../test/test_controller_node.cpp | 2 +- 26 files changed, 43 insertions(+), 44 deletions(-) rename control/{pid_longitudinal_controller => autoware_pid_longitudinal_controller}/CMakeLists.txt (80%) rename control/{pid_longitudinal_controller => autoware_pid_longitudinal_controller}/README.md (100%) rename control/{pid_longitudinal_controller/include/pid_longitudinal_controller => autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller}/debug_values.hpp (92%) rename control/{pid_longitudinal_controller/include/pid_longitudinal_controller => autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller}/longitudinal_controller_utils.hpp (96%) rename control/{pid_longitudinal_controller/include/pid_longitudinal_controller => autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller}/lowpass_filter.hpp (89%) rename control/{pid_longitudinal_controller/include/pid_longitudinal_controller => autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller}/pid.hpp (94%) rename control/{pid_longitudinal_controller/include/pid_longitudinal_controller => autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller}/pid_longitudinal_controller.hpp (95%) rename control/{pid_longitudinal_controller/include/pid_longitudinal_controller => autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller}/smooth_stop.hpp (95%) rename control/{pid_longitudinal_controller => autoware_pid_longitudinal_controller}/media/BrakeKeeping.drawio.svg (100%) rename control/{pid_longitudinal_controller => autoware_pid_longitudinal_controller}/media/LongitudinalControllerDiagram.drawio.svg (100%) rename control/{pid_longitudinal_controller => autoware_pid_longitudinal_controller}/media/LongitudinalControllerStateTransition.drawio.svg (100%) rename control/{pid_longitudinal_controller => autoware_pid_longitudinal_controller}/media/slope_definition.drawio.svg (100%) rename control/{pid_longitudinal_controller => autoware_pid_longitudinal_controller}/package.xml (97%) rename control/{pid_longitudinal_controller => autoware_pid_longitudinal_controller}/param/longitudinal_controller_defaults.param.yaml (100%) rename control/{pid_longitudinal_controller => autoware_pid_longitudinal_controller}/src/longitudinal_controller_utils.cpp (98%) rename control/{pid_longitudinal_controller => autoware_pid_longitudinal_controller}/src/pid.cpp (98%) rename control/{pid_longitudinal_controller => autoware_pid_longitudinal_controller}/src/pid_longitudinal_controller.cpp (99%) rename control/{pid_longitudinal_controller => autoware_pid_longitudinal_controller}/src/smooth_stop.cpp (98%) rename control/{pid_longitudinal_controller => autoware_pid_longitudinal_controller}/test/test_longitudinal_controller_utils.cpp (99%) rename control/{pid_longitudinal_controller => autoware_pid_longitudinal_controller}/test/test_pid.cpp (97%) rename control/{pid_longitudinal_controller => autoware_pid_longitudinal_controller}/test/test_smooth_stop.cpp (98%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 838194e44583c..eb9aca8a208d6 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -53,7 +53,7 @@ control/autoware_lane_departure_checker/** kyoichi.sugahara@tier4.jp makoto.kuri control/mpc_lateral_controller/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/obstacle_collision_checker/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/operation_mode_transition_manager/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp -control/pid_longitudinal_controller/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp +control/autoware_pid_longitudinal_controller/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/predicted_path_checker/** berkay@leodrive.ai control/pure_pursuit/** takamasa.horibe@tier4.jp control/shift_decider/** takamasa.horibe@tier4.jp diff --git a/control/pid_longitudinal_controller/CMakeLists.txt b/control/autoware_pid_longitudinal_controller/CMakeLists.txt similarity index 80% rename from control/pid_longitudinal_controller/CMakeLists.txt rename to control/autoware_pid_longitudinal_controller/CMakeLists.txt index 3e7a992b15e00..f0dce81eb54e1 100644 --- a/control/pid_longitudinal_controller/CMakeLists.txt +++ b/control/autoware_pid_longitudinal_controller/CMakeLists.txt @@ -1,15 +1,12 @@ cmake_minimum_required(VERSION 3.14) -project(pid_longitudinal_controller) +project(autoware_pid_longitudinal_controller) find_package(autoware_cmake REQUIRED) autoware_package() set(PID_LON_CON_LIB ${PROJECT_NAME}_lib) ament_auto_add_library(${PID_LON_CON_LIB} SHARED - src/pid_longitudinal_controller.cpp - src/pid.cpp - src/smooth_stop.cpp - src/longitudinal_controller_utils.cpp + DIRECTORY src ) if(BUILD_TESTING) diff --git a/control/pid_longitudinal_controller/README.md b/control/autoware_pid_longitudinal_controller/README.md similarity index 100% rename from control/pid_longitudinal_controller/README.md rename to control/autoware_pid_longitudinal_controller/README.md diff --git a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/debug_values.hpp b/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/debug_values.hpp similarity index 92% rename from control/pid_longitudinal_controller/include/pid_longitudinal_controller/debug_values.hpp rename to control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/debug_values.hpp index 409af46b16ed1..bd682f9566134 100644 --- a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/debug_values.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/debug_values.hpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PID_LONGITUDINAL_CONTROLLER__DEBUG_VALUES_HPP_ -#define PID_LONGITUDINAL_CONTROLLER__DEBUG_VALUES_HPP_ +#ifndef AUTOWARE_PID_LONGITUDINAL_CONTROLLER__DEBUG_VALUES_HPP_ +#define AUTOWARE_PID_LONGITUDINAL_CONTROLLER__DEBUG_VALUES_HPP_ #include +#include namespace autoware::motion::control::pid_longitudinal_controller { @@ -92,4 +93,4 @@ class DebugValues }; } // namespace autoware::motion::control::pid_longitudinal_controller -#endif // PID_LONGITUDINAL_CONTROLLER__DEBUG_VALUES_HPP_ +#endif // AUTOWARE_PID_LONGITUDINAL_CONTROLLER__DEBUG_VALUES_HPP_ diff --git a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp b/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/longitudinal_controller_utils.hpp similarity index 96% rename from control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp rename to control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/longitudinal_controller_utils.hpp index 4ea844a140f4f..171571b493774 100644 --- a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/longitudinal_controller_utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PID_LONGITUDINAL_CONTROLLER__LONGITUDINAL_CONTROLLER_UTILS_HPP_ -#define PID_LONGITUDINAL_CONTROLLER__LONGITUDINAL_CONTROLLER_UTILS_HPP_ +#ifndef AUTOWARE_PID_LONGITUDINAL_CONTROLLER__LONGITUDINAL_CONTROLLER_UTILS_HPP_ +#define AUTOWARE_PID_LONGITUDINAL_CONTROLLER__LONGITUDINAL_CONTROLLER_UTILS_HPP_ #include "interpolation/linear_interpolation.hpp" #include "interpolation/spherical_linear_interpolation.hpp" @@ -155,4 +155,4 @@ geometry_msgs::msg::Pose findTrajectoryPoseAfterDistance( } // namespace longitudinal_utils } // namespace autoware::motion::control::pid_longitudinal_controller -#endif // PID_LONGITUDINAL_CONTROLLER__LONGITUDINAL_CONTROLLER_UTILS_HPP_ +#endif // AUTOWARE_PID_LONGITUDINAL_CONTROLLER__LONGITUDINAL_CONTROLLER_UTILS_HPP_ diff --git a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/lowpass_filter.hpp b/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/lowpass_filter.hpp similarity index 89% rename from control/pid_longitudinal_controller/include/pid_longitudinal_controller/lowpass_filter.hpp rename to control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/lowpass_filter.hpp index 06fe1793c8123..a743be573cf60 100644 --- a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/lowpass_filter.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/lowpass_filter.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PID_LONGITUDINAL_CONTROLLER__LOWPASS_FILTER_HPP_ -#define PID_LONGITUDINAL_CONTROLLER__LOWPASS_FILTER_HPP_ +#ifndef AUTOWARE_PID_LONGITUDINAL_CONTROLLER__LOWPASS_FILTER_HPP_ +#define AUTOWARE_PID_LONGITUDINAL_CONTROLLER__LOWPASS_FILTER_HPP_ #include #include @@ -63,4 +63,4 @@ class LowpassFilter1d } }; } // namespace autoware::motion::control::pid_longitudinal_controller -#endif // PID_LONGITUDINAL_CONTROLLER__LOWPASS_FILTER_HPP_ +#endif // AUTOWARE_PID_LONGITUDINAL_CONTROLLER__LOWPASS_FILTER_HPP_ diff --git a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/pid.hpp b/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/pid.hpp similarity index 94% rename from control/pid_longitudinal_controller/include/pid_longitudinal_controller/pid.hpp rename to control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/pid.hpp index 8b981c0485ed9..8323e35b5da27 100644 --- a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/pid.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/pid.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PID_LONGITUDINAL_CONTROLLER__PID_HPP_ -#define PID_LONGITUDINAL_CONTROLLER__PID_HPP_ +#ifndef AUTOWARE_PID_LONGITUDINAL_CONTROLLER__PID_HPP_ +#define AUTOWARE_PID_LONGITUDINAL_CONTROLLER__PID_HPP_ #include @@ -91,4 +91,4 @@ class PIDController }; } // namespace autoware::motion::control::pid_longitudinal_controller -#endif // PID_LONGITUDINAL_CONTROLLER__PID_HPP_ +#endif // AUTOWARE_PID_LONGITUDINAL_CONTROLLER__PID_HPP_ diff --git a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/pid_longitudinal_controller.hpp b/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/pid_longitudinal_controller.hpp similarity index 95% rename from control/pid_longitudinal_controller/include/pid_longitudinal_controller/pid_longitudinal_controller.hpp rename to control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/pid_longitudinal_controller.hpp index dee2e580e6911..7b9d999a3decb 100644 --- a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/pid_longitudinal_controller.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/pid_longitudinal_controller.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PID_LONGITUDINAL_CONTROLLER__PID_LONGITUDINAL_CONTROLLER_HPP_ -#define PID_LONGITUDINAL_CONTROLLER__PID_LONGITUDINAL_CONTROLLER_HPP_ - +#ifndef AUTOWARE_PID_LONGITUDINAL_CONTROLLER__PID_LONGITUDINAL_CONTROLLER_HPP_ +#define AUTOWARE_PID_LONGITUDINAL_CONTROLLER__PID_LONGITUDINAL_CONTROLLER_HPP_ + +#include "autoware_pid_longitudinal_controller/debug_values.hpp" +#include "autoware_pid_longitudinal_controller/longitudinal_controller_utils.hpp" +#include "autoware_pid_longitudinal_controller/lowpass_filter.hpp" +#include "autoware_pid_longitudinal_controller/pid.hpp" +#include "autoware_pid_longitudinal_controller/smooth_stop.hpp" #include "diagnostic_updater/diagnostic_updater.hpp" -#include "pid_longitudinal_controller/debug_values.hpp" -#include "pid_longitudinal_controller/longitudinal_controller_utils.hpp" -#include "pid_longitudinal_controller/lowpass_filter.hpp" -#include "pid_longitudinal_controller/pid.hpp" -#include "pid_longitudinal_controller/smooth_stop.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2/utils.h" #include "tf2_ros/buffer.h" @@ -408,4 +408,4 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro }; } // namespace autoware::motion::control::pid_longitudinal_controller -#endif // PID_LONGITUDINAL_CONTROLLER__PID_LONGITUDINAL_CONTROLLER_HPP_ +#endif // AUTOWARE_PID_LONGITUDINAL_CONTROLLER__PID_LONGITUDINAL_CONTROLLER_HPP_ diff --git a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/smooth_stop.hpp b/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/smooth_stop.hpp similarity index 95% rename from control/pid_longitudinal_controller/include/pid_longitudinal_controller/smooth_stop.hpp rename to control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/smooth_stop.hpp index 9a0a36123e143..e433fd158026b 100644 --- a/control/pid_longitudinal_controller/include/pid_longitudinal_controller/smooth_stop.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/smooth_stop.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PID_LONGITUDINAL_CONTROLLER__SMOOTH_STOP_HPP_ -#define PID_LONGITUDINAL_CONTROLLER__SMOOTH_STOP_HPP_ +#ifndef AUTOWARE_PID_LONGITUDINAL_CONTROLLER__SMOOTH_STOP_HPP_ +#define AUTOWARE_PID_LONGITUDINAL_CONTROLLER__SMOOTH_STOP_HPP_ #include "rclcpp/rclcpp.hpp" @@ -112,4 +112,4 @@ class SmoothStop }; } // namespace autoware::motion::control::pid_longitudinal_controller -#endif // PID_LONGITUDINAL_CONTROLLER__SMOOTH_STOP_HPP_ +#endif // AUTOWARE_PID_LONGITUDINAL_CONTROLLER__SMOOTH_STOP_HPP_ diff --git a/control/pid_longitudinal_controller/media/BrakeKeeping.drawio.svg b/control/autoware_pid_longitudinal_controller/media/BrakeKeeping.drawio.svg similarity index 100% rename from control/pid_longitudinal_controller/media/BrakeKeeping.drawio.svg rename to control/autoware_pid_longitudinal_controller/media/BrakeKeeping.drawio.svg diff --git a/control/pid_longitudinal_controller/media/LongitudinalControllerDiagram.drawio.svg b/control/autoware_pid_longitudinal_controller/media/LongitudinalControllerDiagram.drawio.svg similarity index 100% rename from control/pid_longitudinal_controller/media/LongitudinalControllerDiagram.drawio.svg rename to control/autoware_pid_longitudinal_controller/media/LongitudinalControllerDiagram.drawio.svg diff --git a/control/pid_longitudinal_controller/media/LongitudinalControllerStateTransition.drawio.svg b/control/autoware_pid_longitudinal_controller/media/LongitudinalControllerStateTransition.drawio.svg similarity index 100% rename from control/pid_longitudinal_controller/media/LongitudinalControllerStateTransition.drawio.svg rename to control/autoware_pid_longitudinal_controller/media/LongitudinalControllerStateTransition.drawio.svg diff --git a/control/pid_longitudinal_controller/media/slope_definition.drawio.svg b/control/autoware_pid_longitudinal_controller/media/slope_definition.drawio.svg similarity index 100% rename from control/pid_longitudinal_controller/media/slope_definition.drawio.svg rename to control/autoware_pid_longitudinal_controller/media/slope_definition.drawio.svg diff --git a/control/pid_longitudinal_controller/package.xml b/control/autoware_pid_longitudinal_controller/package.xml similarity index 97% rename from control/pid_longitudinal_controller/package.xml rename to control/autoware_pid_longitudinal_controller/package.xml index 82b297a69fee6..50ae7ccaf2e55 100644 --- a/control/pid_longitudinal_controller/package.xml +++ b/control/autoware_pid_longitudinal_controller/package.xml @@ -1,7 +1,7 @@ - pid_longitudinal_controller + autoware_pid_longitudinal_controller 1.0.0 PID-based longitudinal controller diff --git a/control/pid_longitudinal_controller/param/longitudinal_controller_defaults.param.yaml b/control/autoware_pid_longitudinal_controller/param/longitudinal_controller_defaults.param.yaml similarity index 100% rename from control/pid_longitudinal_controller/param/longitudinal_controller_defaults.param.yaml rename to control/autoware_pid_longitudinal_controller/param/longitudinal_controller_defaults.param.yaml diff --git a/control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp b/control/autoware_pid_longitudinal_controller/src/longitudinal_controller_utils.cpp similarity index 98% rename from control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp rename to control/autoware_pid_longitudinal_controller/src/longitudinal_controller_utils.cpp index 4e9ef52a4969e..0d8707afccad8 100644 --- a/control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp +++ b/control/autoware_pid_longitudinal_controller/src/longitudinal_controller_utils.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pid_longitudinal_controller/longitudinal_controller_utils.hpp" +#include "autoware_pid_longitudinal_controller/longitudinal_controller_utils.hpp" #include "tf2/LinearMath/Matrix3x3.h" #include "tf2/LinearMath/Quaternion.h" diff --git a/control/pid_longitudinal_controller/src/pid.cpp b/control/autoware_pid_longitudinal_controller/src/pid.cpp similarity index 98% rename from control/pid_longitudinal_controller/src/pid.cpp rename to control/autoware_pid_longitudinal_controller/src/pid.cpp index 530b5cd15e754..6d2c61f639746 100644 --- a/control/pid_longitudinal_controller/src/pid.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pid_longitudinal_controller/pid.hpp" +#include "autoware_pid_longitudinal_controller/pid.hpp" #include #include diff --git a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp similarity index 99% rename from control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp rename to control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 9a8223c610f9a..e1dd414b2446d 100644 --- a/control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pid_longitudinal_controller/pid_longitudinal_controller.hpp" +#include "autoware_pid_longitudinal_controller/pid_longitudinal_controller.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" @@ -1148,7 +1148,7 @@ void PidLongitudinalController::updateDebugVelAcc(const ControlData & control_da void PidLongitudinalController::setupDiagnosticUpdater() { - diagnostic_updater_.setHardwareID("pid_longitudinal_controller"); + diagnostic_updater_.setHardwareID("autoware_pid_longitudinal_controller"); diagnostic_updater_.add("control_state", this, &PidLongitudinalController::checkControlState); } diff --git a/control/pid_longitudinal_controller/src/smooth_stop.cpp b/control/autoware_pid_longitudinal_controller/src/smooth_stop.cpp similarity index 98% rename from control/pid_longitudinal_controller/src/smooth_stop.cpp rename to control/autoware_pid_longitudinal_controller/src/smooth_stop.cpp index 27fab43fa506f..9d8ad05235f11 100644 --- a/control/pid_longitudinal_controller/src/smooth_stop.cpp +++ b/control/autoware_pid_longitudinal_controller/src/smooth_stop.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "pid_longitudinal_controller/smooth_stop.hpp" +#include "autoware_pid_longitudinal_controller/smooth_stop.hpp" #include // NOLINT diff --git a/control/pid_longitudinal_controller/test/test_longitudinal_controller_utils.cpp b/control/autoware_pid_longitudinal_controller/test/test_longitudinal_controller_utils.cpp similarity index 99% rename from control/pid_longitudinal_controller/test/test_longitudinal_controller_utils.cpp rename to control/autoware_pid_longitudinal_controller/test/test_longitudinal_controller_utils.cpp index bd79d7a8c3ac3..de4d32008aa28 100644 --- a/control/pid_longitudinal_controller/test/test_longitudinal_controller_utils.cpp +++ b/control/autoware_pid_longitudinal_controller/test/test_longitudinal_controller_utils.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "autoware_pid_longitudinal_controller/longitudinal_controller_utils.hpp" #include "gtest/gtest.h" #include "interpolation/spherical_linear_interpolation.hpp" #include "motion_utils/trajectory/conversion.hpp" -#include "pid_longitudinal_controller/longitudinal_controller_utils.hpp" #include "tf2/LinearMath/Quaternion.h" #include "autoware_planning_msgs/msg/trajectory.hpp" diff --git a/control/pid_longitudinal_controller/test/test_pid.cpp b/control/autoware_pid_longitudinal_controller/test/test_pid.cpp similarity index 97% rename from control/pid_longitudinal_controller/test/test_pid.cpp rename to control/autoware_pid_longitudinal_controller/test/test_pid.cpp index 82d01e0028a9c..0e3e0c70945dc 100644 --- a/control/pid_longitudinal_controller/test/test_pid.cpp +++ b/control/autoware_pid_longitudinal_controller/test/test_pid.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "autoware_pid_longitudinal_controller/pid.hpp" #include "gtest/gtest.h" -#include "pid_longitudinal_controller/pid.hpp" #include diff --git a/control/pid_longitudinal_controller/test/test_smooth_stop.cpp b/control/autoware_pid_longitudinal_controller/test/test_smooth_stop.cpp similarity index 98% rename from control/pid_longitudinal_controller/test/test_smooth_stop.cpp rename to control/autoware_pid_longitudinal_controller/test/test_smooth_stop.cpp index d658a5271d249..4f4fbb2354fa1 100644 --- a/control/pid_longitudinal_controller/test/test_smooth_stop.cpp +++ b/control/autoware_pid_longitudinal_controller/test/test_smooth_stop.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "autoware_pid_longitudinal_controller/smooth_stop.hpp" #include "gtest/gtest.h" -#include "pid_longitudinal_controller/smooth_stop.hpp" #include "rclcpp/rclcpp.hpp" #include diff --git a/control/trajectory_follower_node/package.xml b/control/trajectory_follower_node/package.xml index b7dd546eb4bca..92b99e690931f 100644 --- a/control/trajectory_follower_node/package.xml +++ b/control/trajectory_follower_node/package.xml @@ -22,10 +22,10 @@ autoware_adapi_v1_msgs autoware_control_msgs autoware_mpc_lateral_controller + autoware_pid_longitudinal_controller autoware_planning_msgs autoware_vehicle_msgs motion_utils - pid_longitudinal_controller pure_pursuit rclcpp rclcpp_components diff --git a/control/trajectory_follower_node/param/longitudinal/pid.param.yaml b/control/trajectory_follower_node/param/longitudinal/pid.param.yaml index c39088753fe64..ad6217663fbae 100644 --- a/control/trajectory_follower_node/param/longitudinal/pid.param.yaml +++ b/control/trajectory_follower_node/param/longitudinal/pid.param.yaml @@ -69,8 +69,9 @@ max_jerk: 2.0 min_jerk: -5.0 - # pitch - use_trajectory_for_pitch_calculation: false + # slope compensation lpf_pitch_gain: 0.95 + slope_source: "raw_pitch" # raw_pitch, trajectory_pitch or trajectory_adaptive + adaptive_trajectory_velocity_th: 1.0 max_pitch_rad: 0.1 min_pitch_rad: -0.1 diff --git a/control/trajectory_follower_node/src/controller_node.cpp b/control/trajectory_follower_node/src/controller_node.cpp index f431be6612009..4be04af5fd184 100644 --- a/control/trajectory_follower_node/src/controller_node.cpp +++ b/control/trajectory_follower_node/src/controller_node.cpp @@ -15,7 +15,7 @@ #include "trajectory_follower_node/controller_node.hpp" #include "autoware_mpc_lateral_controller/mpc_lateral_controller.hpp" -#include "pid_longitudinal_controller/pid_longitudinal_controller.hpp" +#include "autoware_pid_longitudinal_controller/pid_longitudinal_controller.hpp" #include "pure_pursuit/pure_pursuit_lateral_controller.hpp" #include "tier4_autoware_utils/ros/marker_helper.hpp" diff --git a/control/trajectory_follower_node/test/test_controller_node.cpp b/control/trajectory_follower_node/test/test_controller_node.cpp index 3bf47233f1f3f..dcd3434705ec0 100644 --- a/control/trajectory_follower_node/test/test_controller_node.cpp +++ b/control/trajectory_follower_node/test/test_controller_node.cpp @@ -51,7 +51,7 @@ rclcpp::NodeOptions makeNodeOptions(const bool enable_keep_stopped_until_steer_c // Pass default parameter file to the node const auto share_dir = ament_index_cpp::get_package_share_directory("trajectory_follower_node"); const auto longitudinal_share_dir = - ament_index_cpp::get_package_share_directory("pid_longitudinal_controller"); + ament_index_cpp::get_package_share_directory("autoware_pid_longitudinal_controller"); const auto lateral_share_dir = ament_index_cpp::get_package_share_directory("autoware_mpc_lateral_controller"); rclcpp::NodeOptions node_options; From 240c976d8a30ec2647903d58f13cd2c6e5fb5a5e Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 9 Jun 2024 04:01:49 +0900 Subject: [PATCH 39/65] refactor(path_smoother)!: prefix package and namespace with autoware (#7381) * git mv Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix launch Signed-off-by: Takayuki Murooka * rever a part of prefix Signed-off-by: Takayuki Murooka * fix test Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix static_centerline_optimizer Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .github/CODEOWNERS | 2 +- .../motion_planning.launch.xml | 2 +- planning/.pages | 4 ++-- .../CMakeLists.txt | 10 +++++----- .../README.md | 0 .../config/elastic_band_smoother.param.yaml | 0 .../docs/eb.md | 0 .../common_structs.hpp | 12 ++++++------ .../autoware_path_smoother}/elastic_band.hpp | 14 +++++++------- .../elastic_band_smoother.hpp | 18 +++++++++--------- .../replan_checker.hpp | 14 +++++++------- .../autoware_path_smoother}/type_alias.hpp | 10 +++++----- .../utils/geometry_utils.hpp | 10 +++++----- .../utils/trajectory_utils.hpp | 18 +++++++++--------- .../launch/elastic_band_smoother.launch.xml | 4 ++-- .../debug/eb_fixed_traj_visualization.png | Bin .../media/debug/eb_traj_visualization.png | Bin .../media/eb.svg | 0 .../media/eb_constraint.svg | 0 .../package.xml | 4 ++-- .../scripts/calculation_time_plotter.py | 0 .../src/elastic_band.cpp | 12 ++++++------ .../src/elastic_band_smoother.cpp | 14 +++++++------- .../src/replan_checker.cpp | 8 ++++---- .../src/utils/trajectory_utils.cpp | 8 ++++---- ...autoware_path_smoother_node_interface.cpp} | 16 +++++++++------- .../static_centerline_generator.launch.xml | 2 +- .../package.xml | 2 +- ...timization_trajectory_based_centerline.cpp | 6 +++--- .../test_static_centerline_generator.test.py | 2 +- 30 files changed, 97 insertions(+), 95 deletions(-) rename planning/{path_smoother => autoware_path_smoother}/CMakeLists.txt (70%) rename planning/{path_smoother => autoware_path_smoother}/README.md (100%) rename planning/{path_smoother => autoware_path_smoother}/config/elastic_band_smoother.param.yaml (100%) rename planning/{path_smoother => autoware_path_smoother}/docs/eb.md (100%) rename planning/{path_smoother/include/path_smoother => autoware_path_smoother/include/autoware_path_smoother}/common_structs.hpp (92%) rename planning/{path_smoother/include/path_smoother => autoware_path_smoother/include/autoware_path_smoother}/elastic_band.hpp (91%) rename planning/{path_smoother/include/path_smoother => autoware_path_smoother/include/autoware_path_smoother}/elastic_band_smoother.hpp (89%) rename planning/{path_smoother/include/path_smoother => autoware_path_smoother/include/autoware_path_smoother}/replan_checker.hpp (86%) rename planning/{path_smoother/include/path_smoother => autoware_path_smoother/include/autoware_path_smoother}/type_alias.hpp (86%) rename planning/{path_smoother/include/path_smoother => autoware_path_smoother/include/autoware_path_smoother}/utils/geometry_utils.hpp (80%) rename planning/{path_smoother/include/path_smoother => autoware_path_smoother/include/autoware_path_smoother}/utils/trajectory_utils.hpp (91%) rename planning/{path_smoother => autoware_path_smoother}/launch/elastic_band_smoother.launch.xml (77%) rename planning/{path_smoother => autoware_path_smoother}/media/debug/eb_fixed_traj_visualization.png (100%) rename planning/{path_smoother => autoware_path_smoother}/media/debug/eb_traj_visualization.png (100%) rename planning/{path_smoother => autoware_path_smoother}/media/eb.svg (100%) rename planning/{path_smoother => autoware_path_smoother}/media/eb_constraint.svg (100%) rename planning/{path_smoother => autoware_path_smoother}/package.xml (93%) rename planning/{path_smoother => autoware_path_smoother}/scripts/calculation_time_plotter.py (100%) rename planning/{path_smoother => autoware_path_smoother}/src/elastic_band.cpp (98%) rename planning/{path_smoother => autoware_path_smoother}/src/elastic_band_smoother.cpp (97%) rename planning/{path_smoother => autoware_path_smoother}/src/replan_checker.cpp (97%) rename planning/{path_smoother => autoware_path_smoother}/src/utils/trajectory_utils.cpp (94%) rename planning/{path_smoother/test/test_path_smoother_node_interface.cpp => autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp} (76%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index eb9aca8a208d6..ddbf26ebc485c 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -194,7 +194,7 @@ planning/objects_of_interest_marker_interface/** fumiya.watanabe@tier4.jp kosuke planning/obstacle_cruise_planner/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp planning/obstacle_stop_planner/** berkay@leodrive.ai bnk@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp planning/obstacle_velocity_limiter/** maxime.clement@tier4.jp -planning/path_smoother/** maxime.clement@tier4.jp takayuki.murooka@tier4.jp +planning/autoware_path_smoother/** maxime.clement@tier4.jp takayuki.murooka@tier4.jp planning/planning_test_utils/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp zulfaqar.azmi@tier4.jp planning/planning_validator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp planning/route_handler/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp zulfaqar.azmi@tier4.jp diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 0b82057144f0e..34e8c9d31d837 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -28,7 +28,7 @@ - + diff --git a/planning/.pages b/planning/.pages index be6bf0af9b2a9..a16f2a13628a1 100644 --- a/planning/.pages +++ b/planning/.pages @@ -53,8 +53,8 @@ nav: - 'Obstacle Stop Planner': planning/obstacle_stop_planner - 'Obstacle Velocity Limiter': planning/obstacle_velocity_limiter - 'Path Smoother': - - 'About Path Smoother': planning/path_smoother - - 'Elastic Band': planning/path_smoother/docs/eb + - 'About Path Smoother': planning/autoware_path_smoother + - 'Elastic Band': planning/autoware_path_smoother/docs/eb - 'Sampling Based Planner': - 'Path Sample': planning/sampling_based_planner/autoware_path_sampler - 'Common library': planning/sampling_based_planner/autoware_sampler_common diff --git a/planning/path_smoother/CMakeLists.txt b/planning/autoware_path_smoother/CMakeLists.txt similarity index 70% rename from planning/path_smoother/CMakeLists.txt rename to planning/autoware_path_smoother/CMakeLists.txt index b2f42181f9a0f..a5873fe3735ef 100644 --- a/planning/path_smoother/CMakeLists.txt +++ b/planning/autoware_path_smoother/CMakeLists.txt @@ -1,23 +1,23 @@ cmake_minimum_required(VERSION 3.14) -project(path_smoother) +project(autoware_path_smoother) find_package(autoware_cmake REQUIRED) autoware_package() find_package(Eigen3 REQUIRED) -ament_auto_add_library(path_smoother SHARED +ament_auto_add_library(autoware_path_smoother SHARED DIRECTORY src ) -target_include_directories(path_smoother +target_include_directories(autoware_path_smoother SYSTEM PUBLIC ${EIGEN3_INCLUDE_DIR} ) # register node -rclcpp_components_register_node(path_smoother - PLUGIN "path_smoother::ElasticBandSmoother" +rclcpp_components_register_node(autoware_path_smoother + PLUGIN "autoware::path_smoother::ElasticBandSmoother" EXECUTABLE elastic_band_smoother ) diff --git a/planning/path_smoother/README.md b/planning/autoware_path_smoother/README.md similarity index 100% rename from planning/path_smoother/README.md rename to planning/autoware_path_smoother/README.md diff --git a/planning/path_smoother/config/elastic_band_smoother.param.yaml b/planning/autoware_path_smoother/config/elastic_band_smoother.param.yaml similarity index 100% rename from planning/path_smoother/config/elastic_band_smoother.param.yaml rename to planning/autoware_path_smoother/config/elastic_band_smoother.param.yaml diff --git a/planning/path_smoother/docs/eb.md b/planning/autoware_path_smoother/docs/eb.md similarity index 100% rename from planning/path_smoother/docs/eb.md rename to planning/autoware_path_smoother/docs/eb.md diff --git a/planning/path_smoother/include/path_smoother/common_structs.hpp b/planning/autoware_path_smoother/include/autoware_path_smoother/common_structs.hpp similarity index 92% rename from planning/path_smoother/include/path_smoother/common_structs.hpp rename to planning/autoware_path_smoother/include/autoware_path_smoother/common_structs.hpp index d44c964cf634c..18f5ef82fd6d4 100644 --- a/planning/path_smoother/include/path_smoother/common_structs.hpp +++ b/planning/autoware_path_smoother/include/autoware_path_smoother/common_structs.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SMOOTHER__COMMON_STRUCTS_HPP_ -#define PATH_SMOOTHER__COMMON_STRUCTS_HPP_ +#ifndef AUTOWARE_PATH_SMOOTHER__COMMON_STRUCTS_HPP_ +#define AUTOWARE_PATH_SMOOTHER__COMMON_STRUCTS_HPP_ -#include "path_smoother/type_alias.hpp" +#include "autoware_path_smoother/type_alias.hpp" #include "rclcpp/rclcpp.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" @@ -25,7 +25,7 @@ #include #include -namespace path_smoother +namespace autoware::path_smoother { struct Bounds; @@ -131,6 +131,6 @@ struct EgoNearestParam double dist_threshold{0.0}; double yaw_threshold{0.0}; }; -} // namespace path_smoother +} // namespace autoware::path_smoother -#endif // PATH_SMOOTHER__COMMON_STRUCTS_HPP_ +#endif // AUTOWARE_PATH_SMOOTHER__COMMON_STRUCTS_HPP_ diff --git a/planning/path_smoother/include/path_smoother/elastic_band.hpp b/planning/autoware_path_smoother/include/autoware_path_smoother/elastic_band.hpp similarity index 91% rename from planning/path_smoother/include/path_smoother/elastic_band.hpp rename to planning/autoware_path_smoother/include/autoware_path_smoother/elastic_band.hpp index 1915757b360a4..65b9db9098561 100644 --- a/planning/path_smoother/include/path_smoother/elastic_band.hpp +++ b/planning/autoware_path_smoother/include/autoware_path_smoother/elastic_band.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SMOOTHER__ELASTIC_BAND_HPP_ -#define PATH_SMOOTHER__ELASTIC_BAND_HPP_ +#ifndef AUTOWARE_PATH_SMOOTHER__ELASTIC_BAND_HPP_ +#define AUTOWARE_PATH_SMOOTHER__ELASTIC_BAND_HPP_ +#include "autoware_path_smoother/common_structs.hpp" +#include "autoware_path_smoother/type_alias.hpp" #include "osqp_interface/osqp_interface.hpp" -#include "path_smoother/common_structs.hpp" -#include "path_smoother/type_alias.hpp" #include @@ -27,7 +27,7 @@ #include #include -namespace path_smoother +namespace autoware::path_smoother { class EBPathSmoother { @@ -128,6 +128,6 @@ class EBPathSmoother const std::vector & optimized_points, const std::vector & traj_points, const int pad_start_idx) const; }; -} // namespace path_smoother +} // namespace autoware::path_smoother -#endif // PATH_SMOOTHER__ELASTIC_BAND_HPP_ +#endif // AUTOWARE_PATH_SMOOTHER__ELASTIC_BAND_HPP_ diff --git a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp b/planning/autoware_path_smoother/include/autoware_path_smoother/elastic_band_smoother.hpp similarity index 89% rename from planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp rename to planning/autoware_path_smoother/include/autoware_path_smoother/elastic_band_smoother.hpp index bc566fdfb96bf..16a4b2bb39db7 100644 --- a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp +++ b/planning/autoware_path_smoother/include/autoware_path_smoother/elastic_band_smoother.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SMOOTHER__ELASTIC_BAND_SMOOTHER_HPP_ -#define PATH_SMOOTHER__ELASTIC_BAND_SMOOTHER_HPP_ +#ifndef AUTOWARE_PATH_SMOOTHER__ELASTIC_BAND_SMOOTHER_HPP_ +#define AUTOWARE_PATH_SMOOTHER__ELASTIC_BAND_SMOOTHER_HPP_ +#include "autoware_path_smoother/common_structs.hpp" +#include "autoware_path_smoother/elastic_band.hpp" +#include "autoware_path_smoother/replan_checker.hpp" +#include "autoware_path_smoother/type_alias.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "path_smoother/common_structs.hpp" -#include "path_smoother/elastic_band.hpp" -#include "path_smoother/replan_checker.hpp" -#include "path_smoother/type_alias.hpp" #include "rclcpp/rclcpp.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" #include "tier4_autoware_utils/ros/polling_subscriber.hpp" @@ -32,7 +32,7 @@ #include #include -namespace path_smoother +namespace autoware::path_smoother { class ElasticBandSmoother : public rclcpp::Node { @@ -116,6 +116,6 @@ class ElasticBandSmoother : public rclcpp::Node std::unique_ptr published_time_publisher_; }; -} // namespace path_smoother +} // namespace autoware::path_smoother -#endif // PATH_SMOOTHER__ELASTIC_BAND_SMOOTHER_HPP_ +#endif // AUTOWARE_PATH_SMOOTHER__ELASTIC_BAND_SMOOTHER_HPP_ diff --git a/planning/path_smoother/include/path_smoother/replan_checker.hpp b/planning/autoware_path_smoother/include/autoware_path_smoother/replan_checker.hpp similarity index 86% rename from planning/path_smoother/include/path_smoother/replan_checker.hpp rename to planning/autoware_path_smoother/include/autoware_path_smoother/replan_checker.hpp index d06cbc093a0c8..35b0e0102068b 100644 --- a/planning/path_smoother/include/path_smoother/replan_checker.hpp +++ b/planning/autoware_path_smoother/include/autoware_path_smoother/replan_checker.hpp @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SMOOTHER__REPLAN_CHECKER_HPP_ -#define PATH_SMOOTHER__REPLAN_CHECKER_HPP_ +#ifndef AUTOWARE_PATH_SMOOTHER__REPLAN_CHECKER_HPP_ +#define AUTOWARE_PATH_SMOOTHER__REPLAN_CHECKER_HPP_ -#include "path_smoother/common_structs.hpp" -#include "path_smoother/type_alias.hpp" +#include "autoware_path_smoother/common_structs.hpp" +#include "autoware_path_smoother/type_alias.hpp" #include #include #include -namespace path_smoother +namespace autoware::path_smoother { class ReplanChecker { @@ -66,6 +66,6 @@ class ReplanChecker bool isPathGoalChanged( const PlannerData & planner_data, const std::vector & prev_traj_points) const; }; -} // namespace path_smoother +} // namespace autoware::path_smoother -#endif // PATH_SMOOTHER__REPLAN_CHECKER_HPP_ +#endif // AUTOWARE_PATH_SMOOTHER__REPLAN_CHECKER_HPP_ diff --git a/planning/path_smoother/include/path_smoother/type_alias.hpp b/planning/autoware_path_smoother/include/autoware_path_smoother/type_alias.hpp similarity index 86% rename from planning/path_smoother/include/path_smoother/type_alias.hpp rename to planning/autoware_path_smoother/include/autoware_path_smoother/type_alias.hpp index 21cbcf8e7eefc..dc565d69d3c4d 100644 --- a/planning/path_smoother/include/path_smoother/type_alias.hpp +++ b/planning/autoware_path_smoother/include/autoware_path_smoother/type_alias.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SMOOTHER__TYPE_ALIAS_HPP_ -#define PATH_SMOOTHER__TYPE_ALIAS_HPP_ +#ifndef AUTOWARE_PATH_SMOOTHER__TYPE_ALIAS_HPP_ +#define AUTOWARE_PATH_SMOOTHER__TYPE_ALIAS_HPP_ #include "autoware_planning_msgs/msg/path.hpp" #include "autoware_planning_msgs/msg/path_point.hpp" @@ -25,7 +25,7 @@ #include "tier4_debug_msgs/msg/float64_stamped.hpp" #include "tier4_debug_msgs/msg/string_stamped.hpp" -namespace path_smoother +namespace autoware::path_smoother { // std_msgs using std_msgs::msg::Header; @@ -39,6 +39,6 @@ using nav_msgs::msg::Odometry; // debug using tier4_debug_msgs::msg::Float64Stamped; using tier4_debug_msgs::msg::StringStamped; -} // namespace path_smoother +} // namespace autoware::path_smoother -#endif // PATH_SMOOTHER__TYPE_ALIAS_HPP_ +#endif // AUTOWARE_PATH_SMOOTHER__TYPE_ALIAS_HPP_ diff --git a/planning/path_smoother/include/path_smoother/utils/geometry_utils.hpp b/planning/autoware_path_smoother/include/autoware_path_smoother/utils/geometry_utils.hpp similarity index 80% rename from planning/path_smoother/include/path_smoother/utils/geometry_utils.hpp rename to planning/autoware_path_smoother/include/autoware_path_smoother/utils/geometry_utils.hpp index 39783b958fa61..6cdf34f319442 100644 --- a/planning/path_smoother/include/path_smoother/utils/geometry_utils.hpp +++ b/planning/autoware_path_smoother/include/autoware_path_smoother/utils/geometry_utils.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SMOOTHER__UTILS__GEOMETRY_UTILS_HPP_ -#define PATH_SMOOTHER__UTILS__GEOMETRY_UTILS_HPP_ +#ifndef AUTOWARE_PATH_SMOOTHER__UTILS__GEOMETRY_UTILS_HPP_ +#define AUTOWARE_PATH_SMOOTHER__UTILS__GEOMETRY_UTILS_HPP_ #include -namespace path_smoother +namespace autoware::path_smoother { namespace geometry_utils { @@ -31,5 +31,5 @@ bool isSamePoint(const T1 & t1, const T2 & t2) return (std::abs(p1.x - p2.x) <= epsilon && std::abs(p1.y - p2.y) <= epsilon); } } // namespace geometry_utils -} // namespace path_smoother -#endif // PATH_SMOOTHER__UTILS__GEOMETRY_UTILS_HPP_ +} // namespace autoware::path_smoother +#endif // AUTOWARE_PATH_SMOOTHER__UTILS__GEOMETRY_UTILS_HPP_ diff --git a/planning/path_smoother/include/path_smoother/utils/trajectory_utils.hpp b/planning/autoware_path_smoother/include/autoware_path_smoother/utils/trajectory_utils.hpp similarity index 91% rename from planning/path_smoother/include/path_smoother/utils/trajectory_utils.hpp rename to planning/autoware_path_smoother/include/autoware_path_smoother/utils/trajectory_utils.hpp index 55a7829a5bea3..ea717fae20ef4 100644 --- a/planning/path_smoother/include/path_smoother/utils/trajectory_utils.hpp +++ b/planning/autoware_path_smoother/include/autoware_path_smoother/utils/trajectory_utils.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SMOOTHER__UTILS__TRAJECTORY_UTILS_HPP_ -#define PATH_SMOOTHER__UTILS__TRAJECTORY_UTILS_HPP_ +#ifndef AUTOWARE_PATH_SMOOTHER__UTILS__TRAJECTORY_UTILS_HPP_ +#define AUTOWARE_PATH_SMOOTHER__UTILS__TRAJECTORY_UTILS_HPP_ +#include "autoware_path_smoother/common_structs.hpp" +#include "autoware_path_smoother/type_alias.hpp" #include "interpolation/linear_interpolation.hpp" #include "interpolation/spline_interpolation.hpp" #include "interpolation/spline_interpolation_points_2d.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "path_smoother/common_structs.hpp" -#include "path_smoother/type_alias.hpp" #include @@ -35,7 +35,7 @@ #include #include -namespace path_smoother +namespace autoware::path_smoother { namespace trajectory_utils { @@ -137,7 +137,7 @@ std::optional updateFrontPointForFix( motion_utils::calcSignedArcLength(points, 0, front_fix_point.pose.position); if (0 < lon_offset_to_prev_front) { RCLCPP_DEBUG( - rclcpp::get_logger("path_smoother.trajectory_utils"), + rclcpp::get_logger("autoware_path_smoother.trajectory_utils"), "Fixed point will not be inserted due to the error during calculation."); return std::nullopt; } @@ -148,7 +148,7 @@ std::optional updateFrontPointForFix( constexpr double max_lat_error = 3.0; if (max_lat_error < dist) { RCLCPP_DEBUG( - rclcpp::get_logger("path_smoother.trajectory_utils"), + rclcpp::get_logger("autoware_path_smoother.trajectory_utils"), "New Fixed point is too far from points %f [m]", dist); } @@ -170,5 +170,5 @@ void insertStopPoint( std::vector & traj_points, const geometry_msgs::msg::Pose & input_stop_pose, const size_t stop_seg_idx); } // namespace trajectory_utils -} // namespace path_smoother -#endif // PATH_SMOOTHER__UTILS__TRAJECTORY_UTILS_HPP_ +} // namespace autoware::path_smoother +#endif // AUTOWARE_PATH_SMOOTHER__UTILS__TRAJECTORY_UTILS_HPP_ diff --git a/planning/path_smoother/launch/elastic_band_smoother.launch.xml b/planning/autoware_path_smoother/launch/elastic_band_smoother.launch.xml similarity index 77% rename from planning/path_smoother/launch/elastic_band_smoother.launch.xml rename to planning/autoware_path_smoother/launch/elastic_band_smoother.launch.xml index db91e1e2dd97d..62658f88df3a4 100644 --- a/planning/path_smoother/launch/elastic_band_smoother.launch.xml +++ b/planning/autoware_path_smoother/launch/elastic_band_smoother.launch.xml @@ -3,9 +3,9 @@ - + - + diff --git a/planning/path_smoother/media/debug/eb_fixed_traj_visualization.png b/planning/autoware_path_smoother/media/debug/eb_fixed_traj_visualization.png similarity index 100% rename from planning/path_smoother/media/debug/eb_fixed_traj_visualization.png rename to planning/autoware_path_smoother/media/debug/eb_fixed_traj_visualization.png diff --git a/planning/path_smoother/media/debug/eb_traj_visualization.png b/planning/autoware_path_smoother/media/debug/eb_traj_visualization.png similarity index 100% rename from planning/path_smoother/media/debug/eb_traj_visualization.png rename to planning/autoware_path_smoother/media/debug/eb_traj_visualization.png diff --git a/planning/path_smoother/media/eb.svg b/planning/autoware_path_smoother/media/eb.svg similarity index 100% rename from planning/path_smoother/media/eb.svg rename to planning/autoware_path_smoother/media/eb.svg diff --git a/planning/path_smoother/media/eb_constraint.svg b/planning/autoware_path_smoother/media/eb_constraint.svg similarity index 100% rename from planning/path_smoother/media/eb_constraint.svg rename to planning/autoware_path_smoother/media/eb_constraint.svg diff --git a/planning/path_smoother/package.xml b/planning/autoware_path_smoother/package.xml similarity index 93% rename from planning/path_smoother/package.xml rename to planning/autoware_path_smoother/package.xml index a0e83fdf8a091..445f8a0e6e736 100644 --- a/planning/path_smoother/package.xml +++ b/planning/autoware_path_smoother/package.xml @@ -1,9 +1,9 @@ - path_smoother + autoware_path_smoother 0.1.0 - The path_smoother package + The autoware_path_smoother package Takayuki Murooka Maxime CLEMENT Apache License 2.0 diff --git a/planning/path_smoother/scripts/calculation_time_plotter.py b/planning/autoware_path_smoother/scripts/calculation_time_plotter.py similarity index 100% rename from planning/path_smoother/scripts/calculation_time_plotter.py rename to planning/autoware_path_smoother/scripts/calculation_time_plotter.py diff --git a/planning/path_smoother/src/elastic_band.cpp b/planning/autoware_path_smoother/src/elastic_band.cpp similarity index 98% rename from planning/path_smoother/src/elastic_band.cpp rename to planning/autoware_path_smoother/src/elastic_band.cpp index 8e538a0d6507f..a443cfd37caec 100644 --- a/planning/path_smoother/src/elastic_band.cpp +++ b/planning/autoware_path_smoother/src/elastic_band.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "path_smoother/elastic_band.hpp" +#include "autoware_path_smoother/elastic_band.hpp" +#include "autoware_path_smoother/type_alias.hpp" +#include "autoware_path_smoother/utils/geometry_utils.hpp" +#include "autoware_path_smoother/utils/trajectory_utils.hpp" #include "motion_utils/trajectory/conversion.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "path_smoother/type_alias.hpp" -#include "path_smoother/utils/geometry_utils.hpp" -#include "path_smoother/utils/trajectory_utils.hpp" #include "tf2/utils.h" #include @@ -84,7 +84,7 @@ std_msgs::msg::Header createHeader(const rclcpp::Time & now) } } // namespace -namespace path_smoother +namespace autoware::path_smoother { EBPathSmoother::EBParam::EBParam(rclcpp::Node * node) { @@ -453,4 +453,4 @@ std::optional> EBPathSmoother::convertOptimizedPoin time_keeper_ptr_->toc(__func__, " "); return eb_traj_points; } -} // namespace path_smoother +} // namespace autoware::path_smoother diff --git a/planning/path_smoother/src/elastic_band_smoother.cpp b/planning/autoware_path_smoother/src/elastic_band_smoother.cpp similarity index 97% rename from planning/path_smoother/src/elastic_band_smoother.cpp rename to planning/autoware_path_smoother/src/elastic_band_smoother.cpp index 75300286ac9dc..2f507c8bae311 100644 --- a/planning/path_smoother/src/elastic_band_smoother.cpp +++ b/planning/autoware_path_smoother/src/elastic_band_smoother.cpp @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "path_smoother/elastic_band_smoother.hpp" +#include "autoware_path_smoother/elastic_band_smoother.hpp" +#include "autoware_path_smoother/utils/geometry_utils.hpp" +#include "autoware_path_smoother/utils/trajectory_utils.hpp" #include "interpolation/spline_interpolation_points_2d.hpp" #include "motion_utils/trajectory/conversion.hpp" -#include "path_smoother/utils/geometry_utils.hpp" -#include "path_smoother/utils/trajectory_utils.hpp" #include "rclcpp/time.hpp" #include #include -namespace path_smoother +namespace autoware::path_smoother { namespace { @@ -70,7 +70,7 @@ bool hasZeroVelocity(const TrajectoryPoint & traj_point) } // namespace ElasticBandSmoother::ElasticBandSmoother(const rclcpp::NodeOptions & node_options) -: Node("path_smoother", node_options), time_keeper_ptr_(std::make_shared()) +: Node("autoware_path_smoother", node_options), time_keeper_ptr_(std::make_shared()) { // interface publisher traj_pub_ = create_publisher("~/output/traj", 1); @@ -384,7 +384,7 @@ std::vector ElasticBandSmoother::extendTrajectory( time_keeper_ptr_->toc(__func__, " "); return resampled_traj_points; } -} // namespace path_smoother +} // namespace autoware::path_smoother #include "rclcpp_components/register_node_macro.hpp" -RCLCPP_COMPONENTS_REGISTER_NODE(path_smoother::ElasticBandSmoother) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::path_smoother::ElasticBandSmoother) diff --git a/planning/path_smoother/src/replan_checker.cpp b/planning/autoware_path_smoother/src/replan_checker.cpp similarity index 97% rename from planning/path_smoother/src/replan_checker.cpp rename to planning/autoware_path_smoother/src/replan_checker.cpp index f451a05a8f835..4e5911ea5b42e 100644 --- a/planning/path_smoother/src/replan_checker.cpp +++ b/planning/autoware_path_smoother/src/replan_checker.cpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "path_smoother/replan_checker.hpp" +#include "autoware_path_smoother/replan_checker.hpp" +#include "autoware_path_smoother/utils/trajectory_utils.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "path_smoother/utils/trajectory_utils.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" #include -namespace path_smoother +namespace autoware::path_smoother { ReplanChecker::ReplanChecker(rclcpp::Node * node, const EgoNearestParam & ego_nearest_param) : ego_nearest_param_(ego_nearest_param), logger_(node->get_logger().get_child("replan_checker")) @@ -208,4 +208,4 @@ bool ReplanChecker::isPathGoalChanged( return true; } -} // namespace path_smoother +} // namespace autoware::path_smoother diff --git a/planning/path_smoother/src/utils/trajectory_utils.cpp b/planning/autoware_path_smoother/src/utils/trajectory_utils.cpp similarity index 94% rename from planning/path_smoother/src/utils/trajectory_utils.cpp rename to planning/autoware_path_smoother/src/utils/trajectory_utils.cpp index b4d0950a593d5..5fea20c9a405f 100644 --- a/planning/path_smoother/src/utils/trajectory_utils.cpp +++ b/planning/autoware_path_smoother/src/utils/trajectory_utils.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "path_smoother/utils/trajectory_utils.hpp" +#include "autoware_path_smoother/utils/trajectory_utils.hpp" +#include "autoware_path_smoother/utils/geometry_utils.hpp" #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" -#include "path_smoother/utils/geometry_utils.hpp" #include "autoware_planning_msgs/msg/path_point.hpp" #include "autoware_planning_msgs/msg/trajectory_point.hpp" @@ -30,7 +30,7 @@ #include #include -namespace path_smoother +namespace autoware::path_smoother { namespace trajectory_utils { @@ -98,4 +98,4 @@ void insertStopPoint( traj_points.insert(traj_points.begin() + stop_seg_idx + 1, additional_traj_point); } } // namespace trajectory_utils -} // namespace path_smoother +} // namespace autoware::path_smoother diff --git a/planning/path_smoother/test/test_path_smoother_node_interface.cpp b/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp similarity index 76% rename from planning/path_smoother/test/test_path_smoother_node_interface.cpp rename to planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp index 30e9fba1433cb..41c48630c8f8c 100644 --- a/planning/path_smoother/test/test_path_smoother_node_interface.cpp +++ b/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "path_smoother/elastic_band_smoother.hpp" +#include "autoware_path_smoother/elastic_band_smoother.hpp" #include #include @@ -32,24 +32,26 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) const auto planning_test_utils_dir = ament_index_cpp::get_package_share_directory("planning_test_utils"); - const auto path_smoothing_dir = ament_index_cpp::get_package_share_directory("path_smoother"); + const auto path_smoothing_dir = + ament_index_cpp::get_package_share_directory("autoware_path_smoother"); node_options.arguments( {"--ros-args", "--params-file", planning_test_utils_dir + "/config/test_common.param.yaml", "--params-file", planning_test_utils_dir + "/config/test_nearest_search.param.yaml", "--params-file", path_smoothing_dir + "/config/elastic_band_smoother.param.yaml"}); - auto test_target_node = std::make_shared(node_options); + auto test_target_node = + std::make_shared(node_options); // publish necessary topics from test_manager - test_manager->publishOdometry(test_target_node, "path_smoother/input/odometry"); + test_manager->publishOdometry(test_target_node, "autoware_path_smoother/input/odometry"); // set subscriber with topic name - test_manager->setTrajectorySubscriber("path_smoother/output/traj"); - test_manager->setPathSubscriber("path_smoother/output/path"); + test_manager->setTrajectorySubscriber("autoware_path_smoother/output/traj"); + test_manager->setPathSubscriber("autoware_path_smoother/output/path"); // set input topic name (this topic is changed to test node) - test_manager->setPathInputTopicName("path_smoother/input/path"); + test_manager->setPathInputTopicName("autoware_path_smoother/input/path"); // test with normal trajectory ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPath(test_target_node)); diff --git a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml index 486ea547e3dc1..3d786ab995e5b 100644 --- a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml +++ b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml @@ -28,7 +28,7 @@ default="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml" /> - + diff --git a/planning/autoware_static_centerline_generator/package.xml b/planning/autoware_static_centerline_generator/package.xml index 4cf19c1da0e6a..26eb41ca1de23 100644 --- a/planning/autoware_static_centerline_generator/package.xml +++ b/planning/autoware_static_centerline_generator/package.xml @@ -18,6 +18,7 @@ autoware_behavior_path_planner_common autoware_map_msgs autoware_path_optimizer + autoware_path_smoother autoware_perception_msgs autoware_planning_msgs geography_utils @@ -30,7 +31,6 @@ mission_planner motion_utils osqp_interface - path_smoother rclcpp rclcpp_components route_handler 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 0705f0b51ddd3..7dd3a20848aca 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 @@ -15,9 +15,9 @@ #include "centerline_source/optimization_trajectory_based_centerline.hpp" #include "autoware_path_optimizer/node.hpp" +#include "autoware_path_smoother/elastic_band_smoother.hpp" #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" -#include "path_smoother/elastic_band_smoother.hpp" #include "static_centerline_generator_node.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" #include "utils.hpp" @@ -128,7 +128,7 @@ std::vector OptimizationTrajectoryBasedCenterline::optimize_tra // create an instance of elastic band and model predictive trajectory. const auto eb_path_smoother_ptr = - path_smoother::ElasticBandSmoother(create_node_options()).getElasticBandSmoother(); + autoware::path_smoother::ElasticBandSmoother(create_node_options()).getElasticBandSmoother(); const auto mpt_optimizer_ptr = autoware::path_optimizer::PathOptimizer(create_node_options()).getMPTOptimizer(); @@ -152,7 +152,7 @@ std::vector OptimizationTrajectoryBasedCenterline::optimize_tra virtual_ego_pose_offset_idx) .pose; - // smooth trajectory by elastic band in the path_smoother package + // smooth trajectory by elastic band in the autoware_path_smoother package const auto smoothed_traj_points = eb_path_smoother_ptr->smoothTrajectory(raw_traj_points, virtual_ego_pose); diff --git a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py index 7a5cdfd905fe9..6316afc8cb3dc 100644 --- a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py +++ b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py @@ -63,7 +63,7 @@ def generate_test_description(): "config/behavior_velocity_planner.param.yaml", ), os.path.join( - get_package_share_directory("path_smoother"), + get_package_share_directory("autoware_path_smoother"), "config/elastic_band_smoother.param.yaml", ), os.path.join( From ac483b97cafe989fb39e1e3ac445103432cbc4a5 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Sun, 9 Jun 2024 15:27:28 +0900 Subject: [PATCH 40/65] refactor(out_of_lane): remove from behavior_velocity (#7359) Signed-off-by: Maxime CLEMENT --- .github/CODEOWNERS | 1 - .../behavior_planning.launch.xml | 7 - .../motion_planning.launch.xml | 4 +- planning/.pages | 1 - .../behavior_velocity_planner.launch.xml | 2 - .../package.xml | 1 - .../test/src/test_node_interface.cpp | 2 - .../CMakeLists.txt | 12 - .../README.md | 165 -------- .../config/out_of_lane.param.yaml | 44 -- ...footprints_other_lanes_overlaps_ranges.png | Bin 127593 -> 0 bytes .../docs/out_of_lane_slow.png | Bin 110077 -> 0 bytes .../docs/out_of_lane_stop.png | Bin 183400 -> 0 bytes .../package.xml | 40 -- .../plugins.xml | 3 - .../src/calculate_slowdown_points.hpp | 106 ----- .../src/debug.cpp | 187 --------- .../src/debug.hpp | 69 ---- .../src/decisions.cpp | 383 ------------------ .../src/decisions.hpp | 115 ------ .../src/filter_predicted_objects.cpp | 146 ------- .../src/filter_predicted_objects.hpp | 57 --- .../src/footprint.cpp | 90 ---- .../src/footprint.hpp | 59 --- .../src/lanelets_selection.cpp | 130 ------ .../src/lanelets_selection.hpp | 73 ---- .../src/manager.cpp | 108 ----- .../src/manager.hpp | 66 --- .../src/overlapping_range.cpp | 126 ------ .../src/overlapping_range.hpp | 60 --- .../src/scene_out_of_lane.cpp | 244 ----------- .../src/scene_out_of_lane.hpp | 65 --- .../src/types.hpp | 235 ----------- 33 files changed, 2 insertions(+), 2599 deletions(-) delete mode 100644 planning/behavior_velocity_out_of_lane_module/CMakeLists.txt delete mode 100644 planning/behavior_velocity_out_of_lane_module/README.md delete mode 100644 planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml delete mode 100644 planning/behavior_velocity_out_of_lane_module/docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png delete mode 100644 planning/behavior_velocity_out_of_lane_module/docs/out_of_lane_slow.png delete mode 100644 planning/behavior_velocity_out_of_lane_module/docs/out_of_lane_stop.png delete mode 100644 planning/behavior_velocity_out_of_lane_module/package.xml delete mode 100644 planning/behavior_velocity_out_of_lane_module/plugins.xml delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/debug.cpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/debug.hpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/decisions.cpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/decisions.hpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.cpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.hpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/footprint.cpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/footprint.hpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/manager.cpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/manager.hpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/overlapping_range.cpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp delete mode 100644 planning/behavior_velocity_out_of_lane_module/src/types.hpp diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index ddbf26ebc485c..95ddb97d2bbb0 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -178,7 +178,6 @@ planning/behavior_velocity_intersection_module/** kyoichi.sugahara@tier4.jp mamo planning/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_no_stopping_area_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp -planning/behavior_velocity_out_of_lane_module/** maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/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 planning/autoware_behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index fdb6bc1d90643..463740d978ca6 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -32,7 +32,6 @@ - @@ -164,11 +163,6 @@ value="$(eval "'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::SpeedBumpModulePlugin, '")" if="$(var launch_speed_bump_module)" /> - - diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 34e8c9d31d837..196e7b2c7262c 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -2,7 +2,7 @@ - + @@ -11,7 +11,7 @@ diff --git a/planning/.pages b/planning/.pages index a16f2a13628a1..c144941662a5d 100644 --- a/planning/.pages +++ b/planning/.pages @@ -29,7 +29,6 @@ nav: - 'No Drivable Lane': planning/behavior_velocity_no_drivable_lane_module - 'No Stopping Area': planning/behavior_velocity_no_stopping_area_module - 'Occlusion Spot': planning/behavior_velocity_occlusion_spot_module - - 'Out of Lane': planning/behavior_velocity_out_of_lane_module - 'Run Out': planning/autoware_behavior_velocity_run_out_module - 'Speed Bump': planning/behavior_velocity_speed_bump_module - 'Stop Line': planning/behavior_velocity_stop_line_module diff --git a/planning/autoware_behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml b/planning/autoware_behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml index d4478f87f0610..f52d9637c2134 100644 --- a/planning/autoware_behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml +++ b/planning/autoware_behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml @@ -24,7 +24,6 @@ - @@ -68,7 +67,6 @@ - diff --git a/planning/autoware_behavior_velocity_planner/package.xml b/planning/autoware_behavior_velocity_planner/package.xml index 4d5dc17264df0..70fd92fd9e072 100644 --- a/planning/autoware_behavior_velocity_planner/package.xml +++ b/planning/autoware_behavior_velocity_planner/package.xml @@ -76,7 +76,6 @@ behavior_velocity_no_drivable_lane_module behavior_velocity_no_stopping_area_module behavior_velocity_occlusion_spot_module - behavior_velocity_out_of_lane_module behavior_velocity_speed_bump_module behavior_velocity_stop_line_module behavior_velocity_traffic_light_module diff --git a/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp index cdff8af4ac56e..cf8b918418c53 100644 --- a/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp @@ -81,7 +81,6 @@ std::shared_ptr generateNode() module_names.emplace_back("autoware::behavior_velocity_planner::OcclusionSpotModulePlugin"); module_names.emplace_back("autoware::behavior_velocity_planner::RunOutModulePlugin"); module_names.emplace_back("autoware::behavior_velocity_planner::SpeedBumpModulePlugin"); - module_names.emplace_back("autoware::behavior_velocity_planner::OutOfLaneModulePlugin"); module_names.emplace_back("autoware::behavior_velocity_planner::NoDrivableLaneModulePlugin"); std::vector params; @@ -108,7 +107,6 @@ std::shared_ptr generateNode() get_behavior_velocity_module_config_no_prefix("stop_line"), get_behavior_velocity_module_config_no_prefix("traffic_light"), get_behavior_velocity_module_config("virtual_traffic_light"), - get_behavior_velocity_module_config_no_prefix("out_of_lane"), get_behavior_velocity_module_config_no_prefix("no_drivable_lane")}); // TODO(Takagi, Isamu): set launch_modules diff --git a/planning/behavior_velocity_out_of_lane_module/CMakeLists.txt b/planning/behavior_velocity_out_of_lane_module/CMakeLists.txt deleted file mode 100644 index e8191f9b632d5..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/CMakeLists.txt +++ /dev/null @@ -1,12 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(behavior_velocity_out_of_lane_module) - -find_package(autoware_cmake REQUIRED) -autoware_package() -pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) - -ament_auto_add_library(${PROJECT_NAME} SHARED - DIRECTORY src -) - -ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_velocity_out_of_lane_module/README.md b/planning/behavior_velocity_out_of_lane_module/README.md deleted file mode 100644 index 99396eb0edf22..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/README.md +++ /dev/null @@ -1,165 +0,0 @@ -## Out of Lane - -### Role - -`out_of_lane` is the module that decelerates and stops to prevent the ego vehicle from entering another lane with incoming dynamic objects. - -### Activation Timing - -This module is activated if `launch_out_of_lane` is set to true. - -### Inner-workings / Algorithms - -The algorithm is made of the following steps. - -1. Calculate the ego path footprints (red). -2. Calculate the other lanes (magenta). -3. Calculate the overlapping ranges between the ego path footprints and the other lanes (green). -4. For each overlapping range, decide if a stop or slow down action must be taken. -5. For each action, insert the corresponding stop or slow down point in the path. - -![overview](./docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png) - -#### 1. Ego Path Footprints - -In this first step, the ego footprint is projected at each path point and are eventually inflated based on the `extra_..._offset` parameters. - -#### 2. Other lanes - -In the second step, the set of lanes to consider for overlaps is generated. -This set is built by selecting all lanelets within some distance from the ego vehicle, and then removing non-relevant lanelets. -The selection distance is chosen as the maximum between the `slowdown.distance_threshold` and the `stop.distance_threshold`. - -A lanelet is deemed non-relevant if it meets one of the following conditions. - -- It is part of the lanelets followed by the ego path. -- It contains the rear point of the ego footprint. -- It follows one of the ego path lanelets. - -#### 3. Overlapping ranges - -In the third step, overlaps between the ego path footprints and the other lanes are calculated. -For each pair of other lane $l$ and ego path footprint $f$, we calculate the overlapping polygons using `boost::geometry::intersection`. -For each overlapping polygon found, if the distance inside the other lane $l$ is above the `overlap.minimum_distance` threshold, then the overlap is ignored. -Otherwise, the arc length range (relative to the ego path) and corresponding points of the overlapping polygons are stored. -Ultimately, for each other lane $l$, overlapping ranges of successive overlaps are built with the following information: - -- overlapped other lane $l$. -- start and end ego path indexes. -- start and end ego path arc lengths. -- start and end overlap points. - -#### 4. Decisions - -In the fourth step, a decision to either slow down or stop before each overlapping range is taken based on the dynamic objects. -The conditions for the decision depend on the value of the `mode` parameter. - -Whether it is decided to slow down or stop is determined by the distance between the ego vehicle and the start of the overlapping range (in arc length along the ego path). -If this distance is bellow the `actions.slowdown.threshold`, a velocity of `actions.slowdown.velocity` will be used. -If the distance is bellow the `actions.stop.threshold`, a velocity of `0`m/s will be used. - - - - - - -
- - - -
- -##### Threshold - -With the `mode` set to `"threshold"`, -a decision to stop or slow down before a range is made if -an incoming dynamic object is estimated to reach the overlap within `threshold.time_threshold`. - -##### TTC (time to collision) - -With the `mode` set to `"ttc"`, -estimates for the times when ego and the dynamic objects reach the start and end of the overlapping range are calculated. -This is then used to calculate the time to collision over the period where ego crosses the overlap. -If the time to collision is predicted to go bellow the `ttc.threshold`, the decision to stop or slow down is made. - -##### Intervals - -With the `mode` set to `"intervals"`, -the estimated times when ego and the dynamic objects reach the start and end points of -the overlapping range are used to create time intervals. -These intervals can be made shorter or longer using the -`intervals.ego_time_buffer` and `intervals.objects_time_buffer` parameters. -If the time interval of ego overlaps with the time interval of an object, the decision to stop or slow down is made. - -##### Time estimates - -###### Ego - -To estimate the times when ego will reach an overlap, it is assumed that ego travels along its path -at its current velocity or at half the velocity of the path points, whichever is higher. - -###### Dynamic objects - -Two methods are used to estimate the time when a dynamic objects with reach some point. -If `objects.use_predicted_paths` is set to `true`, the predicted paths of the dynamic object are used if their confidence value is higher than the value set by the `objects.predicted_path_min_confidence` parameter. -Otherwise, the lanelet map is used to estimate the distance between the object and the point and the time is calculated assuming the object keeps its current velocity. - -#### 5. Path update - -Finally, for each decision to stop or slow down before an overlapping range, -a point is inserted in the path. -For a decision taken for an overlapping range with a lane $l$ starting at ego path point index $i$, -a point is inserted in the path between index $i$ and $i-1$ such that the ego footprint projected at the inserted point does not overlap $l$. -Such point with no overlap must exist since, by definition of the overlapping range, -we know that there is no overlap at $i-1$. - -If the point would cause a higher deceleration than allowed by the `max_accel` parameter (node parameter), -it is skipped. - -Moreover, parameter `action.distance_buffer` adds an extra distance between the ego footprint and the overlap when possible. - -### Module Parameters - -| Parameter | Type | Description | -| ----------------------------- | ------ | --------------------------------------------------------------------------------- | -| `mode` | string | [-] mode used to consider a dynamic object. Candidates: threshold, intervals, ttc | -| `skip_if_already_overlapping` | bool | [-] if true, do not run this module when ego already overlaps another lane | - -| Parameter /threshold | Type | Description | -| -------------------- | ------ | ---------------------------------------------------------------- | -| `time_threshold` | double | [s] consider objects that will reach an overlap within this time | - -| Parameter /intervals | Type | Description | -| --------------------- | ------ | ------------------------------------------------------- | -| `ego_time_buffer` | double | [s] extend the ego time interval by this buffer | -| `objects_time_buffer` | double | [s] extend the time intervals of objects by this buffer | - -| Parameter /ttc | Type | Description | -| -------------- | ------ | ------------------------------------------------------------------------------------------------------ | -| `threshold` | double | [s] consider objects with an estimated time to collision bellow this value while ego is on the overlap | - -| Parameter /objects | Type | Description | -| ------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `minimum_velocity` | double | [m/s] ignore objects with a velocity lower than this value | -| `predicted_path_min_confidence` | double | [-] minimum confidence required for a predicted path to be considered | -| `use_predicted_paths` | bool | [-] if true, use the predicted paths to estimate future positions; if false, assume the object moves at constant velocity along _all_ lanelets it currently is located in | - -| Parameter /overlap | Type | Description | -| ------------------ | ------ | ---------------------------------------------------------------------------------------------------- | -| `minimum_distance` | double | [m] minimum distance inside a lanelet for an overlap to be considered | -| `extra_length` | double | [m] extra arc length to add to the front and back of an overlap (used to calculate enter/exit times) | - -| Parameter /action | Type | Description | -| ----------------------------- | ------ | ---------------------------------------------------------------------------------------------- | -| `skip_if_over_max_decel` | bool | [-] if true, do not take an action that would cause more deceleration than the maximum allowed | -| `distance_buffer` | double | [m] buffer distance to try to keep between the ego footprint and lane | -| `slowdown.distance_threshold` | double | [m] insert a slow down when closer than this distance from an overlap | -| `slowdown.velocity` | double | [m] slow down velocity | -| `stop.distance_threshold` | double | [m] insert a stop when closer than this distance from an overlap | - -| Parameter /ego | Type | Description | -| -------------------- | ------ | ---------------------------------------------------- | -| `extra_front_offset` | double | [m] extra front distance to add to the ego footprint | -| `extra_rear_offset` | double | [m] extra rear distance to add to the ego footprint | -| `extra_left_offset` | double | [m] extra left distance to add to the ego footprint | -| `extra_right_offset` | double | [m] extra right distance to add to the ego footprint | diff --git a/planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml b/planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml deleted file mode 100644 index e4d08367ee4f7..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml +++ /dev/null @@ -1,44 +0,0 @@ -/**: - ros__parameters: - out_of_lane: # module to stop or slowdown before overlapping another lane with other objects - mode: ttc # mode used to consider a conflict with an object. "threshold", "intervals", or "ttc" - skip_if_already_overlapping: true # do not run this module when ego already overlaps another lane - ignore_overlaps_over_lane_changeable_lanelets: true # if true, overlaps on lane changeable lanelets are ignored - - threshold: - time_threshold: 5.0 # [s] consider objects that will reach an overlap within this time - intervals: # consider objects if their estimated time interval spent on the overlap intersect the estimated time interval of ego - ego_time_buffer: 0.5 # [s] extend the ego time interval by this buffer - objects_time_buffer: 0.5 # [s] extend the time intervals of objects by this buffer - ttc: - threshold: 3.0 # [s] consider objects with an estimated time to collision bellow this value while on the overlap - - objects: - minimum_velocity: 0.5 # [m/s] objects lower than this velocity will be ignored - use_predicted_paths: true # if true, use the predicted paths to estimate future positions. - # if false, assume the object moves at constant velocity along *all* lanelets it currently is located in. - predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value. - distance_buffer: 1.0 # [m] distance buffer used to determine if a collision will occur in the other lane - cut_predicted_paths_beyond_red_lights: true # if true, predicted paths are cut beyond the stop line of red traffic lights - - overlap: - minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered - extra_length: 0.0 # [m] extra arc length to add to the front and back of an overlap (used to calculate enter/exit times) - - action: # action to insert in the path if an object causes a conflict at an overlap - skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed - precision: 0.1 # [m] precision when inserting a stop pose in the path - distance_buffer: 1.5 # [m] buffer distance to try to keep between the ego footprint and lane - min_duration: 1.0 # [s] minimum duration needed before a decision can be canceled - slowdown: - distance_threshold: 30.0 # [m] insert a slowdown when closer than this distance from an overlap - velocity: 2.0 # [m/s] slowdown velocity - stop: - distance_threshold: 15.0 # [m] insert a stop when closer than this distance from an overlap - - ego: - min_assumed_velocity: 2.0 # [m/s] minimum velocity used to calculate the enter and exit times of ego - extra_front_offset: 0.0 # [m] extra front distance - extra_rear_offset: 0.0 # [m] extra rear distance - extra_right_offset: 0.0 # [m] extra right distance - extra_left_offset: 0.0 # [m] extra left distance diff --git a/planning/behavior_velocity_out_of_lane_module/docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png b/planning/behavior_velocity_out_of_lane_module/docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png deleted file mode 100644 index f095467b3b0acd9a0d1f770422b2f845cd342246..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 127593 zcmYIw1yoes_x2DfP^S8Lr8ZI-Q6*W5aNybW8Z4KY?B6WJ>&QSBKRRA;QQwdqorB>&SSAW%d2x!ce8qrdh_N~ zhq_Ed;=vvZgL>4#OGN@_XJ?c5lhrw=5S*EpF~7WpFU6WKynARFkWTJapDrDE-DFY2 z@3G=P&&YG5U{I*>;28Lc@ z?gvY4bycz@$|Ey#K0(`=_>`0-K~C~;#-pJ1Gj)QYAyq@Y28V-@XI@xp$Zjg`1G(zH zzND>A=h715Hln%S96#5 zIQNqz-0X51BMk{7P?z)EA&5c56PC)7p*4OmMHIx66ag(4K1*G^F-fRBGIRIfYtnbn zY}sMJO&cG-2Nps{;J21DF-Rt1|DBHn+a-OlJ%m_5ux7VFN|~F3F%{Kc;@*=jj%eM* zb8&P$_+~6z+eW6VaQSwe7>15G^bZJd?GnDY{#kC4CphGxA#{;QgL3;bO?7Gwg7WcM z7O9{cI1zBA1Z<*YvVP0QOioMnGJ3Vtf2W%=red#)W{vi1#`5K34zUijnb-VczJuCc ziiKY&ruMT_OZLG4*#WkZ}EQzK?5aaCy6IXM_gy8$SO6 z#rr!YU1<+Tbm03>9Ni=~-`;fVj+;AB{p45Puh-~oHbKDM`I@l!=Z=Pb=oXg03kpzP zN*dj9mi@QbKksPSDH2%k&@13y$lJVmk$k;T;N4q7dggKkh_m7GmS`^RrqIj}TVse^ zd_(b6YHx4vB`J2Cw7SFQ@T+1(?)*Iz;lH6UdzjSNbN8O$+LMk`vVsQ+LQxNPg@(?* zPXfB$!5eB%bw3KHjzW=;m{?3!5ovJJZgID_lv#UgIHNh;3q1%S;KKMf+V}PV z7|}yOhe^RKcR5h`g!xEyIq)+Q#RhTXc%p&>K! zI}bw}2e=Q3iHQ#;K~9)Qga54~OP7RwT(J4hR@|?AUw=3=ZQ@7k)2h;*#gWF#-R`E2 zGhKdG;+QM{#@%fK?q38N({>^q9^VGal%OByP-#sz|90b}yX^-P2(gtA=B(sadJx$z z&{TtfdWoE#{}#0|m485>pb}YQvetS`fJYDB-BX_nO>46F@6!$7({?CZT!0^-OP|-U zF4r4(N4oEs+zmGB7211LqhfFjk$YlWwVBoQaFLMyicEZMtg=eCMg_eHu_606h+15o z65{*Qlp{|Rtc<}0N@ zbDguvbLNnEW+JHyTQ>rauX`(+H%W%?SPTjBzs!ICGVn!!`Y|$#JzU;k@S2ze8$ctC z61l(A&K2W=p9$8KW=DsIpPX%RAw(Z!ot#Rod}t+LctI{qK8Oi1qvQMK*chPu2vCh^ z&;;8K)A)AD7mK_HOaQo0`1oj*6t2Yn9jrwpyt;ariu>E`{}5sr8K&|7XQ@Bh<2t`` z_>HseJfiE?LpTi#%DzC`V*MvRJJLwB9C|U!FG%9MnS(9__GSO=9VQr7JcbwBScq*l zV1FAM>sti{fSGtZ@0O&{dM3>N`xXSEciP#sO|fz-@LNBX@(_5Vo}Pj(GIxKtl@U+Z zJxM4H)h}^%RvyhWSG;ncE;+OQ?>iD&Q9qd93t`8RY;iUxzn2=pf8_2=y;vC-{I&2Z zV2$U0CIe~}U!=lpVOGAC#&M67Ds_mhMiT$eqenY+!p@_IUjL2f<3pgAYZA>GB5Q0U z)}5GQNgwKoP4-#=nFaU|B;>!H{=(C^eW@&diXxI#*-xNZTcYwGoPw0xFv;1qA+YG* z`|WYBS#Hh-ZhE-YW0Lp#Q0q4Zs{JYRf~#~oxBeD*aD&pm!UPa15DM0C=Y`4LU7i{( zHBrZ$D(fKUOfJ+ELkgETpp2a_^SWfl4 z7`HVZAqCauw$42N`?+snPrAwx6AW4@T#;yas|!E5)gz${WvVj>i+`8~qI2q^WIy7# za?RP+P(<>FQS;1uzBJqT z5E9Y@Y)SKe#;3oN+9^{@LV!5|wV_w$jh11eee*K#|7M$O#EoEmr`;OsAyc?Fv3mDwNs-|30(ajWqH$dJ#j+-kQy`2Qz_ zm;1p0j*z{Y9Vj2w`R@4%_zV|?Eyc#Kv%ayhQ1c&7iCY3`OS%eb(6&b-caRKH zpc?{33+hzzAD)t+dc|icJO0lYKTQ!wpGRL~4dI*)!xW?7orfBa18L@CTZ|FVd9-V) z$-v-GW3tO-KP}xy9D0(vkHnYOG|$ieX}BGtJAF{xtc71U9VT`XZ&^j)?-&aXin*4* ztk8Vy{mfSJ5g4ErC$zI3e`fV~u2lciXAny(cT|fLQt25_)1UiU{>A1*G-L<%^Z z37(xsYx|~ngQ6$J4GoF2_x`=EbTow*E&nCj>g}_nhVmR~zXuPOuOu%B`X=YU5z-0^ zJ5pNP|9cbU&Q*z0w?;xKf7EHOsL23?Z8?^cU!eUA0&qyeO#*Ejra;nO&MAYt2q=RD z9>cmvH9-7Q;G2{4FC1uS>WC`a{yTgN7-4iFY1UKALdMbWB^s1NgA}RKY`}mv*7|KF z4}On~?8z;K6G|d8I|j3wn?>DYQgT+dG9V1^LS16G&dvhpq#Cl~DU(OW*@63yKFj6q!76K0m*5LPa{^ z`TeKuO1*)pc_s<@Bm;5$W-pX;jVASo)$WwmZ<*pzwRZqK6N67k$o~8gZL&YOxX6Th z@|G0wbLQvF4l}BI*=>cUJ~MTt_kVhmYayke`qZ9i3c1 z3a+a|MX#<1w%eokLG~skqn#I<6`XYqB2cGGn?2{_tJ$pH^dQhI1tmL0GOPOCp+qs} zkZ3_=`~-YfrE-T7ySx%x{hRt6>C|dO4E&9rd(+98d8*=-K0fhZNM`jNERla4XJ%N? zz-Q=`S8|j+{(?gf6U3Tp@yi!hWx$Xq ztK+2rL!u)>9Nh5YBz+-Z)8b+FhzMn~78?$b5Ah@QTSsM@3Rz67;4?qVvZ_CGQ#Cclw5Y)x2m=9pvAuaB*oz0E#95V|`7%R1RX4 zM;pA3&-<^lw`^xVo`wL1=EVmLs}`Uj>weJkJF#Zx!^6(4z{Q&>Dt2`hVtQ>+@~lFp=&=4!}|r z+*UFW(zk&_GE@#=oMS(4?OGlYvE*+Yf52#TRzmnRSO3+N7H@64tPkXx91=f6yUYAqF0nQ`clv8fN zqe$=#)QVyMUidE-MxA`M>{n5X650g{^Y>^ncYYyLX=^iz8b=bnBy8Lv#wT`|pj}^C zK%o$v+h6Bqu@)9$M+?V0OX{)jz>3G%b~3TcS|JO@J$E_mt2Ph@+hdH?XLF{a29 z9UY0v0!3zqpEwjga#8XZ(}j9h{)bZ~+eGSGygza+5yYi)> zUyJ}MjV-?6LnYTWF65G9JtYtrtIjz55ox z-5x)fMnL&+46AyJ-FBuNjUB5Jdrn>sNcLPE}KgAw{kg~ zH}zsm^~y4QZ$fmcOAJ!0$ZJsD4D!`Ub&+C7j&Rzh8p`a|)PYOMLBFQdrmd~9IJ^2E z<%tMtc^o~A2&(HB)gFnhxO$6z7gdDeBgT*|3tK~|)M^o~&_>~$K|+Dd)Psi$y}eH+ zt3{p(2}wYupfAzL7jsH!YScu5IBzx*SwRp5fI$^CBPfZO#q9b_V#dcJo_ZlxKV7*2 z{2Z>(p>QAv4R}vf(hmEx@a{lhKP8bLVv?`6a8!EYxYi0{;J70862BM&w`Owy z#CQc&3`TQ=LPKfQ;CgaV@Kt%PnuYi=0EInxk}lc~&&}Ui_+o(`i_+-PG&x>6>$)*NZYD*Swot-Kmx%FT@6#n}uJTsJMOlVQ(D{f6X1Tjw;f@jRvJL{3A8^PgKjx zIY_nHaqX3v7@ny9S_NpP-r*W?9^4OeqG|97WbrO6T5A;3h3auoLq zQY3QK-175(=IH^cnK_NujLU9AIDhQCO~T|0Xlu z@4~Ut?{Rg9mg$pg|4~`@?zd-b0zWzXpvhEz=y7FY0dWq+15d0beUxF2C ztwEU=EFeA24FollgH#JnA&_Tq$!9>Isz>> zh0KXSGf}ZijNLiobf)-{Y-9T!e~+U_V4|HHd?j=xgn~lP3$4zY+WIHN8cqlYdVcC{ z4O>k5&aG{)xKF>mO|O+)Squ#5jj0%-<|G(`)bmP)kuI;nrLu&^W~_7c;Kp92Zm2cBg%a5$HMArta2YSR~ zdG=uS9vjSqYxIn9?T*!_vzDS`L-`VK=4vU219`{q0Z_&g7>qw{b9rKR%KDSB@6@$f zBx{|QSX8Sl!9(qnpYhj@Hw01q0DqmVu^lZ*yCRGmIo7Dl&P*rW(BNkE^|*}eK;(Mq zH+hAR?{Yu15G|XB>LNKxI6F%Zk-*!=@!Q|clD3uD-5x$YzHXP z)(O5Vw3_x>5kM_Q2)fVA#bOr1T<`$I6KitYz>%Z85RlM*xZG>;Dpsqqa`Si7$t+(K z1Q}VJ5?vVVpfBWwHWrroz_QnM{^6ny7pzae^flHsyL@IpKVEI{HC*wJdC5m7DvFeBNh+%UIE6Ury{=_=y{Q6%gb(ie|p^|*mz# z%RyEfCuIq`Gvq0#TmVXbhn2rh^!h6GX3hBKAqsykOOe=fVo!hZIcN@nt3J+}MFN3A zqvQ>&J_PGN`)(h+5OYXl*WQVz_s89>sG+U0*n4Dgm_^R`QnIwMjT^vF9zU<*(n}BB zzx?4>VB`5|!66q)C$BY{^(iCcPNGYh_Mi4ARn^4|NFa~`a+gXAo_G^Dbd)I|@- zWo&57a!|Pavykbg`iPRnW~ApED2HOvV&8>7xokf_Z9;q;J#wI0x%%VDK?C&AV8df` zvLAK&X?qX~<#)H-ekZ_X$nO@10s7ikER(4k0bl*ZB%?Tl0DOBK;PH7f^)2zUfK^FWcUQVhwQ#cJ+QM=v$NefL+8 za3>MlKqH>_&$rKiMu%6WeRuzEP_aaNttE{9?-A>EKKJycSomSxmp(O`scLZHi+ zez|GnBoNmh_E`xJ#Qw!a?PgHksDZ=Oq(`YRsecLHnNeEU(9lp+6ar63OkCJ|jv6O) z;{*0L#UN{MZ_~*}cKJzZh%r#u#7ml>4oI6~rbl@11FO_HgA0@;!bLCko2tPc6`H)4 z5eml(+Fh{-3w(U(TCL2YBJ1h;JB(7VrKQObU%l?+!vOtwe?<}-M4U%#xlzX5Rw)BV z*dQ24yX0;d_#Dmr;i4M}9?_@bIz0NTqk|-19D)X&b1xNVDzBak1PD?OkfnUF``WPH3(#f^ij%7lmFTih*=AM@3sMz*QN-) z&lld*apJ&nn{d4{>#!Xgbvpnjs(=}XLZ9i?*e`qmDoHfD^=LHWzgoq#{{LW?PA&hg zj>GThjX)7nV@L0dPzI**9|pGCJka_N7UzaJVs+lzRo|)rFYYBl^q-)8G_uL-nI!w; zU|K?{-TKPpvo?9IPgM_o|6VsKr;n~rR+w$}h=tqCG`js+9}Y8ndSN2e*rov@(P}lk zY%`2&K8^9J^mbY1bVb&jzvyF|Et{jz`TAUOzp!yY z1|;k2>&Khp#^=7e^BAb7BYRKOc(1M6YdGfefV#-v#FIY2b^l0JepO=oeTW{=T;+gP zuK#3r8QEo*{Z{+&mfCJ@43!PlKXIyEF1^-ey(0+$;Wj9pG;6at#ksoKeoTKFsgagx z*hmvsxIQ`_#Vs9(`$oerA?)_q^-dW z=I7rw21q5de1`fwuHGCaLe=un;PP}k34nDOQMH4o`>0>xbEFU*aKSy>O?1+nglWa9 z?09mU=*;DBIk9W6A8b*g*yNt;C*0^@R8(Fj6tP!~_iX{7QeR=82TKlXyb7GBhn=Cn z^IXc?>>$$cfP9SG^;hVyr~R)Npem44l@}k#%u1HUSyC&H_Q-p@=(Qf!nSp_m;_%+s zf#!-m(n-NbM@RN7EAIk@_XU@Q4FZ5#(BE3T4gx`XHi(_G(seth>F<(5vVrX$8~nvw z#-Fd=-T|!QtBz^#s!MTND?}{7Z6yn}ET^NJn2-RM$uGEQEa=W(Dk5L%jSKc>=Kqc% zJ^%#Ti&n*pj=5^;2+{@JvWS_sAjaFG+yMPo*!9~pmrqeaF^odag0_OXe*iqhV7fZb_2%b0605cVdZ8NcGG=->%{KSH)v3CImNIo9egG%wDZmwD~u!sJiHq6N>FFeng zP&&9@VObn{zNy1V!)E413D}}xf8B+;jgNI+JscFX(Qa0wOT$BC) zT*Q(zAW}}DeLjKm042Oax?52WJ}$_}f*arCEv%*3vn#}p>RWW6y~_I383(s;a*Fa) z{xwszH?zBHgX04;rD9jMtcw^;Cnbf1jJ~mhd{Y^uQyUyg{ni_F3CDayPyIhh2Isp# zYaC6fm#x*)7H?9~0dZ&}w#YS4UnX);Qa2g9G9IwvL;I(I&Dv$-lR?@Wn4i~>Lh|R8 z&;g`O{#i28i;U!(xMqqf9YpM2mLS5w9mz_!;>k8GrlEOY6(i6R8Ga(L%L z+m>PNQ!9uWmJjb7R)WRi^CqB(m+yTYpDMpQ-kB}A8M&q>R}qz#NoR$25&So3`WNuD z6wmSljX+jC-Y4z!p}I4$MaQ1XqtqK}z&MnWa8YlW!)4-@VL(W~v9WO=M82wd9?nV) z#M3&unsvH`i|$CZaiD-R9X|~Z3;f%E!0u1^t@IQt>3Kr0iok|RoZ#d+l1WHj#8)rP zy6b+Q|%RVYZ*qD{f7jB9?E zx}EP7uDj~)Y(oH0C)&)~$YfPUA3L4rWy$q(8#V*G-I}bKlsConvC7=lDSGL0}A?~ zE1|V7+NBOizYwoVLKt-1&h|s3f|xhfEsPo-37-(XV+N&3zJjm|X|gK-;n-&hCfK*& zP(v>JcPERB(A)eGcJ``*;9<#sM=&d`(KNpzH5(*10?1r*&`cj6uMeU9^#hjhjH2L*k41Y7aY5|* z-_uFYQaGGlU2pWxgiwJ{v?Q-vUfELvC$gmeA9aa|iDy}9?5qls^rYll7*h1e5)%h# znf-g=j-}W>MZwPQRyLNrG?-=VvcJ zIAn=<9M`I!e{@+cv_w|2)dNCrVn~<+>I3u&n65&>VStkg=0Q%H1Lc-fPBC)CeV{y5 zpOK%+-sP-b^?|kse&|X#t57&+DIQmH3Q*(=c#fxMG|{c`l_Kyw9X-QKp4YKC z_DYzp4#_&q=Y++s63S}x)akBeaUMG=^9S=lT+CeKPIDdj`H zXp28QwotiafAXxWuIRo!`>S`0muCYdUeWhx95qIYbORzFK2}O9xzOr5l}p9>!xuH1 zYN)}RqXpY1^hmv9>0Q#Cu9l6^Krnzs=mH#I8Css#$0 z3Ed%6M!?@?jub$lMj}jX{z3ugq->ex=^`gHK46jT~n*4vz2ii@Zcp(I!5d zjStFSSK%%(kYIq4hG*tOO=p!Kr?Ur z$c};np){)tlKs{~ChAbm_wu%uXmW;wm%~)c{VzJq)SY1`habqX!(~wKq9B8_HQ)-5 z=!Rf$!-U{H)ao~*HfL(}riNXONj?MgeCg?acD}+3IgtdZvLEwBnYAA1p&G>eSfi#p z*m$Y8v{LasT!wk#8EQD=UO|HW9oVCyl3u5{n!H-p_5m_;BN^ohN1<&ZAWF*)HK4pd zE-lBZjhQR6{S{~_d3pOZn)lNtu6H!v*8Wl!L@ur901MAAC@8q?=)`LG`ad)-q`iW9 zYZiAKB>^=y|EsTGvRPi&DUz2g@Tv1{ww1M4;3Ae)Gqok?CVyNc(aGdL(Edn0G-~4_ za)h(4U`&?_%MN8&VenPTDPS|MON`M@?0P`k-oDYI-wxwIDK(WtU8(#F=%?y zrBtB6`$Vnj^67OyONLv-vAim&egmN-kc`~ka<=5E89v_c@$&kU!iH=hAf8aI=Wv`n z7A-@g_Wi$59q5Z2C$OEiFw?`>y5jZvKDLeV?C6Jg4*DhQy}rL}-8F_yMJ1I8#y@_- z`Bxn6({&M#L_du!JO7*+kFTKV5I!9SJ?;q&4J`rMQ4O7kZ;SnEX_-eqx2;5{6Au&w z@pl=22^EXW+J@5=4!@}_)Y;5Z+Ak+TputPnpFJfu1^c|emvW@BkVvVMc9wpZgi3u_ zjM}s3CPkQS%-wmZBtlvik{>j7z%iftyrZ~?!qaYz#aPXpkr`JfVDsL<-JstYJjItJ z9cG2Lh3bNbH0n*6tmlQ{2w*ClQ zj8|+$23fI>7)`dxEaJuzi?%tj{ozxg4}4EU`u6! z+xeS*BpgOPv|;kLF@oZU)6Q_Mg&uv7)HfNmA0?kvDK1+G@~G9H%=?U)p?-;8(FcvH zv@dsPfUbI~)-VnKU@=%-bv#REm4+%KgITK&y4@O|-}t?eineDTQIYs)(QG(#-&ntM z3E;XSNQ-EDi=>mEV1Kubdu;foyu!;XZ+V4H+&TpqplDL@quoXQlqUEGo0*;>ZjZO) zDLBW#foh>Fp2Z~kCbK?WbD9_;stpeZd*!j}k?Fk65iY3E)eDMUCz_Ki-N$#{-KsLFLDL^*QiL_J?Sdu( zaJtt3b@jTic4-C`lubdMSY238rH@ivTB2tzvSrs3=Kk|=vAGuML6Lew_C1eZGuTVi z=H(0a5@Ct>bkWOKMkwde(i&Xn>!GqQk zwGfguuPR$D@(6*;^@si*(QuP!8@$7t;VBMPlvNCdr^T@?)~Z8uPn(oTz7BWb3dK_H zpICuF2I>@H$OKC_baA_%GlMEad7(RKCTM_FFvH}w45pk|)@sn8V8VOM4V5rEXRx$= zV_CwY%K&D05!oBT#itLE?L~fMi>(kU9KLUubTIGRSFTlQr_e|i@{PNnx3~Y%l!u&@ zvY7JZbwzwuwQCh+>$+uCyM`t2xJ$8mL{UU$bdl7ZKQOM9m&#omzDPZ#s4CI_M>BUd6{2D z`MMzmInXBMRaL_oM9*v7XZbl5V9eZ4^or$;f+Jz0#`lf$O1f){^FQ!|9;)SaJXjhD zoTr@LOXN@sd7D`* z4P8m2w8raKK;!xYsc^V~VVvnE!#dN8@Lo!LPak}|Pe*cAai;kMmAp>3Xh4` z|4_jM98)h`o&8v>q$r|NhGa0`J%|u3^5g4`8XQZoL4}_2EKzD*= z|5EMP`yeKvPkHt#<(X9#AaVF^M~vuL(!^yaPUu$~&Ke3u;kl`3d4qWkcAyjSZBw~u zru`tPM3~e-EkWnjR9p4HMpJ?#l^uKru~o%d#YIQGWc&0ku+%x~m?-9vCSx%}G0d zUw4H|8p`nEF@j{kygr1hL!4GCK^6B%8Wa|~CQS6POOzu|AX|2XQVI=6{#gASi!Qa% zw$Uyi;+v)(x_{DjSeU|%(u^WNu9n*6d3sT*JR|2yMlX$-IEDORe*R`A;x@kebT}Xl zKr=3Z;j1j5*{VJ_$Pj`I3tkdfvc!4x{7>Uh2>kBScc3|Dg}53>lOZ{_o^Jn&O1@&T z>?5csDOjhFvZQJ&iZD_CwOu@UAT&xUVWFvptfND;iErL0E7SS4GwnJ45KaA2%&%eX z^oCShM0q!oQT1^k!$f%(mye=1h?Q}u%WxNN5941e4}NLyf2Cm#6!4}Drz*Q`5p;T; zOPkX6k9Px5;1o@CkeDC8ffdcJl5VeJ zpJn&i)73RgTz1D7SqhGp!~TBwIHCIH{z=kUfb*m3f&rkz0NHt*HJ0}Yv09(My!@i` zUX2u((Uw#}(6;Zw0fzX&fLGSo& zHn6fD`NBcl`(iPk;Ah%XJa4?C#;|k#8aAtAF8|)x&w|iq7}P#6z*Qh|!#H|yjUT1P zrjn=j(#Cs)Ksu>ImdmC7PGBS^WQdXQ;vP_&ISB~wv{oPP>rlh5-uMA)3KsU2kF2Qd z>>^Yy?8HTPVFjuX3Xe)l#gOG`>0{I9kCh=bm9*scl72DtZO=<7!Dhy`d8_?BPJT`6UJ z7Ya>|h*BAjvfzVk;Jnke_m;Rc0@|klh zj_tS~xN^2F5wB8rpTHz{j5CAW(R=U1$QYUVZ#LOtX}Q;4GoRY|7dYzeIBn4?hK7c# z-$*d>rNqjuh)L}7mqiVV!f8q{i9D8FJV7|J6F7swr~Ts?;} z8y`g`8ygesZzIph=-Y-LA?BChA0@x3=?0px@8HeRmR?7GCS#M@oByu27feH~^!npH z4?J6f`fYT|FLJWn@@h38a~>E>1$febYFT zU=ZhVyU*^t)MM^ImS}UZt>7MeTQB(Fk8fPOXoI828^0KvuS>mZ$Fo%I5-&V_X2W^F;L3<)2*5_mdsFDD{L2w4NU&|5%9+Fx#USixIFVT zel(C|JIh*kaasPLJ)b$Z3YJP_3(h)jh!;xeJ(e5Pkv-RyeSlsn^m0bn6s!X*k~LO1 z934EopW}q#^J{Ol3X@K$_P|B`H9rYgJ0>-|G+9!(Mr|hHLA8pkpIke}y0A$+EH_yi za8j#dO*0g|?8-nh{UL%BxU~h;!;U!abw>k{NWt9N#1c?Vm`$!v6jXi}TJUDzjgcbI zEhi0_vGB6)OmN?dLrK(bbb7tP$I@5l+I2!#tb0gnfN_j$RPgJ?lW=yj)h%l)> z8=zW#h2}C6U^~p`K(ipOM~LjlcmW`VHh|@+x6;VM#TB?0cJh<@eTSZ<%q{oVs&z8~ zq$7-nDX*P1u=nxP&Gi+KWV-a9vo|GCsfre+X0ZYfbQ7bJYQ)hu>r6wu3_G>DX+QD9 zE7>z?${SzB2t(Mo0yR*+aDemCsOvM~zAxhbQOcfqP?w|uKZG$Kz?dER6KN#rBRs|| zcUrtf#jXknw+(Q?!K*~yGR6z{qS!dQ=P0{3ECenFdxC$oW>IAf0Qn*b!Ot5VoK(hJ zS~*O0`};P|VV$=g4Hy4oZ~17+;o~^bmJ%*<52n{U`#}j%hJoqnCeI5OFRX#%t;xxW z3E$LLIYVm`6FOd1B&w>amnzTVA9i|9aVb2A!T~P2oekrcLrE%C8>xlZlm@97w67io zh^j|jK=Sm-f#^VN_R(aBu`tQ8W;RsLk@k8wtjh!QIjg=R-mBLbUER?c&w12;rHh`n zJclIsKGj2ay8Tg+32;js`BvwwAsWSrft@70^G)Mb6#lc9FXf@xbt2O!M2KgkwaSrjmEq~Q^j)*j&M8ZXZT&j01Wr?_ zBVpGz#V{U>^TdhF`}6k!TNfN+C=sj@dQbo<-bk}HTd;H_e zX3vXb(vk|-2($^?tMI>g!Ojy#{hY@WxFH3c(^XQk8s&wFTL7n^mQ!1W$f$2Sz0iuu zBhvSdd|srurhj&^?TDW@+!wD)lOt%oV+#9h`a%y~^jS0o=*YApi#@d_XagvA?N8f- zZ0y44uV#|)zI|bn14%GaUj3|~?(S6qc~yxElu$_-nm-N>4Ly*1YvgEkFf+UTj1WRC z5F$)R7FB2khy7*@viYi5 z&1RG-oaBDA;x4grS6harjE|3ayh;mo4m1)++uya3c6p1%xE)BKjJnd1A%2E>Um7RA zY6B1*=hyl22A}3en}%gk`B*`r~_+-KVDh6U#n2l%eRo zVT&5x*C0R{8MINc9>L#v^PhJ-d-i^XF|*_~L-!q{I=Vs6Jp=J!_hfySga6_QWm+wXveu`nL1(GOu#k6?E^xf_4b z3K=0YSFcrb`H-XBA4DTl{zM|}ttLGPxL>G=1WwTV=DKFqYZ6_{P(TkeNo1u62r=R7 z(|m{dJmN{be06m-r9Dxt%K37uDIi$J$1mTJv8eB2LyrCHr6L4igLgNGe-*QLNuM3F z$lEW3;RlB7zpLQ+^769W{Szeef@l4@54f-!C%L1$dn?09EYDAlm0?CRx{$SeAHcK=b(r(k!6E*#H~EP5Mf+{ct-kkIgHO zROH|fAJ9U7s!lWNh#t%$Z@Z?M4y2?Hw?Q70O4KTnQ)ve)CMXXlLN#xh?*n>jLbfhS zDZK05?yhzK>t}$pdUC{XuE51TGJH@gW|OUvQ4;B!6jN$ZJJB8wKi2KAC2_(7THc3g z&5AK0Qu4)}9+mei*|B}_e~ijch;0;-LQ3T1HeXo?Gzr^2T29>C+k5tYWVhgKs@^%s zFrU*g=cBOAATRpk6)QVfcrt;IWyMsNBTyg&&yW>1aa>bMjvyr3eId!)<}xaIUT4@= zOCLyN?hI5`)@regk0pq(!z{xj49uuS;|LJt{0u-;oPsvK z?d;~?#39=U+Lyt$=_ZI6#Jf;dho%oi<5a9ya$K(Z>Z*a|U!h}_|LX;iCof@z!PLED zdt+Q#TKuaUG|sQJXXd#XBxS!1Jd@QcWF=X;fkbfrtr1~Id8Irbc?^VU>{%#&l5MR!k#9|6wC+Vqn` z6n_BmV}YhVc@kJm;D%4ZOWT*1{=L{)hz@22ucbxDfYb#+Y@cS5wWr!(z`0%U25g&)!jo`&U{BTX(MqT|z;w0JZZw)b0S>BaK^Umzfe zJkj>=uWZdKGP{U(*ZHHO%|07aWnBD;C!Pu@1YDBSPnu639DW*gqPqR71SO)^>jXQ^ zEhXoWa2Y38SKHak)k)-BO5RuJ2Q0(G492IAMe-C#;&CE371|*}k!^&x@bk z6qi7d#_1%evPPJT0i{sbcZk#d0UAmmR=75y78OqDb%905JI&a62m!XnCcCw?ia0>w zeFFk@C%}JrVS&hPw#n`f>8-5|(NAhvu6) z@COxu_4kI%x(6AWYkeM+-U~e?^kU?Yx!Lesm*D(B@NV-8e7m zpw(^*xjY`e6gir79Uz+?;;Bz147;-=Vbe2aBIVvIS_IsulU#G6Mb* zUMB8;*~NS58ndN!w~D2Yf8n6WuIG?07SXX_S|}-Q#H|+LVcMj()era?Yq#!29%uOn z7sT`4_bI;&`db~qBuuvwoo6rvpFL~i_R|0^Sq^ieqq4*iSu$-QuN)-Bls&i#NZU5d zQq5m*Dp^qx2qz11Tku)rOlJ67G)MM7zngH~Mo zE!1@thTAu4DJ~~sWHR(CMR|w6&kx5o9X#j z$=rs93znNhvWw4CKqXc)v7{ZncxPIwjek+B(4MzCrWBicd#vSuwCyC-S zhc{dE$-udQET!jZQJ}$ zoaYz0^e?KFJ#d2H+?E9*at?{MIUJH>j;ovNBk%qvythiaTrYT`K~A#tP1aa|?MuUc z3}+p!iU=}^-0Q`lHMMJu=l6Elsrm#PLDeWzft!;RsfN_*4Tk6 zh5bL8zB($(?hAK7noqjB28IUdmWH9bySt@RrMo2s8M;FnR2l@NLAtxU@9Xd0d)E6G zYi126-W|_=_H&w&dz-5L0|(z4a}W$BcI(OfBNZsT^@f*aHoUlUb0+)RC7J$QISU+W z?(+&0J7!*K8D-miNnGqh>)P=<(62+|Qp?~2?<$9~R8RT`+tig!LZj5%w8F1gZJx@4 z|Ju>+VX9yJ=gIhj=l=wRPKr-7p&AC=)MHO179OQo-NaPhh#iTc)JGKxZ`d?)9S66pjur!vCuilq==m{5qQd^*+UN^? zS4lS+!gCATrinW3ygm0nb$aRNqp-K7DlA@XZc=(%Ha!=)=U~$Acl=j+U{}=~8KX$( z167PGeOt)#)##+oxxfr_P{CcSe9@a}-0$IIkn>c|^%u#H`Ac^@@!X zj7n~iWWNFr7F(qkc=7D9Q*y;%_@JV+?0-4yiTX=A=kM<#`-Qq$ZZ{%g2CeVJP&R+;WYGDW^&iS;#D2Y5BFH;XR*BAr72i)H?L z|A^zq`1Pjm#Z1!i>*L&uWWjAMW~U>gv>OriHcX3y_|}l`RYdQCyHsVs z7=-!*uhoDg(f(V_Dnh=zCf z;Gf8ZG~a~TCGq^W2)c#w%~X5TVE+E{4Y}*SXO;=t#|}j3|1SM$VD`~m>ETtarYR)t*mtE z^D&_^c9rF>L>F`Ke|(eBjV%$l96Jv~D+hzl2Ziht7vqkW@6}zr+SwzP?0Ju=-HC4) zrR)3zenmus@Ds=#56z^!5jm8j=vR>+5TFI06&?}Rv&!4*gB|pR`m=C|*f?k~PZHtcs&KVZ(eM(uHGTFdN&Rpo34=&s&d}(DUTM+Q#)bAE3K>i zXdiN{7C`*EVsFo6d1-Y)0C_7SI?aA%fd4O0_Gg;m5rj&;Eo+TVGx&aLiO5)*QN{23 zxE!YX)l$=ZNS#GnQc6iF#@>F5y{pCScUrguA|M~RwqWV!$sw#b+o183KZK4YLtijy7&%ljZLHE zl9g80qCbw~P_tagI;(!7=-L0mQP^(&FVz$J!_WaeikdR^%^@U)X{H(JPW>x#ZjZI? zN$pR?5B}WGBcnKm*DOJNT)JU6Fjx8hKY{_g>P1S15=7>uOTE{;PM3usPR7CB9?-Rk zDy^yll7x#4bQ}gm=xfHG{D4!D8vli-*u<-JlwW~`J{ovRViKs1p~+<(Z#wkSx9H?1 zJth$%LZQ_a0^?H^WknG(kgo1$F3F5kvejjtfu# ze8?}HVD3vN1fY55=wBk6Ee&k$hNuaS^Z6%3X~|&cqHw|p1(1~+yQaH)A={1RVuMWr zXRj4lOjNO(O@9TU?Meqt!?9AGg#h@^X$rHlT4~}J+dOoUzW9bFUkP9*rFJw~Z|Po4 zE=-C2ec$*~Rr9Dfd3N@2bMvWOVKdS2JOr}BE-&Rdb<~rxMhGGPlFovk0p8zs3R3{u zTA5WFnFQbrH8$17qn!5~D=K1W6v{bDU)|B^Us?uzsL0!zeQIrh3`5F*uB@XyOWZ=E z1&g%>eaAq^AuOhB6w+(4y)D13(g-^U&-Sc-x4uBIys>){6TRBpDO+7 z0v|$54pi!ydarFBye5utZ7;rBmI3lpfOHfLCOwiYVJRMpqX5`nTAE~0GeROg-~CgD zAmt|vUCyUdD~~WGReP=@^LN#R5W5K77cvLHb$7dM?!XibGT2SDq3K07QwV$l0tK%G zQ16~v14H60k_?=Qdf2hl^!z+g%nXaYp{61G;%`NWN;sCxT?;-_h?^9j-zw8MR@NFB z7poz(%)b3aLW1fS^PiG& z1LHHe5ci9s&*~f9S$Qd7!O8`BxICJR`?sbtX$%t`x(qeieR!Rw5RlpG#o!EExOv!S z!sux19m{JRN;7EG*(yr6A-z9>@?QV=B5Yd)Ovw(bCNVXkjtNz|?r-ZJiK-dWM~@(e zMmm=r#C<*;i$O3;qN@D`X4QXpQ|adIuEI9(Ruywl@4ga)XkmC~G&@FA6QNW%i3SJU zfAB?ydMIu1gP%7xScg|{ax|MSgVmtepOC21V zC$j+l12<_)#=t}=RxGp;cWLkq1So|kFR1CM*iypQfi72D{V$XHYKAN*-kSJUQ2a{s zthJ|rVH2I1!`3BztvGr0Z&a?QHQt(Ok9Y0uS`{h|^iqUz|*=}s1>M_zhZ7rNxfW%YI~Eod7XXQq0|;IJVf z>CRdnD8_`wZaN&(879%&VSgB-v+1HP$T215z910;)z%F4)RvP}o`rj=p@RUYqZ6x==!R|` zAX^K4FwiCEa9-`|{G$pm7Cx{T);-W6Q5izf(jcpQCwt%2{9+6+2(l5f980`~gjMH$ zkBuD+FcDkOpF*C|u$@lT^*(tzntk$&Wf6;fbRKwJyspsdT+JLwTQL-PYLD7PXP3a6 zc9W9^@cHT&?bGPOC(-P;BUKG$*$wO3L&>uUw=OQqFOnKuW?z#tx{`+iiFgvkKlTvO zVPlUZN6N)ZCxNxNf{O>?=KaAb3;0ous1lC>L+asseYUAWUV@tcStN?vhIxbo9hL5@ zo|$|l8p*nio_!BpJhSnL2QFq>a@c1L`ETxu0X|+G@iIA@HY)cwc0DF;g-KU(*A+ks z%b53jkmJc~I(BjygCFLU6N%tech3F3{D=7O(Eu7z`LLXsT3+lfP%&->4+E@OU0q#u zb#-J!DScWSuSjlupS?m*%?J3FACo&y4OCG(F~Ahk!SeBUiD0F1 zMWDe9L;zIK{)s|F|N6T+UwCPcj*_eM?hE0!fDF&~NDl~DbEIP*vXua+_aL=MS^jS! zWKMJDPV-$AIl89g29R>{78+L2 zR`%X$Y)_*I;4>V4Pc4_l+kb?v0Kl&ZC(-jM`*W@xyMa}0Frg)-+FwH|l$tB`tU+CrQqTpIBZ#-NdM1yw0gCOPwokRqxs?w~QlP=~HI0dd{VL5}A zv04Xk#Cy1Gj+xER$~@S8(wxpolOzrU@G}UqQc+UB=5s$rErYhqOQqJw({!2hN0m$m zj-_{@hR8Vv-{mGpkasXv&{(D1HxL+4HTQ%Z^5DVJX1mAg{Vn^q$Z872l#_q)NatoInfWr%+f)@izBq#7mGZ}%&5NS@0{j;UzOtYafT zeF@%SSHm!rPF9~Po2@L3+JdOJLwH#g^a_2Xu7+jYZV8&8 zh_Q==5FQTp2}VL1T6B!3r86FF*E2uXi``!9q*ZO1lS{pMFqCiqz0@4zzb$Rlzcz%- zWg=Q(q%wIjqtac_E~mQGKBY}=%3L=R5k}0xIP$t2p{+feL;UWKBow_4uAt ztWk{aLxpS9W2Z8O7qG+(gdf9zPz!-|WN;)OGq47N<}G_oq?}SNt&n<(t2dR(yQTyL zpcAr`Zc47_K1)Mb#>`f$KS8davkP!W6CjfkOF&z(LjmIB^XGJw2NxfomaeY6ZCM%M zy?FcfE#Ri}a&oqsx4!`bDe8FO*;2 z>OrG~VpbTPb=4WsNY<*r(BCEGO^{HSQMhPA@t>nm3HPsS%d4~)ZdCNMcFG^2@-^!N` zICM5>GW`!@{Kar_a&_|7`BD=`wPxJGYy+IeKPc^;yg&3Q?96SQ-0trrv|L}j>z+zK zjz>Ce$xWNy*Kx1IfZaG=Z7MxTqscIQULXfVvi=BcrX23Zv~9%*y}GDb+SJw;kmC^6 zHJd(l)&;aqE{RQu{0C1O^6p`pWpFO#H<~5HM^B~&ZyHy&Ep?WA6FmqQfMO4GDAzas zYfw!R7Qg^%akW|k<3Mfc@!?=VeElJ zCfY^S=G z=AWoM4>O93wMKC~R6A?E_jkrP zNpQ`6zOF@(mRFiX=r0PSsR|6+SH!cLaWhE@{&_FPU&_QBj*k8>qpV_|-bMZDn%x)15Or88$mR8&=Gsq@prD zHa6BG_~i2NKizy)0r!#W+tUEFNVjHG7tGbRaMp%aI^WqfMnwp7L{Ujf!EEg5>=&6%c|gEl338- zXs67{*0yc$er50ODZLn2#aeY<+~=rPUKTZ7A!T{~pGSf%ITNt4)kUq<8}By#EMwhc z+EV{sKa~RuUE}!IGNO6=VFl*5#D$?{2!i(k)<+_w-s893VJH)sM>8tM_LC}{ z@Dfac4rfYdblk1q9UL^n?&Rb|%J=em)al?#rjx$vdtnVmbHSrPIH!VyA>x>$<1p6A zQt%F%c{j*9x#(VzY_8i{`1J@Gdsu|8N8L{*_C)7?#U`KPRQKTrO%aQyu4YvAxWmN6vV`?!(PeqipR7L^(Pex~Wsx^ptJ?mdR~>U0;j2o<<+s+bi8;GL?5V#1e-h1d|R| zIi$lwg(<{>UxX>IannV58;kn;Wp>|OM@69)GizySoiBnwUtzGm*6OW-QUoDmI`RvF zD2k|LIP-EEVzmg(YsK^;f%}IOVsc~E)TwB5LC(CdSLNm5X7uHSZEdYhO%|^&{oi?a z=WNbmy&5zth2XMM2JKvpeZ&+daUvr6A0c7vAgme2Pe zrwqz8y(A?o>*UKI3JzsWamUB0jk)#8SW{swBXpx{NU)tM!_sgwlrV&ZICYCY6xdiq zuTgz~xSApi?7~Q2R$cxP6CaPQj@zi~Rpy!)2zwH}jLQI_Xn4@|3jWGPLR}px zI(otpJ{UCr_b)=ogvqlOiiUPaT4Ar;+$T9r_fl68$|Iho>!*o$S`((48WW9~*0k+7 zOLy8Ysf|^~c#b8eP71??Y}*m3#_N)7)CtJ-58m#F%*dF&!lq)v^x65B)WNk(Qd+T= z*TJ6&Dk6+PNAy+N>Xet%Zd~D~7i4qp}oISbk8~)zxi$Hfyv{p& z`KRwWrs+UMPkErAQBya3y5MkA+&jY`RiFyuBK2(?wXiF=Hh_=0-O=YiD2PKyNQjsB zJFjS0{rB(n1o7%@%B3N_4;_JUr&U#6pwiOHCp!mbyr>jI4H9ywfZ3YHewikDW+Qjd z;m+0FZj6Tq@PKO5m-H2!N5K@%&SNzt!*K64Gw4Qz&Q&6M1h$ZLgJ4n%FM)gZgPXn)> zC&ACNvr0kPJbmDhzwPufpT)|8v>MB!j4~!IjYswzb-fxqerUq1zS zz=Je3wd0$b-@K1aJR850A4<4WU8iFHSlpIe#3n_s+9{1v+q8lfp=O%ZdcCXQp^!jP z4J<26$;sJh#V~(mUeVEop}9Hb@Q}GYOA);xNr0*>q38 z8ZyvmQ^e)XtnU4g{Jc3$!<)y4A-Z4_M%jPb`Pkgc>3V-kEh+^(odxGG;+465268ggqYp3UEVKGzVr}`l6G)#0Ad0w zE2|d)H{i4b2Q^?_~jf8*k8UD7QSgsHZoJz2AOZR*K}VT6Ydw$jBuWcGE?z`4$S zBqs-*%^c31dV8L+x&=kTrzceucrsY^B~DKZK9iv3KA;wa)In&=1_3u#rWbhs} z0DHLe8n;esX69=ayL8~uos}@02>d;X^3PMPIJ%k#2;URn! zei{CO4mLK--&JMJs6tSFo++Z|ohD2XnH4AZk>MeRmc=F_4J&=FI%VJumMG&FVT#fK zVbi6VO5|46e?~}I#9ABui(?SQSf|!WF5+ORHZJeFq-?8qy7togZyuE!-mGuIH$$mu z$CLXPe;LXiY6kdLW8QRpB{PmZdL37-5e{0^RD&;Of+tdda#c!|!vA8^ocjIF$}Us* zw{r?6st(V5hO&oEqEZyT1>dBkHDntjMrB|N%G7s43$jft+I{zGD@2W|WH8Nbx(}=W zEmfMc8+&Qy>DgFPGBESwgYi^s{>`7W&s3jjY}KONfHzG|=U{)ouI*OX^25K8-U&1j zB8Bw#_s6QVd_tAcZo|1_XH9~G4^Zj(6hp}VvdQ(d`E*EY(v39N@^zON%;w(x&7!0A zOXmuo$TKq+S8oimIy<$j)k3+EvZ`O%SEg_VpP=iV_amWi@SBElmljJ= zw-&sUMg>vLTy<;ye%)^he9W@8HvgnM(^g*?XW#sL+=)$YD1q*JB+ESLijK#yivvlI zn2w;KL*WxbHz)@;op2|Ea0hPfXD2E>2i$u}4=#|V?8uC#ev%ak!W_c{jhE!7%c-qn zTj!GdC0BQ3&+kR7k?L=g<{!Y3lZpP-*pv*%9@E*kgvYV z$o%NObA9*|FY^ha`MJdN6G@4+D;^tS?SM%VLj z^Ng3VeNs*Kc-3~uzG7}QB#w_SfsfC{#W^qNs#K)gCS;$|oDS0YMR}K2KTg#zD*-<* zY(B$WNohOlyHz{CQTh5zpHqlaspdP;Vn%=4;|f-CQofR6W!yf{FVF%9dx{_QO~qs`sW!ZZS7QL}m&#ZfD*>7jca#~}nT-R1kah}Oq`{f~ zD4dCwH0fq?qW~J{Vkf0pZ<#>4i0Of0#y9ff?zqwP#e8q2EqnjUZauHs>qeapUMLNsi?d`@u={NlT6~)nT$}Wj6DOvx@;5Y;xC@Jp1C5?3E(uCH^mm&rZsjSQdAxe=^QqIq~`dd&?KK3F;E-qVFo6!*&MbgCM^ z_C29jY&N@elSS<{DEdF+B{(MPh(UP*xM=HxA}SF|9Q^y<(2#Ff6v*IZGF4On7II`O z5+^D(L%LHvqi}mWV34!a^A2s8Qck{rG@~~tDd|@mt8lMoc?>oVg-V>3dI6__$EV2; z4RkFYNpfoWxdB+adW)!`@0AZnJ+nkIPSyPq6F*4A%Da;3Y3Yv>lab*yxGLuf+c7aw z51xE8EyU4X3fdjd=VL9RBx-}BYd*j4?UkZQitIDjo=jd{a3xbz+ki553S3){o=yj3 z2P_g@k#U|o3Fqb^4W5<2y|=bG%*md84ZD7Dz9&tM#(q6g0KV}JUjK?%l~i{)x)dn?R(WFZ-#fXSA#d=4T_} zVfL|~K2hm#yieSaK0OXusLaL=loOV;E4#LY?~zwu#|LK2rgzeJSubhYP(_;>R$d>q z)t>s!E=nP66Gaz>-{4Ax@WucE6)9+*l4Il8W)uIv%$$MU2Yn;JD*3PiR*9zjhVISS zptPTwW-4gSXYRaVSPyj8B-K1`)|L#-U6Vk%8k;4Zu$`S<4QgXQOgQ!HXksVEhh5aa zd%WWFFWM>r{RuqM-Pje2$W@QoVNOI=P#ckNMiF@XC$$(ea$89aZx4RzF8)Vjvt0sx zQutpYkkq$$eNz=VReP{5ElSu{Ps&Ra*QR;~OEdD`cL+}o9ex)5Px7?w#7OAR$8NN{ z0J4Is()F4Ky&)v|heJ)K!z#QGw;^uy0Z&td_dq;(CuK&0m^(2sAw^?B><-%7-(RQs zYy}u%N5`WS6;ZdQmdD=S-oe4ao(RnQw@CW>`tjsKA2vS4O>V^3SmpiMd@~>|y+7K# z5>N}PYw*qfU}>S z{yc0piT2ESg{K=4(tfNczu0~xAoDN7kl zHxfe^sw`t;Y7O?o3h%s6kdTr4LaS^|Bodb+O!)9O+X9|r{lXKh&F!_(TFje0mgolr z7#r~t1}XnzySMNF`99!c?Pr->k$!TU;^aE^+_VOosjoL4PeV!y z@Emy^hQ2u;8++*A34hQ{Tmd7Xie*OV#?}TYu)~f&&0o1vL7EY1+`$O)u9Y{f%0Bk_ z$fx=^ofakdi1V@aAFn2fs5!+vHhM!@L6L7n#?J6{38=&FK6Mu+<0^KBo%zx#;)P4mOqD zZ=Xz!rwqN{idgklhO`B-yTS^wu*aaoe|mO~-JV1t zj2V%qS0}no%KIhYX)gHr1oL(E^~vV-MCJ81nDb@Cgl%lRWX3RygxU4;I|Om~elumV zT58UnUc^DIf(l|qoSae!T!?;f_$3=+f9%(9h_96$$xt_W*NxUcE?^7QPusn|{>=E- zfNOW}X?SE%k*YDxOj)ZOJa`!dk`oXMDF$dM==SyeIQp>$9Gu_PL*r2>-wOvG zuezPi(NL8vDwHrE$)C#vktjOgtaWdkoU+2+`2(L$GLZI*k1=x}4ZJx{&VH*au;bwd zb~1NhfkZFU5#p{t$Z>c=X4q+!9bx^=(x0l?;NAn0bQxqBTKeWDOHIW$vRj>VGsR*# zqCq>}aqG9?tB*(R`EL`c>T43vj=g3X;YrybXwAKnLe$5feycvXF?n(2j&)C9V*VVz z)SU=C%GB0Q*ELY6tV+vB10HE$c82zfZ9r=k!@sQ@ud0>-gF+gos`RCpV>4~Z@ErTZ2L9vfln$>k*N#j#V-?~)ZsXerEL z5YB0lnxDgzmlKmeL{Z~=(x8jr5n0CExyArza78F9{ZHz4{E=OavrIGy;81rZ`@*%{ zmwJ0YHUE3>x&*HI@_nBZVt?|LtbFQ5TzxrP?Ek9L>at6NeIlOiv0MBn5UUp7H|Zcb-z?rr{ch^?NUk;f$h zwd46a#jueGu!OyW+xN+2lb4GRW6{ZO8-y{Gv?%JjK#*BU@_sf-P$X%f$B?3TP^m$~ z_2+hPwoal_SAabza`{w31e{Cv(~Vz|Jq|lLSUD#U$B?KV1-n-=tSbQ1MCfBsmX?-&ep#=jaJ!R}-ODdE17fEfGAlWLm;an9R0b^e z>b@#waGE?6+|r5)^8J1-4ZTqC<~7#0c}+HH`}P6jJb&7BGu?VpH#?W0o78V zHP7U3QS6A{BM2aKu$}>&I98D-%A`|hWF!)?Yq3=eOcmDB@GI~cet3a4H5zfcPoGSi zKO^0}Jq_q!>pLg^=M+)Yk9?M%wq+a+LkUfUXXabH&DPb*?ArXUVL(ct?ZD{qr~!x- z45ctAVfG~oddi5r0X@F%um1UX+IgK9Rk)R)G{h~vptV8D1&QkZ^fTROGpOK&ZZFxY zxvImUcSZ8d(W}E*Gu2agA`K0&Veh>>Jd7-++OfZYe?IdbKn2vY(0@>y_1J5J#IamZ ze>+icwEC%g{+q!!EB;Ty6sqar_obmV)h4@=umKd9bIKY&S$Siv2XkxNi&91V)zwwx z<%#W@bad7)ldk3E0YRa5W+o;$Q^zA2Mu)bKA3rMUZ}1UeHLQC|N1g9XuOfu7uRLrV zfodS3F1%p1|Azmvk=F4+jI^|tzta6;QBX=w?Lm;hHe)BLC)LhB@fe+STh=jtH6Y+_%Lc$-m;7l7C(c)#` zV{6Ey1g{XLagv+XT-;&`fIq_`DMOp4YrWzXdh1l!fCm|FuSLu?FkJY!A z0CkeO^0YU{pF*<9(YX*cQ%O>Wwr+Sql`O2%->jN52=$)Cq|<^Mzf_i7Wi!qtI9Y0? z>rWfGyAh-lL;KR-ieu4j3GYAg8wiqv*yPmn6iPDQ@lEYdh2@zyl?RGS1q1xBqLPY) z5r;XCJm^wYtm@x9WskWhL}_d#MU1+(H1~ErHj}QU)zxuCAyN|hR;(~Q)&LD6P=5d) z`EqeD$Bd`ImomKC@$g6g;EUTktRDjxHo@{irddtvvM1U6quWxyT$bkfMLFxn%@^9; zB*mSZYaLs{NIPP}*6?AYadE)oZ((uU-+!{&Apmgl`FNU|+On4BIf9PtHQ@k9gXW;z z4%2?~Lw^}X{he!GB*z_MV&d0!Rw=$XY?hr|%wny=XE{Ld^1>(N8Q4bFmO?r|WszH( z?T|h4%PqrNgQ#a~1`9IgUb>dQwv7$#2Ej3J`PHWp0`FzIG>doJi8=qK5&?z#9U71; zfU=1;F4hf)KX$&}_!}aC!iTE5>BK+{9fo4=tBSin>!Ei84D@;39wjnZZ+{k2H5**T z;O_pxJ^3{UP6QQWZ6#vYb0(j{J}~dx|)(lyltj#b(x)m{W}?~BA@dk z-Vx-n;v!o6wtw}3boiXctApMO|JP_8gzDhKhbF#iVjdUTp!rlO>7lMUz%jT8`ND>*RZ&sd*VNu1A|n%a+vpA9 zb$uEbXjMw+y4lOU69TDD&CH;>x;XxBnPJGrAtY|DwwzWNRMY$Z?!%6%_z)^>Dm-j= z{wbSf@yJ;1>yi*UN71Z}=0tLHabY*Vd8}ohhqRrC#TyWXvdWtfgY&^?gHMf&Nf{dZ z1W+Bi1f< zsEUouFAbNg|A9=gv>53K8RJ+XN>@AGAJ+Hw0D1zm4lD4(g#|FH^L0tk9vH!euSjm) zD|Agy*N1MWYd=%_=md}x^{P}z48B->k+1nXA`AC&UGwbl>}8;#VW2T}`sR19`O$k{ zXASqXJL{*jjh=|ag-p>u+$NN5euRLS_PE}u<-dtC*BB}4h$Z29luqwO74~Wt#m&s5 zN&RBRm)}~Bd|FjdPb+THV5R;h74`}7=#m;meOh=Q1rPK&2OjD49sG9m+s_^SKMagKvEV!|MY5;?Sqf2Z;H>SPscG6fiJW~K!!!v_ zNNE41ITbgs32ws48A}xGWxoaVB7@J7gA2NitIN#pt&U~mQ+2d&Zf{KK>l$TB%QR z_8tln$rLz~5_agYsdWg5Fi0C*2Awj`3K#fzPv!TB?SeXkf*=n4Lgv0P|16{d&4n-k zZhug6#5Jtveh^1$`p#WB?D7v_W_c8A>G(6ha3WzBMV@tW9-N5IE-W~eL!xxk_IB3L zvc=`KkAjo}<1pd=WA3R5xEt>6MQHvSl5|S>DoQxSb*psb;YuE3EWrkezT@nFj*rhL z6QigtECROU!TB93s03e{1-;3@tq>B0_&v9BdWTO#NQ20&DphnM%)n3}n~D{hUb9*6R-!CW`~X+p#2Eq90#Sd?Ud%fWGxC{==Szq}iN@h3Z86A4|dO&DMV zT6$aE$|TcQsSsj(NwMF)OY|1ccQrpEib$_0_tPKBlohLj&<+)GszZ9qfAZktN8|
j#V8NOqcm!f|H}G#+<|Ynx@H=)LJn% z{uxN|1c8ti^PQ6hPn493N&;sXRbSY*?BQ@Ac;9APRT@ZBic$;1Z&w21R(>3jUlIRt zC>#JDnJ?HYYO&W5N^|Zb3{2wciiL$mmpG%BKJ!b0;<19Da`Fh;2ny_dS%qVZx!F;; z&@!)_;Zw9JcXdiKt!@y z`AK|o5$62X-aD~q^YCaX4=x`ZXoDaW$bLT}S2!bfe~D!$k8M>MEE^g1%drpuiogvd zG1PLl>sIi)z@F?K9qoLJcXQA%k3=nPzgub0KRK?tXueaW=SuxBbg?Tozp+uM6h%uA z(`U{(mD6I(^?LaqjF4qXzE(q=(II7dets|lEfko6u|$0kI~`@$7wGHocl+|#Mz!Pg zd;ADtaT8GdY6x)dsah|J98#grp@qT>SEzBd6q{_>r5=5NYxf_dp#M3ltUOC0H0!!G zm?u@}v6{k?IOZH=*dI-?=U7=yvI_qLx+5qyW>uE7p+`Hzjmmb|dbU{H+YHw?;Ko5OFx>7rpGqVqg9sHN59QrRbM`lp4Msh)8!OYcYT}{+ln(Vo`2vIT9rKt|PkyfN-#=Wb4Z~Ez=ahiq5=cr1 zeeLeH`bstCg@+rhlkl5Zo? z;y51__?KbHP5eAIO_qU4~u5D{Ng| z&-_;(R{#h`_r-8a2hPvmU#PtucrbCyw|%VxCfqY*OLZ+f=2vQ_Eq~iyj zG#`(P>|qcQI!iPKMgbWUcFduCS8WPuECf_k+V~jXX52|}IeC0Qd|WdM$sjw}Id-|F z?hG=3mly!36whURbC(a{*gwvvs-N0mLV5g=Bh;X)B-JGFYo-zv1I1E!5MW7w zaoYXb71ub;!#7~udw38(auM|gS^fC9P{|H}Bs6mvU3h_59l#{m^n#?-FgE5V`SRqa zOcu0TQ=9eQf=rE)MN@|G#M64o50fqRlhB6X9=9;)_|8gc2H7Mt(t8VpWaq{N-C$qY zmbryU2!$upJar!D<4A#==N(@-3R_&YY9vYi4Ad1ab#LeHYBS*;3sj8|frq`|?`2G! z>Ujb97O4gt(AD+zd4YM4rdn2ViShjzKAY`F!CwE*{Mk4I04c!PaD&%tbo4ko4=Lo~ z`nvP-a-xbAMD=*H-w&SWgdi?lAfX=8DQWywj;v<>qMa$>{#88LIMwRAebk`MyZctf zKi(gyP?FOo6|-c1^`~hL7r2!vq_u zf!>OIzBAAu=3wu)(=Dz(1(^^boEf9ONjPam0eMgE=a)=*C3`aAh>s-ebU;SN zhuoVM-rGhcu9t?ntB+MeaX?3sH8>k$nbeU~k&%*ij53kH$~7Mo01+f`!$BUFEfZPU zTww(DTNIZ?`*XLO)rOe#h?s}B%5jwuIO4Xf6TFnus7 zB2>bMH4m@4U&k%|O_jQ;cYS^O{bd#g-cdGZnVV(P(yE)QsGGNRIFzum0!s7-Ox2|Y z{%p=(!baXIRbp?*YkHoW2{K-NICDki)<)-5Vg1^=FadR5VC zKZ>Tfm-{Wqp5u0uueOLgj4D#{s!s*<1|C@NYb<)0t&MsF?b#Y$O=o`c*y%xX|e+UOEfP`wG@#u}5R84tQ!|28ga zpl4vPz(~^EbXnT6I^iZlVZtF?z46cE0-VQyB#L0963G72>LrQ4TgIeA*)%uIsQ&1< zQa{R)?Fz?TT&=QPGpJhX1()r7CwZ4KFmG~Ixx719(?l7DS+c**ZH1WD_Q9xISZ+rx zQxXf|96lX)piSlJyP~f0(g_z^oGKHE<&#{P#cyThAot^}V0(i7gwUihQ7nbO2%G%=scS}Hz^haZ8WTjcHZsLpca8WuCY5c_YA?pV(Ot(OS{kHC0% zh(2Kfg_IQ{fb3d@$sd)Tk1e2jaHq?2r{`%NNrQIMoUDJ^SyC$0wwL8XGuBbW6eS+4 znMO5>03=5^S5t*y#t+&G-38n<3J%jr(UfzH?_(0JHkJ(Jnif_0DOXSw_RDU9a8ir? zObrD3V{csC)G?1&zQjjf7a}M`_<1;Rs+EuTdyLLEi4UAAr0>Sj-I03$T+QbcU#BTx zN*yY|1eG{hT&1jbwF))sdC35-yCS&WBQy!PWe{tH=cwx(b;1E^VgRv@g>4guIo}eo zO1M%>IBn?49Io=WWnN&I5vB%{KttUa3$>UUjjbw9U2-Bu86yLex{=@ra$;p9D|Of> zT#Zf&aS0SIHUL{>n4GkeUf}8LU@t2#g}ZMne+Eoop3doP;dm|K=Jxd$gRfQ|)JE4~ z1c6KfzKq2Xizql0S^P|BSa*{>Ov)at-Zso0ctqFe(PW z#en}2h0CCCU;x}0bjukJ>|RWtZXfI{!vLy7xhuKwCk8P`JN3r1Erg5IY{!t!9L!K< z_m?o0-e@qdJ!hBE>6^Yr7W{kd(a4Wl8XG=&>Y9gG2;zygoDz&c^s1(viy#x5NCc{A z(L5q&t!u$i=(xD{k6Ug5iY!3=feOhFLy1ntL> zN-*@ZxHfj2Q_>{etGpsfRcV1A7UiduWvIA!SNYoqOQk zE`qP;QDark-;3=|D-QB4i^C2FzSq>SR{(d)voI+C)>@3^Iy5tR=WI zm10TjPFblUcZp(r7b_I}WYN*GzNY?zcAEgKo@%*09{#AdRY+bvdF8TCO_TXNayO06s4gXC=w>BYHog6!4-Eu}|a!A@Jw zwe?6l{VF67R^Ig*#TMP{(G&=j1&LEb%iAdi)1iXWt?HGVwB+@Z@({!lj&_P9nBU5A z>t_{%V)Plpj^Ih?%Jh@V!FEbhmHMU?{F~gAgYOkrChBUOT)tW22Rwy;3S}T?K<)>B zZ}KTQ2V4gTI4Rh-NMDGkd7J450A-z{Ez6g5uzo+ginX+@$Es&63FRTc=$|gpy00WE zNOka9M1_O))v+4HF>L`R)^Y)mKmu_9-q6~jE_%6O##4j^hG5MLbNNs9dalypz5IddlNxrbktd4`xTq`$yEcTrG|@hE@j`kWZ4EI4ntX6j#Z zh5y=xh?<^8_Fd>SwbLJq#Qg2@Au_KFD8f5wYH)l$RJH_(Zt`PinkUaWcqtvu^r9?E zWu`UK25%A}%nuoa18Tt5EhxMlJ(6|xUG+1-`T&X%TnNgPOU)Ukmj2>gri5n3b)a>00qOBor=!*MhjaACfj7M{j^K zS}>e@=&S{vYH2`%1|&h#CkyKYn^H;C%3g|r;cqQo>*K!Jyu^qIp0|M2|w;&KY zm+6ug4iy?u6-8Yp&};1*b~26tQWl=Eqy?^dPC@f-_=`6>MAWh?zH!_Nx73-@ zIJv}Ydyrxc*oL!bCHzp%^iHiDKK(Y%n9G%X&>98nc?dV$n)aU0NnQpj2U7+-*|dxJ z9xy`D?B9JHfZjk4`;(rbC;nf9svsSSw%SCCIMj_(<}=f6o&;A##^)#Y2Vw{fLGUK6 zkFP1_;ub=GW8X9OphVt{nVP=x1E~Q{jSL9DV!lIoK>DaV30iG*6d+Geqj_j1ndN9R z7+U|fkn;*uQ)&4-3!}$C9cM!3hf`oi>?TA35o9ARmIyK!^a?H8ICUxevHhaLA`Q2A z%0S~pe832+23Zz-s~D@$@2{806exbI@a510$q&E@!8WgQ2g5jtOq`7Zk>cI^R3;4G zx|HN{BvTM-d!T@Ts_=OtbN@x-O;9#4w5k)s<0yR;qJH0)>LjWEKub*|``&W?C*IO5 zKD{X=fYbMCF* zn7NHb*dQGl(k-K=Cf*<=l$rMs<-#@np@+DJhzcWheJ$ZyL1xtSOdG&i63T#a6K84k zON>QyX=Fjz?8F09Jk+KhR)sE6AhpCR1m_7Ioo*8a5M6wJURs0gZ&|%5OHu@1CQBQbqM^d#DCQ-7pgZ zQBcqjwgh51BmK>EU}amJWouhnZwbZ4CUid5kSWl%(XG z3p0Vt%fjW*mi#Q66idwUneIZkc3*o zIRXSy73jTzD(*S8it&<#G3TL9X8l(h2e=l$eR~!tYwS3bs8*6Z;VP!c2yI>O5c@OG zos)ogj^DZRM%9!hZEl+hQK69>;hl-J7?_)U`+aSuY2zm%YF9q4+Oa18Vtox6{xBM! zJTmo3@Ac^PQ_dSV?t9UEnej3BQbFWK;2%HPxds9cqdb94Dzh(#c2eQ5OXn1Vy^nwL zofu4UrSmgqs>VHai)0r}8sjhNd?tM1#R4-;L)tFMQJT4T6BAB?sD{&BN6oFw7D-=3 zKaY>)69>Fjhv|AYG)y!RC9*kVV_u-B>+I@E+^{t?tA)T&2jE<>il#6Y2Fooy^5(gb*3U6>k= ztvZuLbbi%1!#ocTsJdD<`u@zZAHPSd9h9ZIENXHlyUP(^=F~V{sf$<5tX<6IRg@Pt zAhysOedF#bxdXj}yvwYb#vMixur0!NEt7(2K@P}^W2xgQp{ZrWgBH?|FcZrrn%9J2 z&*5wn(0e}i7iW{TvvyZ5+c-*1a=ZFaEbueI{cc?ctt6}=j`)zKT^3+Ft!obz&%e9` z#N}cTJx{xWRh@_D`bpaTr2X>0a8sal2?G(hs}3&pSGIP53(uGYULv6~dp;E)FH`r; z**ZejUZ&`WJKfl*;xj+Z78Oxz=u73F&;9&gwD?eW%*_IsfT5bZjK12RDd7-d*7A#J zkPJ2WN*M0{NuDZU-i?$b_x1Cg8kSZ46KPEiPqe?mxl^e6t~}(~@C!u&4A_)ywKFCv zZlbyc5j(MVgpg;RwP7!fg9zLL^uAPR99HsDh`-%hHH!_;B3R~Qd&qM`*`2~?U0!hT zgGPZcDmZUUayby5{VLYZylb&TWrrr?K+FN@U762}(H2oSdAs zl^}%yfAL}UsfokVVj$dM>C#n9fQjSf+ui6i4ncl?LH^W2(_;42#kz+zionFepMo2? zZcI`?nq_+HzQ3Ucs@3=}+E$_VGVZJ9o@VB>=H|2?yiV05C0T~#iReQW!f?Kom;v2R zV|Wl^Pc(jpA3sM8M{oxPq2KTmyUP{7NUhQ z(R7rIi?JiA-7x58jF+IsnaUxP5>dxw2o z?dg0I(ylY8j?Of2tN=mD<^RogSjzVHxSB1F?yCj6 zY|RRLLt?Sq^W>x>6&+gHjFW4i0U?NQm&xO>PqmPN!O4N(mGTiWutG#Kd4KU(61LZg zU5yhg6f4}h$Kh6h<>yCzRt2h* zam}7}SUaI{=bn{d-*_oxSB?5CJoiKt>{}iEuX@~6ReXM-6T&laulKaM~WtVCe%}&|dH77fa^%$&q4_-i->7OSh14j87uY%WkWpmv(C?|)dFRfz6CmWj}>`(G7y4&OwxzyVk0W(Aj zvsLseT@{RvFQITSOc`zBL#5dp`7MSuHf}=pknzIsmvnd(Kte?3N7ZDlHP3Dl!@-4n zrt?BduRSEO2B)?wHLEYgwTi<$hygA7H#MFu1<~fjO89eCpyC2i_oi~nT0W-cqm4|% za}Nu$NOa0K`EB|cQE%e=)rGfHBAxK3T{))@LD!pniF!H~fB3Kk#ZI z(E_Z;23&6TzT%?ZCwqGZN&04{YLtTB;-h(h50q95wai_H|>-lM!kNgfsiJwrVMailZgBWucc|&+0 z!NqP&FSm2a0THXeWfmdLLEShqqsK@^EU5b1)SMCrGMUTY~ZYZ z82_hwY0K^Es1GJlJYHGi@$s<|H5gP?RdoVz-C0kbopFGeguMuY1MF5jT1rZ&60X2t zc^2X%aj~a8%lF&qhomp#{7aI=rkGjAqKShuFwM1%n(g|YCCkR*v7?PHII&YEFgm~_ z395hx)%piuG+yY_*8!Vq(PumMTp!3Ns-CF{hr>?0ul`~+aPazbWSA2Ar)F~LYf!d` z!klX(E1j77LY0lrES34MYCkM514S7loGYWtKMve)j!}N9)80#)nVXBUse42#bP%`7 zfS>v#Y;%WkwJ?f36pXPh!#E`A&mStEv=wOE@hg3*`wK&hxBJ>816~GFokBx)q1a)s z{*dhExio+Uct>Zvqw6-?A-Q|-i0~6pC9RabP z|1x?@E|7V*W3)S`Fc0l{5W%&E4r)v1IZT4bmxb?K2{rms9Dk;?Y;6J6C8zGqG@>j2 zd!F@U6BgQgir*o7CTa}CDUUL+y{9DL4A734QfLB%q>lNN08u}?aIBpQyY z*$=^r@BoT#W;agmxLKubT_co|MCrjBz z5ul)fIFOKgmFHqX-_rL%B+|sgBe%s< zRoRjwkyT1Tvd@yKK~J?-O&VrNe1c z@ULYk*cgPHa4y9?ke*OJfM+kba3hwAI)1mV>EfUq!mmN$GLWV8W_MGT1WSR}N1tDoIeH^cQ$Jt^to5NRbh}$kMR>dIgyO!W2S)7cWuD&oAAWgc4QGsa#E%ShW z(z#VM30BFj@x{Tcw)<@o-23MV&+py{5?V58yJCW<4mcTlFuue~z-lA``auvU-*O?q~k{*nj4^SJQc2 zB|hiDeuv*-wZDm4BMf;3{pLXU?Ev5~Tt?&ZP$-kk5^Wda^x8o+)rkJ9^bEh^r|u35 z2ZKn$-uxCfo84|@4*-8wD>DBhHTV^X<;pB{9;`lZ4t)FOzhgM(9g0F$BQ%^6IHefs z?PdZXQ}2CMiF9tw}1Lx|1y~?$Dtp#r+jtILneyO z!A<`v|KD}3_P@L!+3Niww+DBT|u+kJOb0?;e#k|Mkv)LaxNqAG_*Dm9d?+ zOTNm_hj;ID4ir=}$e*Xwhdil;3=IIq>iVcRSRxHTV_L-C|D@e;w^E$|@cU={um76k z7->WD{r<2p1QAY#FI8&|f7P~-A)U`&9($gdpfYIr{;c=y0Ke%BmyPzMvkUzgm;MK! zIKNjpu#V7^l>1emuNe($PG<`LbfPH60n53_Vfs$J`vQ82YqMBFypo}}Oj$M?kGWm4 zxg`$WmJQba{O@H;$=&V+vYW8@48C!4#1tg+2(l;NrGNW(^N*F2O?#OL^1rGe<>D%?Xd^*%?s(~z~5g; z@181m=BNmMma;8L(6FKIEpdMpP|B~m)XYgwwWQY=EnjhHCqHNpc&g5Re3joza-5J< zZI{bct6R-0yGbR3V0QQ~q~f!;)icsPjFQV0g;#}Xg4il8`oAWSsTT70Je>IaRxqyHWDS211|ZI=aS>qt2`a;g`&(v`hE zuoso^x|Wv7((5<>Yeg?GD&@C=LOujZ$T>CNZTOP-9yZxC0w7!nHLXY*Iq&hA%}xg{ zPh{aFX9AJc?dEaO1-`0e*w>ltxL+*63|OOZk_k~UK1uq3#DB)Hva){GkONyzOiC3Kwsb$e9u3d z;5h=7_#j)5f|+YvFB0UhL9!-}+#q03$y8L-8@;Tojl3Z47K?qlTW_5d)8D;W!|#Qu z|Nd2JX0;}R9FpRweSz)l3l%AD^kIqAB?V!c|G(Ia8@*q&+3m*3n=i*2DiwJDWm%MnM(_F%NovhO6zbrUk`*m6)~4hIaJt-TkN!r5`i&#pHp| zco7)R%;6X+e2E>V;1gX=TNC$LdoKpY!7CtyN~WvWf?;t6VomfoR98^Q8d4<^eVw$! z2D!|k&7!V`Mn9#szF0qCwjR>h1qH3V_N7_TpWKx;NnRFiv@I%37Fw3KKzk=$k4W!E zFwm_ak4tpNIL>@FklcB<&&gRIY!Z}=@JV+e@;9f(4yByXyX`+s4wJ{c+#|D43T?@x ztf$`_VRR5(4SALdNO||9zUL!92@654F*c|vgAc@)B|It#`j^R_3%=J>=eCN-4p7+D zqoxFc{YushK8H10LWth8KAPkaJd_ciSb8X?(_F?!J1?hPHGK4R{wNcHfsk)s=+HJ} z#?z^8oS}M-gW>JP=~mV444M{dHP6HohW)?bZuui@iU9BJjQ%kse~D?kE0mp9k?GLu z$@_VJq`_TR_jY9_$;o_bbO8LS{+Up5IZA-~ReQ}uY#+@=PBqg_`np`$Qb+rHD`BmBzi;Z0zaFL0{{(K*csV(|Ihx$#A zEmUb4^sfA;-Frp}Y|?ZOZcKDG3^ok=S20(#yNURp(EZ7bu| zb^>`ypS_IMTCTq%h>A()SF%=Cd(O<1n0|fUk&P2}uW{g&Cq6LyT92EhTC1$HGrL`w zvx^b>)SWV4slOjWO9t|*Xy&ir9@mcQqtVr!9vm#pZZKVadA#xVGEep6()AJ0#+6LZ zwRpT!WMMnwyC#Q=%N=Z6Co|5TbrGhOv9KR7!6SX zjza}mAI(l4xj9Gj^0qcjSpz6qJ~lz!+GaF=U>apZIOK4Z|p8w7B)A>4< zqp`!U4I#K4kRz_a)U`%^c<@I0$<2!bvcac%AtkB5wEXw4xrs+jlIZkIQQQ}8OTBH@0 z?Xgna$}V)Pb41uysIqj`B3oS*aJnKm~x*qTCG>eU--YV>ql)c{ZpO+*W{uGQ615`03C0?HeTk4;KTo@VUbv$>M+sTBkNgl^@s`grM z1}0CRIk|gG6T1Zg2`&K6_}rX<&HPV^u6~fw{$AdcN?K0Q2C8a0ST*5};A;CL&~IN_ zof6-<&{S;*NqB{M9~aC1yX({9Eb2S4wMdyOz{`7^Mo_&c@U8+1@qfko_d+?xUgO!n zFbiE@=b51tr?P&#o0XjJP<}yYYnA=}oVn0$f*C~ZFLqE3J$wHMY&Gp@g^c%=PQ4K% zHE?94(2kJ-92Tfs98}8=%;*MqafqoD-xWW1cpeU&^Ke;H2ZZ~>b1=37@6F&QSsM)$ zRMq5U4cQ>&myscfA|_tz{zWV0_y+kGVw>|V59q`y00Gn$5F9KR6;;)av9JJe*V*5e z4Pt2g0DZsuYHI8qfTc~&qC;ELcHk`f{d-I~;{_t9Ywd3BW>0{O8C;`*e43FV7quZP zoCtM9Ucd#~WUwbQ_=M0#{|vMwCW^ZqAEjq?tc?G5L&i_WLKuZt=({FDLNE60@RPI) z&PY{6LZ)IstIZN?-FJ6ts*}A)BC=zsUDHM_sDD^V%I?eQ!X3&BkqVNRDvzCkw!igr zcKitbMH{4nRDDW@W@{LU;fn6P;kxhJiwKnZhzNKdW2s?h{P=Ca%BH6M?ahy071`$LBxI(dJ%xgMR!M> z=i`O2B7q)ppxO6b196FjJ>4RovQ1aDeY|?T=pACKLo0X+-TOHiKI)pi-np{&ob>6R zI20^Uj*WvuV(fhllj#)(HIz&u&%~z#$M0aS7CXYb;?x5a`{6NLXx9@>dmur%;$ed} z%T0TFw6lCB`*$8_aH7ib_bpio^wiPiHG6Iw;Whf>9eHC-gw9(oX z&`DvBu?t}7s>J>OKsWBMSGJ8)H$2b`@?SU0tc~HWsCImRE{>||0g$1PX+Dz0J)V%! zG}D3H*$*@yX$@jK8e9|zH>Pd-0eCv|(BecI&&a12g}y7zoI3`OqwxTrtQM0QQ;6E> zxb&E?XRo()+~?yrG!!FN^DhhjX5cUa_){a@?3i3<7Vs|2RJcX_!BIVyjhX&W^%wDJ z**!X zwGXv)8yj!9Za7`1hxUlz$xN$!@!BW1R`m4b}``p5lH?5 zY{V>x6@`Vgs{j)#H)Tad)yxbcko48FZ*;u9I*g}PItz!ry>_@Hdw~2Em9h^h#k7vn zRvtTHh;f|JQ+@_g4ydw|5*qJx%1g!u@i7dA2tVH0Z>@J~z}gaHyQrvOLbg~P80~>T znzeK?u2Y5ZWtntVdQx3=hl6kbRKgXKn$4378sHPKw~t+U z4~=|}o&Yr0cc^MyZORA8|6?ZOB1mX4`HP`#)~->>75%U2aUKm}p<};UCVwDS(L8vh3g{uV8=4cNRwmSR5Vzx%S`(vuC}CMwVSO z>Gq|O<;niVjvkbkm$xPs^{uFn^X_&;ATWjOOF1*y7{?mA^sXIHr_j*>@ZVYaeWRm_ zL_B7OelOcFE6>M`J~}%)zaw_PF~|z2$@agS6Wf1wQb7ce<_x?TiV^621e?yPC<`Rd zDSin^4IzZ`)8{8+i%g-@P}Jj2P|NBKSq*m%rLID#F;7=%>FP!PXv`8Pyj5oKhHNA8 z^3=Nn$8n2wxIz77FGZmkG+>}(bQCihx$Ng@{6H+gjq%ApkYDjUKFq3x0;xZ;XIH9m}Lz@z@i{n#Nv2!olC-!UT$*zHO=)6$dm4?I@thF`?NKMFL5Poj&!b4HOOyq>TwAVFTi3 zsZO`(?akP;?u*r0ZzoBO02nQ_fNaAUI`R7J&%z)YjR6Y__Z_l>6hg z=!2fz20yz$VO{qUhfAc%jg+2B_ zmx>zD=%}Hsy!)RAa$gC(l05&qLL^Y}?MkzN1C)X!fL5nU#SNQ6+sI0d?dGGF#6+kQ zM+ZHSjns}u(Lcr}AaqfX+rVCeuDM%KUC-jhQ(TSDNzZ%Lkkek9@F^nRpmh<_ts`4x zThW&WEM^zK>y8fJ2%nonLBTRxq$w}A;k6||L|ucl6(vlksp%3A<$cm0XUoUTR36(w zhV)-JDa}w>Sy`qjQU@QeT)WO555lRT{BH(zNj&+fXB{XKE6We(T3>^%re`Y3%0OLb zi+cTIO@@+_;Dlfeu{CVmm9EY1MqWCPQZ-MpQT4`4B;G05KM!VrtkJ^Z)cx+M3sb{+ z*PO^EWQt-}Hu>_+`=2=o`H&xMxM5XfyUCP1CDK49QDRnj3RKMA=8=24O9G?pTpNBpLml^+-ToOPdcEZg$@feH&w$$RnP@oDI~DRjvGmFE zbJngeo42RPRclsg}li9E{OCUiS`-L*bMj_7Q;+;T00NvZSS%jD;c2!%joPOx;Wa|Ig#| zZ&I1hWZ6!!&sTj%ne%@0ynQ?S>pG!XB@yHPWL2v}h-FUEGspT@n!)WweUF`Y$KSC& zglh>2%^Bv+L|dErgyojY17bS@CG}BNd0B;~rZ9Rm!cFRDlkpNqW^;SQ#8JO=b#!_k zTaH;qsN*G^+w%fKY0}b`)6qV#aZl5Y;61~R())|yMQ{2jgivV*&)Rt-w0>>Dn=0B!;KoO9L9Ahe{~nM3fOTL zSZB0qVlLKwk=aF3usF34x{?#xKWoQ`pIXOtwK%2l9@oQx@;vClW*B5A?LiOWZqCk) zb<|5rE!^DPLj`!WpE+*r9|1X29){_{Qzqm&JlgY&bBpO^rxq4;6F-}A)2qrhm`1_F zR(^gB+EA%Jf_WqzGHth)Y8*0O#uxkmmUGSCFy{FtB=vTM_Pr%5ef&VeU1M4fi`+9{ zO{md@)lDWGsq#Etw+kyBo|ghRnF5!_f0;Fs&OH^;f7Ic8R*cC0>6E{nHMyo1N`r^{ z$$ppU)IvX-`kvH#T*2)794Aq$n8(VBY-f>B$7YPAmd3IUBsBU@5_8OtdOsV1+OWM% zBZ-qdujAi$yCaUDb~LM%q%=RIF4wJ}iDMD=0TgOC?&k-NS0k=CF@BF} z1y0HE`E@5wBu!UK3zH2hi)WbRe2|WSx9_vwriv_e+Uv03;@s!2Z;O1bXop9`PRi}P z_c26*R~N@RiWM-FYBeRe2AlsVaI`E-N=RUF^6Z}SvdeSxfX5}g@7?uDarDb;y(;rV z-dNIlp6!3gCLp8D)j4KKbUU@tRSqseNeI7$WqeIW0+yh>Zp6eQRd*NDn3Z(|d>tLM z6$b4clmT*xR=>fS`deE3R{6L=myh&SC{?le9Y67%l#10XrfU1_oblZj*s zpq&CztYRp)mQ{f}UTDC47ru`Gj^y`X_0F{NHq%3+#Kn}8AlW1%|ACU zn~NKylChnVkRLdq`QR1Cox(WrT`ZIG0%wLn^c~czwrYBOJX7&Qa(I0aFimJ<^Rr`O zXlRGq`sa`p0r`k@6fok}4bXuNloLi0O*lMGR=c6m^Z;)v#}yeNOLDpsf0q6YZUNAe zRUi9|!c)b?rLIZqxcWPeaCP6}Fa?zcM~;c!VUpbPZ8l#LAy zFBRbZ)KNj?FyVDK-QsR?mN4Ff=G7COTUe+lbH7sMXv<@T&arRDNX}Jhpoy(t2pK(J zm-e`_Z_s+TJNe7U!Q%R0OOq$Y*X6E@6)Pp1h=fGVZWNeKs&j>%F_Z$cIVjLl?P+gq zQOw95+a54}QCvLNDGu7-O9P17+uU~FzpZc$4cGTth)KYHXiMLLC>NV9fG=Rco_>_P zx$P7ojMTM0>Z%mpGt+zOk)3KKN zRrx$yvBbjCwJd5DN8_5N@tCn0&8zufrM#*hicPAxLaI@6Fi=K>34YpR*6X|TFOO$& z?tEv+yvy$E1<3}m@I9rRK_16o$>P?Hvo%4K1QM8nC>>Q= zptmd_<%u6QX|8$pJu;r7EGDq0z-Q^rq=@n36|sN(%U!R~rlHg(#V8kWYq=9;8pAYt zv7XIH2jSF#7BPFZpll{(9k*oLMz?)WPk;=AC?C}8L)G*IOulf_NC6w6!0Xg+VoTFA z?33@KkNzZ}3n<{E6xi>x`9o zWknlA@*aGc56l%vCWZXl($#L0I)J?3iumx*3V3<|cx+G4_C{kU8#lSQ#Mmbn@td~h zwXS=4y~6&`qWHZdOTE26P1b2m$`Q48$Sz-QICV(Ja{<$qDptcSlo{vhVq6YJ>fT-G zMnB&exZCx)t^Y}xBk?yRbf;eFgP@RoT4=aSLeY=@BfutmwllkN-kJ$27VvOuq=fb+ zShIGd;B#HDH?UIpPQ9dPe2k=0gt{hhq`t&49L4~)_6^D3xAY<`)HSZjP~_y$qQb&f z;Hx|io7ZW{M>YxlVR$l_)WdO1sBhPBM8Tcp5z`VX;h~<#4(V?APMgHoEKAWG2pl?Q zt6gaU7x&*rCE8bablJWh4|RGpl=Hq+r^~w4$satl-;(eNoeXYiUWB+ zZe|(*UBD>b=~9rFwXvKXHJGjg`Zj^a=hKtA=+*aVpieM`J7^bmQpfBI*@P zgPS$80u>Pby?$2zS`l*cKQ$dnv?lB>s1K5w=Gx6X)5XED`L(tX=4x?Q!Ge-Js4>Y7 z5j{K&iwW9QxN9_;VJL4RUYo~1FfX^Kay54Hsnx>>I&WKe_;T}sB=lZnE`IHI*Y215 z`&+sGgg}6>I66AoNZh`EIH8B#lEoOR5~SfNZ(-#1*89FiuN-+h!j9O8Bar01W34FK zej@@P+v14;zNWZbvNa+HOETk}z}Ib=50-M<#OWI<)ci~v(MzF_W$4`+fnci8T=rq1m~>d^&GmJ1 zBt2S#xV@2awvTo*fW*|btz66eU;E)y&ue4GKKnqb6v+tK`QI=V8 zR5^;o?J3J7I&Tu2n=W1%uSK})GP&-CoI%^}5ig01x6A_5643Y`!5yK_386)DyM$p8 z$0Y9s;zxq#6e+()Pb4yG0*?yWfI6_B0B#_%x`~ceAF!gPSly`@yLW_9A143e8%azR zSI?~7$9?0l!>6K*@wL@_{yVd%`tVfNki~&5W7h+VhK43z3he3+HHWY8bomK2b!W0=w5oki2{ZJ-59 z!7WIQ(+Q|@BP*2lL1Hqgr5H(7JxoU{BS0KFCA1M zr%W7Ci}6E^1Bn&~BhE@7`BBJbJ3{9GGP7!t>ZVY+qtQO_`hyY17PPP*?$WL$G8*rE zAZ%wa{mPM&=F>Q# z7gcL<4|kfzL1^R2_R^;sVQA0ekV*$qRxsp@@MCiU|KBpg-n_x3R8 zayMZmPsWqE2U0ia&eG<-CN(LJ4=; zv5>yCi6Ao?#^ur^HQ7NB(XLBPrIGkWA|x98?B5oDr8j1ZrmS_A#rW}u1F4W>G>ocM za>{INF1hYWc@LJf3;{cpL5hn|U^dZ_-zPkEE-@u(T~xNI`Yl|q^i`BlPgU=3X^RHm zaBH0YyRgvcv%LE`A7g%AJR|5#qoW)Kqs_qq7jGi<-e)TxtXl#(4%g}VH-L)5EXK!l z6gW8)`rU%&54o6^TWOO^df)zOkeYmBChvSvW+$mu;0Kmke$s?ocw2Q7;25gyjRWs0 z19I||Uu2B9J*neG%-rQI6!N_y8QgIc40d>L2Xqt}~N28NQ8snh2G;R)j<3kHD) zA|N&${f=|Muj;0mnIzz2i0+$X(e#umC7#&i4AN^UJ?ByFks+$Yt%x&CZM>@sOJALU z8Zo`krf5&)qMR@88{KQJCo0Xa&96}3+u4a6PCzX~GUZ83OH12S*%?HoL!+&wZG0SC zAUpb?Gpdl-mk=mVW4s}q#!1K#lo+WIozpS4b$t%_E*1W+J0CJO-%@76Iha`{zWM8w zf!Y6<`vQN2b3G(#LN^32px8-g^Az`M=lQYBxMvez~VpaCPN+F7Ah(IHy)p0YfOb$-H!&&KFsDoc~?0xhR)afEb3D z6fV7ol)+zSLPw~oqABs=>VYcJD3gYRROEG{qN)ing1L?vpYs{ipX-lC`Tw7}Wi)@2 z#B!_L*ZQPLzsRo#o6x-8MqS3wTr?PysmUHnFyT$pRNnHRbG!jNr#Q?jV4nB}{ar%Y zuqv3w##1N;{?LN6Q5BmWN@QSFmFdQrF`UK4x=oWiiCFl!hxHiF(8|s`t#Q4gNXDRV* zZr}8>UJ&4>dTm_b?dMdF7naKy0CD2OX6|`A1Q9By80V1)#u=}@$dfQ-hEOsDCeF(X z7N!#u52U#|qPG((N?lNpj88cOGKyxgMO82YKCIxduEZ$Io)Tg8!O z=B6|WM8e|aaBP3ihmitH&PS(-$-HLnCo)Z|z9yP4n3la8rB z94H#8KXWj;Bq(BKRM?-4kbi@!IE(~in2X%2wH>{^g}WvU5_p|QI2BspZJ+k{H#9dl zH1kt}A6uh}VnP!XadGCj($D?^kJt^t0$xNhX@T-6t;^E){1gBdYzK^)fAgQQ;vO8) zTD-W}9us*S0q)c8?wI%|hBzg0dvO6@Gk!zyC(9JNu@DXeR8_~SbZAmgwH5iIkJXaB zx>R=-%3ewK!n}COxISG?oWl z3&w?}Y>4A!sXieg;oovn!QsTH%uExmL=t1@j5%G8hx$ArxZ~)P&!z3@P3!e&wcz*A zow$*7R{Vz6OD2{IR{83BR;D6A&AHPh3N0E63cM|$Z3g;)v6k)kOc>dbxG2@DV0h7t zMr8+_1qcf{&^J(eeW>53MoHk!UDAAz*jCAH11@Lr_$UzXQ7SjPja; za-V5iU*gt|TG7tHa-<214o&27bgW?TwD$XbI6WG`7UMfHZb zbiE#Pj7d?sF@&ArfyIkcK24zRs%t#ldw5!t=J_0$0^(+wlrHgfDq5vTKEQ@|!{xead-xxe*$x!eaW&(fmoQ<2iAOk<>_cL$~8_{21rE3@zzRyF%IF z)-XI}iHoYsY`kmd`*!Oq*3xn1Z$F;G`mTWCP%3XAFVr9`UObgY!Ic=gqtNjOY{jNI zNZ@}iv1iCn$C|Gi(fjH*^=_lfaxpulCBz1H0Tspv7Se5qi@WYPl9_~m+q&Y{J3649 zbzq3)_5e(q<4iXjPCUl&8e2($+3#Q36vO0cvj040#fD4C7wg2vX?rG*TW*L}m(6ZKLYG93< zO_piX`S9ppb6)f|WbM>DED(5`42QiI7wERhHqNK_=nj`!e>LPK44C``iZ~#UyM2bx zZHF3;xV;KH`7xb#%AwAks2rMPFZUW}K5m=?K}HN&gxVf^Gtzr}*V8roId4d^?NKXz za+~q@6c2;Q(6jXOJ$Y^RmA`-84Cd~_o6jnDKcti0Ap3vSEm5K3}$ZSy!&iZ)?%q5Uum-n`|UzF3gNnqcE?O* zeW^O_X`wz?cC)YVR)^l@Sjm>Uqpb4Es;iAxrf0&}Oo`0L6$4;3tKFvoWOp`rA*)lHP@CT9 zsutd65+nbdFbY1ZV(Po-q?C(}5=&13s>8jC@p@>6ZVW-7rLLtVFqfef7%S$oud1Bj z&KT!A2ZIb`4JTP+T>?+Ei%Tlw_pvv=aRywPUR?YPi=_=f%GCY+m}pHa^jn)uhp6C%xuK-SVM}P|6Z_V_Jg!_@ZPmAeB9EBf z-&N2|Bpbu{%hZ_Qbu;sJG`U0S0zJ#6a5&-FAJy>c^fyxE)9bT?`}K1Thk-2p!lT=? z3J66foJM^DP`=H>?%y@3n`a|l+wkp8yPk-j=fDL38i<9Hp+fWX^F}PeuHePk(N?;~ zC4tMUNDbcnAx=8%z^7dHp&~4J6)w9{+y{4A`oWm^t68q#O=({~SYqU?G0geKQ%=x?7H>XCiJL&{{7LXRrO=i6krnT$7l-Yob(c#ZOufSs4pZ5*YJ$7F|a z3*$Pf_K2>{BP_d9tW;_H_=koXalYPw<%OM|UR>@wPQR#ZZxHV9b#Ux!E7jYJWfc~H zVtd=BY1=LXyr!T*PL4Ax`Z5W1Qh%ykn7IAg1_z2tE7D>LwRd>aMfGe^wd_()e&5Ln zISh)8G_-AsD%a{A=PtKAI}#(nO?u-qPpckXZLHGwdP{hGcyZC$$*DR8mX?F&do`%N zHmd6w78(jxMYP^((qpcGsY5qCDB|d5ln3p7`j6}z|49Q#0eV02e@tCvR8?)T21O|; zK@boSq!EyoMw&x6lG4%*(uk5$0*CHCq;wxd0SN)=IFxiF-Ed#f@7~M${(Q@|&fa_W zyfe={^UUl&f9i`g%VgU@PPXTE#UF4tHLiU*qR+^;@vYQ$M-nR96470>Uq;Uhj+HN8jOTP0|U(QqM2zZ@q*Sv47dtrir6XSUt-g$1u!~G z5Vb$BdxXVa7(rA7FD8nj$5V|%7&cs@ClQEVoZQy0VH*j90Gf=P zd2rpK)$Ln}G_PE@)(hN!abvxk`yEknV)9W;Ju3$vGb1s;2;P#h*H^4I*jNg0eV>H4 zF+5JP_lH4{jg3;B+_y=y5b2%i{-di_)SZSMCg_Tlc?)g40OW~uo9*);ZxH?_VkFKX zW}s;I-5aKJ9Kjj%SOcLiq$w9)PF#^oz_f9d?q^=0XNVOli7lK~AJ`L%$6$X_Iq5Mg z-HApq(;^^)i5{XKe#4;3IB;b#_uTCddaNoc1(ak+NCE(ORO?cCT%Fo==e|i%y2CDB z)x%bt0~b_NK!MK;EWrmQSp^%N&uY}xR##&gk@P2gF(Sgx ztgq|0dO|Wmna&EQ=&ZN1L|LBoRo~VZJdDX7&Xeq{)J*%r|D#P7xT5P1#Lo~W1r>Y&ex+uFfL{7<99q&G; zmlhi7)Q)T>2BB2EgqbmucYt25Pp+7m_iWJ1 zyk|9MxeJ-k4G$+|VL6@33!!mcZel@>hhu?$qwgw>;s#8bO;T@scuX zwmdY&)%vw>nRcT29SwR0CdKM^W*=QHf_szlwEz-<9Lkpr#Z?Q_WIS-U@4D!{2FLv} z(AlegGE%#lsc{RL$8ll5hYP@>0!^0s?E7%ZPt+k(sIkGFu78-T!XE$iFC}zfazM2P z>S6?vL}kv4*}Hwpu?}^ZNZG@*^K>vAqF5p2h8$WWhMJh8LgMyb%HioN3lSO&Z1yv# zfF8j~-xcY5``!6J&msk8X5jihSs6FUDWKHH{BrYh2}^0>`^1@XkFmq$#MS%ho`D?j zT8ol2h;c4W^;vC5RV^FcB7>7iNyn_mUw~-yd8&Ww)1C&yqwI+ML$(?wLZ(p#aD;Vv z=jFAp#L<32cWPW}YCNs+>E&v#lvWb|ls2UB?AiN;b!XxkqL z=N{9*r?n@t*<8}Buq;Y)@CF{VH*%g%%q@=jK$nH$ioQ*jRh+)Exr%peCaF=8)1@$E z{>9fJ!B z>cfAuzhCso%0DSD=XZGe%IIh-zsHX7U=wUk%It`RU$yYqHPu(aERD_c-!cXa4WlI* z6vc+RXTIYL3GPc6lnE5utvi$bR)4Zee^a0Nu_~mV?e6#cR#sQH>&oSlW97rd#a9le zIJ8siEA&3?P?mCsO}(WlQ8gCllrLYNzsq?wNb1AnJ8O~UKjKyq@bI|vHwdX_Jzch& zw!gU?=5+*>o7b>H4^OB8Demp9n8;LJr-4qDd!T8D7SyUPP2$hN?Yi^M4Ha)|XO?yS z^87r!7Cjbxig1-)nX;H*a#OvNag$!=b5Mp7*CV1Do?qH@(WC)4oI9tll= zL9ZM~0?0@k>p@0!gwpe&=YgsmlZbFHIsS@?GH_1CQ}v)Sm*?dT^^Hx9P2dyIpE4%9 z({PPGAhz6nFj`{gdj_koVApNb@@Q$~K%^;mx!3Nu<2V$J`q=*Um#+qRH?)?;A4}<# zek~qFXFO7N8?=Y7k|pJ>zEC@8kRWoU*T2D(8+k|vPszgt#o_{|-394H4Sh4((|^tH z=lCiN8#My9=Y`oo_9P;PaKmisRlcIT%T>d+6y+JG`Npm zsm5|?DPnt^`(>GA#bq^RTkOAR@l@O%t#4@#`sMw&0<)xeNfIpy6=|^i`upqisayuV zu~?SKVRXjP`_Zzk$)krJz5BRRot;vHD7rT2S7z8v4kKz*S+}`gMQ?KYUvDhhsod#u z;;U5uI9uF!YUdHF&D*Op9=NSfjj!*uh>_nEOFL^i-}zDheGW^c@2$&aK*o-7YHBMPAfc6huU{7=Aa=UtbWhmz4CG9y|V6PZc-^ ze7d~;aTH~$o3d@=;VO?s{UCvZQ<6nVN5LP~GxWv?xquuwr7R~^4>fX(*Xt;~m;OAy z@^;r{61&!3C8svQ1-nNr@r-!R(+9_wa$`Ie+Mn`>HS5A8G(nvV8a)$J+|bT;Lwoi3 zmr-*>b&vf$P4}4^6?cScFQ42KJ~zwjh^@JPbr)~C!Q0b3bHM&IGborI3Mt9SQ&}RT zskjgKc)Ve>xj+^EmZv$h@ButC`=;HC^geVMH)X7~=w2!zXKL{FhOTqKR9ImB8nk$5 zf4F|PZ`I`#-SEQq=ZK3rA}y}F{8Yy!eG?k0uI3o}%UW_0KH5zb0ThG^ z8`MLs5JgI`S^t5)j07t1=e&*dwX@(fUobk|MWndOyJjlAGWhADkznAmlW5e%rDw$d zq*pk!ca~iw96W_`shGT3H)~=z`@5k{M?*P)opZ9>e z4xLB+4jIjj!O`Sh6ah$di+vvEaF!6u8_h2N3ZIx}1+Fqp=SeEONyvK0b1lZn4;j>& zo&45iYw5HVniexNeo9>jIG@FbBK4s@X^&zQ3|d@mPCu6AM_N~N6=(3sl-Zmjaw6adLJH15vvw+u8>*J|TGzGCd`>OSujmcyLCHoQn^9bGS`jfUwrs;Ifv@Y6fa8Q zA9DsV`U9B`Sd2*CI7xjjnys-Yi*(te@Tm( zxmg=ixV*gj4%60vmOHCM>S&ai4_lh$)830gITE~7rNFr-aZK`xIzB&VCzFapsv-K@ zn3U8<>4vtt|E~td!vZO)<#_G*Ed3MSfYx*u{K@`s!k@y$O@y8vT^8u!sWC#U0=>a5 z<-1ra_j2~sAzPJ|(`(L7w9nv6W#v~Zi)p34u|4iK_b0I7_iED{Yio)Ax?e%u@83>< zNhv8|UN%agYsFe?`s9cxNyS{tEV)0Z%}JG2LLmHYQGMu<;*Ep0EHiOrW3#HR&iI}9*1rNB^lDfkZd z^d9yH#O^kB{bKr+b<4Y@r8Hj_{rU{7Z50x%E5`_iL{0G`!(0-*F+D>m3xs*PpzCkZ zN(*cji?hC$-KVIh7s4KP_hG`TXtu(~tshX2x2KCD_Wn6*ChQD1g(QkHi`63ToE5RD zB4}}#!}YKlZ~r(~eJI+=siWsi_v*I`>7uaEULMqVdNj(b@>w~Vzf=7x28dJw+y;m= zX#fwVyEeO)P)~#2I$W0-rQ<3`vms#g22*DP{%W6%Aj^4yB#^>(mudWkB^==+wi>YL zI$R=-ZF=Z1a{sg_1^@Gy{Y2(FU9xPZQJao*Sjt?4eg!Ra5h^raXBw za4t!va?4Lwb5ik@R$VRUmDyWcTZ`A`yqvK0yx=0%_=A+)Jy=@H8}HNHG;b+`3!(UY zlb^%n2FcU7PevKv8!YxSmkq9MsL*H=x+za<246-6*R&gXr+99u);Tm7*fPqn(F}2j zizmuSu8ZfWFjP+vyoNr2hwN6xb;(#(9ZY{z?vvn$2^eC-$pqdhojrZ{4<}>gD_owO zuCy>8?9Zp=HtRY`S7aCI&%1H&8JWOM(t*g`0 zG$%%}vbCkm>fiA)WAVtkUlF`o%KkcUn}LqX1*s%Qki@DcPegL-{)8G!&|F?VM@dPK z8|U&E@>Ee3jDV|SGx@jTTDx~FZrM&~yO$lKsbY72bfPh&rc(3SvuB>i+gzIBS}@u( zNV+-u67$Nov9;#&Jlc?t4_0_We#Wye>^?J17FT738w{&M{^f=0u&|4UvK@5T$;JL` z64Qnmst@1k4*5JI@SynweC`Y-XK|M-@P75ReLQSsCS8W>ysXW;WN4fMZJ0zmzQ_L z8M}$9?dXfIt5=20QFdGPAgOmL8)M&#Fh%59x^_a zahH-Zug7Pg{H=SHEILwBkf&09Is2pXb++N}b6njT0|my*zD!BHJ?FQU1%@gSSbAVvay*t-7sD-2m@%10YbvfD+nfH6wJ~g|$OZ^i3AM1S$MM5fW zZ26l`cXf=4(?&xo$a11o%Ej57F>*dtPAm1IZh2+?*EK-`CwXSwFHUZ_8YJZxfUKz( zKLG9#EBl^!upW&#QIQ2vFmbIaEEQX6`xQ<8_?dy$*a)+xRZ!2f@sWG$gEIC*Lvfxe zfFWZa_jMo3%DyO2BbI*fxU40$hnU~PO8{LVoZ)g*SdV1F1teeaNl+CUC`1N2=|WFF z8!t_O$T+ZYI|k;XOG;|{4zNyc(^5er=W7b%8X$U`kN<#*Q^-d1*Abp#07p>2q^{#R z&EjmL4V*iA8wR$gz_NAV^u*$Y?eJ(k{v>sl>=MdUgNh^QWH6aw&$G~V!8L$h3Nr3~ z6oJQ-={4@tz?IW@xJW>NfQlQVAQA=zy)FKfn5al@i3ht(tCTMX`$bQ#;<2ZscbT!4 z=`#yw+Vf@=xMol3UR1!yXdb|CYBdq(6u!d+(B8>4VmvHRLyskiS{v4KTRl#5s-(Fi zIIzP6!)$K`ijW*~1D(uPDe<)fn|)RB;ei1Lb)=Ml-2m?}vKU!p=`EfT+Onw54B^3F*{^s&e&xR>)TDCVeyxN1l zs6Jm9(=lYUwJ2Dt#iCL-lslVZF>P{zBXDlGat8Ebn)WV;*FFX2TWf|u%W7-gF8iNb zjoY@_CQx7qVYg0n#I`YQo0mySO6G(*Q|n?m;43+qW&%-E#v&t4)n~S)yMY6M}za|AGCTG>-daDqsS5eI7&jLc5m)m@+h*BCbVD-CtCpC-CymF4 zhxglAdq$+!_ugUpejEWpBsDa8*r!1$Nug*)q_lVEVPVC+?mhIyTbs$PPc#_q&`QTQ z5e4xH(HVhI%eQ*Rm?0mO-b+DN$iO zOi)9%e>00+zzpDCE~I>d=hfu69w5WY69(0Zun3?Y5yl5&F2`&~mfqgwt}221pvO^X zL5FU0ye;!+#S~HF{dJBHvOY&@D10Lr5wV#U$cd07034P=imq$XFG35JgJ>hlBPfI% z$(*nk9&J*xkdyqImzhP>u>B6iY*3p9Nm18Zax?`LosM1IP36e~*sZ*6vAU)4aRpl; z^g+nTl1Rihb&DnKvr(TxH8&NJ6ihH2J1!rqfiJ#eFBh#RklyuRTsrwhe`iTDIaR6D>y|c+S6O#BZpibs0Cg{UWad4cV zUNb_o#R8%gX+FG>pobccPDm-#{@ygl;vzC(P2TDKK*aa}kQvY~JJ`b@65Bjwd#Y|N zL)xf^-TLSg1C-~)Oli!8E@ptQo9$P?RLSVhA@=(+`pp%MACGR15)#!0s_=W_hb7@)vAi<&rT?tg2n*-ws7V_$MEsCU{x$)QQS=vB%J|Km{w(?XafJV~7xON{` z*QfSL&H1PIBg@VzG!|rsUT1}68`yl{z%=rI&WvQMu6;E1pLZe^KLsiFJUlICRN)8a zr#SzGo9l_6LE76wG(Kx6#xl9l)xOdz`lvTO7wz3L_ugn`Ts}g~-ck;>fV1HZW)Up= zv$QuFzCWO^o^GU5x6Vf!iImOwU{_Na^f&GeH$3&FCwBRb(<;N9Q%%BO#wnB}jlc)V zn0h+W>lKT{2Q>Qj5W?W?m~B~+uICk2(5IGJ=OY_|eCMuD9YhLao#UK%#O!OB8hXiS zf({2+a)&HnD$p;3{~HS2MY`O_s?U-sLVt`L|EM`$#6(<9S@wX9Ux57#ywSljz9$(x z4RiTmnX*b;(x)4eG>osQweo zD}0yg%~40}Um4DjNWoVe@7m?6=ayiYE4F)bL+hPOcG_P}2i&V(z`w)A;li7avn{CH z=sDhhqrpI8`r6r9w)AiSaFePm_beh}s~!&E5vmzjTr6YNFDe_Ws=9y)sQ)r+;n&KD*l}n4c-;N#^=R8mOgoTdn}3?v!)j|BKBMyH+tie z-Feo&2((o7{Y;=Je9wxQ(*mXkI2RiF*QLH@u|pK=j|E z(H)X3-m8(eFGOgv=b-_;B_EfhxLe4qW~pJoutju1iMq-*0p&x{vj(#3^*Y_c1lCHs zz{-?l1Tk=a@c6#jPh9I2>z(0p#uI_i?qol3PknYC?m&T1X;3eG4m}55d-~Bg80M62 zY`vo`WdtXD1d&B0ESoF0u!+7OrYfuvGys8X8r&5L>RAI-r6u<03TA9+^UQfJU5H_2I&#A_wBfD@a?-G zz_Sr}o9Mm&nM8xp_>O{e>`y4@z@N&q%6ilAAm`4pzp^dZAw6=s(Q_fGQB_gaDQ{%i zQcY%;yHint8@kS$&FvEIiHtou+$b8Uy)yq|O7* zBR}~c;=Q?K=D$JaO#p~5r3vTVj=9`M{r7%pCOI{&{h?lj50ZzI8M^egnMt=~tdudx z^Z9~qLToEM6W1GY>Izfo+DryHD%E7uD&!-HD&)x*3&vAv8$-9LVo;_vA0p=hKHwIa@SkN}5Qf?c+isO>pm)!GH`hPW_nmivIfm#( zGnxWY{`kdc`*_QGd^RUl9yOOKXcj%H&>PzlDsCfPdK~{}WXfDB|0>JoD1HxLoWNED zmh

>GnC3_8UZ@GL}>^C;JKLVg)_fub)v5#as+fj@wMk_fG8X$iVA8sEPzB1^ZOP=P= zeOj>55F=ANOTUK|_m~LJo9lQYed_!?-~39WkhIUFQXRaYzMsLGpe-hn_ch)|is4tF zrj%5W+AF!+j-f^kF6dRqa*3>WnZ_?pLxgZzPhF5wasZKbG6Rf6L**f5;1xrJMPH5L z`ix=;$Oll_4^SUrtUIwObqU7`S4M)4aIWYv8G=bR|65`L5Ax|Z?&3wqJ1lIbyl6Y8 zr~8Wi7dGtYA@2%IcM{TjZvtDuAB2o(<>3zf9Rqb@FR{OOLN20C>>oqDc?N;wwBBp| zapRuNZ6x9%Yv*1wPn3X+HQ>G#^lReO6Z9Wv=_T>9`kPnpX`i+<^oxQ^l7%K6^&dMS~>u z%A4iBl>Ej?ostZ$VD_rOXBbN=^ZPj;u4<>xsQDZwNl?%^A zZK*74&-++xMDpiQXFFMLy#owdpgE&$mwt*3PY~lR`v|=t^T+HvlixeTJI+a+qKp0X zv_SPEvho-sm{A!dt!*@bR&&9exTMRlwm?3Qu z{IiCY>0c%kt2PM|`5*(YJEvV0vHeR%I1jb>W~DG`KtcEOws!jZ;kzqZU;LNBfN$#>IZiHU3X5)xJUZh`Bp*BS@@|rvI#F2a6jg@WG#k%{Dh>3niI-zevG6RX2>4xnc2s^B33Q7LF}QK8G+XDR}FOi>za zRZ=1Y+OVj5f?fw)0wYh=y`~0jii0(bA&BdY_rcL&pb4Ej6QspThJtXJZvO_M%E)1% zewc-?#F!_wMz8$mynZA>g*N8z0eEu{^F%7HdVLs1kxWrjQ*&@A_*+)13*RL>s-*|& z|AL3#^K#y<)aT;;g*cuk=Q39Y=qY?Dk-jRrL7HhNM~Os9@bsfZinF?0ph99IRDB3) zS*zG);a24vthx8wP5eNV$`B=1Z2(}IB=&-2t`hb7!dE*hw2cXaVD3Wg7J9zJEg)@V z%6FA}+;zPf-;~|so!cGHG)>&h5`Xb@Qs&vt_0;7KC~ZO#;p_m+8`exvRcJ7rG>Xwn zNf;#lR;6nJX3%@S@a%QA1&)p<&wG~3axA9AGBFC{ve7XjD>@0@jA83D&yq%8-${}a z3`5~s5>+ayf6=nA)3tuEH1s>E~eCK&&a!Q#CvBOm(Nu%G#N1l4hnEl6y@$vBm7etopm1~u|KEz86 z(dX;ZKwO^h$#}Nnz(4EB$xMfVeT3i-nm{$P%+_lUMnne^PBlX)>mXTzK8eYxWG(LB zy;)`6DSWaUn-_PM>6iFz_gluQsJHlm-`ti}cwY;22jtVfzoxt+h>hWTN;tUR8E=q+khk~=ksNt>E- zQ)PkDWH3)l%7tudIMZQM2d_2_E=L8<-7!t`vr12$_Fn3?b8|^dGoW3bjxb*u)f%n> zfL7l^OP3_EkDz0gJ>}WIK=5?m8#EY^?N7O87mLW3ipYCwy#;5F4yVq1WtM7Uf>(K& zw_WIJOQKtTSrPs$3I;R}8paVv|BLI=rZes7h($?UordtsDU;ePezqvwvXmv=kI*ph zK_GF1ytvnsB2nj>^-#RA{v}WC`d;&OW*B&-r{qfPQ&cQlclAxZwK9Jjx@+9e zNQeS-g3`GX+b0l}mX5e|>;yD=o2L5M)5-A(3m@)o%zB%U>{(Fa z7w*-H{7nKGj89a!0SN-##8^UrKIqN$)_a45>l)UME}qrP`x^Tc0=m{Sgi8%vJ?6~n zRg9~PlwnCUJ3q>2r9MsLYLxO^guux%t}1(qa!0qvR4TD%ro5OK69d3S;CY+ioR~!2 zKHE1`R^>maf`sx)u>Pm_Xs0XMHgSnUVcnuVQi{8G^ne1%d6TkQg^l8V4N*9cJ+0(S zaObg~O2W-}3kIONOSCN+PvN)Mn-R3q<*?e4J1vbY*WB2sZ8zd@iX%{WGG0i+BDG}6 zpw1au>&?zyP8bX;Ri!_#x1qc>_n)~rfv;FUl znER_?m3H59N+XlbUK%wYu6UEk)JCMYNISDWPT)iy@;2jSPN7~g8VkZ>JpdZ4cEI82Elu7e|y z!cVh6?=?D|JEV6uTK1lbh|E^T2n$F%JcXlbd)>3l(<*m6dqZto6B6*n?3YKQS;g%C zDrk8#Ot>egcJxR2=Cp*fdbQ`H%Ait-*Ah!Wra6qHHxB)UZ(I_c z@F6*^Pt8Hojoz492^+^|dfoC};d>uTSS)}5mQ!_+3^GDX0v0wA!IX9EHS$H?EF8uk zxG0Dx8prm?O0u)RU%WUQZdrDg?Flbsf#l~l?1;-*fY=O}o{vpnGScYpOE65L>A_hR zBp!4pTB^|*lDQRoIKUnwT%##{_9MreiB8v9LxMJEf@;p|(}(8gz28aUWT&cyd6_?Y zTrQ8!5B*BW-yPXqEj^iM$07XOQ?_<%6Dm9CjL0dyhOAKlQ#;`+u{WrF_)y*aezxwU zNWLAWUIZlK@&R9ojX$hMy|{Th#qUm=bl+#l(8bHtnxw_aX$qmNgvmFPx137NOKj06 zx;gr$_XkZWvtPF_kt+K!?*19kkpOD#4d0p>T?RW@Hwt5wbK3oU_v1=CJxJ}Umr%O0 z@zbBEk_EMYS9uV{ZwNNZm)z}ATua~&gA~E zO~$_OCvxt3L=&-@49|4{sa)CJj|_0$me-{ck*qomHphhZK+o%R(>;>i$^?OiVnwA> zdiAE+rBR$Jo`(ggk&LZ|aQ#*iu)TnWOQ`L;xXeRgBSjzdu}wX{2?xuluhlb1rPst@iEC_A>8ie!UXRTKI9b1$K}i{pu!MM{5nDCP1ToHT z@=`dxzo@1AH6t|CXI}DBN3pi*FqkLpnVsaWcuRaDUBk6I*tgVH)3%fmXb8)ggMn}QJ9gG(z zZl$X1u5~Wje@oog+!34eZa~lbv~eV{SU{2vtCg2^kv5BCqPXFe%%jVz&ya?bk|arS z(B}L+ElQJee#>7dF*|76KI^KrEY{qDxNMw#T|K3eq^v=9@0A|d<$v>MwsxSUs939e*hS#*Y&qs> zC_ZyEt?k!tTSob4ADxvB@q|A#%tx7n)_af#Nx&+t68tiJ;R;dMP59PCagDRTz$k04 z;gTqlZYaL8`Y0op@Pyn>kAzN{@NNU=`7)HVMp8U}|MYrjfildyn=nV&st_EJ7De~u z%aD(g*6gu7I~qDxP*5LKm6|(y=kI>0pSZBb{i1YRux30UBO?tAS~6N{`=!zJ;-#@~ zlP{FAQF`-&fAiX8kMl%nK7rk4Nt`FXOS?Zel6G`(J*rb zWH)KRzA;ZPKN<+Ey|QLQum*idF`pfdS)exO-RWNG6^teCXn0JzbWx~>=ya#7rTeT` zl%qiQP`QJX`(_XtsF=fSaHKJidsizO zV`udfl+z(CyRK^8v!p}8-cI>m>%TZPEk7aLff?>5B^!(5-DjKoraN| zuufF>aE5v}_@CK=qLkU8L(hgQFs-_M6Qrh}FS^Ecnf%1bu74rjd}15) zdN*##tv_$rw*y|{(RFJIXt;{@%OvIjeyLta**3C6-w4a5jb*Jq*ey1!W!V}guZZ+p z%aT#uv?N+~FmAhN(sW-8wT3AR40Ke`K_j9+B}7*xFsSA*0akVamTp=}k-!Hb?&~+H zgoicB%gISYXJ+(aDta|U*A>%>0bm+rF}mzOk68c7U$`Qj->ty_>)Y7#9(84g|7iG* z7V%4KU(+Xx|!i%$kS5IZo0V%8TqNl zeJlG}zRm*4T$A*0l-LJr&f0}wX_qu~y`uTVZpCqZ(D~K{{4j1cJr5_B9&3Q4`K;Ks zk&p;E7h_0;5`V{PEo}l~7_aCjt#w5$kRoVZh^nC1Vq*mcN7YUjVTw7S%!rAi3S&rG z%F@&-MRRHoF!?10J@Ih$)cRxwBctms;CSW!e6Y}|wS_Wj{XLwxWIoJ^N1P~hcOc?w zI>4wU%XZ%yB4+ zgw0CT;*(O6eBII@F7JmUqS-vv_2s&lDBR3ytEv(x^qbxdTqs3Da)#B;~r$ zyyPRo2S!W8IjcRYcjI1t6}_b*{DO=28(VHx77b`6Gl&jIg2{0a@%RH>=KHZvzI+?B z^(*{hpiPK(q|-1PZ%Mcw`qucUF#6H-ptNSkSvFV}6Tz%glfd*UO2O&LlP7YyD$D8+ zb%UZDeJ{p}bi|8+Ve0r>|CxJb=kYm&wKrA zMOpq>UAWJCUaD}8F(&fbt<{iuahR1chA_xH)9ct_$QiQO|L*5?b-DtEgW9VhHADv5 z5v8R%7zF>llOSiu*BM1@Ih1utGhJKHhjpH3MMNmnqu|ttv_vs2xyaVqsAlgaM3Xu> zfySVnNsiNNUU9Q_^!(U9&&>q6VW< z)M@BRXm%X^F%AYPlmxCssmdjXMiW%Hv%Ae&%FEec^Q;y}B?)TXgMpagTkV=<(IyS` zuUSqpFrl}gl#F7w!eL=VJY;sr0L=Z}v@MD< zH<)zkD|=3xoJI6UB7J&H*d1@P36f}Sw5I?PPQpp}I2P{?#mtBEH=U4oZEJsdU6DiQ+draFC zXNJz((ad=8+7Zhk`f8IYG(H{JhWWar_*k$!ce1rqgJ(64OzL&pD~QWh>Mf&}!C-W5 z+nnTwCY9n{7Wq$Ecpm?!g9mc7<)Gh6+aD-J=hthp{YDwxX_`sf zf%QMwElSCS$Vov?l1M$Bi`Z-8y) zGx5^6146sbndK7VZb5-HTjQ?+h7~hxNYuMN+0oLphz17ytv1woB$}9$oY<<($QSHz zu^gxhN405CS!$h$bntAN^xfsUV#>?Q!BOrUp$hXEa$M+|bjcE3u-KjC%BIrhko?Xh zGkn%X*X!m|G4h`lAUvEjy!NTKra{Y;3uD#Sw%68{qcH1j)LE1TZ$h(TRnIH#rt-f) z=4r*Sx5#u`;EQid5o{7~aTn|ql^%@Yej}pGlHH6RR=Y)Y@FaPfc%25f2`;Ws8q@B| zyr{A+twxUDbxG24a&o%QuXsEvR&r`=tU1mDlr2(E1>ip3j$XO~oP0c4$ke8(&r!$S zH~D~y;lau_>y@)prS5If?T3oaE(EeL&y zCt+U_-SAvjPpE{}G-smd!q%OjD0-r{OY}z@Zx07Q|Aw9F+I;(`n-Q}L9R)MQrq268 z`ovxZ2c|=6e&fzkt+6%OyNjEhT+Y8MrWUEdZ6H zJ#EO|j6mR|_mtv4B2nZwW*bmuXB2maIw5T4so+%{gow6r^&tvM?oX(h+1X-+FLfnv z51?O?8UCgA>z7hd%nflumotzi(~_azn})E5Bli~Gm9BDo(3Fhs@)#q# zvaLCL*xD+T25xsrT~28MRJ2Pq>H0bgXU~0i&z9vF{O9}pc}kZVKuGcX?h65c_qO@e z4yfm3AfPY)K@f;>n!$H_b+O$cQzXl;dd+P%u*kf8wj*SP#U@39*r}Vs2}p?shoJ^+ zxg($wk$myP&_)S2v=_eX5(h^Fjir0=Ri~(7#BQ}4^aZ~b#wZ(Q-Rh0@aC-mkU!r`= z=;}zUMql+s#j0qDz|JqXzZnE-5K8y)LBcaJn;9$t)s2fVkNOkU!e8U#3Az~5#{5E` zWqs_Oc5OmtQXKsCyS{2p{6lh2=Lr|@yyJjeIMHlJRU!PaaXIr9`CT3`Kj{PYCqOp2 zjz+47Nuux$Eh%ON5vMqX{3VswPq>l6C_NaI>-e4?UdAIx94pizpyw5YKkJX_W%xG$ ziNwm|rROgp-v6N`L3)bRQ+pXdPNUkKWL@J-R3Jm#v-t=QZ#R3YY@*hrUQCCwSRJCv z54x$Q+uj2Q)HE?AmS*{)jj<6A>pw9NH}fu_G`~0;S5y2% z{N{!D6I}(z^!w|LlzBVI1rOq`I^Gc3uSC<_3J!)buOwBc+Q%a>$rb%}G zIX4Glg2~qyVrFWc5FyGhMuy7tVG@j>mg;*!ca>v2oT&ahYI{TSHzN3v>idXd7`~0h zoC{agMtLetBXm4mJwe%6zmvBW`j$sN9D~?Aj=0J84x{HC1)KYgZ0zh*>cb8%$^dCC zKvVNzD8N8{hLshNgZBn%ZzC(x?8v>Cir1~|<0DuDZ!AW2!7K(&kA5_g&d&_ADf7TL#yh ziSg~PmaT>}U&J%c_A@_z&+6b$?w(HN3?B2p<3uxw80(}Fo~q>*7bUUz^VZ>qr;|Yg zi$0-SQ#|5;XHQ2&t7$e+^c{o~T3EbYr3S{-5FG&*dIQYda-`;QA*Lcm%~hI|ieF(? z&~7t?vLl5myTUKk2_F=uoTI*f;oxfwXeu}^y|1oYX!iOpxnKx4G_KiNlRkv{6!g@Z z^|n4Im&v#5p+Um$NxcRhd+|bPaGSbykfeaW<-+4td7dOL8_n9!id&l`do$5OAzd^? zUQfI@{$B{wW@94Cl31rF{!8;OS(+4MGwp%pg$(g?$h1FXZgrWqH$sF5iklpWglILq zi*N>I!|zqBK%K&r%zD=V4#exGD<nS+K6hbnJNlZmGrCG_# z{&o*t_M(z#&x-R}Ya2SWyqmUFsNjq&I40;E28o{;Q-wFI^*6F|)pCfA9;wpyDf z?@+6ytDinPa+*EiQBA%E-tKaGP=vW{`BZC-q%ANV(?N+(PDpQFB9Ex*1lX=#*)J;r1H$=aFg zkEI)FRh$~k79N~X%AbDswM@f*b&+LfluQ1@fI5=~YHqg?!+ez-X`;_~TLTFmHdcB_ zIsweKYu|vPiGZ)=R#x=wIz$iaRqXAEc(78rXm__*{YB(a*IE zrc^&;_}zA_C+lQN@0%T6Sq~M`?w(zIYa$$)a&CjC_1GzP+AT-nfk92z!D0)_#?bxy zrDF~X;-A8*OD)0Ahab+1hRu?tCsul$aNCsYW^HCQ`8FqL32;00@9F3@U0heXt*|*R zucVHr9~WeAly38#(I455f8QPm3*=yzk>%if?r1WkZ^|8k$J(@8x{3CgvXfmyi zOcWOGUACvx3e+W7R^_jmj*Re3?jbJ}bJPS@nb??EnQ=Z*ar#q0DWTz3*-+THeJ;57 z1EF_0y5qg!GrL~6y@Se}F_T}I+-p=RdAPJM(4w25dTm<$v!i4+Q`up-LJS}ntW}*0%^jlKAk(V<&*R3B6sI!<+ zd46-}no7`6*_ju_KI*`LVzhr_Sf^mLv8ikUUFB>rIrd$HKh>t3!n}xzqKD^5N_Ez}R!&uV7q;t8$`h&v%W2ikjAbw4bo4`)pG7?yj|Y-AR5G+UfDR9StT zT81x%M-F{o9V2iOqoOif%sx@@Xs`1l*T!!MklH;+lr!`8)-%{W_u#S@%%<<)&gI8; zSmdV3rjjy|fS8(Glsv+?m-jbUz90}fRu}p~n2*sh`-bGf0qynPR*!X;rFQ;LQPFwy% zm{c-F7rS&{d}=wb+<~9*9@%n)bW$O)0mwhjq)R)p(E zF0FnTGIvVaC51m$6xc;kmC5H1}~7dR3-smTKuVE##WPBE6O9y5V781E|_h1mC3GeXLS=dYgUV8NS@d%Jm9%;D$jE94i)mn#}u`UAZw zugyk0*3cEdvOQ!%uNgKKK28Wx!HMJaTKf;5`OylDlX@XxCSLsX9-5f3G-*5vUA5Eg z!yQ-`cB+hgVQi2bE$M6a`g5gYvvV!_%O3ODFwcOn#-L47ub~$cDP&LdRjTtgl6;Q^_SaSkSapG&z`_&rfdn#wt0w z#&A+dkaq6*kIi-3@7lS+)_cj-U*ut_z3ML`imgs8zyB*Sh}GFHFb^Q{Jo&%mzdu*~ zMnEZ-aEhb5P!hp4zH8-hnXB%zuqA6KF>rr2c(tqFJ!G}-RO=jBu7->FXQHWlM5R|V z=l8t;NYacIv{bsn!82AJd|bc*8i4h;|Aj=S8=@9-tcMiCwR(Qh&xOhtYeVm|WOoez zHTWH;K)ajv+ALGF{Flug+dBtVP&w4u=hmu&=1w%8 zHO{0&jML5hYacLgoZ*dR7j2J(Vb;NW>EIJIZR-w>Ac<*vf}htjGl!Gc%TuR>c+E#e z=T^{aZW_(Auq#SQ;CO5?bX~S1#6i2`>=ho(RStLhZtkBP5wJPaPo_a&%x&)eJ>KDO zVT1IO3RTB1(_%+Ea+ZK{Zh5vgxqRNd-ab3D{N*gwiks@SX!#BIS>*jLFs4COsP#0mY+gBUB3Zjc@Q{mhcoj2|XWasPY; z$q${AX={6%9lDa{nFjkBVwy%vy+fB6y78Jwl{j_3vCL;h;~WA$ojC1H?{f9$qN1yc zK|au-Bw8LALiVsD@gM>&s zP5B?P-ZCu8E@}hCRzd|SX@~BV4yB|7ff;J(6c`!?BvqtKVhAaT85mN!K|s25=nhGx z8_pxV-}jw!ow@kKkD2G$d#}Cjd);fTz3u8wlcA@;ZE?fLo$Hzt6^wQ%TaBgOb$s|l z!Do2VwmWXQ2nnBvZZ>_rmIJBb5yka8f7UW4iUDWvv3&Awa{rOTjZf{1U{|M-!t`6y!*;dPYPM150~m$ zo{UTAe8H#xxklXR|SFM zCiAC%SOOK4xBZnmCj1Kxxkw}07I&H-4pxd`U%Ld9Ml9iC!)l?kj}Nx&+vcROmH4;# zojlM_=)r@mt+z*sN-Z@jW-L;Vn0;~$ko(h`5=RE!YteW7$)0Hqh#C1A8{ICkvsv9e zIkbth_PK5QlhH?ssJBy4-ehX92NrP+AHVVbfQ?2iLzF|uDSpzq;2}bLJ66XAe-_B? zCi?7NaoZ?F{0gr$+S;G+mH4f-l$kIVylp|~CseYTVra6dh6ayC;qfGNM?aw|pNt8V zgXWqJ&5`5Fm`2CFOeCwn9)=;D`ws=EEw^Q5Y^>a;>AtxprlC|5Q^sA`U)}+U=M7hJ9*D_Z18T2aK=~cHtibyQ@JFYqE(iu2$^lKzm}-?xwpvc z(+8NKJSLu6=x&CH>zUxX*th$681d{g_ngp|4)WjA-jfq+FUyBj)~xBx|Jv9us~{4_ zEBbxEdX?DiwH4gi3#NOfS~to~38y6-G|=I2-b}d>!+!WWIOE9Lho;I#^WHY<+{Z?! ztsbdl*wuKR@u;tD1=EoWfLu(@7uEyD+?t{{wNNJcALk#yQ5Z#o$R&89TE_UWE%2&= z?TZJbXI^YOq3L&pulj>2v?u=(;ocv=mYcCCa7ebOr-cszM-x4~k+tP-?~8WB)G8qb zP7GY8WxQ6;lMgB|2Ske`S9M(tZQxC7b)I6A=6$-g2eV{h4ERKz`Zbd=;nHdS2W`0j z#{ZqXxq%tD#LM2@PXR&av2r1FLZQCaD0qDM;EA`Y&-i4P{yCv~k)2G1zhx2gBVGy? zOJ6&iF!$s@+rGXE)*!?{-|j|Z<)&z#1Ml?Tn{)s_cdNT#70mvF%hid=tZ&*p4nsC3 zVq)YVSBZY7^}GBp_0)Xw2eaN=vpy)VGr-yY-d=;iN^0IR&piJ{Xu*&DK~^>XV(LKW zz?-dj3%(Y@zcX2@-tou82bU)SKMsCFM!JOoyvX0c__Tw8i)iApleFp_qn9q|pk(oX z3zH3?A{UdIBE(1MX9gbG4HUuCHVU#HydszIf|1B@%gf&RVFUMCxJ}kB++U$8p=agV z7=AJwJ&AhC@HFUq%Y8%C{t5XtL#9==1UFrT0uT$=cP_XaLTuX6Ykk$SE0$ z^Jn^GFyQmU^%?#Ek^EzFZ%$VVkopTyBHU#IBFMq2bRM3@v(6+#mGu z#-Ds!A1dKD{n|fKwXPlMH)t(v!6+B5vDRJ8`tbcCzXaB?2C1C(;6;taY)bSv4Z};b zFa@=xz2c)gr%#4-gMb5<(?uTd5UI-96kD8(JA_VD!v^VYRsd_%-T8-7kQb{*C{t%l z9s2`c@iet{(L`z8daneu^U(R`CHLXt9^KZrk@fl4OvJd-DS~^O&n!~#?t?a`pJi5a z$VK+$K8C|a;#s-Rs$Lcb-iCreCCk!_I4-^Q2tnJBie1RhF+B)NT>On+3`MkBN`?KKc zVQ*Dk7J-EdeQ)(NRmIsu5WCp8Ph&ij<$l#5kvzYR`k<{T&vSFN?(i}N@9`P->Fa64 zdR1KqcFs#g70rfsFuwuDd!dVS?@r`0 z@@1c7)5fDpJ*tYX<~>RNZul=H_Lk>EwxrMK*Jn_f-29hX+bCo%dXsegnqz;=Fjo4< zQ12VU<2UU_YpT5ux?Jn?3X`Jy);J$5T~S`$xA9!`Ico*B3ApCiBhJU}#JX#XBeTML zIsZ`4J+^|`vII8Jj*VYd^L3?!vTacFOSlEp+K#MrPj4d+_Rrs9JmexaI+`0~eV9 zfS*O4!9U)$Kk$7~j@>T+R+v$_cH}z7R=(~#>YO>51OvIVUJ%8&at@n|!z(JH`lp+t z?@Sj%xt z(ty3#)JHC!TdU00yh)eJ<+FY%Jk~eu9gqH{0E%9d8)^j{mz#(bGQb#vDV9uo8qqe+ za=l?7 zegJDfxA1|~?BaxM`nH-(gb(*vl`MW00lEJ!s}!^Hv^_G?&uHj*nJiJWh|Nw>K+yNc zJhAK>w`!*;58Rc7dpEYXK62dA0Y{4a`VHc_OzZ}+cM20?j08!9E?+u(f4VpgPzb9K zz8!a5CMcHA8M-}wwKE=;A2x_l@NuvVnW;Ie8oufjrP-(98{V9J_c}^HPt`*4kZIFA zql;C^SIxk4i_&bHx!iqjL4RGT+~i$>b}l#IAV(A+4XKlh2htg;xsC~|riU-B14?#( z|LboBK3r;nV=13aUh|Ld-X3ZZb?;Y9R>{9S$f+-eyY~nZ3-H)XtF2ih?ewdgr9`O|B#fl{0*8DoqTs`i3j8PtVVr(y%Z2Ew z;N(T@ocOd|{cic=c{I|;EpuTeu*j&e=Rfwo&CHu{`j`ir2(!fU+~dGZ4Qc{eCyckJ zL)_aVmXj&GfDh@?=GOVoSReft1!M8rn0*vD!&=<9a?+63h!1w{=>q4ac`vo7Tm-FG z7sx1HP0xy2x~C@$Ods_`gpq4+87>}x=M!E1c8?~hJ-6COcJG=0%^!iyI0OpR*zpuw z4ca^<3g6gC4y7Rr<3XrZ{Q_T4sNw0zK&UD6K3k*e^JTFs0K=eU@(Xw+R0%63ocbrJ zV9Y_E=gw+hc_!y5nXj~>M^#a50AnXGIvHnCdn%6J!qLuZkv7O!&uA{pWcdAx^(MxW zKXLm0>_mJdH%`_(fq(Liw4si(p%dQkqKDh`OL0DO26-F*!0gD(`X<)N1qB9XEGtG|{gy~yrslJGY1If%MtRo_tW&bv*f2(T?hSm=YbTNP50k{O zW;kz?ihPt^+`vVYOS2lZ1TvB07Smr3E#BccYb_Gu5;XNCwe=tUXKxG|zOwPz_2%(n z&M&M?5!+lSQbBl}Z#Z#m5tjT&PqLA(b3!V?WAtRCODAA%^zsJiz>A}}2$Rw>1zdB0 z+|Cqeo|QA>t6K54fb+1eYm-B&Lx8Q4z*7)-lSI{a9T?zhfbFAndJJ z`t|4RVN-d(n6NL-yjrs)_JU)X$cO)@% z1PxZ2_#FO~TNRYvU;H$>!au+^!eNGF{eo?{m@#C4(GpHfN8KFnCj;8;rZ)r z{o04#M2tIzTODS!(aK)A@a_7;0o|)l&g;-kT2v6v91X!oq#Gz$#spTSPOojmvbyA? z)Z$o?THg~J82Fn=^*E&~Qbg;vO=#?)qsZ2z@52${;-KK){RYa25!vQ3)V?>}t~-<9 z@n$0WS7#;TY4Wyin#O!(;vwhyHG+IJF~lZelh67m6sCJI*F4Mr%ZL)yEbcozB!=Fm z0kMOz1Dat~LjYTYt;tOTb&?x!jZ(4rNqb-tkHw z=C`R*dt3447issnuuNrXX?N_L^g>YfA06bO`q4Q&CiAn3QIR$-gh4VFLYvE)eRGzF*XE(!9FT9xNXA#qS zvwzE*Qr|T-bZKM_#wg*3Z!$e54M^L%`g)+3JM5NA>**k7{rXJy52tZb6|b4@+(nDd zBCW^Ttwe+|Ui3_A2Pr&13cwW)vBH4Q(tJ&uiDfq8eWaJwad$(ckVXO=H2PCctT z`2Zq=AHG#*`e9(7RHo1sy#7b@g5Az1D{80W+P1MuB(L~GF9fWTbj?>lZPwHc-9fWdP#%Hg)TTf+oy$fyQhEImq4GPy;!YS3A@hBB52lZ(l(0|7lD^>YjEti73oOnl{?I>+Y>~bC_)MxAAD^-9h4SY|lTQ$*+w1(cg1fDo zcnDdPop#P}=Zw&7f-byXf7;0-bU-b8bRZCnPkB;RRE$V7E$3GebBN7{^H6$P15dU& z%ujsJC#-X(BE9XloHNFC#&5oIGb`#{q+jx$UVW4QKyW;zNm=iN%4)!m+?dCVM|~0( zBID-=ff$6=)0zqdE4uzu#CtVv?I$Z(XJOoxe(LEpoGyzPjB1XS=TD(c^P6Llj=gL4 z!qOJm8Y8>3CIx)Up*9MC-hj6Fk@ym_=T18E12jfHXBWvJHF|`ag_A zaf3V7J8=3P+0U`g5%J=Mflb7HdU*(yv(>WB1YHdYyow3f(@0ILG6^K8c<%(h;A4kT6XIc;N)Arj z)E;^kyfz!P+U>Z3k1zA>$w_|UQ`LCak|$!{TV#h5D8|Xi5#fhIxBCMW=IymK|MVT? zg|w2_1sjA64Z(`?-!#3fOceEr&NOhX;wKA(7g4gWQMtYEn|`^F@B?rUlNGtk4tF>e zM_I&7d=l08$N+@?_puLE^0sunI*?6lDDyF)me@_2Fm*$fAK-)+Horpy4yY9xP=$-% z0>otE)7HkeOdEF4As&-;PMxv}jXr%QqTZ#)yx(}M@)n%esAQzU#AC|zH3wR`rb;n# z7?kv4PrVColMawr!E;_&lnJ-hIpq{@oD0QczlOh`?=}O027OuceY`hA#N-DnrOVoP zetS+b#0wS7RH;lJ7vaA(XdY-sZQHOXVM(12 z1AMRc73c38$57+{Zc)xaAwme+)@~{Q1Y-5uPk=ujc10@ma-9M7mt9 zNT8NWFSm5!J?Ui3{#jK=@VJ2b|Ls2tN_HVK7XEaT3Q}@IVV5ro0Cf-({-5w{%bK%T zBQ5@5<@4S=DJ2D#D??oJQ2y^jIre~|;BJBk zk-quk$p7LZM*TP0!yfsA0I(U<@0ocmCwVIS2rZYFN2ds-PHw#b<(sX!ZV$)h23&|Y znoGqjmyC4YX)d6La$6%fmT=OrMJ7zeOuQ$ziu7muMek`KmQ<7BVW0n2q z>GhPOh~NBr<{<6etnmGC&0NPDELaJ9BPZ)65+DAoZy;Ge5YTcrkD(D|3a#!7VRzYq zUJevqqh*C=VpwSx`%Y7|U!Ig|V0O!nbm_b9iwxuK3wvqn_uoVp=b$qiMiVh?|HuSt z5bM7RQ!G+w4v!qnIh5N*!Zi6*I+RO<00G&Ay%~`hKj@vEsT5)C_4?S+=s?8PfKi7GQ9;|iE|)QW$Q%p-ZDw= z_B~!0aFsLHQ3r|IyNC)A{|n=EkZEkJn<3r<{vRfD$9Gac$cy0~pwJnEk zyZGSI!GDt-nuk1AHu_+ zU^>=k^T0ems%_&rKn(POGRy0=Z)NaPX`cjh|Goe_DoH+ z-3|8r3$qxLef<^Gn@Y9O48nm-%Q)u{=QT;RJp(54j}nazu(wSPovZ;ZoE4!+3q)~2 z?F#KbkRBlw0-7ucMc7S+uepMUb1vn{dELaI+KXSWXhq(hTbp-~eSE6~pUne85XA>K zs>p%RvI90z@Oa&na<&FN=uaaHGWa)5dYx~{{LGU#f!XvgpGbuLhACEq#*10=ek6*O zwUnC!a}R8AAR{zHhz(0YXsx}cAlGg2=SRNh>x{h~>|Eu$C*u6_AKpT~GU3^Fab4c$ zGCBtisE-GL#DvA>pO{Q!2RoFc2Te>U^L)Zzbn*FnrK49P(kD&?%qEF7URMVF5a)ZP z7#PoPCON(z5xt=sWz7fERh=6rnRnX0Bi0TxmV`C()YQ}{Emy6kSg?#Xt=aK5F7@~b zQkW}F=i9j2SbsC`V^Tn>(WO^4E7QXh3GnMyQfd~t&`@%Ay~w2!cC;GHdI-wb&a`s1=)9SvXhu>3Yo3)XyXd39p< zi!Bcs!unOmC0upA#R|4Ei3;u9vTtWEG%NU#3IhdP^koUgEWY~>*jYE1ppmqTCD;3a zE1ApS4sZU)3w8TpH&ExYBdn@s_#}M)g*UscJRRY`ux-ZswES|=5nuZSNF^hO$@kJ? ziJ|YRs%s$M%(C>oJh`VyFbdH6{HDWs*I*+yq&@A0A{Xout;dsdt=hN$6Be;z=Yrld zHa~{gU9|PBAF`Kv`^9oxBe7fq4NW)Q z*n~1fKL-wC*}IrD{p)rUQ(<8-_%nhQb&ymnB1EX&sB;4K1aBjm7wI1rirLC^dOBZc z^L^KpPJ~+hug0s7v|+9GAT`Y=!2j?B02qol(%QHF+lKvZR7G8U zhTm-L?270=9mXmz^xI@_na!J_7Q#Lxbiypl*B#@4hJ574mNxWrW{Gx+WrA?P#CMHM9c+?@O|Sy%?+$ebL^U&9Z(p~Ua)9mkK?{cSn# zI&m4P@7y5?X^rpvr^UBC-ZJUhrO-qZ9!JLkY3gpSU7~H>&Y;~l2T*(359R4y z8=xU}2gB7I&YSz6+J9_EpCs~p3=--Vx1Fwc*=drQ)*}pQ4W(3)29Fz&P}R{j><8=z zC=IlazLobCp=S;OKoB274~mma=kG}zcdynz>OCn9SY8$FTfhB1uRjvOmFOE!Cxa6d zYGQi}K}=+(nl^cRc6-B!0NFjdf@bV3=Vasu3O}wZOOo>+ql~2zZ_+$T6tBN1n3!l* zceBYfK52$=*<}xWX*MdCmX_wk;q*xnFD!I3(Ra`0#O?EY)~=%QdAb|;HC03MKxw^Z5yqT za|(2|L}T`w{H6B&Th4V*pBrh^xy#jWEC>r<2!^v#U~o16M&i`L%go5=HBbsMWRx9K zn`$bIaL3sWQtD6VpNC{iBrC_^LJ^$2p*Yn2@Cl-g;!1aT5y|~4>J*}<6 z3~t-}QB?ExquXt)7SJ=BGQ991@96{I@gmW-3tg$T_Dr?JC1;T*_kRz%ZsU&7nN_{# zn^-igJS=u%7v$B0+-R8nnuW+>rA{Qm_pq=`Eu zWx?DRmP3OHlHBBgY=+0!$Q{qLisDurcv4oi21K59%B~c~N)T#mdFg%i05`q41UqIB z>lvl-g5%58heAxi-0LpJYEWg$=Y&1V%r;;EE~DdqX5VPoPs+lbFhTdc;rWf}V#U|$ zFWUJ!iEX5F^Irk$bYXU?=AKkI8aJvtL?vZS8hgvEI8mo0%5MT1dnmvp^y_e#oLnwQ z@`tv;hlM!s>aPA*l`09iTi*=ps+EM50offM^AB(>)ley`I$rdtEk}9Tbba@Sm2Y7y z6OBPGTd&rIv>&0ZQWk3;BrC{-x3e{qMbEBU+(bHn+I&w~k{;NjVF!3asI<)Z&>^EN z0+%&QvVOX()#_wzRMtyYh_%^a_)aYd`!snZ-N=HvR62=~ju|7OCz+xd$^ zYnj3{U0f7rKh9PcAhUbvxE^i3C&;3Nwkm}I6QR#p19Im9WBkO{*5rU&3dV_9Mv7=; z#5v8c;?Ym!s7($YW{MLAah;XeMHj~_S8&D=y=0RQxfl}KfUrW!Z_w|)OxpI<1P;Ff z{@I@?EH0<9xIW{e?1s(q+#28zUKT+9FlQMGdj7!rM^#U~BsUaI(Zg(#V-2ZMEr|DY z$}xHEqGy;Jt6+l~BN%v_V&?7}bB``GA-4Rl$-8kWH<9B#?%+}x8&)SXt|E90# zeK#q~{|W=OMXHiWAUoJmOVUX^p_X=NYYDQVm=V&erdN3OwZk<2&RlgFPFY;?YM$-8 zbrhJR2vCwq5lmD8Rd*sUu6VGxTyPoNlt{YkDG`|Awabo=-VDTCjeHwd*kq6YP}>*A z)ut*L2G9`XhLGB5nu^mwAkY>T%G^)>#&ByG1qT!-LDKS2o) zow{{wWu-OFa}@l|R;zZZ1Huv$|9Qt7*Z8r#+SZKg=TZV&#ZyYx<3$%75o05li;FE z@!0+V(2&p%0O8t4mR>sAB;uuzwo)-2McbkzrT^t|JFr`MyCzz7?>n=(Y&_yIce>f- zv_GLZAGIy0P*c@jA!r!D3yDl5OBsNytkQFj?=T_&+VNnw*U>uYbqwzlA_dA20i|RMrrfaU$)m7L0KE=0J}x$esSm{xjTXd+ z1}wtR-aFOcicigg-}PB88ZdF}@}*l?KL>KC^M>Pf6pmf3SGTRHdk(1Ovg%vJ7qZKQ zIc@M($}1|yqQw6CsG7@R2!8@{7;zXkqEp!qT}#*S3vB**y6dBPj03>wBZvp<_GuGu z4BkXu_#nR(%~{TA=9*4)DeZLepgI66$yrZ|KEqzH8>~;PZ_Y9kABR?Yw3uKvn&&IL z9X~y$c;N5RYucwe<1aYn?DOn;Rg?w?2SL!{x9{VRvf%#`4MdlBq4ZJHL1>_yYilZJ zsqq_0d|rW%WmrH>0>C&86gD_9<>UBO^`Ut0TJx+tClbu0moSu2S!p8j!LN&%ZDh0; z#ZI73%As+Atf7t@0{HX(ZK$9EDkus?boqtgQmU)mTF|xf{(gBRx=Y~pLV^kBYp@s4T**w8`s~!=SSMK&78E;Fnv*IDw}uGg#TM4^YH>z zj^B|je9+Z9@3uj7cheLe5A4eO>hi&`lBk`pl{4b!znftl-lx1>-vusokoILOj>5F& z);CSNhNCui62^+phBv0yV&=O9#s;0^(^h{xkZB}8Oc>aB(mwxA z^dO|VE@#xh$qnP6ci)uAOG5R>l*3GFY|mR5CnTbr`DT~o{{5$qV{r{Jsu%$?;_9La z7goCua+miGLMxRFX5Nk*H=8nD+Ho&6TRnx{V9nf^z1X=hRCuo4>&g_Rj48bO3S|E< zj9?yP)MO}Q*#{GS6c6Ewppc@dQ$H%x0ZqAqe4};WIlc7EH+H?Q+|h1FF8=!Qh7apz z3@Kg$RmpF*&tQmlpho)mFE8vMQ%6h7P|?0=ze61$y)9rM=3x_PADey`OO(e!9^wsz zS3$L0pUhVOSK|B0J@_5%oy8!29!h)Um6l@VQ%U9RH9cL9(@yLUkU}NEnlzd7 zZJtzQdvy1r@CD^U6bWUl%J#2**kA7_;Qb6q&7`uOBNq+SMee^1 zA1#%UlVxvqddMa3B?)ALmRfK~fQlv^`qpp5tYCMpD?=AMME(RD=uZQSpZ&ywoLV9p zNKbgl*b8QlSlLs&wc;ciV*f8iQIL}(7&qxSMBM#}{_dxI-1ns_ODC_Jqs7w*@QFfX z802(B>QJfg6oWeiT_{dlMZZ75loS|=B(`P&#E98Z>pow$y-S07P@vnHFI@zt`M<#D zmBof2oTbAA_aH1bE%Z>^myy%G4c4CJlO5Bw?C#1)|NrGXgbz1}U24EY7O{A&(H(h( zg%7#{7%zk%IUB`QQ`~3PHy-@WywHLHt@C*3^8Thoz~g{*dy0y`%a!X_S*6kAMl9V0 z+nv2eqg?gF3c>8-xLqIbr=^M~T9*Z8zZ_TJ`+vE!mN19PBEPZE2y8!5Xz{H+TGemQ zFRs3a`ofeJ2fLcOP8Dy=jv~#%*+$_OLU+i^c6oTWb}#&La9}(lzKqE*7^nxoQJJu+ znMg+&U&Q;$lQH2i5r-(5Z8;ap$VpNDUI})kP??p3CY`Xc)}bi&4*%R2E}&4(f@i#M zRu6Q(`MP1}J>T*}nMPbvCh$5dkg;w^I^W((dv6hI`2+X;t9llXW1SFcOT^9Qe?@W; zcPS|WF#4$b!Qg9)1gelj_Z+MT3H=oC6SnSu8Q}Z&cFP}-NaY-arSS_jZ*~_JXrvJ(O24QwQ1IlM7p6OdPW_fw#*t!ta_ z&4cf2eAmaZzh!ueN63;ecm#sLS*ksNIy*c$pM7%t69}Y%sP;4abaOW5F@~kgxh8v; z;s!?keVw7#^y@EWK-+>nQZ9d8f(7UxT70AR7sY>zx2ZtsaZ7RWogZaw-N~K`BV_w~ zR{-ea`^;6PH=Us5f0OX~$<~#jZh0tnG_?o(M%3#YoQQR<<>rKv;STNdq0EqdAu-Ec zAH&5|a%r*K3T&_6oAm8#GZhH7V@89FSi<_ll{q=QQ-M*pU*shk%-4&g%%Mh3`hi?u zB$1UkSbFJQ%xL3hr`Lo|{N42@UfwsX8~CLm(?G$G<0EgY0Xe&Ujd__FyRmlB<5mrdSshlP*YuuJJ*yv&{I4_Ydm)Sat)O~9hQx7u((G21Mk3j zM3l@-yfVBdD-EGOqEj(|4)Q)8RxnbPI=PWDWbnA)9n%lw9V*UC>ubEXUl2rnS6_=x zJ#U%4y0}`NoW1NS^x87G+Vi=bEp}B&z~FkI|7u_}SO&i95L_IUs<_OknW=%Hhh{l1 z#h_%6v+iPBg{FZ9!=5Cos;LyO>leZjRQ6sJ@ZN~?UL)yCZJ66}>r2tQ8fz0j>`=J` zoqb<3x8|y-t80m!GbQJsG#q8Qcl#4uWDs(hbII{9-LJIV4(Uhpi83T6#tAF?(5C+# z1OX)TW5Rc)<312@vRZ(f==KqHiv049o6qH{&udo+EN4;<@Oq;lg{yW|H<%&M%RGT0 zGe^HHLruD^2P-~Hb#1dCPl&=VerwGLt!w;WJXk*eSeO9YPru7AtN#nenUkHpgkDhI zUlH;@+ifszu-Ze`6gP|Qmov*&nuDdAErQHHi=8a27|E@5HiE_Zk&pL(Y61RPlc9!^ z;8Si03lVR^{>+Rm8ti^`QL|Qh?~l{1@Z5PxBvmMRT#8zXG0U@2@shl-HSp&FunUkB z9VnkfHryBosdNHr8xQER-zUSjv9S?%FFn|JdNdW=iL@;o}@)tvnl zUs=@PwA4R?aoh#U^LKwMl0Ay<`2dFS1KrJe6g#OeuT8u=NfavR?z1Ow^+&UQ7wJ0l zA!{Tms$&WGhyDZ7ywRpMeu;-p04Ork&IZa=0U9Sl&B3iX+PR25CFSk7Y!yiy>OX}p(W znu{fPxACqn^BgTG0yE@rpmwWUAwzVCxC`cQeAW^U3QVJm9 zll^H?s)7`wwqQ6*@{w~-Vz~5cL!T0X0rYSLccKaSu4>Jvt%>VVVnt&%b>F_6H?%b} z`o!KS&*PjkXp;ZW%O@Z8n=J#C$6dzY;O8bOl%nGJ&!GjYi2#gud@-2E+%FJKe2N_B5#BUc$GNd>X# z|FUjP0)ZgLP0w|800(X5oBvjlA=>E1#OyZ($C?KIo_v-j43aJxSE>@-!qMNz38r`y z-pQ1vCeU#vzfR!_ofI#YnFd-}WDy;QcMp+3&FP+|u)@rfhX_dh@mBbPso=9Fn*|XQVz?f zSFcoK-0S!SR_8y|gIPL?oAz`w2L8HSoK4e!`giT{)jns9PJbfBH|=yl!vJXf>{fxp z{KGRuJj_4(jtp^Xi4?}pjcJ(MbPg=*XSy=DYl)xae4B)~iL1ck-iM8Y(>jkMo&1%VnVH^R;ys%?-KDC) z_65{O4K~WEdW+Z|;*m0Ua2f&a&w{OO!=W*qGPVCn_fv#%DHA+?Gm1$KZCh+KY+v0Y z36Y8G5|faij^N~Ala7sxtJAm3*O;B`5=wsjdT!%@tZm1`qoz3T*t5Q_PE6hk!eRzu zA;d-~2vMZi@smf zh(lf`hPAXH5eRkLBi$<9iRo#tzjK!WG(3`z!toQ6kJ_HSTC4eUnW@3L;X^`9HZMe> zkoNV-eJL1`at^)}J#9WMx>$XH1Q6HvExqR3VLM5Mv$4pG^lFYDNabrmCU9mv=@3-2 zH5%?qTWp&j1u?j3u?uI-8cLQ+y8QV-oaSNER8rPB%+^jqM`xigWje5B!S)E)DdMSi zPP~wOjc+|DreLHRT9>1z=R;t&My}%nYxuNn1w2D1-`38~##UTQD=;vf>7jASc=pJ8 zm~4g)dtqMEU@;>o%B*U{3SYHkyw>$kIB)=5m2Qvu;^oEBg|`n!9EJ=<@wn~$ylH*i zB%!-k#oMt&!&**lBZ#p#MXV;JZ`FG@x>lGc!QdNl^AKGs<$h`p- z#y8fPl&^4bLM(doT8u+J(>z75?E`W2`S~98^q8BY1!J;;m{Jz?iKlqh5U_A`=w*1{ zqt7(K;clY64z)vT@A(rc+MWTU+IJJ32zy2I8(tGASTVWfEXd!{I)ZmLtBSSdw#MR^_7)?TfCf? zI9~?9`>5U(NK;`p4iuw+*W#=_vt>%2={2tq@%G@or>Dp`75E<%WO5=GF^^qcJWTY3 zKTn(HCHguL`L=Yr=JPD*3!F24L(~lb(u7QLDG_hetv%UR0&xTRy0rT1t}=ng3{X^DB2tz z2Sl&ldp#E<2Oa3yqrhipV3vwi*Qxujw5&g+OaDd*t8Z127e_NS^I zb`^B;%2_2NR_=8(vKcSrqtclu+JOBN?o@X;@dTPbx(M8E~3y-BKsh{a0T41Ep~ z=LWrx&$*1VrTz7$hsA%hqY4MqJJl&M&l;1oV|h!N@dtYOTv&p}C1OFT0xJrV%X;<4 zHYh>vR#^B8F?VU|(&Ih>fUMnMyCCWi+|u<3HUc<41L)-OcXqr`KNJl&w$w>#RYP&p5lFbqJ7p~RYD*uesYSoJ<%*C1(ExM!yCb) zzcSes31r^5tyw6zsN~B^FA>T^AmNLF(oyoU)aqTBWMjoBy4PbW8KsDsi8yvbAcQzN zlS=!MlY>wI3UcJ5mX00-2IJu1G#c95*>NT-ukM|cSO^5lB_>+)Z&ce^(Xf|eaS3Gv zC{*e8mWnVlGb}m_UdE0oZ3eu(BgaAC;eUs?ZqkM$TsgfSYyt@L_y)Z$~t%MLxYP zxBEk;M#$pHnBe*uAW!)$7g`Rz|weNItyP86xrU5G^X7H&o-`qv}h5|5F{7H8p$ z32UFDv?qF%o+s))CvjJOy}b;3T?eDz!)K#BzWF=OjggBH{vP!NkE4Hc9w^pCbQ1Sn zB6IAMiXOV7#*?m#(t+M?6iU#OGes+|WI&&MSxuL3lHAV`{K4ijtD zckgrkZ_pq3D%=&P#-oe1EA5?}YK-KIhO#nk4idm|&*<|gb4iz%LHBpyH`li_}+3gM;W^&Y3q=yx?8jl4H-iH{tw`0V#SA3qYZ} zUeWx3yKns=xzY#DThJQQr5qIpRMTw%8JTi_od|5l*YlzDx6HkMY)SQcRzhxhqn zD(-!$#Kgp|t`PCmxIpQONik~Gq-{0i`Fr4~GbVRkj!%owdr>3NIf_I9!>%R!C^frBgw{mg4={Xz?ugW(l(E0=>JR?W-TeAQ!@R$dT1`SCCR zsSUUrL$S%-%BN~=s)2EcuG21B{PoQm=AtT|{Wu~wyVcwgsy2L8pi-CQfHl@#ispt3 zi%DmMTrH)Zo3oYwhWD|vwH_?*1`)Hz}sTW5qF2PMiSkA=+J-epU8(M#dp(cmd4JLydp;4V*E# z_F&uAwvQ;xJ(eJ9&b}(ig33p9?x1b4tKo8^!QnUrufx(Qi{RsoR@&gdnx$)bI6)MZ z*1G>&;0L0NvGRq-wOAndNiyxXg~S;YfGpyOHZlDQ>t5R9=H7RiFFF#TXrM__hb1nk z@_S!H+_Xbgl1?CSG1O@}Er@63t?%511a}WYkhw4JDmI@=OP; z&oA}`KtTP9ZJym-K;V$6NhXYT5T5Ew9;2{!+KVq1OoP!W@moy%9kCg&`j>yYL%!;C zEq~6D2DZf3|Mm0Xmyno+$wy$f*hZ) zu6{Q*GovKt`K|yA20fFQ9cFj-+S#WNRduU9EJ$-Q{W(fc(?LmMCNR#=ly)7P+R&!O*Y;LI{fSUL$tA+ zOR^a?a5Or*qLLmpuLA`&wx3l??J$hJl~_jEK9EB#Fi_o8CKgdQwSD2yq2z7HL8z9T z($-gSwdix6@ZMSe>g6reFRev8RMR|gC)J3L!WGycRK}!LPZ6%AF?J6o@L`5Da*5p& zAru~}Vq%Bx89qG~hEhJNPP#@9<#5?mY?~AkIvIRDTY@h~)Ts3y|Gb>3#uOXnIhia) zOMVr4f?_%nSKda$zce!Ir^JPnJA7n#pasDk47m0O%Iw0sw{Mx84Vo?Q zK3M}wj@~ntG{>?n{0R+yD{%Mq6R4(Z`2)AsQbeW)KMwebla$j+tJ;8x^C}(5h7g;qJR{KY9)8bP`t>&r%Q~58f?5)# ziEY^hox-za(JL9RzWCj2X+WH)ns%Bf>sls|iCi43Q1hxzcAN_E|~T+r-d!M&Kvi3hns(u7mUi zP~@4Zp{BGWw=Yuy+Fl{Bu;;!nR8F^kz?dUtJhf-8ar+WFJf9;-bY5`eE`Bf?Q$ z^-f9T&&c|Pf@gEb=(;4EN)v{fV6kXaBKS%3E8vLAs-o80ZdI?YawXZus^K22*X@mr&X#6fQX8pyGv*Eij7%MH4D5URP42v-kU{V=em20?(oIaLvxIDA?yiBLl*$iyOr`Ys34 zdxvEWUVyAPf%CyUPUm&TZ!ykIXh-F&+wtybh-eC*Yn)%cO8Xj@X7W5Om_e5WN6r>HcQ zVG^J?zH)NK&BTb;ZJu~_$}{3`uMMTgyFbHi4lik^HVZv}7>1^Q>yFD=_-Ip-T{~bU zNTc;s%R;L`qW!)qLR%Z5btSy;>i4hb_aBOFcgA;Jz4Gy}-AhHP%zmkUzu^c-?Tg(~ zqc?jG$$a<5PVY&d$azr|=37v<`31}$pT9eUHPoDT?)7bKP*kdVo}YE9BJ;b*3zI78 zEoY-P9pxW^ZANUwj`>DVcPkiV2f9TbuX{1|8PI#sSVpwu9S%V590i$jlz)7egI|ja zxd{DC7i95qoW)pbc11C1%pbc+C$8G#6PO?!>3}h>RmFImwNrWVb!)Nw^Lq2OD)yov zGBDWo@3rCM%;M2bp<9cauH?{n2?ltW*d%v<_Olrhc}JY%6e>DC3 zE1=zDKaiJr#A?uIr9Q7D3*2;e`Sq>@>MsQh`(4j>G)fyd4Uc9Z>Qc*Zj`vYk?jzHU zs;2Y)(+}&XC=r(<1{WO**;u*?$2ParU z06$XGhjGn5fPcW;vSD;%tzK03_fL#acoaV^bTOx9fcSWAuxgW?4 z>(JZ)4jOQ@jJ7mf%<@Bsn5`J$^WZ>nu+Bc$CS_^X#P#bJbRt zIB45O==*G_IEsi#y?zG0)f@X-#2696j*@F0G1`zs9nC9ro3VjIkXh3N*SLmEWw6Kl z8}WnhhzC-URT_*O6%Ai>D@LC|l9B{or*~`LJcJJ$7L^0E9q^aj^fB{=Oe=Fb1$k8Q zp5*j?-D?q|kmoV?=nDlSrKXP^m5?Trrc+rhdAmUDme3)uH2F zDWrd~-oJ7ptf8@{iXc!KSrnu1f@Nc4b;;bZI9@np(qZGTMT2YOw6s$J4oBN77Za?Y zwGN}oKG4~ftyjuLeL?b;A%WhW53qaX0l~NKHo&8^f~Dd&#{(KVR!#v)@|gR`gY;YCJa#oy|+6lC`t07xllB z*U0~xCzhgOZJv9My=0|n!!b_;$d}%R>5jkDkCe|a1q6i8cwfW~zqBSRW0!i4ZuT9I z6rkJ9>(NIbruSp#42yJ>iVW8!Q5jCIenARK&*Bhyhj-eYjg~(v5hzv^!?BZ-lj5H1 zXn7tqM83waM)3Lv(J_OvzqX~~kMfHu?WV^>4|4-9;^ZWGdM&KF-xx$@6196aV^}se zA^m{P-C>7KPu)%ezpbOQdd#Dg+Um;b*7tEM`I#-;af2}1w{p*iXK%M`$(A;0S&ST{ z8<~2rN_*Nj>)fcy9Ou2l%jR>eUvHd7ueLlN>mR4Nd_|79wmkuHP8unYXR6v%kb>XSR%m z$fpy6(JIK_eND43*lDCf-!~mBDzk@X#LgR8FcfE>%{AWDBFB0OzLr!xZoFo$*~zlerSJ$paR> zQ3H9R`uZ?W?}gfiGLcQXBHH1E`|J%LL>~#XJCl)Io2K==E^Sjp=A1DZp`Xu_wif+y zqG34TM7F)ATKsqTT_Xu5WoWzkdAw$xmY7bCUQHhrHHX%kUwPGO=NFy*|DCHp8x*kZ zF$-&0#rd*D`zEe572;U2vZNH9vNmAC!{=$Ci)X7@GOsS8WQs$Zf>>Sd-P@mcs+0G) z=IQI3iN+>`4NYn5=u8$=??RFjs8fEo3S`E6OgJb*d{h^ zsLObd6$Ba%n(Fmz0D2EC%`7zeC`nJ?aigoXmAeLmaBO4d-^T1463KUGNd7JOc)2b* zZQ=;#^;;{sG)AyTr)%beP9nLdlha?ZVUWH7K>A+x1%O??g?>Ln>6yUldS$oyR_7lL z=S1$4g40DJDv%q)XzbPzi>Q6uSF}&Et_n#I@^|q7dw5+=Jby|I57+JYsy2ldSidM_ zj-ewRBO@rvUUecnr0LTrFyd~%TfSW$MmPCocVs4K)yvR1En2^5EAEP6JNP*^uf2-V zap;TsvY&Tjv2*p-t*J+L-Yi%i9mBsBQrvcldE=$0>yx!*9I<&8%Cf`qL>Ji3SFO1M z$Bu#fN?c&2R%pQw5v|TUN5|PTtj)S)L!%Ja435! zR*6NdQgjtKOnl*^3HNPOBZ^J1e(mOFwlsoEstSDg@|88ix^$ZKe9yC->q{06z4E+$P(1@2#j8}>cO242~VND^eZ z=;-tY@`6f8cXf0kXm+1BlJ4I=W&RzRc(#YbAO0-VAr3UQv~1^D7Zu_h!Yuy?kjowu zex7Y&_#V|!inh=_#OlSh_ni9kG-eC&m`gD>`c~Jw&xd8JDzsLv$(1DJo6^-?;Ti)X zsEGZ!nXPrO`yJGo@A&CgY-zPysJ&r#ad?gZ7T-9Tf%;ppp@3`hN**He%hTR zB`y2L`v&42zB?A+tc&EJJ$4ZZ_TDS5M?b9^M3=m+ID3$VG@n0J=7~PZrcz|hPM*sX_msjnT_E@yKofKDF+#K)kd&j3) z8>>)!<(i1Yp&P;dSp$LiHPuQ_|A1_Xn%k=7Q|6ENu6g&DPL&n7FYa@%BKBe=z%~Mo zkloMfu0-|^`Pew~IemQZD#neHFrqXPz zvaF^?{m)Y<)I`KzfldHL5tHF%-RH%z0AB=ei*r0V^gP|&t#GI!msP9sVHTT&NH;k< zK8=&4Bk`_JUH!3@@i+(&E=^gc%|>j9={ea3oV3L5{oK<-bDIoCV$<{*r@O0x;|a zri<`?;h<}`5YHEya~nzQ&KmkiZQflfml36&r_jzbNb)^~WUY1JGFdZZF3EZYKTxu=CJzcT`<)*p z-i};U<*EJizQqJ^NH*SZOhvUPmW1~-sx`N zT{;dRP=KPfewi=ELbpP%`pMwpqBiesyKYt$M_yUzJG3d7%w&2$Ay+#ofg~Y$W2b6z zGTZ2E>!6UaundUJa3x&UQPL~SKj?SN)Wqw3TxLYQR45DOR)I{yXDz7Vjnz8isZpc1av zE%lgOFr17qV{<;-`xqfW9^^dj@+#;`<*D&^NeE*4D=@9+M9`TUZL z90E$~_XiA3j(_qq?7Ex&-p*TWRdNdr%$lGD31Nsu%4{l;m6zS0UTE%jzw)$)rFkMg zG&|YXE0dpA7a>pVsiqTeKcVRjx__%@S?4_l)5dJuQy@#O)(a4TQwPPc3fFr8X5rws zr|U&p7=(QX$NGz1Rv+ublEVd=%ey!o|NT0Iwz_&a=C{^jZ)`HZomg6?^+=tr)@REV$mApDfuRsOs=J%+J-?0_V%RMf^kvxx zWS~ms5Lw_XyW6W0QP^$p?925yGLBwP)34Yj|L+SX7Z zDy9=?BsP-IP3xP-M^-Ig4a_`D$?hL(He)q=Yof7CBR0mg-I67m_uq}^5;6aBv1 z9r*wvo7S_YztZu;TnC2~$+~;W<_O}wuBFdpac3zP&VB7Lj7JtE5CD15Fi{Nwx0SN? zNnbI@0b(yWrn&@V^!I)Tb*|l?Uzkh(Gb+r6NFP;9v;vt76%abqQ_pL}j&oGt?aQ?; z5(R?ikZ$)$xVB8sN%^Ep{dms(UaxgL)_W(xtg}l7{0uvZqN{?6HBOdTe zf3Glej4-gQ9t^JIe3KhT$pL)et4|&a!oA7N3#Qyp5d4T><+}rTI7m%ClcK)#F{ zBQ{g(@R;b<_)p>m6+*VTtop>*A?Cyzo zVd3qRnlY~@`o7rzz2#29d}Yi1DT-1j-w(eD`}?_`E_4TN1e_Pi&E_n6vB}DASEYVZ zfAUtae!vZDj(+ zqE~C;EEaAhuk4W+69Pe@JYJT#C>v5I4EGN9=C{7D9=^h#_0um^s@wMD_do^74&U38 z4+O|VgHxY{@!K~1Tuq3bOxR?DqM4y?`jDZ+9GvE^wWsX%wT$#R#eQkFi*53in%6l! z1`5%)1=IK)<7atJWYk?9Cw@9qjIWK1OP?>D`|ycDx>$Sbn{i#sjh`P=uQ%JwP!;=uHQEZgY-WNHL3w}$LV^Xsvp|9#Q-Y< z{1x)xOHd+}T;v=qcsw*yM?ZCGbTu5%m!INE_6%x&tr`8h7CX^_Ts1*;HUK_38$?|nwf%G$q*isMFlACD{^(kZQ82@fn<4Yw!@0ofgJ3 z>9v?&b>Ev3Mn7kz=tPh4Ceo8>-mG5-g}5vhf8cXxIB6a)pCo3%uMhra7U zYbGOr0Mvhg=6YL_|Dc6Z9QYS4VxNymh0lIO9vKR$Kx1n%N7>SY9=<;M)rofu$X)m8 z2}PEV99m=!D?wq=6JMMKq>DXQsAdSlDq3IU{?uOnmyWni4Na?vuC1m+^&52MjGNay-cdy+oB5{qPyFasYYHF`aT z>J8GC6!W&dL#BrLpDXd)`kNT{fJ5ywZm=ahgz@{Wg$fI8Tu!N%_>_ZZ7F(3_+houF`b>e+~2uCuGsCX%nCaosQl2EZ6i{GyZr z<5f1oxL4oN{$fV;1`>L^w9J0zy8i6ry@t6IjZh49$Mbypcw@@T(cXU2U@7hVu<@n- zbf(6BOkN}We5-8PLmWr7{>QlU^WgHGv@Gd&-P?KFm5<||_-ZnEn^Edl(q>!dyUkrz z^-gVH0#4eg2KF1b%4+qKLfYkB&mO+|;P^p8i2vCKdps+1sXe~5fEkADkWeiAl1zKI zn~e)ly;X8+yowdb)_Y}-SvX1lCjm-kc4m;i6VkHsq<^!1!*73Kef?IFel4dmZs>Kv zYYp*iwW`{a7ldD5I^>}DhrBMb3WF(wzcKpKkbCv1Db$4PVZt1GHBMN>lBGbl#c{Io z#XfeLbb3(Qp&V^kv=4^WjqgmfGK-6gSB;L0Bmoo7@mb^S{U6|O)f%itND{P2uft0q zJTxRnHhMl|hjJOk0KJ1--4z23+Zf`sIU8~;0FfGop>ffhCLH1K)iPT=y|MOZVoxGK zJ3-5J(lf#*sj_Tr`Q#KaE(2X{J_bgwQ>gvkIFqA&|@2S ze$@qL?%!70jOvV>6NyOAoOBrFXwu-DSl;!HnE$gO?fD82Pmb6uwCkra0qqv`dY_oQ zc%Wj?xOAAM(&ao+=h9`M>aP`N@r33Mz7oGS6;8V>xn(7|vhP!Ae=nq^l|tCs@A)b- z46WX)Cc^JJO(bmYTIjoY^Np;&!@uI^n&{H3Bl)Rr`CjkVO|b1j$I7Xe*A7_8-s3D! z^?SZQ?I*EIsZ{xIW*BQKy*a-14B} z5HCp>WYFn>COI~k_HK~rLe%QW%5IIicG(!$pI8pV0GzhK^2>|?H@XnP!`-8^4EceT zP>V6ur0_c+rpISd=jhW|f;gLM;Br{ac9jyEe#giQEYkKo1nbRWdyunNWyBp}@I~Tq zBQ;kYmE}j<~kzsA% z2;6HZ`2sSzp%fq>XQ})=u6OL5d{`+hEc-M~t7)mPWjb}@Qm-?^LB<4@)Fm~xR?cFp zxSjIDNe?QQp;m?OTn$=OBC35_k%(WWBU8(E1&lo)HJr9@$DUimhP;}c43;?}U4#|P zIs%5#4YTUMzh;2^_tnxVA+-0TKM6`!KUFn!UKuIPJ(boxUT9LBn{3naS>VRIT3rfw zoqAb@*838W&~)}ZAw>?F@b{4nr*48oE4#v6`h3fS#-wzN`=g_yi$5Oo*VAZTs zYiPwtmI90o1)0D4<)z~JV+jkVzeT@|VnYo3^VFfgcpg)|ouE$rbm5W6j%^z~TLcx1 ztqx-`Z|cKAPe+FinbFhp&VlL%B;Q)QwQy(2Y72GMiG%h~^Vgp$t)=1lOoLqI!4nnz zgF6>dby|>Bn^>ifoO?;6`h*;WbEj*MSYw8f$*MJUw!#42IieKbmcnK)Cn_SkVILG6|SP? zjWE}r%^XWvxX!KY0sBH3svECjNGLw^L5WaV0r&`*!Ts|B4tFmHHam zqI3KW4#NgHta=4*u&+&3oi(NIXh?r@j?rb{lXa$}t9$LW z9k(&e)vey89+y|`K-V5*Oxot`>As-A)*k9Nss)x|X3mtg?N#ET_uR$d)6PRSFakn9 z;Z_p#s^q=4Cd9=eOCXMgOB|Fv@^Mp0tRVC2a4-E)gR|@PYI{$7T}Et*RI)Wz`s;zb z+Tdchyjguj(qdY*jP4NUG31ES;yycjhSSCeY^JO5)7)JJ%a~`y$g2H96?oP}*ptVa zCeOhu#&amHQI;|@b>+t+6LK^Z72mpTGotc9Skc(fT8V?OYokoy$7#Hh_|%vz2@T5{ z*`~inb+6C1adL*6tz2{=;c|e)lU`BR^q^)G0nVRG#kDZUB2*tpmKz{-T`DpI#?a>Ld>3-8sGI40`b!F>p z$;}^M8mrd0l;D;f;Z-0|$(P2Df&sdJ+|yCd*HoHkrxDNR?+l|0NVUVO?%3-?0YeJ> z9s*&y2$*x$80y_u*PyG+s1{zjo#Sx1GHq9sf-Plx$p~04BBJJSEUym!<3=&b5(NkK zz43ceS&`it(DL8QDpj1Z@V`e0bm&!rue3_G&F2W z%)akqy`LIpxys>Bib9zgMx^Bl-F?S#7DkS?WfzYhaPC$LRe z+fxCFKba)m-4-W7x?mHL(D~oLb7B5^uBAR(a=R^{t6R#u-AA9;Qd3KpO zHuQ3B26r#c%nW11K`#C+*^YC%?++g2DFvZ4X3Y@D!Vfj-y@z{zF1Ry z!i7ug1WGy4fbNTkeO(ZIu*0n=+0TEU?^*cAk0KE*a6+}@)~pUB1{!+hjzE$Rl~5AV zpcM)O{rRT}(WOUoow7UQ-5@fwN9HZHVp+EOd$i$@NG6!(7EB4P+6xR@!EDdKp~#nz zHYN0)Eq}a;N=K?u(Xatisl7g1jds4QT7fCHVo*;UoVsLGx$Nj985tFmwzg}#yL)|o%Af(g@)0%G z2*6Ro6^6kOJ$Xh=&Kz}UaNF}sv0j@lfnZkpsh!3wBYd8bQj#YHS8UT4SCpN<7})z7 zx45{`QHSeLvJC^bmn3llg00z_!qT7alX4mBhfn&8s-LvuMB%wjpVCs2-^VPdK!2!^ zS6LkXDT~?oGb1K4n%&szoLDfsGp-w}%zcbm*YfZEnomTv^W=}4*ne<#{ZxqsM3M%p z1&6kRWyDBAS_YgR@NNSppt~Xe3QHMgM0z5jMJXJ+_5FX7gfxO>OgT1_<{+fE9H0!9g_lFn?kl35zECgx#I}bnfP3=?7xF>t&?0h<%F+2JqQDaVwsk(79_0uKlP8`MT zOnRM1HjK1{Q2QlvJcFI2W!9;qAn+kFoi`$e85SBdg6wdfnBxFZHm5irX!Inw1S3Pr zaxJmT?vUYQow+Ge%OG}fYLNV`y;vv?o3ip7BL#ml`Gr_;HK&5quYo)17Gty)?oSzX1>Ea&`U zkr)MZyLU%WV@D-Fs6yU^MxRneLe@E-6z8}Y1YM3TRSzB3vsG^XS+X|2SEHwKr+-v0 zQUQf5{nO%L`F%A!U8F;XAiA{GaFS75Oo_*4YQ$ZLtcgPA;&gb)PEB&; zZBZf8+G->zVu12D*OxA_*C%$brN>oR@!dml_E6F?YCY(XW7Ez`P>Rm_1s9a^jlAij z(VuX4AxOz9Ry|vrI}<#VQ7h;&BL-#FG_3@9$*P8(yHUsy`XW{t98OslsPP2rvG4Dk zceaF>q~DBYHG=LO3vRmXdO6Y?n>>D~DaMGi83PZHD@}@3)bR{APc{ae1AOj(b;24f zW1x8Ttd$fN9y>2mIG;%$rGz3SCnhH3i+a(X)bWC-DgbMax@U8DAbE=^hPg8p=AqKM zb5ErqyYp>N7^YuF*U4PU!Y6BxJ2<~H9)r=g|2j+P zeGyBYpG{5O+P3L#R$gdRKtM1TWe);@V(d{JkyS!chlfQ!YzjxlD^s#n)7)w&MT8_{ zTa^O4*Y{WvRSSyqpCM)z!GzXr!#{peCm^l#RnaMKXsZn@v_3m3HY1OqPN(7bAJa^UjNmZz3)sO zwDUzV_Yju#sgrdVG1Ak^s?oh?0$FqGDw9&S#LvmFsF7`(INXwDm15mXsB)&90V16YbnEdYge3LT@nY;?E@x$j*b`?2#i4iDt6V3v)ut^;{_=O;^Ds;Jkg zs?7TONxD&eKcrtL@v@%g@$hBwF%kBwLPE=y8XpKYT!{_F2hV#@#$m!jZ$jhu?kmmx6_BQ!?6SJnKYrInWCL zy6!XKfj*74C0yOxbvPV%yE}KcgHRH9u4bs_&9!84i?gBX-=U^x~dAiW#0p(G}*0-2He&sq0S4C0)&{y}~o9FZwy`;Xn z8|%U$ls{IjdrWyjYW3?$PT%(Z08e02NJxr|y4lqPJ9}^X7Y)z(^uUOi>uOX4l>2n~ z5j_vV^BuM$1yv`MvQ{d|txBAnoQJQYnNw7R9XopAnC+jHI1YCLAQjMtD!D!F@77l_ zIgV+QXkA+i*cKY@3bGveraC(JOZ7W(>2#nfmF8MSZLQBzU&zdxGeoV@OQ^W#gtg+-w; zH#}vzeW$3nu6JE(B8-W$Vw>JzOw9AG$ca8C&~FCC>U z3K8BeY`Bi;PLQy7#=qt}mYBi}Dw@MNV+Rjxd2i2&(A<^RrIUkZzQp8fc2R^VJ?Jn! zJGu84Zny2{8RGxBd{(ee;?!P^MWraS>=Rki>Wpt;Qf|M(6VhtOB)9m4G-)Uhj39v!9HG&kr zRBN$nor!kry_V}1GPVU>-pMimCY&UDx%ZV8+ljl@uiv}*47W%YwOZ2xAnNa1-sET% z=#fP+!?uP2-za3L8Gu?oi3+oW2cb)G?4W_5y`Zh{E(u2+b=0KEhEwrf63>dP-l~50 z`8$)`aM=fK#$|BvEZt@3n^HxhJQQr|?Os$+kYE6b)K+oLXX8KP&DS~{(J?K|JWv~# z@*M71>IH%LG|I*Vo9=^HU}V?djsfo9+n9*SMfF(q#V99&`-*MQe0}|eS>X|T%}aR) zK^@cJN>YJl`-w*6zbyD#Ow#qHuYasrkr=;F7HK;oR079XILdA?a*nA;!AkC7Y`z_L z;nHYaJt0TdD}*Xy@gJj`xV4P;hkzkih2_fbU$#cIIt+pND!A17R^ivrDcQCj ze+Q&Qd}DY1J@*+gGsGy4ugug!oeZM64gk7zY^>&+66B>H^4*b{(O?ke7CreG5{Yu` zdD(#HOpNE$`qsS))yT(utL2NlmOaahoPW8R`GUU*YOY&pFTU#?boeVmWf;ar(EX_p znB-u0b7!uVQT$-7G- z$oj4~;(4VmP&ULZ9G@*N-s#`YTCgTqS_97qS+Gl07HA*dxe|Zpe_|Q~)rRSbF)v%o zC2dlY_fXadKG!BX7;W{QH&8{rPQ5rLi9TzHet~?rZlULEj|c zA%n*WIz#*BA6VJrp3vPL)HRx4moe+1YbR8j%CEJ4uN>ZQ zfJJ8euGhV=ia7ZQFGMTn(dK_sMZaQGl~Y+1xPO%&3`PL<;6ocaw)Xb+`CbTjx@3RR zuuYuB4u$n(vBk_LYh?r2ZXw78I&qmu4xPHU7&DM@Ukm@6ieh#1m6%f6C~s05oNPJr&)Qm>^PgjXQWC#u z;9lSeiyJgRtkWx{?kM?^qB^}**d`tK&SZk)dD(b;UpVJ0h$W42pa9)R!y8qWYi2nD<2(0;kV?r&!qfTMHn zU*nk2{H6JnUnyJP13yuJr~brq2~TrAho1MpqVd_f>w@lEp7e&WCh|&kBkB0_KP-gW+D&Z0%e~Pj(%{$py9BaA; zkB#Ivn-hXDy&b;}UXLlQZ~Lj*nk+VbiVwKK%{V(-l5_X(Yhu80p z=mUfyef!Sxp-Maa7#{Dl^=mWi{xQI;u!6hwx9h&Kf9SeJ3R?c8J;Oq8!G`Emk(j>K<1{n8t` zPzAd}97lgF8eZ$>lPXPjv%S53&Ja4WiWSux*FZsFZs`jfXX|gN&#TjpR~*ZQ(CQjS zRxqjKKW8C~{uvTPqdl?zT!}wPZmSUb&`SwUP0()k z=QpJM3{XU??$i6H|5BW6!3YR{ZaCqa9%z~K1I>DtcE(>hv~yq>l#f)ppUckGk8^xVp{Iy~=$-7|E?);JvVV zc)c<8GR32m^x2d3Vt>N<7ea=wOlRMd$Q@mU)|HlezkZ!?>oLFoOrmHCDGFw|rID7v zNGX$CXM<9SzZJd@3DzxxF@=H=hOb_ksGQd@wr>uo3FAdJACt7fp+7$G=s(EPP_|hJ z%-t@&5VGX2!-L^0@xD`Wm+Fb)_mN128)@WG+kdON#a~@**}7N}!B=qcmLCsENZZHY z1Ov&t8qnW=i_7Zkm0SO9khrTX!q;?%9g%;6PUft*s{2N5Np>?6_vQuiH;`_ zanupjzxy9c=p;`6p}Tx;Y83j=%!EfzsQb|{QWAi! zT^@c_G+H}(w~Wx4IbRbjAcIx~B?a_FZ(gtI9M~}e^INi}cV#SWQEsD!F-q|tR@xL& zIWc87n!Z-r<78J`KZGUFg~qB!*XLOghP<`M_l&e20`izxIO({f!oz4b_`+s|;|gvA zEq{467lJixH69;ezCxMP?eU$_^qYQ0?|`BZSAnzwaf5;Bw*lMl*o`{dT^Bw#OQ8c2 zVkmgnHAK{Vq!zz!zBCzoU}R8}dgpbj`^mVp*f#QcoV=)@5`{+blk zocy-kS9HmK8MmRNjQ%i-4{-8wVc90_`t-MUMPo>?W+DDyM{xNV=G<^ zAPmDVKwUu0Zdm7a_R5~sT%A0;IBLC_ z(r1egEKfD3zKI(xc3GS}og3^ZqKeRqcBs+-ylIH#Y4fGU=dIt!|LU0{|}CG@u&Qi~H~cfA5*BJNY}QAb)Zk_Rn{5ijv&!;Jx|=7D+x z{kUo+uIo$=6UM?Lxot`5?~h)-TQlk)zT9r-$wy$O+`bhsnEd+(xfT(JFNK^kyWaB) z-Osz`KFc_1eDK-&(FqknOiT!=oZ}CnP&DYX-T7u`Z``2E$RiY{SG~rQiGha4SzEwD z8_2AH4o4J}W!b)>0VYx9RADegJ@K1uH+LDVaPau~bKBK@vW=9j_aDa3TeiO6u;z~> z%EyL~UOtApyG-!8cbK20y)iS00X@3*UY%8Uz=y$=PXGq1&lf5pG9Pe$ zd1NR3e1(TFQZI0!ru4Hq-<@hZn}Flt0iF{lo5Ejyo6>P1eV`-tix7RS27$GepnsI= z1-MzC4sPuGO}o;yGeaxw$)k`$kccs9#V90_OA*q>$;k~i&63M_25m6PF1XquVZXL} zz5g6JJ! zLQ)U&7n{tM9^e3|2aacQpy41hN*`AV+2eZ~0dw-5w#<5XyR_-^#xd0ND#TT0TJ=#j zd{6MSkI!e>#+jTPc2=YL<-MCgd<$#YbJFWQbk~EH`qQSrI6s29MYleCQFDzpfMrWu zPy3I^W7ngK#Cf_z1mnLtfB%Um@cO0i+7$ajFg45-MhuPYfQ0Juol|5UceVqEa(IG! zoplM4KCuCEwyx)CK>Cjm|L*jFB;@VVVcU1MFc%R;^j4E8m4<(88Kf_hvo}v5|1cO+ z?UK5bv{_N{1fKK=px@fyIgl|uIb;HBn(-~CXI;`Yj)fizqoj3N-+tNLZ!Ej`&cd3> zNy~-LEM&4^=FEaEDsb0I5VB{d%J6}l7cd=tOQLboP(T^2I~|IC1@qOav%o5MVLVD{?P^xfGE}(A1(mqVG|H`fM@>q z47$PNmGs=12A6Z_BT zara$9r}KnH&o44u4DW|%W>A!b5nmBDG6|JxGnLeO~PGn=n^dj##PW4MrL>Bz3*D2-Vh=h+V-M^z(6aD6e~y~2_4%-Q6a)0h=Y0kX!$n!3*F*}8UXo!GsMlT}jcu|thOO(A+PW11sT#UUTV1!-#!dgAT$?K2TuHVR&4*YDXpiuF`EgDQ`ajGrVFOYdBi4IPaYNvoe;| zR0jHoN~WBHsWVzYy8ziCV|~Nms*Zr>3bLFiSV%JJeom<Znu2oc-wcCFUH~QQDOnmdljBtpf+)a+se8D*?VMy zfYZVV3CW#jXPpIbuUb#fE_r!twtzZ)ToUV6LG(FK>v!a((-v^)M@yF6FFj znsA^rL4E^8i~HLd7%phKjUTr*3znk<*^Df}xv5YQw0F{{&Q91i1@`l(=CgN|FRsS7m z4cl4VMK(w9X8XzQn}w?@)&cbnlsC64;jn0mbTC7Bvz^zKzVkvgTl=Y6>mMn>P#I`X zY+&w=5fdxkSs&+7@86u+xJAB85NB*iRVI;^-{1Y*>2Rm-e3auN;0Clx=6H{?YW_U* zuh+Vj>VPPVJ>1ybhQb};>fk4Gk}gqhyle}A;-XS;=54p6oXMvRBqWkLEo5`)sNHJiE2kDA?}m+m$0J+S=9XeJTrzp86Kc&J+OReEknuyy_afm&XSW?GqZ;v}OCr}geqG;*$uQJ6SK=lc`!04R zl){xoDfr@fzG)lO>xWcfYFN@9WpPy8pbdJfo8WESsmC*U2*u5tfdOT_`}}Axl06bx zFdrZ}m1~S0;=ZQ^kF>)(2qrp{O|R@KK%s%g2kV=gR)So?aMrIj%s=#cA1A=dUut_k zV55!sJc!KHP9Pth*^0kyJXEy%Adj;$GD*-sb6klnuCmDRu0-vnnb?U=j9V(DISD7Hj(v z74vn)Lp-vx;X^BMztfRkyEjlpPmA4ipS_)#1!(@35ruouH=|C1*ek`pI!u~kYPX~n ziwXsF|JTaB_$7Gpt;5#DK3pG}qosiEF{TLaQU_;IK_-7%3t5zsS&i5$d0Jp41ba=& z3>gw_pqvev3v3@SJ`UZI#f-c1sN4 zzueZPla4_-EL{7{6ls)e^!Ve|mvy!vjwV!|U+%cVrF6v@^S%Yp=pHq2g4*5^6EHc7PmRR~ zI7w*ZRqI%=niR5apf_Ra5o82eD=Npkmkk~M(zF5=Q7&*OH)o}$oou*Ksc_nQ8X zr|W=fYHPY!QBffj!3GjRdJ_G)=|ZH}P<=`XU3v!rLk~R^X(CO!5D7}} zRf_b^e~|b6EL@A_f}3;ioik@<&z?O__B2x1uC~;oZWH;xAU+96?28DdP-9Zb7x$l^~B(rlVH zn&W6njc!4^M+NyyR}b*WkZU(0I28c-)ucr1=@;M1YiVlLl$bMr{Drwy@xA0YTKUNX zxCvX3Rb6dgjh!)nXrx!Y&>i1S;BDFgZu58~ztMIYoic}RH2i?q`}|um%0#M|_g=gt z6}joTcxm{S+lZ51&j#4$kc|Qdc|`4~onXx8>qwk4Cs*1{vOC*PI^X@1?BAZT;55{=^Ge#e8W0x6q8U~Y|dnQ{X>oFxl^9f z?{d}p@3T2dPo9`rUofrs}3!S1}~o7cC2i zjdr$1`N;@#@Q-i&KIL|)%9(B3FnRT5*>ZK!GNE92MZF*%vGk1gy}tt%YdvKrsofQFH!S_T@9UMNbP>tCp6}WYn+!+( zWx^(l!M|5lo+zxbgSB6t`uFU@F{x_0EDtRxDoLe`f{SGyQk_QgJb}>gIV?+$>z*1y zk#KV`{MIx&X0F*4)>fjCO+NyZ9a6`4!NlGcEMHQcF_7DMeL-mPx_B6Eyn@s3cW0Vx zZ)1&0is{9@q~OHC63&u|ae|73=_6b%@AXOHN0Y39C7k_8sc;}gx{nHC7; zot+)?(kA3HI3gw%dv~y_({Xul%Wc2%!;&si`&^~TD0&VEf{dcH45e|%Y{wrI7H0|D zmvy^hSqG^PAFc#2LpZ(?Z%M0mn(>^)h|Jz z$;T9jx#Fo8_3(kf-JowKK?3HMR-ds${ zVunJU=ECuvot@=3)r0xAob+ivYxHoxZGO<1`~ia}25PXdP8vOgOt_^=w`d2MiWFV! zX3^LWKkju2TouSO_!cVbJz-&xs8a!@g%2*{Iyd=^0(Z!~|H+Tu&|zp`}^5zbe(fAvLSZ zK?&h%GW8d~hAq=!b}3nDJ`x_E6i$7yz`UPP@@a3{L+I}O4J_t$@>8a3VVkV|h&Cf? zX*jq2{)lgT@t??!l-K=JSsO}GqnJEM)1z?4Zy-qM)k+ScNUM<=DkEZA=)&DZ(4N-ZuX6b_FUaR)G&}s6?`;$sbuC5szHIR&kG@s)an1#Y z{e19z`d@r~k+bD8c}R|qeR*7JV&c8K5>>wgw8XqD9odz*H_6}pec;+^+8uF{=aT%RuSF}b$xf3J`|S2Ymu!%o ziSrKSi@KY;3-h{XVcuH;iz(vrzo|@J3K7=&FQQ9-%v!;upr5wpDou3wHpnVx{V&^Y zYe{I_ffaUS2HJ;`Io5fM{;=(xVga&{d@`9CAQVfwZ^k{>sAy@Osn!t}SvVc{>xSO7 z#s_klU0oeq*Wa5hT$weVb>R6xdppmOyFjnnYficJN}grE6f^CGT2AwLAwiGP-G!f3 zQ=3MA)Tf48qOAYks_+GF)obt8UVwHIvDKERuUnt~h%;W63+QNWwf-0(dL(QeaAiZX z8R`BT`SdM+xn){k{L|K&oQC^*;8JB268DGp;c)W&kyoRld>0r}D$nXW<7BT=%$b6k zTQ;UDX-yH&`@b!cwK*a0?~#N~pj&mTrr2-9H1K%~Oei2zYAkw-aVqdlP234c%mg5N zg)J1lp|Zvdf7kbx@L|q><^A)XH}yGvED$^LMb4I;)cUA57GgFbI@0hv3pxpzK`P1K z)Eg?lY_!fP6BhmDS$4*gikUkTpXf8uof)v}9#aqh4r{#7RONAUWR+*|)7h_!=k1cU zG^7>mg;hj187u8(oeHR>i}701d;HN}LH!5zpHusiMOQ&1>q*V2DS->qHeW?kK|FPG z2px&^+SM(=f@e?BcCI_D?r7OYFfR*Zk+v*5|GlIDee_+zr(SlkYzo}tvoAX^l zV{f$n2BNRF>{84N&Y2G{3si9Fh9U2ggwgy%6IUt_I-Z-BWWO_Av zw8TbG!JzwPR678^gvuVJ-!P-CObTh?{mnl$y0aSeRm|zn3(rYUtg`m+^5)+$Tit~1J1GaC-?Pbi#?Zk-fJ%edMZD7;q_dfQxon65V+lWCiVeFCkvGr;u%PMkfdUwRL>bMQ7;s3OFJ1qA#^CAGFTS^HD$v+yKJrbSk*5B8+TOe0-L=|TXoeZp**OzFc0~T+6qE+Sbu5SPR z?&+B&#VVT=Z_P_{i|L!BlCfQR*LWY%deL(0COW0|Rg`n$j|0cUdoe%Cthy)H|y?V`YR@a%2 z_`+VI6CF~_-48emG&mXt&ECMtlI35{#BJTGTP+;z4iH|B_qleUK%%)qI4ocZlkLSZN_Agm2cj?gXOGCdCo!LREP7 zMTPV|TFUNNd2!2_zxPj~6|N@V^rQsx)b7C>ii=%+(&ZF4#8?>ZZ|HXRUqB_M4y|kJ zxQ7p=H3t5Z?MQUoN1TmKCs|vxFtZh zz38v?O(CP>oyjWMo1R-oW(&*<3>JR6PmZ_iZDM8}_v2Fzvk_tr9TNZ5pR~>c8X)y0 zh>}>XaKXW=u&Dy&m~y$fOI+N)5_=RVcU-L}#BG|uC#9^v7BDgE*&vq(bDEFC*)$U8 z9NWkXLxbw}Hz!qx#&$&O5&7O(ssjt=6Fpv7Ro%N+#Tr%v2ZcF@CRSwC9@rG9#)Sr?-QEu*5*trf6%y3EqMN6#dh8xp7nA1{P%4#6_^T-xJ3EWpqoNGg8Nk@-5r7c@)o5< zoD__I|LzM1ch5%p>uy;?Fuw%U z&Su+{m$zrV64fm-HDq=-HV! z7$ijVA`H(kpZsfVf$92WTG64^&JK93ykyhc;gz0ucxt{iA*+S`tF5(iIp9sYdiDGc zDRWTmiW!x{M&T7$}oInf)gO9QMWJT>Da`o%3ShvKhOl#sA`Z^Om@E#0{CFhw-WuK2XgsaCoMpsKA9-b>;@0 zuD&^!-?nzf?Y_)!p``!bF-0ho1s&((r~Wi;48Psj*a5MM*;W19vJ~S8QK#Y+N+(V?|G=^ zME|s4{@@&Bqy}ATt(lNo{vGxbDUisFPGPV{ofl@%FD0?1^Q%8IA`8~QufClA_vpDa zRA#q9s&rVwdHy8sNvc~9!C183969C~);#w3IL1Byk+)M3VQw~^nGuQ;>)Eh3p0kpd zf-lOZPhXUD{k>S`M&A!Hr56q5^Wt1ZaX$c&|CP-(!Z3f!2rQZ0=>Tb zLi3Zn)J?&KwU(C5rLLzUuja3FK9UboTuL(@Cwdt%)Z zme#H*K>BTYb(Kci0*BsRGepGL4e!m27|<0z=L~0MR4S{(3&wXx8IA1#59+&qo$m(-a# zNH+Mp`rvD`UEaXb44P<(*IACy8r(Qys+unq5eCdw4xFGW^BHgzZHV>AN?uoJGWyF>IWc|XdD7Aicp3s=BpE%3W@fIU}q{^qmsl z*6QuJ+h%7Q%T_PrluK@#{pW>joS?edD+W;l@WCWDUe`2N$bS`x?R$nd?@as!>1& z3=ZUkG%LKQP*#XRCb{;K&XTWD&zIg8T^+B<*U0|SI)bVbxPC@ads}K49N$Ix$m?)E zd~UA=SqwD__@zyV@09Nu(q8p9{9t;!)EYm@sW6O^Zo)xC?!j2w`f8|?hCTDZErGAFGC4pPKJB&uiU9hmX<9LvTs^~dD#!j2FQQ=-m-}BDKgbt}mQH;F zz4E3OmN?B$zj!#@C%#$>wu~RTZ!EvVas2`cH)nw>n?rMlKJCza#r@I^L1vOK2<~+w zUvQ9MN3HUR%2?hEFj8BzE_|C3zJ+@KAXvwa&QFp8Zm7{>O84A9jMVm~KGDE`rmx{n zfqIbxz24afzM|ZBUj~p=a;j1C94?6!?+cNwcAQW|j3o}pOT-~~9!&nqN8WIeM2|Ks zP)pa9m(QX_l+>H=`G)7o82&~h*|g-@np^0wQN%kg-tSF|64EF=4FCU_d4{?Vni2K@ z&^PFy8lf|uS*8a11*vx>BbZX=uok)aEPPgU7GBHz=f};y+v-k?Y%}j3#&V%M^YJW1 z_GKrL`zlMkS4ugVjj*uhK*StkU`a?{eRS6h9A4Pg2eT z)0ghlaCOQ9OpUYfIhk~CabB&K2fNVIV&lCUSuDK^^k||s9lnb>v@Qa1sMlM8)bz9XpSHiU*r`FTpwcb zK$2o#I-Ke%zl%F+*_k77l1VOKTm23$>}oVg_fK|z`Kx9mXD1P79ys?NP=_mL5mtAO zgl8LGG*N`BeS-BwnZ}rVjYI76Xy(u@iW>`3EYj>j1MdtzB3J?^wepq^8XQI1Hhz=A z6?k0vkhmQO)Ul6{P=&LLOZ+doXH2-tOF{}o=~`Lp3oQYXf;Cq<{|oXa zY|F}tC@mGqWJUypBStniNg8gU1RnQeT0m(oNMY2{d<;6OTsaF3%(kC|RpInYL=X?AkMk;iG{s zO^RE;KQYOH!Hp<&BcmL(IKraFwZ`vsr_h~_yYp4$S`u3?BSpA;-h;KE^v)7T8=D^F zvwr{0L&9pxpv=Yb{5RQA$!3wzGh6qNlU8-Dn*&@;wBjd(#d3dxJWJPNFt$ICAixY{ znam8G>wylztfaxsCtz|0T3(@ZQIuE}sTmmU-ZZ@IoJ(K=t(6$OR?4==7+Hq!_4E?X z_<*>+%{Oi&`rm*`z^UakUyH6YuOHxS`1SQaP)L|xl{)-NP?6EtM!?N2`YQ2rw0Lb% zn{LBLW@?@JKZ5WRn0qHnKz;^8Qw*J4dA`FbLw->6o?(z^*}V0%I+8zAzEih1E&>xE z2l#DTNDd$~ltKhkKJHx^PkI19ySKL+s-&!F)ua!Qew>(p|G5x>uL(RobjCQrme)sp zHa5&~fkdT5Q&5VDcpopn!8joW`XMe!{=;Ml8d2yj{;Sq=Ttm{`4oECIJVhVRxW*(g z&+*+sdvR|+m408NlI{)PW{6kON@sOz6BDgl4Z>T$aB&#wm=!5nBz_VOrQvA)L=DjF zMJKz?z-arPfVlqR#uVpJ55>8eWS3E^m{&A7@PQ>YWe$x5ML)y&AR0&_L(NEsXHY)tdhhF>Ki$5PrKatL1OVVSd7S^)^yH(+7|z-(*QgS^ewJ3;xMFl>2;=t@ zv-l@1;SnOk%te)DT%kIM816UuR|u}Kr)e{D3Xe12#3)NTrIYf7H}#~5rkLN}@F?oz zpJaVoT2_+Q$0uPw?$E9;?CM>$f8_PQEV%WK&J0u$uAA95sReeXkut#tBdr^(hJ9hV z_t~kA!g=@t^wA_|&n!bwHHR*qTs>N>N}1V2zUX>4m&U%V=MT>R@&k^>KuviB3P+Rv z-uDel3$v7yPS}f-xz;CqT&1jmrJOo(CnK;SUdJ83sph*qd?1Mn@hUKN1^~U;Rjpp% zJ*unbXDvzd60Ca-c;j4#)=~gMFPk;xdOl5h^1tNum$R} zF*7MLNuj+q^Urk;27*HW9p#zs__Gg(Pm6>u8cKF<{Knp1(?C-~AOW&;GOE;ka-v{^ z1WuWU;=NL4?|Q1Xnmq5J@l(wMx-0iC8YW}{XQ%Ik9u3rKJURzKphEaS1C*+23|fC$ zx&W`1f9o0dTZgie8{%zqDq&}@XS{RQ>wzY1C@;s;8WL;@0{}_MtlvGzewH2Gpa^s? zj}JXey(C0$Hhy2uz*BM%kq{0e99}+0Krh`;&1Izqc)h%H$?`86D5d_cUD&t|1TiX7 z`IVNsYJt+jiplE_MTp|RTB$B8Xa?}XXg5WCpfNL3c^S9&{N5f&mBhne;{w0J zRXL&7D-lb7_9%0UX1^60-yd0?K1yvgHFA3OBXH;dw747;%pNd?@1_{6K9L|;%2#v@ z&XS6*wW>W)Aj!IlIGch)l0?>B+KDulj;pe+%gN#lz!Q-!4i&t?1OdL5X|&*xrVkKl z+DZt@g!td)YoV@N<+&BK{z59sJpKSPtPp9Evx=^$s`|y*!2Wf;!r>JEd*YSnl^YQT zKq9@Lf2*w|MeTh8WEtOZ)*Kz{1mWWwsDNz!akJ%y#}y@<03zG>8fUN7cX=HDL#DbC z&MIf-$oo83#1zueiR6GLC}vLm5$mObf}Kc8hG_zc^2IM?0RUiatU z0BbHSMMnjdx~%g0dTp3NtAKh+D3H4cnkD&XE=~S!m><+A{{yBtCaziOx_zV%JPN;M z)%}$h05hzC!q)t#begK8cr_%-8#k7!%u*no$Jx;r)p7?~LZr*UMW=rY#@T(?OD77WhRmFBSr+cx3(fHo4#X30q-XzxV5FO;`t^zX0tePSxzq#95(4EN%JLjNfr8 zw)v^NO!5bzv#pgBem?6BErO+=JZ-G91nPeXvTB6l z_V&&O%%K9!5&0tu>zWep!j8Lf86gVjbv^1Xk;1sG(NX;@LSomWp&^y_5}=}i(^6oI zo&#wI{>c>>iYvTk{HRx1j?Pb7b-zv`UJ+2QB0jmhUx09&X6P#`l{P8ypGQ_~D-B{U zl>(fdErbgny1^;b5|vr@Bu??svU3MrbLZD`*7ZHyWQuXnUcMi^A@52Wr3Ux+|D2Zg z4I~Pc4^G+$BWN*^GCVQ=lXd`xFO&5e#6Cp6K(3W8BZ@M7!SQio7ZSwp{YK^Tb}6)= zPz(JOWdxYI>oD_2(3|JSocJ$EelRtt!Lh=1}T0f-*Xg=bnob>bwcK{^H8&jT*Px#fn?=K698BNVA6AJ zCm=3f_p?TfU%Vc(oW0qjbWV-{SViNc5Vc>!q zR`W3A{?`zXlg-}Lb%`~DeHc8h8{6wLIuZqN%JH$mK2X0r^Is(S>98L2(%XD@)hUYa z%5%X3H>$h?v{PrJPHSB8|YqbO15J$Q(Yuc)V6Yv78S$hVL`&)vcn%`8lw< zEz<|1MqUEm9;_Nhv%feQb4g98dX1*1&-0|SZ;QOnwcje?)cp`OR~7U@H?05gHEAri zvmGgV?LMG{${$pLf43 zES-0o{YJi3OiTc%F~PkDzeUGzsSfHS(48FyT2c9hg{vzoukSxDePqXJ z6GW`M9yOzjNiHQb!UOq`617y*=BYmYm}kf2iNf&Bg7m1l#Un33XK@Bh1B(PF5nP)| zE`Hs!XU7wTQxmyasMWhY~0vAyuY*19I)vHNjsjPCk&TpP8oHX|dWUHz79AarbKh^Ckb;5k!^ z_L4GU;J58<=NK$7x19@6dmLc6DsId^uxsmpwHj8m#dR*r!9$AWol?qd#hQXt$WNxK zF&b5UMshy09b>n)lRHWTdV>7PSII9Q*wk)4;ioFb7-gojKF>(QUl8&K7Is@b3JVEm z#guTC5-Ez++#cU%NMyb5WTvM8aJRUO&1)hRFBW9>WyaV-5$CrTUkr`C9O{DpJ*B>I zJPS;ZQ*6oTl|^aBw16y`NQdHt#Fr$2vFm?;?q+~&UVnSZFx`|Cr~?KhUiHmK5X;Ri&L**-Ud3ASfe`8L;y*8N;sM4Q)t9W?DlN6~3PdChDn9YIbUrM0%HBjK zg<6&!R(js_bOK{@Lij)g*Wuz^?kOP~al2n!}u)UL6sYS|5h0(?5pQH;KU)L=>aJ9G5 zaN+IW3&&iPj59@K5xO=wuY7GYsVOZ*;p~!S;8CV>wME^v>{kwXufO}^@+U@3-e*$y z2a>t%jj{2=P-BQi#gN^-F#n7{jx}|4#nlHtHUP*y4fsdm+li#Y#$dDG-@4GGcy=ot z<^l=%g*Koxk(_KrslOoyL@|?^ z&}JEOxwaN?A_)SfS_OsX$Nl*8;DhD+6LX;uJ|PFJ@BME`9qOt)7<&ENj3mrp;K>-_ zzW-}_I=)Ds`j%g^pXBj(49N8lgM$O&OF2QGwv2N@N{d}yf8dDK0<4E8@G<|R9tV`~ zuUpc4RfAE)`QUeRb7+uJkj$#7kr1rJFz{7GwplwCYw(GoXYNHBM-S zb?xyl^Lp66-npb$n(NV*=~B;dJzGgo`ZNl5x*AN=5!j40qJ#)FB*g0`_8BET?$M$y zg*^RfE1+smeycR@Ik!5Cymchm`%p8X@`JG<;?PR*?%l~ks&LSRR&P5t4Rz^k*3G%r zFkO07jBZyIPm+!p-W5Fz^6XN|M8N+yh6 z@C;VBRd#mSNx%}CI;Z}yDn)k07HSvkHj6YhVT(`k!TV6>0JZzQ7}?~3PW7zCSkXtN zq7m-4A2|A>sqR&)RQ-{NCk{<#`cpw(hCDAnavD1FG~2n=HN3cHmpc#UkU`gLUZt>B zIY3Z2RK0y+AJQBV6NS}g>sa4j9!M4UJREPReVB{@+-s79n<(CH{S!`NoG|QZhs`X zQ8;a%TJ=nnHW{UfzZQ0DJJ?HaNvzweWX&^NG*cl6b8`!dKm}l`++LaiD1be%Z=(za zXAg`(fM6`d_?aTSCGHd#;p(tNk4IEHFYhOdc0u#$4(nyl9E-3J(jDmz2NO&**sSvZ zXj@=0ZOU1l!>c`ItJzMa_O`bw!JW%aX5x8Pf%n#CmK{dKf)|n~Tfb@lj9Iq;i&6V#pjR ztYvpCzTB?%dX`0i6gJj$t}^xF8hSZpLh+0a;2M1i$nbhqR6mE;ZC^9?(8J}nZNRQS z!#Sx&IW>l(B<(HaVob^6Rg*aa4xA{?YjX51Dn+}UH1fcD)2`&+DQ?<3@)fh(a?$j> zt066`Nioyy`z<+q9TtWm4h#ffFr}O{5gNbE-7lb;kwXicy3=JoE5qnQ#JiVYuKE4P z!m<4~xYgKL9{b~&x^hIkS|BD^P=MSWrgGr*G0MofK6eGEe2z4N7RZ#nAHTmEw=S>R zr!`;6fw0_%zf3v_4yqNgrOe4--|;vOToiqp{n;kp%Rq*$;&TWss~I+`gh-(pV+z-Z z$)tLI*YI95$XT^@hUh{rE8Jyo$h(?GNnv=E@vj*rv8c*#xrwPqNynfKzrhn|sBVBJ zx52?d%L-#B?b?L=n@)>K^Rfj@1;Q%Mx*{5;a3>?D_kZzO`S;h&S_;hY8fq$!q<(~d+c4)OpDM)N%dq1A1|nQm(Ra*P$v514PS`8 zZn}mTHM*2@E^oM!$FW&nlqZfR+|&%KF;D7=9dhx$?JU~3oSe=I?b%=u?~d9xpZYbR zy%iV{*r(#4*3X-1>_pzZpL9ltv;P~jQ1P9~Abn|WPy}5fOLt2o;*_)gT_p>^J3j&A zlDMIg6xMGxS4R?G4jP^HyX)C*rFVtgD3xFh z9A>y)-I#{iLKGKWJN*48l0)CNtxvd%rANo+hv(=`5}saQbL9C)nl_humN;+lV$Ujb z-QQmW)sgRH&x{pgOmUUXE%_l?^#}89Nc}sghY}RUC-yeH@ygP<5P3w*au(X$rCvn- z{tYe@c`{E?e-5X-KA18x*eBHaKtpGvUR<}}YSk-?LMJCwwnmwT}>bUFyLDi;w zj2!0k5#FEx$HyPu`G^p%jcU)kt0QvVd%bZ-;#IZthS~T*LdLhsg+s(^(HAR@T9 zkA&@{9D{)+qods{jU)RnNIFQ;DDSO$#8T*2JL3?4kNvmNTGY(~SIV?RrRgo4X8LIO z%nr7@{=D*b$gt^njMNzl(SZ{0JZ!%U^Gr}~sVYvkW|1R6JK6<~ng{~qAt|`Q!nqHENp(|y%*LBokr_d3|Zlg%+%zAuJ8k~>eQ3Nx#GEM^e^2ceXlf9 zp2ncIw!1#lBM?axvhnr>I3$u0igguQg2e^b^6CcZP`7e-EU2(Rqvp^tSeb)>Pj?2E z7j?bGVmKYeA-zTeeNy3=+}<%b+~3Q6rk}u9qY4OOXX#ei1jue@n1uuy{Z(_z;kW5oYTHFcZ=QA!1IKBfjqH4c7l|6 z>{WVJOCeFPg3*6#nXz`UdQ5*8a_gE7AD@l$X9h73(7)YlT@e>w6&O=qUjF3ClZpx# zkn@9KbcX7M6||rlHAn{ozaU z#xJLtslmd7pGMf9bW|55@A;=>1$;v;)v;qipt3Sn?``a$?!#kHonrD!tGcwdej|D8 zV1U8<&@O^$g_WdZYFLU{+e{QXkaGX$e_e}y9*;w9@sm=GU5m$WZQZD@*dT5V z&`Wr_9dH;xKy-qkGycj8fS}Oy`6UDIgGd!|wm>zMjd%}u9iW3Fz&J(bA2rhFpcW3P z4i04P3GyZT$j)P5&sTad>AZHd_FWlXaH$PwK1!-5LqUOyqgh&2x60ns)6?^`Mp{~3 z{j6za=)q%95|B&C91s!`aziQJ^P5Pnuiuyo6R)(NStn)iipvCz3@`2TSP?H!)GBy$g=RlBqCPSG4C*3o#lM zTL@-NnS1{+KbcdJIBWxe5E8d5a*N&Y zZkj@DIp$jk_h-)o4pr*asYs(Lt&p`MIKd;D&zi7R`PCamMT?0dtI*8yg;k zP94u;dyiN874ByAg1Le90tQ0uFL9NoCF{73!W`$d2_Eq(P%@lq4J*{I9Rz)4q#~TB zO3QI_P5N~nXuHTcP2&j5fdV}XjXUo?&e6Zd$p9#i@1-2kfmv=H%*WKJu%1Cf+#32v zGgsETSB^WUhcaqeROrory+NTA*yow%e;^ zLEK&Gzc1k}KW}1aDr^GuWQtxtKW0`}=sCu4bEjl!z(cwhY0jfS#DD%=F4#p`PqR$E z9o;u#-HLO3n2yKe(^)~jJ8>a3M>w>jj{6Oc#%NhpPf5Y|urF^&F}td|EQ#JeGmWIo1=r2C zR*93@!n%#FfdbFn35l{H@$lj5oet;f(&A#kV|&9pG@tJjXH)0Aq`qy22E?2CvF?&i zx+%0IUHRt`LFnU5MZ%ArBLOA-qWF0-jIq#S;^6X42pcw@COisjffrGwKCP|*Lgxw` zhr=ItrYP9@#}=$3CSdc6>1%M7;#^IYibFZ9|%)vcZ^j~&-Dc&tS(a-ECm2Q5nFH^+!} zq$2|V+ocD88dHz=Qgen1$148}R@80vNE~g_y1R>lGRtj#8fkjzf7OocoO+o>M0PKlKqziT|QYh}i+Km{Tn zr7Xh!iVf%*XT1hoC4vK)m(Dt@004)L;hkF6YjDiBCFkm?Ke9gHILnIiTA#KEH(zEA z1T!=am)pcO33baRkC~tl%5bebrKW+xdgrZ0JSZa8A1~GK+ng-7ZiG#ocb`jkSv}2e zd}-__o-qsGkSN+tHOf4rI8#7+@u-)lyxE?XZ51HB=Dl0ET6e%xpkM2}F^d~JUUmT> zkhs_3>&Lgd%m}r$Bj6h~P(THgb&1GJ#SBe#Y*vU{k!?Sa?yIAo;3Nh{`fJH4J~}8w zB-t61)ZgIlt!O@gUTYlxnFaks-D+ooW0F$?#Kz_2Wpe*#5K-`s`dm{6mbTVm3J>V6Xh3FB#vghcgejE|FlXt99-b62eh73 zvh&#uk<_e@y06+`=C=mMK07UK7ak3Y8tk<%1GvHjvE4u_0rXJ`0MsD5J6DUjuvB(+ z;W!hK9LvrcF)bU85sHx}S~1uqetU41A6i#DYXZbCP=4&p4UGp?UQnW$TYX@P2yHcn zQkHUg%+EG|K7sSDys3kCklzD8&Yp z`I9qHhR-dW66@I@fC(rZ`u-pPG!?+ujf;;DE+#DexCC#BI;9zsMQVb`5Yzza{Gd>% zDmA5?YGojEdin>>L`d(OCnKX?if}+A_4G`R2eWkXYB7)GGQlwU#r~yQ{rVAW0NP6& zPPmgZhyywIiSF*H{blX~@W|@^v?O-1=a-Q&ux~~GulMAY^zv`muV3i(jZ|;2hqr)- z1dkf@4OEOBx46PgGJ*IAeOSws>b;67VQvNfJ0ZimVA>CW(mN=jmiR&NeEVsN6+W!P zoSX*UY2;nVY%@{RxPeSi&H{1h#3>}1?FA`ahec!!1`a#>qA$VyaAr=0O4adi) z3U+Io3sV!eyVGrwVf`KJbw9lW%FhXN(28qV?&cCtLicXq3cJ0pnSeeMn>h*2TVh4! z2p~ho0LwV5?vN-R<$-LQOw4<JikZ((y%xXx}0ubfp{ zPE;Xm9v>Zm*J*RIZBxSeG~@x`5Z|N1>vDSQQ48G^;;^c^^*sH%Co?p?kY31n|0fi3 zWL;|eYAv{C!Kb=guX277F?W_|6(#9{-iDKz`osGW&!eUKZI1f&8!iXsi9+@ETZ{dt zt=fRgXEzK~lq?du&C~&_?3c-7>#|1>@Cxpz{z!MOrfTIHAX2yD^ld_9JtSVp<8Zj; z-@knfcY(uBJ)9PUx}6+>nC$q?$b&8M33hVjX5byYUUA*ODp|l+c;MClRhF9n#7UK+ zw|BQq%=M3;W6xme80Wp+n%@4>$H`Ro9Q*d*C*^B@J?S{7*n)rvLb&p&Pbr>qo-Da4ZRN_RllP4le#0|4p{}|eS3JC z9pQ&nUu7k>uF|D~R4!>_Aaprs)#K#kM4u&0jNcG9dkn+-o-EL9fJXgAWeSN_W+WPn3qteoPi^Bt{;u&#vt7e(4{gLt#gkgMT>`P*o ziYS!<{ie&Wk2=_8Y#z_>0lvOK>t#!~i0j&`B$C%*orl#7B!lzaEQTkOv^FiI#9g3R zZar4#DJE8p!Y@uV`gGVfl=9W zF{)*3!WgS2zwrJ>j}ORwS#x_dmyWjFi3z?ZQVu~l{=(HAwdJ_Vk4|-+{5C%Rok|6U-k7bX zpJB(9^m{IAOe2pC+w6AK&7xv8V;l#pAaHJNwD#!efZp4q2vE*DW?C5-JeF{%KXR}y zot;0LnqnvA)0`f&Lmb&9YF~o(hFg|`PXP<@TU2tD!>_z*`HJ?LD779`;n7U$iS*R7 z!rE=*6ytYUjdtw)Zz>!;AYW#!sZwLZ3hd;ShIucl`;(K4?az-!^+j`(^3-ld?rMzF ztLBW;LnXkkI^tsW_uCYBj;6t|3N85sbBTkUUEVHRgVnE8(Ul!|8?a)RZ*oO6%F5uk z-%eKcAFHIj6NR6mlPlF;N6W(D=Kk`dy9921oj1`-Q{caUemPj>X$p{93e4V=tfgmp zY-ZR{4@Mt+9IDmbF(_eF`3z-0M?GCgMnVEHmxD{55^laD^&rvWj(<<$e-xag|5hWM ze;yxQuuIo2p@~i@6k`Cr$0Q^rEIO*EluWIA>}bNZUo&&3xYp}`fu=`GfE3j!7*6s! z;cv?H4*||x^7_>mu~USDz9qzsOF5ZeM1-E@8vO6oKU$=p9+T9>b2f(-iOO~51yO}S z=9%Ozw=;+7d>_{<a zb0q)7-hoLt?gWAF=LSj!Rxl54u>sdOwa@$C`db<~s;5{|eK@1n)icHEj~CYe%_6{+(peXlg*Ow82?1U%I&L$Wr-qACu-$;G`-2|`GEL%VKq9i7{_WP zSJnLOxA!R`yWAufhh}7M=GSHXAh%SoaQbjfklkwedJZ1JE~t~~PIWi)1O+8e7M^3XRNmo1=mU&nLxn}1ooV_`ekX8$aia53Uv9A3oY8~(4XYmbLA>*LS1 zZ+SQAHZBz=X=}!9yhWN2ifE_IGz?opawm!?p)$3L#x==W8kuNN7*-9@QWV1yVi~vE zFzzaacE!t{b7pwk&->@hd7g8Azu))w`~JS?d7gR3NqXOCr?#QNh0A_zE+Cdd*s^*eH%#FK@jPM}*oY{*zo~3uoI5e(- zU^L4=Q;6s{yK)Ux=J6@&R1Is{h$|!Y^)6)uR>>gsMK!B$)D_KSH#Pvuz8Q}y1+zr_ zaMW#nY8tSX#rcWyg%&QCOt&}qvkF+RqM)8w9~=2hAx;lp+{PERXw}LfuJMenoczH* z!vv8Y$HCk}&~HY+Mscm09^-X_t9-TPorw?pGai|3YcF}ih=PptbT3-6lb;wwa+#IS zR_HhLpXr63N@xeOthZ(8+ZxD=tp=o`PnA7TjLs^wEU^MsuRtFZN76c!2^W|Ff~E*= zSe~(_Y(&oUpDrFL5PZYT$Z4baFT+-fj?{&QbyZ0NMrGz*D1BE3Eoa4S+O!E7)2XMU zBS(nJ)yQa>CB1@l=y{KKjS`l(Ck!&6zLTi$Ae$Hkz5<_2ET+$;OSU8_!ZY^Wk$I*O8 zh`UGMU1_AQh1|?Mzp>&!N`$EW3{_lKR#qPfh>3>M#Ow4=6IITaLJx7_au5H=7q#T? zA4waI#U0p!{#rpxC&-&bmA$z{>|idA+fO8|YSz{DaN>^V!^20}OkQ$+PT<23T`Kr0 za0jsZF+z^GWHn1`rqD4SB9yly^sJs{W@i7%I~&Zl?HmQyQ$Q#&Cuttnj?Ixl-e9TQ z#mhe+mv11fq`;hFUY&IYul2NR%3TR&@yygoPLIQdH}|5p56y3;KOih_ z>Khsu;Co~AjJ2*MLsdgwULHmbbG4xrQ_@ITjNZC`wv4>{ghq=r)!s~M<#ESTsR4`eF$#doDM8>WR4_}i|hD| z$F@(Dg}VaTnz@H<`^?sf9l2)ruiy{Yht?K1P4b8Oq4A>jiSS-B{og6kFyk=S^c*vD znN_P$_f;B&xQDBtz~}2C+!MaUT>?rWDWX{CWQ`Gcl=r6k^k<6?;6V`17$`K$f|_;1XMy%v@!LSb^i<&eMsT*t_j`io z#si*QGi z{{=#$7WyEj-1)*;4iO z{8!74V7UutKur|i{TYa5yzDJ2iq{X3#g+}g6;6)3dlrDwjierHBd}6nB#aC4Xvy_z z+~p;g;jM!9#L^tI{-FmHaY6ODpERip$k{-oU@{Lc=6MhYS6RZIa!?a!oWoT1H z=@81N+at7=0@mFB$v!Z~DGwop^qbA26f}u`k(L^b3*V}qASWz%?4|||5JjM* zdf0(l02y)ZtzpQuoH6l9p)$8O$KYlNC=3dc zrsA?w0rA|g$JvfCXh8>4Q&Tinw2$GejC0cl7`>^eoScu=?mjp8vDII7=pnl0BHg|W!dWWJO_fxGbGxX`F@XDPSXJwiFeW3ndO4F+5_oStf!PLP;i&m!1L`0{2&P_1 zf?u~l{xqN8s$kJ))`u{SSs*4A0}&tk>j(0FcnzPw^oeVsFJI zd}uJE<>ly0^2_|yctdD1#}xFu?NpPXdV5rcDzj)p&NO0mXW%S`U2~_+pI|$Mu4r0Q z!(t_nc+;WnMlVG$$F!5j?H_U{wI|aV&^^qSdOUuD73b!0=&%n6`Cnx5d z*tI%z)~Zqo=`jzZX1ln#O!8`}syzMd0&Qc`;Q!JI5<#lwd7j@cV?>2CS>ZUe-nK^gsfK6CVxLy7S z_`Y)H+p&vFvXQfPkk+&t|0!+wl;O8RkV4RuT4iV~^TjlEJPz0V3Wx;J=jkz+ASzAj ziAiL-EQ))fDPp0Xe}o2ZKEV`Dkw~G6$2xl6%-kVY$~QnRk_a0~-7L19$C?lTFqYtD zYD($`ND||qf>A9g+K?321}YL-u35Jj3#vmbPWKGxUq^u`eYT&93O&zd#A+KA`=^9? zTLdKx5MIE1?0jQNJx##6C^6X%Bu4ZAkf?;iH|sSP6v1no>FSp<7*RBEa9IaZR-|^E zRIzVHkNtgvqJg2!-bEi*`OFwdrIV81&+#r>=U04RAczEM!{iC&=p(20euyu1IR`Vb zth2P=BYk!tAokG0(XbG%ze<6#uNo8lwBG}~zh;jTFxC;6?Qa*4BzY>P_c4CPrM}J;zPF$LMB$eu?(y>W9{v5E zHQe}NMcIJntQBo;$l$w*Wt?rh@;uIc*RYIZeZTDy5SP!9q>4HnLrE*5H&A@Xk9D(- zfzvbq9l2+D=<}NIise(?R{Fia^yMCaG3K&>pP8B|UrcJTU<9~}1BQ4S?UDA1h3kcGUC<0QKZjo;3F6r*Pgmi;+!yEj+ zw;t=VV8P7nGw1C1_TJwPey=2rg-MJF005S(jD#uxJQ)VRr_hnXzo@VacY{AL9AtEy z0D!;<{Qia{(mJaQ0F;2N#9MVYgS`b$FA~dCw)?|@E!O@xmhQ6XxjKg6=q|;SK$yxN zt_KE7Oq_`o1Hy6k>7lr*uY-1v&L7+D^4WG)k~n=ITb;`cE{65_rS*GB|4oA0DgKvu#tXqL zMamaOLC2iz?5)`5grS`?8J&5VnVGq{LG$M~cl-PMPVqE>FT~MV94(X)>inb@L6|R| zqe8vxt*w(9M$kvCV#vml4W$2jy0f*lwYLYUX)-umZ1P0R&25wffcH^VS|tj@ZoEWX zdWys|BF{t4W@d;4E8U)ceyh8T3bZUm_>)k90^|c{$E&AzY56MoLPqR+O9~4^=l^;% zdBplxX%$s1r8YwCe{=ZN|HdM!eSDWnvjkz7TANWM+3W8IqA$3$iq7^!bQl8K{@mZ) zB=Xudg*!b84;<*7fF?_oQEON_+b;~|Cw8#sU|#H;&@~y@+t@G>*8O|dw?qNhxWPB- zbxCKg-g(;2$%TbMYyxQrZmiiH=V&_q1Cwh+h83u!W5|oWX*!t_aY9_~$$z_<6{r=Mq z$h^V*rrgOf_;`pq3H8x|YrkY5KjpD`70!36y0{pf%{H3i=QINF9OFYKEhdkL^*1yh zDg^iTaQ>|!#C^P)BdU<-1h8ny%i@T&XgUZ*0u^h*DHc%DdOY9^$&N;7a&;8`Hoojn zBIhM$_xijG$wBpKn9W=`?;L`#!kDnNpEtogwn(gnXl_Nzn^|? zdxC~-WQy@9ju0<82S)tsIl~~KDS4~HAmr=dU5!IFjJd5f>`~OyzAPx>@FJQ7HQwTE zhd>FTU}DzR5I7FqMIKI*03R^2V$@Yx91cpMLGm+Vw^HB=HghuDk|FIkV;#=H`flC3?tkzKDAW$Nba0D-Qj+92n#aItp@KS5Zkx38)&S z)AC8Oj(6vkU0q#U^OXD->ERP)f@c`-$R!dOJ;(pTW~6EV-5gUl<{~>M^Ua7|h8{9n z*hq%?1(cSmWVv$-k(8vl7vCEj!f=O2<|9jJ_lN`UQGq_1Q!c-`n4OjGpZZmvo`*0gpN; zqZqIDdmy%&ixy&v^0}?PUZ5Pyr^PVd2k!6h&to$cV|F0QFf^M^*FC?!XKw#qquDs; zBygUN(aX#W1ps#v$;iseY9sldI>^TF$&Bi}!puF?xZ-Tujt>bQbHPB!HP@A%;A_aQci(=CHSpejlaxi51zQGlJD zo!`ss?&cH6AsdbjTfWA0-|!&eTrvW=Rtj2b(k{rK1;yoGSV#vFGF4>3UgHMG6#P<* z9H;H=e`{l7vkXP_{H~s(PQF)mO(fSz`i*2{=GCFLfuzwmL~s%Y^$iy&$0M2_6$jUn zA*rzBm=^v~a;YPhk$$ZWAF8K6GxafdGc2wKNo;AH7VF2MXD@En{ceGwTB$BF7`vYM zg@j-pXXg$?^9sMjK)t~Iz4vWo#bW5vYHshFqj^YW@c|XbyGoX>ZFtxCMd>FDN6+~I z^x$OZJ9>;2YwnoBD7iY_xseaH9#1c}%qq)&j#*TVMu{()vh!1C(U7g0Qu$6l_g+dM zT+!pwO_EEm9&~Utd%d6>&;1^!w6|5+>6s!0jMP0eTDWO-9^NeSh#4M@EX4Fx? z_~jnZ0tlI$x}*of(W$Zoht@eOBjbpXpmPU%d+Kas0Z`uo!CFhX$Q|aqqvFwlqmSgQ zFFRH#W%n*sV`U($L2MP7R;;Dn^419A2Qlt3rhlSeh-Y_spI4-tcdIi0K?&wAN3>Zy z0c0SQeke{($gpXb$)bE;~eX=q^K0}`GN z>V_Wdu!xZ6HV%2~0VUz66)=cxvZjFXe{1b48aC;VRYCi@FN>&t+S~#o(=T`SHE@#f z6vs{lqCTlWO+U>!JWq%KO*4bG>vxBAd%!9ffP1mXEblTazI}3bHouyzQ>9mDAMapH z%o2w5{4A?WeD$&ZgAFlBf79Z@w1FvMY~XbW*AAZW(b3Vjp+_4jK7xl&66z-lQxi9{k5~+w_pf&&S}v&@egNDW zy9D`AxKh|?B$ezx%<(D{1uA&>L0dO9HTBaq3@@$*>Nt1?lFhK9}j0%9@!MLQUbM_DS%Q{$%c>s4Jr^L>Hn-MDT#PEHQDg-t^6 zw7$OnFPYC(tYthby*1%veRAhJaUXbA0Mb3}UhM+nMnirw!E=Ux5GFAw1FE;6m!f8j z*wi!7su957G4Bd<1!1B`y_ue#p3=on8OQ5dN}}flmRu<{VI7+%lZMU&Ky82D26K;B zZ?9x}@v5t^saKxlENu{5BynAMtRuL1nU`JJ`_%`v_&Ei|#W-I)65HTg+uIzQ zwtjP>td!+7QIRQwUv2v=p1k$5`ZQ{3BX!($$b67DD9!roosR4~`z|#B*)iN31M{Hr zzA6#@yDC|iN4?@iS{-vC7lv3X#Ht7t1E)`dV?_lA_|I# z@8QT|{G>ykCGamYixaHZ_GZ#tJv`Nz%M~DG^4bC+6M?VC`Ol2{Uik=_+AZJf-mEE?>t6hDw37TBgxk;-VPtfX*ycJc0OjzgGJEHkIqTEJbI zYgy*w(!?3vTz;TW&`aki+RjZ*O;xG%Ync4AByEqc5*SCBb}Ig> z{hBdrl8R+a`FA)mE79{YN5`@YW4fLDlsfqh8uUmR+Yb#>u!^_TNN|b!Q4^QpI;XuF zE3taHf0_uohXLeHp-HwDjOtBu_?7HLt~}faPQBlyaJ)5~h`j|dD3qX%Dk)(-JD)B# zP_$!@chO4M>;2^OuAb@7BZfm~G4D)`mgpwOtx`CN4s18xkN+_GR9GK3#C-&=sYF4H zf{f&$PhK?B6O{qlSi*&T^>#2{%bjwb$$Z zStRhRz_M>V6%>!;2magf^J(;eeqKxExb1k#AgSPJ${>D)vsXv_x1RKgh122& zZ+ZUbm=h!spPty6#1oeBo{h_@5rkccOj%J`l|z26L6^CWJ!VU>f3m1d|5lzCX>kQ3 z2}8ca5DFiu-nC!LPK?{;7F$}rw)p21sXia=h-tdn_}2%E-#|v5Itu8^7o-Q054$xj zPNX#XKKKmG{@ZT4w$IjSA;?VS{$f95@N9>foI_gS=mo6o+ZQ*X|J8EcDF|WUKCZJT z(CvL{&lbxb=Gx9LJF^Kog)!x^(NUGg)?$&gj9>OBRDcY2Q!n=8wREjd#Mp_L8ygp< zrljqT$FPAEu4O3X1~B3H25P~+NyX{G5I;6;-B6s*mm9#M4Qd(3B7=^n@pA99h^YxszGae}YN_#J*U zHKh(=%*5SDE{qTDN*noBBkf_Ukv3AT>eMXSTnboDLT0)u*}}aJsP<>=!)PUiqu;ktS8p zWBa6p1Aa~y&A4_7dn0$BvLJfmBSFDJ0{9C;G*PKffYTr7az}wwJzX6QILT`c|7GAN zDI%_7YbJ$pI~(E@nF*Z*^!K*JBW?aDC0EF*VUi8pxGYg*BYoIa+2--c~~UBnT|yYuhYd?EDYRGwXbkhv72*Njcl z*il9O)grzze5Rlgzmpl2?so2WjnSUzSrF&w7GHCyhv*>}ObZ_yGIX{HaV8j5>2AMt zX=uvGKmtgygMKpH-Q86%<(O(WxacpuK69~9)mUd_azbjIn3yOt?VjnRb=;dNo12>} zD0mIz6%@=hx;xFmo}nNg`dl>d+0OiN7)aZF6)a)kz8-6MyYf=dWsh=ISXek$IX&&J zdcLZ%GLqya>xYC3DucchyWBwwQ`Bg|`=t3_AJ84O#)QH*GG>H=U40F8ot}x#^+#MV z5fsAhZXeZYb@ra5r;b$JDK{{FyEw^L3bB z>6Wj-O@tub&Eqzzf%C2&ylzkLU`2>YjjxKR=$<4~*@t)h5ZwIoKwKKWuP8apo>I+T zoVl9{RN(V^qnGn7AE@@bAj86zXG>P#XP|3jo_Mg=*Q9TkMG6A%UtGl{3 z4i2Vgc;vD&Gd~}&mQEuU7fb9Kht!92ruDUkFH~#6Qo^dT9_DMWNr0WW`8O*&kCIon z=<75O&+gO@UNO&Q?-3nSXw1I1EtFk=*hh_igO>d-EqG51k(B_+pGyOV&vozl^=y{k zl|pozO}0G}l0!z?eh=#Dg^<-RB_L;jR@L!TcR@MA_B#@fIE$-0)NY_r4;d(XchPWg z8Gbo6YGVIbLWh#`h{17q}Q zvZZA*){W>_3GOB&=e8Ls+alG}tAwUCDC!hLkxTN{97AKy-=c;oz=JOphbj)sibGRU zI&Lkc>OYXX@{B;-)wpQ2OGOaw%JRhdR^ipl|OFIp0dl_&7~dK3x=Svx^Oe~ zm!Iv8c$GI&6n0`SC?}Z=Qo3y2SK6ZrP}_IuMk=?5hM4{5!cBHmoVgddSSjlHrO(4f z-JaO>nQYu%-eTn~=1~U?=(1RB2z%;0)4|>F)Rf0|*}TS#=A$J{2ISMe+)$9DML+P5gX2)C90zz2YP3%XMdM|mLUh6u@TkK#&5_?}m%dnxeAX(Ed{c# z@1+V;7lpMmL)54TE3D8?gW8)z!Jx21nsu>_7K6SjVU3@$-K_) zl;@k=2(m#jp(B~uw4kwO9b)C16Cu%|g`3L5M3a6-T!Ncf$^PiQ0Q}$~U&eDhshc#a z-mzb4>C8QG+M!ESIZtPaSRyR^H|_|=M@26d;B>IUh8nfPf(__&c<0a2t;-p02>uQ& z4L8iQX|cY3^3yzIqCtt}#x83K7dvQ^^)2eh+OgrFcXA6FJUs26KO2?L4AM#wETW2c z6&A|vE*A1PmPHJuT{6IKDJgF09TC?-zBJwl$H}jksiIZno-g3z6r@P4^mrH^B>0j; zktX^3a0$DVx%;DSDoOW7kGs_Ad9I4SN{cVA0D%9$0S5&qMxGvh-%} zRju9!+He}a`bI59Ho2osB{r|qk5q(6eh__%AKy1Avl9kqnR*&AcitBK1&s3z=+#9! z!Yz#SM^nb_2ddbIXPGK{X zaSCVh%5F{XbaE)Pv=M^V5PBVmG$?I#MfP8|EaJy&`zL<&jj*qIWTBF1sMi1`{!VIx zSvZdkv2nBW^Jqp(Jf9ZPag@!Si2vluYhH%c*Vn&i=m_8G2rNs+Nk{Tq%MqT^nsCB* zSaJ4bDfPxdDV%Wle0PN7*qh%Vtj9uNgGYcR3cVfS3!*kxJvMFi&MV3{U&y6svEFq* z49U2Z=xo5=d&6;ey6dVXGWoZ}s(+3BT7 zQszDpD)2BoRR_+RUxJP*O31{#g!_Q-iPf!OKx6o~vD|$lc5N*!X=LiK;A~+oRns0# zy^0(TFcC(@isQA6ZvL-62sMG{U3vXz&>N5XM6Q6} z5Up0d*&JDWl>EVD!10=%Qi?!J(GiiGt-+@q;jK4+j3MHc1UXLsel9NRXC%*kyHjy% zp0WAymB>wWei{YL9*-6EYBi#FQY*r?;V@ZaeJZ|%s<=hX_C9NU4aev;b#aU7RzcUa z!R5-|b)8ucQtyW3}?p65s|rs`WA6qe^g+#h$OcO(<}Z7yih8YE#%o87A8 zc}HZDp5;0yA^P3}!RIx6sz1gq{Ror03Y-=}H#ozSz9v1EtKI0ub)n61^X|`llk)40 zc?2cQC;~2Hzt8|-@s(~hPgh0UyQPnW7r>^X4uzx2q{IiAtd zu+|}?rsgFO&}KyW;)myCy5l|xv+eHC<_S{kP^w_q_l0QFOxi@@_giH5(UOCkK=1n zj^)aNlRU$Dz6Oh1;ZUI3em}3NF|n5|3272e6xS$t{M9`#50P1R4i*?#cQ-fU=gU#CG@gd_sVfb)9qkLM3_3hul#z+eV1TZo_ z{_dDMwJbb57v{-O+|^|fksI>rlYoAgawAxAh(4jLfgz;044DZ9-H+GeSoC@Xz{V`Y$xL(89bJQN15xo*T`iabSdvrjOjK==pGZE5x{*6cxJUkPR!>-|##v{g=HS zQS!pvlRU|7MZ|^svpe5cceq~p#MK0zRpf&db(90Y?T|p>a7_vs*p5xNuQT=+^c=G2 zLTcUq6dn;l@y0Q$u5NbUrF~$)Poa@_6Wfs6OC)`GlgTALSipq@Vf-_XO^=It4uX^$C z)S}uufA&F#f4yT&Xpttj80!M906hPxnHibfl+Q8l>usu&)^y)Y zWj-HEFbt+N*Inn3F_H1F`ho0)5>)Y3H?wVSg2j1WTjxDaL)b5d(+BeSr3F|#A zVs{(Q15)I97ERTlL_2Ep!7w@&TT*VrA!-b?$Ryc<#I1*Qf`~+v?po7 zu0_ynZR#mM_Tq_Q-0dMD_}X;WNI8~IW$l`!KVI(*&!YjzVvfg-D^rJWeB4+VFtzoM z7H|S4&2QGF->A;80`7tkj9^XVA}6+#$x7`1#|2onNtnsF(RcL<+VER5;(J3bW8E;8 z)!dV&lCCMah_SK|^wD%ehw9A?EFX&hdN*u|2*l5E3pX+@S;NNQF4E2tT@yuZvbIJmhQuP4ZUa2!rA-=^I2ULNpIa|Z|)aPG9FanN5Sdda%YO2+4nOO^=Aek zsNM8lXCdFvvT;{_O+Ie--Fdf3Du)mCs%d2)mpWU3m!{{CHr5vSlOp1n?_k06WTaJ5 zx~Ge%#c4wCH)#-2%8frcL(UB%0}VRh78S|T3uiug7IQ__otIdR0)V;idP=j&MWx@y z>I)fn;R$N*IgrMXFR2MwSz8m6lk;k9^yf=vRac8VB7>914vV?px1ph-TSs03>>xB$ z)U6@ch6NHnyDUYzwT?b3?t*?D@0~cRn50I6NWh{LVM2gXNLl+doLlP+isR0*&_Lp^ zN&YvotVE2HEi^~;=}$t{&Pz7lu?5>dz*Vco8SQ1}Pwih&tmk~~v=L3Wy=M4J*gxtk zJMYnYy>d5i#m4VlU3lo%IL2#eV7YYc-)ra<=M;BzU>>dPqus>)aRVyfj!0#>c$HW^ zsk-!^e7`!vG%bvyH!gB;WGq3?_9xZg%83bYW?+z|nY>J6PWmuWN(CdX(UphJ0#>%D9j7>Mp2QQv2~G!L!e5=h&Cslbpp^&0tq5`C-k;F88;k9*WP0eH6JP_uY>GE{2ypb z8yC-amHQ@>S8E>7i|iz$uC^lg|1QX_Uthv-oQ}#m4(yqDBit4YfcF9|ZAV_~FO`r0 z!{*=RUKOyD{U5Dc7j|*grteXif8)pJ{JHVNC#DTU2J#uSy5;IdphySwenzhpTLl~j@$yp&oe;ML*r zlUbrJpdosBrHByjv?^Yyb74qjj>3gdLetup%XRlPnE*eAuHxIhNo+~ka$V-=BgXf% zwt)5vs^s$K+tR7{2LhmV2lXRo-CgNr^Cr-GeN(FE`*4=;88PE~0`=K~01i*O#pGrv z9)6gxDL3v4hNm|^1L*pB1DGScR*3$JO6*lKZO4LQHh8j0eX7GmjqwAXOBu}F`UApN>nNW@5|PM^Gi`#SwFMRpmi$cA(Z zbyF$O7-B?>^c)`Poz=MS(s1X~B5=-;IQ%QX zRSE3ud>O#VYbM9SpUO^^YkJro(n31`3x8mne?kY$rs6(*C8{`y$8Mt@L1-4HE~cr9 zp%|OkRvz9a{~Ez{@mPTf{yqw6?^pbga<3Xy8!Ru^shc3@WJ!iNbmsPT+grwYZGvy6 z^S3yR{65HSdiD2lA=ATk9_cp8UE6+2r^?kAwJB%5Z2f$yxr}yJk9?wqdu@ zq5ocU@FsurGQ@+?%jLj+q)&CS^|8LK%P&V%HTg*hKT#2(FyXUb^~RW+6np&G1*F$l z|M{FqhZf(jp{M70d->6&tYqvwGO&Go(|NFe{rJ~AV)g|Zfw)SH`UlX9$V|{}Do#yL zM++-YXWWPqhGIQ`ZuEP~&iXa2nl%k0WnT!tH}qvfh%DZdOyGTs*WHBr1gtP2g_Mj; z9`D^t_C;h;9FQL5FcxF-aWL+}QoF<>d3Va&6vx+3%8Zud)u9I|kkvNcs%O%67(mTr zqE5U`@LDSvn9@LkGG{?@lO3}DzH#>gfVJSaf83OujXpoNZ>+|l$p-pQ$0T6^AYqasj_`g`?3Rnkq9BR}2~{z8On!dHS`QI`-uEWYlw_9-JHCC{@l8Kqr1I2`5vd$yiZdZ`Te(cb;V7z( z3F)xl*k?!Q55Ku}4EF2b#7tsIB*5I!qNazlt~%TNOzCL;f@$Ex+G9&Xmz0^E z&pH>TPB}4dUb|q&$wHQ298iY!-2F7N!(F{g7AQm3AdT*vplP`Ab!U6~ z6)EZI&E08KL1`&S?;7Vjq5(VcNJh3os2{9f#q;nGJoU?9dihdgD6LKL1H7W4Our}Ulc{=vk<4i!#(fZVruVLw~Dn!(mlknDHWuUaD)_k28G3g2@3@;DeLxuciMwi(#BOevEF!UV?z>Kx-hcqz7Jr=ag8V){SR!N zD-@hg*AvdMo{ z;#dW3WtO)w^p(2P!X+&&$9D5-GM?xSK10a+s;QeqqvJ6Q=$0a)o@C3qZz6AZ14AZg2MMP2PcI7hmLZ7u+XoN ztN;B&a&-`dFf>)v_kL?Mvpa$Uq&1ypeg;W9Akndqf)ON1fz72Bi8?t*M@B{z`00-i zVlyPCQ}Hyo8_loSRANrbE3UQ4J@ByJDapmxlPtd)S9296XxTUZ!{1MFuaU2f74Yt( zCX-V7{)i>y0T$wV{^}XfdXk3Y<+>Mz6L$aivzN}`g#4202R{8uO}bKrrepR2?gq8< z!lh)dU0N6X*7|dg$1>~I^ZpQv7q)oHUPGf^e1$cL7D0A z>0=LvkCcbL;ZI90ae1k8kxf2#9`LtdH}VXYm!M^8S~0$DB0XN`nEh~hbX&tx}9^CiXV z$|@Kj6y0`TKvsXqd=R46Di}LopQgk1`F#@Ay|(OhycWA$YX1jCZ~f&kwy$@l_bQ87 z?B8aB^TER!{SzNrV$`SehgZ2Y~3kmFr>dQv*QAz+ejIo0s%jMJsGAn8DlfV-A^3A$rbfdDQ+!Xp(f(MJg+J zn7}uVp_K%Eb8CetyeXby(}y#WvWsu9aadXdMacbz|7dQ@KtmzZMe~qW2^@78UBd^Ys61KKpC z>>vBB8^#&arBvK$XER`SFP^q^h=YRMrCwWc8acADmu&AN*ueZUpBA>D{4L9*Oj~XI z)Lg`fPIwbDbe=dYENt{$Hw;mdet`$qW)@(-jO*Y3aQjA3FdWU`y>jPZa5Uu%K?C2% zepePtA5>qjlnMbrOeM$iB@!U16z~P+u4VFH*#$ZP84?=QNjVY~K?07~2xy5ng!{AG zxXx?56@)HsPy3EkhV>uP;oqM)M7PvY04ayJ2oR13r;z4G`iBBqx1 zybw)mypKoqnh>{&hnM~RBkAI_Ehi_3dR?VTK^XEh4JF@V03!O&U#4Mh%a zOK08vV1{B@oA(#C?wzZ&=f12tt3$a0sS98830m;M(=UhXrkI{X`IG}y{4Pu zuo^Lw@;&b*uy){7w&d-7jX(m7RyKVV?FIEjSG~G7rCL0rFSwu{kEDolRcf47<ANRQu|c{H8cqMfWgKWEnL*707lI%KXf>rl#D1yVau2PB-jY>57!0RT+D3^(hOE4VRFKu-wgcuiJp`5JNPA*WPu!2OXl7H zq115lyRh)#JV`0H)y-a5y5`@yV8?XyaaTj|^}|N3+p>9^9-De8$=$u@Mv2JaU0SI> z#N#0CUg{r70aFevvCYoPUdx8K)@KdZ2$43=FWeC~{9yMN^Rs=UGJ!|^>NL}D<;%@P z1--G|TW`kkySmCA+FVl62K}Q6rhu@}h>y|ny}$PVT8gDW@EGLY*?+&)?;q2MU^dpGTEU!B49G+(yZQ^K$!BZ>F?wJ2nBc^Fb7~Vs0wPo(j_(Ke1aK zrQV;72E=ZBUyRAc)s7l$TIX95pD4voP~!%h6)cQN!OF#tJaV{Hg7nV_zC3?- zQ0k%kF@=F$3nX$~g3PWnI(uu&pmO+bb=kXDGR@9=?={P7{K=9+(ef<1G_2&Y85(O?i3h0Jr`n%vnL3*MeRXtTRDWo3JWPM_Lp0WR= z4M^8iVmXzv>dg7z@^DG)pP$cm0W`xsDO%FfXi(bjf#Uysul-I={V(;0V<6TiQKay~ zAI3^JAvk1~L7c0~!y-ZS^mIW%Up1aRl47`n(x7_Y^=7>{vLJW3l~hGfcs>1Kx|}g^ zc=O35MvPyg9v77tuUgz7WA*R(wGhymWOPaoS7HH=-Wno=>m*N9tB6|#4P@y>wF(4R z9cOuH8U$WO6*x9(+zdla^&wGzsmPrMmQCF!EJ{Y~Zc*0?z^RUZgB{Y|Pf6i*M*{!j zk-NVr(qt0UOt`%KLTF&q2+cp1kx z;c(g!1?(k8xD3IJ?4TXXomNSngkQ7od`LekD znDgz685QpMgcqixM1ucb?A3KH4B+>^t`u;Xo|;M%@lMju=eL^65fBuV9~&G4f#CQK zQ)#0~TA+aa9Gz0Si1+E%=)}On$jC4Ela0wjEt2zuILsUv3p?yFT+b5F!k)BlkLU8) zFDeAsYiPt8`zOmHXur?xki+3%TW>U>I=C_svFtFSdXb};{N3FwEC{OiOaTFI-g}o$ z(8oCJ&2TvX(ZtW5Ia?5;{AJvZdYvu%vwC)}%1I6(F*kq(XlQ6~yRbD6g#G^;CBgc? zQ4NBGI476Z&dQ3x`j1koe-?ybU5s*MeqO;Yxj;X;j|PUv?G*9-dsf#$r`8TQsPHrg z2CkVwFx3(;iyY&`YU^z1%BoNKpt}RrR&b^wX&O=W-VvcUgv&m8m+?M|+y=ZFoPx-z zg_3L-9Cz)WRoB$)roB}&HOwb+p-Ki@xFCI?uRoV>z=G+?3m~hm-$}~E73{}Eu&rN! znS`&6O(6ye^q;1D@2LC0>QaOrGTk>Iu`dG=KQ3u*k$gsWxLOUH7EJB*_;7nqP*pVv zya<-~By?&dm&-GuF;&-;{v%@L9GD!N4mPYJ^RSH46-Cu zNJeKnlaOVwu7*G$pp07a&t?@ABnk?(w$4T(;V$-vua3>j#(77VmeQfv(O*>m?|D_C zSN`=%|M@G^ipmD6V%MTyK3m%?60ZL>ayi5&4w6|>QSp~iZbC(GX=7E0-BN19H9{5Z z`DwAvcu)8S>;FQQp!JVEr-Vohg^5BihicOlVqJLp*HlLLa3r^@OuHASXJug}EMhK} zOm(x6^g$y{zn%1;fo=QjHSo*1@YCA2(Kl!r>h+T#p?HUmj&5cYAGEKKpOJF~?aMPD zpQ>bia!(~$i4LX!(_3ed}C>TRGMIgng>Efz;s3K!!y~fpiR}c3<14ySp@txpon1xLr!lb(!&@g*r4RBdnsB`#0Eeu6jQdMsAA zT2$+bC;I=_3it@-?8m33Hcqarn6L*1CKXw6@v(z?DGiv=sMMdUentVNmUIuHPOr&U z+W9&GzuODt^j}8y7z3XoBFUZtzn}X1M$`A|HR@IRPKsFWvRKztRgEG* zifaLFw)!#a{s;4V32b+h5&VOTo9!}12rkm|74(dNU}c4uHpQ;mIO4bme?;sUwFD#p zx67Oa0jH($4WR^uf)>}{_wkiqo&}t#Fl|r9Dfg>>hVaO+;Iu}S4qXv`uBv3vtC7o+ zPyQzHrvroEi zys4_{jF`=-f>LfS(TveK_cvwui?J__2B^TUy=CDvTC{BKXM|~)7im$}gd%6nnDKw{ z1{>k&;nDDF0ZTkSJD1nK-zn@~#5Q!sd7sl9+dh1aQk9<@78Rwpe1aZgGN$%s6mEhv zIq~Ak{Gh9A+b&3mRepAIlIIYgmM&uMYM(odn>U)d7Vbi~gQ3uabzCNUeyeEwLK+=P z&m#jKm71rdOqN}p+9kiJ9+=u?w;!)JkXq70M=kB9E!dpH@LA2R>A zos{K+we2>CJ<}Fv)`J1Xdg;Jt0jq|j`EQa1jx{d%V}wsd>8}sN53iQKYThNnU95M} z<0_+OwZVZ+D=)Ctq&V*26VOJvKMTgqoem0gl!>UkHIPl#GwUg#r4?^2I}}dg`*Cwf z&*h+zR^D77rYaHA&&R5%64h^@7L%xKwVSmHV$M3rT?U!zE>{p@91o zldO|U5}j{g7d+kmO^M7}5pPIuEA+`F7% z3{H+XfogS{9zwRj?fb)QuS|Oi0~v@^z3BGY{ootFS_ILLF@I8Sp;9FT^es>~_By%h zRxQQf6isEM)3TN*^V)y(mQLZ4{Bf|wV}s5NW&00I4#>s`!q7U!@Qy#teT`|wnnR|I zu15N^HNV;HvSX`Q!X{G_WRT!(&?%3omxh@js&^-|cO5P{fjm=J>$#zrejZg{lOIP! z7XRsqz5U=?5Al?R!%c9@efIn!XTK?bJM@}Nx-cX5WF`c(>Cv+$umFftyTb6r@3G$} zeXG<(@paNCv-F152;Yl2iIdDBriTV?*OqL_*(#eMW!~~E{k=*wsi)1{ooM$tO*y*=~KN}Qd#csNnC{6ps= zq=my_$oI`*{C7jijl7>(Z<)8|Sa z0CMqw9|hJrrmK^m7{#qo)txG}RA=URV|6W*u#)n@kgveh4-%Ng6R|T5{=%-|6pTtGH5KoL*xIA5SZ5#;y8Bldm z`Y^7{mo`_)m_nsxwRxggWZ>Pl`syc*R!OToTU&2*#jfpadHX(V^4*+*LhQ+LwCk*T z1MQ@5&%!6Qt|zzPfG1sgl#6wrMTJf=bci!CCB;l??CY^Yf??9RPAE7YI7SUyD&Mhv zeOB0lR66mcf3?+Zxo=z2Z8_+-=0OdBmLQS204*+dHHpfb_*%LKHl;RU8H#U=~Wf{ zz`Ta{x%WJ;MI(3fBYP)94~>X9&RNZ9jAOQPotdQ?oVc6M$C}@OD#{A0sCtJ$oW#xM zwiO+ea4Ua#&D!x9&4~y&2kXX-Gi-0qHD9sj6iV$H5{n|)Enn$_Z88b7t3U`e-Ay9% zrbv@*_=%WA+(~je#5q8;(E>}ClpSVcqF_BRp$zX`TVt?#7H++>m@v^rB(##7Dha~D zPa^}tuT;gI;yRwc5_ei;2N6$T;GfdY)xCg~A8PS=XccC5Rn>{R+t&79=qrfD>g7LG z{k_$EOQ}-phDO3Y_@wpZXM&oSOWXhB0@x&V+f4nC{C=}%DcT=y9_KM249?7dfAN!n z4!7>?)%bJ_h@sg?GsC~`94TyF&)rn3<$F#&yLwY6CnzfG;y!@-%?Umtq!=o@CVw_A zh#Q@u>UZ;2A`Fs&8d{|3bO~-Px>;3O5;nl<}JDci@N-R*4 zH*FN+sK3^TX%j2xg~^o-4Gpc!c&Gd4M^@c{t(_fJium!Rtuqf07MA;(5x&>g5f&XF z8*qNWr;a)6i-KNx^;Z~%Ibw|A=4{4}_o;(h!xi9SPVU?Ak`>Y68r=CH5zzLQQC* z@5(YybovsL&33^_V6sxhcf>(k&;4}z1`-nf(`A@~hF42+dOy8H=H!b_id8$g2u~wd zh9Cp02KM&)`ZMdtLyh9sclT3MQ_QLKU-+qH8{Ei&DGYJ>DS6wt^CTYhSB$IA{bqT1 zc^_Fd;MdMuIwzaPfv~RGBAyaWnPds;iK(NfGJt#u=Pv8-)q`tC+Mj)zyJkH*fDP>tZg|@!QmG zGR;i)8(CF7X%O#(n6#yY5r(DMAk>wWl_9wKrKKRbz$`G(p179BU_)wwDs`Prs0Fje zMd6uT{!fr*=i1WsVMxD0o0%B%jPvs|;^1jTMa4+d>M3~cf8z2e7{2vpI{G65e0jR{ z&{R*4FY}`nR3K|%NWcD*I6OQ>2t!%;>6}u-sYlbAdEAFH>cbV+b06FdTNxR{u_4hE zN;7eHkqlXL4sceZ-58u;51oJ9m8vSsp%mHuHKkDKwC4Yz=_-Tb=-TDr!4ouiAh^3r zLU6amCAhmgAxLnC;1b;3CAdRycXxNY^L|yA+JDr}&hDJ^NI%_u7$pC={m{}m4U84D zChPFQ0RA~t4Sr`XY_G|W)vKrMn4a3u8aVqRydlT-l^_e2yBnh;{|82(0FWOk8VZwTXMTCdPbaJYT!`#e_ zF^#RM?VMZ~;xbr(1!ne|)fb|=r!yh~d*iM(-*yxAw0`kw!ORwa5WZs3(obb+(|6Qr zZsR|L`!_#Xma#6s)$@6T&XjnApc&Gd=t95!LSbK8(+GwJXwu)3&7^FB;crWcD3t z_wV}3blRvX>KPt_$%I-CDR1-9&%SIMPkcG|#w|p^Ed08b*7op@IRYR z4@>NfcKx&5g-(Apn&khg6OH#V%52wU1)TthAh={HO<$e$R*mb*w;#f)QGotfNpI=J zMPnwPv-ykWel}PjCcxC)%YqrD!`JxGEwiB6tD46>P- zEKGjpa#E`V)6gg7?&;aWdx6`C*NcgClbGbmCfi{>R!H;?HYFuRNyvhnXK7$=7AJ#g zFjavi+Nw=hwU`1Apxs-ourzv@mPtU)7G5^3n~Xd8Evgp3P((g0acuZ|Lp~}%MP0#~ z+9&~j;9F$S{Adq``4?WEPSaab1^G)qaWGvvv1uryOtz5X+pJzPtL|vt+w}bK6}%UI>F6$?(U?ZU?z9|GMl^p6HBXh1|gxV(9 zXJg==tA^ugjQa2u`?ij4RqO9FJ_S*FGyt_)DRs-!OYS%n8gKzxpn>l{uQz^ng8n>+ z#Na@zQEPiU7XX-xhN@ls@MB)g{d007TA*9V&e=Z8#8(eFs$#nbRwVmu!TQl?4WUoU zY%{zWIyBqtDRO_6Ysfy3XvM(&vgzmx>V`AgP?>LJvvo(^NbQ1`nonp{D13GnprSj1NTL zq;R+{vj|{7xWic6(zW0=_=t#@?_`tfQ{{YNgu|rAn4Zm^wGW&x0Omsp z$9|~qZo5fJKkFAbDq>B}Y~yw8Q&w2@cls74mLYwC#)_{ILkH(o`aQh6@t<$qi9Naq z_TbjLZrN`nfb-pHO(+1cq1m%73cZYLW!;TGL7HPW!YdpT+B8za8Fnu*+aHnJ)_0;D zTr5|gRCSRa5J*0W?0^iOTF8fM5n}`Q_AUIJ4RV<-!Q6Ydw^)&`&G%B7>lb#aeCPZF zvHTpycq9p8U7^&m=vmyUvX>9_vkdZL{f02OxxWu1{I+I2ONfRKu^P5dNwo1YYb$Qm zY;_^-GqjOgXBytlMqa{%Q6f$4znFQRbY`SZ8o}W&xe(zlux=5P8QRUkj}8LqoL#Fq(rqWRP0ZcdU(4%vcH0c z#=^gU%sf2q2a^<{iUU?uoT;*k@n-BEJ42uoORNO>bVrv>gPN);$T>|K7Ci-3c%Sd& z46Tu~4F(vj_kwwNV)JVaU~S-eRP*(4Xg=VOJ@rFdfM~}{g)a1uFLIvUm1(kL&02$3 zGlZ`8Cd?dkbN0)eVZCLc!+$~@=#yaq=Wf@yPj1|dbC;YvH+mA(a(q-8e>s&?sx`A@ zlz_h!H09)e(B&VW;@D=O|KOkjIXJ(N2uD!+qopZ>nyTEUlUvs}2PHbJJ$6bkhWc0z z?3`bHw_a%a;ft32*Rkds@avObsgSr-I8Q!3^OkLAE_fC7(8=-NzCwhs^_yU_&;hO17>q-gJR0@$Cmi5p z&~4mPRnOPEw-}-t{24Dw9tB1F9ej)L!|*@L3JOXpDxLEB3NPcU(-pL&Fw6kH)u&b0 zHIJkD1Ue?6muvZsbGS=GF7GcGFEvk`R~(kRtwDq_I|;GV`wk2pyD9Q(E~$HqmTKkN z;Dkp+5gZ{kIUP(MRdo353}IjPt<25!Up>#Y-_~JL$?@N>{{++NPm<^Ln>oD>uLlPJ zbS8N?koSF@R+hiHz8+vhz~D@^23he9D=teBT&s;PCz=gQL{a@9Z#BdB^?@qW>vFnC zd2v|l-2vU3tHFucG-c-dq9=i8AK&sTqdf+U5UeL$5XQfpAZYnik(!*@N zw8^n+#fq-Bh{2kh`si1@$<5TCr$Z`zBysp?J9ugGRl>8`$i4R(HA))Fk2M$?VB`b7 zsDNvZ59)hd5>z7w0OUH!3bToJgpa*=;=5jALUUQ{b-54&L6GzTcFZG#&*P|zZo8(l z?EEb&c!C)Rsi}}_{kx!jNlUzmV?4lMKNP@mZ>1ET zwB|)HaG95c9^#ElIhKjjAAHcj+~q=JmE>igP1~2mgAGtS3KQ887~(wWG)%wjm?qk; z^1JU0?I;&e!owf$?9i><*6&7n8I6|f_};JH$vxlsCQ-$~j0;c&3KQ6Ntkf9v{!3Qm^nWj=-{nE*q@7t4FnP#0qZz$KQ+n<(}mZBna zP!*x~IGN-nxb|Oc>g@b_*{!9i*?!;4WV6=p?c`M3(&G93dscOIbyL#=)7vGJ>&fEH z`cE+HxkZaP2863z|L2ZHYHT%m_O*qt^?$yGVRI{A54e#-btgGHQ)Nkc2mnnt!4p{h zK!tH$;pplJkAP2Xk)l8=p<1u~9{FG!e$dzUVljANT!!l%pj|u6tlU_fwmJNVABdNf z@((WjEBlVHP*qNJXtEnEl7^YUaK3YfeA_2=>|xKi?x-H&)WhCjyDUR!ddYZ_gz1vmD((q_ z0PhbN%Smo0G-kDGrrWvoS?GFn@qMsp-@uWS5`0=5Z*Iwu4ZWZ_Yt$A@onV7(T4HvE zR>A>pod#N34X4VP4z`O<551FjaBOc$zC-)?Q^z@PGU<&3z+?c#W& zdqrMg#_`_nB$44XC1sdOp7?D8{c~H}pqtl{9{CWhG4NXfs7|Pz+H!9%Ewy?v6;y81 z?>t7i3+S*!nE)czJf0^ret^4#2G(CG--V>Z#UVc8V8GpU+7ZUvM!l5`} z#=W7~|GnAuc;5c$q(QIM?V=Y~&xi{-dz0?8B$l@@W&tPy%?JyV@R^~ap*o;1Emk-S zYGpr1OOMSmI^*be4P9-8=43D?jc^kv#t)3FH|7v#*eabc`0PX!-;4L1beCY}vdw#7ZvlPFLrycFwbs6n6~ zswttkEb9O1%kdX3{FR8+;=_`s{{OtD+OoL(K0!LVKRc^IYy(e=_dE|DR_{)@USEHR zzkUDyv|*VP++WdQ>1AgwmNGdSrcZ<6U(8CoIUE*q9&Y~!BmXH}wCNop!#puIw4~PD z&&=BETdG}3oYfcHr3bF5#P`5KMuMb9wR*{ofA{ z|BK=08{L4e*F`T#*RWpVgg~I!IXK$hUY~@X7REu@9n~-^NI+P1+lm00D&QD4BZC-F zExE}KCSGiIK8hgV@_C%fY` zByp*RKYUxJ6z*wcWK^doEDzC-O)*U`r_FP6nGiCd2tedX#qQrRuKHofzc$3|BAN%u)Vf0<;AJkiJJ{y9*;)utgYt-9SL)SOfkkGRaXIlrH>)_y zv$n*%hMqFGBkF8~V~G)|XT~2*uDj!|*yakS;lWV_Z=Kic$nf3kP>01GxB+f1TRGmc zcYaqg%b;x}D^ce#6x9pTR5q>he^y)q8R=VQ|x>GR(@^HzUnnOL*)zzi0=>wLMMlDBN&z*S`;Ir0q=s}kH3$K4g{+OPx7qa35KXL=G03u%zEDzlEu z{T5FlsVl|9*^^<#t5|DkMjyt_kLryhYfN@Auqh0v0Gu*%@>n~~-<8bbxZA@vHtAu< zh{%r28gss2a>f4wFO>orpdu%Um~b$hZT zs(Ah2g)VUYFGIldx?c`&P{$yJI5rGteC8t%I#+mq1{b@gwRA!)o98m-235o>f`_DjgIR{`F znI5OsIwGJnlxwh;2rs#OZkD4R)y440tmNs1f1_P#I(Fggm42oHz-`4s}e3(8)qp$DC9#;%^* zy`SoB*UI-VgYiKg&xF~uMcHPTe~9ECb%r_}!EXkB#rm>Yp2cTd7Ws- zC4JHyRsBc!Uc^tOM`k;bHSO$b?1eh;LHgXQ(99w+<~osKj0ZW=lk5#rzofAEHcm5Z z7;FriPGVKX>U#gQ-#XsBu+jPn3T;6rnl7-`kV=z=Zq{2by>2qS=5%xjeME`WZ6=S5 zq!cFQiQ!I{JM-O+0a^U`BrrW&7bGwH;{4-BOh51L?v5JtKlT|^F{3!%9xn_hF^T`_ zO$EXuBN>^FLgQ0^mtvRX)ZgI64$&>oq|wr-gy#M0fGrDD8vLFGPis!A@sObb3DsOI zVFxi6Lw;Ysy(RV8KIXeco-jX+3L{*oN&p$|y)>6LjisiZlVnu*0ftle>iZ7_sR94k>Bx) zi}R-tI}Ntnko$LZb*7g2xFa{*f|8aHwupd4SY&;Go@uM&*;Gc(sD5oeWCg9<5!o>` z0rxYCUuK7)S4kddLfvua+0kG=m49(@0a`Q)c^~8@5yu%bP~3l2n*(M1mn1RWS??d8 zp3J!eRv{2)clU)2yH+rryq%-JF$)T2c;`JRMJBiXW}?K&*F++t1w;Nf4#nq;{zqHw z&3>(U9Y&LuRC|}`!c3_XGLd6)11dw^hj1b9zD%Dct_ufSgGL69<;3RwSQC1w>|)}p zp<1-T^d4g_Q=ECuqByIt#3l66`S!qp1FSNf$?cQvz*ZQXZf2Yb{Ti;SwCG>rxlSm4 zQtyDoop3qMZg!3*?skbvsX@)%Q*NyjaY_+11X~PIm!>7r)Zxlo3uK|WjrCI1avI8c zHgkRoG_s98xW3deFP7$|g?736xE-L8&>|}H`kpO)o37KQfrQsd0;`wg?Y`f1JVQ25 ziD{r(HO`{41*Bze3z0=-XJ^~`T%|s;HG)w~E!J40-Tf+`Tv9MIYAltVMMI7Kb-vhq z&5m39r!_x2yVGV5;)%_t_y6R**uO_FQpu$iZet_sZ6=#$@Hp*9+r)WjP_^HLexyJ7 z@1l^1NZR1rpy{=|#m8a)bK|dWs#xgAUAWqbYX|R%@9ecw)ho2>&cD;YTfp)bKNYst z(N)J4wM;eDwol!X#c6W0Hc-k~YC}U59VS^T{)p%&;${B03m2sC`E*vba7Fo0O}{qP zF>c|Qr#vjZao|K-OdA?22VKb{0Ixr4FD(BiSW+h;Dxc8l;L>bl`>W#c6Xo#a{moQt z{I#pC?d3g+Wdj(xR_4m72Pxb=plV3zcs%jqlocTA*nQ~+=!IQ-DLtz4F?68->+EO1UxmodZW>HGZw z^+d;JE%fC#xZo*1`>mISLAn6y(AZEoDkwKCPB$&jd|TZtV;QU4eCrm$iN%Qu*M5kw z5e+J22hM(#j@RvL0)@xnsO!QbQQ1Us|Pa^B}k!@D2y92^Ln zRWW(z$-^-{OK0mZY(r~alvnfCF69g~WFbFTvZv)vFXGm`!o%fjj6pm&XJmXlq5bpv z|8oKO(#OCWvSCSpj}LiW=j%MtJO0O|j?oaZ7;;4{wX^|lc6KZj__LjV%T zYiepzpk`-gKEH_aeSW+-T9ll%X%Kq7-}O!pV+C_c3A?-xkNgRW zqq77tL&hyZIRne@L@}FZkW<0Pazs5IxIaI0-&$I-5&Bt$#?i3{9)&;ZG-Uv1xhAHX`$Qy_Qzq+5-j#-R^g1?Cd62 zj+Y$IDtL4lHvVA^UyL%Wq}F?TnOs&+trQE?2ygG~DA3j&+j+Fy5`{R*%|#^d?_=L} zIqe{@Xh^LzKHl!2zwVTKXSQ3eRa~|jI~>EL8oD3ps1|ryitm|f1ZAc^^@8H&i@UW! zeh~vm*WUvZ59>5l;S#Q%hTKM;B&BO-&*$y^*I3EZot+&J@UN?>xdNMj7>VuWCeSi8 zbDYa=PDk7FXu9R>GN-Yq#-Xj;XDSs^qpFVBg0tCu>IEOZmB{?p|4sDvIQ zGxpZp_tHUok~&S0yKuiS?o;2^_HunNHCLfG?u&*Q$B`3bp=FEBCGr;!mTOcUoai6j z7^E9aoMV*mIxB6d&b&_Pp=M2AN!HoD<0wh>Az&w_q zyox(}pmMKFj-NH3vB}!;A?Z`@z4^<^(z|aOu}h5V7*%mYrWGlr@Tc6;rXSbDN-@D& zG)JQIfuN%OnyWhP*44J-PR+-V2S0wNc4pVX(`zDcfo{*&{&hq;tTPqB;=xXDdOc<8 z=rA1bPOV>Ao2j8|W-l4Q_(;j_yLFhy1%4D>VqOhH2w6WFvKmt>@w~^H&XW&E^TC(r zWzS0?Z>Bot6@txgWJTL*e~OKGaQGh%T~!jSmc91>zVr{Q|NL%1XxgyQY|O*UdpQ}U z_dFpVr8i4#(7;OnGZ*6BMz@d=U8jiZcT0UIvBkNfWNt+DX8MmzBe@bmMtvVt8T zNc9OO@!7ZI*3{A>@wwmV?Ck9A75)0YxuwOhYQChR-Q)TGVmQe$bF9aR!Tk5)tf_=* zTCqA0m~TD!IN!h9=kQjn`iK^cno`YwO>u3)lW-F_u8nP+B315v(jhFJs^s3@T4=6= zs4r|#?4hG*#y6-h9C=D5;4?{r&HIf%`iR4^FVnn4m$QS75QB;ZiP-@}@>E+**nk`|Z5TGAw&A-IMqL_1Mt)% zf$Qr1(^)GoADi4-M*rZob9ET<9993y#=ijiJd_=1nl{pQuAV6O9pT=!EfBX+T++m; z&~5_vM^_iLp9tB-td{M|jNZ#kf#6LMI1mWU`7M=argqz~>T%@gzkYbEVx(aPnzvYf z4gfunk#QM8V+e0s2`PG<77%hJi}{_NKBHZeoSY28w%0c|bqx*3{_A$!n-}+kaa6&< z!QjYlrmBiX^YLGg(TV=??IEm`A_`tCud{_BlJ`OvIhW{C^)!4Q^GK7(N@nlb9WH9z z^JP-q4RlFh4%};WI*En_?#!PuDEh)fa?*kNXfIW)3YwuE-J+F}+xrlvQMg36HZmHE z=ufHSG^G&?^LLl^Xx&|l+}s~pR}WJfOiXA7Lo`O0bS3Vf@9RRY3xoMiT2URAJPnb6 zlQLqRXsGAbI{nXwIoyrL1ZvHh3LGe7Vb?=JOrs~s_3@9YSew$0t5{kaeI)_2c1Cu( zPW=l>p0*mArJ99YGIy(=4eNisxD<=MEg*VIDJnjGthSjryIuT;yf!4%UZI6*1zC}8 zLe}g2wCaO!X8MHhmL?;PY={{)5;T3kU2C086{JYfRQ;rzWf) zQSC9dPDzQH%VN42WGaDDI?8YGtr!-SwF$M<_@qN=3&A@%i8qh~7_A-CD(hYeu!ae( z5xvN3`rBG4Bv$c}h{gg_>SF4PA?)3as@j{dQ#+rbEhf!WhPrAP7OeW-h{k-`2e@Xg zRVP!5CRrJjTG2+tU=%;q**6LM2?`D>4Ud3QX8CIGip3TdTk*E%nzS+ae=B1+WxNL8 zyJ&(%HtS4uQy6o(QsRzt681SOPC{Irc`o8je9!`H6wh8U^`1uteQdTA{(^1z5 zO_`;urpvN9`1}Ko)nw4ofSOKBd`RUjVY4954MyhFy(EuhzWQU!Vy+_JB7i{Fjyiw0!V|vRX&kyh}R@Q1hnAZBsez zRxUep0>hts%IccC425WHH7|uaLlOgASLxgqVf*1ZVtz%w zxo%m+-H1baQ|DlUCZ5Dm<%e&BeO}g@rb?BE_UDLHV~6B^PHfpglYX8Pdd6?F{1usH zAWiVs_W5)T%1pLe@heAb;%hoEPm$;OcD;6pegg))E%6ptxVR^+SdlAo;zWVID~@eR z1@J3V6n!^P;<+I%%P%OXV{$U=7=oA9(!L_;|ouXW$7dOEqY$Nc`Cf;2u7ANp&WsT6hJnKQ!7RrDbsOBj~+ zSENc9Sp=>0pFA0xAWSGb|2Ta(p1MNXUYMe-_WYliog2$mgD5KpWCi6n;o097^AVZ!2&gJG+WFJNYFy9uuHY=>awUi z$bwnnPL?n@WttO7ZWFZDE*!MpZ=LO}2F%KpwzMY2FOW?p)en`H;0^hFjZd&}{xLrb zqny}6I|m31DRT=lJ~}dVUteE?RE{#$k{OGtsLrcx+s0kNG!q~L>yqQJlj zFFLTiqp9FpnL}95#0ZHqG<-xo{8~{HBNP%`ZQzt^g3^i6Ho$448BRAk_H(!>@q8hf zY&2GOs1xagaIf0U1xc1bJ$o504qKxZqo%K3a)%nn4O6=(M^)GHQI4$MX{#>tMF?2N zAb4jQSv!n#sjn=SVY6Dqo0j~?p7uj=|Kw~|MWcI2W>wrfq9d$7bYnb9JPhULHb%i> zJHrkgpN92JJ|4dJ)_8C6z9l6n!~3H5M?cA#D=!qg=$|LQr?cjx!=2&4+c-{4^RJMi z7ZJ>DFjQqT)|C}FKxqJ=&%@6ST>E3YZa98Y^CX%9` zCMb8VN?m=UZR-qY6OSyoiW5*elg?-Pt+E!%uIcGxhAT&dBVo54MHG3l=4HHE=)&f#dt|za)OtFsEy-y)QA4Wei-Doc2Ut<$3Tz>7F(O5+Q ztnQGge~U?iAnQ=-vMKfs^Dy*z>`*5FU)3zFQ)f{@_l|0TJ?>ZT7QV6 z{uG$H%8!q~J!Bpvf5@xYw?K5jjC-VUk1P%7!(R&8e}_bWB8=3wN9ClLPz^441YXBD~XXUlbzAG3}!|d$f3&;wFk@`Yo}l7FFR)W9^mF*SnjU+H)IMG#l?C z2U~(YkSM|=<%0^^1OCHPL1Kh7lua7UUtQz8&!Td)U4{_8mKiV$Ol~eb1_tf_!kO?P zw^^n_{mN90NYA<)rS~}CnNYb~dFqJGIGp-)EXKt%BlQh$!Vq`N=-O@>47-P{~ca*zv*?VFn6qS=(qH#Rm$9_xH`R z2WI2s3K$acF*`M#MBGHzSGRyl-!vX=ss6Au=>RoVH46ga&+%RRzcz|(CaM=W{vxIW zQXy6X#ntq5!#lDzeVgm4d^^1~9BneGi{aoGk{vu52nbxT&{pM0>Dq%RzJH-buTRljL?$&m^FEk@hKmKVFP zEX=Rm4msO>A)P<%hXaDXMLMR!;Lcbdl1ZUA&N^%WjnSM-ew4*VP(|YbtK@umloc6@ zC5IX{ivc1Ibvlb239k9)l;%_OPZ9eRvC8LPmzCZ;ASmnzL+)M|d66}Mz-S_WcO-xLN!g&)D z6G36K8D@X+_qX4@Bv1g?7#^YJL8D4RRhzlZm_-f5r;;YG2KmqDAPK!5n`2&8hUq@| z%A5htEQza7c0CnGzg?2s+E!%9p+$ z)ztjHn`6?;`mg6A5%_(ta=6Bn0hegzne!@V4*zOp0$*twiKYyYTHyFenM1uCd>ci3pt}yMg5Dn4o9t;pm90 z!PM{PY{6{<+IB?+?#Zaou6y3bPr{ctE|*N@RgFd|TPu5C^m{gs7Be%bUJHYGQ%JBW zSeMqAKwtii1=jC7*4yryQX|7T%k(*o+%5Pr&XVirvHK`l)C82ILu)|dcKrGbto$(& z+m_Pmk*p}ph(W+a*K)r~!YmcbG-6Tm)!z72*amS_!82AV93-zGf-$jIs;?Bi3{|f+SUV)QFFbcT8t9x%I0fr1dRk zHzb~GdLow-5UVV1E@J*H>+sz?kVpvzap$ksp(EmspS|dcLJ{isuQqtH)~QBOvkHw0 zmF$TAGY2*ei)pF_{TnCmQ(Id{Piw4Xh@UoBc9ZA&eRp$=2{`n0Y9^an9m|R96M*}`> z4}PzJ*C}>y7W4lqyA2(6<9vo*_q373Re0%> zl#qGJH0279T(;Nit5m~r>nJo^3Gf9kN-AiZY+zcgUotNtodp$D43AX7s)yP-g55+|!O7PvK;;4^d&Q02A z!7zT~d*B&%c`~Q?#WC@lAygS|udW#d4J3p<=d!IuWyM4DV=KFjhF^-poPyk=S7)=67O}=wf=bQ#3>Bf*y=gd?nKzO!dnBxv zsBddSgxGBq@#_7#V`u!qV}d@)>szl{&e$-#WuARF(Y>N--0jFtx&e6RaRqPiLqgNxTH1vRXmx@Pnmr# zLN`+>02BhIRw2LVFv+OptFx=qxlUoMwb2(p;7ctR>M0rE5lahr5PYFmtoxU&^N0zO zkq=Ji8>(g+?~2KaQ(vl>V;W4w4DVJ~N+`9aZ?g_#qRk+240Roe8-r27QO`5GiF)>g~&uKOP1&&L~^1tV+5O9V#M6!dH6pTjHMPg**d(p;(=ItP%$!Oq^ zWV$r1;!36*6&17*dGTD6WA?6ZhLETTPj0`q@d*`qDfY6pE|JNCROy-hzAeYKz#a~B z$BH1Khq{exIniT3$c;xndTtEdqI0>kc2y+Cn}okT^wNadp!5wW(oeSb?1XwbY>{2K+IF zm|?RSR(w`Q^G{sgp2EW}S;F^Yqs#B4)0Kt$Wls5)$?f^5njRup{X%w^+cOx>zZp!n zm#xtHS$o6j?R%*bDvKsXY`y0lNdDj`tx#3UWYzuJ8Q87o`MP!O68dc0PcO81kaBZw zWfY?E29Yh=1$9cODNhZZB*zp&yF2IHYVv${!nEUYzkjm_6pPA?_T7dGSmMiZ6Xp*I zzJJFLPT3*7D$6!pewRwA7~q+r|5}9|< zr~Qxy{b{}d3ZQ)v!R}h%yj(>SO+m<_XoAGT{`K_0N%DzfwAX6)=q@>qpm9trzDYI_ zQU;&$w8*=GOlR|&ticpM<^0JeW#??}eE&vv+lI@#{h8-jhB}^d%HwG4?>k`J!OBe9 zyt-KD=v<|oPk~L1!##nnazLr@myki|FD67zjN!@8$vGg5t8}cfr^!9&h+y?)eiK0J#uTgmzmi98u&;QW? z&m$bOe0Rt)PWSk6MAcs3=0{V8!LvQJ{Rra7P5gzlIuFro345SCj~P*iAmphAPa<~> z#^H?c3x6O;N1``sH0oxT3V;P-lfJ5+U`J*-ee1#2HRxqY=r6({+Wr`X5LmsMwe@Fs z-Y2@ziHVCX7_*}XU2iRqp=smcS@zbqDM|?CFOlh-JY-7L(ga$*h*A|-C-$o&%>0SI zYxkuOm7=No^xT-vI0&_YmeO@-<{3s19U;uP;u#mzJ{Nr_BM1X%o-d&%J=Iz0^Xx&f zMvZAZ&4%(G~e^?ea&9n_VvUXd9WippNzCOZni#l)ObN>dja}G`}_y5?M zBEZ|761EA*3^0@SyS-L^^0NAZbi0@CrOLsp^b4y4_AjUDXYfcYlkW_~zbbH6<9Id> zOy!HEF#baOyv$5jrAng#2xanv44$XSs%?X01p&eWvS&(|nl+h4LAs$VoIZqEKZ8-S zsWC3F$JP?2Y~K>;Zkh@w+dnl}VKFuRCc*FV-ceYPwY3~tGSP$mF~si3uc(osPwVid zXdV9h2PXHlHP-U6>JI1c()E`?pGQfPpCUmB%jj@=?$_8awe~g6&E@_7w8(g8$r7&OpNe>N@CthEJgaK99X&C67_g4j0pC^pd`-jcZ<`6!^YKCevt&9T_}nO8udj6-v++8EhSNtskp#*ypaw$FcA_bpb= z0v&bcyA{cnJH7}EbCo^}l9V6V!i(SKlDIe^^jWFMS6Db1iDJvnYScC^5-}M0?|*TJX0IK;KfQs)`E%;Ge$tvjC?Emdp)hhT=ktcTiM!7@zDeB8qH(_- z2B{;*LBo@-WL+LtL}&~*Ox6ZO_VcY~Br|EuHFTlXr!sS!vfmzQ$}na7D3^0_BJTq> zRA2;SlBrlU*ou{xAb3ln3@62#gs5Mic(Qx$>m1m-TUw9v`NUHNLYg_aB5Yh=mPGf# z0uMjj+PYqRdaG%6RkyGntWz5a4@KVtZKOU|vC)%(c5_OmxWcHmG`eBOyXgd2oY}>F zFzndNw60ujEj5-_i*)e_-%Yh^_bi_nr08 z(ECYjofV6BxL09C!KG43sZjIf>`zYtGNy6S9EQ7+GPB{d(=LI1F4+TpwBq7Jf8Kc9 z@uvkXdeaagGl88LNyFGkfn#YC&J$&R881aAkZv!XrQP=6gBtv|`Bm|u%^ivX5vZC4 z1~HDYY5d$=Ta}-LCVi{t~sYIS5X}8 z^lfOL3r#u^3jA>46-Ub3-Gb!j3g-q8{A;>ly(BP$3yyt96@j7yeaD^j*dO2Jb`4`t7jNXB=_L$Rf; zb4TMxZ}|MVLK!0(^#}PBFm@Z_&85@=+%FaIDsPI-RaH(ye;VtiS}{Rbh)ytt0C>~F!fU&nkOY%`zMe3@$6s+k<;F?2uBve%!DNm&DPX>u=m(oA*8C6Q?t1*Y^v zw}s~toP*$*E@~f9&Js;LrRqXt2|mhg^FUNTofpgL5}4z@4GymT8uXUyM9FMZt zny7rvpmpRYKvLwZ%3|O|4AN5NxOzNGMX5K^;jFT??3;AL-8v(NH1otxY*53jUXjAT z3IW@?0;SMJgRL|!9;WU973?npDNmrvDkX^Jikz}UB+o+Yo2^ySpmO#92Ujg4imw2pAVboPjQSD*!x9B|y<}uYzp8smA4$9@spPG?sP* zemRcJ{$icbyouWREbVYB4#d_}HlCJbhZ@50Nu~T&34C2QscoJUaU`I({^kVROMh~y z?IgK~fJlE4bh(srdE2~UUrfL|ZS7s$c|LoG;5||^Zu;PKJJA5o8}Q}b1uBxwc7(0v z>@rBtTV@;Q|7Lr{SJKc{L#wXoF$+M z=EvVDc_AHktE>NUKr8wU(#jS2^BfGdhNJ&=|HE7$3rW}QF|O+>{+x2>SR!-kio?1S zCr{xSee90HbaLu7y``dq#%)c@AVZ+jH>yF2r7!ZPuUZY`gl`tF-_u1CoA+Im&+;fB zenGI0#q6I`cb$G$7onocW4$fI!9L;^S)6mo!O&4Q0+&almcS?x#?`bI41+a{>GOfW z6iz%t2T`b*=mMJ}riEJv-(z*V-3Hjj6Un|o-D6ryLPU;}W0#!etQz-YQ{qYqth6#O zZ|g>gr{o+{cEt{e2Lsc%?G5U{AHyrYNW$6@JX7@>n}qd4Gxh>jN5}Zy()k!)!QI(f znAU~kq|qHH)4IN{^#MQ!X{5Dr5N63f*^7yZS-{ofr+@d8{%J9+NSh{hD7U`-Z~ex< zDa!1YPrOQnH8sFI&kSbz29(ehJoKVfwAx zG@bu0gHfd1(v_*DX=!*>x4KHZo<1ZbMAF&}r~A;{W@uee$%K=)_Z*TNlR zON{qA$W;*s)VS{C#W=P6lD9T!f5~Q*8DIe(QV0MY^^jdoZJ+>oboYcZ!eEE4{&Amq zCh)Ot!|uK(1oOW&;gPtgRe!wNXfMrA?0r(F1|F!cQ|MjD5fmg76chyNXtSes{(VOr z?LVq(B(+eoo)Pl?Va+=`H_y)HdKavAqvSb4hu)AkMDhy?yerMNn-~^?2%f|O(%{{$ ztyi;mrWLGn1-})@D_TUdr^}&qose!hPfh~@5jB$As<3ZIn!7aSg;siuC{Th*5dAI!n<6!R7%}WvtdIzo*gf zK#9VmSG#l)BiJc-_+zpnpupbbZM{ zLq%EMap8iIAW!_+iKmF=>A{L~5J|)bnj@C^9&56)u-Jo&yUcO%HHO}!8#FXD3u*Qu zZ)M2Yp1ZjO?@}hurq&tjt77OS9;qYczZ@%Y-0#xVe5xr?J39J-M=lo*_`vsnG<{`I zoK3Lq65I*F3GVLh!96VQgy8OONgxDwcemiOxJz(%cX#*ue&?LKwY5K}qUzn*o}TIM zN17JsBbGF|L7aP%PNNi%f~L`rVwf1)a#k%3ocpp>bYg9X#Y*L9jEJCKx2a~?Lo3yw zU4K{M)Zz4V=k{fj$KaJY5CK`eEPVxiY~5$YLfHYQzkDSh8h7>znNA`RWUm!Wh$uNV zdRfX8Ww}P#g?bW1C#Y{3$;{?>EFBS3iv?R5H;$%-p4ewzLKgp zJb0u2g7`Rg`+yYK}9d@Ls*O4k*K-@$4OR%0F)@wU7tu3IK2I zAGVfbbIRQ7WjC-_jHmPKoyV1cqWjcv16S>b^?)pgk%}piYFaj&$dZfI(3LWUCm!nE zkstTjt}l~kG)dbD!Yct`Rhclzq_!&7-f%+K;YEE7S&&`vO3%2J0c>EInqE&rq>5zibo#W?#{L*&Srysz~xEmS)=EHBi9^2Fr zZc>EA2ttU3d!?QyNtvo&3-N*7eA=QHigr?mKx_$~ep7Y%s-IY*JM0X+&qzgMfvJzd zzqujm$A=~{!Tf^Y$=uxP5U))Xk2+!}gP`)6volDr1z!mP1(g z>zvZ!ex671j>w~&-AW{A8U`0 za8vo&rG47)wqIv9O*Jg8?)r_|Km^I_6rK;hI<~igOdOc*_>}~YrW4nMy0psru7mZn zn=qIF00+w)#mcS6Dv-#yC1(pv&1`-nnnJIerhd_+0-_I16fFvR0?UnT%_MV>=i9f2 zHQ{NhQ+6YbN^Ul7*y8*OrYS{paW@_9@?{OyKfvCGh>g~gX-Z5N(rRSoV*$m+DvpId z>po6$6D*wW#JYCv$#X1F(> z+bI|^Y9KG+gq9Kyr2<}E2N6d;<_|1a1J_*ki<|gFDa;3tw}00z--7xZ46Irp^d0A0 zt2rx|or?TCDD1_$&VQrYg&e)0fSyKeG6uO*q}|)l73Mp) zKjmkP7RJV4=vk$_5$uQI=Fbdwe=SL$u9g9$uJX6&V^szJA~^w7jj|@fVF%qKATfg6 z(|s3)zjYX6tV~$i;T5Xjs4o9T-Z02wQTvK9(wncd0HAd6lAu7{n^oL77_c$FZwC{Z zT14)ugJHxt8RrR?G(D&Y^j#5T!iM zc+?3FPR{&{pj83)DZ*ccZMI`RTXNaH1eX%aW zI5LM$;a}{ZWdK^(L6^s~8+AZuozz`-&NVY%NO4Q>dm_E zd0aE4^Ff<11*zB9p&ndQ{<_X>*ONv43m>POMFU*CINoL^Uuj($>3RYKqRsg#EW#zk zTR>+xeZaUm+|2qRHF-wrEF18YSC`#F}RNxAqrI-^fMV*kZJLPKK)m$>;4O z#@CF}4z5oGbW6-0k}&56pu@%CVipoGw)b~A)mR(YIseQZ?t<8fn2^CI34tf51JujA z(cTu-YA)zSv=aMp+JSdO+mew(_gnB%L9vLkG3_T$-_V>??>74?JdsPZt_sWB)B5n{#Gch94j^NAtX? zsz5h4Z0?#Xtfd1V)HzOCO=W1HkD0DK6;f*NPg89Ro)kiC!T6)vOcqlZ2c~VdQMBCX z)u#95f_?3`#LR8O4W_yne+vrA_sLKDic`8wi{zaeB3g@r4Zcv8c%)&5cu7t&$6}q% zq-~mE3Mq!cyM3qsa~M=#D?7(smJMkU5KyeQ1)~Fy z)_p+dwJvor2s>Ll5nIx+4SN=@%6$CQ*4B?qS6QdW4p&!K2t+B{?63)D)w1*JDQD{N z1;m@Lo2TeJK+?b<{2H*Dr1aR&iJUN$X`c>hqb7Tq%5{Q;gIvEG){)@-6x_^#7c7vL>0UPDiS0IpE#yR=0Wk&Xm?3dpW48*E z@Vgcd13$jOL1cb6v3a+ZsbtZnAy&EbpvL6t(M1FO9aLA`^T1-WhbGDS(Q&{qz2n~v zJ-a)aG%wz?tlCFeFq5w{{datdi3K(ZaaoRyAa z(;qv9N*4R}B!H|5%!@vwlRTcSkmzq`wJnm>d(32zyE`Z5ppr&JX%EyD4aOY0sIt3r z6Wlt8*zeBQR+mp^GJ9fj0oeu>xY1_*YFgK4{j+bV{Si?A%uViJ=N6JW~p!%NT)y)P_?7s>%Tb2K{D0;_JGLqzBXl~k5T3hXEai*Ji z!nYjq$yLaNIk=1i$5AtE0`=`DZTS}Op5I&=2-NPFk~7?)ee@RapL@FN2hPuzYxn(p z$5Yv5z|9Ik`Vx8eFn7DVB*?Z$5nyKryQCJn2-4J}7RUfKK=Gbg_ogoeg}Z+93| zmk&Mb+0ME^USp;ORoXBsKi2IGeBiRxKYVl*>nI7eiPvwA5Ay2L4~2vKa4U{*`soms zhl%WKPPO7=pLM0=Cq$6qFd7Vv^TZtzk<9;yCe!I^OiY#Qks(22bAPTC;_z3wOF+&x z(^^u@99^XCml1m2GCCWTm2m~TANKV;HDv7ntaI2d5@XLjEEMznV(_u#^Apz|D^t-8 z&83DwEg|OounD6(i7SgqYCcuHp);eqn`dyNUDn|I_Ktv@f>jbHI7C25OMo{V@)znB`JCXVS`Y6Q1 zcYt{QZv>7k@np-8>Z65<0{f;B!o|>`pEJYE*}%1=bvOJo+n%ze0Q=I+^oQ!l4#8>< z;pzuokgoIDxs3gCYDcWr=aBKXY$ik0R=bzE&O+5nvn5o}!l7WW=_*b$xi+fJ-5N%n zPSa9_VHLYGj@ua6PR~pJK&cG0G#%KGG(Ru|)i~04$JCc*JUB9$^BE1~$&swNAuR6{VnS0B-%CGN~AgoUX){P>o zULCK|XM8TSb7}X1m?%5mSn2H@2;P4Pc=!y2@J%XVKsle0^;>BA-vfRl)CtU`B)h7P zWv0jhgAW_kt@A(L19r(3hnXv8PJEgE12BUtwy6WC7z8Sct7jPxRLIn{pce>KzLNeO z#@NT#ELi3a2j6L_pt{R{d896=l2vg36Xq=WM%&g8yE}0L77APB`w16%qT6tu22_Ap&nNvUWU@6YF+K6_J!#gD2+-`K;}zug;nET)76Wz=(q z9&ZkJQR6r*<-n%9_4PdjKxOnrQMu`F2;-IP7W-M6z&zh=YVaJeHYu`|+P2}07{+~E z*ZFnHg}2tUn#mQn^bcn~KkKah`Aj!LS<{O3J8+A(275=Fp6~GzEZwmy$f)-O`ZNmM zR{ffWJN}(#;&TRD+7x5&dOat{!L2^IUef$|LeAozmt^!WEm_Cc3HYK5+V!@P@1C>b z1*^lYibDc#YYwc6fj5kwesoflxCdifx~_i!^?Jeu1c3rf%o*uHyvBX?GGvxGped9% zvrRR%FeJlpn?FV9O8EEm1sBkLM2sLMu03TWNdClqKf7W-wyP*!6}=W~cqkOzxmWWD z-nv#K)*WwH_`wm4+3?A`%i^axk$)|zatff^9`M@)=wQ3M%AR%MuOL<^Ivs>hA+2jg zb1)7Ol^1C%P&-7r43j@~1g6!w0_Zd=T06MeFi}sZp*)@ri^6a^EAYjCQ~H|{Kb89b zJF+1l3Mna#`<7e!)J%!`=_*M{Nq{-&Xh|lILbBX$?Z|TRDxr7l4^~#JF%7^B-#vrE z?p!R}Mf)}?i^IJA#RML4RMt)4$|ixWlF$#*uEN|GuWg3a4O?4l;DWaq{n2Yo6F^`BnUApb zHSx-+pkKn($JCohTj9Vl?a$?;(T0E>a_wN;f-b4~+6po-W}?+Yj+Jtqapp>jD{P|k z1Pgkh>x*MG$G!W=m^-%3I z!4D2UihVYxT$O)nYT6q$EXn+(w=|qX!U%o+F?8V6bEgp^xp>MTX7;U-ULE`Q00G<@ zDkT}#V)ZV?6yd9T;DEvOFq8*OuU#nTlA&ZbK3w33{@k>6c;Jzld_ zV$hT1hlIGW;vbW(U?Ke>pJ?Vr95|ce{;4jfeooKKoMYhuWI5(Z+gx^sp8fm{g8=Tc z1UYiQ1lN?pcHS>e>bVwyZTs5))Uy8N@PN^s*Dz^6WMy%gbQR>q#nw} zlz6BOKR*0KOffam_WEo$A=Cvf=4MK(&57mg+F^NK(Rwju`{g~@v=M5Lgj8L`ObOeg znzNBC4XuzWMOn=4WXIskaIFw($A9#oG!)HADfotT6`!&H|C=85*VgOiT_|)xjAz7nEMCy zDw_%&inKUf=-qygwwjQu_)KDT$~ht?6m@$Dg&UK$#+Qyh{)#;;Is&U6a;&n6T6Bf0^ zYb42mUp{e~nWP2fYMRj}K{gb!hMO34snT}RhW_7qgGAy=6_#wV;0z7Un{{q+s5o_F zuc!W-n+PHAGefq1B9t+&wv@wJt~}*oP7|OfeGq?yFFQ%N+;Nq!-y%Umz4JF0<&#tR zzEEc*b799%l)=!i>b6zQP!}5L`d|Z}=^L56d~O%l#Ohxj3%H%eWACDm!TI-(u7@NYKNX_*uV`QQS6`d`B z)sA@*vx_I*3D6AJV2&04aK0oiH}~d5foXSd7qAN%Qu)g3@*8u(?SgW~YO>*pvI)R^ z$@V8qr`W{MTgvc{Hzn6wnEP5_79&M9`k? zEg8&^Q?k`8NSj|+D@^CRHmfg*U1CL{Icn80`D2~rPd~cw7NP0%{kL^!ZURCE<&Fc- z@>>4VKCG8*bu3B<6rFGZY-9b;fS@=!uFz2XC}>A^SJ(XX>+*pLR;IANT|yzA17*s% zP`$lC6~Y7wY5JV-Dk&u)LS(*`N$?zng8T^Pa6TpVKlWNi!Z-(|QNIfIaOix zFFOhfR9IaFgeMKcQ=QiNUJcSgrkUw?=H!P#h$(VclyQL*i>h_?pEZ~qt(@TF+RSFA zzSzg7kXUYL=qu2%G!n{)57`59bJI(w?BFyFqQ_y16yk=C%TUFz$Q}DXWAOQjvSB=3 zzis|F%Z=j4UddE{ils)XZE*LzjF_s9!wZci~BM~98Hn1kr~GL6EAR3 zc%rcJ0*hu1S{emsnZPhDv(;Hls#iY1BwdQ+Tgyv#@G1M}{27%B4DpDU>Uah729vWn zuSB{ydX<9o8Ux#|HVdjJnWv3b-jzh;j;5OZAS+9ct(l#%-|!c`pOh!a2!`mtKtnE! z<>04#Nb_VG=`d2ioI<={v9h}!-%Tfu& zzzAKCOYY7pwAEuFs(OxVo!Ft<8OZA;|K(PCsg)?8T>@`J5Mah!6tj4&MmI{@D(vIZ z=k&XMFEPK+F|ax&oC8e|EfyU@V zNqJ9mjjXHzp_S#J5fd+M?p}HR{>Mnix76Gh9&O>~EYds{O;LNe%7w8uOz?Ci@><*9 z1D$Aln*dnY*Rcv^w$}_RXjq7ujcOg4#3oJY=vx2M-7`m1`DR%Lusai@PRG(coyRku zw=ZW?^)!~@89Ov1WLtc`>vrhQtyC;u`8|p7;lqg%Ifi0oebI&(@YpM; zC5Vke^jOqmsHZFS%5}MI`bce5n!3P-qxf+DupKq6OF==A#H>GLsQWRO_U`5eRHaj1 zTB@X=fCtesH8bl6rn0ZGfZm|jc2dVnfuE=Cfk^iFzOEw+K0D>pDZKWbf4x>KKfb%7 z%G>!nKFupk01%}!3w~FB$aSiO=shqQLB9v<{-!z7Ri|3HJ0ucMt|ABg8=RSH0k~(a zb~a}!)0oUrY$2&~^l>+hbv|M`?a>ICGBC>j=rAM`7D~6K}6F(7h>si~6 zdpqDHLTXyot2|-T=8JSzTgwa`?IXgV+y>5MG^3{06RzBgmY#CC4M)s=WNe-oEyTBZ z>eU$rf2Tjwk!v1{lHSk5lZ|#yN?`l)7R=aj{a$;2CuWy^pRo^Vne<5O8U|heCNt;V ziO%IDZvV$=Iu&p7lyAc*;O2Q4F~6TTUczwPN=TE`RvNdxEI)UAb=DtpUs~fT%S=~b z#B-s2R)CV6sRqR70049tya-^dx!qpqR7%f@1YJhCFXu3R-Xyh~`0|816k{ zSsisvqoS~~tggRpJ-_&sdP%9TtITRErp=CsNEs$YmA}{iDlJZ_+x!sLWwb)nnpbL1 zD;K^UZk~=XF0$v;$7|>M<9SeUOn(zQB@UZeLOz)=`4oKj_qZsZIU()TO5GNEV#fs1 zJ;44U;AgSA$i7Z0A-+Tsu64xHm)U*ju*^ZfYflCW3%ef_=HO`ou!)^z`JVgAz_mdn zbhbtY3$tOn0@VOfjA*#`&nxreS)9L$)Tpzd)0U1jab4j>w)U>yp0PSaONx^p;|bxD8Nw+rHt&?gx`Ux6Imu7&pj)aCVc zSkM7Im-_=oG^gM!Ib)$=ZdhMM|c=R(da4+CKp^g{?`N-lC@KX-^VG@kCfziNId+#}-%mX~!* z%E&Mab=JiBjx_ae!*-wR?`~5RW7+fQR&0I@=*uZR{b)0>@$zRPQpucSnC3s@d{ya@7VF3WHlO>tts4 zQz59EeDaA`-r?@=J^_UUs5)9w%XVqC-L1kryZ<*-O?>ZOagW6su}!xusgJ(tQ320u6?e zC3+#gM|jIH+f;$o!m>o(%QLO3bqP};)2Q2Tok4QAb8Po*ZL3u;4RjTwfItnke2Yd8 z!3=A|VOOM?jKvQ@r~KkuwiW##Q*G<-``?ya`eAHMIEZ3ZEQ7;~`q~?!|0HCSGEe zHbwkg))J`H_r#=kI~E~4^qRIYyeBHFc(NkwJZ$e)h4>WzZQNQ|%j9%)37V>tnSo#AeFyH zJ4R#-^UKl#+lB!hi%Cb?d>UQaA7`Oj%Jt!P$hWq)8u9$eTIQ?`nDykV&3nQW=Oo*A zk)=PF%iDG#r`y@1lxz)U;|a49GR=si;qu&`gMGXB)oU&%fpcv2g~38O zHqc>xc{#3r*nS%Aw8efM$IuHgL0y{BcD`n&qV!2xL+S%7&Vrps^%>~9?8!E|;BHpS z9R!&IBz%y;x1#%zvAQ?1p`xGWnokAVp-j3RgDDqq>DXGtXf|I--n9Ib$Df7mf{^!Q zqY<+9Dn}IA+gw^q^0W~Q>fQF*3wC&aedfTsr@H05XM%;WUOPBaY8bGX=;$q2TBON7 z0|fg-Ab;I8cs)3ne1i&*pN_O!Hd{g>jgk2ZnQSeGy0K=sh7d5Bj<(9`^agk36kG+}4b|MX|X-2WR~wV_)<9_G#EnPN^);D^@XC{}$_i33=2S zXL|M@wSyt?4}7BBG4>(r{S_!B{m+b3f`gIj^IkW@gZQdVAmRVJsJNkJ$oescLkN8O;s*cz1Zk}xH4uf7gp?lC{c5geHaXYM55J4ED zW+YdSp!}Xqz180Vn+^+alTnUQTN`zKuYe2}n)dj9_|XDGTcTCLUW!pnh$Bwnrkzk=J>`54sZDG-?9_@{RiIvmA}x~6;f>;t+;A2 zpl&Wp78#23eqICg7I`nEHvTd*Km$^tK3XJ$0f)-*mE!&FB4$llml&)(f_hEW;l4zA z!DE)zpLV_?kP@Ns2$Jd?*`&?B;-T~tss_z{)oh^z#3n-hDhUv9UXs>wm@D^A$@t->FdbXYl&v1nP&*`peNqafkeJh6=#W!HaVSVf9I) zzj1HQ+^_3-li;I2z9)~JD^gYlN9&e7<}}CavnoS@);1kk+d!fUJ;N-~fg>;Mm?=(P z-cC;78;^evx|MBG`wfWM!Q*fG$c_cJhr@m`Y0X^Uv8bA$pOfe|7qek{w(Rkiy*z6euxI zb%JC=`lR6DgU2(xds=f~+Ij(vY2#%PoX7Ct+l%)fxWZ}AlYee*Rx)YYMFe>SU!-_n zUarUU=npg$?~?s&Fb%N}t-Y_Rj#SjAW_<*i>~vjY{C9OfY7gnrJSWRE3rYwvr0B-# zidm9Tobqc=&2hzhgqSSJ=|a+;Tv4F%c^ZRA!lIDAXffh)m(-5bNk$S2$!SE+^PlcI zHQldyj|+O!>@fbCG+6SJF{v8^+Rfo*nc*&5pN~LS(&BPSdK--tp%bUmQkWHSi)V)Y zNX3pu_5yXtX`S*Q1396$G$;_BatO!ACMnnUem%6r<)#i6CIck7F1yoCyVEVySA1Bg zbkGlIkXWs7d8SaA<|;sQup1US>AId1q9uqO7w~-#ADb?rL_BS^D2<;dmoR_!Q4(&p z%J?qWaeB{ozqn!;Ap>f^ot6eEz`Nr-KgZaee9e`j!~FgcbEZPvc<>HY^QJKRBKek$ z298ThO`g1)f3_T(*aJbd`&?PCx*=s*ricGGhoi95*z33IZkghWuWRJJQ+cM&rDWWg zOhukL%#AQv$BRa z>2YXay-X&FAxkzrTC~kvw$9l$6~4 zBkq3{E1GFAEojv!o?EP5un_c%TRWwt%Frj}e;&lY3?X?b-Cq*#c-X(JE?fTgoSWO+ zfA_{VN?T9p)rkd$VcoBJ%W`)`1wmU2OR6H3T`|R3u8K4&I$||AOT8WkC&+J6)Y{>V zeLjtdFNgp1znL02YHN=-?1Q{AD|lQRAyFzFrN#8(ADxEw&;&N~*tctdS@i zEAxfYHSUTvciV^rm*j#%W~tJ`oPIzpU_ z1!K3r%*8kSjxwv}SK77z{Hw^TnoP<52(VY{{!AWmQz`s8c{^QyGpsPo^4m>FI(XT; z&Z>WL9P_2fJDd0D2p&%Sn-vqd5Wh!Eiy*H~GCpUVf9%}x^ZbSNmN&qVFqv>83WO*7 zM`YoUQrK<_{1s^*CYA3%*uXKC^+(^FsB&NG*z# z^z5C9^{Cw$T!t?|Z^F&*@cQ!3+dJF?tyiOQMbV^i9ryCZ82CAGi09P;XC#&RZO zND>%N*B|oE9_=?;O64NG3`K5k$9UXjT%{M9-xBgihSUa% zBI@kXy_lBi?<{m5o54IIN^e;x{Zh})7vXdUJv+240ThY$eGW&sopgx#;jtE$te;&6V!nv z2z#g2_Bn>S4wV(M1idl+|B^su`QB;k{OY^1Z3l{f>IVN0x8|`h8+hX)Q$?uxeL%G{ z8{NF$knCKdE!Kh^bBb&s53{axjRhiIK?Mz>bee9s^_>3B{S$LfC{Asg&o9odg$0+` zR}l6=zhlwMC11%nANVgjQ&~P>AGm<5T>YP>Ny4Nka=u2}0rIa{pqSOmhpn0TwR*_3 z-mHo7O@*GDr+1*d*dh2UfpQ3Ctk_*nDxoORqEI3hylVH?{`v|1aUZs$?X_Ht^Q0|i zu0xJ2&QBVJ2^s%}#^J7{ihO*lF1kH&K@M6$a7L&{_=>Pqs9p`dv0643Rzre=3pFkp zwml7PuNOU0TxGSdZvmdArZbf#Q|1LEk@4?j@`(*^fznNQ2@;#UR0P`tMi>cM1M<|0HIyb8r``b^*7AodESc^uEAK`vEW?fCmv&6u%0CF*oxwUjHZV_io zTwW&&F~{@vc0Xrde^UF$Y=`s_CSUH54E>Zj%I3_(g!)>RhSJSPcBsk>Tad3z<|L@I zQGx*Mi6Fbj)gR=uL$|lp8<=g(FN}t&T>{%HUw^>pNMRax=Lx%s`fmFus@wjQf}DG3 zyZ7r$4*VA(cL2A0yyH$uiS6Ko#_-l53$sI)4&L%NjK3b)-qDOvj6r;HweQPck7iEg zPs`huY{|Q_*d5N*Te-UUj7TvbNa!x|J?>I9ad!)Xxg+KyjFQ~E%lDS7G##>&otGf} zNO>~`x5dhgCG_u#kCR5SYPK?pkgN69*dgvAm>CoE z5oA!QIbGM(#CJ{HxwWNWfBsdKMJlnNuMhv45wtOpBMy*VIsx6D-QlFsw6bV}_zK~) z`7ci*?{OSk3x*#4cPtN!L#e5N*t6Di_fk*}^7Hm{)_bTY7o~67qmQ49OT3@qg7OWrJK1lPLSi)5Y zj>vk3Dj2-Xsx4AUo}98q3nBr z{DM?rZdjU`4YpB|2gWd6^yzKgMRbq5r;rm;eF+{*=cx2>TWhn$OYV)J$<3nmT5zE7*9WJ#5C3! zVv8@0V7mXU> zJnAK03R3j;c64;xA8XrNT;fauEPM)gV{gLQFbJw&J(h%gA*V74zO1vTX*)Jo`m(BH^-F$EL!$60fC)%; zf2xU?5I|Rs(Kj+-lONTzmjM3&e4wTG_RDJ_5%H4?MWCb{app$PuVhfzYFiez)1kKd#&-eT^}v#=PkH)GyCcACV;V;sxb{rf$yxGjJ0 zAXh$V$SFO>1rLK;G=8-5N6Rf2JtG0{d@tGjP7&8(cbi3yOq_vf^7G>yf#4Pu+BrZW zXo+SIN zm`66Y7eUrFOYqS%R>Tr_U!Lm1t5ce#ahh;$>m2;`scYccfgGq}QybNA`{{)- zv+>HLv{CT)WuT?0%Giue-fp-UBd}W35knCcWXLDd;ZAk^W<#CIGMBXER2o9!AugPJ z6VB2CDbSb17irEZn2S-H&5{8#(47L><-));SE|JKXr@F5SMWb^64KVIA$c{o%F1b- zuOJL0SlO!Qk|IFwZ_!suwK5Uro_MU@quGG@2K<#@DAw@0#9DZk;jmc{jN#?vQ%8ED z%*l+%6^l_qB-{bSfpxl|W2cMOJ5Cp)f9v|wQ%NzL7ZY(jagbR(n2@5=xvSr zlAt6OL%;L&R`WHR&IfM8=PUz?IN<7w`|3TPC69>`VoP8L$GW(lIW<2_?3()g)HhLN zCjHBIv*0Y3yqvDZz6e6&yjruA#zg({q@plxiyM}b_TKk^Qtn{0={Gq!CUpetTQQ1Le-%Nh-qB`#LOia`Lx{z+is_2l>WW%L$*9SKyJZh)+6mY z%gjVVv_NrlcZbKt-R>_}ykwqnj0AL;F}50c!j8V$er(;GYADd>OX_!AN%&z*O9Ml- zR^TL@@=483cWD==%0|5pz0*TZ@4n2%y8X`^u?u-y+vb$TiXfwdWy~k==YX`YIN6gc zZp2G0^-jsxkrEK~1m|Yr&}#hu78V{OM8c}v&;}RKuLo8*Mg~Td67vxd-!@yzlOV6Q zaPBkFo#DR!geIMR28OceNj+8`b=8S{8K78y-nj>*3wpCZ)myw~O|7h~09jSIa$evy zwOKDLC6JGW$)4tJgi=Sd-quw zcfOF7vu}8KD;v%YJ5PfC938i-w-x`WooX(~?qIVw=WVKWbznJX>q_5D_koY%om4ae9Q-CAklapG$m_ayq+b?2i%;RnVtg8>cwF%I{~FnCUCmV9*| z?5N!?jg96<_4MCVCjrQc-O&qnLgHY>(uWA#IOT~J4nkk;T~J%giL>G1Y5UajYY+5t z#f=;EfwqA#r;y_G+Am3(EvG8l&$@RfTCS4FUnmEllVvwsO1>~me*7RG1zgU5Q!yQt z@*{o%0kL*5e7CFdpt5?R>#WHF93TWQ3!ot zHJ{d!a$sNL)CKIztnX7%ui7=4Ck;3#;Oop&r6~9v>#o;0XY>GtGs^RSDG1;%^GLW6 z?hmrd{q??D{r^~i?QmZM+7erk;m+zUtUDKCl#?B;eN%XB!*DgDQBBP8KONclqd3q% z#3KWd;8N3=*@*-0Ut$|HG&Ch2fUe0c)Bc?2+v9#on!&nU)Up?lmiWcRyPGmPY2L7`DbLHejjB?!8WT+6njTrlqfo62wkOP)%1N< zGT!}>EddzM6xlsmd|$H=)4DC`h);NIoy#rr1uouGKJlVfQFsj;cqnjrqiXZ4h(SLi ziO%M^ghW@N-&hAa95XA`b9?_(KYL|NQO)*q=QvwaeY4&vy>-C3nU(V7<;H!Ks4xYL{fQ)UXSC<&-5eG;-tj3o*bgym$oA+M2J+I9` z$m@048V(If15DUG&6!U79wo2UsPum@U&mt;i>pGO z8doF23_|Q$`~!hQaWgy&mqjJxbw-uMeeU*^Wp<0B)jC( zhY9gHI6JdbE_?Z*FF6`iy*Vyg5-!HgM^W@2Lv4rAVA%T!GGUgWX6u6iyT7M1NFC1< z;T|1>&Dop*_qANMmW}%;6Hv5Cr=;=|hM~r;#hLWw*Y?L%T1y(+oNwv{=VYd+JbOPJ z5yyeL`Jn2#ICCQZ6;g66%mq6@&YU4=h=mpf%M9X8ZSr=YU!ULU#?)zKKWuFEL86Gf zM+Ao#O4SaEREv~U<{yEp&RKd>vJ52ww-b-k*$N@a(?n&exxlXnNbVIjtmqqqXF6=a zLBv7r`0|rVv7u^7HB&pi-QT~_mj~^>_?u6Wy3LK2-oFE@tYyM(t%_JKGLt<&bw$p= z8L<-rqr`>gVH3+ZkNf{AN-ZHW&EmBy&fsU}fx=!$6XCC}1*`w^35~L!Fc#8>q2uXkx=^3m$cUhJC7!9 z9o~Kuvcn^7vK=ZcPYxfreR{kjI@3{HJ%+>qUhjJ)Qg})7!v9-iQ@5MDj}|z|Xr^zK zD(v*g3kmhz!j)=EKR*{HdG~=v|0eszWmxs*L@^UC#f7db}^R&ayzoN`Si| zWd`Urg||ciF&867i{-LnGqo`Gs+x`*Fp3=)X(>-9iux5Q$Y(d(=}BwXfr)%qLeYid zLnQBgeR67Q{^aSXHtk?z8k>2P0t5AN5~^ePyimA7SUhJ)s(Xz6^_8 z;n9z)DKLK$#rCA>Yh1bRN6*RA6}SpmwuVX;2ardUWO%Qco&Z><9CPGKDg$*xLqd2} zGn)md<*31gOeQkP|MQ?`mYaDJEeeVm1-G)FH8;2u)`j)*95N4~XC205ui-;$!2!L^ z)Z}R^YG_DB;})OQ(CD+F7z|#ENT6_klrsct+58inwd3AY{yB++9N2 zN_R;J5(-EoNH@~CG>bG+QcH(ONq568wRD$sEg_vtcfKE==li?f>w-UFXU~~)X6C-{ znd2W^wDr$xM4PPrcE&Hkf#@IC(_Dpr(RH`iX}xiJ$;(3I3|2+NuSQ4mM*iW3h5pIY zfVY2GcKMwCPki|^$kfPZDJ_?j&nM+;z#F`#BcmXJpP_co6ciV1`0A`;EP1alAMP&a z4;{Wh66+?;xH%%%S_~GKdb%XGU3m=1)3zjoAHA>BEjFNLWsUlr)Mfq7OHvyiyUsj6D36LOqLxb3vvSy9aIz1x%Kg|BTP9H!8e*pLK^zG@+@8kq$xdPx78 zeu>9Jr(g}_0^K6g$P>CY?M!_mqD6T41&T*8UEBMlg#+B8JagYMvFh7$tSjm8EC{SJ z);Yr;Bo(0{K&JYwc}qQ%>0te`I(mEr^r$r^jCHaC$ZwRDz}ePaz|=^M%uz6=Z_p8t zG<1?O^gHGqqGmXu( z;DY+y{d-KP|2ul`GjXFvBhnI*i(Q&V71?QgXtb^%#Q4W&G+zSH2Jao;bYY$N7r+TV zA;j>|Cp$suKG#+qiLg;ymy|Esz*3J)OYHb(XcB{JkLhY7Q2N44sBvc#(!(cdq<5&> zw}s7>;B*#lEn>W8H>(?4!DweznwBbB#(23i&CLOe6|X)m!|9cd zKYs<$c@L$@v3X3)2GNi$dpU>RIoNKu*}Bvjq)~b~49*S(gL?GJFfoMv zQswCt=bUZEP2hi>{cQYf zDft_!hUMbaxUC*C@$zujVv!{E7(%Qv$A2?%{)=;eEYkV@}*B^n#t+&%P#xiT(Ub`xE8Q}$f`LLuWl+QV}Re1u>V z^zCd-`Owd4FXD{Q6M$bTs8k&ExdDbN`9Hrg0fLn0&%(lLmwHoHcOq+hOmpGkFOVolq%gHy40nQ-N*&9ZQg$!o`a_-s1wK6QkIJEI}md|e>cRd!6yhw`M zON(%i-UsPMcs@SK_{c6)V?6dk)rz*}O%q0UcL`$CMty+Zh78$48}^L@)Ei39zWdtj zQ=j`CI$Ym|-i936M>dWFgi(tPNJO*GmU6p2>)Czwn+g2ros3TsIVN+efqwIIjz2XXXtk3ks zc(Z<@(HI zDy#aO+{!z$B%6$Zj}fTtZ(;o}X9Ju0>)8RL$&hmU!If*&&`4$Z6yB109rf!L#`1$N zEVt4TU=R2#PN-uabKD$|emW|RCkprN>JYvcf{s)TaO$S^?qw(9SRE&vTrObr6lx?E z_LiyrW_Xh_PoLFfY&$ZmR#NU-Nd77j`3a;>GF;k%Z;O9sBVDUFmQ4ccp%oa zRQD~V574a#WoM*{Q(#CdjooAFe(`j@Da-4}CjLL|R_di@wg)7SvP?9+i>yjB;|1wA zFY23&K=)hCXA$YaZc-(h@4PeHy2ifh@Lta{w+I13hhnURi!p8npzVCPo{BS)*Zlvk zJR#O!O~EzV;jnPprQaJVckGsFc)`%g5sGp6ne*bk6=EE&=1Q?9 zl8W8>ayTgVlA)xWQCl&VJ+ij7D9GyH`_U@Na1pE4nC?-7-tij_O?DHCRy#4wSIeJ^ zcDHH=7RvyTttgu|5&D|BHc@7{la+^Vh#c9CBfC!WcW&=|+{iJ~^0kuq;2#%qgU~m9 zyXlnFgHw%cEN$lA0_JmIe%Nr2w>+iJ?| zGCN~^jfl{#1O`9Mt*1&ou7C{ps?AGit5vk7EE-!2~tdUplJV152x@c^@ zW6Q>0XEV*@r_8i9v&djxL6^ZrrL)vtZidt(}JC#wqRUpgps7AYxyB_0s+0Ihk&2FmtoViK5m)*ff1Dl-ZhKg*`3 z)^foY8j1#hyLd9>-=k!B44}Mee{o$#LC9VRMlJ52$BOqfJ)G--C^Si|c1lwaPgJUW zO6X2v;*;nGddXv=O6)If*_I=5FUkKGDRno~9GLnCmI=v=N2x=lC9jF7zG$lG)0c?8iuhUP; z9*j&~BK`i-+J}jDFU=N1PEb?1K&ZLMx4DNt%t9z~~=JKB>t zCCBkq{dmT5j>gb#Fb=40#)^=(nQK#>nR9v9eQNTZ_T^crz@2x9Ck2NdWJLh4adPsib^oqhU=^d|#^qjR8=E7m4#n z1!a|K@A~4@Y+*fQiuxnOz#|~(yqt-P#DtAunJm;~s(cEP{OZ3|d=xKoaCgc1ela=f zkD?iFMa#Ie@6^3Wa~d3@b)B7;GY)im0aee)!`)7ZzJ(3FYL|UZ*b)~R zGB21<(gF#udAe$~(7^!a?28zkVZgX~@rKS#f;Z&vR{(D&Xc}bQ*->&PrB1BnQiAFx zoQzXgwyQ)pev#>IVx0|sDAk)N*tPnl_2^*As|~HKQ9fyu;Y_bIhczRy8RRiODU1ol zFx1A3cK8=$7XaqW92sAkfV)XL>*x5%Tf5I302J57_F49;Mpboq;rkqLMiC&t#m*oC z?U4j75qCKhqF*%n=)SDL@bqLjIW}Cn@BjPj`%uN}da{HDkoo{;DHs_!(c{+P9vsLX zX$pjIcJ!gR8WkVUhF|Et4ZKNMN&TN!lVuE4Ejuk;<0`R;kEaVKIF@j(8}lzd!0nS{ ze^DgVm{|sTsV*$%3E;6{;{IcH+4cGkkX{$&S*8cFCGpxBkD^LLoojIe5Q;f0D3cY? z4inrM`mWn9qEq=SN)6-DAz>w(0(JaZ1|wgn&1gJA1i+5F)}Ec(*`c_Js50M_N=i#U z5TI-%5@jOuyRPc&xOiD>+lubFfuuRH?FXad)Ufx<9hRCvrL%rYzxOfYe)s;rc6C^) z&}wsnp|MF{XIL-`f3Sz!TDv+c%lp5h^j1FIw`SoLZ{AtTr5jl~V^Qn0*>F>BBcGVA zr72Y4;p6MeLh2?bPQX6@@Hwx}pvSNbIW)nnfbmUT$nc1F$;LX+DnXGSBGBbD{Fq$+EO$Y%*A5eg)HRKwA;LoWgvrkze-9#yHTy~V@#;Tv`0{g(BKh()?&V$ z-qkq@>W9Q~Nx~08ihJv-Yl>jddwO-9;Vk5Y=Hl%Zf5K%gmZcg65(L3+cU6DPRbFIT zJxa$AAT-1I_;Shp{@jgc$yfMJU~NC-0-=#b%RrO6sdZ8Wu=v!|nqK^@wa|(pU*MLn zbhQ*w61Ux;DIZuLRZp_Br%<7mbl#0qb59c97B|985K0lw*PHORbb7XM-@LeLUTMeM zwCzk@x<7{FuCw!t;)-}vXt;h?YmS&?VbLG3)2ISo*n58EwLUad-3QeBE6o~cP-~ME zk{KWA&t=8dKy5fzx;vrc4OW=ZV-*ByX8k+-o1lklhX+sE#S7ROf@JAPpj3Bm@^tNr zs+hytHbns0YToAbH?61%$qsPAbWCM@-5wt@XS!{&{629Bc$^Gg>dP)T|2(d{Mpl-i z7|^U`HsKQKonB&IM^aFKd|9Bby-?J)sF8{7(sgK?vl2o&k2X9xaFm$HZ)RP@#--)r zSv>lr7Hnk?Ct6rEHLiS7IcZb6Q_K&Ojf3!x%M+ zUs$>f=MdTZSY2(elNlz1>5Lo|3wffRm@Qaa9Ld7H!(sI2!f7lh!8g0AhV8gU^+1Fk zbx-cd%vf+{53b2yLvg=AAc;5y2o#%w_>;UyLA(O9&$>MP{8F)Wd?s}2-TVo2bn{*Y zpJ83R8H3W;*G-Dnv&b4F+_c#c7O{+87`>3OY|X1j)gHz-O|-uQ|Fbj!SXS)-Ikl1k zr^g0yUqQ-(dx~LdD!Syzb=mh%j=M_C2|Cw`RUXa%l=ZiHU*Y+RoYxKU`7K^!O7zSI~5xyfQg};x^NDw4j zrH`ZFhMhUCznTysz}>=wKM5a^(XPW-^Y~);VJ6PWsx<`>JNWHcs0aLUxShTB+%FhF zJp)go0@8&K<{{@!1Pt}6qu`0?(8+EXvxIo}O;3%?H^Z~SH4bo~-7~?A2=nUidHMK@ zdRcMIE!X{#l%bJ(JQ}`w}({2>r~8%q5xNz?=pFESt$99p?9rnjCq&ZYW=a_bw8Q-uU@eoyatz=N-jQo^KUUUHShml8 z{AaKnO{H~u(Lh+9H6`)Zb5Q7^2z5fpA+GslwrotlP1j}Z7)nFVX;wum$=(l(jz5uu zy;(RzFon$^pDY2Z5SOWwbn_Sb&2hVZ%dX+R%DuIx&u}>rEv4U7Dxw=OIvy~(s0ey~ z4sfl@ObS(fqbQ*S*uT(wSO&3;nan>qtLi@)2(;NSBoTqPKfKVi0REXtOJ@1MvYwPp!V}lmS&Wkd$(H~*OY@0rC<;_1H{n{2PF3^;FBCpr=*e{bLI=C6M;lSKMy*zg3a;g_sZUO9GK>kbTG-PsiL{&^+isMU72!^Oy<#0IaEN|;Ypvq7m$wN?I?jM^ zE*-P5ym#RT;c6Z2ENplRHs)KAFW?2Wvo#=GE!6>{dk#75QLh?Rug^ZeOQ*79o26`$ zGW;XwUtMxZz62BnR$2J1x;7?`E@Ig|_g?Simm24Ls>}_vM+n?O&9U zs;yAMDT$_3f}40deC=yiets6w=fO;zmi$-o&tYxQyiqWq+u4+QYb!HLhFV}PE-xo3 zPog&14o^a$VmlBmue^K~Df+O=Q7m4ZG^6&4F2df01_=`NI_2y@c)=bknkyR?p+KQf zNVot61GmQ@WWs@UWZL}LOtJf%JH0&a^>&nHjQ_n!)AJb81*~m)vccoY0eV@Nz#Ur< zU6zO;8|fl{ZT(XhvV&SE=EmX)Nx11PijPr+B6vyke;$QZ^r1bA4$OHS&x%1rIP|R8 z!$Vj6<83xuywzUgsjW7%r!#87?L*yr~S!Z&$_+;Yy>&=9yHE&Y(wQP!db zkmwX7Ln<%|?=*+@_VxnsMgRF#TwL7JveZ;hNXlv81*lbw%u?Z`KLzJO|36w-X$ zxUX#K*;6#I*^g0n_T|uN>hWOmh2@j~zH9c!Ub2`i&4d7j8a7Ojs`uD;0bvkiiG=ZX zCth>(f>*Mj@BK!_Yl|d)bB*xnKD@5UgEbB@Jdj__QJ&l7KZW$hUhz*5t-YavFNUx- zuX8gzpIgYyi2@aKu4NxGul7OVhqe7XSON0+f?bFR1DVzTX#u#Kjf<`=2BXzHTW@-J zL29z9Xx_}PVubsK`Ht2+7bZtztmRXTBkbI0Y7~#z7sc^fbu^P!(*@I-NsNJr&^`5m znZPrJ7Ms3MpBkGbFH+>jwjjT- zQQ#TTbP}tdW{7U-XOJ)4ME~ZB;d}*jKR(!ruo%A1bNAxR%7;sk-J95We0Z<=PmWM@ zsal#?!k*7_<$5Ot%GM-v1ZHB_iT9Y8B#U*7E1tQnJzr`uSQRDqOv{zfyn~r6z-}1qEE`vJKa@X^)>Pf2*WFTK0cmTgOqQ2ywM4HT8~M3tB>~ z8E&hDN`p@>OSnwvHQL<@!~{S{q0O% zRuO9AX$0OfU`+%H*0s2==hEmAn$tJKU^3Ag4f=Xqffb;uH_!mfu70YbVb86u@7n14 zB;3D}2J1CytH-7ZV*I~7>IH(fU}V2pm0ax1q?$TwYX<%%A09curxQjEaHyW>wVq~0X}zb&S2@qc6cdu$&%o*H)G$TD($ z1i(BU3JGKl@>75LV%XL+{_eN;?)b==Thw2HNr2I_1POx?R;}!@GJYqpvY7UP0ddsY z*&A1hx-Dvlbo(q*s|&k-eBY*nKU$3Uc%+J9f;x?#^ZAlpu$otoGt^o?Bm>$7O-)k2 z(9oxVmH5>=74Jszl>#Lj+&x8oh~DP6KC^ru=^AF}8t9u}thGJeuPv+^IYX;G$ljRx- z$5fp7-)C(!)2e?&ut?cx1~p`Pc2<;uV|{1QUWpI^;K>O{HO~Ut#LRtrG4u@`-56r^ zgX=4HyWe%USV_-$$ENdKEu&KSjrAzqnO}{@1`U77{5OeqL2n6*eiYSyw(dSLELavc zCk~f;bn$h}wdl9UD6x8XqehTrNF$RRYpm3+sj8(b;WLO6!*>n6Y%91thFtCy02!WaQuwy=87}f3V=mmB2HdSjG?|^McxJaUPF>krCR>p9YVgld`jq z%kh(IA7O6sXefU#vMTDx=^E9MY+U1~EM)i-Jc1y}D|UN$lb=`iIAA$AEKLfIR>R$( zZ$NVuYPB6byI-2{`nByU1!t-9I^{u8vW?;Sj+nC$=#^)6Y&qx)!-><}o1@Fl4C!iZ zdU(U^jsl7j`uiRt+LO4M8cCJm?u9n}ZnBg?Qv)CFt4`@Bi6FXLpUXP|l6x@M z;mx{8kp^_+66^VT47!rROy*dr*lUbV865Fk3fvNa)QtWuf51;)J=R8FS4;={I2Rxbm9X6^^lTD&>&O`O^)ygk2 zJLW;EClL^0JJIT|^r2h~jfRR1aOE{S#=PDSW089oO2%6p>t)s2`~YZ9p5K3K(eAVr z#d7hRg%THLw-NzU`P$|e7h>kMh>JfT#uX^)JiYp?=$HSvlKT2+*(b#~N zgV7uJ0t){5TF|~@W`F%HXkqcVt+lEg%EA}(BKuvGi|<~*A{i+3EX`EvR8ZE1Y<2E* zJqB%-mwL0zTJhy?Ez5r^Cn}SVs;Jyr_RH@fA3aRREzggCA!d|0BHl%5gEy;YKS-PX zpr~>?_yDS|hWF{Kq~;h$k&oQU>bBF-xhv%ImtF&td_EPEG|UpUq=%G+vXrLeTbs;Z zIUJ;OLYo^FPO#r&@S2dirD#pP=8k3mVPX5fu(QQ`A%}B~x8vC@@?9H@ad>ryFLwUJ z9cGp_iUtam44XspPriZL!NY;Rv2jP$a9XrLc|O?!U)w^<6s$NVl`clPo*uEEvbU@r zntOIx-rla96tt2dz$U7wr<5-L(=lfCf6*lQdl)owdyj6!EZruJ#v8!~A1VkBntSr+ z_|Ivyi204m8g_| zQPaD>uDkzgD79`M*Y0M|r`;=w0DrqB;1`O9g+WWYkKJE8%xv5WfOh;+ULXU_Q7A~l zECZdWp$5Ejrp)k5<4-@s6V~eo^;%zrm}@Ofm+Q7W9r$ci{UMAc8uMjGr z?O6wGi%gp9v8{n+{y2VJ%Qbb6L9jnHMq#=*)xjL_G4oS!Ai>}o)7_FCTaYxWoIz$D2loz07BXju4p4IP0mDZUVB2|l{|l&GY>tA8v0Si! z%xl3}z(1~SnBldthd~ydg zAeylxjQva2vyt7W=+t=j=#H_)4KxI3(g3{|2p6n*QOiBbrJ$nERDsMd%~Np3%|hnk z$lhUtEdKBMS7dNLkc6=k3OTs8)@5)Nqb`S1^2ll`jH`qsjMv6;-THoIA`}NEYgZ~% zOm4R8MI5Y;o=BJh?H}dPP$6wX-q_XIP9&i0vvg{tfm!;1Pp zvUCMxz<3~l<6g^-;x}N{!UO=E;e*)#I9RY}^3s%J6P=trhK^|ry<$LE7egmH@Rivo zG!ILIJ)iip6kZkmFGwPq+Um!2DM@pdC|cm158xo}Mf=CSAr5f7P{n&qAPHxBj&0EL zai-zji}}inwjhdisfesby+5;^%C>{6e5Ail)e>`v^(t+qe=FrM_yb@hFi|i$h^&Ec zjDq>Vx^?yJM;QS~=4189n*8Lo9!JvVO*&iuE@62n^1Hj}n8n@gB=NCF`N;?M6Zg0F z>8c`4MOMyPenk<<;R8R+)dYJQPpt!_6lx#XVoqd@ZNu+h_uY2lV%cV^eShR}IIwb(Jf%t}kaP_XAMpk!qG=lgE;hs&peG5YT%2Q_*JLbwquNq^Zr&8A5v7q-;YqOVZe!02y z*M;I|-=9j26}nJe0ppc`Se}>3(45^#jrj|KpaLDH@nhK~kEa+$Zq&WmfSzd?DpkQy zx|reWv9k*5rkSzJ3!a0jPlAn2&Y|G;go`rJKTiVQLH1ry)N1V5*ffYO5Ca)U-Vm*u z-U;G_EL`%t_q^Rn1XYf)O4(o|QaUDaON(IOvB6>nbNH?yBndleBHwPXnc<#8M5CtJ zpiGmgp-Tw9L-4mxA5e@wa?LhABmTUIqM0qdIWnrJ$B%UMHOYjbDm<6aPSl>Z{Pu`3 z<1;AdSS7!n<*FN{Q!M$ERi#hySyVavry4Q3bdaYNYRy}ZE^1O`12JHpQtJ5j!jQX_Y4dS1hfAw2EWwA z75e$WXzY$eK5!JZXi)HdBhw|tzN(Gkf$J4^?_S`eYPd4L8=I&}2z+G8y>OYmXjz z=*U?8yUH6yGnGSds&X|X|NVFuf5X!RF_=g!+!f;NM{rZ<9@e(Sr8vMTm($Xs;~>I|PKOP-C zHGheZh(Az~j0l+uyv{@HS$m?M;u+unprC@Sc-$k4u1a!Fac9yTyjW~M)0 zBkOCpYF~3mh+w`xK-~XPuQdCHgHuS(9f~#&(Y>ADiCeHF@PLH(Y6F~e7V_P*Yn9J8 zWU>1ygbDuYOiiMVZU=cL|2yXh?9D3%(mRY3+kugR0KbG^#$5lD-aCH1^QkiCA>JF> zOq2G6euxP+ZZINjJ$+D*6v278@-eohsI2A~4^*1Ctt!*ooL4mTmj8&*sx`Aj;@!l_ zewa|5;Lqg;=~Nw34PDV={+IBYym`9x4x8TfXURsA4BepWkn@A<+Xh3&vQ{S3uC;dP z_SpoMpK=Afn04*KRiIHX_Po51K5u$z%63Dcpc41bX%C{#a%Ll5OZH2?Hy-C_Q|1FA z#D+Gg7CV+8XYbai)c5opOYm}LFxr+A=22q&Uv6W|fK^^kjMv&4?6*I+`SHnWdbTJ_7%EZ*k!#vug-yI1(iK9{YPi`KVYK^z0%?d z-Mqt_gg{ILU%Z6jfTvkx#K{l{bidVwU4zBuO581aY|_&dceZ$JLkA zw=_`Um9Se{i}f_3HBG;JG-DkoJ79~!B&Sy`Pp6&xFFs+*^BC>rV~{_^P+Ijqv5HMQ z=shnvpAz@}ySc;Z)ZgY7<@$*8bN7>A7Lt{5?4xZUY#KK43cho5bw!< z?T)C=sjKUSq8w6)6mw}~V!J2w-lmcbDhM=u+wZ2@Ol^AGx;>6R(u(Hb*Zsj)jE^4u zw_t#kD+ZK0{lxb^DkK&B1412(%uhV&do9;d(yISd*6K18Oz{y3@*_0mx#N($;LS{@ zQ;jaWK9}!VJ4;8F?H%Bk&=sn)q+A@h{&WI0U2}5mxD`PUiZCT5*HjxDLbirfm>Q1nZ24!{qLh0fzL(v(=gs^e(69WT z=CGRcjilc;-!2C0ZTkP=#Gz{M5jq|e{ZCxz;$2W1RRtoaac4it!@-F(@m`tw)NOju2{=y%l(GE@I%0)<7DXE za<826a^K)e!hB(iv%})yO51@C#}(>#u5S$`i(be*F!ox}Mz8R7rQO!h_w!#VV_?tF zweGLwz8Aa9XrLdTKN4!Hs!LE*ebG(m!x^0+6{_yKnYZ_&DuM z?3WgM9RBvrTl8Y1bgK7qV16;-!cL?gX7SRQKg*tP;XDhEQKS7RB80aXGl*=c-(2`| z;f?%~c9`Ylrxw&cIZ?_eTVv`B3877BPDly<(*5uHT3irl9Io+HX3!#>;aj>n2N-{F z9HO+Z%9<~=+lQ#Gu6~IX)~h-+1^h@$o7&kRuOz*et37iiO9@ysZDM4&xK`ZQDr-o> z7$oV^U8l0e=xIV9SJ#)*OX{43g?L?eMA6fG6g%FiUH8o95c{mWZDCK<8kfgZU06s* zo#IkH(?tSnFN^=3BbEtt6coEV1RK*#pKZq=5Xch}uxHoLNuQ$G>k^Vh(TBno*+S+My=)GeBlBYN zr>x&4b7pNXo|0)ZeLdVguGYN=-PfoId=9GyYaB6Cvfav^&HJI2Az#@7+7)sX6%^66>EK!eR!x z=!3=DUOK1c-4OGm4(TUbhVI8GWrytMqUqjrw^`Sl)m|nsV;Bq#L|MMK$aG-XV_aiQluG&LS`DJzupn{*-ld-PyoNAc zmeXdYgb$Fq!F;xdaao-W=VysxzGe$Lb-_xNwjpk~p_HGcR`OhscCWOaT1{>&o9tHr zi}6S6lC^$O!L0!mx!j*n46OM;L>@|1Dr9s&0Rq3zaJbx9sS0sXa#D(K)NQC zdlz3c&%*w5)s42fOnz3|#mFlz4dRqY(RG@9jZ{SOLKSO^Ckx7M()u~!Rf-xzMt?|e z;li;>{mb8-sgUuK%Ou@S-i~O&3 z9JF{APW0p_eq0Nc)-}AmEOUf3`TV)oI zF!a!yhJ{$9z;~~b_K+LO2Tv3L5;YL^|kUE+mPQ+kcsB5Ap}c^9w#X8=vKTj|>!yP5~KP^D(b*#>g~c|6%*(%+dT6G2$D4c0x_&qy78%yNUv*@#IBx7b7?b=7 z8O2X6a@6^3%#F{~t%pd-YuK{I92WOeceq#My-!6EVQ)3Wd4zj%)9AqbPnqoSsaf zSOz{$$JiQEl|dGdH#FPO|PU zY>t~J4fA-@M4_+s_abS`A5UAHrJ*VH=u#vLrTH6IQ8nOoA4j-kl}g!ZMz=YwEa-=0 z@aql%k2F{B9hfKmc0kOY!LJ`eKfb^^P7#5xS$!++_2e7#L-Td}=dpM)pl!fr4vaph zwaY_@5Ms+!S3cWMfPvj;=N3BR=B1w}zD-i|sY~ta%|x#?pCm+J3KqE_tEeZWkaNLM zIy6v^**kL?Rq?#7JlMp9B*$N#Az!!57YWe;xg2 zFjUk7jQBnFxLy_PPUa7BURe`p7V>632*-_tNNh zyvV^gq$)R5#>wrpCT*b5EZ1%%u2b4v1Z?<#+|}R?<@vsl-`gn>BXbj6rs+nM_D*_N ztPh;zKHvYu-c(4j>D`{bz1~;~{>M3Iq}(=4U24qI`a*gKWNCzifLc$xaGp}k*|j&3 zWqeI_Nlbe?d$P`7T%>FC-2I_j8g=1(QdOu=eFr9Www)S>jaL-Tm5G0Tk`QBOXjN-y zPMzxyQ9?+KgRl3}*9?l1vD3sIb^{O35kV7iX};2?y+E`WWz&6z{3au1FRE8m`w$vv zx8GQR+z$mKfmNqBmr!xP#7ZiQ+qA%_KRyFSw|ybPo3v`eq2 zkJ1_Hkys8e3mWQU4)C3P;;EpXurr%9wi{^WA<9jHg#@0zeDchO#uz3J z4X)Ri`e-UvAQJYq!Zi5b56pVbm4bG1A+`#M9mqevx*_Gnn{G!F<=eH=)!TDi&C9u& z=x27_vK(lL;Zr1ZS4+wlzxKCda8WI{Y?IFDd}gsXUX&YaS3q5edTKu4Z^tpMNcfbZ zN>AX~>uNRZTia4~0jOH7LxWCL9z3P?&fImY>{92@h-vQr5%q#iDk}v|)pMJCl!vO% zuf4#hpw`gZ{A8=qAIR>Bt5;xTE;7t01=Ikyd|?xu%&Ukf$*?2W&@&hrQrI@CQ;DMc zgrZxap;?ZfDDGcc5N#?Qgs{=kkS!3$s3_Y6)u8;QMp`aq*XNS!UJfVswL)lI5Y1`j zsFy`_+e- zD7FPy3dmz%aXPQWDyG7nlWZQJoW_aOj2$xnJI!NCD0Adixg9YeeqFF*c>4jxN|YEi zuu)I1PghH{xKxbbEL*AV=U8|G`eHXYhPU5Z=cQ~lQti>%ha|J}G)xgeDc{zHXBH6G2XoqnD_ z`J-uC?W9E3r-n;N2DYIf+-_;41A!c@x$vVt+{VD%AdrdIq|S>XXI@PCW(cbC8{VSw z_{oUfMY+=y(k!tmyJ>43whB^~yT*=u9B{2hxl~qGP+EX4Tg)R6=&jxTKc-Rq$Sw-G z(GZc%g_d=hhwQMf;q~OKyda6HUvRN%p(J*Gij>ufIIV9t@~mP-_6KzR41P|=V#~V)xHB+VRr)S??MUZd?K68z>`VGC3o&}z}B?!nRHU1 zHI*q9s1jf_4C$eZ0AIME6en;&&Eo=a{11e%n$6r#rV|y z=iXAtqBAOTF^z789K<_>uIo7*K<48cgtka6$eXUR1eS8ZDFgF+r7E@%PV^FWd75w< z8XX6*g4wvE3k->tJ(TRe+-!i^FVHKR)mrKHzT<`G`ujxzTl^LX%Z+q&@;h@y(XQ#-74uCwLa4vpVuQiAYxGCkVt9c=!Hh^@F+d zR5p5K`0sSG1>M?Afy=lm%f=k{tr-ZzmX83vs^eFdI?<_h1f>e5M9 zq{vTe4A7^4vJW+O5#_rNo71`i&HLa#WiAa^92yqh#&|vdkEyQ?i|YHn9z;bHK|&BI zr4f*B1{6j*q#IPayHk-?kdg-JZWy|xTS=LrBqfGs5QcaUe!jowdH;e3X6`-roW0jx zd+mMB?e4u`eV*3lqV7Wdo+d#CVP}e@u2aLM`)$+J8onv_s{D6Lm=D`xS0K+v<3_F(?;?-q|VR zbFx}hA3cXwZ0D>K_0QC)i)h#T3S?~z$H*wa9`lIO5I|ngOs2A2HXl4DZ_Ubi&1}N0 z<2pfbMn8Bd^*7@Ei15VQVWqr79fVus`H?Au9!-1^&hu~EhO{iS_e#-kSk^A00CsLV zxY9sPtWa9;F>Z#(VV}min^o=HcL97N?9R#tYL{iz{0br!WjKG)!6U!QnKQ+Va9#OE zp~h@ev=kv1-H7R)ckD~N$8yaxHBw`h^}Zw!$U?umXaw{7*<#(ZGGBrEGp+Q5XayZ+ z6SphenP6)w#zO^Dwl{8B`+-w3D~U>RvRT8r-}V>zx1N=N#*LG zLJ-T|Do=LP>n3k$_Y*XAm^Tb;t3^C8tIN0e;{|eiLD}$7&Y%PCqh?X{fex@Vd z=du;JC$F>6*k`d^I%z(v?d1Yr+p#p|VxB%jTFYH)I$GR062fsCve+-_!1`;_7WaJN zj^F=s+saRyp!;eW#O9{+2*xcy80R+J02vuX^fxBdQqc@q%b*0sc?dnJt)v%jLTb;I zm=9cgo_W->gx~UY@j82|g)7bXAdpB^xte?wsg=QQUqI;JO6+f|XA6dPXOL%5IHqov z+Vk$LWXiG8Y;mfbR<{jQH_T5BDw>m?ar2Xsc}ylJ87Q6iy~}PsfuFiuxz+O$WOT-j zp)M66*LRLCdu&&3Gv&Xpc`**&oHp#V1AYM)Qy+EseGh{Qvo)1Jg-vgrZzFWBU5XsO zFu5?rA>nuNoy(E9KTgeI8GYaU&;}$L%4}{{tY~6GzX+hWva8umildrEO0xMI&Mlh0 z;omoQc2)xz`R3WP?^%*V6dc(rj+N;8jRt2$f8Vb%enn#}otv|JU7CY|r8-SuMt%jY z4Wb(C!vS{t#sAuZX7hfn>RXZHe_n)*ZEI6fESV^6HE_C+a(1+-H=Qzb2FD?g#K<7c-4nrf_qE@JHl?3xv|cpYH_VwErHrRp z?uO@Y$!KLQ)DWYC{zOS>Gi=OGOX<++;MVSn-IdMNue4KZynmGG{`@9ZA|DqA2Rn9e z|2UhF!L`bPhzae>Jxrjs74upOW5UniZdbt|6ea+HP+o_@+|ZMfcE2zPW_kLD?z?lo z;7El@6|(I_d+QSR{z zSX19b7&$a^X7^+Djx1Orl}0yQ5HmL&3ceztGYoU_i#9DD+YB)adV&*AX3ID$XZW5< z4(sjy7cCd>)P2~*aD3YXYC947wIT$=7M-di9UpOIvTkN->_#C{gAFlLniH@eNN0`@ z2l7{B+c=!^rx{X__(g&|{fW7y9WuSWH6F@ai82vTsqCy790Mv2XNkM<5&w6{#fQ8$ zZSPs_+g}||W&ntp?_t`>d_Ry@4WkfbpY>$6a2AdLN7 zc`?2)-BURA#lj?X)@G}^TygY?k_hniwpo6?%`eLIX0>fMBGVot&If1y?iMfxj0oEs zsiAAh`!1*jNSv`DYg6fFX#6|9_WvT%;rA0u?;604sxN+?A~UIP{cuYQYY|yy`}^Im ziM!;gm4Afs8CW(~%8d|&9R$*2Vz}d&M*b%OdH&syd4p}b)#Y-`;^i#AnhH|(`a#H& zLSy#Fr?A4C(S*$F79iua!Tn1b(^%VnbyP5 z(9qOEoNX)AMb6uc44cPX)+V)ynE3{?l1Pnb9UVYw^^u{Z_5-`IclE{o;z4XesUe~;XacMb7rSInDMcb)`{!EgJ>6M1(mh((MV+4F9#0e z^{%VQVy)@vX#$!Pg_C%YnFMRtgyE@_ZhURnf)nrDdB){@ZiZ|~b>FAqF;g0I6U%6G z*@zL|Oy=>7=xYn_j!7ovUh!d>#Y^-8CZtPy&^b{Vw95p?T;zP+#3C#V9`Y!ECg8o~ z@9L@nbxS;We-jdL`au7JwK%4$bxZJ$f@T}uI^77lJ`#*0o-m+sZB5n2@Md*+J7fg2XwBTzM=`CQH3wwz(Y+3X8VXXD_RXChSdg zHH*Z??>wKxj;M9p_LG3+5w(g}3ru}@<-N2}yh{LqsO?4h{ecJCa;;_!abFNHJWJu& zL>xd79rU<{W+rA3+@yPGP}M(5;E66#u`w_^TROWi*?Mmouw6_5$#`VFm>Piesh zDsa@f>#>iRKW2|bjjzJtoi+jOSzzdMmT08|(r6~Qzf-|*}pH;u1Rn>S!#7@ zdd*z$FAK5d8c5r!@%OBJ9{GCfeMw@zf~|9xiRh2hqC6mBG%F%$tGq6KF43raWY2TP z^NGXM#r*Yz-a3i>UBu2!G|37gMy<@Tpeph*N>@;xe|Ko|=Jp(xXdnUoo};`a!Cp_R z4elP?i~R85M1!UUN;Jc>8tXU?S5d-pgw0alfxO{o(9>0z#iM!}3;L|O zw@|BaO<{(ZFgpL0Uk;^91Qo-2VuB^I$_rgG!Dl`Coh8AJ^_ZyowaCxv35?U}B63IH zfhBT)xalPHSgS-btr}lw{0^gwB8)azhV_XrX4AZS<}w#ND`oi?mS8ihte~Z}D4q~f zw$CXsO!{^Ak5+ULtv;*au5|HovTSU@UGFM+%&AA$?L|hCOLm}kQWa(b^yGOlFnnbR z_iD-N&{-qv+r?PX-$GY5J0umWMD)7!V-rK;Vx@jfjF5bo{L)|`5SiR*h`bjj)10dz znJ2UOZh%DS2x;!?dy!q4HNwJplEjic_UTp^mQ_XzdhOs~ zb>!FW?;k?D-u3I|f>%trx#8PB6tgtmam<#fsR74N!j3-Z-z6Wbd$U{+X3k_i)~Jaw zzuE`sf`Yo6qEO2D)~_+~1SM4hz8dx8JsdlOs`z%p36I1dyU#ahm=G;@(zfIL%ZS1o zwKHA~ZAevxkIXy~N{ejO5yl&^VY{L`rgK+)|Hw z)qKg{S=;7)>D-0r#L%ZiF&viGqxptp(KG`c=I-mX@`MfXR<`D!TE6}CH%fWWd@U#u z>6Rg>U68-D+uTrto6KtwAQRQ4O_F2G{+$#0@%vlCur&ke({e3}|%rMi3 z83^UBghuv!qcN-0uCdc@vf+-s4@$cAPC*S7rz?sKvcf43qb=y)#Ybzu+xIA*(bv~c zjvlj3xGzwJ-r>(XaYkoPA9Z0jGa= zZ=|W?wG50q>65d=U9)Bv5h_n8RkZc!<6R&BANogMik@a)b>D3=mml4Yf*yh)a9RB^ zW9CeH9Fx^IzWIpL^5T1vcbNLKriwQS(Z5RG5iP{qVFup~qX@ugz<`Sjuv?>1wRU$M zC??LTAIAs|%CJ>>h!TadJ%7%!Ow6~Oi;S%%qtQS6ev=>arbh!~7cS~A$1tC~o{Dq5 zh7E~3goUWunBwB~Nn@T3-F%BCi$}R};)W=6x=8Nd2S$6~)TeBGEJ(m_4b`-nGA0~l z@835Mp4jGB>zE4=y<(%zaN2;cm-5G)o$EiUV!CXSue%rYfg8*~0GH<%_$zw1dWtYL zP7*o#STYVJR}G0#FI)i@pHiN>7QXkv^s#Va4FT8PsOyJe8+3U-f1`D+<4`bKj$s*P zi}VifUjAvJPnAZWXBk!1+B$!jeFp-mHd8rylB@7i^3W{U?muy(BXHeOG+L(1OW8*6 zL*{G7*d((J_}~=cV)9Uo`3V4&BFQq9#`};&Q(SwA?XJ0d_bcu0GW`H&*B+mrZh!x- zVoDDOi=^gVVt&%)$eOF@RAXcKOo5lRKBCwdxs0|>{in`H^e#5Z=IQsCn=Hlo5F zgeGj%MuuX!kxFA0$3%m=-eQ<^#|MVvla6ijvDNCk`?c(h`ojb69C0@xi@$1x?cWiO zPa=~RR4#>2yi97}veVz5Ho=k1?4A0xyw>igp(j@yIR3l8OB|%Bvv)4g_E&IW{_y!+ z4R-0+Pb)LIMwnV7k$M7URM)I#Oy7{b9f+))0*rcZNQ9d|?mi+;AN(F;laIY961=a$ z!FXw|mihY6rOvgt?P)%rHePQso@hKQJMGY6_Z9fk{2!sTYtUDs`mX-CgXt!|5E z@#F+{%fwc#SBvH|RJ|z84*QhX`OW2FtROqK(3_B<5`>A_4L$dHKKIe^&<1bK(KZuJ zBel^-8inHpZ!$gq0=bcH$aZ?O_Pbr?EL#NQyYN3%F}gZK&x_Vww|92pBur1lQa-LlC}n<;q34Yb>ZYS{y9*x+R-f!Rt!Qn%T#Dc*$_7C$K-yd{~k z5)Mt8oGvNwGc4#44&!Su8-dz~XF zq$HX($Atm{d2`om;^|Rkb)A~sR|a|_65Q~cun)9^4Tpasy^2CZw|DGr2NL1Q3C=1Z z-v>OB@^p8XhH98>%|o;GBg1dLlAtAwPV5U5X`vziT4St*#EJgxX6NptGYw>cu8S^= z>~o;Sd~Gd`^xDZ1UX&8^H@dC~+u1d#mWR69_WC`&2~&vvHnGWP>eZxKX%{ypn-7|Yera-7h&p1{vNvoDLZ@4vNi}_ihf&p94za`#; za1IiAQ+MroPUp+?5@)@t{EzboY>cPT`{Lge&y@EsYx?vT05}1pI6)#N^D(U zV^9{)Fvj=Pugm%=b(B^yEo~Z=F@jf-ijc7MumEkWN7vY=lb@H0Em<46!0j!- z3ka}U^#SwI);(#ZI@6Qj!TRorwz#9VxWl{^K9-2M&H-G#eyl^y6QbaYHYNF{-%fob z(aBPNF9fu;{h6?&4*5tSC5Iqa8crhF`bK zNCZ_%|8QWSXx8*_G%5IOAJKArd~BZX+4FpkdUG70MC|w-8K_0Lj66^2%~>jkS1?Wd zId1{}C#-ry%1OF%#L9zA;tO}RF-G`SxWU9$^)+eo>jOwrLQ5RGt^RU(?qpGy^w3aP zcI6vR%SWcx!ac#S9@@Ps2mImiEI#L;pn5+t0ZkZ<4R%99J}x-f14cFaY6l z?O|u$BHSiZwKb=v(C%(%eu2^k)K?k7Bn7J8)FWud&|Qwn5KIMF#{d=zVcUqlcV>?J z4${$=q@<)|r21)X74?rIdnqQ1p2mFc%^we6(cX?{XnJF}>&27ON=yNoqr7K9m1mou zf2!O7QzaZO&Y(T?f4u-g+;WKY0t+_&T9ggRj1ta^;w8`GY9oaz(K@w0G_}C?D$r&) zah+4>%x90KuUf~>XeNF>W!Ej1@zT-D!6k&WC%~l}-*|u0hf8*ZJ#=aad(!0NZCbbA zLjygdB8*0IM4XRID_y(<)WeGi0%6i{oO$4H=R?c?SV~8aHn(C12jKR|{)0x`%A z$Y0reLVWMC1b+w9FBGP2IlD7&WS=A&Kt{a+E9EkK4&V3@`v?=j57}9mi>OT^Y1CvO|Iz?-W~)ssFRQ<94TvLVfDfE}@b`YLMGr2|fAo&=Fzpwgo(9H2 zQCu8VD7hz21W*#f$&!PD+f489`&BO2QQ3i_mlA%P)KI@?FH=1IMXp*b%J>eX{o`yT zW|zGr`EX(SQ{hwFlj?X|jvt8~Zr%}mer}Kep`*EnG-Z+7eQ+rq1|4RS2~cDrN@2D1 zjUyX9()i#5zYT=Mr#ZHS(bj2Ms4V{hnX!2Ebo1QCJ`f!ObevVk-1t*8KoPHf`)3(u z*~`gZInp&+=vo@zYm1G6WAqMfC5Z?zfNgzRco*CN#$mGJ4m@jSGZfj zh7ED3vS~H*IrysMt4M{z$e4rQo>^Hat4(#(g)Z|sYi8kI>aKbZRUP5|K+En5M1P}G zAJ)Ax4>#O8*L4HulakO!2dWOoGcR^Djz6hP)}U<++*qG<`gfe3Ux0Jt3$qi+05T)( zJ}|^U0zB1dIP-b$0-5AtExXqx1A%${$#+yu3(Vip<+spN+NzSzg1tWaUpKM+9Qt#F z0jo-_`J1x&fD;Q_0x9b}DozCfbIpkttFDuQKp_!ECV_J8H3rvfwZ&e;a*BeQq`~};N-7t zrxSg+;t3PAzfCia-W@DGff3QFD%|(jnw6t&*xWZXKb}ZSO)tF(GimdxN>1tcEToLw z+S=l1{hK9>=tf9zQ`|X^wV0S!avJ0vmwGZk23y%k+bc6xJ2JL+Z1L!#{lqO&2Q*WA z^BI}>d!aI3;uW)&_<1>o>jomnMVg2!Ux6thAxy$ra-r{^eXr7Twnw!P`;I@hBja%S zE9dHsW^3D(R?<7_-4Aes@3Uv(h-E|xj#dgaePDK_8i7tmLBD~DooSMSE|rtHh()k* zaH!9f%VAV($b9yk^Vd+y*|G>7?%L#DOYe>^iNE)a-`RbEds|G$KI-9k6{x{g{LU}c z%9ly6E>gFp3|01Iir2Z(X|D~=l8vuF)T&%=tpeJsOjScBp zm$oSgG_A*&Pf2u4((BS_mFds@($ZgZd^_UyN<+vM|d$n$|OnKGkN|IOU zn!P<*KO+-A;>aK`lH9Qi>ltZ(w{p;07iJ-EMUZ>eW7esF4f7J9jdK#k7riRw20{NHTEAbM_hV#L6% zIXbd=N3a|Ft$RPvd&t%ACDXQkDs_A&^fSmS(C@L@3|rnW52fom^v&Wv-g$qh3zLXl zgM6X7dI%?2>9UgT`||*+A&}Rp-)el1H#J=U2iCwrE^j$W!eH`O`hRBcZIZX&d@aje_f?1V zJ|sYLt7jSonlyC)8ZSTLWVy)=XbchgYQ*Lbygn0cSw4GUW3$Npdi|lo`tsbE%_k7Z zk8on2t2Ew2Zd9P-9ZT=|iSHB1*pMHRpfJ0Q)IGCvSRJLrX(2qeQI;Jd7(?rOJ`nPV z=de0=z=E{a(4msDJvs(u?bt8P{w7s-WL!usI{QBqKKVd;Qo`QfR2g`(z+o3zB@N!j z(+J9-FO>nK;ml^NBy1%0RP)wfi4+#g^ZF8Id$e{D>tR+}1}as~>}ikn1>mhCOqP)L zA(r6VZ9&7yPWje*r$q^e`-#|0%(hXBRGk*LU>}Fyft5%{I$q`4E;8rX)}@!Jx`IV! z-1*m2eg3KD{vvF=u==Liqxc_**f}UHivk=FXQQLx>x!{7ED(s8`m=|i5#(0Z%zl0K zRjL1F=UMrM(P#VF(p~=f*8~82$;$LSfm0|w8bd>B!%uvDcDDVuP)oq6wwl_u1^*jm*EE)TBH{x#o z$-i`(NJAc;Vn7}6JFXm3{pGPb8|mazVDH*0^o5aFvCbdH(6}nNV^|L$i~eXL>tY#%>PUEAIG7 zA>3FsR=q(3C2Q_jnJ{lrt_m3y8YKVLehziV_B(vy_0}Zwss!FoH4YE%^-w-}iT~q| zep~ofvj?!Vm|>G9CfTv^mQ>IPVz)4L$N@5WN}Ts$Pr#D}5NC?$rNo=Z6Sh0&fU;e{ za$RL*8UEYnA1AOV;WS)bS{KI@hK3Gc$B>`JzCi8KXi}3o(tX?=yFrT}gFBVX3g<#~ z`|KdmE((h_2PH&m9n*vbIqV^Kh^o>QIv8syyhxhydMk7urq1x?)b^A^aGx?H1rVw`jEEHR-@1I3wi z?nkfsY>{JOTZTzbGxk%CnjDgmaP?Kc+Jyz*6UXCS^a*G(=E?Z@%A{$dgKr-s4XWDQ z0>Dh8SlX=R za}AceSG2auKUCg(6wZ%)H+LV}qeCgE!AvTrM4seFwNg%vtMWbIt}$yTi8kj*T4;L- z#pMimEAys)nmoX=;MS0hnn*Rp-{ZCDV`{p)$uZM8V&C*ln4<)4tPfxj;%?@6P)dMx zwXw>Wx#t}p#?JaqYCyNNEHWyaglqGqGsipK_tzfTNEZ_ac+DQCi^%%12m%`vb;TY| z&E0w?r!vs;(d+xV-g}M(0@lEQFL0b^nTZGSR(iN*lj&*#I`%Dv6+e!)m4d zyLR$R+lk}sW6DfB6Q;b&c%M_F^WG2+u%+YmYX9tlYkD=6hO!uaHhySdVBgCkza16c zi4zdbAe>YHb0vb$F-)RcFI>#8^z7>l;pK0AH8A2M?9EPpK&Q^4WWS+Sbx7_1VtK~F zBJO)a(GuutGsbP-blm{N#IU4G=FrxMD^=WHbhZS0%OzKaqP1_)Eo>xruVsN=+os|h z&OI{`eA#S?-`@iCH?QWIP+fP~rdz+J9p62tS;KxeF#>&e`8&xk{Vcox(60EP6t+~T zhjbD~|NIyZ=fS!T+wG13GE$uHmFxQqoiFL^Vu0%|y6dXM<_P~u0x55Vrh3SGSwTQJ zvQIDXXK{l4VsJXKVkBDgd4gKVq8`BVuS$h<09VHUbr{GDp3K?N;|wv5p&g&?SQp~z zGqUC@Z1qS4hIs-akTZX(zjsb_dKbq7-26ZEE15iHOtW<0x(5lc1ZnED<;5Q#*DmY9 z({o?fJD1W3>Y;hIwYapVb;5ffdOwmD^2*Y3TVg(>q){%(TU$N_mr3=h;WOr&_PZLc zYNDhBURhpVUMvZw5&nvG$1Q@Ot>CO->OKT=-CTC3^%WxBoG^`52V9^x ztOoqqY{VN`BG{Gs55JPo62pV|%~HQhr|Nd#t*+C|&AHSfb`%tB{3((-sE%ZUf?jY3 z>PJC!N9XcWw$Llpt&ygXDC~JU+tKQAEWcI|179=S6iXV{fAdDWnZ9W04!W1WKsF4E5w=pv8FTxoQY84PONs_ueQWjeNYnJ z{D^r0Z^ck!^iikbuO=M|G&RIyfhWJRqBPkRIom~~d^&lcUw#RIfi-3t?%uk?6o z380DZ-JWsOunNU)&*J0kW^_5TZOlEp52^0t^f0=~$$H&mc{77fY$Wq`|22=}2Pjbt zL&VdkU7blKl8ZnB>@`l#(XIE6Kzy^|P?Us%S^o5)1{yN(Qj8h|GHE#Xd&2;p|Jp__ zVPLBeBsOM{y->3H8*_|$Zvd{44i&_FIPJndS3Ft-6Z5$_BeJ=S8hk8Z6hzYEg>m{a z{K(yr%ewjJt><-B_|^8-JoST`R{z(M^@TUYL*%gOnlE>(i$+9MmuMfo%>Mgs zS?IcBi@0R1t~R>+qupF+?bW@|)GybT<73Vt)n+?{J%)bs`3+{0`lQT`jmq=FI{&i0 z6*IYQ1lUHmBVgmH7XP?_c%|IIuj^C+6({Pe>4wfROzQ*vEu5|(Ko7+^jePOme6lE# zgIbP@Z1xj2=C{&KiywqQnC+~HG!pjLMtHq_N}32m0|Ska;ON=I z-eTXnYO1JE{d=h;G+dxl-KT1?`u>jv)b_7d_20u}z}4|I8)*j5|O7A45(+!~-=XP+Hz4{dJ&24zzSJ~ zJA%coGo#e5MvzZM2BrJ=d)9&MVWcTwT?Q%WaQrMI6AQu=0mOTJtaMu2(FTTRvLIo2 zz2y4DbKKKi;rI<`#FU4z)l|w6waeyj5iPkt)^|LRbdWV-TFL+ zD~igVS1=RXA3eN-tAVjhIqJ`eiyNc!U%>Y zfhWv*;ou1FHn!2^wLmhkjkAheQ|T8_XJltvK00zZu2_}18=oCwGRLDn&^r0)c`HLB zi8o<6w&fr3Kv8UDP3g1w;}9_`90gno34aGjfd50uHM^WSnHRF{Ep)qbm^L*2rf=dp zY~(7}O_~ZvR2m^>wlVjH^SSwBoXJUfgXuw1>rEN2AFgE{^7j(Q@Dh_C*LG=i7VBK9 zbuyfo=^Cy zawB;#m=cPmbGay3fsiFcQJUp3s3=rb?qAkga};Dtj+I$gF>)D<-ADD~She)l7tzwH zs!D}uDo`bxj`G*m7~i&40LrATO+nxu)fn0VXhH>&JcZP}uX4ya-G>aP5diiA$7^2< zefgMw*oE?GwvvyW=A8Wq2e+$yi`^vR)-nE*mflBP?a*L5hJ|i^s z;h}RL`sr>=qTm>ub>HlX3211VBLG#k=ER2y^z<#8QjMl{uVByJpUJv;U*!FBd%ZHju=)H7dy!(J49YD<8=pwRWv0HTPH$uBPVJ$m=N zi-qjGMt2JPF5=NJ88O;*QbQGjsNd$)wIU1+Ku~2P1#KNL;89_;wgl@^d9I*|d&+M4 zv$)rh2+$w~>YDEZ;eP0|O%w5ANwFo0!zCKk__IUp_b>g03)A(vx(E)C*ExXf1CpWp z>3%C*^!2~EF3DtVhYU0?Wf?nMb{(BoALWVq3g8$2{^=c@bpi|-Xv>8je}lC&WQj6( zznu@r6xOjsVrwGME4dRFPpIuG=Pwq)-aSPjE0{qIWg^vT5IVVx9@_B(;84u-rSmUP zsRCcI!-Qr#m@;gu9T59xMvw4A;T+PQ$T2S?#du{e*M;vMbbHR zEja(wx}2$ky|Wkn}XkaG`td3!6t{f{DtC zr7K?IO<)#^!+2qgv=O!6KK9sAE#bAF6<8v3-+o8`r^rJhaWQqHIN)W#cq&DWyXtm%QEsLs}s<4%DzIlRxC zA>9rWog9*-kwZY^PL0W%M%`p&(>Rwit_wu zwO-8!v`39YJ;|7qjmkkqE_Y@ghu*TIiZQf>e~BOC&XtS!2aI@6$AA(*U{fvwDo1-` zV*`-FriC`3_W4d~&^W}bI87^z+l{GU1h4TiSSLmd5Xd}hyxYI#nH(JJvs`b#l!e>) zfWh`BJ5hg)iRbGL6*HNG%S+|~#D*x`h^GhZ>RNLnYKMq$-L{x1%;|fgKi)Oq?zMpY zsz`E=Vhui58Cx75Jm-+)a@^{Sd`^>-a`7ti9B6!$O)1H+SFjii^(evPpt_+b7^}>a zlOiv?JrYZAnW?VB*Jo>UsBj_6T$5SRg3*YQn|6|^V@}M%l!0$c^Zb*q^ zE^(~{F6s^0HjT@cSwf#+PfIlo*5i1g>B-SANu<_$5~HwFAzml<9<-lx7nc`Gw$n$$ z4J?19bZhhc*lECR0(&y&)Gjke=57rS%G-lyibzyO$FRAz4tdDMwn&CJyo&}CP`zDY ziM+2o1|L3CJw|_4_(9W_eqH#%Z%C?r90_*E)}NIaC}idCdey%^(5&!v6w=ApCbMN? z1$lvvYhSJsgY0)aN)k&-(_agCiqgMB@UEu4t7y7nr9ti;dDE%fDr|b_URFG;xV4a) zy0d9{`)QbvYt3MNrxViwM_lv?U`RSwb@0fA9CJ&lTV%eU@@xYWW)-ol~~ zQ9{?Nk@@M(O=Aj*%_rwUHBfrzM3ZgRQH_{R;b(3%e4sL}UQ(9+lw*mW&bH~`#{>t( zQ$pNgX?zNHgs!)&u9WvjJ6-R)qT8{iz>JReh!tZtA1!j^*t(~h{;&&|4Zb@psS%@n z8|o+Y25(0lEWep*=IcHaDFd5ea!G_+ZxTF2vF9SmSSv=`C}rwlM~D$#+TiN-E(^04 z&F#6me;-;Rsj6d5F+;Wl$@V*z?)#tF72OnN?c2(zDc+|wghYW5GE@@AJAoV@s&izSJfdgYKLgkM@Er%h`}`BISdZ z`P{^zd=6VEXB|qDso}Xy`JCv;JSS|AL&$~htI7%>tp^=gQemB|V&$qK=mEX7W@-9*W1QvLk1iR7D zXc~(&r#yUGgiaR@jtw0(w9}a+XLt2* zc|Uw5)_h1d61{kd8EFEDu9aC)ihm#MTJyJTNs-^Ch4fzx9l+>v<4Pjskk}5s53)2mrAn2-kVH z-`+syNl?e}>ie%3FA-~dK@1cD!2fala<}*4wumyBfxw5KU-;*ses>js4ablGYoPC! zZC%cE-UYNW?zo@VMe%U)-gRN(Uv?@)X39+s65%hy2c&q>#EI~7!WuUJGBGy-N8%j6-*I4ax>g8};eob_FAW@uk_aWcq zaNeK|W{+*c!3oKvfZ~F46dWn{h%70tYYS$pI<6M#t0RUnvTx(*VKT^0xgs#UZ~tWk z={Z6jdqoVb<@leiL?$e=VuX0bswO9UC!YQdHzzYS)34OdVI~J9lS0Ke9Q~lanSEZ? z;62q?oV#naFF=ry<<-$WU8#u+DtQ@&3Y1Q&V`y1;k)i|0!~?<*5lO1Vgv@X76aTLl zKz0YmOUjUS8C|KrvtI|pC@Wl?(6g?sNjy13&d@MU5T8BEJ1a$3xTO&AO**D3fOUk) zmI34ofpP8ec-8n1)!Hx|i@EPI2uD>MG_5^UL;irlG%3wPn<+$&w1N-*r^4mPA%a7{ zzzrH#f5Cm(9|(TEyfxj(|7LeS#&>4_?UOu9Tt(ItGx!#u`R7Y(EWU-H$D1JC;_@=7 z$jd|23^DP}a3s6s^}XjBH@GB;qyPR11HCubo6bl&MnDrj>+T~d1NtI-f*)y7xvaDz zhn2&zK9rNZTlr1jKo-|7y%S2m>cZ}@5&NTDz<5(7WP5&ZH=RLk=h%aex_9|=dtnhH zt>WCWbg*(XJOo~1*+!0EoK5}8gkVykn(?6W?YV#HSFh~~(B493z6&DG3zWsJcn@^jxQhOMP{Kbs4c`USgkwrxL?7q#cQie$A(iW)h zODj!d=fmXTHNC9w!HG1|P50wthM5#mpBP1qA6hBv{-boPK$Y{|Y* z7T976{Gr$`{kYeOCBSMJFuRUp z_8$x==b%m#jCDZbsiuCiuzo|~fzVKC$nD`xEQo`(@v^V0g{YrR!AZBGlYk78shvA$ z4bT%6q0N1~xp>wi&b>;|X8`&iuM=gnd8vWr72#Wx`c3*6pLkr3)Wqxb|NKvjEhxF@ z!9iYY>FpOk^mFlt*Auxz3&oJmW4cD=F3C$t7y=N4j_rOI~Tb^FpEy(8Ka z&DKVYIcW)fLf)K2e^@Y7GSJvqd{*?B&x;odo#VM@SvnZd^QFbmI@h56tNTUB)!yaP zk_!Jv!C2Tg@Qkr&s-E_7Hj9Wf1wgG!KTr03)%-E3#$KzN#y2-PY2fazVW`0E$s^OV ze=hw+!E8mvle0J`eqofiD3F6TQK$38w1EGy_bwqJ;pcQ}$|tnKzM{%9o=#hOFc$^& zbpdtUiYG%0c0zF5SDDtejGfHIpPU-1(e8N|sy4T8Io+fj?Z3+}fYTFrC`rKP3KqB3Z^G;{d#daQS9 zFW1VsBa_Y|!WbiEiO2Qt4u#8n95+Lx^6ies+#377y~^hRgl1;(2bLq93;4Eq;dW%J zddaH4``}=bIF+BLgagwy8Me7B5g1+A)Q5!kq?FLdZ!h!w2#bz`$(o*|5SXA70<|b# z^33afbkFkL97wLA8b?QP^joIEU@+vJLxCXNeOHFdgZj%U;hr?)28mltssszX^#Pcg z>g@QwWMK|kG7$A7&=Si(vu2il? z;Ymfeae7{5L6hJ4Jd4N2|M~Zg13j22;?gj#Vp{^3_A+ChEtq)W$z;gAUYFEFIKg(% z?41_%XSYJYAVUB2CBnnN&&Xa0hs779WcD{hEdE;yLP9FC|GsL-!!zEIDVg*xT;BU^-=5a*7O1xLgE{Q-+p(}^>x#6s=LHLg#CM9 zB{sa;`qe}pHtKl{tYVqvv$bK zi2n^x+QWp;?y<1~lA|OP)5!8j6CE$IYZ&I%F;4z-4n!$YaKV4yz&v9FgcKTzwe^Y^L+MBLB9HTBR0%|6@jvPD0ONy_We=Ad9)91G z7x#>sot~~;{P8kQE*Crt#eZ}7^Vyk&ZU(mcFoz{ggjr&Be!+T84vIp+?&kF}SWt>u z(a0l6`?l>kKde*v4w$L^&b2F+r`;T2gy(S-8G7k zimEE7{iW_jX5clrhXmBpA0&N|bh~cxT~mwCFO5^N%t)wldHEn4jj0v40&3{6cva^E zd2Dp)=|+Z;yn9as+Q9?%ZaNJwDpVY zPD9jPYBSs!ANSN;%;Ir7wr?vfHyDsg$nLuAx92>d$}L&s1OrbjeAH5N5g7Ky((~%v z1B#4k$b;+LiTdU=Q%c{Q;^`elZy@Wjac0KMgb>d|b$Un-pprc5UVO?oU0POCE4t6- zIWJi&8A}c>RUJL7bTcF!SKQD@PoSc7G$&>+oXeeM)0Y!fq{A?4aP@!yARm%0E^2mQ z;2`Lp%`v6D0utxPAM+_|1U!k<0c3Qgd=~e>TojR=TgI8hb_8LX-Z>DKIi4h5< zT84m%h+=suQIhTTqjkY|F1NO+PKg;ROIusBi!$>*7)!^<itP8;i8~qjPS#t>KdX&z}RFtDa!?_kNMe|Ex;+zIvD=}_Ye6Q zVI8o3>#ZJ~L*=l)wSo!E-_pnbyJ&;AeBW;9YX_HN?&hq6uZsq}-EmK`Y-|=L)`H;m z9?NO&^YB0t*TV}F7_UuS0$#e z_utHn_7bn!zPN}K;LlxnHw1nCmI5+zBYyEw+A|!VcfhYgBZtc0VxaVwu>Q)5iQUI1 zWaoZ8Wk&uYg0ST`HtF^NJ-wp;vLlv*=IC7RfOUWE`O;kK+UdQ!!9Hz1$AH$Uuqo%r z=a;GrI6F+4YM(|23ONTakYS;JKI#ao+ls8G$BF-J{fTd9DO6HGwdP)zZ58jku#CzP ztr~ri`#mHc;Bd|(Hu0+7JbvuSy|riWM-$rKGX%^)i?{P_4IB`ih6Hy(i1@irUSlWj zn`HtO+?!oZ_MU`?-A+e4jBm7;ZiAZ%CHv|=DWobwtq9^V%I#FUis;Nwn;zX*CVm0C znJ|d=07`Hf$q#W-F14j8W_0+H7IzUA`dQ z3oAL4a?UV@cPG6w_Szd(C=}wl(!FO%=(2bH=KZ(&+~hAxX){(~{Wkm*;2|rvjITd- zgtu*;wIX%AF-;lA>CYorV;?w$niD;~Aq)i$ke-wTg2b1)1wUX4Aj;c>UmSq97c&bIKVDl?_tKJdM`juuDjV*r@bNUI$J+VKU(nje zdgq0T_pfTm z_v{cHeFk4PxFqyJppJb2Eg^(rgHb{m<!!}#>tthMbt>Dj< z%U*1TGXD`S?fbfQCyC4r*0`shgM7+=1f)i%%c8hjWX57>z%+i2otdK>@N}P68|}99 zo>jjOCeT569CS3_$G>)AT+Uz1jCG~(xjSjId;gE9ua1iH`@SAfB&88SLJ*|{q>&bo z?rx;Jy9WHw3Mkzz4MW$Ef;31D0}LtM-7)Wjet+v-i{)bRhxb1Bo^$R#`|fk@fRKX~ z-cPBN@J%<9!slboMVhuhbM9sqp!0T_bG5B`x_+lfos_?RNyK)^Kr}ow^cOE=Mr<_p z4y!ykO;zvH3|-R`iU%jOeg|v>{@&+*aO?XESI9e~RSwlo@Tg13ZT9aJ9>H`?Z z9eMmPmlKWx-??3O6%P3N@4Z6uiF4z~!T)>?TxUsv??_{xUnzLLlhEMl#KR|AIKU^= z3+%NU`L5-+Gy>HrM=wugNHzGC*PoY(xpz;JSJD~!H6nY*YPQ3H=t0X5M(#S^iH827 zzQ4pnHc%rq59btH{$>qM)Km)-77O2JjBpLBM5ra^933ecZEjy!plTx?HZ0BpSbJcT z>2;e6l8li3NEdzqp_Jt7on^$n|yw#HfvGT&(VQn+Hs#oOgXZ`3v)_)!FEYG7?Q&c$&pw zb=S=1MdB!<=a+Gwy>fM?{E4l<*ogBY=eX@vU^&t2Qe*D3+RJMx=628hUhD!YZ)HDx zLAd9b*V+!Y2-%s*SkVlt@IYZ96)QK(piNzZe4p!b`>v0O`yf<@=gUultaXcpdk-O; zPxY_IjEJ1*G&K|1^gnew>HkZ6s?t(Y4E1qv_j7PYzRfyfZdItNmimSZwTheedh7)t z=PJM_1H2o0O!bGdf-zP+SMFV&3YU(VS+@p6*G$8#V4s(M4A%>Z^t6_RtONuz)cpp$ak&lGgdIOJ=9X7@4)O1KXB*{HcvjK1)z|QeD?`zI_$56ZF^Kq834!YU%!iVm zsSwEBiWb}50I!k1K(rIB33$zoye{{4r&}_A^J573VtvKv8f|1>GS9jY0pThyP}AcU zdyz|AO<&?+U?uxJ6JHFKj4X-LoAo}cHQ6JuJCiYAIV~dgP}7e}TU%)6fhsuS_61l+rk|uYnqQjgg-^7hDKHOQak3=Og;a znUkiIP^xj9tD;M@R>N=+zvNkMBV=*K$Q&5oX#Ts{(7ev|A9_Ovxo{`>6cxShNJW;k zK25FE>b3a_VSLrEA7d@(R1!2M-f_?CCWE)Ahml&InRC|}-N>fhUD$|0WRrlyf-qAt zv88qtb-|wab?>s1)277rv^#U=h2A+XQscqzs-6(NW}k$%rXfEqAKd-XYxi<+`GCPC zFx-B7D=Fs~s+qVjeaJ<|iWCqj{Gf+?Q4)?D`byMN`EUdcttZix7-X$9=`BIz#I!rp#tl>=zmot|Mq zznNR)oGKRXpKXl?A91aUV27>xKFi^ahn!^Y(?%K@2=4+WfE_fev`#xDNN|2 zGYmkUM4U|}9ki_stw9ZYZS;m6^6pd}_VWbRZI1F68^EV>i_cW~Gg9LY2hSgvDkdkEWu3myqS|)ulnO{;mG}&cBE4K_1@A&RYObXM4IwuNO!IOyWZ(* zKfeQcU>iff3=CpmE~So&sQ;|{0H(c(%4)sEJ}~sI7_$+4D|G31<-w8k4#)JT%*dUH zNQvd22IRS~YQNZ-415n2UrbOq;Ehg+90spl%k@~s$O3fSmyPC!x~!=5`-EZtqf6JZ zLsrG~(%G|WwG%UX%Zt0TfT`=CWk-vppm1N7<@_BEgQPz65vtig zf1*4Wym|R#P5=8BzjI%EB?Xy+4r4iQJdN(Q;Nx)CVS_fUMlH{hEo~nM57tE&dg0az zA+JlAE%wDm&HORp5^s<+2o<&CSnlK~fiUn=mQl@CL(Tc}jtRB(QMfw4K?O|f>sfJs zjj?I&Tp7RW2MjV;vnG6WZKn7t(PTbMLcPp4Fbnja)FVMF+3sWu_>Kaa77Q@lvgq2}YX0N9FzvGiqwzw9kDGtiJ;c4krU{7m)o<&-Zk$=pK^)>0Y zfnb`Bay?d(Tru_H6gAttul;^$2pLT)15Ia0Bc5G>#JYc?*ujbZHAXR%ySIgVJ4lz@*D|mjBLn z+(}JZ_b&K@UibogVDv<>yG_XYwUk=!m_1*nDJ1cP8yhs*UhLUSEVk~_BxXGCv1{QA zAfb-<}HU1Bv3E*4$J;?ttNFhMZlx=<8elhR@ zVk@;W7GWj{bu!>pXK3-*ak!1^W~=xOKA(ckN>nG6@`~3#58f5aQ?`Os@MsQd&Q$B| z$ebK8Ti&ucFB_|5BiqYyx{}k=%MzLIGx^<1&20Y2?!TU#-1a$=xf^sn7F&9j)qY_H zWu@O;@*QXVrAYW-E@KuOBTZ30Z?Yn`xJxHK@SRIG@!X8fPsw|1&BJZC8Us=mxi~hT zZ}DZ=G-J`cZH5IDQqlaHuW1^R8$2lyGz=D^+8dI#)$-mhc zN&Z<@xASRg<=}L0^F}_){izrJKfpjVki|e2ML%vJAS8sQ1V?1dpbuJ7mzB4Hm(Sr9 z*D89VeZvm+W6sUs*9e!lA~tv$%{L^DOUofL$WQm@F5oW0W;;F72nk{2>PdbA{Z8F~ z@0Pp`%j-PA*ZOa%!U}%x+?hWP!#S^$5g_c4_DCwzWd2D*PE_`nvFwNOrAjZY|vAV{w1Z5qRQ>-CdFK zsNO9;{!2c@o;Nk>Hl=?pAt59LP-e%9u~rCA?iJ0*CNteTg{|*pnrU_5;Er2&{V&%K z`I_XeFw!7kDRQmd=q~WA`DA^~hG|{N_VmQ9cT2ro7Eu-I`=MTHZ^?FPf5y%yFGjoc zH8tFDAb#J%waYSZS-Z6=F}xdv0bcW#`A10E7jwO6d|JE4Vs+?3kz((<)_iXlFBsps z{V6Ei)7MC?wd@xuqFp!x>(yoHQ(&WWO*yV=L|oe@WVrRJXBfL~-P39=V?3B4G9CARJUT*~{ZcE5T1Ey?x%n(jV9ELnz=JW32h0Zw07xC?wf zWy6XLqq{+v`bCH&=NT`@jmFpC*297iM>5 zNwW{>V$K=OQ?Dk$TKo9x2)b3Li>Rk67b&Y{2FE_bzvrL1Zw2>Ju`)VRqwv^HdycHx zUeUdbwXGX8B5BY+h)^uV#!#@?a^ug8-U)q^k1uAW`t`YmHg=&{e@LI)=L^Fx=QapS zJpr?$yyTRvas%m=Kg9X}M-g5NvR$IH69};_l3aUAY?hZ+)UR)l8u_2?Ptt*kt;x*_ z5$b{XV%XNo1K);%UIfwj>b>^;Udb+qAqeHz%F1YO9bW``BIX`p#D9@gXm1g6wJ6w` z0l5{E5eQLWy;h5m=DL+!pIu5cjvBSl$xtj;i+`YCH-iB#$0#mmPz+ree3qccX28^A zQfH@Vql>_?9583dw!yGuHYYVaXXhP8S4)i02tPQOLodE7QPX#2;YG3~ydcnY80C)7H8s|W&|5Cxg z_i{6*z&b%&KQ6UcD)_%0AK+|xuiw4EZ0T5PhDYe}5^Yf+t5o4N3eL666I~W;F=@v9 z_$oJw`s&gs?a~PiN*W0UVikk4z16Idp5&g2*Ujc=g&y#ljUGqJt7wcX zHl((DfYy5uMX!ObZnXfVIDDz;x7os0Es6xf0EC(*L^o~p8~g=VU7I9sJxp=1 z%NZR!MKvC7dFKn1x6nk1HGxEle41Kfur1Nyk1k)jy!{HYsL^Y~%JBO)Oxe?sP>FV5 zv&;W9OH*X?Y4V?qyBh@fIsc>{fz66xV8Cqje#V}E7hm1|Nr||T$yIT^oPS&BzR^!v zIyZWE|p<|dK@xKA&(PU?X_G64Q6kYxO4dTX6 zTI889UxOI(=c4t>HQ}0?T3VX?d$>+TZ87%oCmgA4%s1vBf%7j2-Z%@JJlX6Mv>oABg4qQdn+b9*7p=B~Ek`eY$Vw0SngBhW<2cU9ak$+QnOtUR?*O6}S+T!^%Z@4i$cz#q)sy7a%SF zpG{&1q1{*d%J_D;XRNK6FE20Op~F;*m9dUgOS5H3tnalejRHj+F(CW)e@U?l~K`^tZP!&}Si@-I305|N_ zvKOuJ<~|=z!0&t^%IDGC2+)^^y3QG&|I-3UFJH?MbVY`(h*T9kd-J;;ymb~H9(?Ac zjrV9&-kw$nrQ;-i!&_ArWL4xzf4{y|F06D0PM4$r4*V5`R*B0;y^-cp+Gziwxgr;?T>f^gtw&P3Sg z>?OW_xm4_w_llc^5LZq?_Os^T7s=tJVFV`1%c)(77gN9DR0T-v4bz{zR9nP`-RG<{ zUe!M1i7#C|I>iXoZJw=1{Px>T2>S;5b$`49tvUKwPG=InNdW4XW+KKlCrnv`t<}$a z*cT%9c*=To?aeO-r^LRbHDtN`wN@?@M@(;p&932rthYnR{b9T?R&S`Pb@@b7%h6gM z_68eY{T&^lL$XEg{5UrYb6v@si!|e~0>yPrp6tmu=9*!vX)bvXfpushlK8h-cg>h& z?@hz=5+AmdaKnt$=DNpAopFE02i0D{o^skS<$sAXQC0egqxNlcSW-O5qBxQ3W8S1! z_wB6Z{I@&LqRj;|X^BbhoPeTw;z>OE1e30fWaGaCoQjWJ-_M2bpzWVZjELxbLA?7RX`0-sX-R9-irMo+rq{Cm-p;dlGi271oiQaEj6kb< z3$nlgW)-4MJH!2EU!Ei;Zo*R7FPpO{yIZ8|i<6U+atrK^q*9~T^FNAHVCy!5RB&Tri9i2=2p0ISiOb0GLLLinQ54;CdrV zEFO8e;9o4$>l}Y)nd|n6>M7MLeF}2fmKM zUu%=B&wNcIN7M1%{qXcdS(%^tb7Lh&ga-=OElC}Te$mhIS>Ppdz5S!7x%H|AR4Fo< zI>~%lJe(S()w)Ji6t=#7&nQ11uFDPD=p~+Qj^&|WP~YCqk2pLpm(8EEsavocNHll1 zN2m>)wV3#}>O)W&G`}9Hzhx(RY95)Y@y*k7^MY?cqQATQ1#EkiLV=w6AF5?w`Pqyk z7>vH88}KSk96Llj#z_M1UMw@bUn?*#JuS_0kw{B`Kc-z4k85+? zHB+kC?AcM3&k`}o%6neq81mgSZ5L1$|FQ892ZtAy`8I|DO?-LnjoR zeVI0Vjb71uem%wMmP@&%R!G_(_2QNhps6KSJQLLRNu4*S*et(Qq7P>XWYNX-D>JPA zh&^)*5I8YH7F;^sH}_Vw?R7lgea`tFhPWUQeZyb%&Kbc@o2EWp}9F3 z5ovedsX5C(!-dw{H$ym+!x_yS*ND&rxz5mQ*l8pLseJQCZMf5hH93Ef)zr8GZo+2N zirN*I$%P{>!_9rl5@nOST9^g?L;XW_YX{!s+BeN-VC_4Yd-}lj+BuvLBAyQFYBSmi zdB2-?kP-!%9ACrv$CAUljqcZ*YeI%$;zLDE^#B&#Ri{JCo`USh)ZB&c>NSY8p3PY9 zbe}mi?C{mEKxMs4w1%DmNB|}O*1+-c%iznG)TMOd&;oP&yCm@$*Aq+24a=_O?;GB! z@u`p`_@D({_1Ieyx$YM38sfdXK9w;c5SetnLzY+=vhP8!;K4bk6k9a;Jysa_{~~#gbf%h7ymT~n`8Y~!i*LzEo%0P8`fD}wZ=kA`v~3)b-?YBWtP9@+h@)5 z5K{!uV^fwf|M5#ZM%q>@E(WQu_clTJVxWeCTzuLD**1N(3Q_dzcpGj#10eE_b7wg5 zrANN8-1u##(T1b~Wz%+5;94s$Sa9|~{}<{^2{!4yC+2u!oCAcfH$(qZ&AhmxzW;DF zp;QZ?ROCw58|pHYcfm2=6bopJ0dfs^A${#n^y|G3z0$?%E)>1)2EFb=BPVh*Vi=71 z?R^p7(|*oYSYBMFyznCC-p`7-a=fwmiJBc~QA5TN6&$lUwHrMVAu(hp=xMzF->Fag z8afdx$n2eO?Iw3JMZZNXyUUMn=?_;UctK!75GkBD^f!fQjgA~$EJ$z-cE9_r899i| zE{i^%B%v2h%lsN*3hG=wRCO+n=sAq4w@><#uP1W9d%lP0RvjCe0l$7Bdv^2j$=;%< z)XNr~p#}L_aXC-yCCT4qbWcHBx)*!n7S*01rPi~O-ml2H5fGBEzoImqC_7#$#y@^% z^~TuSSD)hS6##^3XNSWEno0KRl<8i!`A(yu94xf1gqbaWk$g+R{VEZrNTM5rZL?>S zqx-x}-b80l>Ra3G>4XwB_^JqI|2}#Jnpwz$5Wh{|Qv=uVynL*V0j^&lY`k+72VC{; z1uJXA?}pt0$!-S$C`4SXer*#tKO&%xdyPKVSWQLZx`<%Is{OInu7&fJJYuxWBmb8oJ1J zJY(4~1;++FFM6d3A_5;fz=^rL+->*@+N8vwf!=l2i_D2&;CG0-)?}?F)FpELpc4{JG};BJvPXV{mfk|cV(R- zpdtN+2+Aq1v+XeYVz%jipb?-v-zN!pj1gNs|6X*?4gkaQH5ntNizqXPvod08uKMg) zxd58^om36+%QTrD?7uk@WrgabA4fosi0~d}k%aQe8B|7-=~nJ1T4;UH2{Qk=TyklDY)< z9~R}Nwz?W?X~C?XXKaV_J{rTm$s~Y3BbwkV!UJ9-#F!tr>4s3Est{~JF5O)$B5!|_ z4qLp6k&fq)4KzyC3}g!7QYv2NsN1wWxW_)Npq{Ki5i!4rzQ)u$`_Jn@k!C;bdfr+M zMYi}#fLRev0s&=v`}A(vVCp!=bN0)t|Elh{W8@{12~kV2_m!ujAYGthdw^r0CFoBA zTJmz=nu(wlqd0Wjxdulze%O~Cs3zii97l$cKV!f1POAGX3No)Ta1vj*Rh?Bcrqq2W zX-{)|yN7p8CNL_5isBadvvV2@-Iuce53BDvx?v^U|$3A(b!h+!>qs&&X^G%}HKSLUN2QY*keU4i0c#yh4cQeT{9Gvs! z_xd9JUESYi_v%;pjwEX)w)h|u9=e?b18Vb%g)qB%gnh3o{~jwy^^R78tv`T=Oe4@9k#qo&8Z0f9D;-wMQ#P<|Ky(*No(*sf`Lm*c42F5q&Hc2=Azfnwoc9siEbHq$a#EOUn>FSRfp zpH{O3zQbKQbFMY!;K`q%*sRa$7;4u3y*xgvCSk+g!Ybc~^m2?0ls(&d(#{s(+5h2| z3i@33Os|V3*y}m>{;2?Wky@*rR-cp$?}@Su9@-b2%6^H-xxPqjdiE!p{i-S|A%U=g^$UN(c8ct%+qbrm=b; zBO;mVa&mKKpSkXdg9dyoR(Xt%8`j)8j#ysscMeh6b$-O!A|xz%Xbj*$g1w2b0RdSNnI=^a zie9x$`E8D}rtv+m`KFnf5LawAqb3ed4;~ZA$M3>t?+w5v&jN`%9g%_ft$ae#b6vzs zmPb?~(THb`nNl;MHlda}8N9h+E8=`{Bl>vhLMJaEgu1F> zeFKG?qTw#rlg+@f=iuJ`J_jG~)of7B)^}qos9*WyQM*Nh!y}9^@fo+-N)FHfBVO1w zyQ!4j8#3%ymp>j3?(-D@qum9GU&J*=&)aaHsdMmhQ$|VFL|{IBXU32;Y@Pb%$8O=) z0vlE!KDg)EbBWDiFG`$Q%8utgTN~E-^%i@EIS8a~D>ktM+p4V^V{yOyym!T%Mn@3a z!J|?4uE9b=7$%6XWP9b?WyllFAf`#Y$(~-u$^iu4lg1apHk$Ng3B` z`C>ON2z&Rm=nW8)4wHUHn^|KH0dUFz(SYcGABwv@dPfJ@;ZxLNvKK0DnCEee(XH^x zOqDk0Dn8SbzAm3CA+11RXdjt9xgKjWI^3VHe*GD5|Co72Y{0Oq0r^Ju=K(5uyeede zKU%E>3^9S@DMUqR!<$0QnVi`fe_}>WWwh4~) zs5)Gc`U;CDo9Y}m;aDp$uj?G^J3Xz%zw5pYB|KS|3((C&>Vl@nhxUwCGy*j3ZzFB) zhhD}%y6@S?3Od}g^c*=698p>Ty_9I4Z)$$0la+-p3f=d!&6}|HL<=skrY(rgh`^(T z3|#0o_p5t- zmpSmqDZW-~ox%mlo~fQDCdL}hop+r(QE8o*mK=M+#x*LuVYd1zcxazLsCiXL zE+{REvIS|CCRj}pcaRnX?+IC#+t;SnTZ(^>sQjJ==MM!a<5#mQq1cXDey=W*AM6cx z!|9H$WI~6DWqyJmgi~zE!(XmBp~4eCptN51Q@`JEeV>w{ZiZ!iZ~$y^zS02N^@e3^ z8lZSZl^R}NfG1xvfNS`=b-ygQY1-N-ACFzGo< zlaUMo#&s%WwoiJ{H$Avl&4cKaYZVA~DegLM*aW=L7%o92#^E%3PjjuE+4^I3{)A_$ z=S(v}Jl}@z?NLt0oss%TbKb>v%_}s!%`7oSC2v{pAbD0$0OUu!s_a%p5hZ4rYg2l> z7zSCC#NvqLfQ&eZ9g)VsMT5_QLvRH71!4W@D`KEejH5W$U8df z5<^9_(Qp`fITT%##zYb{smopJ5Hc*ylN1Mbb+720$DV05sXvs8Uqqr{zz&|O^rVVJ zRcrmCl3fAa-tQZ>C2|nsDXbrpKKtE%yLC$$EYX#mp$EZqKr9+%ONP2)n($1qs$#mLDq`!@+&Aj&G&hl|r!qwMG za|uaS5ms!<`gvG9RYdSedJ2q7;WDL}y1}=5cR045x=e@x1~d}97e4*7RGWS&j)Fn+ z13wkA6PlUPXHnCn1u<;(S=+8Fg#$e3fcHQlx1tgv>{|B$)iG;&g@;ixAJ$6{Qo5+z_3Z5{gVOvu?#Y3VCLL^4*Wa=cM$_dI&;;i^&Q@lf-b*Er!42T-uY*Fi*k5VdYsITB zmhcWHl&F?iOM`s!{MTf*PG%_FTHKfEt1dg*cUWk`u+PK(zl^f~pO|B05dhS01l#9) zbv7M;A_PM3gKlE5_kIt}{*fy+SLs0gB*-*dPl*-6k%ANG=&>tVy6oM`J0rarH1rgN ze@A-HRzl2qd&tts`#Ug<;Q+I={uh(`?(+Ds{R?mNISUvpZcG zbEk9vD42*t0mBQpc?JCH;R=4fd;?|a+f9&V&4IsP&QZP)wO*rD*+NpPpU8Y$zBj1g zWb4*VnChF5cXe%*%5l=K^Bsg327F`@h>#pdm^7evdSBX%l=Rdu=}~SrjYh2IrcFP& z(~|I_L$wXC#pLPeHEjlq_^}5MP5Cf%D0~PSF?276-%Z z)Jb%Wg@j4efK(Dl2UPnV5WhEEQz2ak3skd@2oEi#ufKk=N`<_DW)7|yHC+!RXc=Xu zXGBUW=#WZB3>WP!P9iO}i*-)%hQ90AYmI*0AN{d!bk%&~jOIq3VU`14I||Kf2714U zI;!=nEO#R4pZ&YMcvU=^Xt=Q_tiJFGx@w+tP%qry(<8YzC~GM1U3GrYv|~_#y+of# z3_@#kf+tR8(-21dP-8@C%-mpHW82+m7k9i9R+s=DK#ys4Sp!%t(2(Qo||t-H~Wxp{(W-2H999J=U>v>a;^A|F0}yQ%^dF!khV={u&kZ(>hXB7YUPn(%R8<*O#t zz4Zzc>B)W9pAn8NiDKkAqgSrjaEO5bukY_j$&lTRt$W?qt-AGrvP^b+BwGeeU+vy% z*(ZtTe8(4q0}Z@{Fm{kWtW)+LD0J9o-orD=t&c%uL(!~}KsYobpFs!2C=y(RN_+H8 zZd(J?w?7Xe*dBv?t5qOc{291`S{Vz+FR@Cd%BGmz^VNm3;9LsQz=JS+6vFM5hjlyf zy#Au^gy2H-zlvy4b}Zl$#3+Y36#JLr0Fap|IYw}HLV|EEu^D%P~U|9Q6K=pa;6(|RKVzU&HEqYj52 zc9u)Uq;7yZB3}(z0irCy5j~bNAfn)gRnMf8MXXvL!z&C1*IdOgIL)58)CUO8#bqSC z4-V}6q%<&phP?rj9nLk^1O12xy1V0t0>yfq?3|oxnIj}bq2&}HQsMR&F7hN~YgD{T zto!ui3?iQ%a&i@K8xc&9w-o9nla8nT7SzEfFC}e$4pO~Pbi)|n!Vv&ozP%lqiJIzJ zDl_U|(EUxdO>$&A9yHW0_uNP83En?#=;*o+%1>9FO>`%{4$^aecx=E|Wyi$DlAUFfr43$KkG2~owg6$R`hhLpJo6b##s z>n0_}k*NR|(Q9Oog$9bSJxbpXRtIx6BXIm4qRo{Mvb7Sd#0T@E2u$Lr(BRrV))S}&Sl@irei2}F zkqg)M+A~2R+ke+>yF)|r=wauzS-=!n)c2xYD5Mw@QU)bL79Q;E5?`I(A!+tm zdk4_%VVKDC(>VP`rUUa|`6kL0_6?GY79 zS|zY;NsSLMepn?{Jyg@p_qA`bQSL%<$}ha5Acl7I!7BL)VpM|$JqFUmq{Qtr=!SRZ z1~<9FV6`yV_QQv*xGVU;@|a@$ssDj*yAVa=d(-3hDdF~tc{sD>Gis`{vZ1KfLyvIeFt@=-sP zdR^u{+pVCc1MX3|8$zgo73SciMQPmfZWSu2DFbFWD#C=NR*?*GZS z<{h%eji@h&nCna#4%30^yRB4+m;`Hamo$TR9YWu!TlDDSw9p(SMR^+= zSEe7TRCZpFno0FsTNqI&)PRutJK4|hUxCdu3oDqIg1?Lsa7%X(%A~+qr7>!t zYMkY&^$mz7 zf09dKf=83buGw~`{QENw_X)fwM}^r!tbr0x}j7+SD)mjy8Gm=kVf?mwbLNgF zJrR^KmG-gdnh=Gh2&SdHu(7;>R<>^;T=W zkAXPR65LM~|IVzHv$O?qS!#k5 zSO>}-tsb<1GW;+piRCmMz zi4C4=bpuU)hO%VedWWSa*&LY}^3{vARb^qvNBt3VO`5nJ!+sSlt^Nu}1XyoXI-l&X zxaw2WJOBe{?9({EJ4MG2wgThD+`E-jDEM+8xz*G%(enlK_2B?DdoWuMvu7;6wTRvG zuzTZOBGlQuC{KtL7Fom^61XUb%7E6q!T^W44cBFOzF0>mxY+-1FR8(EE)T38n#8ai z*}vi{JK+JqzrW=o&P)kBw?Qd@9?UYDZdB=*v>v@67d|Q)p(=~xFVQa2e{$$ z$SaR8(OrvgYM1^bNCkc^w$s_jDOlZL$SFfl_i{*^j!NND&Y!u+rcS>&aq(MYo$l~i zIyMX^kXnBFMG}P_A`iTZDi>e*`Gzlj{IAN8EpizgYXp4(p%Vl}DYl+0RkhD9teP#f zcT{LMciL;a_d37r#oCFPA3$^kJ4;!Bm3l-7a@^_QYm*{)hDTgL@Eio>R7VnjhK5q& zQ+Df{mD==m!PV6*ExYwBYsE9SbNa8C>@k+!m80N?KvNextt5{z+H z=4Y9;YGG=s!0&E>m?akOL>DV<2f2VBB%a5sQWgf~)FDIBfI#CcC4nrLN4m0{ja+DZ z`Sw~6BJa9%wPlM1VOHF_bsom~pM2~0W`-qQ-&4Z5Skf|+ox3c%&4DV`xn?b2k&hI% zBAAWEH|+l^hN>E7lvE`x3{Vfa zqMij<@8vtLI2^=ATdbZ~3qH)l+rfb~H?3HGmMgDc{rGq?-;R$SG24?@J>gDa9@a$z z+fuYWxmWl~>eF5fG?rX0*zetVF2X}Dz|0J&SOK8P&b~=cumdQ^i0b>MajC%O+bSSq z7Qu`ySmYhrhcb&&a~&|JjQY2|Y5D3>g8_t%9#TdrfGthpEkShHa8Zh4p<2J2U`n4P zy%=>V^uWr% zK$5OkWd7l*G7TwP!I@-PhZuVa`yioBkN#Y+oMdYM}Ldh=F1399Q`3rN0?f` zt>JItLQ9~4q0ktOsD4|x7i@m%cl~DxLM`t;$mY#=4<-ac#LCZqmW>YBd2SnMQp|Z;-~I~s3Z6dXfsu% z0`~NkSt`521jVq&Qv^;*Xbx}(@!dLDeEHYx^~`3|PZnyrxn{Qa_eahbalj|W08r?;*|NA;*vo5nr)!*_PhEn(^WTHJyXEvSW8Bd-g9vdCUZgD zl_T1`^y-W;D+bj+%BYNAh-L79R64e@wcjlW-UeFap*RtZPXFF8E;-r>`Qh{BBqQ(O zK>t(Z8pnL4pAA1qwA`?impljGyt$9gH=d)vMB@H(#U9bn)T1Vu$}G#1wvN?MmYg~I z#lsMO>P;Df-|_k-#Ym==|4Ngo!=&tiXjU+;`=b60vpo?|k7D-1pxHyn=bfOR7mO%v zuO7$79TeCY*1mF?5W*zBn*Jg&Mg9i}$T>kY;gWgF{Ly>7kFn4uVbnG9s9d@pS9QX5 z9xZpuFv+#)9MiT9YbY+L@7>bp9I`LDLuob)Xe+m7RXLCSq(x@^lH~iCm2SpXa8G46 zl`j-(>x@W%$_6oMHQ>JjEh6t7E5I(CciKIsORqm+Mwg9dqQ-EQhn zsNI?yyr1l65?}vN<1zled}U9qP*Wq07cPX)Ss&hmkU1?MsgOvMc{{N^axPU7qZ-O_ zYSV^4ezXlaFe|syYVq%Eg;=yC;!!#_%+Zp?yd;vGb2Tu4qlgC6E`7GvNiD!;6ldg8 z*t2aM>Z;v!@Hf3QneG?HEHhLQ^OP4(VL`?M3xF@C>u%BFFY~4OrHy;I@AKoA_cNqz zE3ZuZMu(Ea8wKqoKXvHC%X!H?3-@~_e;uDCsGLG)vr1{{W-Ej`#Js^vOC5j4329S9 zF)<*gk;(gfzqN!g;hsO@o1kh;B)-7=PZx%l^@~+^bd^3IW!#Dc6dI{X9~NKdjl>O! zSfA$Rv{y5R$-uKE@hPci8zTYWZ!{%eOrHC=az@w+xYnG&D~z(zlbx`lzc6)(=br0g zrc9<(EqnP67k)I4?ZA9)+OJNCg0BL93U_ZT@%fAw-Y;t)d-*#iVCviu=rXwI!SAu~ zv`k0E<$QP0ZDQ3lr&eJqMzIjVMgSN;gk7CnVrN~-o;z-fw^y1gY8rgCitBv zgUnGW2o%^H9rz>=H3uW~{+y`S+0xQttShBSN96Qr7se>uo$_Uu^>ReX#!G8;Ws zHQ2br4#Mu=b#zYtx|z$#>65ka$aBu8kMPq+$K;3W_e|u^P)R{PwjOy?e7O{k0h}G( z5?(v-mQ82$YdX+74j0HCmi-eyiGTK2{gnURLK|JujqwFJAxLmNJ_&2_dWM_vW4!=k z5$zxQMLe!2o%6s%eDKtl&QKT5^efR&OcrIYYkSo#_1Ngk&PSVVuUQ*Nvzy2EpT> z9hd4&`c3XDrRTgAjpGM{A22hv<0K>{e`kmwRa`k=DzAf+ae-dbqijfyc@;TeN_K^~ zkqv2(#4Zzlb+=*X^qQ=sK_c^tKXOJcJ;XgV{j3@qoyyt;-ZwjE19W&eb4A%Jd}pEd zwe=0umx)$!o{mZ*oquRS*_c=i4x84AJz~K9dY}_!;S@ud@n!6p%gqhY(>j-60X+2; z)zk8tE@o^D`=Iq=Q7>#xv^zFxZ}H#4>~Zt^c>CQNo_c-lL1<~>8tu0CS6F?fpX(0s z9&rt@{mJ7dE&J9+98fe3y*oERXdBg)s zPSh#a1hMD5@!#4B%_-UDZf8XiBXdI&=1itH7;&CmZ2F@=#fBT=qU=$oG%nE{DupP**0CUkCJ~}@OWtK0o52-x!&kzP+@gBR((J%bprxiv3oBEjMMdp?4eDBm`-$h^SZuwe z6db3^N_erLu&|Kb6#a9BSII^bDwhwD&Bd*S>M}wc6KKj#Xz;=#G6OivZ#%#*E@Hu%>q1UcOh7GJ#3otMqnzoM;bGLyA)&$kMH9gNFH0 zV=CD69>i@u3;aq7DK)UWG5iw?ED(;&`O<^o^I1(pyIFt zEo9tAb(CSskH7S1k>3Z^Qx)rr95Umdr?<{E>6c`%kGo;jZyW_j zJWR)DW5g(u>R~?C<}FV_UPJ+ZhDLoMq8wwG|T(8^xlEX{?m$U#PF$t>7jNx=8q?(~z1iHVJk z%~{;)y-3zKk$bN*&fs1DFULz=3>Y+e;q2~KRv-{ZO6|edrY1mZBUnuK-BJYwguZIY z@k#3-`;;iiFwGDO|ALO{yZY10v?6GRPK1yt+<_!+>!{7{IaWexfA;`^ zx*($F?g@x5dPTs&)6>Dh0m7VV3l0aU&TG}vM&`t?Z)R+Be28G(H$nCwW%{HnEbWWh zB(e&Tixa&?=sB!ZViZO2JJil(weOw$7bKke$p&^a!|o6=Fcv|UT!7c*b(UPNe)-9{9yqGqTgE9K4V&Kw+jlz~m#i!DEZWAsczj4bMA;uB(? zeSX~3hXUoP!NrdXr;oCj=^M3XOUAI`$w`~=!JRH%j{Lqy6xH0gSU<)uuf{#18(wj( zE_hnstoFx^J)@FE?Bv!eoO1&4!L9O<*3Cp%+S zO@T@$e z4Yg5S$vAEu<{-J!$v1S>6>Hlm<-v5)lB-y)!;c_P4nCHef`crmVwu^R^~0Moi7tn? zENeRstxLpWuTQmWjSfGg`V)%(qp%RbtqD>9~JYYwgzlWav ze_zndLhg9+O42%w#_x?dsEC+JDpN?4mxL-*2SFm{_CEI$LsZ$b$Di#H#bzb{ucoVj zYU=;u4^Rm~rIe7435dj0Bm^X-JCu?VknU!nl)z|^6r{UEYLp-d!azzGFghKKk{t1W z`15~ucFuOrdwXy9d%yR7?&scjZ+)q!sk1<4z|re?!>+pNITU7ua8+^8Fg1LP8EQND zhm5NBXjQt!gku7o(MEMeR+2@gw%($Ne=~pe}FujLeIJA)yRNEJ97ZO!09Ajz44-V5>- zb$r2bX?AQt$9X(j3=W*908}$Y1VnrqXw;;Ckz1t$OYsBWP7?xmwEzNP3ErkR>a z+_{~K8kX3nqxhH;yX_tv_7%yjd*o zUy0l+Zpd-cSx%#cl6C68q;;$(t5V@};^mc?@Z6mE+UQmBb4<^Av@bZ7=}>lIf3d%V%uU4i;#Jl_m36E2g&M_oTcC!M+=4l;61-_ z6mm>#CNxc~gK&1oF!y& z7E-*!&%%ia7Q0XG45?KFUV)Z%tn|a7ban9X;};>rk5Pm7>?v!cK|hNC(Fch@i3349 zpC6`HU8)=PwwNJNsu;B+d6%?W$OMxT$)>v8I*FemeoL7u=K_w4ojyBb2i60PRIg^g6T9a* z8S6Xfcpn7Xx;6#&TpVY6EI6{ubqELTlVJrUL7{U6UY{yZpH)d$`9L)K50wKul16r;MLI)dI^??7nvl{USs$GBHI_>w`YN{z=3=p5EUSYw&V zfm`HwKqtR;o}fue)(^D-?Sjqh0b1!RlG@Z9*93CMM^)g*_kG^QYLc+zUkT(VRdM*; z#FChe;0p^+Qsl7eHiD$|sNKAIx6y#f_WV7gtU=aNC>J1E;GsJgnq;Oh6^lFCNjN(T zJCs~00RPV?|0N5F+**~M0fEOJxIgP7Ro;u6EAQhuvu`du+%>WM0ah*$B7^lxqq~km z82kG4I}Yr)yvyGd!o7*mO?|PvI>~NY*Msl;PzQszPl?PN%x??UNVJ}4Y5#mW%lm;_ zXw~8VuiJFbo+dtfSih2CkZef5JNethd4~h+phxpA0ya2AinKZ{sjIVq=5RhSg4kCap5`U2o|}YA5?j&!1%r7 zj6L#q*VpC7R^^`UE~nKE?)PPgY74KU9@J;P4}JN5;x~cMpP{+AcV5nZ=^V04FOvcd zR2KLlmLcE0IkRs+3XXPwb(x-=i}pj&&&0{$tI;L}2F& zsLxgaGo6cLh?(;z!v|rH$n)NYbVzL+FV=T-_quSmr7#ukDL?q+HY>M!I}i_KpH z;rEi`bC1Y*Btv3jF3aI{zEc;I*{>@Z2p#Suuvh`uUP*@$0m$CN8-|lDun`Xv6B8WA zWhAx1ULJ;SKA1d|lM}awb-hl>NPFVv)ez(kwGts)&7!a?!pk-nO!eammU2|12^Cp$ zFElRKp|0Q$Eh%9Zv?$^x5qwQ2=cY;~GxY_}qK}=PeCxtX0>-AD7graLR_GLxCZ$B_ z*N74WA6HWg^7)*N#wzKB5Xk9L|BKU((LvAwE7*-f-f#5l5(81u#xx8@0jHC;l?0Mt zBV?+Ysg0%W7Faram)TA?JoCJgQ6wgf9o+Jq#4MufuJo@s6J`>pIKZA4Ki<7lqsHF% zE|Hjc#P4J$nb)8D=sg9++u~0dk90yKAVvsN9&SRJ5Z8euulofUAGa;G`+8Ezyn6Dt z@W}JNSz8gC6NUHO8qzK=LnWDUv6b5zy%CHHw^|tTjf|9aRe%>Rj@VW7Bu970@af#S za6aF{!cHi?C9~LTpavW&AdJePMt^vadFW4mbE^3VW^XNwGBK_-3RQF%Em z43aTID!E?q^Xd7$yj{B3+v8i=y(D~E{XTszH~N*+Tc0) zVMlddF+Y~%d(;c$o;ACS`^K_1+0Pndi)9Ib7GE$lnGRFq!UeUo<`k5qjBj}_!}+Nw zqPHwKHA08d^hHF|swbg$>P?GnyM@uUqogdVi-6_&W0i8(8RSdRtt%N}Y3b<^oU@=< z9aUR}=zIwzG3aE56u%MB%4l*Y4X?ZZR=*Ue$9lgP4pZsKB>Dm~lQpyS_ zSuOU3a*qpAuin}FGU!5_NvqoVSeby_(v4^7hq6J%LpgTV=i$Fu!;4(mDmXxiXF$85 z>uyavo4HnmAXgGWyV?sI+1eAcslorr$zuAqWOi83Dc+F{Rszbj-mamJ@`=W2y zupm!)VLLDruYr-qv6Bnj`$qp(1>0Z%Vba6EY=W9;W7uKfdJrVJWCX0N*7kH$V=tRNBBB5bxJey2 z|FBCxeE80lvE{z{J44T8+e5Vig?qgX%6VnAtKQJA)R5uk_~nW>gGjwHhwC?X`?3sM zM;d1Q&I)|D1L7b1a=OYh)^DQ?-D`%fGhY3VvfsdGpm7W{ook9NSciUw61;;;P+a#hS=Cjh35^yre}BP2X$55Ji?>wqFiHL--a_ zo}}D;PD4CZUHH0SH;E(lhODE$b>fSj8~Xl{lu9t{1@r0eoHB3#;TDbymb zbt3?fQC`*pc=Ym}2oxq4Uo~yN`|FN`^>`+e(eZqaD9_%OyaqkcfzktJW^>xl!u{iQ zk^N*<20ZASbsDSeS%dPKvAP-N}q2H9iF}K z?M>5Kv>~E+)>*njA1S~))YW7~G6HkPgk8t(<|H{CB&~piuZ(}nm+#HU9ewcj%+vv( znY2nC>X~Q1ai+3?xSTXsxiLxTVvh%!L43xnh(Y4ai?k(Eqmi5u$lAg1lz4y zb?4z>-3G8}H@&70lm|n?`%$hJx&!j;*FtEhzS0MIHJ({04%cp})_WhIz&`Hxf382K zxBhr8T{so%AMTnxVo!uRc4_>m%t;0mYw!LZE8SFcyf)|>68PE5BsC@VF2a4UxV7-v za?a}9S2JL5EXB-{!F~8M#hV`nyY$PUf1F$S^{lCq=^{Ba%50WNcp6KfV=4D0yy2J^ z$(VV zm1xo%S!)u-=`Z!aBEArweH;=A`z4%wqNNQBwFIJ_p5x0;^XI_Wgp{3s%!h`BhM7t! zbMd5iGBH_V-8T_4kN*N~#NH|&nB0?N!1B86|6UFX>a1)%!9*`c!Toh!_FSBD=`h`v z$Nr*MA8$Jq8#Md8lTu<03~QPb-IH=wXR4C+b>_NQ|5NC?eFxYs-4iS_AQ<$o=lKYI z* zeLxQa%o>A!B$83$Jj!$psB&Ml2a2>6P5gF*S#cpIPclga%Ms;;WNP3o!1HXA@?rryrn9$6Ju?mKg|4S(Xfb>M{yIo+w18PymSxDP zbVg$`kF10^iaQ1pN*P#x>&A28(eqKE!}%)ur(W)cCTIPe)@b9J+1n`~lW^(wE8I3G z_t(CHd4Te%YYn&C`auV*X(lWv-Zp{KbRgc=3jVf2h>et+IF&xbE}cPFg~r9B(EnT; z&zI!flV09np*WSAm4e@E)+u9rD3>D+{6H}-Q>~Z{+~U_|*>@UQ7W)b5WweOS zS)#5!DMr|?(LK@WbCoIEK?LOTKCr`g9Ua$Ag>0*1CJG~6Hrje`GipU2j}+z#3S(LDvUi<@1@lhu{0;R6O*i&*6>&~#V(4*pRF zNe0kFS=^bb0Fw;cZS#7y%a-0#!w@|EVrK$7v$^OK_WWS$I!h5pzA*&X{}1j44>nAj zToG4be@S#t%~1-D+kbl^KVDu2%n;D$2lV<=aIJrky=#2}s0-N3{(+$KbW1UR%Ud{x=zH-{3E;iy+<-gPrVrp$| z8H`_t76)SLQSuv#mfqKz?foeL>t797*1~g`tNUZl{#>`Qv2h2|vWL2l_YPHW%>G*k z3_Qy3*3-39FM1##KsI{4?<&@QBLM&sUnUdaKgaRL!AzEBKO7irRvK1!%1_1=@%n8Q ztq^BUt6l=CmRDeE%q;>}tOb#i=L35vbe;dE+}X;CvmwBnJC@yFnDdAZ%Z1K#_Tv^N zd3eT+HKKtu$NE-Mz?iQ{esvU-2^NW>Cx3?zO_pRYpj zl(5alDnCz+1^SK=w5?2v1x&sot*6(^Cp>L@JvOA z>yy~FrY{79yROZ8q4kWBm`HgKz0E9&S5EAcyua>ZU%yJ5eAN?7{(PkxoCnf5btTB>JryrHtw zGvdT)j=9GNZC$gCZAu94oP?SAz`TAmZDL*TNmEnPw^`h$kTLm5Y%|wmI-AN!!9!h;KKiRkcJ_1FiP!B#;5MXvWp%C# z_eiq)5*A%ME}QC$aa%CB-0DOqIW{(?3<+5EvH5phXCWLru+15vWcz*d%JcE^`puk|Ck;QP+FS3b9`uEti)(>QLqU%!T6i(WAU8?x1Hy# zf4yOajD!a#IEo$|3h0=#+gigVjr|qpfpbm&#OoS%6yUUa*oo2u5#!tUxQp=+v35>B zGu^_>Bk!CJ@Z-~Je+lCt9`an;Eu-l<^B~4 zP7y-jX`8hqr19d+!gp?lg>Ccu7#)J8de&U%zi=eh9slr`{WZG-h3HSizaT-$I8GD3 zqCvhA(KmT#4fi|<{vGz*U~Z;KXS&=!esw$wbh>|d&wV9oUq$=xnNN6vFwnuKjau1| zl=A_$MT`5;XtLF5Ug|$q<`w|5|Hs+TLIkK{w6E;_<7Z`-y|pWP<|^en-EF54lPA?v zemo6(xEeub9s=L3#2+mO)PGasew3hX5T$GwztpJP_Sa6e=8fX q%3=+Oc+%qcb7hxq%ZR%5Lc-^!W*UPxDL7UP02E|ZWh$gzz5O3V?9r_N diff --git a/planning/behavior_velocity_out_of_lane_module/docs/out_of_lane_stop.png b/planning/behavior_velocity_out_of_lane_module/docs/out_of_lane_stop.png deleted file mode 100644 index fdb75ac0c6eb8bcf93eb3341f7de19e2b6123da9..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 183400 zcmY(r1yq#Z7d4ClDhdclgG$3t(j6j*%+N4HgLFwZ5+b5>4_zWd%+M)~NP~2zbc4h& zH1C7{{@?e$vv9GHxp(e8_nve1-se07t0>9g;ZovaVPWCPzmZYH!om^3!otS6e;fFp z-0f>c;M)U-H`>lvSR`+Oe?hk-nkSX9u%2Vd%e>U^FxZ~;bfI4JWIC&^nk(TSWca}J zAm%a4%ZGPk=qmZJyW`m-euWjbM$u0bF0rUaoro~2?kXhKU{X>0=mGb>UQ2VQwAd}v zk3y=(pitwVkaxoork;ch6QqoUL=_*@VxP#D-ipDZw9Le8*7`kBW%q{8t|MwyM=viT z@Cp7v??{v2h8Nx2J11Q`JndYFpcZZ^2n!DnkBsCE9ix2u^!WVp49=YHA$@I!euRgI zK0f9NU2yPlaf#C|K#0FT_Gp-!oSe+hXLU=tLqXug%?xFELP4SQx~~Q! z7E~V4wt1Pbn8kg@KL(^#dwH~pL%=< zb>KUS7-DtHe{LA7{LF+fI^NW3WRX3b)P5shHQ}i-7cg}mM^T#vQhh2j?CgxDmrInbxO-b@aHS_fQJsjXeP~Q^iRwie z!?7_Bm-M!o$<0ErK&Jf{f$ZUL9lGB6MTDU!-CAn%9faPc)-(dkaBcPw_Fv=Ck~=kK z|E8ECz|E%9hsf=(*T{K*zfM6A?HJe{-r(e9cb#^Q4kc}TGF<-m3SePno^4b7&^m`a zOW;sZrl!zLiidHth5vL}t=)h8a^GR}F20#UWf+^R^Z}HyeQC+&z;h;DaR-Gjl>YM; zRwj9;Ay#IDFjtYZ6+GH;RfG_afFLp~>_w;wj*a0xsRmHlH4ABE%?zj8Xfq!bD1ciD z`H9>578X`XY9&|0;~!X9LUD(Spr!d#s+tNgzl6loM>yde{)sgPI40|FM^V(wJWs>H zTBAXxwq$DIp&Q1KQp?_M%>^v1w|>A!V_|_;O1|SFpr?sdca2xQB(T-UO|psZ-wpAu z=YIX*?(H1r!svYyHr1v3I9OPeQGtYE(9?(7ls|sUJ^_wa#7Rw$pO5d;5c0OUg+)@7 zbXtu;`<8%-se1ZZ(Ax{&rqc1UH@;0x0|^}W8G5$q0M8+Qct}>p`H^)A<8dqKEwF%Q zLZOWQvGO-ZP>##X%U-x2A7xr<>PYdEx3+gpdY^Z{54X7x8(_KX?=2By7E?e(ccj6`j7pGZ%#?GlQY(^=U6|PfBviW2Y z*-mIEAfIId;WjrjGJ4t9ErCHw($M+=#>D!7!%R87g_TKKQ2>5V6-?56#www23=3L6 zSn1hTW98ZCJvtxW1_AHHlDgwOv<>=jw%}IIR;66PzRf%|QC|86!DT<_&WN&YI}6bm zi7iTSeUy0fZmdk?W6hU$w0Rx4SMdWSTNA5Ztb`0&j+~IwIq?fZ6cu}oU5xyLhDs+E z;cUG*2bmd`ir7vpOC@4?kB1ol&cH&n2>QaBnr^AURjw#G#;3rl3uV)@{taCF-tNxM z`{ionhZKPM<>chhY{<)JS1;(kG3FK&J?iXhv z>H7BebOTi|)JTCckR>FF^Tv2sQVowg+S?~8N5|M4RPpfexM!gY4igo6h;|@|J4301 zWyUaC8$fEf7w~d*;PmoJg~c?3YsfAP)4{hI8ULrUq6C8D-`5AM{m*vqBWX7Nc;vVO z?k(cKtNjpdx%Q_e5&ClfwVd3SFJF>SXIEFgqJACYsw_{8BcObgh3%!dyAuoO!derb zTjA>F2rjsjF_RhlDW7@T=Eg{4enWl|jV^G3Z(d%Nb~x<8+^8~nE4aFXk`fPxzi*SD zrRDvOfj3n4*`-ze8pArqch!}H;jegEIYNe%9&m&pUuQn}H~csp6&CO*=)N#SzP+O( zoVUvB{rf>8OVi%h9Kw@fc%S|Il+4W(m8>3V^s@~|s~z`d<0i-~Slsw@h8xc-DC^%_HiH$HKyfhb`@G}hregERxbXPF2c3C}CYdxX ztakxyar46KiExCMR^Sqkv6;SmAma~jKk_z#v8&26KmU2a!^WSnxwn@~`C0u;3fBs7 z@0*w9J2Fk+L@6NpnbJADQazp48L~6U4SxM?v{U_~s9OnygsqIb1SieMng>B5 z4_(5#K|a8BS}M`hGke!V2g$vU9UvOSLL^*gUCEu;r?T3E-tpmjA(pa%@-jB zoZ&-Gv_%n>vT)CmDjfc5?9MH^&AD25P;zq0J2U37V`7d<%*4b9W1=GG3B_08RcBXOJURQ9HVFZ4L+K&++G7SH~g0c#>$ ze-UJo2H~Tutgis8H^fVw^Y-as&M(7-oo5rHU>nahh8~dLzgt^vXKQU|V4$O8pu>}& zXZ%E=;D4Y0;c}9$h?0_$2M4%w9);G+@y+}D`+)o8G$U^Tn;;$nK@Z{M5AqNiQ{7W9 z;q5DQ386z9>%EU?Q~wsDHDGZegjA*H*Mh%tEROToI4LR zcQ8amnAYUr9|VLU3k&lKQJnt<3$>jAPyzvk;^LFzO%ng-1c$_WCDXC(%I>Y z$Ez*+{WT4J(q{*-UO1;2QDU^D^v>l9PMnY{2!s|pslHZbR?}}Oi?u5PKXNnJKa>7` zE>@?a+fJ8&th)7@&LWAVc%1Cf?pso-Rsg+~XOU`ghq`u=$H2AUf2Jy)WBZ|Ue0W&STpl*d zn^rS-9~+iK%UW)XSDi9sSYh$XlrAb$l^Xzy8WUjI9KzMxkvMwK5O&nvhYE;|G%+sb+-l{ zS+d)I-IT>aNI^1vRU060(<<*$_BU9=VfnDz`8M|JGT#Qfy5uhj@pmV_HV)Q$T{RRV zWPN^a9d3-XeQB5aZ~0$!I-mmY?u@AG-lo6ts#yTu-+0w7k&uv(mW3k}8YoS>lt!vZ z5deZNZ%?A^3v>i>&2%e7=7!2RK%8^Z#@PR+a#P>>-pz+9du0XBL7_y6gnQU2Z-~sD z^xOU)uJk*SQd9XN3II~`l!C&DG_A+u4C=c}lA)%0m5F?$QzgsTuG>DuVF>9-zjJS~ zlwA6M1`bGWhqlAm%jmdDNOf+bL;vQPPP_SU2jt34xIJef1W0y;{BD@q2I;?rG>ahh z^~_=gnq}yA(M5x_f$>t8#y3a$sI;u)qVOa$B&fZ;ee?JFzvzNBqOh|F0O9T`Gf{DI zpPP7BN(cbCV+>~eahNAek|)?3o_)-i7&ELw%SYGol2-+r1&k$OL&(Jdq$Qt-s3O21iNLeAD{>?ANr_9XENhH&oo0}0beLSJA#k+e%TFnCkD$gIkNUwP9_I>`ps3>)r zZ+F9J!W6XtknvLU#PY!imq-QUfCmxfE5XXtkY1)TD%!mNTqQ4k6F7r*mfVV4oBZz} zzyHS;Ix6oLO+LumI}d&R?M(4ew#I)O;8$t;-o0V_!7F@{=#7ktiAnEcHsHOKa=8GV zL*p%d04-6Vq*eaAI4ZoOA*jtvJe6W2-P;`i93bwX86hGE7WZJ}KoGp?U+yFSTmHKu5RiQ7?|=Cj!C9#0+0ZEd z9>4x<^KkpKm*C&nn`Dmy7~T8n+}2~;+Aqs18|RPfOb48 zzW1Mv>S%NK-9HG6tWTN6TvEAB<3gPH{`;KHj<6Abp@y&ySswMc`e;y!^8vxY_f z2h2)#*&|TfGdPy;^mGZj5ShN$-v;?bdp5h4m$OS59UL5@nhqb@2hCQ%oJK4w!W7;a zHoVL|p@)@w0qpa?g=xu=0{KQ8IvWSGQuv}Z>f?f_y8D`rkf~ydOT4GryXq4zla^+i zscDp*I}f4gC~Fw^4~6YJ$1RsFl0t*z-_MFJmy4Go+3*BSc_Zd|TMip&1ezV`yE z@EX=@qQT!eNK|}5fBS~81EJr#g#B-ljVBw`rUGEa0INKwTji}p{8GBC^j7zvH;M(u z{a1qKsC+tmdKSCdbbTHci8d@2l0MFV6Ht~j6?F@iAvqzax2C41uEvPRj@gic5O!ht z(uXU6I|4rA8xh`5K4|IUOKH@{PAP;AzRxpY~n3UU`P$W2$AmCVQD z3WPQ|5lSrpgxtDi&HsT~G2lP&m1zzNK^=r^7Qa?9g15C!{GKG)Q7S07V-Q-23a~e z#Q?wgW72P+Z;Y_q0tjtPEAk}M`rW&CrlzeYFFxh|vk_K=x)Sf(#{Erl?a@x(?MVom zJI;tYF)BKm(7d69PWL)%a2>eJUSl^LNq0v@=Rc>%LV%co^EaS@v;WQIN@XatQp(by zN&g&${vN(G^FXmYE-c*pjZAm)gZi<7t+_4l?W>uv{8Nvy#Mt=C!jmtySOzU{t07ZS`LZd}vo?DQfXRtEnTy zsj3&NK6tg=g~~h$e=Ya=^~7jpqOTJ$>+GxlCUjM%e)_a8;R)aN%?MCKdV1r(gDgv! z|0<@fCIMXAW=}0KV9cwR|BXR|kIpZ@s&r~`jDA=eWs}c8I^Gukvx(|2N8v5ePhX1L z%%c1A!dkn@zl`p8J>VyPghL;FzfOlnvCwu~P5Y>3^kA{2Wt-%f@ZSZ9pd(WC^OGb7 zM6h-t_j)fQ7(#=xczk@k`n~lgL)|TyxdwK?%cTdam~()S@dyZ*KT-}4do`x2gB@>a zYrC_tAj!0eC?)<)Bm$c9`8`mPnozRp?14Gbvi&ee< ztB4hkZ=t>J_)7sg@b)%4p`xN9VAuWqwjjT^boUuwz~+F--NUl?5WCgtB4TMPNtK~7!$>+5tJ`GRA&s#N1~Eg)oj zd7X{qtA~b$PGxzCBr(B&K=kU>E9^yP;4C<>Z{MPuYVvDJ*8NpBZL64}YxMmuWcW~? z_XCfxO<4@lrUvZUSne6&1FG6UyxB${g53VJH)4n1ukNHlrd%g@|GYh@EH(^BjofCl z4!gOG+UAHy009Od!t(*`4nbTE)F0ATMeIdTVV3pv)uq4GhkPh&suqdmBR(dijoZ6h z8k~>sXA4}Hl`n$A|6jLqNPTS+IQ$VgGE&}aV8Ik&cC<&#FL{)W`8{~{roj9BsliD% zty;=0D3GGsCpR_Rwc(6sXKwES*fOf1to%&-Nz|lVqZ`1C(8|gvC~&^c&dwbXH0SGb zlGa|kNdh>@@vx+;$T3+4BJIQ9QsPz#CmcRLN>(ICC*Dsp2x|TsLnw%H<~~Q-hBNaF zfw(-IkAuc|p@S)@#!C6o5j{Fu%ah=#Vut9~Mjs9!Vn5t;t@mR5_=Cn@in%V?P*c+# z@JDTzJmZhZPUC~ij1)~-?uvaW`}+OYKmyX#Bs;%f-rmgLg!Mtkn((wrN-ErNY5)6@ z6RHN15On|F0w$s)@^rk;2+deO_lE8{1VM)FbgUyWU4W^Wl(J2pMIyf@l34lhib?Jqz3U}7lN(~^jXB) z`d4eWmQJ7y$vf$AL(Ja1vW%>f1%_X+9Kt_7H~94`^k2-`{wAe@7!qt{+{~lud;f<8 zK7E+zvFa$t3_BYFb(3iV+M0t1Wrco%l=_>SQ+bB0z1o7fj{>E0_M;4hsITls#+@YV41$50 z5}APq?K}(HXPqc)6Zd!v3Y#KwT0oI5GP|g!+vq5^6VyspLW7pKJrs-$x^v;D}$X z%3_tPedd7gF+~WA=crOZ-ho$UTDxNa@y2|SeCK_lekJ$bk8epm7KyUQLy)$aP`td4 z0#cuU*+0n>z)GHDQbS-vN2|<@`NhR)24(Qs~HP5B4TiwX-YWzt7A@FA|kwvsxaK=k{n za-SbYnS)nC5>%k(mr5+ z*RxCLQIr8rlqZW#{xQSLKhY^ci}_CoN6VH$6p{2$!$8cP)`uooxhsLZM`pU!8Qba@;J<^b%UpBJ6y$uu*8!6d1N{3)!v4yHm*!(af zmlfx_Q9o3&F73^79H=>xtvjg zuBdO8=mTy&p{f`hSr2_o2!z)UuQvAZ5*qjz|Hd`sc!=vHt{mH}1NKMIH$?8UeUU$Q zmX9Faq14G*+GTrQ*iOV$pfdO36B+r50S?=_!YdYv6;UBi4!J0~ZSIV@l65N}&;aAduE$@ScuL*_|jhaRW9NSg68i}p3Q zgmF+}SjQ3s(i8eHC=a*SM#Ed^$~rPTufL<(69@uVMS}rbYjShVU_$&8P(0pQ>-C8bzESq^JE5Rhs=n`0^Yqk(qiLegbPJy-c& z0UjP1aly>G+f3R>Y+BX(UHj5mrw)^Ecdgk(GgLFw1hd4-6RL6#!W*G43>!%7Ht%6! zp}PV6QSw!{fdO^?S!g)3J8tapTI)wjb$Bajgi=8P2eFWm>i>EHxVjBI-DiI$F9K=s z7b5gB^j&n=zMN6cAkm6^LL!L{4F}1IAyrRY5DPz=ea$YGj4ladFjA~}vJ?AMT#3Xl zMu$lB?8vb`uYq4ww64BBwYV7!SRV+rfcv^tJ|A|Gf5s6^ z3w+*`S&~vM0MHuFX-CQzZF$psXd{?r1W;2+~0{cfYCoo$FNq%{QRRoU5H- zDXGujAgPT$_y;peCaGH&;?TA&froYDvCOLdm;;;2vvsBS5_>b*3gxK zExSDOyb@DKl|?9gV;n+2T0Yw~GUmZlihS<_UaLr!L_*hXkUVrx9{5GyEKF@xSD9V% zoAn3h>Wz7Q*9Hx5f4FMeC{m*ikdopBarKIE010pb?KL_2G0ZBiaa`Hw=LxxOX?80Z z4;hqqtWC0pewcFB8bNg$&)GLBLtUJm;9P2TdZ2OK!Uh(wf5|>yH9C6!l6E3Pw>I^` zwb1(ovtvS;*3h}jjHPLT@-3OT9@ZooyVEl7jh*fDVo+DsXTRw$XAg@7nml5<%-r%} z9)oFJtUPit>#nL{K|}e0rntnzx3DN9;-|9v(_TbO!npda4{b`#6#_u&I&6Aw<3{t1 zUzYkLpO6@siingV9p=$x2{}krl$vTpSv@k-U5`YoDH>TaYvc#tK~A(=P>yU zPBSh=;B<+iEBPJqMegwscZ`InqO@Wz#?;Ig6Dxe0u4+Or4;ves!Qn-?WLgy5CWSO2 zX$|JuaHPQB0Al$if72_+kU3TgV70ZiwPVy~l@Y8YgoIonKW>fVVM1rCANr@I7N-RX zMKDM7v{|gMEo|3h#Z?UCRok)vnIK0uSq(jMeOquHm2xH z>#sVvhC)}Xe3zAO5Sg%n$`IrL?#^qGuAJtrlP-xmS2AIJn zpz)wga3!vsprFNN+WDL+j{R1m%ApoIA~q~bc7QzTZ=5HkH>cKaHVk@<=I1G7PjVSH~~TU!`gazK;k;9bvTzSgH=H=0S; zH_LAK^!IdC_d_zF2(s##_G-I6j{0K1FoV@2 z86t);#C_sC>3>DgGiAet9xwO(97vr~dTh@_y6Bm%uVbW;&y#<2a6w0iSVA>&b;awh zdhNbzI&f~Zn$B5q4%W~~@-*`FyfsK76_97SEN!bJ~Ds5V$WzNl2pU+Tc}20 z0Ek3gR|a2!C2ZtjA&*-&060;cJfp4MNXYzDiS;}*ejKUQlgRD3E70E@aE6;>Jj4j+ zHld^QysEG8tR8#R$=98~?dGL5-H^us#^)YO*ua#E^(p$I-63z6K;67Qkk!@I4qrpk zITk-Sjh5j>1rY_G937qB&_uhhDl7mU?JO!P(S^yHW2^V{^k6GVy2g>zfn{W@J)aW> z{xs4}i*L!<5AJ+#HR!z2WuHBN)#$xK!>_c+P(0v@I$w>f#atw>RegcCdSB#T zs|WWNp8Ww#`QsL2O`_+Xg}05$eLd!#@1p$s6<6F|N#$HjhQjUML`p~Z(*!+_ecK!M zc++Py6q+QG!|QYWKKQH$fS5wm{Mt7CP@XjW+UhWtSoIM>7C#vTxN3%{dcQBxT^+Jm z#(a!J$e2>)sMuP$_oV)ZTh^&5&-+t-IwFH}qVpeU=}E6QyERP1t;lCO6uDO>M# zAFhSpA_l7ebyYjg1I0K?**oAoGqXM~o{kckO-)TcN)8nh z_#1|xP6D}kG}i_xErX>R{uWd z_^)TNMRm*xiOLNJm@dr-)?iQDZ!z+wT=fiw!m=NiC(kJy&-Lr;pkvI6_0R1l>0M^& z43oi4r?!qgwnJ5-*;|rvzDv4b0oNTP8`ZL|cgvN_sO#Ugr{7X@6=!@C#Fs#5f}ZwF z&@=Spuhn2E6Me^U+4eq>DigeqL48A}n=flfrVjsC1wjP^r@iDg4L|Cjb?!T*4&zcO z+a78ZdRz4@;VL3SRKssSTp};V;QXHJJ$T_4ryaq^(L>J92=i~j8gg9EW?*&P@c_=4 z7$~$4a~(hpsacsZZG_t6&Y_wLM$5oR%q&;blnt4Zv0R48P^UK6uZP2X9*vjX1tX+{ z(Z?9A%RAKF)q4wz0U$-6o0w&3)j>NuxK^;Fa@x3+gr8@puwtfQO3F*Y%QSR3DfNDw zoVW0FsX$^$`+a+NX%hc+)7xiB!6wFXhAUQeD_!e~`6`P}0E9*V&pN|@_Q_3`&m?P6&CjrHui zQo5%Nnpp>;1XFuhgMdh9CSZWZ41wR`9va)5TxfLd*|zz@j{nd`T+fQRCL}@0VzJ9b zB#n_Sp+7dgQB5dI?WWwwLlMawA7=Yu$mTkV;-o^u5L<5Yj`E9_@Q^wOJ*|e6gJu)p z%Qapr={3oz9nez+p{4?u%WcUKKN z)r;n`$&IoxnPg2}f%$VxNXjmVVbJ#4D@F7Zr$y(ti%A_DzX!nveWy=P$^!E-BH%=U zJ4A!q+Xaq9QNF8QX$XxQZ3{Y$Wkaf=`r{uOEZ0?qck@|+25>sxFc9@ioWEmv0$c{* zFytbr^9?jK8H^6?8u=3;?PX+!K(;MUfr2^7#G8%^B~8bJTREy9qzU#oTa=M0gYpqG z7n8k{WZCI=il_(}!Qm(mf9LA`MmII5nvRo;u=;{4ppZs(p zHV!09>d0e#wio#+R3`Z&^ir}%uK+9N6XfOA=Kx$b^mKPi*u9Yl&;VHo;f}Kg&w`<5yQy zyx{Pkot%^xt)D=jm*`@6*uMJQTeIqso$uk$<7?P5r2PolZq%Rn&MS@%*lv437xRsbCpW_# zP2;pvFDZQ06nDgPPMaf?PAu*XNpP9H)yT-gWzd^mJ9U3_(gmV-sF8e0|4&kfb*6`7W>)j$ok@&(KO9dT8KvN+IW;D-=aR-PeF zb(GiY`0JixzgO}ci4km|OuK{RD!ItDp{|(5b7ZaXZ8N`1YhyE`aNBTgr@(x164Sz` zGwQY^uU)<34KFlPO1`Fa8G|}%bi-<5HsIckGQp3&#^iL$$m?_C!8N8>k&VY}=N3)) zTB7fIS~7ByOaCb2M@U3hto>OOO&%Q&2h_t&CREmKAi7lE72xL&l>X{k-&dS&U2$uy zEENnr&);0k*_uR@B?{~-Dl3z*6oSM=d|X^A9E>X?%wVY<{lV#a-UjkqrPE_{6?>2C z&VrX#Hsn2b9}%*41-@HG&$M9E4$#}x(I4(cPDIi!)>GZ}t6sEgs9HXFup?fywdYRY zO_va4K6h$#oF$I)z7V!t?kq7yeECtf2|XUCWI;+A59n=iVBTSg0nDl&hXi5>$X1%H zFCz;(??e(tpIi{Sy&~MCFI6*ij@wsPc@_)@blB}9Q;Ire*XZ#)f7waHYk<*KhokAamt0{huaRr9)8>cH3s&Q#Agen=Z^UqGc9VftAaO#P zFO`f9uxs70b$ZSg-Juzs}+ei6nMN*Mp-P0I)%0(zTV9+=C z<6EGdb3Eprl3XX1CL>X>dajbIt1Gvw$X}(WGriChUQ&fua{Q8nq=30>O~bVzo;3CW z1}M`m#DR-Dc~EZ{j2EIQo;~A=B1a0nq>Ip8=IhdSo7Txre`z#~chDC6&h%qkYHebu z>`?C2X!)MtO!Wnr>B2;k$H|An*>WGal!oxr4iEvuzuk85?w~Hh$N=a)U zZM4m6pHhRJ1f(_COkM_&H0|=j+3VfGuLETz0F->a{JibY+zs*G&WtJP+5jBg&!{M% z71_e(1_(yhT3to)biRwM%&;*_&~-awx~Ev(R!QBSuLaGmp5hmW2&!WSTLO+NINVAW zPQC@tTeOsq_~o!Gz&-GDnZI2nKU*drh$xUk)k0plWYS2?Sx-;Qo@QXv>v7G=U^vWZ zxnS?T1aLMFi8}zLVyMzKLx&AHr}Y`Oi>-Ij3$%_efpUtG4Gps%JG1li_6sWwG)L$i z^Mr1Is+WH!4+kn^ThK}a_0hti>FJ(|w4qIbX7H}4u!sodO%HvhmF4L4&5P<0j*Vwf z+z4G4tI|Qtx^Xp0Yw%O6Y5j}OI~&!JJqgOu4(Olo6YtgDM8PBNjk9y1$a$eU{d7Mr zvXnte0%7IQ-}A5Qqtee_UVORMZanDQ{4yN~Z8BdzJ%nA_dNx{#mOGsu)K>!Cwh&pF z1osR3q73iPvwCz3m0V^7VhgRUV2(m$)G#p$mrJ`6D4+5;otG?!==%&B?o`xLg4hey zgaykgHv36H!+Onq1r03~$3=hmn_1&8Y8zjtOJ?ldf0D$xA{wZ0{u>k)pRNDJ=lm%r z`mDZ0kH>Bll}XvDC1{mW;LDRw0cgk++;~4@48LumMq0s_`?Oize*RP8Zg;cc=bHoF zY0)ba3O;LtnoCG;61JtKrS>iFrg=kUY#2~|Ed&*In+{c`sv=AA87u?p7=OS1YFpaL2(GsUKAx%o zc>%#Y-7Tb0WgznpwPJq~9RTwF(u}ZAj2Sc2Q6%EeND=#IDq*PU$o*ml2!Mu#qG=|=)KhCm9A&@$Tr;2O5jVKdk+YFMb1*P`!9-)*4nGW=WJR(^9gvcOuO zyosMuR2e$XdwG`ObF5u<))*W3{?4Uu)BIlXulsJNL(^byrS)2<<@}G}r;NHIG>buR zHX9P=OX#aTxXDsr%P3a)dxV6ntrqoHh+~>ve?$IuXk09b@GG`wF}n4M53X6tO_~NA z%hz`MIs7n^6NSW4+n57sTTCcg&$hWDYQqxbxn(ep0dW)#Ex+?FG`>;L@$8T9Ih>bo z#*8|;b2CG(nNpL4R^K0aeAKVvhk#K>sU#EH=WDoSXG7IffaJw((93mrmB`MvNDYuBq#1nnY4txZ>r~m%x5z{!G$V=oPQcX{nRsGe#aG2bplCS55Hy4CEPy6|34pZ;<_iGfBamY~yX5 zG=BP++ew5g&-w~kukNXEd@K1wowv;2>{WUk=BoGZYdi5=2s44sIV$^@2r<8)!^VRw z-~KF2ocQ^>$h7v`pzV)I`}>Y2JTZG8=U;Z)+!={fZMwdygV`5E-}Vo^%tdYi9XHVM z5X(XyHXVu|1`S-VyBgEE!>?j6oCUK~=pE7oq;|@A47# z;}YUE%e|MSkcY$eX)|J(e=cJDQYsb}^YLaMrr5oCFKFsHcrsG5Y~39+G@X7geafLB zvFEXB1ey7ifT8t6^ScQQxt@%I^PZ3j%pHq+*S`m9h^H4HUUWNPu4^`V2?=N49k;lD z3<_$TuU(nLo1Ve=ywtB>8DgD%wa$?1w};d<^o-G`^OAjBQGKoYRgzjrf%#ggI*r9I zqWws&x+?xcCR*7)4jj8v({WjNZ*mk@2vy%XH3V`p7tIdTB(t^+3^<^C2tlO+AxJCY zm(WTI6b~o@78HKg<;4QM{Z&Q}^Xf#TG0_Xd>UkVCR)@h( z&mAwmB22fR9`ZhXN#?lu2Hg~vep>F{IP8V_mgP5%>2Ems1qcTFHSppOK|!(gyH}Bd zKHE*s>0|D^`+k5XLPtki5_?!dg%KOC4ocaeB1(SbTg)UPf~I+y<4PJtwvI@Z7J%c{(=<9Z5tu z=#yjB=Q=)jK}J{2Kord^AXf_gGFZ8@a8Abgcn~ui<2%ce)aM}PmlRZ+uUOru@2QJ< zN;v4f9V7OKT(TOJ%M11X5f|GXI%Dg-%;;8X^rjBKuDD6?%MvsnsJ_#K`tgoKtnXC3QjwJbdSJ*Yt=YR^NU)@ckELZ^UCN~yHPGu1M*_9*6FXm$_QdQo={hd?#DcNr`MX;A z^>unRKu%89_0G6-vF;ol<$5=%==9m+rFPAOx3|Dd(P`$V z?nz(5A4mUoazFOG(@+!2Y?w%W`Cuhz?KDRUvR-cNY;iI9&F}PV+-YA}&B^7IBcW%h zam7DjwLd)VJlH!J&p2e{czr)o3~1_et?XZOlBr10H&_uk-E=%z%xyaRu^y-!d7W`q zSUi6mbk>e%qquv9kr_AiIlMQum=r-(Q5~Eo37uLgp=>84v{hY;)IUV8ax|qX1RIN% z7pcAyp%d}xVYa|Nyv;4%Ru^0~Lu+pq31ft60_4Xn{|R=>cRd@G{TcT{zCMM0VH!e5 zvWPXDiR__1T+DV{$4gJVy#p=Xhp^LMq#+vKbn1!U9dkEwL9AtiOS&H$?===Mn6uU6 z^d;`UF`@=e|Eil8C|i{exnL}SC-2hrp~gFrSZjFXk-@fR$bq`G0-F8sEO|(n>MRn(Y7Cg zWyGFFj$WDj<=|$6j_t94N@6eGRoHo%furuioYcdf0+{L(Pk~gC{py1i*8H`njy-mc zJqAh#QCTdL8g>iPXTSWq>d(LRCS|O~7e{5i8K3=G?P6vz7iFQ$M)4}+F4rGhU2*qI zd}gmQGNqvDy~QwbJ8CYMIR-TKV}adenMk6HekEn|Vuh}Roa`OizR~4|b4)_x={Z=S z&G&gUdHtyC5-lC$p2P(P1vE3ecM+FGlg^DTbQP zrHr+GUKtpGn=V6qi3uG!6jPhvLB|a0qDi(QH35Ff+8)>Kh8N>$J*&K}5@iSNb&8Gi zHnxNIJcxJV444^a2|tD+xtc6S61^I-g(mHh=77BOY#m{yK4~8WT2+a%2SH$$qb3+=KGm$4OU zI!3fUkhEoE4i#X{RU=u~{)UElDwwVHl>#jSeEgN0vd04hNH%XMx*bJk;!;Ss4Rn)| zT6_d60VJtfETzFi?T`IZJ(W-wLCRi7b*j>S4-JY-rM})L_EvxXewWO6?H2%W;a)hwWKNI-me?mB ztHBS+;`Cr$W-Ac;+<6H*o!B-{9Yh)?B*opLFU(9y+!=lRF-Cc&KIN|F@dc!2BJ8UD zBbY8(QKr(pM?IWu>!D$OTPWI(Zg)!k3$2RH;;CCgXwaKWL4uXbQpv3v<#)DU>9X?Z zHpnx@%{18(DG1^qmq8OU~+?Z`;u1XJ%WQ}{j;?fk!gK2!gnoa86Y(nlS z^^d#iF~FnLw-w#}s#;KuIx#naxoCN}ZhlHx3p$$jd1;12Y0?KCxDut5`a4#_y`_b| z#Jtx?nS==jcs;xArlX4${57Ot#C_B-;w)qR_3mfqF8hBRo?jUdMc;taUJ#($7tOr~DlMxcyiP~f)Lk{+(jDP(J?6R0r#az65tkRA zX;M-0U9HZCduDx2ak^nqyL}(FP&iy;JID1uIxFYjE)?RR3Mm`j>+!%48~QNWw@JL? zNc#~RS2n|d-J5(>bwCV@6|v};DuzAv7` zz@JGsge!oj!VHWN{kJyxfEMt7e;2@R!ZxB3=ti4zSHGnBdQG9~UX}grE|!w2j-IRx z(9$XwQQ~*xHqeW{ZTmr>{x_eSp>@_^9!*5eL}R$VPAK=Ikk{YF%%$L3<-JHygTL95 ztdV-gdra<|$FWT(AwczM5&M{1W^q;D7_$?nh?u_s?Cn>W9Ul~QSg{gc%tv$9zx~Zs zNIAu3?aRq=`ccY!Up*!ZCfoMFuF)01mt0==uBB#b6PyK|(_u>1-EBE-!;*@M7wT?j z;bp{ZKzR)iS5QS9D2#D~*?vnBulh|pV}lcla-K4#3>^iPe@xhw;wHjUQvRn(1#}bk z%`03jb`p(9fXssSR-+=7xTVIQaR)_ff?lVy*lDb^{xhBoDg~7y|NI=+mk)+Zcnp1Vht z1gwF9<0z<4sYJ#vS$d1f(GVb!4mal(cH02TYS0^x9mqBg6`R%Oa5C`or-xjk>-V)h zu29tOz!TUW`L~g03@UhIq~k(%7${8NPs9GZq5(SR`+PB|mQlEWn> zj&B?JRIq_971+Z|h*b__&vk_FFdP_$r>1@6^s+kcf z)3-T3J_|gY(|FTB9}yltNz1|-V1;Emy>9E`aum#*-sxU0UD?~s=Yyi?o25fjJIs2p zP~co5a@FSit@nB%)VQSfcEFT!1kr$Gyvf2K(hk?KIZ^_ zvgx;Z#p%7GGP})#^#R!%+68o2n#-ou^s!HcG~x{)GrP&Bfxm5m3q06Q#Y+Pfq6Qu! zbCe-T$-f~Sg>gKSV}PL>TSLYKD;7N*5AEEqi=$GN8V}+CUpu}fl8Oq96$6S^3fb@; z(EcfuO~m^g-|>)BZTa0Yzvsg3I^hJU( zVtP(Q)Fhs{@tvkzKUB{*H z^7-pP)^Fc!c6OvoF&^yYF@C%@vqbpL0p)6zd+NnZZ*)iq7MAM#6V0e7Q5OkB8#MdB zSuE6Hj3@GkWav--D)>=N0{eJ&?H%|&j>^7S+$2m{R#+)k5U3ic-kRks417)UAT&q~ z#K=OTSUguHN0+N?B)g(klYktLrqAx(=@PL;ZoJ|~&Q`>l%qeHuXPE(7e7-Jc!9Hj2 zt{Sgl!ck|Z^C)*9jyr%91B7xZg~x;^31nHAO*AutfOIC+AiAFpY=6dgR0wf5 z<%q@BDk@W)ZZ`4ZCgB9o$1mkF8|C*a4;xZ|&ub<82ntkf`jP(B`mi_qn z=%)>>=FIR@_(;}wFq`^zZh#qDflo7A!93Q?kl0H;O zog>FT>b<~wG-%y>;%5sq2)#YjC0~D5Uvu`cEbB(c=9DBweXQuL?0QpiwLmz&C37)w zvh_|~BCmT3hwWbbbfco_E--&*9G)Q0j75h^Qn4iw6CYuChe%DnwcHWmKtrrv#bDp6 z5F+1p9e-86at{9;^$YIUKE<^ya7`XTxC*}wv{Vuq6aM!3bKY{6HQzZopK@BftQzay z{KKDB!-sgmz$E{4T#b0Gr!)6GbPgO!#eptVQ&+~u|2fFY48P~!txV5vZ(j*>hT7xz3;*j_GJ8X+FzH{ajUT@e`LfJL zRCbug@R70g9&C}}`mWZ#`QzucWftnsjZ8=J>G8Q+iPxp$ZQ^r3-uj+UJGaca+n&)q ziXA&{=?PPX;z=$9BsaJl+6-l`k4Xbi?Pr1TX^kpvr!1NGp~7Wr7DF+O_oe@FkF(DLUspOQGWK4d`?`NKwp{2FSlF?l*|-(dl8_r;B9!h z`fOmQAjVI1X^M_b%FBQvbIibt4=|>!AKQ=GE^r&SZ_M`N{~T>DjmY_=@Ur?o=3mFa zNf`KO^6_06s0-B{{f4UV5)|Q=5&3}u8ks_hd?}8LtF5kDb8e=a!)GpL@pG!$`MA_O zO_=m4X7}NSZU+yFnqw44D^jH1DCD@FezB0ljh0=UjoLyl!=Pt`N4B22+>aLi))7#r z&BmYZQaUO$t(Tag1etSz}3mggtLjNsi+dO#*>o8<1CW!f&?J<=u< zleM0@NPNVvRxwlUp@~}4wh>=1)xWou2p?1g$SgkxzcvNOEf5s8=_{`|05!de`OeeV z*Iqy!efiuI3x#Hx>>G%=k7H+LWn~jz(8aIk-;_DBfud+lOPy(>isgD?`ilSx!l+}C zx}m5zTj%MXgcQ##Tz-f1rOO{ccAG|+&0$_V&nb^uS#YQE;XQytfY{#&i+-j+;9~6= z;7l6+O%>q%CGHZIm>zF1$|6<%C;}-kWN5TIB{alFoRwV^w{O4e0y61pE@FL(EwgN6 zVF_$-{Y|kRcZ?9~nk(SR=4>tL^27gg}vi)20X}RT*vGv{Kd9mfhk>Fn2#hS_0oAhQ$SqU!7z6nQvO<7i;zH{dm zGa}=C!k!}VtjuAAP2TZT9+mD(DB0 zX?#+zJhyT*D-3pH+EirbeduQckgyr-b-8q}7<~hEzX`Nj96()*|Gg25Kakv zYUJBfL&tbEMLAVw22+uh zIvS2g!kuDrFNeFDl9fE+Lq?k9s4?0;xTeo3$)SFh+tFiQypCMvefWMTZj0x~AH~W| zj{%ZOXe6F;0!K7_L-lT_Woh~Lo=)kpQDcp_f!e^kj1PBw=@PHGzq_TUSUlipm6e&$ zqBcgs&^Wx4Mc-%}C<$>Pw(g@?S)j4ori}Jlks6(4wa0vUFx!&_$E6W26as>1gwbg3 z$^Ce}`n;^=` z-^mASQl)?-!E(1lk!OMQ6Jx+`#5-qvi*mv-t%w3x;d4=_HHi^*)r2~v@E^mA_F8JA zPc~HWjul(KEG!;ql-I| zr1ssWo#dr@k(|8bjsCp>^)W!O+U!e!;P5I?-#0(Ga~uQh7R1Kxb3TL=-(45i5u^gSs6CB5Dpm=QGweD_Y1?^1n$SkvF{=fAxGJ!BnI%2SYzWs{3A$uG19 zZmQY)QMphQokAAeJMS;mb;t`G#*~olDkCS;kDtTtx%@*gAXD>H9m~v#8r~Hr(;d;Q z&FJrGi7<^;hPw7F;;M!rrJ+i&L{j%PO>Lf8e0oWW1ZMRBDO-bs;QH??;?+-61MSM~ z7t2c%=Js#ty!jk;Zx7arXWOLsQa&eYC^Q|CIiDTw`>yTOx1}{Yg{-4**{r7V0Kun| z$1<_SO*@m!&%D3h+BF5AA#)Z!zDxeHQ>fysNaA|b`pxHoWIn1QKAkdJbJf+PPZ2Qr z&O?VfyPzRzkuocjEfcQzQ@gJd5#5Yh$=d?Bi9K=zgHa+j4BZg6?!1N3D@olGM zi;RTaOsR{Uk~*t=NS?5TqS_e3*g<=b@B2JDY4wDa7M{2VMw)s*8lj5{8;GO?pv3d- zB5{R)%GW_x%PAaonpS3@risPy?-Nk_E*$UrE@JVJT2d)IP;77-(=gj?^veL3qh1+> zx(g6M6C~NB##~vdyp4NWBM9_IFsTPD!Tm&%GNzAF(PdxeTm=KTtWv?#4Pj4M$qFFR z3TyOvhgtUd^YBq>A$@OriC;I1Z%g(V>YMikg>6}>*IRn$q-P+SG&K`0&9u8I=u~{p zI?(1LP?lHDLy3cJJ}Jke*z&!{EWJc~!6P|d)_g2FF24CvhKdGzghg)()0~bk*KD=> zC3RB;i%yv+ALW16rqw^#5c!$*iA2MFlfQb->NQ;nRSv-P;}KzHXZJ-HF5(UX)<(m+{@yN5a?VlLsI9xPR*I62y|d>I6G(4P0bE@l*;Y*> z1i;D7K1*6!<)-t|dw)-2tWJJ{ct@dD!y}p$&!p1Z)97cirI@}x(ssoq&MBEkFZUQz z%T-?(*<<*h=ey??op94|WHbtMb5DJ1HM*&SJ$2z%8cYWyHjETYzg_WSQ^ZH9w47{g zoD|zq6#M?(*Ez&1&T$7gi1hUhiTWQWJ~(=ECP2BDb2;s$>Bag};?{z-WxsW;UeBML zk}oY_Pr&6o9f;nu7^c-Jk@mfJ#Nk=?vi}fUZa?zz$^onSNQE(o_q~yqfyUE#Y?KugxC{ByQ9!NGKo?$3D z1E>Iq?9(>KHBFeV9l=a$gPjIM;j?-k&B2!MKOM zchEO5f@mk+a|UL#GOcKL6m8{%Q}P!8UrFac14$xwuQn#SeAP?m)vr%aeZPNmepcG9 z-}3lz!x65udH+5l5t$>S*)w45)km^Z0%tYP|m82W(QLU@?4e8gIpF_|E-Qt z)}v`%o9l)NP%xZcc4T=y6GM*yb@?S9aRk?m{}z|v8gca4b~FnQzTifPo9{IkV|yUh zoqdj;@VK+Go^vGd>Oo$(CF^LAkd-T%zn3s6p>j$Wu1$J}Eu%d{SSLv~-#9WzJH;ax5G4lHO3n)Xe)Be zrq&e*vol(JuBahRX?RkGvZ0ag zxU>;)%EwAX*{E>1nKnTFz`-tvl~dQYy4&1nBw_GHuKKOt5CZ5YJM+pd_Ev}E$s5e7 z-&m%uh?M1YaQoY(S=aiNxAUJ)KZ^BWHg^!a$T~eq#jGFzml)RirjZq>0dx!ex0*_gmLDyTcv|e&cXypeulb)mPc-v%^E6 zBU@Q{Jxhkr+w!%MIYG~6W93;x7#Rii%||wKVZVsH-Y4V{y-3~w;LRC2WV19eh{`|RJb6}F+c_76=2PffM-^OObjrH_# z53Ozgi8VAf_}Wo#djKg&28g)X{YbN&OG#^D{(UWbc`A|@a2j|bKz8!5fc9niZBK7E ziAd#v4-V1HjH{ScAjQ93Tua9r7`0Nit$hgF=s7Xw!$uNY?`ckvhcBOWR4ihqE5Oek zK@^^M`a6e`VrH?D2N}};F(;H72peBZK!1i)xNZlW7cH|pSkeL2Gc<})+<*#VHEdJB z%*N1mv_dWsQNs%}-fIrp$h%3S#;04g`2w5>b+rVieCY^_tH;4Lsw{PUzfTvsV=`_v zb@M`y-XIPG+F%UbR&f2t5&5KoS`kzb6OB^*i%(8pn}duejvn+c2Sq+6ZlvClV#4dn zu4Mbfvl5aE2-Q}`ok;MEy~wv0~y`kVDqE6aFIvO1{Mut zB_>o3qp;13oND)dY)|2XE5;86rR%2TfBv6DtqxAx=KoR=H4geErMyyzOpSRxM7~`Jj$21OpO9t8yni* z-aMXr2TSMSqGok%A1fOZv$pQv=zZ5U$b?!*izb1Bu+#0nr>%3YUhkc%X(){%Py$LO zoQ@p1{5e*YSR54cBUKmR zlIk<5^y`77E2i+seYO4kBbe3u zuZM$&nK>7Od^`v3+=1VE;Kt9p52FY}AJY>ioxLrdeOAarClscx@z+RgWQ=ZqHSrJ; zK>aQYxR?8PfjuY3@WjUR9RBiEUCepUzz{OY|LyoWK0tBBj8|mP47Ix{g&A3e3}#=C z4;}#opO1bC&!!_8!`@kW_WWRy-@*R*LaFV5on)VO;O4xsU1Jq?hr2=KVSXWmA$8+S zaTOT#GCnfF?LNSc8lZ0gvoiHK+VVW>HxKHU3n@T%!VqY@9o?TklD{fvdV4zIwmA`{ zXGOlk*WoGn!X^5z-Ln^_XIRdD=D!W?xKAELD0UP#DW3xmo)D3*F;3)BBXP>+R*u2Dg4|p2uS6)QH5um z?X656vkcYotKLl$q9mP;n7{VumdQPCmmia>$lGc-8O`(Op++yv;?}D`&%986G{s;i zq5M{=dKs@ji6b8)qa8cbD=wFUANSz^wSrhPm!ns;?|D-Ymi6It?E@6$s-gLk6%;X2 z@*C#aDYOuEgG|~TD0N2Du4m0H{D0r>H)eCHMRyR|Ql={lN|2owV@K zyTf>b9KVE^1<*fmOZh2w!)+^N!>mr_&-nOw!H_2)iswBhKc=f0*%{-+!P#MuP9v3e zvi!`6`Q3m@{J4!ChVsslCX!%$5a-oEMojKzrUl?ja+&No`U#p*4QZWGbLGHH@a6PN#DSp|NJh$oZgnhL1 zzghr4b+%UQ|Dtxv5^&CR)6A2VvY&kjfN$C~J0yWSA%=vGu0o27oxm@YvV?^M1@(Rq zHjC}px$jODcN*UJEDeWCj5=coefcx)&^6auTKH1SK&e+oZRNXNsM`_$XX_^oQNh4# zVn^0H`7A_SX(VBT_yA0>ntH1h7|#8kvPWuG@574$S{KhzOV&UEz-AYQ!MSgC+m!)} zK%CYWu+8On=I}8k#)7wV1}-0s5}4pV^R)NdvUV!9;Kr~2y)U1bRd*UtdEjEf-c_(N zMML6nn{L1hnL>URHC*N);X%6c_m8N9@HIoPY9WSmLs*7hmr{Is!r@mO8>vhwK;^}2 z16PnEllCB{`Vk^r6Jv%mF+43OVt^C2@!D5gQzexod99?!5WS0c@8(#z+&P(3v}$N# zzjnViS$(UGwa3vV*kOhcqHBn6ws-SwEqjdPl_7AGQas^I8BzZg9xTQ*ld+{zbFC1( ze@blo*Xxhk_%L(J(R5W;CctAM3QAh~79;yP__y-I82r&P@P=!!Ip%_U!AH2ac0bvo zeAA(=c(~tm`9q(y@SfLoJ%Bcg>M4}cp__CKVfuCbrll2f+r+x%30j*+v5 zBO=+3T|}C(Xl~dX3}ebxTa+%rtXq{U?t<58rSJ3RNfV2?Mlv4$(45SqT?MA)H~e`uGt1cHAmfUA4#p4?GeW^u zZ(KZz9mWB%^TYuDO^I!C!SCeFzLyL(Vp&fxybdMESjHm4mail93IW74w{!5{O}v19 za9?Gd`-FzqIDI_H&DAsYmaxi#IgzMF?g`TY!s;OY{kp#|}h0qMa+@N;cVqXWqQ1b;Bc#u?uZ7K%7h z1@jU#7|yXvTln+m`y&TXc#*;9+Iu!!p}v+v{z&=GB*LkI3D2fb+C5!~P)OrVqfS4p zW;n8pl-im8VNGgh6n!PrtOXq_xrJy@ksJAte;4VYP>DgAdw@A=t?SFAGMFoFUC-uv z%+-_a<#L}^APIYE3pcd+CW-g4sf9a#Sxs4KB&z$j2oKQK zEN)Sb=;3R>;$2Mr)oU>Np`Gx5Z&5qixe?|UCc@2amK3J)aXM#g3h%`09$@6x_yW*% z>ZMH^lbBx5OPF9@4J*dG5O;1g|pU-;Wy@(HZyxFQH zEOBshVkbi1UGcO?RMH~xmFMKCx4$ZERn8!A%+$T_t+3KnwCBGiyq{n)9J#-aY3S9z zXungZqTOt(;tEvM{?75|GI38Rgr|1kMAqj&?7l)r4I*2XVew5#PgX!WGQ_@x#v zX+by-OLbpcXM4{EK)e4>-@a|8B0`sKbj7o@?ybCK|n~gvoK{a1PlHSHW0%k1H`TF-zc^B%U_q^KFR$JCR$+ z>k4NZ;_m_R6q03KYGNfA1iF=iYo$oh;d)7*8G>?rWTtt056!(uOs{@vQvA>D|Df0n zwm?G$o*o<=Y%@}}xT!r2kp2rjW9Q+4loh^xo$(@c!PZIGh?z%-(cQ=$8(jY-~s93(ZyNkfVPwk>k1_d$i&o?nWrb4kd9DVO%Wqzb@aYP zBugC?XPiXu@*l510MR6oRLdjd{3mB3F_)ba3J8k^|f zajI3f2G@zILWymo%4B%r8t*aZG22}OB}RkOC+(^tdf=<{pj-oLHT$v`5rCZ96R*nW zc!~L~g727P9n)nHg1%veY9gbTVToClz_J1VWi*{H*N`3gsQl+@ujcz|WsczLQs3^L%W++?fp66+pErTkO}TZjbQDZqIMivXK1 zl&6KhTcj>QOwh>bzgUA=4a`bm?%-8pfJFP=o_~%DlMaj_)49M6$|`;I^>la*y3c}R zj9hS|?fn{5{Q{Azd>XGXXlC#vFZML2u2oaUx6_1SfNrXxnby-op4O!w-?#I-GXq;3 zOplNS+$(z^1wELKS=)Y(oxyJ-23>=M%FT_1bmEjH91aPD%svhNGI$BX9rt#AL5#|bM zrqe4b;EDZWtMaxpzc(D5FPA;SwnDiY$3PXBWo^z>$Y>1cWpyk!e8iwR5wjg8EU~n& z@0`KxM0w$I9=&GS9YDC>c8#%X1#yv~1OVggOGwFVh6UjYL^I#!L@r5%^4`{v^bz2- zITv1<2sz$w70w-M^z+Ld=dD9}K0(|YF?U_a-3r^(6)M389p3?A!h&J%yAyy6`Zqph z5fWv>-Ld+KvBjD4R3Ndyk&xfTpMm;12?w&o335wJNQLBdbO+Gb{kb(R`s>ut z+)M%jvN|lxKh(At%aKF{$=F=7n?mG!e%$(SDYeJ#mX_uLMa}3diAE&s4{@7jQRM%Rjl5{IMwmvNL>Z`#|1$rP72PC z2?*F?{a-w2zZ;8OBnV=H!m{x}g3j_*t)r$^wHpIt1FMrc3-Rz2%?wYEO@kdQs7p)j zV$Qp0G8&XuG65n8L9+&HW0~gLELbocv{l&e-v;?jj8M4@k-*HhCbKYr{m)n~LL1*M zqG8a9Zt6Oho}-+R9xA7#s3?_-JLMI3-dxk4X}eJ(&80CDnN1Z{Hq3nNi}2kdq4c6a zgYipAEb*5T;MK;eG3Oe%H7dq{&cY#MExSuMiKZIy>@^GVMYAt^PQWMxS}AIC=;9G?cs%x@eYtcQ$4vvD0iw6!54Sc4kD(BAo z`;mQWs3NWJGO|$y%fDe^xbZCj$S7K<@f-uB<^R>15KE)2hOz|yeR@M!1&#@lv$e0$FL z^tn*j3{b*yAK-FM--*bi@s{~>NxD+uZ459`>BdhqpSg#<5)eW90xQWe_JZJ%*eR`k zJG!Yyvd>aPT(&~n?O@wK;p3WoW{U$)oR|y=2e_$6SXzu4= zV(_*fB8YX~gMsj@#7F4$lRHDdK)V+<3A&gXM+If_Aq8bmC((+~6}HC~NV^;G#oh4k z@i7gZ<1a#uRr2`*1U)b9{$9Nn!&kA979ZlD?qbT9`JS2tY zLUZ^0_`cO@l9Q1Ygx7^L5`gVd1_f-LoUkBKWq?@^h|3fd4DhiPNi7-fDH(z=Cx88A^J&rU`|MKc5$CrJt5;T>T z;QSXI?Z#t|lt2=+X+F>=H@AbGlakjT2W(jEjGym^i&UmVKYlD_B(6POFtf6vjEMjY zS1Yr%gv5oOAygK@Os4AR0A6P9*VD-gNijHIixE;zDZeiTzm~0fT7iUW*XR35&`9Yg z2x$1b5s{A285IZ=21$E04c53^UKV77fTZ-Jo&%yE8QqxV5x7=JJ>WBmw&V zu1b2XVSr*mMAhYQUVs&f%Vq$&Ua_xcpi&X4 z{Oj`M+#QSag;9;}gP&FaEhF zpXEiFrYzfs3+ieUz-cX0F1-&3?>zti?6Lwk~Fxso^>=dYMfUumnJM8qR30 z1+O31(V_->(3A^b1MjCc`ic4_fg;z-1km2Eqg7B>&NE_?3|&@Rp06{rlIUkDW%-3CtI+5pq>^({$*- zg3Mml4&3$@Af)~Zg9wpcNjn9GQG`L>DH#H_s6}e&(2beEK4I6nV!@sYx6df;GSLAM z%fb=UVUe&y({H4dkTwKtor?HX#;%A@yJErSRl%W%K<&`(VaswAqZSKhHXuO1#LWr5 zDqZ_M8vW3ISq3sf`m5?DzK3L@Iz3}_t)!{Z${ZzErIf*+|4a+iQDqxlw7CVKW(KZm zu5&C9=!>GpEk+a|Uf>?C3Vy?T@4YC2rz_|oywNcZyEHF1tC0jFe`K6SYh0>sxAR?9 zQ?fR32ZYPi@FabNsNAYGKaohIY;_yq6JtqU!yt1CP^w_g@{Hi(Y`@u;s@rSvo`L z1aQ8;30R$25g+5#tKG4bl4kOn>YK!In^vx8QCXOuCBZLFX|;cNgc$e4Gux(Y7+S2U z6sw@K69QONqo!RT0WrwZpsbtU0WeYY<`6oyF;b61zrkN!z{=h%ybL0F0mHL2zX@Uv zd@Ny7EKNi#$=#nx$FY)C#itZ}4la_i6D%L>D%~B_c?v2ll&h=X*F=CZEV#iO?Ce+( z5{bmJyRV9!eBE1%e%T4ThZ%8XgQvC$&ee(ms)mZm+!tj~x?vbZ8)DCi);`>e|LrMu z!5F5db1_^pT9pJ*1+F3pI4+}uB~kP;#+_|f(M$p;u^-7Rm;)~ z6kdm@9&pk#Fo=|rWM%Ayw!@k;)OgDU+_;6r2;9qz!rnorpA>fOqkTw7NQ19bN6V+( zjsX8{DhcZOc)uqd?H58e{RyISir#s068Gf7Fqc?y+g$$?Pa~w&1{)^@rhH{$Oo%e3 z2XZauIf;-1zrm9Yy?he%9r2Pou4f!Iu*6(u`8JlvKN8PDnGH1TD>$Q%l&vE^8PE-g z?7~grS_E37CV%%HTY;zW2JgU`?xt+_eBg9W`in%Uhdaa2MvNP?>Z`tZKuxtV;=&i=!+@2kwGYrg_XaJ@q(3V8>VDR%3;wVKO>Km%WJk4^Hx zlBQ_)+gQM5HAxZA?!f`e^{G#;N?CR&IxbVIivp6M`)=Z;i6EJX|80#&UgWtpG>7yq z8&7V`-AAL(F6{f?7|pgKx%`y_pxMn!I08g5^%}>HrVNF2hm(HE*2XR;9AZom29wms za!rfsF*zUSfhgQJz4=4=fox2;4?aLh@T9-9#FN^}pH2M52s6ymzMF2F`23KfIa?!i zW07yc>|oy)9GX$Zd3O|{i>PO5`0?%ov}H1NeAn3sK{TQ(^R`d?a8@92VM5H&EW>0} z`8_j{-r;W3#>MD_W@(cr=5HS~R{fm5+NNgDP%(4#JS;|Rav=JKf-*~D(4gnW|6McX zCMa^UP?=Dn)P^OO;l00APEqGWY@wK3Nq-$gOCyvAx$BR$sfC5*Fb-4Kj$PQt?*n!0 zV`BM3a6<39j)(7|TpRdd;g*ZIP}`$6->dreV=53mOQmh+`wpWAUYZ)Q86U~JqgUAc z+{tBUsHM-60S%qCCNxq!l|DkiwAx)abAB$dxKREp_w`Xb=E}`0p(6Yj+;z3?4a;P= zsGn?JVuIpi)&Y+AJvoj@>jHyHV7>Pd;OWIk%{kgZ7>MF^#_`R)g*qa`Z5?Exro`x5 z=wRo9^&$b}4Iwk4K4EnX;XelrbP-DNp=ic1DrJ+}W!TAkRY*P&aibA$;TZb#3?rTmN)P}jt=z<#=Y6zsnztvDoOlI! zd1Wxl32E7$e6j_YkA+2n2sBR`n=wr@(BYJ8<=~=sO^AytSFsno`!3%I7>xtJ9|Nd^ z(;vcl3J?{^&~ek=omIY9v4Dn8?v$?kb=*_M^>=i1@K_VDb8|~zB6P2vSaCP~<&`4u zwA0F*lf<$+S3wYRs7L#=RzgTVW1uPEbc^(4uvN(H6B3RDTNPrcG^deS9rN_vz^vFbp?#q5ZCsqzq;d`zm?+ew)I-M% zkX#0`vRk-+b!I1;(k!;S_Rnu;08UZH{Q4??Nm?iD)bHd+*&lL;Pt3o#xF&h{ZmvZ( zgchax)x_&P51UlszqZmqMgvEIo)^p$$I4~3GZ*2_mDp5qTK*6Aw~^qXA*U0nmYdB7 z?A)Hu^P{70&b6$Es}Mgin~?(8;CD%gijg@}{h}f!aI9i7o>;|hZDVES`HKE%;e8=i z)%1@;JuG8CL(WIaul4S_H-rvNr6QZt$)KzLe62h4;D!>XRe3I74{gu|ckpT1}iWOsG@F z?)wceQF7Lq#?{#J8p5so17}me*?q5}n$=fjMyg=JSA=W?^f0PVecw^-5r{OiZ8+r( zW>#F^fQ+meRzf%7@-)+*Cz-A&B*y~I@o7En zL+Chd2%Gs{iX{7 z>?+YY4jOAy3XG($N|yQ0j}-F?9bdo{Gk8?j0im;MJ+kTyGG} zhCaqNlOiPf^!otJ;y;S+<;XQYV4vuL^%C>eY>&38Lyq66PDN{=k3Ndaj8T+F_N^g{ zAmBzk6EZUa=7Hh$*zw34RtDV8NgDR%JQ-0bApVX)uCZgz1~hU_v1AGR>-bid0^0c^ zhKVdj^HeyotG_=Kh}k;xvm6>?q4S`891+eU2LT{(T=Q*WGEXd`B8v8duM^47{+B?6 z&xZjl6Zv|WQ_f7*DqnI#dPAlH7&Pmm4k%C{p!h>40PN?JpJhy#ykUbZiVOe&q^eTI znR{m6L~|xRM2mra5xe5(I%*&uoK@HdP}(~=jkCX0V`gC~uFXZxS1Uf-8k@|85IsRr z5HM`*JgabPG-Gm04g_E;VAb*prLdlTzJ+~lsELhDRdaJPS#5|~z59AUok^uN5c$jZ zlT_>R!&T8I;(LOk)bD1Apr`myJDa3%2;;+z5+5S-hMu@$#c84;@pEu3&z-Wep%M6R z<{s}IX0{+v@=#4s4>N`;z$%VUtkbHxtyqT;=E)XVn`mr;92&qV@?f7z6Ewr=cMW0} z6fA}B)yhJxD)*fdZBfTq53CL(OM%x74J2v1vc-~8 zTEyxFzsR=V00f*6k~CPRz^x*{NUCG4O=g6gFi>taRkE|#oG7>K(%8GZ%epgIVUyCf zb!(fW1<>jP_CqBObrvHN$Z#-|B7o`_muF`+e+&adsI-YRQ);VNfeN*boykHB@=@AU zd@C=wF_Q&YWt1Tp&(5~?9X(WCPB@=5eEKJzp!-ee&5d`G`3FKigaReNlGG(Y6uDKR z^$L=pjy^^oW<1(=Q&Ozc^4e{+=W1>1iU&}fm~r?#_O&txKEBJ3S4Tt}ePk*xf*orM zis_1~vboW8-_#o3)vC}-7y@MN0G%%$>c-2mbR{|=4Mdomr153R#V}%nVw@K7Z`ZjT zZG4bKE^fApuQ_U|=;RDg7fby*L(7*2#v;d=@9}M+!#D{%#Vsd9q0YLy5}!R2YovR_ zN&IAPGizKc>YQd__ds1`@i_`3Fw1681YP;PMyHv}3Y2N;PyC7q_N%@brKOX*he2!| zj^zqi5vR~Bu->S?zk7y-D6>E31Fd`+7|RiZe*gXrWWn;4D3z^{H!D?nN$c`D;|-qy%iFhvj5Dqe_cyaUlo}QU zVd@s_U!S&Yqqy^-1EN-)jbB8$=6m$j_W4>>3l?hreSntEg4Pw2IGDNJhcekW$+$)x z(U-TJ{Wmg$I3m?9Mg%k)`qMIAmddE zDOhX@I5pZi-_YEhH{=`rSelCSxf+gDC86pJ9oxzc2X(Xz51!V$d;PB#;J||k{+$5h z{Kk(Yx`Y`xgrZ(trmnl^1VWdJ)H;t0!E;qGQug$xN5+b!wQEq=%(vK3)^MW1R;&C} zG>vvlS0o1cY1j$UdXvEU>OYHtP&K_WCo+-J6Z}b=lzn{kMgbUCCvXtvIGy-3&B`!5*Y^YjCgCw zo^BfMw(2JkZQqe{f#{2DmYpb%=G!ASOU_hV6=S(MO9CAR=9gtPxIDGYjn1tu&$JRT zo@w1?s2u-&+WKI&lRGfOu5zaXn93$dcC@#bTLA*5^%+!ny12Ob=`Chg&|Ab|2x(NQ z*_1L{&S(b6KPT^r`WFDTMJr_DKu zoMzgF=H5Z0!H*(X!+ap%sbG~k>D97UYVGgOSEFE(X)J0MFFAM`8fGmXJkHd&N$NwT zZ*(BUu()o(9CVac`1Kr$kMIXRUc8kS{t)8;$gw*UiEG!;;S+uUiK_m}AW#;T#qU07hb>f{1P&ufmJNM6;~AQN zjv+}Vj@IAHU6OCAx{_gRzO7z@(SL#LVD^ZZuSQ6P&CV3y%WrnuS-&0IxAcX|2WUZkLOePZ~bRx*5{rj-NBs<`CrYmDKv z!!)Cal;*-HRaIP;iPX4a*S z$dnGYrwXg^5TYqs_{lJ>nq+UT-BsnSA$ey;4AL>1peQ4iHNFnN{<6nY}MLz z9Z=^Ihrp7BjzrO6*m-2uRsEX~#*4ix!6E!ymq|MHi{7!&&PrY&?rFeaoy@Zv!jkMk z97bDIiY{IP>e`yC9E%D&HA7}BUEqnEBKg4Pan7%$ffz#q! zf3%TYvB?7a`5iSI0~pq&UDDqzM~?mhSrTt1X*8@^-?fdo6qx7=6=$+4pmh@N2#|7nx4eH@0ULGX{|mft=GoY zLAibOh#Gjx2S6pDxMQAz;P7ousYJr)OuS4J&m@C1Mao zdw{hMCTQWi!W?@`4WDia32~zn0EV|!-xh0}KAF^C2f(aMSm~J))Y|jh>Sa;I_o#E# zXxmx;2a-Pxfyl?v`Fr-WDN91`QfcwaDj#*F7zPrvpUXba3|OtBv`4aL>3XmE@fR`L zw$iuSRW0k!Dj2$&3(&yVZ?`APanPE7)WDjetL%`vuC+aaW0A#*L{Nu5r6*If+jO^$ zFwkYvDGv&=={G%-OM``mZYYH>I}j$?@28xv>qfwDyY7}#NM474{B3cWm|vh9ndLKs8m zVcaBjzu%g|crvS!*A{53m97*o!luo?Brm9rkzdMHEjAfyI=syNW13?6rUbJS;SU7} z$Y~8uDMJx9jj*?r0>l!Vvt_t|roJJE`R&T0IkB+;&OStt<>^w&L-xks$IH^?^2fzv z0jHN8#lF>_Y1^?u@gQNgs5=*yW)?)m)07@-m;#Ln*Xesde{ZwZA)-70motFB-s`del@oauH^sYa^UMH+7LJb_d= zsnRy2mB|$5r@qza9j~KOoAWj^_wbG9`LrD%he4YT+n%A82i4!<@_#L~4-Beyc)pvt zw~IkVm<*F?&Q@~jWiahjG7I!EZ7mRg$8D^IIO(~v;4$ta>i_&dn!W>^>i7Ns*ds+E zLRR+Pn-Iyd$FcX!-h1y4Le{Yfna3X4Bq5HGz4zWBgz$g*{;vP~>bi0X)%&@hd%Rw+ z`@SPi9TR`wJtl&_=VwN0(+wORbj;&bl17@6M(+5OOzb%ep-Zj$7`-5p<<1)BU}vXK zmcQwrJ^_cY8oYT`-A?o(a!ZK3f6hUGWVCJjUHlO8^&iLej=aSxMD>;L;(bw(CUwoF zz-kBi3CY;biwTMva)f$+7gH*BRQg8$BQi>?1k?9^+~_; zehij=ue!ECjj8Jv&#nv-dW#FkaBQ9R%jP~ogV3Bj#kpOD>+$Lec}OY2P1bNlLQ+8D9}^$jP8Y zdy!9zr?3h6ZyV3RgtX*ZF1hjSZ@~?Z*f?(1#1uno`j?4oM@<%OqwZ8N_t zwVcrqI;6s%u?IB97xiOHsrkh7fI@$U_I%?#4~JkfFcZAJwrFO{rBwW zcrCX$=T9Ct0RJH_ZrAC$A=EZHqo+MHH`!2~pYLRUxGck$`*dZ^;dR{TFiJ4VSLT>~ zL6HzibAA1&g(H+;AZ~z}WTHyz=kDeGz@;PF8O3(G&XeosF5D77*x!ET>o{~q+=DcTueJPAqm#K@1*iny0;LXZ9bXyoLx;N z94OO1EAM{V*mpBrC#=E{`}o^;3+gP*&VCboh>L{4I%{SVC-Ec+UVVY{GF&pSj zZ7sDfDs~6S9UTcXQ%mg&&Ki1pq;1|(Ll*09Zl^86QHq}$VdR=+4YAQQ;R1bss&#U& zjmtFE0=RIWTX1l2NH0gK26jDw$^_69jXt)OwJ zxl-nk1p$QmG#|HrfI1gg%ooPeOF`ph(UNM(s$~M3?t^(M*%ne{xI!p`B_$zsWO$X1 zCV?tvN8i^g(ADt@m5Qg4b!dOt=|&|I<8ptB`5AREi}s}4e|Qx>9T7A2J0wj)KcA># znWZ@-0(W_#{L?eOfbo>8bgA1oHy>ny4hSwaiT{`d<$VKCH^UhLXuDXVEvD`F8kS9g91!e(es!^7HjI;2`OD z0kyS{k1$!>$mnRvgdO~dHCI=)C^Ii=&t_F@aXlaZL zt&UZMD)R@>|M%g;&o`FIL3iE%%i`AN{iCwzwFX(DCL1Jr*opbc2g=mTG<6Y26}}y6 z8mJm&n*u}SG1*sGjYOKvaZbpR5Yv=7DytP!2J99Zd9^z!y04{l;>_5CuXhioM;S?j zHd)B%gu8##TrOxw%b5e8=CDOING+$uK}HEL7kxLq6m>y}{Z!jY zrj<&~<_lAtq9lYMwpj^<)FF@T(Uxc`x7pttFa*HN9e>!!&BqbT!S-5$TGi&uLMOYN z&rAUu;&m$Hftmt>=sIX@TUOj+m>*ITU#ftLy=z8oD{vskPre&gNq~G(b2z?_84IBp z#iC8D+UO4m2#5;^uyzyfZ*lWs!LfbaaCYtQcX{}NlytVU&?-=JGAOrai z>3aPnV3Og9TR16P&gNEVGoPXZuz)Z5g(3VE3*%K{MZe@(yGoZg1zU0CxrW%`_fm~r z$@B3GRR#tDs`C=Fl+r0jhT+ZFOb?LY2G^k9O%4&8`(a8vtPdPQj0Ns~uH)kH4DR`B zJ;S6!+RZo1e+UfhLM+AKRwrYGS))U!t(*fd*VoEe$==0>mnJjKC56h*q#|*+E&;$)qS#B#ej=n zQ{m-+e?qIahT2=%Hf?&(#acXw^@)kI=d4OtzCa6;i)gdiY8VR{&a|)1Kb-98fHmKL zV41G0q~a^f=;6bDG>8V_;zTNiA6n^>2Y=p=*gX}>%oJ+M!g^1$NlG&?mB+(6 zU%vG-X2+*%W##8j5XQ#$eor9)_R=8&9svP3SX2}JeRGrUj@O5ntvu#`T9=1_-IJ1P z)Zn(dc4M4!t*$1KuP(;C!mOGm8N|}$Z-OMW#(}_aPCru}84dK1{C-4G8&U|VqiR;% zl%S{wbais_=HAi4HjA&61F5WNz8mDQby>D` zkvL`98_Vty4qg@ShFmbY57yElbHpCBB8}o45~$tJ{ubGLmhbuHolqGU{C-q>+szSepn&rwL7JLmKd_GSfP9-#l+5lTNc&76(8k%T3{?wcb1<@ zjSV%}au=zeI|PRl^ec?YAA|_)DlmIc`ajc%x_qz?R&W`pJAC)-h&93k2#>8nPGUV* z$cD&9Y~xqjUZyWNt)Khht5uoQ#%kT+` zQ(iC@-Pof)VTD)T5Un0;iVlapjbT$&&tUgQlWi&+bbCZpv~xofFKT=yY;k|a#7Kjl z9z3R&mZVr#n{wuKgt=8yWf3!&)PT3~Sq!Fj5R+_FOZ?}}bUznGPsM=%Ak2o^*=}__ z<>3k+P!*t2tbO|gQaI}Ut}UT{)yX^NnGQzNTal?x^~h&2+=CoTw>Zy94B^qSrg|P8 zF!G;$=gN_4w{ts?0?13sgv#1PH=*515B%xX+Uj_8lwea-wk(VvJc`e$3w51N3HpI^ z1q_;Ta*&!K39eQ(NwlSI?hb~OiLMq=uLW2;)vr;OqPdG9&n$H7Qnzu zD}QX@qTW~j(`L*i#o(8-1$E>Y__!7o~vyxV7l{N&Rg26K*6$b|RkU+9?WLUcB@Zj9Nut{LX0 zlz(f~m^{{{{qBOHqVZIEVUf~QiP8!{uQY#=txM|t5<-+S@)CsG653C)H#oBP~v6Du3rwP~^d^p<1MlTOp$B>3F18oum?B z`9h1g%wvo}Lmu;QcyrwGs(7LI54ONT4M>sd;HPb^Hi;?a%LXGiHVwu%S&9NDZzQo{ zn8X~PTtE481(Y86G({8PwcB%~4If>ihvoLYjhe}FZS!f%+46}r{g17UPJYnhy9G~2 z&Bxq4uc1-vooyf>;}0sc){VBTm&nu9wzjjieQ#&(Ez#7Ro{^)p)Si)%p?kY<{OoU_ z{+qClmbtO{K`uo{7q#q+)5T8q;bAH5w4YO3rPb9=HfuMxx><4W2x&e$KHN{2g(qU626xGgbF*JLf$J>>FIt+wJals`$WBQZpps5s51Gfrp?%F(B4y9 z7mJ-p&zz>LkfG>nN(26-F}+D{ZlZ3&9waDVt0_e`9c^9z+=aXp74bT`Y+DkLT79wo zeYvBf#lSsK;%P!j8eBa#_NvM_FE5=-v5gI<9FIJx6Ubl?!gSmAUjj?q=8kfopzj|X z>dHh&Sg9=>={GaeK!;XOVg`NHU{2c6`|5xw? z+@lbF+}RxVWfjmLkKm=y2aKA}IojCvt{{ zhUVtx0RbKT8!jR_gGvK{9(QF(mM>C&^ytxGb#7J`(yG39v{B}V>r^xXaD{vMQxtlB zE(i2lSxsm473U~wi9^dzQ|2?Sv|nsJDJOCZUrgK*i9CHu`08^!!HMlGA1AW@_co+8 zH2{^ZZO9G9XUmbvQVQDe8B_5wk37#1y7ipR6kNU-Z@9+3X>Z>Lfb}dTo=^l!&++M> z%&Z>2t1rhZ#w*j?kD^{0Rj<0&v9U&*38X^V+1N&hhL)STMMcQ&R>R746ybEb_4?8j zI~UhxZJtw95{EBIYg(3SqoZ3Mkw_RA<+l4wRJ0>TPO4WLk+(nJIG~~7^|PX}MV9w0e2hl6Qa-WpzoyDdPj7QE zzZ^^*8YfJ&l>V0LK+EE{%}wwN z>*2SGAOmBWUWt}`Xt(`d{R2d&2XtWodPZ2v88a-QscB`o!*8a_(6(yRwdK&Wt!GV@ zgs~ zKLl(I*g2oG7m!aEjsin+0aNI}O)oY~k{Ix+8pnXAvqi@Rc2k=Q3krI;#CaNH z>a$VKZewCXP4R@h^C{B;dueE+L-}MNuAZ0Wb;W=b?*)5yjBR609s%S%?WPC~<1?I5ved6hhuI4n>y zL8<00PpE?3&jtPdkyw^HHOcY?PD0 zE1B2HlfzlHm8By*^ptThSxs6e-aK15VPenG-u=(rGW@xhd0|P5PoTelpc!r20D&&1 z^rnIGpp{$3hm?UI95c`)+5gz&T?JU93)tk<|NTbTXM;hRM778`GBvhQP8(BBDlG&V zVFQz1>g)U^;p9t>ZKK*V)6>mndq=X)f>OpRnW#2E@La5M^<@}KxoL;+PpY_d}NwCKydtOvPu=C|_VZCy-2LTd|t)&xdy3 zYn2LI>%jF29;GInttk?B&?4;f#)0HKAYb*o%1}H(qV;@C&hX+wpoBLWY=5hr{3dN{ zDmAjDBjtSKzr1Z_%(VF^LOLKoNz@B?w1@7iPLeJ+tUBEc0_5mlkXc>M&3&IGO{8Pa zxjbBCo}7BB%aBCWgSs;At)Ra+d0beM1XcRbL6ORPDfe^=kDYvt7s%6^1EMP^Icv{oy?B4 zJFWal2u#V$QWzPQufv1HdL26p=!;OQcz9xZ9j)67C=*!7>*eOgue38WB%ASMq~|D& zj1=?rnuSDdj-Uyvbok4`cRnni$^yOY*QejMasDT#)u2r1s^|6JRlPD#;6GX(7R_Of z%*gxqXm8&!Zz()}{CLfIcF!F%th=>UB%$B!_VNgvvLeIA)om&dBF#8Z7rte{!HDGP z;iBk26$8RY)DTHIxqjfjaA*KFU}c2~$yT=3(9i&mh?)Q!GYqulG&Q9WxSnqhM?_%Q z66W=9?CtN1`2YE}k??wXVFB2)4m_@Z1AMcKiwiL3fi57-1`ldTFrm%G#RUKiIe;~D za-vP^)OJffkpoI|5XD+$svfOA6C6TRN#Z)?=d)8`aWHem=?#qAvEelY`CqC&TTa`Bn! zj&^}-dh(XCFCGx>&ps)F;q^ERWG!vj%(v9Q`#Ty$#b&zo-F6&Wq(*|ZxIvC zGBQY^kKXY47qo>Ao$Ty(_s;|b>qR|Sdh}ovgUE>zglM zwtJ#-ZZCbjj_JZdl>L4TLdp5|#4$-^&+dXeF;son7IFEwDfZtV$ zXpK47Oe^n-nk9Gr1NMNnT2U|8P!^usr_N5NmCosez=qoD(W%+=?3|pqw<}#f=K$LU zt#uiSES9PbKdAxd@P9i39RBx!3f)FMuD43?mKrf$UDNGpce>0KS8F<%P zp%{bi++qL_W8lTg%5Wf#ORdBS{Uyc4gwf$_NN6kAzyM&V`T2RUXmH^uUWQiG^RU_D zVEXK=uFjRV-zAi~p`n37#CQUK`vLGY|PTMATyKUFLgYKy0WcX z1Mb+^*xv;6cv7kB@od$s_;ukCQmH(>)!J~WG!?)k>2YD$*%hnTQLJ7&O8ta?Pg9mJ zKCX35GF`622_DdNnbhM20t8sC5)?rSZ){o0jf{lf-!DI7Ta*2Qe}|w z;-ymWMiLV$4Ic8$v#q|0|VR% ziyRAyl+>)&Khbl+l0#Fa?f|M*Dj$ zfxlKoTNbbVt}bH=0^C#bvMn(3#VM&4TPB+9NM`K|nBtdO+}6Hfm|9uc`072E6;4BP zaC%idhuIu2k;xLlDqoeV*RZi-f1B#-E1~qSx%g$O&6Tce&<=8$C9jo$gZ-(s=xE?( zHPvuwV^@mX19>);ZJ{ukrPn%(Iz$nY;t|wj3HUg$_~UivA@51G87{TzHxn6 zIbjS3u!{_>%l+SL!4-dvIis@db)V%eR}U|*ptIyWcOeSkSD|4t7 z_5x|hMgU97QTl9t4M78*5M=JJ@Agzy{7yQ?#>N(!oMH<~pSw*>O zdsN1%4br3fOnEf6eiwm-@u3f#M8GczzNNjNo;J}=OIPF=9$M`5P8_gmoH$@hRHCa= zQ8__h%~qB#%cBjap(9QhUFp1gsK2_bb;-WY**WpqFG8$j+1Fj)GpH9VvmuilbZf<) zCB)H*Ho2fOo_b$lh9M7Gnui@c@uNH(IisWqhK?vd9-_v+;p*-VTC#U^;>qB3R<=r# zKlHZLe}yzh!r7wXGBN9R$+nlbb{;VC(Yw?Cip)Geknnpg(nDFD@fv zE8+DM;AH|dNV%tHW=Kd#%xh=MG)nv>@@5Vmqk}N{b?3aSd{88l7fg>W9AlFHad6>E zq0N#i0Fr#*#kU4iy~Q|?Jh4iqAB5vUZTIZiGr($wQp*&Mz2_4F(i2h9Sb?-tupkr& zYQP@?LC)dPQKc3FWcmPdyxT2IfWzTBhWYVy@=0`H-Ee1TCopI*4*bcJCzPU|Y{>&4 zie`Cwy4au{O~Bxm!86syg80JU^mIXt9cedB$gE!2X>>M_Sj< zO-+42JiJ?Ia}clj}I%(&ct zqgx%|1j#YJa1*u2~SKqn0Sl6d=-g2^} zty2TX-_w;5s->|T;4s?S+Camh>+PjO^-QdQey`~Hyxn)lqb@wVkMooJub+W%)Yc|S zfSrQPoCc+kv@w4L;Dt`V8GR!7d-VES`IMa}+(B5BP zzdGWgOMNA+uBrKPeYz17 z903lv+oVRl3`m8ChlUngJr014G{))bjPL)e6$Ag!^t%9kX5u>wUteDbhoha>4=py< zBxwRa84N9%?Y6hK$(j$WDl6Ddj$R!(SU6rQgv6=V#6}*8n!`BKvSvF6F(8L{6*$QA z{X}cIsh}a1j{gWCf0&oltZe0Kf>TLosHAi4> zj*fyE{mMc=O>;KTCNiBEBCxL)#1~Us?CiveEiIf;!N#6SLc)qbKpD&zmD03~wOICw zikSMx!mzk$5>0-x#yqRlp(Y@Z9kXy&6gx$~Yc$q)^;Ewob@Xe*XcG=hZBUS*oU|gi zN|kA7WMr_;ACmujsV&3rDhA|K{xAX#vV9IqUAU!ijxr-*G^n(lh1g?c>Q`bJgqZT9m-s($wE#}jzA!yp1hRCmQMmxcEI+wDnx5*YjJV$+qZB1 zC5&4PtQ_rpeCBvWKG|dz+kh`l83!epYs=!of++Afe0*R8zjv-6WpJzl`TGe!#meG2 zwHGGro<8*NwO_d@827znNQNtSck491CYk0MF2`#3IDq@?)_z};8F$eUIe%JAsfH15 zPvDBaN@Xe*OwjOEaq3&cWN3Mx5QoZMqwN&G#x1H~$kzJ$`nZ8@AuPd`o*H5jf9~NS z8yWdo6&nK0P&`}iSntEE?ed!;D*C8coR-GgLLrTP-X8psk@UBR7qWt8#%swVJ;Dwnik;UsnYsm22EiX<%nKrWy`qZ0PbVH6eW#%>HFcNVTSv-j*(j_C| ztCPzPw+_Y8*4%S{g${WdZiXEVIfz+DgM8?=rJP{<&A-jgt09N6c6zPZVy@e_izoTv zqvc|!N`j$*!6k{36XE7J?}}ygr+w;Nr28jV=%^6YfgN5})?W8{Deb2)cI*1<3y&6^ z&*9V`xchy8DQRmX3SBrxm*rV012ILZk=jf>Uof6DM-zXSKVjm%qSJN|L zMe4FJ_R;6iJ;@@T&o=jFiKQ&m-*G~B&wYBNf(hMvTCp2<&BcyVFD>A0%0)!q4$xTTWvd|Qw3hl zbJ1Hgc3!QENe9_NweycCQJ4Bh0})5LOEYNGTF}>8_I6^t8Hzj^hktqViQD_mN6*9{ zG6cBbTquJb!)2f-lIZWACQb608%GwKuxy2ilwUit43dtjoc;ac*V>TjXePP^EZD`x z1|tCmawY=l&>7YU>Ck>Oh;5Pjh*hfV+*&Rbq_o&3reLs6ox?5kYc%c2>AMh!lg8gE zwln@E*#%xhQw3VwBy?<>7i1^}YiPVTR%Lo#%Vrdz%&8Vqw zD2FaWQ=UBIQM3t0OT>CIC$Z+MaPf*1VluU_Qjgq!t-#eMHX79fW{9kfudccU1gO)| z-rR+bMq#Ys#NQ^VZv)*bNOU(gHpbp-5>Z|9TJjuJHZ7ms-gVtAbb;oC{yrEi)lyfD z2)YN5Kys&cwOe_Cq7H;U#g4vnaqJ5-|LhG^Y#)dWWJv`DqKXT#glh9u*7pAS zz-Ll?_@_cI07{gA`>jx1?!hDAg7E{O=wwE!Dp z+o(6Nl>&{J{*UJ6;5xUWHjE{hpx@xb%4nmG_TH&;4nf~tEyu+16fyp{7dqT++!;819DP=Few%4uRdbgOu64l1vWJQ z0Ux6-6v@^B1$OE;cVK14?Sy(6Y0#c=3;(O#3g5qk_paR%wU=i89Om16`Z_>7^L0l9+;N!L79wk z%{K+*Q%9pSeC%>RNJmSsZEnKaCRLiPjE=|I7N0Hj_7*+YXu$n4_@CUf@N}E6q-YTO z@KTn_6XGO7X}-8<_U|s))HPT(yeiS_D-F#rvHH?Ce8Rb@(NhRv^qGAU?iNDtSX;0C zZ-kCk8k6QDv)M)Rp2=!a&!snC=V_q^R?vM+_4 zSNBTta&vRRO0wu)vx1eA3-1)ymYPmwzPM7BqTf~JJZ~mJd9|=W{v_(|zOpMRBumf< z%shE1;*KqFTSneA-&=8Lvc}2qV{prrB^9*hFg*Iges#QrwBS)RY-w&te!gE`Z#_DF zlXJsanKM5AO|ngH#Dd4E^LiWH57T8;D$mCoS?}lcq=0<>xRT> zLo$a*8|GQt;xC7$)R3RCKbiWO1z5@h)uwEDE&H>}CFo<024>rIlD;u1+KZOqw|RsP z2ea4hfw+sRRY^{Acq=Fl1+IMbRXkc)$h<_6G&8-7#uQd7uKAG5p%j^^opWEt{3|;T z%4~7j*B>=3JaO%9FtUT_r7hDU*1gwM z!=?ew!yc#0AsL#Yt_z>T(elfj3i7iXhXJh3!2u*U1Cg*tO_pG+QI2w3>tNAcgR1t+ z*MW;-laoAO_4F(%*mzZc(slhTFn8o{tH$zQtoi$l_tL4^n)rg|*H&m^oAG2+<|CcWMq{)Q{R5;vtuis2-O{k-d3lk_!5Mj`uQ$*=}cwhe+ zi4#6Mf=?F@eD3uz!CjVdr6v{RwR;!apx+uDs87&rud|PKpTCvC!j^@LI7It0T|wP6haEV zodc70B!K+-ZbFz>S76zize|W@1dpBj&er0hp3ns7D*!zY{tlG4E zhWiTT)#*z8?fm}qyR&|N_*u^SHJ7w%y|=M=I0O^>#agrDhYo=W5(t=0R8cQ}K%V1eu7_O@-8&3uXd0(uxJJcbcIxoDE4ZlS6r0=}zXxFVHywtk)tf>*pP z6n=V{i3j<*-jnT6!rB%>Sip=s#uu+{I4(@JuOur)N`*x_r&x9Rl>M)TtdYj%U|4`O zX%tsq)){*z=EL=^^UC}h7|wwbi26q%)01LSOxh;=_?7$cDHqu*pkoH)_2xh_C{PQS ziq*@&`{}wr=(_*agRjCgc+ST5MgHS>-T)6PB?Scqokt!TI0~S40xG)g#}Eh?KR>wq z2Q~Yx|HAP5%(u+LJLgRR1@yl@1B4ks0e!Unbd<~-ejs~`rW$0l8(Z*xhQHA-eMfiJ zNAC1b)Nw(ld)PqIuW(Kp;c!|Bb&} zn7%QU`t=7a6g>Fl7DoVO)hB-Q=zKK=OnsuyA{L`u-dK}W!^M>C%Ih6G{7TV}Bdtg9 zbwdg@fomO&C-Gd9dxggYT{54gut;_S&Q3x5M}F1R4NCl(@7*5L*9k~0X_v;zxfWw! zSCF@N`qDG*XYN4tn3|euR{N*3fTDX=DB=mqUrcG?T zzrj$nH=l)oGXMUdNPR%;x6Zix#vEzm(de)rA6jxLi^kynIqi2A<6~xM^f(2LTlsv_ zwZ=h98I!r#%D4)f;i1mIoVjVCaIm+x7qe-wPFJjRj0J-GDFwNu7+I;)uaM*=YKVdD zA~xzL*53chKJYtY(A7snyL&oU2HU*d&_0GlR)yQp!S!WICo% z9$jXl;Y8yb)4@Ou0Rm+mw(V1IEp6?tzh_9m$W~TY*XL@iOfM!$W}v}Q%*R4^#Hv0*nuY)yJCp!7;@esclZ1}{LT^!zO=neId(6BlrcP`R z{ZY1d-EEatzv=Ah?A>qWgRW(r+j0YCW9Q4U@A<(gWBc_#;xE&gU(rBd6PQd&&(=45 z!0k{ zX~MSsIHFZfPUF!dgJHLVFrVd_DPl^pvq;c-r=-RwTSkOi)t;5n}${v(G)nB5ml?5X#B$tw#;6J>_ z7`}c!e!QVvmytb;onyS7BB8?ZgmDB#ngc~pX0?&BaCdV&i19KCek9{9WuQ61hD&Y< zMN_^FgrK-IftE9X%L~`kUYke^`lAWQMr$Z$Lr981M(sN(Ym7R`VXxblsa`^?_#JG| z@mX%}%&31IgoOb@0k8>8uiYq|JN0F-!BixTXIEym&7GYRLPDf*Zv!M&z-T1UFLzrpC|S#czho2@1*lhmZy4)dih*)gf#q44^2OQMlrY4mBr4Ag=EU< z2lsG?-I+G!_3fiLB-3-J`+Jc5386R zX*jC?CHT-=U~aC?B*Q#aK4n{`Ibem%_@Kvu)~_brV4GUXLXYm2 zy?PNNk!QFYnTqS%vsN`WrfN)ea%zu2kYeX2Af~GAU)sx#dO&UHvy|A`G0eFOY=HKd zs@!Kr>1HH9xodVxke|l8?di90CcVZ|EjQqUn0J`Q#$Wu|BrC=6cA5X%0U_uX3O!9G z%Y}J*vIwwRMG%bJ-C)y9*#h8j_*ccfDlCYEMu7MVti|l^2DhbKhm90({x1KZd(AO% zqxtyw7&L4jyy`V`@$m4lu&}VVA3C{8h>x$Ts6ao zK7dk&7On5Iq+L!}7+&lnsxzbJjWFM@R~}_nAE=Q;87OAOk>BciuG_n=TpFt|ByZ=- zVMHZIjo~h}SX;%6a~0`AIhk-F27K>BpQR{2`z8Z>-LG`k{s!l5#z$i5L%!+2@CyT{ zF-ADYlh0hZZC}bQX9M0It=Dxqk8T>C3CSTKk{T(C^LqYP3_Lv2e8c2VYc+*OY3@2C>qD5}mYjF_$S8gWt zQJN-*Z~x#J+=(eyU4+)-*HnLj%`PwR{%L+qM%-?6fGY}(F6Mr~`1OfO?A8g#1f9lw z=S0h$>jxvD9WQTUcXzk#)W(%p!Uq{f2HIDzQvExVM#=BUq<61ZdX~7IW`1~E{CdI6 zhlkBtBqQ9WIZ$Z}O(eWferT{ot zXwf$wEs*Jqy>~Y^?`a-|NgG|>`cw=0{xW%pewJ9vod{A!diigp2WxB_O_O1i^&*~! z=|1FNfBg8-)OB|>`ugGTco7g=S$TSTIy?XRwblbJWUY?9zrVk&Eeq)9PnOqMd(`hj z(GOJLiYh8#62lFcm;jQn3`I=TkiK;j4vx0Z86`PITT972lFurxTesHsh&@le7u9W~ z77SD4-`ukAen^LzUj!#mdYX;>;4p-VAC2mVaPwkhS?%-ZsyHYo&HliFny17&F5}p< zmg{7dJASa+>CAx$zIV~usOk0XnI+-7=Y6covQ=EF_1|v>Z#AVVR$lE7qRkEe-IA&V zZ$DT25*LVEpd(3(|1NHrC7rU7q(9YXPF#r!QG)Rzkrbo&;-~0pFlHjc_T}ZWvf1vi z%!1M>TMtAPA>9B~+!G3M5dcXg=F>pmSy@`14yOJdPvZFUA6we^o;pJzGcF@GK+$Fw z$UpS{9b@{eZW&f3jSXEx@IXz9cR3f>M4joPv@D4=-^COxLcX7>I_#b88Vh2JejwZ1j} z6&d+-yS!H>@XnUm?doRu%sB924b2)mk(nOSTDOnlPlQAHo9k5Y9~xe*fS8Xrgdg%) z(f?DH4eXp7Rcj}G24)99iPTi$4T&_Sy9h~>(x#?|@6iKkMoF|!)mdQZAv-?t8+7t! z%Y%Q|FV3g+oqWXpRdwf>Jxa$Bk4UVntN=6$WbHt|;^lSq{rmUmXN({gUL4FQwF0d) zkQMCy%m)|#8uY1yOfj?ghyik|4~XPqD`J3G69BC6w_n4-Y+Cki(L zB;&6Pw+t9Ms9gRW@D1grGZzQi)xc+3miFef_)5zjfHf`SCFX&b%wAsIAMMLDY;O63&_;itxxMY&Qzh)^;~D+x;GWJfA)u`Fxqq*-liEz0n5i!yWN z=DE9%Ft;E{mruQyE6?o0f;bP)d6XM1?IG7rNbohy1Y(| zR8#Q78D|F8>RvD}vK?j1mzFf!Is|7giJU_!sSLGM~QxVXHy z0PKBSLP8pH>*B)W9KSRSP_`^68`A$@3(yZ*8mhbQTWcYz)~>E~U0n}Yum5!a{rh)l z=mS#>Fb3d6`V*+If=#$cV|y)htF#cL=J6ZS`Kok;po?!PSw&)QX{oZ@mM6o&$jC@v z-!09{YwlTQF+!vUpom!Jmh$8xj~!y)@O`Ll;zqc(7+Bwy%boC7<*KIg9ytX)Y2(sh zkcOx{OA=HxvLnIcsh!CFg0uF6S;F>x{ahlQH#Z|R-?m7*k|R^FwE<2_gPi?~Vp5Sm z(RNpw56ScUtuH-!?a~ASxtv;-Dq;mgj7L=(fEek}N~1202kzt%bMH?8L^&ajx%LL@pZExPn4UBR@R(%**Sxwe{~<>1(p#swxhnmT_M0HA{`3 zl`mMK|AE$-GoKdK(&w?EGe|dshs0MUU8ixy2~42@>!*>pcDhREQ)O>EE1{>l_1)D=>YIDaQ5ka1JcxE|g0ErUzi6_Z}Yn zsZdLv7gp1lcq!1L#>PhdCdU9UeFtc8UC6at4sn#P;1}l18Y20?Tz1-%MvT~3tfK1Q zXD!Z$BXTB<@n?S>IAN)eGFzD852sWWeNyAKT&FII!ahaWWEw_;NWShDx9mE61lh!H z(J_9bij|VVIvDs-%PXKed1`QWyaIuk@8fxE4QY**HGlL{A!BQOTzHZUC9SyTmaZCU zGHk7Op&u-V2`wvTa;;5o_9KCCjXp}+JlQ*q>`C7VNW@N-2?y1Sc!*?8)66qG+bLUL zo4xxSQ9I+n7T=Axwl>j(-^dhDAh0Rhmh8BG?an`;X`hz|27sUXR1($O7*m#_2Vjlz z-HVvOphiuWV)ebPty`~SY{~={WP5+l^!-E;U|5)-jRqrZoc-2T-_XzwQNUj(oXlJ_ z0n{YXJE`_s4;`5cZaJkaYOpURvk01Mlc6aX8&USxfNhq5_rN`ZtVf!Q2Y1F+S z+h9xI)Xw9#Q=i~y*yhdNS))3*^KRH5_US9yIOn!sd8XD>LAkV&Hvh_Yy(tU+A{^69 zD?@P`sD(iC0jkxFW=U!;At9!i^}Ce{8uU2Ka}$)6JZ zRo}b2H>fh1d~jNBZ^>FHQe=38%`M<-UBk%xJeEFrAmR1>?7@YyiVB!c1)3Y>lOiJ{ z$M@VN@<`C72*Tg<%}-1emfH$s8S3d}W@WYcUhMz<>rb0ldRN%o+<Mj}c z|5p$6h;2VY&HR)JH#XLW(krR)Ad$6udmzo|d?)k!w#YgCBDnz2sS`x>jWr*Q^q?GU z6+m$oc%bF!kxG1(LCM?p#dGId#J9e_*$I^^DhUd}G)4B@zt_Z#N_Ev`PD5rW3Q!tn zW$0#QB*w~?+e{6}m)l@N+$gq%%&AzRWqM`b!P`7d&if#7_j`A5qF{#g#vj{Unds5L zCQDIBrN;N-D+5l3WW7cZqgpO5POb6daz%DeqEADOai5?<04}T!Wm03k_V#r+9U1OL zq*-lSJJM-sZ@ETKi^+BnMU~3da}-9^J^CX^UAdp23lK}71C&n!EFD8K&eIOZ(mzxxx+<`be=z9ZZR zumcY!$X&d=yqJhufgmW39IQPpiHZWeO3li@)kY9W0nma0lpH`K0bBsUqjYt2W@l%q z!zb?nO*bEW5z+DLQuf8CXn-4MM&SYc{blM5a3EMgV+LR1bdPp_WJ%{-1h)m|KUaq^))rl zppXQQ3@zZ{)v_|iX~ID$&}8udvitXZng5zBzNfNkYr-C5Qh7SU{ynm4?MBsXNI>R* z9Ul9D8aO(#Y*kWAv2Dy81+?*BAbAFY`^7~H1d6+1Dw5JHKz=5nNMvt_NAhKqLF$NO z`{)<^P6ZwDLc>1mx}&?9gEA~&-rM;By+NWpJb}lHrA(26qYm(l@qsiX5`idd2gjZ| zZDl2-wkexP@U69%gfP0%-FN=aV+a877WW20>G9n?_t~U>0WHaTJL7j8i6I|?ZLmv{ zE_v+!vcJxNnS>|9j6?f}MMGtYR(gR%Ogj;ZBu!%T^+aBk|0xC|w#-D*)v=|vHbVbk z`}YREnb`MpON8*bauKmMM^I~>I!h{m-&TSi?#w_N?DI4@ygX8t9ECb>bfv>jFcrGg z86ZlE7gO-#Tugxl29VUEBxN8{bmvIBH7YuDl6}g@-qtP_wDt|yO6bZ1jyg~SELTK%VZQ328MmRrG?w?N)`p2~VjKneQYurNR zs5DC(2RL9+PuXyJ!#R6rvZ0Br{5@tGGMXaI@)T%B)7(cDI<3w>-^5yR=w(KB zw)`cUzI?G?{sSqq^2y#2&s}PIff0O9vb&kgN0cv<9L>O*swnI>+WdwGjmkI-K@w+f z^$#t@Ul~@|`~8hEkMzretA<)UE^3zVTw{5uvEJi>v!Cvy*&i!J8MR=|gVlMy+1 zX9e?!*@%gj;Z8Jp75?#I)R}I`VR&@(;ME9IOcHqA|C(AVY&0CchY+Y&YU#$r>|Cod zZ7#F7x(jU!=D(~>7=*lBe`jJmEcky^%9BI$-q|l)zktH^eb0I%kg9cct+Y`7nm)Ey zj`gP8!0#;Vgrw(ALm*EGA%AYw&h=+Ro%J8)H_OSeVIG+oJZseDdNal48n{Sk&$F^#Up-ARtJGBHi5} zC`e1}0!uebN_Ps<64EIRyL5MmbV)4T-5@Fbetf>~kIR3IOI_~!o|$vz%$XFA-=UQ^ zwDT(&X8_^-mj9FX*7_op#S@KN_ph` zki5H-pk-LcK)z8Tm+;v~VCjbXsAFslC;v!D*OskqZ#Kn@nQVgxbrP;DN9i~@WXi+q zc>H>Y8ov7`>OyxK@i;`z5BqUrf31n3E~VuWrtmhOeztC7%xNNQ6SzG44tm~JkD^Ms><-h-`m zA_Z8?FT_4vqeb@$a(6q75~_KrjOi{UCk(cA-8hyK=8~qQrCGZ~=iLYa-Uz_ny`kK+ zWGOKHjG4{#p%<0<95MRhvqK*o03^oIMfbi5H_lf>@dqS*!d@?qXt$H_P&=}l_1*}e z0-}tP6X1UEAD&ffHe_`^WTxA)z|#?r13~fl@-S%57eeXzIzx*@xOVsehP7^f*POKC zsrNn54LAD9mbqPvV)q#p6x1*MvyTSL{g5?bFgGMk+i6$w{1TklFmCmDdMEL?9bowq z)Fd==zQ*%@*O8JdYlqGmPa;`PE$8i)M1R>`hC_%e~3X^Z*{@MqWd1F`Bt}=47s;@N_2$1kqa@U%}hDfFo1!rMY%56OVcuFCuj7sEM@C3;#87$G9s+k=`-k> zZd$Fep}`r~I`vXu^R)cd+cn_j=X~VD#o{ zb;$}kxE=2TJxjD-s^}HSyHy&rf*I_sAB+8z3~}%#;TxhKcw-*%A1zZAnQnKwTWkq6 zp@$p);MTPCNpoVq(bb^o7PFAB#qQ?uO%jy`5Yq4d^e| z7D^R=uf3EM21u0er}FS-jkD)`b!vAB(2+0Q!r#lj7n_a}T;{}m{=DMP&2fgFE;Qh< z`5R^8wliV3tcl=`k&KDQ>yWvo0`jba_0K02+A|Gr{49(O4MCs-Cx;}mo ztU!Iz7O`sdy*T92g0yMq&(JML%dufG363n{GRE^g(d1acz-j4Rr>zU>!U~N9Cy;&i zpF;Dh@WSdi@Jr2=!C6m6jlep@8JQMIvQ)H_2o`40i!Kz}9a+&3UL0Guj3Xi@sms`G zR|l>&-NCJ@H+IZe`z=SDMl--fV!pIin=e6%Ga^e)(eQ%0)&N{b_t17;KCDJ27lk7WrUX&k~__3lqV{}hdN(RLkr@Q1b zZ@USznOue+uo?UF)t*RCH#P9^R_Xr0qh{cgY+@ExG!V4N_x$#kR>1ukVc2`J&@dq_ zxD7wxq-af13_kDK1FuzRX}+h!eRuX|wuHp} zcF((2z3j#@__TW)dNv|;DqKZX`4d^LbImu|qiw+n?jCx_Al-O!-8c3sGseZwEq8+w zl|SpX3eHHux*-fDW=a!1n3#lB22~QbNw_u|Vou--?4SBX6U}tK3?26KHj`J zYlz)~Jf_4DhBZsvk}`yY`~m0mql1ON&mAa0zXWkXmbGv)XDS;vNHoEzPW;kO_d+hj z@uBLd%NtyQ$k>m0gf}S-q9e%$$#wacqD!#{mh5am0ygY!#T}j=&ZYeN#osY$p*d7+t<3mkXfvaKFw23KlFe%(u}UCc9x=L(?MZ3YDk+vY@NwT5k{E?> zo^rP%F%d9Cs#RTDxR4itH9#G#M4-=c77|eAS4lom4u8ru=ItM;Jal2TeoWK6`wghS z>s|Pf_Y~I&PMZYz;IwC9URw7SfkjqK3C0Er`u5*qjB}||s$;xAya06^{c;sVkcVm? z+5&gM6+a3vF`stQx%VEXu<7F*S3e7?Ft`rPsd*G|nU&Qt2y&eq_y+A9d&bH^_l6DH zIGTNZ)7CMP$`i?j$bd3as*4%kx&Z&Xi1dsoRR8UVE~m$nafxJE6wpfA@}v3P?Vqd1 zq^n`_)J3CvzDxn1aG+xF>u{)!>M7Bu&x;rbq7Uy}0X%o*8M=dDq)!{AHZvhq_#N|G z)@#={r40f4YOG`FhYaELOZeBzMH+{w5TmQbCej(PC^mV$UCN1+oWNlkB9LK#Eb1sL z(L2$cDBVRF-h<81ZY8u>wr6^m9JpC;fviSTR^w?32wBZ=UVD$m9(_+0kQ#_*(Nra)jp%CFb6-HhZYNO zzCC*n-=&;VD#HSC2fgRCqcOkWroG@TG8R;Mn@y{V9Cfh8Hkt*jL`b0QR-3PRq2zry z=W9n8r}BFRWmVR?W~Q0j^csipa6N}F{I`kF4^R0M!)?baG`k6I$<&F|k>kQb>YL4` z>_cr^p+ghlMRPCB4+3?U-P$ECZ!MT34zhgmMRKbRmYWpND+MnI*Cj-*KRNj<^F8p? zJWv8Z!*VUk@D5_n2xBRwLYev}LH%VvcJu{rD@Q*lhazb~cw+v0?W1c@v7C3;feiGJ z(cC3ACcE@)K=W?nlGea3Eih{Mw^+Ti^!wq-@87j9g=DCNDZ>(-&+-AsMH6)Yh@fOo z7aXJKN;h7OqH$UV?unDasr<5tbg?mZ9r*O9uK;8O0hj~st0F5ZxshmfS#x&#k(vfR zL=UnN1sVp;fBDWsc1jiOQT$Kqy6=j2$C%GvbX>g*{!r%nvKqb&KHT4H7fw^-Q#7d! z7y<&*sXXIGVdHD2Bw$akLokpvGCsQ?%a{~Kd%mdHhpPH)gl(v(@8xp_K;m`gn1Gz- zO+f4p;?!pT`tvEKr#q7HSGC_!pBAYe5y)~THvk=!YF&~Hs6z(FcfQcV&WFN8+CA4R z90X=`-^1|wFMO^b%lmlIgdmW9%8i@_8KS#5t7Y*%&S4{AWmj2ZvJ&0pVj22({TotBC-v_Ry7Yt8&YoCsKl6c`RyVA)Pa zzL_e3UryCm7HBjZ$+FG3XkM&ji7i@{eU!iG!EE1XceD{+<9_PmVP;YfSd9{OKcM}YzF67(DI^K(P0Y&xltfnxG(6CHcP9?pl7L-q6Lv?)N&czK#3{1mh+DY<-} zxxBpU*1#T3HT6n|%~dX)eJyo>NY9BsQCYv*c!r&=bQl>J_?1PCf_t72;S zo;7HM3qcq!uGgzG-Sz@ZKWASYIZ0a0-N-!iTF`xYEbra2n?49kxQo>&L$$>#lX`t0b(;HvYhMzV@6Ui%00MJnvg?zg+Js`$ z-X-e|hlJ#ZTNODG2956Ls{4ivR)MQn2>kgg zyf=wsaQ=p5Wo$5V?GuURfo@y!w$4A22JH+B!_W3BH9((6HzHoYJ8u8B z4>>OsT+obUEpGy0q3tPW?)4)P$5zF#1Cxkt4X#uiM zNt}^OYWqyi>+{RWH5AO<}ZBFB26KIrlG35aO4u0v_x0<;Xd0CeLD@dfWV@9{DYcymOxe&&c zJ6E?+A_p2!vuf?L-%Ed@`UGCbhH^nK)@~vg99lePGXk(qz3 zF5Sj!+SHuJ`nQ}zpj5Be`f-f57kuAd1mjLP0desKj7zdzdQB-7@= zW$6?tt058nuc|?{h^Y#vo~jmH&{}69o^x^;_ay?Jzd?$tVPAbFhwA=&l|u5_&bZrL zc<)x#8a>`=9N@S3il)%v;l=4~#g!5G2ihbTG(Y$8PzW>_0qLAKAVd8o{n}NJljpdj$b2w_vS{-m=Ee+ zn0=wD&{@$r#{3(dU#wjO7_l`+Yh5rr@-WGGdjUCkG&;9!8Fq%JD1|?Ft)XdQqlc4bc#%%KAnOuQ{Npy zeRD%(t4FL@!L9dbOKsvK+tVO_tGxL2CwL&kPLm}+miZA1eDJx?%QRk1i<+y{AA``zD!9lYnc&?M~f zi(90;>{Ir2MiUhEMe}qP5LA$q=y;K@Vn;RpF39j~pGoQ_)vf5lm8AwSxK>8fj~i1H zfrULep)qd4o_cAfq>6ib_rp-6J9X9E7 zF0lBfJdwQm1W#i8SzS{%Mvs}4mYiWo2waWrvp{5SAPA(Fmf+8%WGxA;Oa^DmK)J|W zf?uq7fci-Eso5FjS%N0(w0gKx)d+Uh)EMTM>4nmAx2kL}47P*dd%*N>%by-{V20XA z0dIaL9&QA@TY3}kl)6Nq7mMXR_y559UnypeB~l5B5jxnA;NAQv~WMd_w%NP6J5_T4YOY-fIK3_?6lCrqJVBHXp zylWQaDay}y{{0Zh%gwT!=U7r%KI61w(-SDTH@kugYZ2B?g`}^YaFMb@GEP%ym1o_uuR@oPvy^L1jW2I#n1MLv=*B@OT9#v%3sNSLoAkx@wU=^{-U-X-_&SL z)+FjV)26}+3^!Lavg=RGx@E&}j2sI;^!FELdRiqV4m=T=GvwTPQ4N=c9@6&M?H^yX zqWgf-%B<|{M$R>h4l8h#q996(?bIdObbq84C(4sB<=}gPG?9P2G1d#;kHvp?`!*%b zP+L3>(X2&+pGpcEFETVs{|SVA^k1p5qhWi60=o4E`a%2>_Djz}pxM55HU-V7@olV8 zrJ}hMcol03g>o-IQ=H0IWY`Cm4ixh@Xhb_Y{$Lferkaz79#EoMhCdn7zt!E@C6Y1% zo%9&X=c9svrdMJ8PmN8vU^Y~(h##B#yVbZLDmL|>I(up^qR_-QX13GzDA^as-h*wU zBPj#Mem5L-QGB%_zi-_1F*ED1StUdGpuTS}%DS>$ae+UVUJTQVfFJ={{ zU3Y#Izg5Zh{yF;8!dZ2q?FTS7+T-W_tB1iu43Pf|ZNk@XAYW~- z;=;dWZKE89v=Jv{vw*J?Wrg|&rOs8SWeVDxM@@WG>8@V2;oZ(~{b^pMC&|xFjPFLK zy4pVWeb>2-mF4tZlDDZ1P)K4&7RW8cNhZ}9J>sH(AY*U{Nw}vJ_^_nVS{RTDIXZHG z@2^>d{~G}ZR30cab1lEIZdpWrmHepAM*+{|XT-#GkGzNDU9VyGOEaq*g zF`W}ez+BpvcZT7SO4L2>ZP@D(RV~AG&xKAx7>Yn>r6EZk&HRti|C)hzis`jI7R^)z)xpZeb40yui%OkE zyvgsza#esL?Q3am{Hl?^aZ(#B$(@B-BKAr1cz32%Rr2Dy(OX+peu4oR;P~AvTwI=3 zl7JW!uzJsuw;P8CE2eZD@}7fgd*Hr6^PYm~HvS^ckRL+D#sU{nikvkr44|rcvQ&$2 z{Te{we%(v_-NcI+F~KTuy^;1%N`QR6-@R?Gr%$#J6!4K%f&G!(+~Qp63XK4b{IR?`>yY&)0zdT^&G*x+ z%OtL>de=-i@BWWDl13hX%}j85{6U>)7g$V~E&TBKZNmm_WT~uM`+`Qto$N{$~2kR2jT` z3=Rm!dE;pFGPyhcVHh5AL&93F%;W8bvrfYlHIvJkkMrNh<~M-mj@FSF~xD2CaM`pNSg zHosebp=%Re!2=--PFYgYBzj{?DliLz!ddKDd-UIHZG?BW5Usff37MCWlw1qT4qP-d zKa(AxI_xAMW{v}O|{~*lc;0kVCJt z+hPF03s76_NpCF&e6eSqk5rhmkH{z&Ro70}e++1$5(Ej@j(lex4iVVE@1rf`JN0)bc z@jRLiTX5BD|9oKh(*Ako>io~SK}GC~9@(eaL|I>t-kf)6j4e@#ywL_j0Yy@3Uij79M$6iuE0Brb*m^&_4! z@Vd|O%(X-*INZXwE)hB%--0Ojc(zuRH&U$83kA}o%>oPGT&svEfw;7OjtGvghFE#K z9Cp}H=0ea8bETi^m3r1`2-k<+1i;~_ zlUG!kh=0x#z-Be%%Y#u!;?sg+KuxJuxqGXUYhL8i#8>&Ai^hf7=*6D(-_Rso8Pxk1 z)e&W&4)O>Te;T>>>Ri2OXOL2xfh9Fp;dgFa*$P>|Z>Dgb39phK)inE{%UHBOa15JJ z4)}^r0`%pTeCgDi(t?S{hmh0Y`LV}c6I9k0RU-Ds3;a%wCvhjh}bFBl_OJ0rY4+xeGIg>}X z(_HEfFxHES8mT;PsP&&|VVQH=L&fH&#^Cgg%s}HBJc7COZ;Z)!7jCs}E2pGj1&v=% zu52oYxptr3riz8>I<&Tisxj--JB)c4mb4JF5NNqpROMx<;nNJS!j!NHn|{)Q7*T`G z=ZieuUtg=M2WM2a*!kfv<@Tp%Gy&7Au`GeIQWVi#^?t1h5rg76`ASLDwo?1c4xbRV zhB~lK4n1$U^Pl3x+Fcvs#99Q~aEUhLk(9XK=hMC0MUL$to1Vt*8_nzDTpfuT45Nin zhqB7KvEJt*agZOdW5Weiv1t_lMNBeT00EO%IKr5wlEU*jwc%{HH{~wik za$9H3UmAw%@zJWB++ zbXuSroo}V2=PQ-O0Q~Lm-jvsOG1xX|+s3k#)xVN`O{Zs%ZmnJu9^fOsI$6Auz!I^= zW?qGnfI=+va;?#+3N@bi1snvw>J=cGA{^kY+FZVkS|v_;A`D!#Aju9wtjeQoRRdX$+JQ$^Z+Xi-DCmns3&EDu-S`sAY4D?B>)+U4>BW|Xl zC)Cz$Y#%y7pD93K1il=cWJuEjU@n){Yms-42dz4vDYQM8uO%3GP+o>A;L~9Gzw$SX zebT=bGi*Nk>Ba0ss;#mX&t(l!OtaYP4yEk@yJjLUxo3sYYKlw9PcHp=mfOx#nU8pp zE+wY3iJmqkiC9Wr`CA`LX+tKc1e()w+)1nYws2@>SSv7M8o--Ex1T@tmpE}(S5;M& z3AUp@+tWaKQdPyR@^Jd-!;n{VV>WSj?fuX`<0^fjo0XofQN9^XDFT`5z7^`pJpK&w zXN%8K_KPj}^XDO^NTY~K9`cx7D+RU_m6%~rPA{_8DZ^^6E}VdkDKDu&kq!Kxy}fl^ zz|qZ3JGrvecvK(PiyT8P1eBb#8jW0fS$H;AcHw~^h{ESJgd(2h{Cz(Yr@`U)RyRSE zjBNF}rx5z@Hkdm4wuFmIDP*=H&LK{H8fTrvk(|WOs!v3P4dyEGHaR~pslN=a@4*s~ zTLu!`V;-AE|B;J$<^QfL^BW&ol)2Iv*|)f~5`27DR*EEA5+St~%uYbiYTg zIb(Q-`R5-RI>mMQ9x61|UXsc{TR-kb0Jd3y`^RwmQI}fBA_sOGzS58@bm`ZD))*BU zYDjCuSNMWEd%v3l44aP$_8yFf+#7ItF+lB!ytzBHiZZQEV7Tgux=vw|FQ5 z{I)+;{FtLr(FOgqg}R=qbgwKIbc%h~dBepbptb?mwI`z21i#D#bVF!^L4v;WKPgDG z9{(=;uGcNpNL3iUeN!9k`4ProK~BruvJkT|z| zbdL8UD@$Jenyb%IxfNXg?X(1$5_WEWLfXIwB7e4YJHscz`Lq_oZbAyA@(3;Qio^Nq zyHJ>U<=hoB=JT|zru_WEpdmDEsq~}c)RUlC2T_0MND(!c~cwU?mk51i8{r9z*bY=Kd;Ey+%b|4Yb}) zk2wL}v%Ig5^_zAk0Kx&iD1dp&AVAM?aOBplP*#2zQCO+JD)t+pFxi&>;Jd(uxQLgh zE$N|K3QY{v4Z9LF-53}JySN7zCSp2V*LukGdq5YPw0Utc@N*;qkx>ymcd>&dLx@t>U)awRiNi@Y_&74Mg3bNQIhHN zzAeE+#^D7Bb5ioy-Zfe+DBI_y-We+S`cIx&m1&X4`t2r9BkUh!uRO`3?uR0I4Np13tc;_;N~yxxPL2%(N^U_cHLuBp*jtUbgG9h2YOkHFS^+96k( zYx1`*VE<^P>5GNiC9c2yLh{bx(`|YhdAN;KBBnN-sZarCqLAppC5CU#z`G|Umm7y( zwp3p6^rFB4|M70x9~_AGiwxvE{CnLFyR_$wlQTvdU4>p6O#>?Wy~=_-@MaEH*}FqM@h0ce$^KzkSr--e&C!=aIZRWF~kS8sPkz|sa}llHK(_?R;{%( zB=TMW-+?ej;VKnH#RlrvoKPZh<+qk81wMbjT4!8s0O-9fjr{c|i96kY z7=ICu+Tm#F9as~%4m%RXlW8;+&wod0fJj7}1O3wAF}fq0=A?weCEdo5Z-}_RKTO;W zx3BUe6Mo=dg-Iy*MkuSjUO@mEk2Zgh#a%RufWRk#z#Tu_c(XR=T@B? zJiPZFd)RZx6@cO3{-D1N^rW&1{;Z$Js}MD^X9X%?4Q^q3ekQog6~DzBBIym#}~ZzsVZRT58ZR3DKYLhO4{C{GEjl>kDnOd9P%t z9A=@3C{23clSnM02<8y*YS(`gcqvFd5PFszp=Ib6>i}d6N3uLv~e6Rqf$kcL@!}BN{rKo)PQv&H?K5r z(^5DnR-&ne6ilsBU$UX_r4GQrFd~H_D}mgE21PG2tV6m<820s#*^z&KdLf?VpDGIacKc;D>qmCYBDOSrGl5eLP1Fo;IqescbbFwF^_V0kf#YCMsnG62C~5>kW5|Ft-Jc_4LIF_heI{9`A`5#&=eTNo-9MX zo(t6k%TS+XtXcDtMHK|YfNrxO(l4{_d{(WV#iG79ot!iuNd zpQ<^a-?+aXlZ8=lR|m18agg-jVTZ#n$K{irSiuMO@E3TX`5(Z1B;;NWX5B;PJZ#6= z`9}v5H)GK&%TDq%WKbZ<-P(o&qna)u&p(5=NxXE+JnmzmjI9&d=tkPoQYD3kpEVU<=r~nOc+?MUfH;k~2 zh{=%2)wcfls*KOhA{X`|RRh{h01vOc8U4QUFQFndemA=mk8+EY4xr7qRkVm2r`~@Z zlP#Wsh%mP93J)OFpdT19od*mke&uK#;YZ0-cpgA-q?i-b(8b0QndzjZ=h4yY-x6e` z3=QQgI9U%!i^L-O`{h<;?l0LZ*8$__;0 z&r<((uihIGYVifnE4!oW(Yui)zD(N2Lc3TK$PuReg{PwDxTd8nQGhTIvTf1QN){ZC z#w<<=#TRl-@$z#$ZfWzIwwq-BdHRl7zJ`I-G*H~HI21zRRvM2UInPRDT0F}_-ZK*& zK;)kuAKX3cwoQk(V`Au<7m|I9D`N-Zn~Wll$vo-&5&v^L5*@~2M{yld>9UlX(*u_Y zPu1s2dOuFWA;Gk1!vzz&fG9Cj*hT(0;w>p~l+Mnqu{%#bAI|jx9j+wkm+Y17{LU#8 zV0pNsquTx1VxC$t@EDt}6jd~z{xBUaZ~wa#NLCsiETE)ri}N?k7HwynLh|wF&sAs7 z{l(^SYlqK0H;sQvY_ElU zQ%~sr{rhrkjBDG7p65-Q)_Upgd%6J?Da@c60^`9mv%T1{FM6kPEQyv02Ba%OJ-DBJ zG2Cf0jz-M$UkOf@+;I478AJFae--~4_jSXj#PKv=@@>7X5Oxr%a_;4Mv4jD1_hx5d zwli9G9q^>e(#U;(@DpKd7AY%c)5OZyR9PmzRQa8=M#qT~2QnTQm|Fvh0X$>fZ<9`9 zqDMd?oZM75D9=l1CaETLx16WOk26zjO<*r_9pAgVKC>dE#qZX7GhLU;Y~;ybcKKch z?&tu2T=+6w=5yeEIGbvxL3>AWh(qjq7JKlHVJ(CGvh`VpmbGX~{uBQf8K+Lb3Fm5e@qVjeW`h6z z_%A|9w4uNIKP|x90J95SJh}dded`xjiOX~YAf|hZ!NJTyNlZ9%sd9!eQ5D^982dp* zuv$r!R(gT1Vy#1MI58L>2vL>o25nNVIbc*3JfDM^%G$c(57I0WY@2eDUM>QS(;K8R ztdvt?gCIYVq}#&yZ`bKmPmr1C@4LicB9l{)BM#ErIL1r|W|gn@-Yz76TSRr=AL=En z7lLN$?Zl|5XZ*`tM!I5v*ZUnv8@7}c%t;{*$0=m*^z00PkgIessRzY*pq%0%a}LvA zu6>ju&>X!m+$RHVIu-z=CCPB-& zJT>`nf0unvux9X@WkSbdBa4y;ur;1>^gRMeW0sr8P?I?fk9_^1mR&ywi9jH##&g`>gHg z$sRcFjCw%2_I1x1unZ-Au<>eMDZO2O*GGPo3-SuKN!pF!ukir~N4CP;?oIW`Zm3$D_ob6*c>SbPcy{x4`s;^Zf&-zRbU;23_Di0WAueqAHJI+U#>S#y+5>IG9w@y0{q1yy`4N6%cv!C^j_*#=&v&F z&lP=0ZgdR3d6E?6L~WNUYQl= zDEUe;H~P<5%YBSm2HrSOILH0cFDlc<*3f|--U?IClJd^O!uKRp*fkrsn>r@6D7Bla zZ`aCbN7%;Niw8n$Wy#QMNzPuJAin;YFJm)MfVluBg4x-$Odb{Hxg@CrOu|VayLzQz zGW0yT5L98^CTBS^?R9HEU>n)f2Ic@QfzQUqQj4D&CxrN*7YY^x;~yIvqEAH_efl|N z{E5mZIMXs85UpMkiutJ{U`+N`#9mazBjF=H9mFFcLdTnTn6x}WL*1V0Z;Ags^O>Jg zzUJned&q9LWj)`=`^~H6dizCq0OE854g<}6znWR*^&Q&Z2Lq3NEIy0}J1*<9>d_O} z36bx48W79Ps{ZA=1~>r5?UPX@6Kblu)gGoexPjx_znJAIAI${9C3*)CR>b`rrddCK z8)xq#SrHu~3uOD+wAucC7v;lJ>-W*e>dj4ZeNFbjjIVz(E?uu$uPqgomCX}2$B=yq zGK61q7P)8;Ie$znEk$U>PAya1J$Lw;FSq~xb^pxugZ$3`kma5U)ZFCrgz4Ekzp&D* z+6(#&7GYeJf{Fa@y=FBb-Tc8}*Ki?FSmdZ4m7Fkj{hyzzFrl zRiW?abM*1*=A|7;GnX;@)Pkai{nvTqI|L*7e>Zr0we*DJHSw-=hwY_^%{^YaRJP|z z^38os+J{@|u4&S0Dy{cn&3~^yuDw>y;A1xK{VvN#rldf)wU9R!pC<)F{se;ftD(Jsti4ngZle%sbL; znPU}B)^elr;g@$_r&auu8`{K*yPy{Uq@7m{4sz+rd?BIcxl6?vDS+xX4^Kq*Onl<0 zzXRh%5naAU#VY2tLzM#i#z#UhMZLMC6H%ksa9-Pds5IC08?1ak!0ruW&Uut}lMCSe;L zHx6M{M$lg6&Sa0aV|I|=;?sGa3AUsN%HMm=jrdnQjK#mJsM&k`&}^?s^#gQq@Oe+; z(e~o6-H%!Lqo}F^s(OJonjTWR_@gGK9f9Nb7|L|&4c(1WD3!}#bn@0`b~g$Pen`=` znp0NHmy0RKekTFTetBaJ+G1)}z1ndY+05_yEEA-KGjJKtZNZ|8>ilUqGd#$O1dAHx zi(V!}qqDC#X#zIMp65G-`%|>P5?^M+>GE?bn>OI)q-iDx3#V24BGAOffMfG!JcezF zgA@<);AEtyya0&|wO&Rz4p~pQ?X;lsreW(j!QqiPHa6RCAw?Z`8-x87@s<$)<6yuw z#QSo?{88OZ1BSfjDLMWi66;;2aKq?gE)U|?zMGDC3x(USI-^;8R<4nr70ZlXaAKIa z@J>DKj~h%2x?k!_%q@M}+~n-R0>?mn7gIR=XnL^+!(UoX;nF+TFh2>wZ6$c8kv#+y z8OQ32Kbr<7z$h5snVj;7ymP=uA;8D`ds=4;xJ`_ja{Im>!UwOd;>u^BN_J*=KlHNA z<;ri4j2vejdEtO=^t<}%zp*Zord^{AwfKl+6$YKFHiZFH$2Mu&c1xlIvjDK#aU*+5 ziU5q;t9g378`q)6I%$$+W19yLX(|t$B;)1;q-f!|tj=xwshEQ*GQ zcfA!}8(+Sy;>omK;DBcRZieb^g$!h2==nZ}hXRg`vyKHcsWB7={fHcS8qc!jTsHAP z@br-maqIuC@_X~;>Fd6cd@o4}o|_ikjxN@R@?{iBHz@Dm%p0?+NmQgCb0$}oqXO!o zPW{f!g{{}+%P4s~Y&IHDG7pampj6xy9HEl%MHNM1Vf?r(D*I$}ZPbJN z!jY?{f`zG6YE7F!P?*;g7k5P5eT8b$QbQ3~1~742Q4qK%5rQ$s9I#yoeR)%--y=`p z6zD9hH)W72k}=pyzYl-V8O0g%=AJEORgRU<52`^m%oJy%j4;S?F5LHLuUgp4Auk=s z$XHI&P3Ss~^0xMqJuXYJUo^4_tMu)vU=*92sw)uoK>7nTi>0_F#BGqb2Ep8q`i>!l zQ9U7RB3{m9O5Bpyh;je5b}nYu3X7;q%oUyHaj2<{h{^nYj}z>IGlJSLvfXvq;(I(j zEVjlf3b+z?#^Po^Bu=l`JN(!vQP>s|=>Zz6YUpA=A`2aBS^OzoK$MBeVUVEa({G1R zA3=#@UyL87Er>DYZz$c#9P|9o-?UUp{iwkrEF~!FmQEQN=}Hr@*2`xK!(0Kp2?4u( zwv>f1#h}E!KRLeevGBJ6|8X-dbBLt(F5oHB{Yj1twZZ3L*hO%5_NZQCAcwER-q@S5 zZC&mbV@Of9AO^zm$tgl1dNA>4_m)uZK98H8JC!8js`Y(1gsP zKl_KxRLvlIpX!117|!JR#N;Ul%q4f|N|lXjPnk}pw@(jofA3t%>O_Vx`dxNBIp^v z{mgFxK}LWmu*+QbAqZBr)`dp>SGz#uP=0j%45WC=_G(n6)?!zeCub}3lNFPsglH}h zOaIA;%XJ&$lvTt$>0~HW^S_n?f7glB>#;VA(XI@Ud$>ue+BEXv|(QRdpmU)Xkgg;J* z)RME&)s79v+8^1}RdxwB9&~ehkV%IE-K^RK{rzih5GLPnJaiWYd3tW+=`JAjw)mm?lWRTyl;)#7o=u*>}Kfk$X#32_p z@aUea?wzZ)P)b07`~?1~-jdfRYD>5;z#zMnuf*X0J_s)=p6|!4s#DVIa{HCZMm`)aYl7^1y`OAC5-$6&asnx>DW zL=p+>h^JOMhNBEdL4+ET##2@3RT(j#RAdj`ydNfeHwD)E-m~{RTXPKyj0vod*_?PQ z{ln=VE1^|*`_eVK~Eh2WdFFlAY9Z>Y(s({P(avQ7LQrL=9jDgS>w zeFZ~QUDx)|B}kVj0@B@`k^@K%-Q6H5-3SVjLrV7y-637l(w%|`(v8%2@P6KJe!=W> z_E~%Fs}?>nCP9v}+SCz%(KhRJXpJ+br*GisSk_#VJW>SSiOx;+ox4t^{ESUGg*CmO zf=x2L{zVWI)ZMv&8$O)`RXmvLTxvfl=MSDfF>#H&~6 znlx!#UzQm$0g=}cFh&<^aox_o?=!w5FmRLph=)t94pGH}Y1KHeR?RBhD ziR-4fquLv6tJaX#vY3Yt0npX>X6~W1S8dUAIN~ZLN7-T>G%KoS9NsaGPLzE3PEKMmL7+tWmW~5Z?rlBFI zP3EaFh34?n?^Tm7hffcG``^*-T7U@#IHlHO29^}JW&rFJ8wO}Eys2-Q+g;zst$l$1ay4exfXf z9O7DE`V%C7I5P8gJ##q?`|#D$N04k?`VH*v`}`$^c`VtB6X&gIuv@X)@UXGMn`IiB zBEeyu@a&r9aI6ozv~I7nhFe%bQhe{l*43zo)jP0 zk9i2S>%bg9XwYVF6#dG|p;ot?=V5QAa0SqEgG>-{YdTf*fcQWF6_EABjOhnXzOF9E z7=!zrsB2C7L>aP~``au2_=?lzF6tv~07>!H5o>EUgt}>Zd>CpL*7oRW$V57P(QvT5 zF=*J9-s&^6So_h_1E6gAsU4t?%R8=VBi+JB-&OdDgas%!?=TB%Pr2dJE)X2EbXqIJ zv7Y+=F28`L*BT<;(t|yn%_03U92!!JQFt>*cG@!nnv+Eq*qbD}Gn$bFC=f*fYEd@X zCAJvpkVKlVacjgJLE>vjqx0hW!;_$M5TnXau z_zB1f-A3M2_v{W%WA{}E3Oi@&7ln1(AIXFzzW1qLfth2q1OfbLcYCF^uq#<<(1vO2 zhKfeOYKFY`73}owDY)8YcapX=0SIvBQ|uh7wS@3x#QcKc&YOz9)}(D3pMR{ap$6o+ zU${LBa?~hXwJTT0c6J0B`JCS|bTo$vJIoYJ?!DdtAsRroo9He6Fdn?IFdZ!klkAaC zvl0$HsMQwBJ^#{`ot#cvrrVubnqcEmI8pX8Oj}QGmwE@(+X2mYOp&z|&d(-=A8Dql zLSI-@>d;KWEJlj)_y5c-B(u)f$OKU1>%PW#_VJ4@@3knZS~R2Mjeqj?YKl>VBWXl& z^(THkT7kfayAx?M`x6ra!zDXA*$K|~{~>+{Y)S8mfnUa=7aw5q8U?;FV3az0R248q zk+)B7v6kO&YefMt6Lk8lU=l-A1khYEs&&VnlSll343NFBawups^f}pcSl?fur~iw^}+f%eS*Haatg-4?Kb0 zh5}3s(h3D?28+4Aa&7D+GF5E@wu!%`BKg3(?OMOalG9#1$SHw+#9kVsa%XYrxOMh< zD>p^eb9 zUrHr(f_7BUbzMby=O!j<>%y!`kO?ER{?LBr93XAg@q1k^TQ{_^Iz4UF=%%A1!L@J= z@FjYi{uD`=NH6DpM7N(=2VOdVf2*v>eQ9u2#u2kzgDExv%l6GDIITMnJlb*HAr%If z=ED<`get(9*d@$1=+e2y*Hw_v+R(GZR7}u}f}6tO_St;|rwOV4GxPW}>GuNP7Iyic zK`^(-euj(w!J`FzDXXFhx4znT1QE+6xPh|A7XoWXN{>RuSE}MfAORaqHUoAQrPww< zK~-#DhO-i|v?_znxt$11c=h_wNK!hqfZIhE?E(IBgin2C17RZ`z*pK8f6F0zvz31oZ39ShZPWwhSdK z-?s2f(SoVku$2X#h}$@=bpWY4m`qZ{QiL;I7F8e6M6IAYur zzqEmxTy}+)uC9*0;A=vAakr?YVeS_jlocL4NOztIFvX8^T)Rv>rsEzn5Xf}Rp8LBP zt^3KeJh!YDUg947qMaP(plJn()Y<@DQ|90_C7_kE3UzOA#RQ3$D!FLN_cu6>X(U5m z7krG1zVp+VRQOJ8S?pRX@x3_0FCG_*=+bI0+ML>qC?K4#6VWSH6H0*)L=owtvuPUQ zhN+5!R3(7+17-5TkD2JviZ3))9{;+{I^xml>Xuj~(z5GOju)qu6`qL;Lgv6gFhOED zch1_mvn;%B$vqY@4YN{c4q_iHv2CB9MK!541?7aflQiso@D&bnxDlVCs)$g=`69#0 z`1$^WR#)~}B-v>-8B7(l4* zY@1Ui(BfTh`0j_Q)V`S!;}N6uKkrHB)vZLZQ!weV>jnCR?{7N`6;rlyF|YsO+8>q| z$GI+}9EIxKvi{`A6i*}eOUz)g5D9RXIMc3B5mQ=?hBsu zR2X0{T`di-+Pyag;~e-8`anLzN7Re`;?1d}0)fKZPTq=$-K3YOO0*xI7oUi)O4jD7ClPrPkbcGbL*Jf)=olv9 zpbiAQDC_QT-MK)Y!?aG~4Hg|w`)DRV+mGOzn-=pvxNF$q;k$%j#a5N%pSsvCr)iW{ z;dRz-difc7OM(&@0pp*FUU<}vw8RQ$@>-yHMYjZqJ51nyt`9vU!*|x(z1^QVs5y&J zbwX&7SAw;FU(Kfi>G!WY0rMjwBdtOksGBVv6ge-r(vi1*;HrdPbrd~4S2tm(-k!2C zy4o%|L82oW5+A4l=uY-vnrgJ1{W|pP3)ygJz_(>7Iw4!WX2L8-6X6<;(xm)FLbe0q+jOq`TC)w#~II7TR2d9@Z zg(vhzRAK1e=W*b4Zo)g1jzy;^0L8Wh)??<{Q9eeL+6QCwP6Sk!$42#hTS%|qpPRQ= zNS4wu%_vK3VIL$vY;tAM;ku+_sccbhdVl5=IrNhBmm~g69}`0sZ_jC4*zaey-+V}S z*)4%P+2dW&_EJ$%qu;*qR;%)Rfb+dL=-B6KW8;OfN1$SUu9Nq;*@$WXyYwQ+Hh>Q@ zVi-K0+ZM$|*mv6ND;pk*u43GcMBbX#szS`6!{tdWPM;G0PrQRolo8!#N%T#qOwlrk zRtAz>O@fYhG*x1$pjXgc+v=jS!Hi5$O1SDrAmL=kPSl5pkI~OgDM3Q61vT03 z?EUX>Lb4#f0s2cvA0zW*K3$Vz*#~)#sky!@vLym9vdt7XF*4SI+fA@H#WZ}s)+;tw znJk5yZ9pJPGhCD4n46rMtUsbjuwABLhG)^tR|JL!f5U0UY1Xb z%C`au;Gnv0ZpHL@jieQFc;;1sgTrUTx4`X~hh~(tN@^w=LdT8tY&akCYk#2@_#%JG z+sr@^N-VNZ_NxxRXx-G8x^j2l&;c1H+Z5shI$HzoXP3{nf|Kjv+m8;gGPB%aZJSOp%iV zXWxDK{*};x=am7&hy#qb0D|pP(Hg~X<dWYy7Tv|)0)80y+dmcg&b6>amihGJ!~D`FJz3L?dQZ^kuQn~3DJqGApp{Y zyFT^+qgUlzS($yn9JX0>=b_%-FcIW}DO+y_3OPnm8`8(UdKBB`D6IgaeA@rh0$7sW z9^hJU{){GTz@FOYk4C1NobIZ8VL!@|sF2%e)~JoG4l1b`uldUm!~c_*1_3J%!1v=! z-!MQgsjV?vzkByLta#n{FgP|g8}6x}vlV*%%)%FlsTLAE+JYN58LKLQ={n=13a^M6 zvxxXUTl-q6Fl#G@Tr~`UjqliSKxava-$|UCSt6I{g`68o6x?w?i-Wg_i5I$IB{6tA z?+UkHv1WTDA#xaYG)u}??(k+je;I_Z6-2Rvr*|VS*O#WHZPsm2{Y@1N4 z`8&P=+Ubez;t;~X+qODv?mqA{5|z+~`T=BO+owLGC`5@~Kw&Ao$J%u~RSHVkT3Dri zT~gSBY!mRxetwc_Q|KFs(b@99jvP@5O33UjU@y2SkayDlP|qXx>P@N zu87W|VZR-j?CVK!d=a6BWPWjy{jl5Oe_PP?%L6A}Cyt%uUUgLdEi?-{e12X$HI@BJ z=p0O~X4_K=Z2RPocHzd>)k5v;z`Ts=CMG$}sE-}D>C4_HK$m>w*36LyKCW>@O0`td zbjA?E&|Md);OaCvUD!_qrWqV(mcOB%hl`o8n?qPZ=Whz+7wyvT!?iyR{-)k>i+;&! zv}Kf;IP*Cn53}>$uO0T1c^RF1+lKL^{uTuy#ig-PKTQBu`=O7++-W|i|4rwEXM{RP zC6gX=+K|asFO^)Wx5q`zFAnZmT4XCk9jQqr%3Lh>s)QP;ufr|q#et{4rs#{oD`M0o zfh#}BZ^$ao>}2~JxEl@_%fGI<%=3H%PFhA)SBmF-4~!J>03nnt9l zzKdwfDRLQ@9>c?+1#6G+$wsLHJzm*iW!@e(@dDkaDI+BzagD+A@*vTDoi;8kwa9qaV znDM?ZX?deaa&OzG0UMs&oCFUl%)he3qQBP%-3~a!?az#--~tei7tb7!djJ=b*A3jHNgM z?Q4@`KkPJamTTB5HmxA8!Dcb=5}!#$J~!}^gH!Yaw~q%;HWHN`)is`oqV}*Eh)r`4 zGzUC7XCJk5t4@Mp=sgU}PinU#s@G|LXrtxTgAfmp5lmrCFb>{phDV0L%BDv#;|2)G2^p;x*bCkuQE( zr-)-p26kVucH^Dv&o^_+nET!`9o&RbcJlD=VReR+2KFhI2lXs!NE@%N>I{$5bs{VP zjEja4^_R7kk+!@E8=H68=q>UD`{)4^ zqk^+z@B#ae$9`(PH}__h_VdKSu)s?uPm!gXzZ=sap~(KNNs|>u-FuSPFp(5>VrHZ< zVkrgx=$?A6oZEN%h*aI8qO_;<)Z}AE54|~gYd1-fGF>a)+i#1Xz{{Ba#K{KcI9JCx zmkkuWGOf1?@PrXAy8A5ui0ZiUk9CGn+;R?%t1YyiKM_Y|%zA_Gj)!Zl%TSGoRe|cf zJU8n(UYzE@8x8$r-I_rxKWLLjW!#CDKQuNw?~z9a4-fa=`J+TfgORW23XC}ar-A0> zi-N(2tZD(VLUu`rHreYSn+iK)s=E5`%`~sY;8)GM)IjfaJA#|v=4xFDVkw#`88H&A zI*8TMdNuEPOg+SuHC41A)P|R(uE3$Ab3M-a{&NM%xZ8s*8~=cy)VYld;vNRrH(0Fy zrOY;+9{~e~b@qF`*v|ngDhx!~*>b2v_kA8e>7S@}n>~4`LyE?Tz-GFlJAz>t3r|$t z(7a~|?v-daGSz*A+HB<;j|t3JhG)+xYljS*Kqkj0l!$?IoLcuc!kt}#F1P%~Sr2P= zKfchg6=eM}yFU+#SslH3-@kgcmTA^iyE0mBK49nV2)D%@Y8neui7W2cD*zj`UY-Ep zTTL?7voBgR^PAq6h46(Vm(5-bZ}cbnNu=O)eQCmRw3Y%*Kp7hfI_OxFskU#}l;<_1 zMw{W>r}Bppbee~0tR~tCoQ&{SftD8+=P?a@y{5I#iuLt&h7Xm+_;+fl7`RVL@6g{t z(0b|ANe59urg<)gfQm8rx7MKzqYd{HuuHByjJM*s?FtH5squV)ig{D!k<>jiBZlC> zJF2_nS)|09ML)jSpou>(XRF%+lalH$JLMi1CV4LQ(9QsRto8!tr;Rc5u`?tD7c{ zYqjxa$&yNzjly}rzO44ioL)-1S&qW>Cmw+`BK1WXg8h>>->yZ&(_HHanNnw>8iCN1 z0oi6qQW&4cKPtwC`dGi2!nJva+r{#9w#S>lDoVXW*zNGkuRUyeYuPspUPg7D&8?_X zRWm$CjLJzcxx;Q0J|R1t=O1@F4smD^eg|CkWNlx8Mi8gM01%na&ZWIyKy*%~1Lyr8 zZGdGl)_W~$PWwJdJ=YRwA7ydf9e*jjte3}5&3bV6`8x$rj*PZtA^8xGuBkU#tvfzp z$qbCNCUx0*N5RL1f`;PZac%X}BU5jpi9U+Q=3q@cRO z*tNA6cF_GiL@|EAj%W};Ir-NgcAReRU`+Lk<{Km=u4Xo?g5q|T^>(&As9Qn}gLFh$ z%F`tv?o1`US0^g#Pb&++=oP#IhdS>8z;jR>x?)PiK<%3<%eqjyH`eCxb3<{0NMNOIJm9vX|0~6|7j#Rf!c=NY3|1Kkp;Twqx2A<;n zLQ<+2y@zAbf6JYY2HA#(G)n0&9X2%V8aM^euK&^_lh<$>C%ZQ9FChB~IM0$(@VY(w zB8^RRTJcq-(i!+NtML#u+V1NSFzdu)P8Lwg6aRtVU zMkg%=8gA23J!#dN*WBB3f9GrJ!Il}aN(7C*&GJYG;JLTRm zAMn$*@E^O> zCKXPW;Ld@<*`tWxExE=tnoAi$&9&B7!1h$e6u9a8Y<+vSPV1@))(nr=Sm>^}jy$`K zMv!mR)yfzUEB$u_$!f5J!OS3}B0&=%k=EDK5=8>i25miSH0kBB=W|YqGt)W*cMec# zIsPqBh=w-Vw0x_fzL)vOk_3^7bb5cg2-0VOw!mftVsdSHsP~vurWSnQiazA<2mn|T zsdcVa{C#rreg*=V9R?xLvIh;BC%IEPTs8iFo2sX>?Lj6tn0_&wjKWrwuTuV7ReOH zEbXx5&n!DX?tOTMw4;15UR*Q^3M zxoxhvfVMwgJ~Hsgammwqswiwq`wvvR7Yp%JcP#R4Son<)#x8TxgZF9bnOrn02cI&d z-&PWb#+T%f*tDmf3#di5LV!{lFiY*RT7!Xb3ShfVDz#he9KonDkrX#?UW_4XGpqpA z7k>u)W29D8#$Q0bmlc?jlW~TLq@~-B$VQ4{r%IPG+V2Y-sXAMVe{1B6r|cL@Z%yqv zUivh5_DlNPn@N?y+5vFTm7o^VdrKC3cf+^lJ;J-aQwHA<8VUVCvf z`-rie>D{`x(~N$}ls)=awEk@4EpP@`+a`)2cZz4v1YUClU8rPx8n&W#23(dEA0yrl z5`Y|hS~%8~t4j0`vH$^Ib%t3s%YMtE(vz+Y(Ef)ev6ctTx6J^S0(AuwmyzPj5iUOJ zSZ{7DC4!oi>Y0mp@@J-~nOL;-q}(5d2VPVyu5%lvfD!vh-UBoZdD&cKVdOi>U%p=U*P2@qG87jarTK-!dMG8Mza0K{|4OO&huZ`u}FO;<* zCXSINl@y+0e!r#R6o-yWbTLi4#yX&?hux{w8*k9cg2TjAX6E=K3P|S#KVs)t=4Ni| zs*4BUMSZXyPx$T3bk<_L`a`d6vpDk=@^^Xx9yn zBz(>R&nz&BBJ-42KD;-8)5co;?^C2@)Ye0Y9M%UoC80}$%C8w=`|IB(qM?MqVdZoa zl=bHXwd@Yy&%Rj;lPlZP7|*ACwl;Tm6ncSBKSV+_{684lKQ{pZ6q+_%0#fMcdvJp4>rky z!>p)n3f*yfvUGbxY>@S*Vto3%sLvl15$WmZ3Mgkfsw66n>c_G?7VqW5@F0k{ResmC zV>(?EOf!&!T9*1XPd!0o#getWsEAsQwcv(^_*ik&xDV&wy*-nw8$Oe$>Db5OU?Xt& z_-2y)s9~o^YxmjA!Z%UguA*(18k~t%N}MAjX&lzcj1y}b8L)P z@e!iV2Rc4rh`e~FS39wY_i69_aqYO6oA~s9g`<>Y0$Aqp(=u0->((|BWx2GnfU~$+ zbS{>=;V+xEtOTf=;DACei_{&8qr=OU#lq6*j9GOdUaaWDJ; z80CGNTXYe}ew3ekC?sSu^ZLV3FFI|o6Cld}A-3}qHl3)!@u~u*NtRPb`1;!r$a&{1 zs}V~R@sLQGE@d#uL6&WT8?eL#R|fvzWD!RI3DmgDy@FwMS%C|U(^^?v*_vS-7DsDn z$Jd7|3*DNsKCxxy1E9#+BlCs*hH#s8WR z5LBKy>1X-S!JVO8_f=1u)UHu~O_-+d;1LKBka&0uBcacqPLNluS+kgsB&aTF14L^p zrJdgM8%%NXtald5C}lvbnW%3ZKO#&?I_+o-=%%i_Uz()3&Ug!2kli|FzfGmY13-2~ zgzn;JKaNZ=B}A|J(9O96kGsA%ZmF#U4hlf8!4%scV^KuykQdPNTch1x%e&*vFH)rA zR8Dd3ZH2>qUC{kgSDZKrPeM#}Ys+zV!3~<2a&!CHe+w!q?qeJkRF7iQwBt2a#4l@6 zb!dGvgJRfI@?SraD`kt4(&*FEaIg0oC=o@6%{V3vCS?_>dL-r$E!SM83^wU=BH0vM{L5&LST#dGw&rUo#nCA}z5NJd1i z8m|!<1{KDG$muojhC&0sy|^Ce>xYq7z+AbvqdvmT9J($76s%wgqhdCsNXgJQ7U}AZ zg|1D4yhNti6qJ-+;z?ZnlcHbi-M&ooM*mmPL`n_x5U#UKOZ;t7vNAhfAv)a9j1Q&v)N{2SKIZLMCMoo5jS$9st4T z!EW6&{`UhI^=GCe%JNf@7$A!vVPFl_0&VB4Gc>KSLrug;VVJ4--h1B)Y-xY;qWb#{ zcfXjCZt1d;0=ing4JmhL^xYN{!db2fIDi4s1ndv`U!8mLl3kYqy>-#c(f23V-!n|8|R=;)wTtQ^uB8E_bb#Rh9Bo<2kVJ`8) z6m5s$+#vc_v7K$va%AUpjw$dJ>^*!HcsixC=xe`^5KKDC2{xi5H_xSIgYX&3wiYX-&RrnshV4d$)Odq<|f+Rt4|6iXD1}( z(%a5SM*e$Y5Q|$SG%yc8)$tBfFtJHb5%Bo0Gy#@n(YcgLmZhG{$6#^6^O;Ad_1kfF zyy91)>Hfzc!0i4(242RUY+MIKVR*~J3-F-2{jyutKEShadVN<8bzRCH23I-ow2{mHHc9zckHj>o z%kQG0i#M&sYQ7aIeaccevp;m8M1WXW|J8%&9Qs$`f$>7skdMBF901EiyNzrm;+Ag;8 zmVb>@6ifMP{yB(hPiP&0VcSLL3SDEq`>DS*hdBK^-b8&XZZC$Pj}wE{ekHYo8*=ge z2^LmzlG-tfF19lL;&q??EF{uqFT7aA9gMi(T(vyscIh(lerJ02Po=*{2D*;F`!?7> zUBUwb2s|&`!%HlKV)}8$J_?A-F%ohU4d1XovrJ=zx~5n@3yst;e6z(+*p-L*9{GNj z<$WpJ%iV;?oEFr-Xp5KxlGRp)uM-CajIn^qw(|U97xJ{bW0ZJo0b2QU5hE+f?}eLI zJf8|->Gntel(@ENON`PzsbD;yURH0*H4&X{o?&Ga6-GBjWdfD(PEck?x0Mw9%RuU=lL-Ly9?YEW-Ui6fJ0$1gEA zd($6&gG|(phySGz(FM>JI!dV#xlmdyI3+bFg)wC?4P?@**UH!%SV7+iY_hH3eu8h5 zEXB_}gY?g!D%{MViedq6zI~d_B-oIx>b*~e{=gTqtD`A1c5{c-eSgt>6UWv4fF|T+ zMARVKs}d3|MlXWSL&cP6X|rF)8|dO@sPlT?{%WCdw0JoeX=HuBkdIZIz-|g;S!!^! zouZpND^#ObOiz|=*OC(H2Y(E@>gC4)+J2ii_*b6@)Gbc{=jqNT73S<# z*KKwjO3zr$cSm<3L(`CS;{IoD7K|yoySBD$3`}ER)1)QHt2i0SBsCQZ)t`(2a`y76 z!$IeBlO2KASKDggjbeVxP_RO7^Y?;|m!@+xB z?|N-j$iLNl*jr#_A^#;IZctJ2VrP@O8APOli9E_aHBe0$+ys%Cz_a^7Tr*^YMJ7zk z-bHQ9Ce!5bzGPv?3w8eHcw@G;-RqPOiQT#uNTX`aP5oTlss8>IJusxp+ET{9us>#g z5$aH=WWD3ZwYz!>0-lr3;P|vn2&cVgo^qkON1DQPeEQ21nz)th`|^%6{nL`?rQ%=C zVl+?|0LK??4D!0S6MRcHSVHI&m1blbmW-(St5HtYhB1jtqn_%L-wdLO;xyQC`ibHx zo&vZol?a`u0wUS7R&>uX^d4G?_(H;x}xk27} z7MAW*aR5&cFWsy_o7z; zQ=@;2RbDvuvz3VG(U$ZlYqJlLXSXPRbuCr4sUx>BtdC&O*39)wA&j;@*hu!ZbdSdO zLR}uAPn`Jj4fw|m#Ia?8e>LxzM>I#jWT-Pzl8-BumN+BlWg&*rGyIqdOs|)wt)-l1 zf5>@ir<7@>ETv-n%Y#XtvO-cIFLThUjRqOeq#jbq4^wYAR?Jq^xAk#3d z%zF9rHO$H$k#W;(S=N0ooyUFMqvfyHn8PL^iWy(7>gvi>t zv0@cDv3tUxZ%zimC}UIk`OjNhs%k=@L^r!!QGU$%EYdybj@abM;nsPU2DZ~E*bo41 zp?-dI3`{ByYy_uW=98}1`Geij>Nt^? zP$kDN4chMUI9i`zKRSYg47Uoa%NIpO$w5j1;w%5B1;E0>YVsVtz&HL{IC9@)L;7)X zahb+n!s`8mDB?O!;Soy33G0U`o@~NO5<%~iyxUy*rw>(2efF@FcA^EA774@>ovm2| zVRJ#ok18EmWTPfIHpjqI*?aW5*G;<5_VEcW?GV2R?HO7Oc_g4*)5WJ) zp$y&)C0NGtZwiCeIp^6Qp3aLD@!!1rS^y8U9+2X4_D1LDcq_VWD$ z1Axl(xxXpK>pFbQpP{&V7|?Uc^u1jANYL`M(cPRmEUrd z2dK%Oha-NMX}+a}U&h5=pxz}#FRdqiUi<2o`@!~gV)e*rjc)<|Gk{apX1G|vr2_0V zBRs&3s5ygwdnfO-vtfty52Kcv+|trG(c?i+G*wtd%lQ15nITaGz)QW92Mom*VFec) zQbqh{f{8L(rmrNn&)pr zDS0#1SVj@qYpw=^w#Daf7)IyE**#G!jWUgN@oG=VbM!Ju(@=^q7W!{ks7~E-$vBn6 zvfv--GshJX;IF`dMqu$2O`t>Pfjuy3(k*&0zfVa;Me!mC$iAz*#3?NmwE{9A_ulvB zev9`i0xk`JPyie{DnqJfxy)H6URCtyF66;d*upeJEAvx%3i?yG-CQ|ZyVSkz-F2B2yWR1#IwIIRv}}6 z9C}7Z1b$|WFmngUG<=NX*jQz}|LCLM3~_soWs6rD&G8o9QUC%VfhN{?9ac0TT44IZ z0z*Wc!-MKuN#0`^qCo7~UG@h*zK6rddoOytakBTtrdvjdG3_3*o=+0$%TvP8h>cQt zCh_Nj!H|po$RFyFc10rIEYEo;vz(;|mw3Gx4(#o3^@Bg&^pim1hwpn2egMJYE55jI zVE?+~i89`>fb`VVph+P;S|~VE#G4D4%gmL=yIqc0FhgEGtES+(9=g9Hdh4_dG^J>A+sW$A{?}Rt9gpvNngH(KoACO=c;C;$HIiHP zwfYaj4MGK7k&4&c^`5H3pdC`?8(EQ>vXvq-T$r7O8bl#(sMN<3$9+k*k*H1T9}W>y z^tv3Rq@+~hulXhc2-`~oP@{t1zc+Ww3E>3Ny6j&fj2#MC-qE0K1q7$JM)@J!a$b|5 z8=|es*=8$Hx;0GkP%hH4ahe5_y1-M7RHe+W&1uC@jMn{-o8EFXZcrlp_C9CdB4OOm zCuTUTqNv_{gd*E!2}>`n0R9YbTH`vgNvHk_ltT;gjs2Yv_hj}orT%g_=-c(?^#CRR zC)3FAh;LFb#?#_9avs-CJBR(gv9ZGsG7v+Pj;`ePZPV~&9cz~Q2R1LgS?s41eJ@r+ z-ptIb`;1VBcp=c@@zCCtHpipir&llth<|w51Bx5oMnzAfl~$L5QA-lRD(?ewIEBD- zm1uFTE|LLGF&nz5qz17IPNas8j-d~Em@$h*Os;X5D2g-aX#D>nQKR8Y`r#P*2)L_u zK0b@0S5+*p1Rm|o-qAeIdPFfhbX9<}TqAX(3F@NZn26^7iMjNQ6K~wMkNdSvyk9OU`Nn;d(bSl~|T@V4@5NMCaNYzx!d$ zJ9F^H)Nij6pU5ylVaK9?d`4WD<d=+yh92G2yaP%3hSlP=_)e>fihOi4RV zCj}|UBw(BQCXK8N;tX*T{gq?tt~V>S9+QMh2#LQf65bAg`sw`l@z@}56Jr#qmjZ@| z^2}dafxVWt9F?8258nn>xfeal7G-J#3&g|M6t}Z#x6_gYFthNAzP3 zIouyub8&iL>+4b1kI{Lq}0ggk2dkpZvC$Wd?yNUeDCb>>0N$+3Ua@zUNAdb{E(9@6(_o z9%8}|gE!CY?~k+|J#?H-v3}Io8x2u;-;k!-SiMKn&ru&y>hWFFNV*U?RRzS>yWwIiEPbSwNDtF5IW&K;|V|JU@^DjSJjzl|(eSLz+@H;^{ z=t1miAX_l5Jb1RACZdjIV9beByN`(KuJ**kafUVJ&moQPk<)<_ zWOJ1Dm(z-YFq^n%bAzAdFQ*ad2Kgz>w*(0$;3RZ0$&lAk{2ZWP6V{Ic+@i(fyNA2p zS3w;rxvHWa0ZQhmpao;Uj*?|K0bYYgN4IUfoq` z`nEv@o*rKW^c6dwzYo{fv>u<8!*I(V6p0^MX|fPram)@kqnvYck77MOI)vHq z4j+i_l~Ikn`8X3Vu3W1n_&dH+)TtSa9!a&(AD#EM;u!(K5u>++Sz@kHBwx~0u?qi` zN&QV2jAOThLyE|+t{~;1IE5~!AsXSsLH!&MidFb*c$4uXBSBL+1gAy%G=Ps;38G!I zAUQ>71*bQ!rbm$X&}NOVuvoFf{S6qqUKTC0H5fAb>dR6A6V86Z9x0XbUTfZzYIene zWq<|YN>8KX;qwGf21b4Sc!l%)NYv-N@6VjGlT+=C@v+jEpFblHO!`I4^#vM0_ak4S zlio47<$7be7mU`;gR@MM3u71kL>0`@F)x>u4w;smu9=D7YpUf;@N}8bx(43gBkg?x zN9KI@IJduE>hyhtDnAZ>uv6HKAtfhQU(ILIlu;2J(U3c<(*joHyy_*MO;VFYI^?0v z0M;I28#P_(lt?&R>bPH;9Z_;v;`8umRlAH4Se%$}Bz;cW`sd79Wq2wO0@ozGqCpRN zjZVF(Nr;ckA@a>@>Lc>nMzfLC^7^F)hcpzz&OK{VymFY;AEk9aVk7M})0){j9shi^ zQ47O86gt^#WV_)*+CRV!ETrHsOj)UR8wR|Lj>|>+(;0InsL=aOX+tOT>YIH{969Wt zQ-OB(2ilW+m>?od$nj)?824FPqp`O>%bz1WCT$`Q!Tn)tf;DYfqgf_AB+ZB}FQgxtG`A5n-?MlkHQ<(C_QcTybHxyp?~Rc-JuX~b-Ng&B za>cc?5$ldxw7Rv z)7aAGnBN2Nw*xO0cr7729sAGNHM@%c?k)EUVig**{q@z1hm{PQ8jEF^(6dO~dr38F zd4u0<^wH541JN!m?lX}iCiGRAXSDsAj~VDweLufjL}Sh*&Td}GMxGl7mBPZMh)Om8 zeMKS-0*`8sZEL>3@W|HUVx<^ZnZ6_4#2%W+71{{y%nHBBTF||H-WlAUaWpwTg2?}D`kwRfSL2D_>=^SZWtyHe za~dIcaQc_^fvgPUJ7qt8wK9uxSokaxnkatLK$TT9t9u(L6!LPx;sO#Y$QlPB@FhsVV=rm)bF53egdzOz=|b-VyZeLY?M$f-Tx7~R zMJBbvYO94=d>32>y}}%n&@Bgd9|eR=NCwg*MCazSM;vN-}diDT&>{&4!FQF1TV>sV|ni6q=k?pW9Q(|LxL z3dygB9Ue}f*9kcg%`$6w&RoFhJLsJQM=Kam(b-uCh3s$I_I=m`7REe8QPE8vNrVs> zq#~TkC+lJQ%?3dirFJ42i+#1sXG;aAKh?e^ z+2h`ws$w5_bBN^Ie}9oBF+eeW{7Yp2^K#EnRZ~+=UAcz;OpzoJdU`~07n2TVd|FmJ z#(HTnPSZd}+F0O1^Imk;OJlDz*3gsb1Vk3Stjs?HUtVH;h;{#0UO*MLutcZw z1WH7mnuEP>@1WFKGR=b~jiw?Py;fF-A}7c}%^&V^ZE{^{jMACvm?U}1A!Duy)tS|# zL9sOpJRIdHAbo00$(DO%-EuoqQv^`>!&40n`QZ0`C-7 zLUWmeJm&hN*Gf*<5-T#y;;5-)$AtA$SXrn@RZEcw@@_`0^P0kEdLAvyo@*#9!+-1| z_TYS+MjeCcA;40VW=BkY{#to?!8!sZ4Atlp2CLd+M!T+COdr}AV|eohuNSfu@0vUMqlY}9e7s{ONjA6F0JVcMDZSXphLz5ieVZfD{79YJc(u2i%uBD(Ac~-m5bwrsODb?&3 z8x5*S%-I6!vaAb6*^6%<$w1_;e(V?yUH8(pMoR``&J3Alvzu0Q zyiAR^E=@1Sw^vpDff@kCNLM&OWd>XpNTY|jdZG#YLd@coyJ*zI(^zZ zl3t3?1pi$s7&gsrbrhUs5@avZfy;iYgZ=6S4O7=Kfu4uw+x^jcT6!yY+M6G3P4n3M zx(3KDt;J{$X_Dc~BT78xL9J$-awUj>>9Y0cdI@$;Ig|#IFQoqW+DpDLNrl)Xx-z%9 zwUP8kEX0pDGij-Y+SGTRW!(tB|5{+qW%i>bb*~e(3Yx~bo?Ae+OP)y0(Ixl)nEL9l zsJid_A(axO6_Ah|8tDc>N+f6K?vxr*Lg^4BhHj*0Xr!g2q#L9W>F$#FU47s8^Zh*! z&%=Lk?>*=2z1G@m?_)-&tKK}K*PK2C8~z4M$>8Gn_6zrRWC!^fE<=$A#!xPB4`c{y-Ba7>sTU0p`*8U10xNO5o?4hO9i-^%}IX-F76bnWFmI^_dnWBofM(i}U(n zA@|_njX$B1`^k;b##91?ePiS5Y$>9lY@{iLyKUe}=E2GhXd|K>L27AbMG_t{J0;68{iJ05 zCr`T7`l$W#37&XfP>nR@G1j*K2_Sci;cul8bQWmV9}^nnFdp;)R%w zRjDH9vDgx0<+4p_9L3by3K)3lVu);yF3e{shU~YPW}N@7@RuZ$-z)f&B(kH5=9pQ% zmZgQ6+dBI5uwR$~1_F+3ZtmjsFxLA~Ijwo0nuxzFq!G_7>G#L)pz(AZ03Jw_pejQW z?*1a(57x{zLFkVe78DQk4}vQlyA!>j9F^)oKOn;srM8Eg9~E668N*M65t@%y<{3|B zh|O@e`=(sGh6<8d#&4;akO4s6!3diM1Cl{2TU%Qvr;74&m1piA z9`{w>+9q~)Z_TS%Q%VXhW@CbbXW;M(iA&C}htgJsI~<-8_gBMfp=YbIKRU` zs`oNiI1AMJ6>YfNa45EObiWH++#2~jD41jc8Pkf7q#1m1krFSydjCGZFf(K;XQ=N%YZgz`ZDP$*)k>6@Nh+fm>-*LcigsYbME6{Dn^Hxcr4^+241lVm ze9h;^Yj52-E(A(hzv7P|fU5ERb@{!wt*xTLW0MuCBbh3v4U`WfI!fghFVr6IU;#m} zwwo*aR;`|~%;5LtN>?OMf6dA=+T1(4v@4T-`xa3raMr8h=Q39d3~h5?YCX7>*tRtN za9~kZ_4!$MOUI?*kneLaC?Isc#nS4RWQ>o;gUHIgfn763G(EHjPFWjT?H3KQWq5}o zUx)nBp7E7Dvs|pLzA!#my)n71g2Cv~#LeqlsC<$e2KFF_#7<3~L)2E5(v9)U!k3(0 zhEGs08}98qmjiZmYpSbHR=Q5cu50Pz!&iJ}Uu!mJGi<)0HmOh#v1ssyy>sW6m-@l0 zU9P?Ea3)Y-wW;!F-->CLasj#_b9`kb_b?N@6yo9xH!F?s!*#M*HY$29z)Ix<5Z7wG zT73%2cRmM;FYN4+UZm(X%$Mr#_iFC~KUbbNo^;M%^2{cxFwrO;>~s}bh*8JjgoA-p zTLAG*9=>l)84#$Nf$~A9gj`l@rVVjM5T{Gze~AEr%u6BH^^Y&C7B5dE?oR;T30%2U zjBF+tgfgl4DV&gRZaaQGuY?XKru*Iwk1m z_T*6wpO$JFX=78~l?Fa&%0qLK<@ZdvitlQDFqk&q*nuiE2B|Y)9-FjAvyTZZ z@Dh#vWOO60KtrTE$?4J{VQBOgu8OhzJ@z>O=uX&>y4u=;9{ZFwkbgc33hykX|M~#M z()E-;uw#DNNp4}GUVcji@wHTCjvNOyv`6xt^1KV1PuLW$tF{An3s54$5&6pV;yksM4u| z$0+|;H2@jIuHfGtpyV_FrG>FNGqpqiaNFD10&ObGN@Uam)dfA_D8^S zIR!p)3O9+g^ZhcyCvH-4t$lmuzl)G27%v3$nH zWSj%eH2hOpG}FX1KW?-t1DPhurhqaNW_|b7u>J2w2c!NCy)|Smh~|$ZL?9zV7mAJ? zDV>0QTzw!~D2FQ19#w~%N7sd&YQ3iLYvp}J4R#x9#nVYqngCXJXgGSr&>6=NRUrIz zn=%MZTi;EG)!Uoyw>N=F@%ryc}~%Wz0QyJ8Fq>Sf{mc@`oMJ9a5= zrf|Zu0ygEna-n}m^`Pf(ni2S@a2lSCsE->QYJ%tG z_XX3dmTL4>F240eu^w_jslcVW)$U4kehTbWO7lS% zZoDxdvD9>2CX8`j_OaflTBD_a)dX@K#>KN3cYAB7<5~}5`-w$-xuqa zfmkBHfd6|1dqyyiUWU*~x9f28;k+wn5$n@HqYdGJPc=Kj)uR4`L*U#=Vg0^QqL3>+ z*!GvPQpg7kW2GSAQ8RY@Fj+MXt@*f*GKJ}8)4~3X6hV#vv;n%%EC}PSr^@7r02+I( zHNh_e;_C)cb^3g^gG}k{T-=A!*g-_PL3NyWhgoc`b4gx5lDwE1eY6%AS}tE+K<`#h zAa)SYO=p3z%(aStG1av)QJW@5()znGt{^BwP!}T+C5T>wuzj(PqCXv+QuXI@TMOxG&ayt^V?*PhsI( zaEJWp(Q7&HnkcYUM(LJE?l%Fy4T^2~?x^Bo9srg zEWP}CYsozQl5z}x3+{54h=suBhP)Nuv|s8V(Yr*AyNbIDoactH8wO1}D=d$90HaO~ zpfZqCh%jqG)qEjML~a&ygxhu%(gtsd$#p(V76C%gRKG66NPGwrXNIWD>UaL~uXSdn z>g!6i22g(+p@nqhQe@7|7pe!km0O0~X1@hNoVKa;SsUq|(7*=G^?a;Q`-O@{_BO|(pg{pS)-pHNVYMrDsa3NOo=vQU@tIMMoi$1o=4X~S%+*OjYX?z|Mo|ZS`iuQn zoV&5G5Uc@HuTW(-gb}3%(^%0Du)&0-AAlneMpo8Q=z44MY#W0!jo^>;`6}h2iD46y zwKa0?)9Y!cyte&)=KgVp(;-;<+w}X7jM_+0ROc_>z`#C)Sgn|KY9kcJn$)zU5C4qq zK51NvP(w=BuOOtxMKk3$Im-tCpm5V2;#t#`h##@AZS9R)u}cN&)%>eHqaP(Z-Q92| zgomMnJ1`%QG(1|CgC}USA7<~Q3P(WOr+_IP`Z2&LiJb>JCH-PEI!yVwr8~&5>vu#G zR13y@{QL#4!MPj)*ik&*8`poRa?kw*^}%H%)p5luH@nGRB_=sPUes(43ybMT)2>~v zLZIiV$z!D4Z6-rnh}%3x$AYPYFH(Ed@@pinWB$jgKcO5RmJWk6YOCDTT<%)ejj6>D zHINg`0&@4=vdThY;^ki{R?40fkc!zkg#BgNM+W4x9V-Ykc1#-@XJHbSUUzR@wv5d* zE38Snbs2!X^^8C~V@GAOgNR?erI(ZWnSdq>EgcZ#r5dWv+{`sQCy~E^4Z{>4F|^YU zpcR)mxoAq8b&~osD%N}WhcEZ#e&@aI2co_XKHC#p8vCUPrr+MsI;hYo8>a^Y;W2$? z|3}@#eL?`URp67a+)yK~kBR`9EL+8Alv4V|P}bRD29?zS7%MVif&Jp~lif8bfuP1d&@VbyIT(}zSP9w=s!^gGr1G!a zC2=ty>z+_)FEVyu>{_(q{Z#=75fcWt4ezc>jqcCxwKE(^qwoCX_BiK2cah`v%RLIq zLpM{U+pqWl<{+!xecA%eyOfIH{StZpgsg3$@ zo|-F9D}pk7=qz#`^Dxom9X2ykd(g!vMi?g-dldZjZvrQhCrO*m>m?CMGqtRnkcAuD z6MIr%#82{DijMIFnj|NC9&C=P6l>&)VKtsQumh9Q{YGz#jXYp77E7N&j3$;pYm zcSV;xZ%12x6cC+t`+A{Bx2oLg#7Fb7`E{0Z3?&81NY0g8jCX@Jn#J?bwj`+s3=d8nkYL-K|_x2xoWqquRWt2+4#sa7JZi<_UC0K zVJ2F1qXL4-$(j4SxCX9A#2R$+uqgx(((bzPV7fwz&XBlDgUaN(topDlRSe^aswriS zQA8>!8hvR*n7D~~71!L~gQ!MDM5IL=NRmo{B|2a~V~nxvp|ks-%MwYQvQ9>E9=iA` zmqc0*iH_6OGoiCekg-$Mj@`x;Wi#Pc%p>miejbvB2~iDubbX6rS6)tNKQ#-xI%^Q( zMK|8RyX`pJd^kZdg%U>b2z>B3z(B-Z^jAJaD7=>Wc?o11Fo$fb>o7P)AcItEUZ^5< ztM>X+qOzcT)~Q(ifH1wTjg1aP5o#r?lxlH@+bRV*DG;*k|fmw5#i*_FruTcuQ$WTGLfOuhN z7ks0u6B2Tc$lG)VK+4rmd!8%SZqR4kUz0AhRaKt4$j%S-p})#RJklWs;hm(VFId~| zi1-lI(BM%-N$zbaTeK?N`1Q@o)MM$%tB-ii#eKBJHV~XzW!-OQkEV#I9>|S>4@x z4T{A)+?D)3ycO=>oR_(p4M(Z+CzhKEz7qf4F7u(0=4m`3bx5H3m&2wDF#qzTX-@aPo5o zMn$(hS6B?yfD_$&NH!UATI-edqcx7pXE=21T2jbY2rXZ@vG?`*M+&XU;#VFXVp(4v zGb>1f0H*t?gqNkGsLPnaETe|f4!(TX?9*>&XWC$8gVmO5@kEwdzo`=hvxCR7EmgfO z9EXh}{v~inp3**PV_p7cAM6n3juatf5I!bM`F}SDx*8RG3_2LVEv>Aws38p0gICm5Jg4?s3b$AYnJO+QKsmdZq3p7ALip61a3}$)3n(%0!AKcSuMvO_Vxj)r;w^FVYxm;3upB$|Xki+P z67Zh>#Rwt-ZwK4;;vkZoCg9AIG9X2s{N>9%LbQoeh)Gd%mF+|oagL$_s`$W02Mz?3 z_+%%t=fY;poX9lbGvx6+b4d-JWPTe*}0^ z2Z@+M$XpL=6m4_1h}fn3Ckzg)pZq)%&w+S7-Td!7c$Pf8-53hXl|uz`RT?Q4+gyWR z%{QFTsVZ!@x(OqONR4AFVB)T9X5L6GM^V0O22fo>!KgU~X8C^{3E2LSDdIrjCxHE$ zzE8`sj=+Frgb%gHn54>8>@$$W`MX2#e%W-$mz5pAX4w_1@eu&o$@yq=u+~5=fEp21 zu<=}2C(z zjr!5~>pzQM&)jWKf`9E`J_uykMv}iA%-G=ppuT&;;_pTe>B&f-)4*aZTO;F*Cq~x!J+5 zCN%mwX$4-yw>rPfz#PkZ)5;~}b+|qV%CYUOrCvSJXh?TuZM$-EfsY_Sp0*IY8fff) zL6Y|a@YwzCWl4i*uO2u%|9EW`Ynm39*7n4a_CZ_RX$?okHZBzKr4;AY z=C+pwo@bw$B`W6U>NG8;UxVAf41Yuo1yav*JOij5DsX>7U*~WXX^X4a{fFy#lZ+bR zTgl;>{ora0C{0IOMk3ug>e3alN)-u?M3+^ACj%jx&^@2S<>lW89$vj+kLp|+PADi4 zv&4^pZO~HqzmwviX!rcRg~)WELgn_Ioe@g+z6osg2g0Rkwn|?dAkCk1~|s#EN;zhDlCF;=c3yc>wXHF8x3zyfluNt z&Ra<$0Y#~Opd(aZ0bBRj*v+2>*HwHl*|8Kmo32zb8R5RrkXQDp9^Rj!qt_HS7_Ez- zAup)kt~CK!`{9220{&Z8d6=8?g`bdozM*WM+9@$qQFbEZQv{q@|1D*eU_RT<%g2~* zyPDEP;9@OY{8%G1L_Jh?%7%&`rL}wuakFQa0$gLW3n2 zjw0_4j=>`r?8wb&@vdsR%K`23`ODbwJ-kORm%j}-U3Jv^TKHQLE0b=<@SpmrJO zdz6K~)qViX3ae}MRUk?kfZOvIV)2ghY6D3Y`w1GcG{h;ZkpMCD)_y(-z0>gGyiPh& zIkWHie=27uV|H+C+w#zv;tuk9N9zek#eu$@br+%qcr3Fjyn|O@225s6utZKDKehn+ zDlTi(F!vd}JlC~(VF&pTxWQ6AgU=8bkpR?1H@zgUOcqkyrvVyekPnN^0WMrhN!S~X z!-INnG#1thbGpCi?PR3 z2*&>}IHvXj7Ow^4Ng!TJZd^~cN%#olG+_s1yg>`2_S7}VQ7iujlMNc{Vu9&|sg`_J z-)a(}7=G$ys9EA@BW*(VBRgrXfUc+o(aiNGOT3g78p~c8XY&QaezwqEOn5WZU`E$_ z#u(0nJ7Y|;s0*9mI#03eyT$Pys@<@skUXCkS}?ZQ`;qfnS4qbXK03!LF|g3WE-~?> zrsP+6XS`#chM$A7pWx)2kEMe$83KfB8yD}%jpo^w?D;&w>(~F6cLq1~maYqgZB6O9 zvRxO7%TsL>PdNiF%UesLd2PA1oiXS3g47dOZmSD36qnSD)>mXLlEaoIkwLk#>q+-63JW{l5liWh+xrud^uJ+8)f zsMhMlOD+u10oN3^odkMq^e&rzvRq&YD6CVziZJd6l)6&EXT_&sL_ zY;vkAnW!5#e6eB=klI;f5nyNcZ;vQoQ`3xuoKnqhTv#jusUh>85Ziqfx(G)Dy^zfEXj_5wW@Z12T)#vBLHTUx?3OL0P1M+9O;!nF%sC*^-yShJR$K1p zKTLi5d&mH^xHo@R=gWEPu%v_%0WWO(+^_OXn#7olf$1RdyGSEGkJ*o}ml5tyDG#}{ zg-ixM0S8!5!@Cgnn=n_?bn@mJ917H+5&a)gcOp5c6O>Vf-@R<4SP&n-Ih#Idtmz{v zWGRl}p3%iHUMvOeU?Mk(%e2f(k0%h{9zv9AZxZq}(+ zN)2kp{l&sqo6A){ceVU60QrwH-2Cm)MHTRAF|1yIW?VN`L&IMG^v<6G!-&gNZUH^V z&+OMIpd(;&g4xTi!%e=kylMa7ARvvD9_=nF>iA#2QC|PU&^`lpCn3y#TmVeTqqCyf z^+MUN?Ty68wrWl0zdB6N2gD$z1!cziJ06d{uerBPJpTz9-z{nZbtTfmO^(c zt0QoBm3(4QnX2%pAD_fBt|L=7PCOw)b-t9lSOk+&=Cvrk`WGlln3Dg9zmZ)P8L&e( z&mhMy>H3PMd;My5lux)Z2*h`5w?^XwAm1NI3|gYxOj;Ruln1JGG!mhqj~HlbQxbjB z*I&!tK+$uo02G3%jSY)Zu=(|Y3!|%_*>g#I?7)r4tr4;qpKj3bgMA3!wa3%{V!aG9 zIk`SJIv}2@^>g&o0IQAb7a?n_C>C*s9R)e8P?U$UMPG^f4xOZfXVrurx>Ct39=WsO zD^w~Hb9w{9BXLKv$zMY0Fk1UYG6^7wrl?N9wXe*~&{9Ns1aaex@FTCxl(OvGP<5dl>F&t#TjmChh^ z_{<|B)3W3mPrP~l;gB`Qsl2$g3yKXdggw8ulX2(^7LwrSg!eXq+$?yp>2!Y|#}7L) z6G_;?Z=A|aBqLBTvnfglQ}qgMg6g0s-C5!bBkia3E^nZZ{hiJ_l0qX(bqtyHe7*N<_lw93j`byZ-!8M8*-lN&#Fi<7I z45XFJHKme0wF1VT^;RF4f`s_r(*J?sz_MzkI!aT7A=EAZ8FM-za3j zDAHDpQno2^JFR?s$~le zaT>@KeLGpPDV@C!egk6ZaH0o`VTK`Q`_4p-;{kV52?R(Myx9d{dV{0-Kj>=$N9BP9 z$&%$iTLOJl@KoMdMdjk?SC&@DN69UHBTP)Zv&P~X;yq32{J12cz#5<7vL>T=e_*^6<*mwjlN;(60N-=9a!?+d+VD?vzLst~iabbP-y()8Hp6Br6LI@0yG? zwu2WH1ET7rp+CL>=+%0z7bd;gzo544d_wKO1djVnh@vsVIdkU)`h zqT(O>xRgvhu*26v@t^FV$NxqU(w5cOwa5A$FwE9Qk-4ar9gy}0oK97eQujR?W8nT=AFkoLYS ztHES75V!l;%S*IS1__SN)V_M(<9^TqmkhDgQ_;*L#A1ALkFBp`-i4 zMR>``xxnCrK`CjZ@w7w}C5$A2W#&yj8%~t@nD;uy(5LCs=LTl#NqkHRbP`v4%=rD3 zpD$@!UJZ?`r8iPs!N~w`d{(k5r+oP4FP~BljpBAi0hCEH196|%s_)FN)6_{-?BHh+ z7`+waJwM)bc#f5R*6-gKo;&yRcV;377(w>8v$@}XH{MHDYrP)A7dK5ztt*$Mbaa|n zs6!}i**1)TJF!~_=~ikBFqMlJ|3+^a8EXgNQu8}Q%qmGHZT}8pR*5If9tXl!&)mUs zMTE#sdT}meDo?yDU|8y*xU*E`pS4Ez;Jz8kCnm zrLeQj;!(qp((31FlwP%}5O!K_TVBoO3fCUO#a%sb&Zd?T zs#?t1zt~N`3PCvwOgJ--fZMgL*iA|a-*F~U7~9(&k?mA>Az*TJ#kuu;w71O%Eb)yLB{zWclWBU%OT3c! zC>5Nd)~`E_*ry;v3jz>8%0HDl0vU802)(M~T_($;oymqFouawznUK%wSPgQd2>L>J zbvgy*rl6{7iQ8kuYLE+K`>>&CuP(m&4G5bq$z4n{cY6pHnwhDY0C3KrBqYJC@#NA{ zmOTB_j0Y2=!{+fhNGy{4FF+9oP*J^l&v2F}wO`Me{@?;|X^exGmj2qZTD{@hK=_cA z3;vzwn%r|c2{kQwUiMoiB2|5$SfFA%g$U^eG}y^+-%xds|I+nZ<99c4jup0V{_K@S z=DQ7pE&X!hq^i7Pp`j|#fpU(QYQ@QVl`crFC)qyM*(YWkG4N0#MIX9hD^B@0KOe1Z zbP)Dq=zMHV#*`9&5CVAWIAfrL>5^u$E0- zIBbfiW&axUhgGU;db!g^5*lc}#sL&6NR3NS*O5b3*7MXRl1O?|sekFUg#`LYhF6i} zC|!;s!6$`3EmPL_-}p3-w7_M*%3ecNS>i^FR0Pvh^%Fk|b zT}dBalq8q2YETUioh{2}zc$}NrusQNRr}Twi)uiB%&X1!J|apsEiNK100nR7Q8{U# zOWm%z-2!Y*+&&dl>sm&pHK?E$BE_ly;M2P^h=n?tc}`zU!KCKa=4{r9X|yi1&SY~6 zd}ZQ0dLSqyB&0C)pVrg-r*7Ey8L0D*-ZbmpNW5dx*4ngl(5X>N6bnr+W@KcZ0uR2) zFVb>X3*Dw94|AYCpGd~WxwBgNt}^uE`dO!)-1Pp+L)>_%p*@Qs>0YWrSGDT`C!ruv zi~?9sWQBzEhbm0gjmA1GueKgUi=sfQCjAdDUF2$LdAI5Bh*n(6K=>gfANN<0$?lPQ z0fN9Aa5&}LFhEZF=5_v@g{#?{`=@N0>@(*nH8rGDnp?A3p4@WmI|_rklbht(chxWd z6Y)pg|3uM8!|bj}lT7XUv2Bi={VHC3avJYMGgMO^Oha(sUrUO$bh!G_L66+_{Dsdu zD^A!@hB-DaJ8iyOuoy${LVK==oxg9(Yg5@}KZZOwkm{1hduDHcwbWB*$7boWNCS{`1={6qlpWJ&M zmW$aT&P)6R1@8^yw$${Qfa}{c*1~QQpl@%GACd@lM?J{?MeZ`8P+1@&|K_)s z_maGnLxo`UC=JGvP#PwL2DSXMG3_hMC&7XL&^CIdM!UjXvVEPbR2dgjk{)=uD{nlM zvMF*+_1P(|>m;_$gET!U3{7k$>bAJ(PlU~_J!96W)W;}C>X=lxL?F>MjYuAU(*{-q zv@Up`PaiAV|6?@zk&PH=K#M^OMSHx(-x8$4Qkc;!8>!!s<#c{jRQHP`m+~s)4MQRnC8PgNJ zA1G+W%uInv9JH%XP3^DG8#MU-`Yu?ewSWq+%HX7>85!jxE%&1DNVYgzsDW;h#u~+T z4dk^UhsR=VhWEi9&tV4W5Wr)-@Bo-9$N-|y$;XVumg zDE3s>EB5N<9&t-Hmu5Yk`Uif5DYyM!tx@ysdYe`I8cxic?rU5PX1+{QWvO!K^>#)^ zWhIxy@e4;0k>gzXpj<@;#&ozQcusYa)lP{Ac4)Ej{n^pWd#ejdaFdT?9*$G+IEUlR zuNK`&5@xAOATc@sb&cGpp5J64KpWzHZ`Mt?C@_)e_V%{gQKT10@O}#Va=^`O(U6@! z8#3G2o88-O6`*S%4od1oA9t|ka-U(dPpk_!0m<_uu2W8uY6*Q_@+tqVkrl_pUAiZd zEH(a4{FzoEDBz88I5$YCRxG6-!j9zo$S~*rXAu#j+>#5rvj4@3N-T2fR$gA-B0+?= zcVm{%{vV=zT(SS!*(Zi8nE2jksV9nem$&|TyX2O)~#NuN{%p%cw z7M=IkuU};J=Y*_)rOxLY=Gy}!WGtve3dkyVaQ}GR3Iq}6!h-&tS8ES(AQ7>MIj+v6 z@h{{wUt7w*HJ$&Hvmer}qyy%|-gu+!t*yjRz+Cdfy219*4aaWt0H_V+(J7Z%LKm3{ zwUt6!DK*I?Wm4{{K9L~LCv6T6$;ED+%*;2PwTT6@COE`d%`c*1I%O_03^e1FOx1#D z!&X?@Q<+D}TR*w&Vke3c>gS8|Q)y;-IU|~FsIk_2`|+dy(rGF}mw>Z)zM`!4@mcWyod=cp z=kKE~%Jcm7!>t(H${BckyBF$Hsfa5HLBR|jgBl{1z|2`|~I5U%sn zu6Q^1@V8sh7r2|lD|IEJc}tf0d%i8gpcAU|Dx31|OWUaO)O0jMFL9%9Ze=^Kzy_T( zbkYoOTV9a^4TC2Ez?7f}8QALg#|GWDST%N5kVs$e4q;w9_!rDW8%5#HD|3#E1juaV zFxQlQ(>b_kx50JfH~<9`3B=`gFi8O5VfSW41MNdE!M5`b#i)rjr{_*YJ zIxdCM3)AJ>-4&X)uMpf|`82UA?0uBV{x23uZj~$1)H+@pG($JzR8uV$N^BHt=bE#; zY(H|!#g|r}Fc8*fb%~?sMWX{I`0rklfU?DguvB~O9SG;r?v42K(rHaCie%m|b&Ub* zUM3(66@1=HU#fFRYw`<+O(@{%rlr5GUmIF&4~$IJXK+j@#3e~jMVP>pKW_;r9~~r` zmVzBdK}9wHxH3O@zCMgXkN)_PU$YFg1JRDMi1Qp}FVN@N6{%0sZ9F+5x(uk=-QC^h%7y0-4P{0QxFQ~HDx9AIp_@k>%pw@t`~@r#{yFjl zXohiZ>2BCHq6+WYrqS{uDZ>ebkVumRh#Tj>87gP2Ko;o%{r9Z`xrTr*D5&J$)`7Il z)O%!$7qG5CE5Cybz0)&yPFyah5K+%WSCE%efHRH5A$rus0L+VQ=9Q_ zPQ>&}>2#OcqZ>*U*cttbWN$rvB1YUph_J4Wl7eg;Lv(Lh>VU? zWO%J1@^V1!GET_{1q%(CFSj?>4Cl*)Er-GU#I{?tAzWQok>QZY@;7yTwccSz!%t#9ddP%hP_0>aw%jf$( z8$RS_Mk_&iLeo*veJT74U+3<9Y!>&PQFm2qlm%y3RZ__=r`e2%<=q=Lf2PDN9vo^9 zQ!mE=isb-yadN>x2V!&@E1k^pVIwld6xCF0>aLT=_!(>Op1q2Sw5W`1VcT5#?It(u zG-H({(LYBVts`2}^4_jzMOS`qXy6jT^WiOEXz;IY+LVGR&@>sbn?q0} z$xBwfX2grR%!f1j6|j1I@t;w?yT6?n${1q=|FtI{?RrzMyvw1QhbRCv-!$E<6#KA# z^6_mNQ0x3heCsTb0~}p{{I=d|pLDSqp!u{`m*jQzD0)R|xV0#A0fX4oUT9w2+@Azu z1x(T^l!@J)S;dE>6kpauz;Z#yx}+}2u88BRs^7JRnftHtnlk0BA$`^T{UJ&>$BW%| zo(!2}_$X{?WvnB{cWq&SyRex{e5C;d5Uh>Nx%9-O+JZ+e5T2B;{`W0Bnz+!wz`)~< z>)c4ew6T7&g8IIf$hfCdtPv=vKg{Mplu7Yi+TmpkQdD@*+pW|7B#ymC*9QS>&$X~} z6a^r?1I2;Xv@*Y2Rw%fw=AvuB%O8u#{&blznwS357D)5#0btZMX!X;05+R?>Q-X$@ zPCHnSVcuTd)mqr|4-+|#u%jaOSajeTC5Z1ReqN-oW($3B@e>IAveY9+1h zQNaD5(R`z}o;SMfwHs=BLyGqaWsvC~T+wjpDoR`UngaWV% zaA|G={$nZN=rRyu-R5d>Yx6yo?VCXds-~Hh_RjFdibuV=5H(zaHrgQ+Tt)1p!gj^Q zY~gE8eNPjYW566CLi8e*YyPgDOL~%PV?4GF3R`I2=>(w+@Nol8@&AQ5DN#mVTEfes z%}tgfevp+mh6k1;u8)J=gBMhMiVxLmx1a^Q3w-yV=vMeZ1P?vS%pju&@84GMmfz@-*v%A2pye2lfS7 z3nBc}SpKR9)b9@8`+V#-p4=48j^?=dLI(M&k1~bOGOJWH3z!pnuxvhs?s|2T`Wy4Z zb3Pf=2g(`~nlQi9*eXSSZLcZKn&-fR^0NT#{FAk6L%*P$fNdlJ{U1*~%`5la{pH{IlUv%Y$9L|-f$ zS_3^TNEVKuf79TRG>MEhcd=gTKh}s09*brkTpR8?FSE$IBz_~2G%^&ShZ^R}Rj#S> zaZBQl5Jgkd2YCeGNF=iC+nwdpl7HP`WBceAB@gtFqBRKP@XtxE#F0qKvGmphj*r{? zQGij#CCl5-Sxtu(7Yc+apcg8W4kPf8GUo*lCJ-Uz?ZsnsB<`e+J&-wwLsT|+%lz7W4K0X;QFu#0`RH9L6%b6zQKaSR4boqN%LwQD z*4&OZuRQfr&|lc<^blcPeLp{S1Kb9)=>5eL59DIDhu7rv=uxt~FID|KKe{HI)KB6p z=+;zJNdCuXm7_$6rHBQALgkeSAoh>uaZdFc!^qUhRaFyUP`rIM9Gms65(fHbav$R` zSXB5Fji#uDBgn1PyWp;j-_Rg#(j-%jfG#~VgNeICv9%>aE!ybcJ0t1%+2yomtlFno z3j?k=XD|~&rULm{Y>1-zy>UoS+_nEi(_T%LXv0+TB*x7`uVR&OPlug>(B zf{T_^CssfqkI~Q%h2}z<>J`@$8DYV@`ea)Y!+O}32a6;)z$^L;i@MsFo108?Trlnp zwmiUhU#!o;?f0JF4t6XB>jl61FX0dZ9pn4N=41*Kv&Qc}I_D^a*ND{~g}34Q5pUW-53IJKX7hGC(KDG{Qxv-*R<5Pn3s>%iIBm+D=4vtazZOWLV*?HR7+Yj1Dw?Z761MSX*Y zArcX|&rD)W2~rbxXy4?W_K+R(X-z`-!oVg-52IY``t7?L)JZK_%C~zo^u4(y%LMin zw${&7%iV34t`QM#Vg|^nA>Hn2JWUET^opJy;oZ{=725|#JNlfgnpi*~@~xAf!*6#l z>%AYe5~q3i+Tpd(nuGShq1Uf6%>%N6qJ@F60;OYb*A)H}hMRvdKQ(7lX!N$8nI_bc z%X_>%Fs{?@u2)1XrKpy-dXuehVL`^go`cuR&oQJ3hKrK*{47~cB*cmKu4&0^kvMCg z_$Z*2RQ`Lm_$HWXh+YK#!r2{5^m~VSCK=~}sif9310l?1+6@8Emi+=SAd6{z3%3@M z!j{$%J@G}sWF6kyk(I0&XOtxSg%0SHlU*Pb$`$EvA#tMFGGa(0_fVGOkVu#2hkN zrgvqBCd=>WM5yb66P{0`YcBq5}^3d`JoUB^uyFNGi$L7G_Apn1A)mE z&wz$LI|L-j+}cU9!=XDl8QVR0!*&mMJ|a3V~5_SULkmaoZVkJ)pp*G{f;_d05k9KAV)j{d}-^yF67Y zkTgE6Bo`mE#VJj)t0{}}X6BV4^WLWar$CDJyU8CTsqOD6^p25?!`uPyF$|2Ly_fZM zEJ0xpC;K6dXy2s-v~xC(t$|ZkNVS7>3s%x3p7TqS}b z*}0k%Zz-g8y{(YQ_J|izB|07M#jXbLfFbIG_9P?rHC5gVz+uBrYVQLH7;m(RRJ6pl z_#6bL)d36W_Go46xH8w9Av!RQs86l9Gi5UihlvKMH8k)0DIQi8~6I#Jds(x$_<491M)3$K9wBZYNwjBEPfO%yt)IsX|wA^0gO)2|k)VEf zXmTG70#|;mjmt#T^9lvz1)h_%eMFTp>mF>xKO-7wCzpH z{MwfXI>RlQlR%4~u4w=Ya~I@MbUS$P>gfiEFp7aMrJM7%FmFPuOTBpc8bLc$Zl^+q z@rs?bwVpXKV+Aq8t_RY0;kV`Z4@i5ytDtZXR!LxpH`9+?K5KL8%+7Kg9D>b8yQ5_b znC%Xy1mh)#(vTR}f=ht_X}`*;xsY*kfOLm+ z362=^=)U0`!(YkI8)tqQovh+=t9%?E)c;C(@>jqU~C@6t=GatFbDJJ9pJ z(Cojv@5L+SO@?e$=^vo{01Kx{Emnl;LNJGSsQ&BC`ci9ejJ_Pm#;bzkynag&y8UMo z*JoU-MB_ySeM8Q-7VIMo=+Yy>oE%N={H96$9o`pIG>6X8d`CwIa4!^a_suqyai^wrXBpS3l zk$`rOSKb>T=4L-2$ykv?q}}(+qDvdRg9iDwZf~D0^hs}-mKUutZT!#0PXbov)HH%% zxhu^3%um#*=5Y8VM=VZkscI^eKp$#KY%edP2k%6UsX;a9t01{KeJ2Ij6)GQm3|FpF z6%Fom2aQd0<1avdvZ$@>x7fwp%CTo=BEc7q;(^vpHa=P@8{0WH;c{JiaUf~1XSJ?Y zH|zm?2zc*mxy|4&>3WDf!+rJnC- zoIa2aDd3VHNpr0(E;IICAUKcC4O>=1wHQ}TriMgVWfy!h4I?FP6?6*bgXCSG&Rj74 ze%mS6Yr{SB-eYYw0iRn3E-931&sMPlvZu$HKIcSw)s+NB-CC3?`SZzLzo z75C*1mN@u1RU@!BjrS_@@}2?b%f*XE-+h1lB4u?wMSgrO1<3!TTCm}=Am}G zzP1c$zm}K!Upo-do$S}VWY}}K)}00ok96bMs;Q6>AFqW5X;~{Z)$s1x8X6=UBu*X~Ey4 zG=s9N+44Xq1(e`j>}{tkO<{p7S_DI$adD|RILWOnH&Zy-Ht79xF$IEmPuj5{fa4e( zk;?z|d3-jj+vlMAjkj7e?P)zjzw?0QYPCekuOa!B-1G)c|cxk1cG-TwRM+X zH{Qp|XVIgPZh5A4oVOfzrl)%>m472Tb6la^_Bk=JNze6)tRrw=NIB~2e40iQ-8~^& z*oEK9HOmSI2L}FnfV;^mmcym&japdvd^*)scH}4<-X0vZj8HJi@YT637~sOA=ANSX zX+LJsEEl0jVDG7#haS?^1{-56pI***cC}2*@13V8(v~ExE}}0%9uNpE&?~2~99^ye zw3Ua4ldzCi|6hW1@3Z+W*ZDyj1$QamX6Ir_xpw!=_UTGn1MAZMO55tv-&j0vw3hFI z%jWSno*TuEsS=V}%Dqp@vL3D8lGtk2I*^QCzc`!**58Sz;8joF5o{`g%lZ+H>$W26 z;OACOmwT=Fb5j02)bF&@8MKie9%>lyivdz~!xZ-ER?YWr0A2AXqE-9moaViOyrnE~ z?lCf?4UPfMHqE5yray!T(AU;=?PI(P;RhQ^JZyd~2QEQH8Ytt09VYRR|H^vS9%x#( zCm>%@Jkj+p=Wi5unD(9ICkMiWUs+C{P9d1e*f+HIt-^|MHdTAKnXQWzUjK2YGAJuj z^70wS9IF3?M&TcqP@=SJ9<3~OE^GEgo%MUK>&blyimc{^#WWJ)cxu01y!l&0HJ}AKssQt))SaNuV=xGo1E1bGhqV$$6ew zw<*aCVqNkWgR7(yN}-!?X+GBE5@V#h3pyTPB*k-ncx&3A)TEn2FEN`EbL0+KaOXBh zZ7w)p6G+&|M-YAFd_@8j5CNh-3}OvvS;LxH)g3{^eX;Eiu6y_Yg--lz*X%EpbfBwe z<8(*L4A-i#GJ__N&tvT(swUB&+yJPrJ*9kh9A9KGh|`HRP1p zfb8>5ZhjX?%M!kpSmgE5PWQY*idX>(dbs*;aOYYp*eTcCb7%wk@LNjM?ZXi4nXctB z6{Y8|>gK^ZmTo@*8%vFKL9vrjjts*j|6pa5{T2t`Ys$SCT(s~OhzvuhT|N# ztw5IF5vOkkBdWSMaG(3Vw_=-B?yJ51#K~-QVpGwon2TfTXO~I6C1rX_Q(GK0_&88s zt3o;_;uWzSMQ-?R(&b4(V@XD(X`W;aeJ_+V%npGPl9;=8vlyL2w0uUW4>e zh`@Fw+K+CLv?|`L*@O0jFV^v?m6~&X57e2FnC@frxi6g60$f#!1{%qM59|#o@8_9% z|EDe9Gm13KH;`z94>En{4eAs1&g*sVwKpGdEK_$OiA2Zc3P#t}3ZAR2{|U-@d#TEK z06sEb2t0gdC5@8ojJw`KE!Eu}@hS&yP^Y=>E3@u=xT2AY5B-I0i`6@gl|G8L9d!1d z7?@L3b5N1GJ5V`8YOPcI)hi+UZQkHf)Gq(HfxzF4ggT5)I_I8v8`Eyd-{x}QlpT@0 zpF+_7V8jB*tu(hgO&F?S#_?(t5pAtArKsvI8sj}PD*}9&e^4CzKb%cDvu7bN=bJA? zFR*LwRYv{kvni#`?Go%SHoZ7jD|D)@2)5$l66hMAcKOIqE^c`l?ytf0X7(&qcLljm zcIUZK>oXX`hdM#j*5}*7Jd9wb$$3c45-M^`a4IZ`mK5#QiceSnX z8JJV~MY?W^YhNvn^|2#b#FdC9DR=LYFDnbRMDD9MIqkgrU|%Kvf=4|UW#}k zWrRhrg2RVpnjuO_$X}IQo(cS_GtE}6+2HsG23VhQNUL{>`wn2(Sin!Jv~cfdj4qfV z_Tv`FhUW)k@%OO3t$04A+@Um=L{3||e1T@8SLn5a$F8a0zy18$$9^T+jw6Gdk=S3YbGiux$i&rSy?m=WZZfY{pwc! zra!crh9zY>oi-%TLG$iH>YMzb8CCM zhypHG|3gktP;jEY{klo6p1$^Q5>I2(g3w+gg89|c%Z+`jcG#*}lVRxxl(4O-_n@VP zID4tHKm#js7=>JRovHlAO4E4yl<62zA|S=PacNV%Cv@+|uFpGZeCcJO!?+r2Yc@x} zla6=oGUKl;CB?v^FO=SH`z6_ZgThN(%j3MZb$w>zP=a>#p)-T) zX_d_)d7pN}7fBF`?MNGWd4`m4DQlv zeVqgS9rEt`*=q?RZ&jl2GXdo)8OVvJ48bFVdo)4^J+Lw};gi~9`HQw8XYbY;n%7NY zQM*?1*~9@NrVx_wD6cOuA$3J$wWq=gGOo%3^+G)=Ie8V~=Jjn>GR!R8R3}_VI$+yGbv6kSMSuT`qC~Mij(Q=>lM4L5mKcO& zxr1ds4!;+{|5Q}meiEq;d|6ElEG}}CMSlg2Ntune-9L`(4@D~|)R82?%4!W~3i12u zdlW@{Y_G9*pOq7P(G*nqTw>sCkVCW6ry_m%KI4qe9UlpI+b>%cZMq#p0zww0onJrw zeQl(mXg;`8w@#yzQ=X0jut3p19&$i~J67c<%Ji!yxPh#&t z+zA`Oe}{?nvLL-6_B?}^wXEU;BQy%l^(W?o zUNDd>BLqq-T;H9Zjl&N9^b#|pB{kR*aZBI)L^06Rdq7m=QZY$!=tx_oSM;Be(b3VG zcmA91D^HnyCWeT$CvW!zNmQl7k6+=dwy#8G?GTO~nY#;N0; z#xX9JFnAkZ!7W~a$F6X$$1Nei&E@*&cu5?M(R`@c7Ra@|Ma;;o1g$)qNC_WlG}NQ= z&Tm)ADTD{NK8uW0|0(KmLVC$Hdp(*ge{~!qDS~Mpvd~pLhk-NmqQ?ePdi6L&t$ab( zU;bgCK}$`tU7d!2Y2NH|>;~PV(_?xvJH?0MT1B568v153)T(x$l#e|w03frx&;bfv zM*%AQ?jrIqm1n^mHCmT!oCJIu_CPu$e*av$@JOm27OT3z)Z4&Qo{5xxv!?jGDy8dM$b3 z)~H#9ZV6@?>`DxQ3$)w-hWT#}@vLrYeUoxidt|GNZFRicls(fC)EZ#*4d=4N$^7ClRI4W-DOq1z+kL=rpg_Z-1INQUwu*mswrqtRQ7XxaoN1W z1TVFiiB+{Mb5CX~)~hi=Oy2VOt)^$|RrpjD%q#+@y4{bFn?FPp_r} zNhkGh&{78E)PpZItPXMcH@_nbr(`FhVKU}8{FZ7oybWDykNyS;@74GmT9 z$+!xvWwdEfpv_fC#}HnUEFwS4c56W|_t82|c8_K|$wsENanvoi@)G9|yG_!YO?UL2 zb-KrByf-?hidU0j-zF1iDrHDAU^u4VUp$f37;rdIXz_qqnf0#G-|YQ{d*|5<*L)xB z-DRFyzOUhUVFlWffoBE`%SM2_S+``HMDvVaY?1XmKKd45F3vHl6i4qQJJ!~Q@w@MJ z%ixK~W1jY?&Zko37P&;-x@5wg)Mw~tJmC*hnidTB>jbn=5QE=6npw`K>9pP+m& z{q}A!521bK8NZ9@^^C*eMf)lWL~GRD>@raf?!;*VNg*30DsA2{wF^9%kIx2tOe8NR zrcaT}Z|X>%mM+W5$N*Q>zUMuA;M&v2HC59YJXefej?8NIMQ!B6Dz(LjDbJr?k$y_C zbqvJYFc#EKhpjc_d>oAEqf=2`ABs~?{0!Vv_-sk(M{GuIU0z+d_kMeF?75v!gd6(H zIg~pzKQ8AgAx3QXBR}Z7MxlVz&>U#1>bshV_XYC}#)br^F({QVG6Z#g>*c#_?FYm_r_o7HUBN<;urN;jH!SGrH>Sz)vY*6~{{+6t< z1D(Pqf1pjqYS6%X;_esq^TyVZzPkP>TZQI93toOAgS5TWQ>lO<6*98y*x1cu7pB;c z^I2SNkizYsIxWyFHUYEgUUPVLEl8X~_eg#f+L7!nRlCdryM(b^WkT|)g4RdEpqM#V z0w%kkdDz+~h>{s7IKuovBe=S{y5{!HoPA;`i|rV*K=gHHv$Tm8740V{Li`_W4sKsn zi%x6oT)i&}isH_&xuYiYTjS@+iow@ADS9R%2F@#Q4Lv7EO24=ioPrqkS?VlJO~1v2 ztgNm=>T4{`N))d93*`-ebeY=2+lIWQ_LLhoBPFl6__#`3T%T3hL5&CPBY(-g9mPWF zCuxqF*Gi6FZEBN#L9%b}{TmnTjX>b{>&bHV=XVX$nFfft9CY*nOn|5Le9sp1p&+;{etV zhiO#S;bwtYyS}prH-agiF31e;Z^peT!^?6<_r}Cc>c|9b!yaxq1odDSvVg-)cu>d` z&&raS*_A!!C;zeUwgmP8p8#!A0N;#w;T_8dM6J-gm*YCOqsZw@|g6DL8hDAl>5oRzxnM>{=R%vx-m zge_o21>Nl!GR_5aW&?Zfek!(PJ zbIE#n+qnNEBR&Vtr$uPN_G!BO8tdDqGhlMNyGMtGTCmy5r88PQv8HLA*Wv5tD6={T zWzWf00V$M)UNRF0!By7Vlj)zwm@2t*-wbAQlUEVwa@#_WkA|PXn9(8XC#e8h)2cw+ zr)^~Z1;qw8Qod0XT*~Hrr#E|r+xA-P-m_qvKetnWzzwrCHC6W30SHe*!bdABu6KK2 zfajFY__(j`eK@k&8NmWSPYGf#9tpXM5Vdlw?Nz)iyqAY&M7xylsS8_AAdB>IHu=L= zobBPKF}MClx&fC*f8U(jxy;LT)M!NZBVd>^{j671za7GX2ShEST2OGP zWGO1WbgyL&OvF(o4seUw!&&%FT~Pb`0yZTI01h!_ zD2P63gSe00EAGFj&JfmiUP=AvY^UNqxuFmD;P^G>zRu6exbH;Ioy+PPHo8GYxrj{q zF5CJJBznS#D4{GKnOD5?*PXkup;GsETU5w>3LJ&16;k_jUF$9(@P}I~rw#G@8G)*t zAHYoZVrR-HUyl%+owp+#RRsK5gtB?HVAJ0X64v?ZE!`QGHXA~Hq)z9wZGY?G1S zy>W&47Zr3lS~(m%0?^i@*JQ6YYPVkm!Ja+Py?HUW#_*q`ftjnJERK3S{bL!<)qN1L za6{ji#1QGoBZr2d0NqCggZthZ5J>3GUSI|88yPMiq?F9E<9MGyLzDwihmSoRQCirj zNcXcW0ipmvhT`{tS`aDVX(OGWY?mubJx0z#hX2w$g3IOD%kc554|M5YpMjtcKC6x_ zZ*B<;4S?WsI2zh@VVH5->FH3#pon`r_(z{n866&r3=)6WR{i#67c_9Jg;t-PhcNf{@6k&r-DH{ zxH-5TMkR;|bGPZm{mFq~HfoMB6uQ}I1*tN% zN;tmRuRfl&jXjwJQvlE50+OKjwZd5ov<@Xf0Y1la@iHZ9NOuwK^a1HZ>Nbtw9^B9* zwsYT+M)0E)y=f1Ucpr@C9B!U;tW67N@qWyrJPSCbXcdvE`>M*m$D;k+U_kSY;x z0sO}J10lDSpk6vTD#7{MeR|_2O#3ETKWDz%uudU4E!Fq-y94I~7OXtIMMaLe;{HEV zQx}y^HJjfuD2pW1(jHU2|Vt5IZ*{n znsSRuI&t3q0&)E5>TJ0_%U|aZkPuik6ioI|Rr$Q6Q^Ohc3s}3@=jHOu&eSI-$<52# z+1g_pouVxuZT6iqDa6gfm)v#s2V{ez&OHf((K*ojBb{fqT)j3G_%8>zW0fwBX^~1DY&1@ z6YAN+i?bP&lFxl9R>)t&I1E?@=$iLi^}(;B6ORxs##;CD)bj649Th=d|A%E%xM3Yj zy4=4%0@o({qSw+A-=<&S6{4L>6r8WGUO9YS>VmW77)4SYJ}bl09d<71Qh5aVg2Wip z>ZT7u?`K)o9VklzK)y{!k~?8FmWUru&{)Wi7;G+`UEIZ}EVJqzaZ4+Z5JAmxBO>qv~&cD+#B2#Y$ju#Zfh51u) zUz~2~ZB{J~fI@X}G#14|BS<|sy>THgOwGvp>j06lhEbE$18nR`SU|>6q0plx_b+T> zJs40Sk3A+Jm&vVeX8hGkc5qNTy>=%rIE~Lj1Je|96&yBO@9yT-fgT|`CU%q0{2|Hb ziY~#pAlD0C+FxRh*dTcYCRxD$!se2I6pEG%t1v)G1`i-+PxtID0PZvg4pY)r#y!fe zt>f(L^N*0f`YvG{K7a*^K|Ye8%Y4$y zXZhz(6#1PVQ_Kh_;h^~{x?=Mh!7@=AQHexbAO_2=Z8X^kpvDaJ!RmlmU6q-@t%q}w zhAOJZrFvilMZL_YxLI*t{hMxapXeUTM%~lzDs1W7MXXDI3h>y{bS~nq=NAXhfhUK* zY4cMsrJNJ*NM5dI7LVs#;i%iYgJEV%!6Y5~)J{P>P4a{v3+pk)TImu^V_`;d4 ziZas=W$OH0l8)GEQk}2G^&$ULGQ3*vcXL9(zpQOz}OOi8|V~v&{pw>Y&0T$W!RrI-lkSzjo>F zh%`S1A$^#zMTA;W=6Z2bl9;%tH#pkqu2LZDkaf0F+@*aMr~L9eb2igcz6YY4zXQoo zeMP0jk!dn&*^xm{ylU=FxE=l|^12V+iAos;3FxCN^72_?q7UJ~`ZXzDM`Wfl)4m-g zs|J1f4?=t!5D%bw-M_YO8R)dTkdq`n>T2?u zm$Gqz!XyF;qDNwV21bl2EPmspTpQM6>~>XSYISaqvZB@J`50{=aw2=O;Wfu}O>2>_{KjIPaaFN%!YV&bI(6N04 z4Kp3FBmol=utTo~GnJ^bb709eMV;GaV%7~$oq0r4fLV%E5e$x>cx9H6k>S>v4R8m` z{Gb3%72P_ylaQUmW{Y{dhKwKcs4$PhpW;s6AmYzMd)BzT9OP9QH}FlbOc>hfJcK%5L&L{y+`#xuh*9*psZe5v87*>LQ^x0oyo z&jgOgco3^^Dy5EQCL*&AFHz%dtT)R&BvCv?K1ENTu7U>7waChV%Gmp!oe& zjxK$!S|K*F*sKqcs&;%gM`I_yC{((93X`i-BO@bo-)^swUXr6DNZx~NK%488teyZ{ zwaoM+_~=NkhB1ImK`US!4buH-WhXH}Co#)=HsGRCq0WvjmRE+Sw}NiKQZbV6Gq zc{Z2&YJG31lWZgL-Ns2!f8mYJU>~l|mtby>)cY}A<9_LseEzwP!M5DD?`tPnAZU$_rG3%HAmeY=lFcJ?1HYrN}u|C_x_;cxXxh(641|lqy)#R7VxH+`#2d=_nQ)&U3gpVkE#-g3E_5cOl$EB+ zySON&E<{G12_rmV@~%)NmjC)0aAAYi4YkHHXyG>{xLbH{2fL}G2$jc>a?xa=UsS?f zzcg)59=ml}$xDX{Lnp_#uZ;t&04ACj&+DQiHkeaUu$}Nkq+pac=7iwfN;?Xk3CO$Q zadQw(ifU)v8$2-{AE}3YkxcPP=#>a$cvw2y}>G_`A zh>S|NJqDzhdlL)rJq6(RL(wgUjx;lkB_T+k)}0Nxe81w$2IES z$MG%Qx6kG4(Evgno|NhH&=<^sb~HC}CdO|wrc|V8I@f#z3J3cJ07);)lCkW?a1eiP zxOqI5SUP{*_=SD$$aeOovSFwVM zhf@6@A8jr}$}}5uw}Vsm3;lh~Cbvjh_sU13*Al-H6ONSieWSe1l%)j zS<^8&Yhzc_g_Hr_18);@cec0m@k7RRe=9cT6v~F(yV|JKdp&J5dif|BD= zQ2n}Q!lDEuJZOAcsTspKDk|(jaqg=(UPJLNH9fa)hdyC)ih<#|^WfBTf9bqyWmK-z zmUhFd+mM@O;X9WpTGJOX<=}{Q@_Fzy!y;b+rG4q~OGJY^DdEDVFhK9bwgePDhr@hH zR;@?Wa{c^D^5RJ!5}WKR4XZUSWW1i@U3x1-Z-(dWqTVqdB4FcEni5z1{l6K+;@UJN z)T@_L%KDV~n66l~HShd|_UpePOEbOi6m+*)tFS)E@0$B0p4g4F#`63^kc%Xj>rqDG z)%slWA+eq-I9lb=hbH=p(H0(5&Zf)6-NTOJ>gvjgfuCUEnD?_4lz92>+$U+oc_LA1 z5$&}go(gntqUgUGmH}eRiuIoT(bwOV5jGVtF>ESuugZkcW|eCym~Q>R_GM3e_^#-Z znDu#UDW!WSI9U3;a;p0@f^R|MSI->ieDoG#B3=b3`igS_{KwKBe0j<=g)e%oXzWk* zFE_$^^_%C}<2I~6zlzz>8)>;=deEQHeUB1Q%reOi@&qz24OKaNzcBsTuO@P~X}(@$ z$~%a~>u&ptMRRfz8xOGuj761rZ@%Z`B=^MFP(h$d}M#=$AWK^ z*R!HS${G)LvFkFR=nJ_k({q31+@|x)mW&|WXA-Qv=}}o!T36_?x_wT6wSZ|Z4Rck9 z7iE&DUb@3m*ERlCJ(+j5I=Np=ujefbbqJTJ2nzU*uVXc5y>ADJUAvgCAZw^u+hn-Qt?dqY0<1pLiZ9EY?c`0+uk_Lpcy2AxUjDkw_*OWg( zy!9u8JEe6q7+^pHK^stA=;?vqA0fBdMxifN6b1V1rhN(XC?e{>7?elH+eZK$G)p(off&S#cNzm0F|&w1I`$acPaHF)%P;;?B@U@v?fh zx`#&{ts<=ckOg+lf`sa$;xtBRk$xyY|HB^;y?qZP?bBxBR&B0D#Y=Mym%!d1p>v4p zGs&r-o;5Z|d9`a!l3n80f#?4Imd2>dCUz1(X66#t%78l%T8|5b|H&y?r6Fd8SR&ME zag6Ig-E(ORyPX4%u9qOSvvm9iA0?MX;ReNUV&hRLiWuf_*$mZ%xZ<9_tueCL7>0U* zCFzmnhbM}#eY>kASJ+iGx)}(DF!c3QEhsICY#_3#T>M^H{c*$Mrzhf~dtf7g015Ky z*($1!VrlL97#@G=Oub!bZ`gaPOu6<2Ih>cA*$7^CJnM{PF;~5TBLbvn^8glpk+{6! zka}bUOir8XiBNqH+4y5F=hU)1%>{7&G*T_QMX~JYpfF?1=F8vtN}s)mh_g7N_gU*0t|#BH9b zr22i5X z*0vHg2Za)KUD!6ei1+%Qpx6=d%i9|dNCx(oO*DYBcABG+6Zg-gS7>4nuG`Q2$|swS zW&rf5W*;?A6(bmVu&VWZA7wyXITw{|)r#Gp+01iHkdD4x>0(<@-w;@4IHxkf!?p_7 z?PPb3av-bj46W(~m#tC0DaB$*<^PQ4LJ=&guTK7^X$j*qFcfNq=7rFF5K0LRJ-Sah z6^MHaB5VP1pGZf`B#&|$1+I@yCj{<=0rvUOkgWVrufW=5!MwC3-U)phD z>FMI+qD8hQFEG)x0J=ymB_4}gXp>*%afVf+3dXykijh`f(4%8=hQ6Ajpl)2W!q7`8LzF}tb{cfGK)nCAL}^4aCON|wC%Vpr>3vVQ!> zw*8xOGA@lS3XGY<=5qc3*vUo8oU)?b{x#=HiDncFTz+A5@h|bRACI4ZRIz&eLr;Kz zWtGwm&&znDCf6lf;-d4YK@g!~n_mzFv{kzl{_;`i7Inq@>El_gbLByjy3zRneU-!t9jyP=5&)5XvoLh(in#`gP>k0Jtk-$5z51a01USa$u z^lcQPp`zwho)*6*u7mb@bKPs2Mk4RG+8qoQA}8&Ng2sU6j$Fv{!b~zN3qKjn!(TBZ zH?wGNOo%d!0ZhI2E3yB-~c@t6URZ>o} zmu$(&60T&VV|i?Ujy{fGFo$3LR?x#4?(qDkdD7n^Q^B2?FPuS~r{+$p3-4Zb!@GIW zH{CLdmRFCYu=cW!KDA_3e@@RO3-2j80=BV4!4IynGbuCtvs=guv4;w+srj`0f#!cL z`azizE+oocF`kJFNq-pGpDrc8UGM1}A7K7z&E+Edun}h@i(%5rcT2lx<32W+BjSQM z4;0g5*LI`x6+G!)IgNwc^NjEtzswJL@yUc9pIgzl}+Qvqfe)h%6TM z3V1FoJS673*{{c$TG@?Yk4A#LLB;?g#z=Y*fC?D>IjenB@!p_@3JTP<|D+4<#N^&R zZ~Z5e8Ysj#M6Jd6RFcY$y}1NutAlbDHor^8dvoqwRJ#qsd5{$atz|>MyUE^WgoA+< zO@UF-S^c0aW9KQU2akKRPCs&j#`xcuJ{PUqTZ}WOmrX0}l+IP%{PF7@A$K1%9lq^R zWdaZF&L9`A+Rg_JOWbH#!aQmb0H#H9ur1@P!Zexq$9Kp*$IIqT@)gzOuc>Yx*YKyg zq%#oL!;yYKu!rf}klP!$ilmR8LWQ1z^&j(gdz zYXkrI<5zc%6?IjQL*c7EKA99&zKLIlEcDT;ZDUM1C&wG2;e7{oGQedG|4`39LwDr> zpIcWsOoI*QZQ`Gu5MMyJ*mRVNS4bahpu`e&=ObmFE{RH1#3`Laj5*{ZY(xCiCe^Yp zEEs|q2^7t+4R3&Ey9#$~#*2X~X+%x~pzWosX})05`u!Vousk>d7pnYYGY-3aPGvvS zyZj=n(fD9BOf+Mi+hO}n*OHxvHw@_=gvDwBVyCb4IDv~IBWv(+crCXO@JY5D9rX^%sxo8?-FxoB)`sU= zK3h`y0kXp)B+Es`WMq}ugD(7}&r-5o-Xp+FdXgIsZzTiJaMSbz_Jokk*J|G$ab8vj z1aRsHJ&+ILeI_q+nC)-1ijaGuwAK9TDD-@MGk=im`3I!prjs+Np4jw^R}=EM;6;9w zjLO%mUw)32VnVB4W%vL2Wa25);Bobk{|L$;RJ&SX$-1I*h2r=1Ovu;SkgugYNKN)L zf`RmGKWMsIm=mAOp;2iL&>d=+CTsk&uA7pGh?U~~ED>$}-k#rqJOgi86^K?uW2=W{ zY49VQS{EgdH{%@p@f$ekb>!^xn-|_ra7&+F_XzmWJ{P`)bSuHJG-)TYSY-ZtY6HlwC3Chz7x!(!@+>?zqEx2ln3Q{Btk@k zf23SJfSJZzQv|FNq!87D;5Fr$Fsitp_7qSs_YB?}nfTfejhmQFHMFx$^~0L9 z#fG#6+q5mJi9{qR&r&7@?OAQPb<%IJ-^5qFT&zlyYB2pd}n`a z@tRVlIEZ#tXRE}P%$|*raI5gnq$D%qo95}>`qv)k@0)cz*&@F z^s&d2oty->7lf!^{6ZgO#mi^^7%n~Ks=@!RcL$&CsHD+aZqHjX|o4_`Ho=i1O&%(xT&sIs}`vcPVm2h@m^01Yp?z1z1^ zw|!Rl#ukF`>3b;%-2%#(y8^#mfM!&8yo-gcM$do%KCSPsGQ_}BMO|MJ!eo?c}(1EYvUJi81D-Q8pHJAmr4yj3rLYW5csR4awP9M0oOk!`M^V{FN_?I2lvjV z;kj?-Ko6C3>KUPaZT*cin?v8mI;cvu>lLKt<$^=`Syi5Ir;t_ zef)2tuCuF5DV^Vb`-A0`9{|s86w#3R=;GR4@?lvd7$|+agw^>z2p6P22e#*;%*Cl{ zJ)pInXP7kCf%RHrRap^$n#UrwtcreH=LZmw5OW6oo`{Kd?r+pN4yvv7m@$x#uWIjG7lE=HuI zQ|?t2y2tlu5!R67FL#`OvzW0O9&|jH;b*Ia@lTFvt};NiH07Zk~N0<}F`(o%jyzhg?1obZkhKOl>oZ*5J=ORidSePz%(E6L~vE5By zdPtcd@i{J)ZML_a**!1j1c~_$R{EyaGSyK)?!w;E(}IyY;0#E3uVDNl4E5LNmqM<7 zucW@+rtf8s70hj^-qmefKmvVclCg_Fn*8l(ka3c%qgf0H_JoVO5$D{KN~asB%BJ0 zg1@#$Nj(hSHVe8LIu=2&cjr=wpupfX!LI>Z$cv5?(z`{v$^MShiPby6tpSUgUg%%H z^P?8zFJCcuJPxks^Xw|;VH*-?C>@W5j_bgzY+r0n6r3XREH)?_!TvLLcT5K#>EEnV z-+9K|H+L~QlVLsEv0!W|v#3e%uqOpv_=mv56TIHs*-^{GEl_ePJhYfq~`|qMOZi%a)5XQp<~c3=+EU6e|bxUG^$+ z3(q9g;&e>2BYek@@VMMm8wmyw)9DjOA zHR=p2P_Y&0AR?xj@I_T=^8DY<46V|FtsU)7tupo zKLgW-a&`wVur20!N%Z}PtI|dsfdS0OnIv{Bz_x29lK7W;lPc`nLAUB9g(oG@1z9*6 z)wQ=Ffg{p`l5Gr}-?h9EDCQJX)Goq@*E1@bTs7;po-F+MG_?6aq(j#7lqr&A+e(!q+^{9v$Zt&G>%z^Ds6tQ3jO3nn`r7ty`=~uxarJ zeWoGG@|JEAij!6+gbfCoQnH#U=REAeg=@RgufUbo5oiC1!5n9{bQGS4N@y!2k?za4 zHes5}9oua61t!H>30OfMb^J@rZMGE$_FhGi9%{Q_pqn1XMY1tmQZ!UJn2%jXLwL4p z4pE&&;**t@+%?6_-sUG)&UEi2sD5P6CWe7QZ@k@bH-9t!aVf5}g;(*}y!OTynyuvP zw4=FiHJ5r<1imk+E*DQs9U{Sh>lZ;ur(PQ$j~lhQWxvqV30{5Jc!J{XhQbxt&UJ=J}FETGl$5?`?qink_9Oq;*DWN4xXA?9c{>@sZ+p3gB45)YxgWS z8VRpzd}A#StM3lUSJreZaz9C(&2xMJZFMVbT%`aS5y1Fucge_2TzvmLES+u%s2z874gqU-KoN{g9dx=A3h)?{X`@+Oc*QC&t2W;x8- zGBU*xozGEvl~arW%!*xaYLyee0NYdC_O~ z3q3TdMcg9+q%t5l4U{;jhdQqjUE1jV!xA?{?H-7W*2=C1!C%*j#3^E-O&l(1!TjVE z$t*6j%Um$zqu4@79EpUQB#+5$-~nweN+beotuD1)vxeDP>k_R)7Cb+`@~{DYRx)L5Y&Nk3L;p-lAwQt;%){bP}7z&B5RaW4=G2H`)oSN+1gBFackv+d` z#^~Ek|7*;AU$l8rKi(90F4F{ek@;99LE-NJ*}ToMci-z%{nIi{cH*Fx>N}p8T?vzi zegTf>&Xw*T$>>So3!RZ>hdoAr(0u+qeUJCw?K`p_>NCETIXc>=ai1~V1OE=h160^J zoD>~XZ2cQMxHt3kJU_+gswLbrM=}Xl`(ywo(X6h!N2Kv$nYGo%#@rI6Uwue>?PmBe zcLu6gSCf-$U6kYq9A_O-xfh_=6MZ$`uG;Kctd-y5RIAr)HtQL_Ysz}~{Hcn!hDLz7 zhOOj1|B{4#sPmeQmXkMGfgUne|6W!RQ66=GWo~(>^35Rb)vafgkP(^_cU$FeCMOW0 z&WgrsBfE@I7Y_xU9t4&9o$*sSe;CN)E&XVl{T_iabvW1@FUBYU{S1doFL{8TvL)k6 z?|$0M_kE-uvJV^HQ{}$?*GIp+1H8;m&%iy`ad(yjDnKWmT1D6cxxa12uR!1 z{#%K#l--mHuVq$;RL7?BX>+{1JD)nLtcR>|9mA+7Y-9$Zep7v$t|&nQDq+pP>H}?7 zcJ_09YJQ5p4Tv&_9!POy2c93ku}LqeY;U4;nT`&7Pgq&b}UY)-_3ciVmxOhX& z`z^@AdU0*=@%Np5smH!s&v_B9A|El(N8NM_yLeJuIn%eX$hZ|X!P^TMl3wc{Hrl*DLW(Yc3 zYWq!z@p2p>JOZE*!ahuR43?}mXLQs^oq3u+Wg8MU)WeYp zP##&Kl6B^BMILxVzca3V&#^Pd{hI@Y%JU?QyadyKiBa$(tUn@e|dSqIrCf{`%_+o%*R6t z#X`?L)#E+}4a!)!@mc}*<-28Hf%oL;;Z-$_wZv~mZrQb6jL(dWnm>gIEu+A`8?lzR z-kffI(L@ghqbS2dSYukLE7^St>N=?rXY9(?V_;O%B9JNbtd|?KuCRUmCD$6;y+X|< z)~ScNy~({zy~XQGf(T=pkd$>-gV0?nlZ{)yWAimQt2~E5iTd-4pG1V)(h(6Z!b341 zFnmJgRnl6A2aH7BVg;7dYbEgm1@v4BD3UEGnoHlpU&t7C^YM*w=>BEy!Ym3`Z3y`Y zDzxF7w(L})?8F{b3YdBtXT?fsjLRl^l-ziJo@ViqN-pQLAvl@0q&(};YVZ3fzbjPD z$iR3HT&Mw5!rKuqLHl=O4-G;d>*lWbtrz2b(6|*b->0DDXP<&xP4;KqyO&Zb%p}}w zSk!SB3z%HVL&yi-#lWBXrr|w+ia8iJPJy#uJ%nlF%T+X*)4pN-ke3Vu93D2lH&0W0 zU2J2h_5&`|h(9YE`;_!1+&cHRniKyuQ(A0+5zCkCz6vB(pVo;-GR?*N{+*%<+_Qod z&*%d&FETEJxA_`R2~V=s$Ba0$KJtv80_Esmk2BLXYB5(ItE2#Rmro6@Q>?b|YmB)~ zNe$vGAST5WYJjAgA)@Hi8DrM_=$(#v0tVw0 zBI(>K{d3V~kC)eZr3*7@j2iQ@dut)1oGB^94?4ZM1+yyt^$*F~EQUO?R{%YV$}N=y z#frv8+{g7c{oa=2Ew2@M@SZ?$n+yHW5|E@QT(K;Zm3HHi^D;MAEpVu4$`G?C`eIjq zHcyAUWOE7X^d)i_GaVniUS-W&tmk6)Uf~AzDqLgvz~g@*45YvJu=R~xB2Pr$DExo5UPS(uo)k=Gky|gFJ4nY2fM}ILeg7jRu#a!$%Qa6%W z+gmoV%=4kkg_qFMX1#NB3*TKA&_lQ^-NrPn0c@(QIhB&X^rf4lEJAOVXwXa~;^8Wp z5+)NcA|;@7frv24B~3`Qf)z+E2z%lJR!`}-;L%ZxVBXlZpZ;1GWa3JG0*M+WlzjI z7kcGF0EE8vZHA9JAH{gwS(7ue-LeaR@_Gpn*2q`_G8Fi=LaC9t)*Vn(fT01G4sU69 zySBem&7bizuCST5)A;0k?dsM_`O9c`ks28Lzxuh5;AjImst+KeOi2FR5=$fFAtU&U z+KoFO9ZEm+O!Yl{wK@(b}v>(NPi!?|c>zxUQBq=`m*Gt2C&b>BHES)LZANalk zxn}^h6g(l_5lc)R{V~41>gSQ8&Hcv;9Zf=%(&W-JuUWKRIl)HG*UXMND0o&6;E1 zO;I>2h-IuYAmvKV_w7yQ4QAlJ9rXb>nsV6s0DBoeg1I@Q?2PB_l{Z^0D^o8hhmulh zd5)v+@!W0c;zBs66m#!$`#pXCA@00wmX}ZLw1sLqSWJ&AKe#t_>g*dk#65;{{gtX- z&=FBak2yIB-~HzBqMHRn^#wkoFUscwUjIQ?jo$L>f`!$4^l8CDX%V&U~*=V23%&;1E9rQZ$-xCDwmIFvBBI?UX z^$|nkWqat4tGU<2Q`*3Wm^d&NoTipwjnFJrjl)=X$kSW-Iuo^}c9AcL z00+}^GE@un^>~j9J!y}P@6bw*E>yKmV95c9uIRZG?fIAEm>;^T#o&K&%jYqTuCpXO zLz{b*X&U_}G)(S(-l7w0kn&Yvas z?<(e-=(Vromrw5l=R#*+LO&8=Y3wQ0^|jn)l>Hqw1|GJllFfW_jg#X+{N#iaV#2+; zo5X#*!R3>qbBtL|^JfNQ{8!6Pg1258*uC}^?-JRT*^%jH7_laG-KfnvjW1fh-?A1Zr;%QXL>j075*zhi(aNff6DgY?^AoIqpe`b~YZ^7t_?T}7SEy|Zgs z0xDTwKcmq2Y;X>6C@mg6*F7Mpy4}~W0Hs)*YCDgqrRphxZwh_uFsSl7YqdJbr{TBP z2k7;?mC(L2J#j}P2P>-(u(tz_mbx;@M`6+`U^9p{-;Nk9z-G7`hx8qAo(!w;%P}S) zsvaA-azJ<71*`1)0?XrQYjn&`p;~zc$it+yXpRJo|JYbGGzBcNuV~r#w^?-RtK;kU z{T@TZRN1ID7g*q+-a*<}wSxOuW2gnp#OIv}LDa|)I)CrN6M76XpMA~+7((9w_ZY(x z02Az+5Lj5a;KJ0Z#`!fFVr4a3wqVd*#Q$_(3pY>#?f7Fm)6HhN0iPIf3B;xZkk=lr zDXSN218zCmZu!9bvJLDg#eDIk>cxGC?UWZ+u6ydn+#Gr0e{LzP^2U|p{6?8lZ|^Ri z9^*Mf32p*khU)sO32%dZoOd)N*ptaOhFfWM#hH38IqEE0_=;yX)wXM;u{Pe&w_W0r z!q*Y^aLGo5iQ}Y2<9K)?b2M#C>p$Ku1HqA2(y=?2g*Lw3AVyX5Rd*%UT)0`C8A_nLOncD=mI)i@&S6wb{BUc3qD<@WKOnd} z8?lo~XZKgj9!H1{C{T_fJ;rQ{m2w~<%zY$fS>=x41{ehJujQ9eRP(J44ebL@u|7cp zn0Xu%67HKC{P^Iu1uU`g(KU;;tOvii84w+Laub=82(xL-bpfTnh`44wuslQ0(kTn7 z3IA77<<^Zn^!=g^PKuwO1-OFA&d&;fHS~&90ZOEmaC@r!<@Enfd+B-kDZTc-#j6tH zc(zpQ_v!XWSsR@df5Cu@mfU$c)ok%sxvOhxJg~gU7FzfNfuq7eI&XU$zL>Wo3hFwk zUsf9_4de3!5+98V-z=B%wNHTEN`S23Dfqv9X5Yqdi2+hj{B=MAlDGO(00DTcODc?V z*26qwWl87M2G{M1#=F#^fA5eZA$WAekr%u3<54G4U53J`t=>~;;zcpf5T0syP|*Hz zi;;?hUjM15Hc&+J5v$60(c&>%#z1z|t#`$XjsE4&AyY%oFdxJgrREnO^d}gnQtn%D z!?&c8{Z-u2rcz-hGjduB2u0DHfe#9SWh_BwuwmHA(u>RCeW5yK6eediBHNmR4`6CN z7Z(6)>BErF>oEjFGCsGxWap+PtfO<>4~g}DEl)%!$H6+>pm7r}F7blp5Jx{ym8gRv zwXMAN+WzRea8J~izk)62V^8LS1-*VV??L?_a4EvN3O^A?Mb`Hs;LZkZnKf3F-SOAy z2XhJB8N4?I*8R>a8aL7BM1})97qB|{PVS}8z!?ky&hS7YXOlf<8zM+>U>mP03c4V+ z^ov$)KyA&re%e2@{wF6jT^+4U=1ubBwr48^9LNd+(JRD<1qt@+M;vt@??GlOD2q2x z<$a>dPDu$7XCwD+nPqY-ej>aWeM9$edY!>f{O~j*EnN2NzgAV+QQ*SJ{+P9X&~z37 zO6EcP*J8J6WwciE31oisFVz&7aiYtBF9ji;-yx=s^w(sw*njT%?a0%(M+<2Z>}bwx z9UGfZU%oyhRpHnN;P*oet?G+;UqEfUW~qnhOVA&J5->zK7Yi3gM;}22Rs?G0)t5h& z0sE$Sk{V1$YsF_R_&TB)Khz8HxY_=8KYrjAZ)sIn0Iu{=ECPajl1(77*-;GdW&ENjdC>CHdl2w*@r@h7Nu?vC2(qhV?{h0(M= zkZ366H!cVBStqtR7G*3H`u8T>m>)Z&K!VNjYd9XYz@c^yq`Gl@uC*IP*RHpl?!x$2 zQ0meB{L&TgCs?2F;Qe82+>|@Y0p2cuR7B%P7BX*61wE)T@EnEG%Cv!L&;EV|6Byja zc?5T{UdQ5vJw2p@gON2Z0EW(~E@PWRL~5DzyA>oH{|d-9qRr5I?t5`3>hWP!y8C1{ zRjaZm4vdzT*32XjCIW}*v;0Tqz20%OdC+g&=0>hc3y(3;yUVeWzxj>nr3R3+P_aj& z&q7&p_t+L*{gXnZG4JK`^vk;lJZh@H{?=f*`5&c;)~YCKkpPrrwb_X>44qO~CX#Tlvs2?Yf6TwYa?~q9SiIJ)(6Pe|+NA5r2x%U-1C}Flv4J zf_r_Y?qs?bWQ_HcNBa0Wrj!8hbDcC2XzxC)m9ILs2>(wcq8|JMD$m#B+ljGLYg=(R zjsGU(WCQ#o3s6I%*~xx&7ZUaNcPld18=1Up1&v1H3PVmPUE45(?Ug|_J2gm18(k-#=GbviNA&AIHxGn|8##ytZw%9NCK;G zWwq)Dw}BUE-vKwBoJW>O{uH`ZIRATvs`?OLJVN>qpQ_ZNDokX|Wg~;!Z%4yBPA3Bs^_tZQE{(tRzUHw%T=;_c6SC=9~Aj-{bR!S7YBx^Iu!v?hMlI2C#I(f!_? z7YQkU82*w^ft!+&lNT9iH*|LkZx&coZFRpxNk5T|h>fid&%-o}!79}5T^aur*6?nh z-|%i5#U0?ZE35I8&>}RT=;_1c$%n9V4dC>c+1?@TKX+DI>v6E!_@~Ts^vq8S6CqYl zW^#Z2?+Zl^bmy{ggr7s4KnB2O05!V7d*G{fp<8+Qn-Hqt`4K#|fVd1XgJ&zlJ6RUE zyMfB(ng?3mU@O{BzQia2OjP%W95W>cgGAE_?|Y5%3TA6Yu~%JlnY{5K_`RTGx0mPxz%{p-|~WzpqNh zx@h>FH~2+@2?^IT98_=8YF0Gcg_+ZHb1Mvg6RcOy2)mB2%O{K0=M0`1Eac)7#m{DATWlnu52)!i9Bb*{;rOPv{I!-| zfS0$EMNi3PGuq#0H9RG5`C1xk_2VUQ^+m3q1$yxd)Bwn_)jnAa>ODgP8_1kp&my=Q@4N!(wl1o7szR>lLSC1iEGYu0U!j3 z+W7j>zh@2ymg%l!wNXVtQC}?)tnq?ir-CM;zpUGfA>{+s>7_KtJ6yVcv!#?6F{b@y zm_9$#L_58iY#5*Txqr~VJ8+Zw)~);nTY1mMg`%5^LiSj`*|zM++R%ftG5=gPQ(*Mc=Sz&E0$kp-Y?Fi-i$WUykYxZnc-3?(Fh)#mBadEASP_%D@0| z<%1@CZZrKi*?G#`B|l;yF#82e-sObv@$^`(8}L1Z3<|VC*14#gO>E%cfluRV)a#5l z9GCri-E2kye-Wa2ii{OyWky?2p(=+$pYLE9@rt61PTGv4tC42XC|2AP`F30}f+&2+ zh#-+l^@Qo7AM7+W^TT$FSHFf#nghYd9yq(=wKp^G2a*sb-?)*=mPoxLmO#Fye_^Jb zT;q~O2yt1?RuS{uvu~QvmSc?B1#Yp!A$w6t%AKUR*?uLW?e)m}FL&>G5(Dji38iol zY(-Rj=|XrY?k5Dq$HtmSyd~E3!$7cFYa_DaU4Jz`7ScjVKnv-Hm;6jKgq~Cj5)<>{ zT*dXKHM{h(W%&g`>%lB>Q(gtyH0guN&dU?D!;kguwdAljokJqnX zl{}=!%cZ3D&EY2-3c+yFD`(F=5L@&-GThGgiyWh-m<7X$ry9y4a(L^pNwx0{#RZ8d zl{|(8Jy%FOIO1df${tZ)yRoH8+ah0Q3{nR^bID|1I^|hz7LU|V#SocyvnunG+;{fX z5Wd3l?Ifif@0Qy_v^FJ;`HbR^$%3W(hClrHJ*KDlg#xgeIk|$j%{Te>+fsD-tD#U(PWjDsNimZS({6rpS`x1UvOE7P+b&Gu zi!VmPE1ZTNP@DK;x15-Z?TJ^@4K=_?$V3*>&~@kfDyO}fPJFTR%&Ou3gGT8l$FR&| z(Rv|+Y0C)WsIT!k7V`-n^TJgr??lUsE@Za&9=plt=_0&K9)>I1Pp_=3EG`;be>wsq zJB-*kfF1E|7Ada@MrEY%Du$VKftNOACzBk@36&XQdW_2^oOD4QwzXgQid^0+3)5L# z7=S?ZJDZi|V(gx(>Wa(;)-u6C0`W(>+0SU(@^Y1Wr%Krg&nA6``c#FcHe~Rp&fo1k z&-T_6TG$EM-h@W{{&S^;?0L|ubJqH2f!pTTK0L*M4@#a{5DGnKPv}j`LY<+d1W( z?MW4n$FfvX^70s~Ryb!0PI8}}Dk%JD*qoR;qPO54gB;O&P0h^k+=@FY3T_T3IuEYh zcwjf*e6`=pQKJziCqZ%Q=1^~|1a3P3{fXFwU0kP{1^>L)eaXVa&T6UEMhkmdPZTwF zSXh%f9JA7mRXiT|(%?<#SPXuZ>2y?+j}h0n65nw+R45ti(_#c2tx-1?GXw3O^lOmh zvv;$6^ZJBxOe0Coc~wr=hi4f#iCJ(|3g5~fwIZ+bUE!7VXbU}%&RFajig=&tXZipxy6lT8(^@s1Q$}*vF zJ11HPSZ2hRRieF3M&{MYP~6sM4Z3M}v&OBbx|=n}qx*jh4ws6#kmr$QIM?V z_rcU&4%<_y>7qfAzEXfFGvmX}|I&pKh0iN&L9VBAkf#ZH~>Pp+4-SUSf|t z#U5=Sw)A77GUFl;+AfU{gxHDOTF@GL-nKB3t4icc!C67b7rta6TdLoe>@H$iD89SqU*?{Noa;D2c$4V?`G1(dxy z$l0Of{fk}Mt*`fM^+0-gs>)hAcYVRJMe>{BtqreqpMPiK`I=!jg~9MCp8XfWXj37o zj5N64ez1pO02>E~0TBN$C~kCxKiO_KzT)#YYJJVy00Ysl)&JVEGZG&i@!5``Yq*#? zv2NVx0epFVV}mij0+KTZZYaEpr!f+cW;EX;v}mE|Na5S~1z_ z?#-8RV>(cfXi+=_9^{TIE9$%w{_*gYr`e2^L(8F6Ybf-NG_Bx*Gcp|{QIex3SHZ(u zv<3A&+rDyD2bzZuk3I+PA%@UoQFnv)CbbCV@iu#d|;RmRM5ZeFD+LfX}$jr&n#i)25b|B8q2VPkZB-`%+I_ z2YPQ>e`0n@?48!L-2R8UO244!0xq#QUNVP~*MYAX73jsXrSCs25)6V%t?!$def$(rBJexA{dO1M%n-M2`K`6*<~X_$2>NniiH)M4NZ|4KCXaO^k5Tk$JRN%67p`8VA74D{vfC@w#~4deMw7vUZE$00N=f7^tI4$Q%zto`CTzi3?_cK5?M zyJPx>23VNShEj|3Y>}<_eq;GA6Z>XA)^#ZWN$}=++FzEtZY!L8xnM^rGEebG_+-LY zF>Nu#?nhZjbN22vOkjU(tT8Bv-D;)z{oIxyIV_nyDqehXII#T*oU>V|8=WaZ*riaL z1>D=VFdm_4<23aE=hF}LNsv(53(`3z}iNWG+k{| zW~CJ5-ax}{eVgSgov}S~x{qxZzvXVtjYLCv#j5twZ;z9KimC;Z>@OC7FMmAIzb2uh z9?Y%q{f*0dv60Tg`CLZ!JwC~nmc2Y29{h7_D>W!btspb8SIC4a$t<&hq6S&EiMQYP&eq*w6E^bZhEJHzLUpMG?sM8G^t=c;jA6 z-&;&;Cg?^-Z_6Ut94EB>ZN%0(-sXvL!hkrB0(qvsE99Qn7)C|#$Do`Mg|>DFff*4V z3Oqdn7l~c4N~)j(xdUynyFPc4cKPmVFcjVSIS#A%Kz@<^*&uBS7E#9l;CvkIoA&)efk0jUb@NQXt3 z_>g$!Gif2@@*ZGp7ck5dp>bMy?ioBpYt5OQVao-q$P~X{-9k@cknCte(07n2%+RlM zszSh9(|P$_y)GA&y(n5X|Ft`hdtAO2+B2 ztVgSywtWq#;35BlI{Yjnj_^Tz#W*1So$bwm;H?W!2i}nd|wSOp02T{5y5{zC>v??|5iVmwzifwTk&Gd@a6Pg{HHEaY~i`6zvK!HzVmE` z(MN1BD-t%C(^hE^$fS%ZJdJ=S5mS+IKfBCTNYG{-hv{wldU<-iCq?#$b2;Pm1Nj7m(Y8PE^k| z9nkn*HU3X~9MVFE=gfhO46x` zx1YN#*XqnXWZbuyt)RyHWa>s#+Jm(%@^A;gw$d4Pw5I-T-Q3yqSlYLnI=|89qFS}i zbvqe#69Q)wU!P>KD>)FE=5m?CzCydrDI?g zf4<8Y>)w$ZgHyfk3j$kihLqn0n1?cQd#hkB7t44LjyW)$Eq7ne8 zm}8B6_wfPv9c~t?y(^@aD+boT{_-mF6GdsNg=i2o*=sDYw$O*Dw7`XWP=v4gb9wWI zVr1ULU?G1^&rGK}H}Hyop1iY)E{V=+G7R$&EZG{2=*{>lE5LT4c;~+MD!NJ8X-6Lh zo|zAcvPDldd>E_pdwdZJkor@5E4M|DS-NIMGUo2cnKXQ0pIZtnxS?Azmb;LX| zW$Xy%NOf=nUy#+L9D%n5$&md8cUwGlD5dTIx1}E)_JvUjV39v~TomBZ8mwi2Xs&sX zZ4VpAh{I%?6<GK@Rd{@Y%m=Pa|EulNo@7d35d0E;q!#G#x? zeBCA>={S&i&j(KLCOOfp-=!upcxiWStokvO`_5V7iNn(#M$rI|`oEeaH8)l+O#CC7 zO3Tz_Jn-U0h%7zjPI(o}U@B&6A|Mp6P)>aorW9aK9JB9GgYkDYauZ1|_BRr=)FpZF zMKbEmkD?t8&01=_FJ`}h=(7L|`g5mnXmGg(xg-58UyC5{4RkBuYAQ$TMAWkas=9Fv z?y8_+Zte&wu1G3Ii_#G3?4Ca#i?XRFsIyWO%Z?<=#qG2AY#shqyIkK|#~0u!+Lq91 z+gz~*->b}{j_{!!?h8^ePxLwsZ#0pzpMliowg_CIS^(BPYpxKrcUfhq4W5TT_Hu zbWs#t=N``Z+k(;IVZnn5a&3Km>WOofc9AO$x@@26bM#GU?KgVhMb5NT>X{_UMAPm_ z!2r?CD2G#bVBcA=k0|qEU>BIhb25&3xiODi)x0`+hm_SCbaTALFy0d?Tk52ivX`z`MWyq?ZHn!icmxfk zb8%0xod31A^7BWL-F+MGR`WWe@7I0t%D*w)|7(jJmtmN?>8UCXr*!JB_o}dTK`-m} z8-cBllGTVnxk``?qwq=6YDSA8wLlg!;PF>}=@W5@{prp{A@XG&#Po|-!=kl`=`X;Y zI($-;6`VO$gAv;xTBfVU*B;BSPg+m3ntdg6=alZ;zx9QED1?o+CaKekv(QnmC66$B zLWgWiLa6vgUTRui)Maz*H^g;~c(L%q24knd1YAs|Oexs(W?p(2#aSqkq`a!0>*YCr z0x=3Y_Z^xGx2m#=AFQhJ6#dEfiO(G$srnB!>WxzvC{<@@oOR<+EKGL$PN6G8yXp;F zP|$N``vl@LkO)zvl*y3ns7RG{m3EaT+o+XUu@rL|TQG>|w}VLBuf*?Jok`a<_r5Xx zqi<3Wq%#!A!6s5a;bNaQCzRP&ND&KUc5>IPDyu8g&?Z*sARVHOh@EwsWL1zOjmAkb z$yH!w#eW=LZYC$d7SGVk(aZtUah-K4sN@rF_^M2^YH5wIa`9@=F1UMUMNb{sVLY_9 z$IYvl!;s?Ff$WOYlrRtD!xa?~MAZE-b1S}+$PpAk@RM*)N`z2mjKw<6bGh#a#gZG9 zjoI>t-2_`5HiZCe#i(Ae0 zUxR`KXzO)-oloo>P1;ZOV%RAfzpwQR6(DUPrxNxjmkJ&SirvgjN5fy+7fWT_7|&^| zgV?Q%)$~YbWMpp9KOhvGADJX%jP<$9}WTKGV0TLf(pUhjNE(&SAHCyXh># z>%{hCXBq(i2VsQ7d^k-tb%J;Xb#j%vE*IL4N~yC8Oqs4a(Bu!nq-CHVY7-kQ+C+ri zgi&dvh5l;7b>OehEZAv{wHE7_waJ(#%)b#l5`Q$PP2)M>c^)i zpUviLtyX2ZldQJav0fI%%X>6H??a6pm9)zXpXOTmQi|BvQWqld>KuQpbV(QM#>dOT zr+i$B{Wulq+0-}^tciyVKRK2GxC2F57#`l$iqj(51Nz(EO#)}$2z7&jl@^xKe*g6K z*N69xj_n|QgH7(ZUMpqUE zC=^XSJUzde2)+lvJyD_HIN_~rfr3YFBagpcRYX4B#c~#5T{BgujSq_6-guVw2EEv= z9x9agLOXO!SPM*`M^#i?&4}6DXKrzi$4tog;7G>k=40#}DSe6Eh8L4Pt=BEiCe5))vQ>hlFln_hgZsO z5x{_X$~P>DjP)cyA=3Q;`iYL1ZjN8jH-X_wXQ{*hSEcqUSAb)p7|w{oK_~G-556qD zdO)IhX33sD{wyAQXL#izTHdVBByEeVpb9&Jk&HAed6scxEg#>hB))|{;Phe zSHV-rG9;RCJ#?+#XOwt+wI|TxuD{`B!rb&kyXu(DgBHe?(-87OtsrbuKD&%53tJLu zZil!OND{deG}-$;5&(ycYhzL0r&0Vn%%9C~sPC9Y_?VyW{;;1+gitr#>95d5-fR@&Gp{mL9kQ>KM4)Q&iT<30NXDlej**R zI8;3B>ssm3wgha#-RHFvCm?URkHnKUW2bswlGETH+skAkcS3?}6|$enZ_ls}o-j}< zrwYE0y<~l?#LgBwHYP%-(m`6LqgG{j|4k@88EIEjRiU1vHzT@2==@FFr`?dB_^Zt< zv`)Vp<~46BfS7Am!1nnVa8=_A6qCrFrksLGk1LiD>Jr><1 z7D_P25wd6HsFlRl^bUUoi9C}pU$^1kL$I_lGJ*nXN z`+oD6&9auZ@Tj!kQaT+|;o~Avqx9xrlRrDlG}}4q?7jjg2z%Y@p#@@S-4J=c={3>` zCcbz=tK!D7lvrJ%U7arGoNjmjM~n(G-EomP7(^Gfwq=8#&KK8{^D+q@ z9`2c|#+ndFwZ|R&k;y4XznGApW=74i$hoiZPP=^3{oUj3X^s{kj6?1pPF~-l3tn#yH>F3>(fUM4KEBGu};b}L>1w^a-xk@8;vBgjk za{VN@Ek8Zwa}hT3|2d^+_EO?01b6yH5u9g?+^}Tz^`VIdp0SsWUy#3-mWW-KF!a-{ z&u-CJg7m3{a)9fm@1kYydT03c-$ygN(}^u_K;_&5Mqw-bAZXVFhTp^CQ?mIcCke(X z&9hcETn$Ugx!1_Xh%$eL)jBQ?k57TQHOI}m5 ztxwSP+18;IpGeWfWq?}MymCY0Q-7n(@n3({5PS-@mrP#NpS29c>i{@L6`zm*SEJEw zaD}rSjp{5BSJ6WZE{->>Y0E25uW+MyqyB7IugJw%dw85JCjf~u5Zm


!plsER_WS1P?J41NfhQ@d&Zw_i!X@H(Ij_91ie`J|qU&2p0H zu5`|KznvFIuJ)tYQ`nD3Nhv`erXXfi}no25IVMqO~@vW~b5a2vA}@$dmp2 z6LpBbOG69SsL$ekg+=_JpKg-jT8MAjG3U9l-VY_pe+!_hu-QQjtPNb8sTGyBNh8sQtxeL`x752CZ2GqA=WB zMMRUvcSN`gyhf=AT3AJKzTi*3tPonPiu(`ApFPOyjD~BXZkq`!GfpM^W%=sgMXOzE zQ@a;Cg-FOh=+^-@Dfl^@tFO6wtEJDEi#*Wx!@3y+2Pwp#EE(w^iE^g9zu&q+%Hb(3 z?b&6B)?@$3x}p>UfGFowSmS-M&^>G-%E)@&B@-=yjNB!}0vO|BJ zsWi>t+XuRSacoy_)_!WXzuUV?lgw~PQo*JK6{2gB^;T>BAk3|C z$7dROMfMkHkJ!+^W()utw6Rjd=C(ZWx;{*0Mr7-xfi_IlZC($6XAJ$vvULL$gLHQ) zwIoY`wf?}3sa%Hg8l1Ru5yLM<*?+#`B#F0KNkRo6ZynQj3g;9~A7TJa-3C2qVL(!H z@2%f1hm;t34nAD$>Db4}Prx1k(!~RfpSvFo*Z{-Y1jHri))SY7d$979&)mzdyM ztB02*Fl%)??f9V7$?$w2yR{I;c_^kNUB>i}TjU&9Jcp`QYEPm2*ZQG|jcH!EI2-WV7tkg4tL*-*WEejsyZkMQC@!6Qu`o{-HknX3s zHNL)KPd!tG0>$ZYoC_wtd==!{qg|-(vKlSkS;KQg(7TK5H%Y=dS%I8a?$`-6uTX{O zTzu8`#U?FRZneyHI8uK&+pMZVLN~-W`6iAe_rq$j+sAF+#RpNc_7z&_?THYcSvED# zze6fHC%k-8u!2WPeamGvx|YUgS_Ihst~*KpMN~~d{v#O&Aez^C-ovPThSqqzEbi+Db z7GzrODz56$E3#gj>^G4a3J}_56R4}m4DU+0eEE~BvaZs-_8sn**>oexZ%)s+UIivp z<)$e>+$d-)tpsO-3=kVvc)O+sdM&<7W5s3_A#=}Q$%;DK3Dd_sww2)X?%Jcdjf$K7 z6DWDM?NAcX800GZ9(vV%5vksuJE6$O4MR;oc zMN*5$-Yly*6;ezNiPwxEiXp9HF?HH~*Tb(&=;t4RJc-N6ex$F!csw{b=qHf43r+BI zzHSFJPrChK1IoW2s>8=p*k4mcDxdjX+ib5d>9wl_(Pq8XmXg^^&gZFMGFEuRZlr8Z zL+wgbFYf)JQS zouOGM$S+a0WhHc^)-s3+@^F9jNXk62)XL{;5dDX=|J4F4>S&m%$V@$NmQAH}B>B9q zfM_tsLi5*ulGG3hz?V4;hG!L@kE`~&qEE--{tnES<#1*y!!Z6heYc-|8M^jtk>zk4 z$dp8piMca*&LNdHG!DOS_@}HklPy5Q0rnDu-ip|1$mov}=0~LuF*aN0k?=c=#EvBA zJO78?blk4BoQ`-aP!o<>lQPqrtLAoDwvelp2g%E)FyX%bvXU3}J%jM5S+=B|F;fAU zX9EDY=84YQ<~l-daj7!w^@Q{ON?zsKTkY^aJ1mM=i!2W%osO#POPU#JGe*wSg@&&f zkgIKIe8gZQSu$H+<$bV{0RK zYl*Yq*KG)&7Q)-YT7OchsE=A0_W?8i63#`9^owYT&V(w>b^RJUSfG5AJ8XR_qMUf( zk0wNW`;AMqrEfgksXy&ephu+x9Ag=8B!PUBoR`5BilO&x6!{Opp*?s8y8{Brd(zu| zM#|K%uu;7VPSo{^B@RgQG5>!~^wynnR<8hyg62rVNr|+j$i5RT%xvcnI~0-7{cL7t z(mKU^zMROW(Z~aW-f5uS4MOQZTC2Ne862;w4XArC$GQUDf}Yl=Ho{BXKQ%}xdc5XE zgHjy9p5Aln&XKnYjkaI`e6Zapeo(jrjB4?rB$qthn_ba{--!%i;{OJB-}r432_R31 z($jxQBD65vf4}n&{BwYhDhImTLvIn8LzPUk|J9+9BraH3X>1`@Jp_P;a~l?^aDo} z;f)sf#;NNa^J)CB$xE8LO0FP1jT$@l6ox}!8zA2WVy6F|ELEe**kPe$Oo0Qa3lF&> zmk1PYk&yYHxPD;l!HN8p|E&NTr{urCkw+vk>BgP-H~&&Am0L$69;xZ$a~B*LYN@z(uV)g;*e6-Xx+Bn(?T&Y^1lep5EQ7$#B2NXV4M@Uu z0m}2Bh23YpC`|Ku%diXmYs;MA)Cttr;J^W=Yq>Ma09$Rm)UG_oUc?dqxuQ%gK^Ta)>5!h~a7+aV=k1Gbl7Ln+@x3!H95B$NC3BVC zNE`%^!vKu!)yo24?&&vwH_cs4Kf+OF(eRPz|D)=?!{Pp(_u(Z$A`&f1NRZWAi0D0n zgy`(*y;~)Etg;eGbRv51ZP$`uiJs^sh~9!A+UmWo{VmD+^L?K4hl}fSo!2RIX70IX z=A4DyEv;DGNc_EV2DF+TYzm+8$5~&+tD7-!+;c%4v1pnlb)d8;c5bZ6_2fD56D4_! z;SRUem5w0W`9Z8WiZtvIaS50x$&m>`@H2h?HG3674_|tEIR`+kRz&JU(-hWt%HY3B z5pd}x{8extmS%Z_e^5j@n2XYX$7SN{%SDs@)5BkOv^zvzCW*F!z6IVTCitgICdqUU zbfq&zUSj4_2-0-qz9250PT6QDiI#hY*V=FWJ1}Z~UYjD|;e1M1!*_oc25MSC%_w z?`6l6mw-t!hs*y1@NC^7q-zErSX7g~s?|L+qO!8%qft*zN&z$CQ|90)ue;ocp&by<%gR*|W zMt%IBS3^{hj!yk>4G<{Zxu}NInfR_$pUY_WGhFR1yI84drF`@Qk5YyTgZht@2LL|H zTyDi>9zkyQQ@+b{75HYM)T`q&wXkmBDkA7>R-I>fLLA<|MKzNRDCtcjkd?S}{XXbl z_8Z7>sip*rKXtA%86*UHU9L;%%3m@jMrU@91771tZ^?7MO8HO1_|>|f_}Xw;5&)Z& zp8e*XkZeQbXm_IK;9w(41I&*G2EXa#QPoSbnQ?)2N^TbF+VvRt@wm~r<|B|)3K8Gmze#+F*;cvGAa!tA58@RTJh`?FH+}s|2^>SNw$U- z=kwx}QD5-krGow@c(a^~d?3H#)YjI!$0g#m#rvDjjNU)n7v|~?(KA>c&VVVsU^pfT zBA+_@bop^JenoVt7fze=VU_phwy+5ozY6yUb1r(CPIrm&v8%A-?OBKz%?k58{N`OP zuF_##?r&wj!Uo}es`v6*1|ppwE_+cygdN`#%i}fEJKwG7jmCbT9nFM&mx(7QKbbE( zo**)9tT>gyHW@aJNt%ajzE`y7V#C=V*8OJLT;lz%Yq;x^FiyxI)7!`vWow?b-z8l3 z`q%p4iW9ZVPT|9qk01^C2cxaGbuO3lTee5B7=}IkmN>aD)K2)3Y5nexp$=IYT$#bm znO%%ff2vFJB=_lsAomZ zlawdKjAs($b$D1CsmV37JC>AWaUyJP%02T?L|1hGotHasx$;8f`F+B5rB`0B$}aIc zfJD)A>!8=jTAmL?yrwK4{$hOR7Arz0CSI;f(*8x5>z;#7<{%oAYiw^3hjRi*?x%!5 zfXazv+TBC?mLzKjUaKQ- zojMFmlBQM_GFoww%pSfb$E(Y>&8%>!L1D&@4Gi23#zxorLDpiLHq)@x25OS!i4pfY z{nNx81>G7Q!#hvf9~PQl3TueMlyk3hTxai#yv47@)lbzEaXFSt~5bfEo>uL=4WJ5$Pe971$iHY!)8;Qujbwl<5i@82HeGFE$AYG=xYF`9cKn? zsMwzw2|dhFMg{ObW51K99KaVGur~qolff)LSF1-I7o!(yOfM86iyCVUzMze@Qj;6e ze~vE+y1+M`iwVv+=Ot*zd+gcMp`Y1=cS(wynktOf?(vewg>;h3xVRo}L#jJ&?&bX0 zW@_Au^)v6OshtaXF@oO8BmeOJD|{=g%|cviMaU7-h{Yv;+jzcEz6?1`Y^8w6L%XY& zE|f04nX3ZFp+CFIojebWWhj9D#t6ful(_2LV973k4ckPCdf> zoJ%*A{Rim)A4+iP@ltVLv@1TXZVyDRP(C20 z4NkQqFCVamS%Dfhfn3_;p467ATT?sDswtE&FZH#j*-0{ZcUNg83|AU*yiap7E#u0s z99>jaI1_(Nc_dk8^k^z3gpxQkWW)Ep?@_F6-*`ekikcNTZ)aRq7xSW3OIf~qQJIZ8 z9E7mV)wJ%7=bqbz))BVdf(|B*bYd zYGZgEZLk=V>o|7wwucSb_GLYoUfqTQXDvE)FT7Ad1L3joFLpl$!IE^|Jhs9aMjuZG z4`ZLNaaUO?wYar*7uiYDO*_VQUyN2^6mB5FEP1%str1bi@PD>XLI;#Yyri4`%DMh6-{yxLm_$Wwq8#bD?nvW#OixYeLjB>z;l_$1nXOxM9 z4g)e@Kp&gjgnG?&q%`-vK?0`z%WvD2$3jV*{=_l+_;vo*UC~`TArDwTV{vTak7oYG zzZ8e)CB-p)LfUkZ|Ci$^f)zuL+PuqX+hRTmURmx}S~QYteiIZi?-2KSffSnxwjjBD z_bwy7w2w4Za)(RM$Dbnj^3@dN$jNU8x8!di(Xm3-t8m>tlr4A1fpOW~bD+85lrrbb z;`WOEVS1|P6XqKt@c8bCLTbJjs=`}~3&{~--ROw)ki4oE*PBZKg^VBh@~tDz<1_Z& zZm2rG~2Ye9@G3pAFk znM`X&A-zT$BocDth$pgzd|0Lii@vHIIx+L$Lo-C-bk`$>4e;>OBoEHW5Ey5;msUxn9y zbMQdr;oe~j%vgJ%7BqeKizwOsOqwz1DX_FTu>N>6oSwI!d%Y@@L6{))t5|{IbF8Lkp7wFwhOQFi zcY;}Ylv|Ia#=KE08y`YK?8sTG%7Y#~p506T$c#e`ELL^zELi`tqjFpEZg>t%GXgJFSSigIdEfUm zISjhYzN+FdH~f~k*sRVcx1gJf6PZXuO=Ck@F<~_d_UgQ&@QJ*`OOnc`5=C)c$spXW z!57waCr(Sku=p)jLWNg|TRF7TE1xd>x##wE;FMO(WMAaA~f1)zS#wKnuS?K7P|>B2n#*k@()w$@oM#!i4Dc|_{Q3ni%;tZ6c(VvV4R($6QFRA9tc;`fQ)f zj1i}!R7xtYba)A4AbQtHK3_C3btrmq=nDkfRmOv%Xz2DoqBLTwGt++{n}&gqzkpW%j3%9w7_H`3c#4!CXin} z`9X6I%FcM);6xN_q5vw<5Qr0nHED6Mif}nE8ZDi}pnDR9B~Ot3Mo~#eO06t7ADpa> zl2j)5Z#*^&E8O}+f9aPqWsYg;nZ)ANwh@+SKWp zs;Jm;vvhY^sf?x8SJvlxofStsSqz0e@X(V;nCUHJNmi+?O^e90aDK6`#tt^;#twA* zrpDjq7BtihMcIA%+_>tq2|Gk!PiQPeey~r)hcKKg`PyF*+7MiTx8S4xw-+3j)zgz# zZ=oi!DU6kPtm4?VhEy7pM|Xv(%Xn~AZgU#S=SfuM!WkuH@nF=U=SXJH4@lkP*rb^0 zlg4YQ`Qo;qx+VoqT_wHNcqYq9cP;wqNxZC7_N|kGr`b<@MrzFa6 zc=1S$_|f_)=MVS2!=>hrJtC+2ahrhxN)R_GC6shFHE>!Fb{FM8z73?v4Aosrjf5_o z|EhWSpn{iud}~uklHA8A;M{et#W&yAWLO&Y%Gn>Wo1EW&(VjosC%We=BgS_7-$7>H z&{fBtZuy@ap`DHUyIa`XoTxmV&gR-1>fTEj#BD*ylfw(rHF(4*RaxeN<*Cn;gM5@Z zS-FyKRr0)yBgQXgK>sRdeY%UHx6mK$Ze z?t`!87Xzp4o>QvrPZGicpgSitOVTcqM{?-9gZqs&MYn8Gm}ckHVCxf=BJ_;l#oUR$Wem8WcI^>)<>`%<#90)@(` z{d7DLKrK&*h5Z0l#`oxuS;=cT7;`4U4io^ocy4W`JhT*uHUo{t76-ocm~cXb5Bs+QT?{f&PS2vI7xfs1O%y-%T?vz@SByTWkKO&!ouM z0?`P}aYNQv9h0Sjsp+h5)se^6PYhkHh>t(i`nG7-w z)s09~44w3G#ip!>F8}2%LYJ*pT1H~e>Rb5vL9Z#+x9Ko5v#-JzvL)FY6>zbh8+6i0 zoTiO;_eQgZ&K9Y+5$HjtG+lJZ9v7}Mil(z$1wh-??PKsm;ZHM1cNwv%he0MEuT40p zV#ylnRb`$R!}WdHr)8{98V7e%zzf>Q3b-D8GCY_wU&Ko)h3(E=dHEk`Ne z-Tixqrwb2OGK~$^6{=|$xc&|>hkp6x&J^sdx5<*cZQwQA(5m03CHF#fE+gnR^o!;+ z8tHUfMB4vY6RffoSyh`00F(<{`>3mLkhcdUcqJ?YJ&;dWs~1UZ81G{Z&MMl4+5kUS zRUQ86T43*&4*0w`diY9PJ|jPv_?@N>)#AeHGeAF^dL>6k?!|Wx8QAg8w?ntYkrtC& z48~s#Q11|d2_6`|9^zS-9c-#6Ja&n*_7O5Ye`$dD$7XyC!y4d|~E3Vb@g zIBkfHZD?pw7Zw(#=_s&wV16Q&0d86X(y7%f-QZxWC;O?jJ!yg`J&y=bMVJcQ zb@T$fzy8MEfV!=|(+ETj5@t|%M2^7Qrkm%gC9G#<|GO~Ibi!D7hM>c-ru~hDebFb2 zU5;9cV7w;$I9hr|Db4rjhJh-)!)O^0$Wk7FyB=cZxo~+W-mN%9yeiEeNDW?FJ{mvk zcQHUy9K9c|hesAdoMk{{ix{h_`Eufj)z4U_ybl;(caimk1zczP{DxfH>K=gn<_}rI zP;yIiZX`AH&ve&57=^rtlsIIYk{s6tXoiYb2<2c$-(_C(?C)F*$#o0x9UW$bg}oW) z4}*T$@`rt;>e$)Y-&tL?zpIct(8;bUT+Z$DvpIPX#}8JPc=-s)%QMX{;Fg#C@pk_` z9Ud*@oZSsGfn-@L0hu&g_Nm;B4J%6GqOce%QIckU#F9@2BLN{{`*a9bnv4IM#5CKf zpL6Rh_kb$D%wApU-(8A7i}6Y{h(^&<5Pl(ca%>dMEWxdaQhGp(msx0rt|0SZkR7k0iyWEC9e6Du_8_vuoHnE2EYSJ3 zFzCQ6;JOg}5&B?vLjLW~6zS{jw4$;f*TWkNcNf-9%sduxuJYezj3|-o_oAN~_3(Eo zr-|?#swBHDZyxk*@@GGMDr~I!6K()$1^qf8&;m=7m6V3iW6yhHFiq+>za4J z7iwD=l=Y{9y3mjTG&{+o^i`j^9(DY?^}kW?%*WMFD^?vJH?vHabvycgtzo!>G0<(# z5{!pmV`|qkf7th+waztX@*VE$R|kdgbvbt5LtGPtzym;#re(@H1gH5s{*WI7tL%WV z9FA}cNjgK?H>S7I3ZCxy{T|yd?Vsx=Ue}|irw4(kt!r*{++okG<(j&;#qv}=3rO+q z&5#&?+*JF+Q!oFM_T1;Bb*lSt<5^Sof2%DurrYeT!l)Qj-;MXqwFDhV{8NPRs6?nE zRvnMyqir&N?swV!6Z0Wuo#E*dXd1m4t5OL(wkywA<1_5E*!`qoAPP(cAc(4_c&wNW zE&)hMGi*DXR3CHrEKP;6` zY2|4~xTLD%Rw?jhHe8aOc-KDn4T)lQ|kP}rYv$;usd1$`|Tuk5Hi}Av(FCy(4c9xl( zeA-VbuE4X z8d9J!Z-(8b$vmHb=@QUID7-QeJ48wTc(i+_f2JNQ^j<>gC>$OrHzL)vAMQ-w4*I*H z@?#E!)o6Z%Xjah>^|3F}{|w5R5_3}NKlA8VTExZdaUN>@AD+NyuxBn>!>_@bamcM&_B z-qJK6vGzu4*_*M!vez$1VO+2vua z4+h3)O^f_?_iAzl>JPG`M%~aU&>O@yG0Vg$#b8XCpJM?lgJD*jXKpF}Z9e z@9R6IFaE?vig-&;Vp&!QTq3+-yL&RyqW%%kX2vZ3c9p`RhKX3@!ofnUCDrl7tEzIo zySmdwXB};AA+zAD3jw-l(&##ECQTwEg91uO375RQSyqkv43eu1C(1noZVLKS6F#LCZ2qSABwg)HNhYM3 ziKK;T-+hHGR>`}SCL`QC0q_Y=Dr7cbZmfqB7XoA&B^18lNJc`4;V0SUxs|K&@_=t4 zLK8BqmLd5e2*CvcjjW}Syci1{`A@(^6s(}G!-&e2_XG4(brtI@o4mUBstYnMs1*h# z57o-X3>j`(#h$Y^7x(*p+e>?5<_06$wnAo=~P@Ri6ja|F> z+lYW54bE|WD{eQq-&b;;YGQH{Ej+N?f`*Tod3#q+{S$1{*K6Oa05?1=zY3|fH*kn& zY)(*To>@)QbL?he{CG_jJk>NjKHM--cs$&rUjmpFs{?%QEH4?M0Vw9iz`={%VLFXz z-LPwb8(BF&L^kh&|FdW25J<(8hqW3Xhk&w*g<1MgGu0Htuw&?&v1%MOUZgu6yK7+r z`mH7;bK~ioF>6=V+_|5;^l0@@EM1bRM{h-Ml(?f4S9T+KsT|G+L4iUx)6=b_FZhC8 zsWhFIj&Iz&IvLRPh!=Mi&1rQ?*E>Rm;Q8W3vVK|%kfLrl9SI?Xel5LadC#XXzt6?l zO2f1G^lb|V@mr?NqhG(os#O+nC2Q}28X!j9nl*p6-#a@4lLkl2>SbjA2Q24S{)mc) z7PhVP?F^+Kqz83T3Q~bAt_R8r&yI5-93)NF?yuea$=M0D7e9-h{*y{^@z@5ygn}#Vkk7IKNM91p2_M_R0STZLB80S`=BL z1^`WYS$@Jf$~WEj?-Iu;JWf~La7*{pXVV$s4uMy`E`y%VI^c%a?~TikPf;thl?hZY z3(IL$wtCNmzSVjoBFP5NyHgym)kl6+%Kf4RrxYV9J{e`%b`^u#wIWjdq7_-qM3YWaUewmQ608OU+7^V@^;{`Bolwu}6^|kS30RIe7Pn?{+36L+7#P zE?bL{tB401xTFBbYouhX356U*}Mt}w81(SUcRDmV2LNu zBiSIZ;fnD(^W13WATCM2&k*n1(U{_pv=k5CkjDSwre-}#H8DH8B|O00hI=ROsx^j0 zMfaC2)({4#Kfe$J~D=;I+ z;{~-dgj?7BcDZnlutQSPivgMAGNZXWw!w93*nPf>YXI_{flOIP$?JC{ItF=hGb`=y z!put1`TLSs6~f-JHw{gz{&Y(NdoWixb*2J!TS#24Z58HtPE8|mFyDm_KXB(D|x zEb=R`c3-06<$Y~7GLeVSgX>9!dn~I`X%EEv);0s(KFZL-z z1MmS;VcJhWxZ4n#Y`(o2-M`#FBtH3I!NvbF-T1Yws|^HjV{6@wMrrEUB#2(`Y^(G$eb@jmlC zHghQPzrHX0VbN;-W!NKuR5iY2kazOSV1n(#;OO)A{-&zB+GYIZ+j@U|aBs|wx(hu| zZFVLZ+jN>GefzEY#OD(v7iDcL3+nZ;%`*&pi5!ZT5JBu-ex4DA)NkKfx+i>4{a1zP zI{4e*Npc@i^Y)EU>5+~F&++*$q*u=b<-p-zleyVHJ}IMFkZAmtEukJY2j_T1*Yz3T& z*scmzDMk5A=ce8+z{skj$d7 z6|ggzi`~95zmpypddrJ-KCIQ&cGv92(Fb;<17988+<;U2S9Es+_Tp^zZ04vISvI-v zex3*$$=HV#{|6FyuTcTC)4$ou<1-(AUwQ;!ZV!1QSF)F3fZ61AA)rj9w3-aGjWgNn@nGGs^aP2UP2J ze?Ocpw(GFZtNNfMyaiWI($^M_Ii&qA2q3FuXrSqIn~J6qY*Ph+PN?zj7FAwUTI=I; z=*pbezrf2=kXqXYw$tLh{dJJB+2GCZQ!6F?Yt>tV;QQp{=*~_+b-MGzc96&7W`97~ zG13{bKt$9u``1PTYrPM=7XZ*cY}O{HLZw2Cd?z)H(C>3UIakt{yM2?VO5lAOo@;nF^CE-cD73#tyZsy`)T zQNqvS>aj2(32tedGYLF(;?qkO)&qmgHVo>kL@hrmT7w*qyt~=vQWA^R%UfvyE)Ud1 zx|Jy%rNp4M6UYsU-#w-m-D_b8FYnpo-$BmI4T6{Rm^s}(lll64E>K4F7*j2M9#DPI zuD5XMeQ%O2wcnTbz*q zf&KiBcV;RYyc>7>7P04pcM8wr8q|7q48b;qg@uob3RZ{TAz`0MV-kvQ*2Vk`Pfg^M zyPqF?a7K~DeCLyB1Ob2kgFC_8L;$7xh4vNi&KrZ#UV&TkZ)Vq1NwgQes z>X7?rqajlk>7H%g^an^r<=P%D8a~ zBqA!@oS_SBTupph!!UNB9X?--6KjN6U+PL?{6qx?^Vvl^llpxTwf@LjtWrY$y}%Aq z#+liAn4r{pa{SGpTR_4V-t-T>puc;!a_i6c z?6y>ZMr{tyEl=t|q3@bz@H0bt^^D%<{*+3N3%)I93wFHgWq$<1{kr+yHhzqs;FHF* zy>b`j)0XGp3jofoQLzq~LysMI*N2{yVn-)uQ|_za*w#odqQ}6G{3InPYtVr_JO_S@ zMBcAPKVCi7YLVko%TANKkK$cH5Ax}Nc;h}w4+H&o(ISc+Qpx)Zxw*NGLK@@CQdC^3 z+Bg5a4v^#Jd{*(bZnun7xOp~lf~vStygpF~raff~8xwGJRLsdX2Br~Fkq zCnqP*)D?F#BTri=Jzw`&_ba;s6pya8HpgiaF5f8EH!jZ~Exg!oIf*Z5tQd_ilBk(64PE zOi#ld+RNr#PwZ*5_=Gc9SqDJNtYDJ#4PamcIwNy2`N8-=>NLDV#=lJ;M7WWj8D$)# zFC>-0h)4FuG+S9dEa!$JAS=Zd-dEE-vM*%9)nM@B!B)t^t!B@^!>$eG%0e+fOH{u< zU7JzE-7?(orYAd>w$>&ELc%FlcxzSF*q#v*( zfZv+P7&N|*{Iod5iWj)*k-+je<(spXYFOoK%Z1+V8aTW}h$D|9tel4-YJso#QGmsc z;FJDTHl=EU|GcnM;N+}~o*})rp=mWw|DcESHALS@3NY9qp?CBHq|^g3|j@BMwj=a19-1QM@4?_R>v#ivobi>ufLY} zE+NeA%aEZL0lFCa_4f}XIc{)@f2TuoSJvs1B`%IlwnYWzhArB zmQV+O*qC<(&F` zK>f;UUWqdqwRCO!Px-_mveuD z@tfLFg#XWZXJ^g(BVpg@kaUO__Q*gUc^c&`A6OfW+$4GkZ8Li@jylJyw!T?kIrH^iu5HbHWpV6h!grT z^Rw(W5xlIDFs>pN9a$A7E-kx9?s3-f%lg8Zj0M34tNlj-;F@kwKt5vet_2;~TaG7KLqJGArwSKc$o12#TN@bGU23(@qgZ@g4F2is>DN=-$Mcsq( z`P{d36F~YPkbb;1C>|7V52lXa)83~GcgqVH6v5xA`9vCbeha_T23(p(vb`F6yakjF zqYyN$XR|Vh%$`iqhN{92QhOIiU}$ie7((W8mSQ@BOBd$a7aFo9l$wF95nOt;DNQ`Oj@Ry!|xOW8TP4}$L?uJLCWT;=caTKg&Bx=pA#}i z^0<+f8%%@se&I6l(JAr(#}X$&DH>yiboV}mBj2Oh>3cG?(TpS;or)0i)1@M@bU5HG z+)eZD7>#`OJzMF&wvZf0uuDdgBgDyXaWF~8cJKZuM!+e+p!6W_@WC1z0kewk*ZO}x z76jPqw+=%Kxo_p3>DZmjL@zcGXT2pEH!w~&)@9(kVQK(!8JW|mYXYF__~wP|sr8N) zj)z8kSyZ(x!48mft8Yv<3MNRtNv7+9d_4S0Cd|$+OvWIt%$vX0$qg7EwT_f-N8cfj|TNS5)vnOf1*bv!JqFS#eH>8vbx2HWbxjZ zy380L401ZdyFvOHiPp(#wuLTDoIqkKDynbxoE4+}LC%lcLEhJG>HiWs(|FoXj8m6z zSF=2ZqaoSNMLe4D5vD3(euHdr&Nk%-r^k{-Y8m{gYGWd!c!CdywYXn6v?-+jw$nVV zwA+r{s79nB{kbi9)s|ZXuvJnX%Rk7Ja`LJl;Atofs{7H|M0^=_c6M}f#GQ1~TBY zlgxe`MJt}EUP#$VmXfHTnP3e9^@+)R6es!?>h4z6Tog}!Gw)^`dQ=U*XuBbl4Wi^j z7N`t5iL<|xOLyly=eSU>_UNIMeK^QTXqfi=`ZqhL8)lNUcx<WO{B( zu6U^yNpMixji3S9{y)z>8??2LDobGa;9V|&=j;9Z%Zu75sIGP_E1)$IWSpR9+!@V0 zpBZ4soLaETM7x+`3#wenhl5K_RG4AXIMU%9tvkDM2^IYQL%{_fWqVrWh)%g(u*%ll z5S6R zdQg0+z?-mjQ|hdw6;`4ErK=SXOG!$HbbR6N8O@UijpTGkin$Q@);furM*P)?D+gzh zH3T2K9Y5$N|7n@ySY^K;VEW1Q*$XO=nx>ZK?y}LyJIJEZ3tU^VQN$OE1)+*yLcdLE zihV`OyxQ|7qkcSMn8!~{yBm1ySw+_II500W4m3i)&&9cCVZi4@0Fq^T^X}<492gAz zAKX|wQUlFqOBmj^uD3gS8XJjofHf&jgy4R@w?(z_SwC)4tcJgGAlLA;D0sy9{$!&f zT|AWP{O7XaK1h-;4L>2Xg~%;XQ0AQ=&Y@3#@)>-MlIUQ0-;@eh;^g@pm#t!uBGPo! zfR~84%6_P=V~~RW!bK;{9aP-NhTV$Q}Cni5nRK%Z@h*Z!SFTKhX!dm$un(Gebf;?L_eb1oGYG5h~XK zZRNS}uo!P^pOY~c@1sbZX6KoS#AP`Q(8!HQGNs|H&WG3=drHK^b5Z>{&HNFHb2B?b z-D2E$fpf2hdyDBja|QF2kjCL0=wBMP6R*9nHMRyQXhid}<)r)z+YY0Fnn8tBz^i=x zkXSuX?B`6-J*MD`dm)1)q#<>EZKJEiuFC&{*#oG$<5|su?;Zll)Yc}1`Et>0&)t87 z*QX`wQ?!CW3Jqkk_uD(9qbV}43w?>~_j~lB{C8gQO{@QM0W8yR9dh;EiYLw@vg&yv z84Mp?7;ETfJe>C`ySN`1LNZ3E+RO$5DFFzKH1Wwo`2GldM4_7pR=mtT|HG2EDW1Dp zoMzv?c3bY$wLQ9U#1#d&U;aNPv>{-vLfo$_|EDtY ziC%%KL+ttZn;*{WJd%7NwFvPw?AX7ySfT|2sP|dX5UT9={0A4Owb6cIhmAuJH6J ze#INtKDo}H(v{rS@ zuENMhNI&DAWy;6rc%s@TBKFCLjwEK-iAI2dXjAR+{BLIl4>mjpb%0|qc)9jf$Dp#_ zB9T#j%FPciFSIZUo?azJ#c)PBfUYROoUaH@yjcEHKTej?o%61^pWAkPb<^ou(?zP% zp#HlH<@=0#ng+V8E5bji#%E_uO-;9|{#s`8^uiZCaxXI{Xe|Nq!YM#1JpAOe43eOM zrO^U>iMpc#nbcF_61B?VuHwoE6rN{~UP#CfPQc)?Wy})%BievLY+_Fo_gyj$9VVJ6 zKL%KDqYm-U0uzT5&Fg@3OR|yv3rGiTwoQ0jJjs`V(D_SSoH zO0Z@VUA*v-r=kfiT9$C*89<35{PBERNJ*T)2<2i*kPe=m#BHquDplKC>1gUq5T59a z+c@sNtItd_tZ{eSE;FS|hDkCN)c5+~fO=V~AfE@?dA2i0}m?eFQ%*T!T$LBTu3c?Y1 zpYdo%rYp2R_0u+Ocb2slpkiJyY55nxZeMvzKa~Yo{kWmF@jGem$OFYaRfVaF?duwNI<~Me)qs3^1Givo=melyrufW@ z60yhOR~Aosvg8#4rW9l~00xHiaL<0R^$p!%R3ly96U#EcuTLX7b}AO8X9@2VG-E1Y=sNr6MlQT06Bv2fVx=->!2D2JHck2ddLpBBb^ffgBN>x4SQVIhOwHze|14^V_DvqEshkN zP=~n;Pa#h3214a>gb_8>Ub3i}1xom)l&*Vd?>)>jybcI6o_v-pQ+BK}DBT_2SFAP* zM+l-Hc60UbA(0y{ehaB}buKJQlK1aaIBvo;Jin5+EW;32xAT+7BQVOhLuVhK6gJD8XCIZS7)QN{L#S(J152BlICf! z^OKX^Y@d^CvMVB)sLK4X9M zsHq2a>I}N#WF5|FXMKK!AC=ZgE)! z{OlU>&6dK-+$qI5D_VZWRi;7nseFk#f9`3q81o|SQ)Kj38?*3 z{C=6*DKbJyUa_~VgZ>lXO7jm)?=c&zE!=Qo;le#hUpkQxH#WKe|4k?Gbcfn7AeWL&=r;F}G{r^eJ--RnrbnXe zE&?qw*T9xMO%LC09;-Tx(pgQIlRKV>MTC3F0&qx{9I(oBkUiok?sO>9W)sXEPe!Z* zT2wz;V8n*H)O)*l^V3Q}_lu@uokiP0`)K1&jCijNttds$tiHML<-XSy9owS#^5RS; zbo+M_W@ruT{ zhyXv-m&c2VLKntEM0fJFx3%#T2Yw2a8zA4|i$5I!4t~05ikoNHMIM>}Y>t-)vASXI z7Cb!t)oCsqcGmxosPB%a`hEXDwnRo&R5oQMd#h|AJ-oj%{+>+#^xU&q~f-S>4rpV#wwU6*Cqf~rXwUsJLT9c6?dGBVym z+HWT@w4C>uP@0yVR8ICc5m$aAmNB`3lu!`o{X0UgO(37M1Io^FOtOXPVc09*paUcI z53MPKaY61^O*uGE+Nbc8W&{Z9s%?7Tri*Ah0thknM%0%t!@{dYf=w>Y>5)5 zTqoOZYuHVW!1*w|8W(pQb;&#ZNH)t&_Ph4sEN;QR@L=sD(m-iphWGE^$LZfpO4eP$ zIG2D48}ce&e+e~eFNGmWOVW zKQ&L~V6`k4tZlCox*Inz5c$$C;B1GeS*=05E@Dp3)5Ivtnc8<7zm{X#Bu1kNNE)=T z8DUW`O3bKOAbP=`s=Ji3=0OMf9ed+fQbA?249i427ger-Cs>zrr?DVT=Ii%_f-`?A z2~FyZxN)^fCmy);TltB^DQ4H+iuV1azxK!h_Lpe5v(85&f(hTG2zK(gbL_W++aT4B z92=wapuSjC%Nd~8_4A=51*K#0b)JZr}e{ni-(%W)@!|L98FWLVP>iqM0>JSI5 z;3xf3SHOJXhRT9r=9sLFnhr%I)Yd+rJkTSG(hKMz;LYc_(lF*@t-bq7qMBRb zB1M1IFYaog6)c~tsi?QiegqkSf7@@B2;bqOShH>hB}bGX{Fmng0h^dlAwcs_P*v@~ zpbdl9ZZwea=vwX_)vFZ#*=ui)CmmM2e0#R}$<3jBx&rv?7gCJiedCHSem z%EpxmireGq?VwV}L`S~y3NIKq>(i(0nz=>K*BvUWde86nffCr$M#gjLgzu$yGlMs9 zqCuGmcFmX@{25{jOVgRsHqn z=ajD54%g}i!V&F_WI(O7N|qdTcR6yEuxbHBUKyA-0o?ueg^I%x#TcfCC1`8yiVrF& zStEZU!TGXASu$CX$@+;?A3w4ZZ4$%zXiWTqx_AATUiIDL!~N0@V8Ny9}V>lhHY5`rYvm&Ix8B$r)b zN9J5eqgx!cR9vvU!ros`b2v^@{n*n`mzR>^U%ms^^xFP zluV++Ph3EtFoZr|lCIcY(o8R+c2NN4d1kB?0zUe>r}0FSUMA*=fD7YNF%m_7D<~(9 z;IC%LYE1cSU-;hPyRE~a^L|hX*Djx4djLuL!EHfXXzOo09wU5J!?%j+Jk1H_Tksjf zy9+MmVkSckz2b*RcYLcDLCf?a)Lr$0^+tE7@s#3e)$$=_$m1$dLE=GP!b7$#>t|1$ zVw)cxe>oVVH-Ll#W;4K~Cyxb1W?<%eFgX_&9Uc8fG)$SQ3Z5x?tL0Ye3JRW~r2G1> z*uI)pBB(U))KirxrE5j`K4f)}Bzi{|!9pvocy$7Yn&~x`nJm8e3I}0Kf16 z!%k=?p}GadTMK$Z3yQOyON}AX^q(=ibhZI+8;EOrc=@|{k5Av;l-H)QF=B86r)zyL zFa~9F3|bG+=K~o7;lyq7NEfDsxW#*=9-n98o_<{@8;!q*hSz z>^~uedRQD_o0CMXxPS=m^ zyP7xAO7;3%0YwQ>%0P32EAk7y;y)6D2!1D)&++CzqVA-rm?OeS)xZCv2!>_pW|4|e z#z#Jinqu!^W?)v3+k6%RQcYdU_@HHi7pP=1jS`PT05@YZeMm zqJN_074pP0hsJozm~O7!z{D+@0j<9jCSygWXbeVy%o)u4S5v{(0>y%&P7u>XL@ye|QT*DSg`wRb)O*X;vH_MM~63;6zNE3Y~Tj%MO8h6@tr!8JxC zGvKb>F*Qz3PPi&>p9H5W1mdT^?RWonvp|uA`Nr+npj4W}W#WyOz^g3|Vv8JRY(B-O zx&aJHy9Quz`5S^iWm>KoMXrH9d*&%Bl)=b}2?F zP(nclQ=wuyZK+n)7^}vYp5U+utt`v+NEJCuQyivsOI)tdnBvDbVrU|)w)~N(|4V8+y}~6jJt36>gL{|y zLrCmD!5mO|ooe`X{yh{U@g*nRQ{&~DLP!-)Mz=7;}QY(Sx)s~g?@fk+%4ZYB?=c))R zqh^IOgmqmI2&B4j|EIpLM`Lk0{xVvGJK-m?Iz@iGSpQu$qE2N4M^shgeMJ_%`_euy z^H-KMi0ZJfNdp=_R@v^EXBcuD-AD+aZJfS*j_w*$oK4xgk-kXVdBm%ySiq~!bxYi? zqz@?$Q;NNkh-BU*FBcgOL`D}gz8j3A!z-QNDLglFIw+y?hun)?n5)ch`$%zks90f`@VNjhak8RaP?|58sGR=; z*c_~T!hzc%o04QE;OJd28}T1NS$`9FkSB^D`zr=|df#Qr@yu|!RmyF^y9hseWBYR# zOp=+Isc%yVXMGjcB8Q&W^hziZP~yJ{rJ2V=KFV|RPq!;q(_Fc4NUjlhLin7eCZW(;TS({`z^bZ6Hh!q zqBkBGzF1;3pW3mx&N_I*S2X-2Jd}8u;d$Jk%(5>Q)sIoPK)Lei!-_HRv%5~RLm>QW zpVtr6To!;@Zm@6B8&#$^|-{DlUF7DFLcv1 ztJ!6XUVqz*gyT)fXTlFafW_{k%Kn7h{La4mK6Mc62$ig9)qgMjCxq*k?mJy%=F zklR#U;da7fvWpZ{6lEeMLO$C5Jb!ZR?VXujN_vLt_owyE$dEeQ5yZ(~Y=?>Vngwen zm_Aw)oy_wK+=avSm`Olw;%oR~L+{{u-_$@P;9?^YvD)mn{ks=mwb)xPWbG&&_;5?T zz9#*4$n0BVc_Q`_@xUEXf^8m?-r{dWoz}DFk;u~>yTFJJlg~0=S8za%ar>}jp`Q1yrWRn#7Ss{`wKbumVvO5Tk zuOyl}NkYB|*stg|KhX|c$*Q_I;gZYNByW*fKl;zqbtit1Cz5~Bzc6jI5i?sQOepD= zf=woR<>L?@YP+){muRpA)D`WtpS%2@jpfK~CQvPy;_wY~iW*LYxT5{?qZ_q}q-6xU zu#dWDWHeUJ_CL7raIu`3dpGpXo&1;G-{|WcG1wlJ7lBzp1!y!UQaduW!9=zJlsqR-^kPc;8-Io*I+pA?=-&r3azAihi(0!*#liqp!?}RD`Q{TzI zysw4x`t$G0N*ShCpHy8h-spqA-^3{9nmtOCG!M)u9o(wxC92v+j+m4oDy99@? zfQ;@fEj)~wQZ-MWRZ&!&I=VbEDPHiz+13?te4lTjZr%6W&!5}BPqFmt7CX~I9zw^& zz<94=8L<!rchg@x^EPY-+&?GjcvU90VZHEgD_AF8&}frtt?3ihS%4)$j=CGM zvyJ!kuW`oOq&mB{>xVC1(ewPpicWQ9h-Zt94@e;Oj3PsgX5_}Jt>&(&AAt5_U{Rkb zd14%=a}Wa=bXGdxPfBk)E;~`Ntjma7{R_692KApR0+MX*OzJPApnOiM8Y$=pxd0i{QvlujZCJJA{^8(_ z!aDZhSe~OgNHxKeuifYiTD0J2~@PJs(zNHuw zuJN*pXNJ-Nx41y!Tv4#awTr6d7Z?4l5eQw@*^&D+dnbBHJ~v0I67Hm-sy^JzGkxa| zy3j$Ax8HJo5fIuajVg#tRmpcEBRmAA72_N6|9f>8W2vwH-Zrd=hM?-n+nz?z`jj?M zU*?cGzR4awqH1qt`H%KlTep%&!Hv>aQKrGT6JgrWjh43q5fSS~pR=qJo^vv;nwWqa z1Z``w6B?=h4~?1hIeGZ`(SB1ZK?z1|P2CjJ{pjYMN{isJQZT+2!ak z8+13yQHhUbrm{3Wd|nEAu-7^Wk1@{o;z|n$xLS^rJ3R@lnipc-fI7CPHbQm5Nyix* z52^;c!GzSaOzoi?q^*xuCOG%?+Fe?IX zdtNF{B^b>LLRI#uh19~89v~7l_(JGezr!R|y?-yQH}zxtyW`*2amUWLEX*Bg;e-*A zfk>a*4=d*{?a>RM`7eTJw%>dC2W^{z&ZinHuH}?bS`uHA;Q??)B6rA_m|I@tLMdsJ zUMxuw#0BSV&c7FkAocg3un#?spzbH`)VBuD4~IZ!ap~ibklnqT#|!FwviOG(S}x7Z z+jc$Eo?<YPts4{EJ*JVD}`*UAMyYt$qO3M_{ z`ab2pefRBK`if;`5*qocEb}FY~=zBsE4{k}f;))7_&f0K^9Nyo$*`zT(kv2>3 zD#SoTH!hT71bSqP#T;McM))~S>c?@YK2F=@M}8mIU$X3MS*HBAQS(~9Fqoj5hsc;= zB^fWKJ{=9aW;Y;6pGP13`14X=aR+#ZXei^)dion3@xl_T2+^9?MGol*2irm8&Q{8$$U@arKD&i8%S=T?Q4<#+#K0T~<7m>#tSn z$zwfm;Rf~v9EnC$z!3vucX9C&fA_n4Ayl7_3s=Jh8CF4tc4b9oEiYQzQ{m17+wb`I zY5})vJndk2Z!0|ZHfVYxcae^A9*vYOrZOUcfxe6B@J-=GsSsbH7dB^R))y8otJQYi zxzUUgR;5?k{9)?`0fRPy$3^MG+D4-j3&tp`p{{OO2()pNK(R;Fm^v&dZ(Uqt+|$<} z+g5o$Ut7|c+H8>9*->t2_KH^C_l$!({y;h5Vt%l@sIs!u*=U9XJeb_X+xz%|!+E`38kgWuhF%Xj5Ro?W$!IOU`>Ivik5Qwf} zVuTBaqR}ujQ{_~8ZP-&BBc~S3Ei17EN5Po6BEpbkoG8nR7PTBYJ{ku>6>rbWd2wvT z5Cf=Z-Sv*V(jwD>8w`U`Y8SL!U}*8W;_0DJ?1AA`+pF&avF8)olr+^toaq{#+}(Lb z{HbL=Om|okg#EZnfJ2=Zq0Od%xbbTqGTc1)bHal!Bk8RBcNco}U6Xn_z_ZM_2geSd zt(qnm<`EiJ?3lDqw@)wYhI%J3MO#2cCw0rpwF+VgUXio--1946+^#6q$bh=g^_)Y=^*%%C;@P_F>!3 zZA3PIUZpw~A6s*4qaLt;&)f7CcJv?62A#`YS5wZu_|U?$IP13|g#X*D9T2Q)4$~Q_QyXVIuc;oR4xw0WAn7baXs( z_w&8arq>@=IixA{+yc{hi>173%n6NBP1&ap#}9F&wt6})kY%zx(?kmJ95O9GGIWrYAwr+goR-oDI>jTi6N4W$j2dV{ z@(f`r5B1~B<7%m2$n$G}tKiKI?+0<3rv6B&9ng4d>`Gm43f#E+ka18EokZ|Dhf01! zoW%^sM6ZZdU0u)#)xJXq;U5ui!n+@Sh1;&Wz5{n|Uc}B^jdWxDnWGzmNT_}JyF8oD zlS0(t?xm@#y?a0FWB+?){S_C3zCl-UOjqa}*`Pm6;ojG(^Ju!^N%VSJqP0vqJj0RZ z7cU=4B>S5nE}4Fu&bDq9vpa!{z#k~k;s}hIFHVpZkqX|Y4FtQw9pAOwX>7kom%kbZ zH*Q@lEJ|PXZ8vMS{Rf)A&t8>s_}!E{Z;-<#cJJVJ{`B5ezq&kz=U|b`SJ2~KCbE$h z3D@fT>3{dm8XOyBb0tk4&E`;#!%QLHFjAnvKjLL9YH~P>XW7jBUGiqG^FY&P4MU*0 z5-8VP_q6vBhd)zP{nvSdl&=F0)hDQLbGwj}YhEZ&;*iPi*$0U!HtK*LiFRaQhv0Ln$v< z>u%Rf!t;9n#I`<=z74dB@HQ;0`0^RU&j?8u^$z8?17~%7l{@Wny;`pJ^MI?jIA8pR zo;|)sX$H!|g76~~9JNKmkIm9zjDb1=YEV!;6tKfqBV?Y|A> zxk{%$Yom1CRBb|L;foI~PQ(sqeWlM1EgXI}a_CJLcQ9^t)KQd=VjtCmgS+S0BwID&7YjR4ej&N?FCoj?{x7gOUioXLY`h$-8y zy^xUWaVb6DpPhvqM&5gOcD*cvB_mlkG$0bY;HMghZk^!7nzpzm-(H>Bn(|vu%&fg+u zlBG{x;F4g}pY*LqrdBgl^MDi-ur~#CbX0MC7Au%GZ5$>ms{Oghs%y*_&&MiEoYRY3 z*>nj$h#Oev$L=R%@1!t@v>){nFtd;n-5#d}!c1|dDXiK(tlj$p`;WUsm_2`7;s`OA zHa(mqHxGV&*!yPxG+-+m`Z$%MNA5p1ozKDZP=D%j;0pRu#T9s2|j$p#=nqz&6MvGab| z$R7q5EutRxU-~KSrI_+`oQ(aF$v4fhk!EiyTQE9{G|*T&EM;*^C)rK0%|s^b&mFKF zBlXp4&SkMl61Z(CmTJJR!%nSVp#0;74D|_ z#me@w90SlB>F)yqvFS9ySZ3g5Dn0Ed#zFeS?>KTR#g1s_Nak}7zAI!9hX|_{*$Fw7 zD{pcQRAou44=FJ;RY7NMjgBzjP=lZQBXZ|QO;;}s3%&Qh$So=C^aCG{4vblh+MTOz zj{6${?7M%?y=;}7FpblCe_S(rkHL!KDKQR({5j2=vT?eH?~ghRpv@UOTkpN&-e*I# zL&5R14OK!-3|sfXbmQgLG~hPR0FPwIptX;mTq+#})ZXlD|6fZ8$`88T{ucxzo5iRdI^N%e|V-O;74(WbSma22jf!ev5w4Q15&b*55<^8 z`i54b<7tBH`%|nyu`GnVopE^L__@d-QWcK)%#%Lt<(9;)2ekzG>@<}$z{iC}l5dwP z=xI|E7$1bMnUo>CW#&EHJaoXbq8hqY(c~@l1DzD939rw`z+iRYX=9Rm_>PVlPcRnOVU~8Su>}ug zsL|&_Z(1?$JnMyhG~f78(?*v;=yNKH-YUN=ZFi8cOfec|Gte6{`~OSjpu10|KWn-= z!_0DG6Gm%US(|xC>PpIcbq0eS%!>@iPpRd9BUn~;6db#xip{DPZ~idt5PEt1fn61} z`JNNICyzo|$}7eoGWp4WTxx0IM5qKmh645F3RNE?%|d!X$Sqi8!X6^i}ST3D^plsU=L*L8t}N3F_GH6B^N1)5!7f- zpTU=>I(@a%eW;d$_6!6g3`yzFX*@K>rHjqi8DJ8|$7Rj~Ps*nJ3R@te`)C8u;}*l< zl5`uRbdE%4W#+Zz^6fwuYn{Q~Q26MdC?BV0i`Q#qv7sl|_aot!rWh4%f9}4ahzJOW z`Vq48yp}(OB{om1%=)m5aiB6}qJ4Obv~C4x6~k{}Ox{75w0a-tf$#pR(QMtdY*HgO zpk~iCUZr%+y58T+%yXymiljs{>n()>fh9AsV0KnkvW)}Zvp8t)&UNC9aumur9_`RX z`pQTL#ovY@|E_4Hlj>HswO9YWr*anl%6Gj?j4b1q&dQ3#c=RnXbdH%;vMmS$mz9-0 zs*sbBlJfJy&&_Ix%aL}lI^Vn?eu3jWv0s-Lk0;+tPnj0Zb#)Rq!q3k?CVWSBr(t?_ zmMM9S47dc)-%XA2f#O==@eIwZVWnC|6Z2R_slM(DB%KgrzJXus@0xcLQ!@ zJu9*p_u!f8_9xG+%*YprGZ9`0Z-frO=Ty1ar2I^SjebeQM0|k*9w>WoK0RJ1`}RUx z_x}DvIy@JFpw%_P%*CtaKJrW8`Zk%LMV7w3{=)|Kx~?zbwToocgXJVmD)DEhdKB{b z8g1$Bs4%0n!3r1*BCyf)(ecWujTR-D0lxc+?tG%TkV!_Miaeci$(zF)aHA&MDSg~{zWs|JQU+`f5D+kmmfb|D;7+^QOug<23 zR_D0$w`N@9|Gxc&QJ{Ub3%LhfLLXOLaPOtN_cSC&7&^{JUOu3PKyt@_p*^*5JJ>9B zeKspRY=q~X8uX!=cd)j0p8nNkdm9#!R4MRH0z~W>t5Mq%_T3h0Mr{v{xqJV9_P1eb zZn%wj`;GZ64x>A+iaVkO;qV4ckl^0v zWoY7QO+zJFyMvQm)_B2Lb!H4#H&>v{M*R4o*^>W@bE@gvB7#aznLQ6!S*h3+VwZPM z%3EK6BfpMMAoQ8%%S0?=;DVeQb))u~tNFE=x3V)`2b04zO>fU2b{-2XT4gMF=zoiYD%GDBnvdlBhn*M zJ%L@YOAkiY$$~QwTj=GAcwg{t8*b|Ayz-cf&>`K2Z8>YVH9am0yN}rnJ;$1+AK_T|~yT5(}C%R7o@i66-bNQIbZcowk7R&B4BcZ!v}ukZSr*?q&n z=dTDpDw;ud6R(-a8ABo^OTXyhkWf%6*hmIVV0TEjad6Fy^Csu?HM0h4SbdZ29MX+f zdx$|(6%{7lElp_{okndzM@uKbWWWG89_qXtV<>ru)-B4dd`%l|7>l8Qo>)!fMx1rg zY2iPbY=kD-%={^JU^G43S33yG)C{sS^n=n>sbRIu0=^{DEuv008g92kzkL$SsRT3R z2BC!h8B^tq(xVeygO)RxHiQ3oYhBU8k<*RPI^HvBn30l64Dxfc1 z{$>p;K_E+rj_+%3L>D=m?8JUu73GH?2{j!Vh!Ni`$RGLch&Y5Kg3tq?PNtGYvFuC)ToNbzO)hx}8n~V74sS2j| z_oWBpfBxv|YM06EGy3pC#3p-n*vJV&s*MM-=4X=KVH~^c@Sfh=Av0R-DHY*VrNXf! zRZZ|&lyqVX;DI{s3G=m)k580xlQIWJC*iW z$n?5-BhljjgcPOYIh zS=@S7_&?grWqwM1ZY*~^jr>jLv0oz?y$klu228dQ!ZoyCA25xSr8Pu89deg$VrEuA zt$X^(%!A|Z2krvE5d)-;evFyp4bk|loSbJBG-KGyisn+B5et8WqS()zoVO<9gj z@Ojk~kJ!eEjy||`L?q$w3KRrV*d3hElTFZayr)z4)Uh#MUQcI+sI>w&Or~s&I71pl z2gi5^%WIap`}=Q%2oF`;bWh@R&fpuqb8mb65lLTG6ec!m%P+T3*C_-VmS96h&D@DY z^$DvFZ5g^MxJE5DI_<5E<^u_iRC6^Gmn2|8>YD9~*jm(xi;4cBo!~9?sU@IHb+Y<; zJrjbj_ysl5KVnrZZv!W|F%mWTXUW(r#M`!&RLvsp8m?^cjW)`NVR=UOj3zT`T5Qy|liljtdX=s8!&;+H2Rz z_+|_9nMGEl9GMh2oXy3X_?mqLrx_YBWW9@?v*WD8#raMEW-WTKR|KyRguH=a@5^4C z?2m*i`UL`6OhJIV-A!IQ@->$my_SeTAiJ4CRz^^wGwYLp`7>m=0qWjp$+8h!#-KOS`)zq)XL>cQ?bGf9?w^ zN%#Bso&~qF52@^0SAWh5#J~u_gjGcV$t0s-D7lzM5}?%8#q-&d$3Q6}A9bViS6)g= zNO)b{zQwxImT-6UXGFzlUbYx?{n?$s<@}w#RQB{=4nKb=d=THrJVdtiG`j#5x-K=; zF3r_0p%}~*4@w@Pt@1n}T_J>i`RjYp?G~!RDus@LD!Ji0=Y?;Gg&I_rQ^t*V^s>Ge z`0%dtT^~E`A}EkBct30NKZ!2`LV6RA0VcgLGoL}N=vE#4xv42-#fWY=B59(aqH({n zMa^1Z)?DUAgH!$9Cynu;l67wOgj0&AG4Rp$aHD4s<aaH+f;xjlN%q+P(dL02m zG#b4OwhJ~lY0)EFG74=R2@t!1&D5sp9rBXf&b-iu=Z1 zEMJu>QE3!Z6^#nm_qrt?(&*6AE2_QZDN6QJLTGRi@`nXEEgY+)F@zF(h4Z!cIf$|b znLAjlpk^L*ppFA<{-dAoJg@9x)Dw9}fDU};Uq{y%{>&-~AD9J2U0cf9l5}NikT)Jx z*~!*x<5A0=P_V|>`o3$Z(eM&1cXaTsz1eAOfO2gKUX1Rgw~BdD;z-BT_Wdlge2Os@ zC46YF$J=!AZ1FJxC_M2Q2r`)DvF($l8W}+!J4){qBRKh-Gx3ri&HW#-ST?{yi>KTU z<-T11uNU-}H~#hntd-tx9EyIu4M?f~0k0^n_LH|D+@y6+66O&z ztFitJcC|?~y;a1gL+FG>-1NH?*%6+hRctEUhS%HOO^2P$sR96xDbHpacQ; zOOB{oUTE_Nazr=&V@yZT#<=TblZKmPVh=|o3^~KD72WS6Ht0^N9V_c2h|9)msc;5< z1N5WN*L!JJ&-bIV>`UpO0%Du{PIqi@e>9PEAWgOpz1DYWHf9{Zp4%@N5x-qx0?_(1*LOGS?d{K zJrf7-frrWZjN9@h^&&l3@ROBtnGsdKTKH~p_N!HoEayZO~mK}0o`dg+w513i=Lg4gw;`;iyia~qqIpIxdO!@men1d!z?rY1MYW`E- zFs5x=f6n-61#cQFYOoo>o1InSmRkUcysD;z<7aE61bkZ<@H$?Me#I&eUbqLSkmS4HJ;iaJi>r<)s2)!qT*u2ar{2T_X!hT5k7G}nrW#cY zEq$(oRz1!8bgo)@BMwX2Dfcob1n(faC@e1>WjI_+mD(%e2oufeZgs0l9KLEfEO&gi zZy}9svb~Zc-!R}(*X3O(ro0hYl?;M^&wF57H*+>+(VbTgxHtorE1hbZn&fy#Gki2Z zJn?>qhh*)TY=|7&I1O%Hq&YP}ep{%3UdxJWu)A%@AEvjTi(&gCCN!24@Bzs1_D5UQ z20Fqmp&;K=e*}k^dEQYxmub6z_$Ml7ZK(A@KZ3OwrMgmfZ9sN~#S1b03XLEqC62tsNvfoi`arM)B_)G&rnH*<0@1RDa;*tYjkQJ)ch!&5BSbV1 zllli0@(pl!ZCV*-=G50Y|8wun=K7B+V1S<}EegXRBr)VcK2%V=|5)W-@n}vj4>Y6| zZP#LRD@1F7W$Q1>XGIt<_=Ce(fy+Q6hVq3Ibfb-2Ry6_6Z8hO0$WOPW0tUmj47ovn zj?FLTfnDXlY9wgWHaU&T){=cXQ_lIUS4jgQ`Q(eoSP82@a(EW&J$=!LU%qAqY_S%u z-a7|t6PZac5DB z?JCy!V02tQ`p%Yk#(j;PQaELPREco|%2SR>F6-DlBA28D_YM8>@bItAP5YBp&lX_8 zod2hR9~uYDrt-K{oMD>LVNutIM_ulr+5Dwd`IEIoMoNeDA^}{I=U!YkV6_kS`YA!s zS$%LAH5i<rDLbCu`wYxujoA$>CMYq5B5U%_PLL z$kaP8Rdr=g_nair{$ARRv1uYnuB?_ZqXX+=T5$Sh`>3pO$HUa1?{u$X=fR#0fCiQ7 zf4mJ?FnDafUAHV;Q&ME4oT8mk6-$Iq6&eV_MFL0Z6VbvJBXnOnxU6$6 zO_WaZoDXzf+yMgVcHLvUD(mtEc`@aXtM51mJa$Sy%Rh^Ee7+%BFL)zX`?fHBO|S25 z3NB;3K!w8jgTtajqep}q5b~T|M8MfPFo5Tx&LYW-{C_5%GmNC96f3sfi1Y%iMn_}y6d zhPbrG4i0`W4NvCmYXsn2E=@^nT+h!gpt{_x*0jG<@#)yleMmn(<^j$v$twqh5kOKn96RvRPZ}7xKa!)3xJMx zbIQ{?i`eT}?Gk?brN`%SuD;OS-(rf?*6DOv}@TBF2&TEUs!uhaxS;A>Z3Uw zrX6y696!>~?N7pQ*g=UunJ|{1p`;~IKCiUH+&*!$JSs!0{eQJQ8ffU+=93P6%e!vq zJ!iI+v7Ckb9Z`8KD;@C%EJ9w9GuLt)x9=fR(?F)6lMx;7AI>CPGT!<~>2fD$aAA8v z0J|qpA-6iamRC_`{^!`y4@anuMHr3=G;xB)sIvR&%id%uaU^Exd6~Dna6Z}8SOG^z z^pxa}-t2DRIRIoc^Q*I}TV)50z&;b9%Y8wp@2o++>G(y0^D}vp$|l%QT-; z`0A;MlyuN)4ddE&P@pdromLD9km>X3DeWRcf)770Sd~Z`f9T z0R}UCCb#u^A>lfln-?MYMVUOeoCnCRlM43GXL|ghr?Cq2gW~Afh-7Pdp5=iYWG-sTp7<|+kX zGF|4LFn#c7vPJ}@e2T$Cil=(9xRjK{c{i36f9u$lTQzZ?br*{RD_iO1PyLS(GQf699 z(|vIGtn^|9McaM7E_nxaoglRC!X+;lt=xZUK*A|9J)pDi=s!hhXEc%tp3w)6D>$R*H-;g^_I7RD$0mIHG!JZ#$2gCBk8yoglo7^6%+Il!}q}lCGe+xD{=fc=6_?tJOd;|TYrQqnt za8_KBIIqkYs~E5em#Q%eHZQC(E9>@0@E!eAV!?Mm0>>LQW}o)JGT6;pfR+dMlh+ym zdAZVeAk6vtYcg5!q&gNb8`aR68-$PbmayQjCN9s62I-2yboFgs@I?Wbqnn6G(2>!E z!1Ou1c5Z$?OTUgHl>C##kc}jOS=o=<=@^QI8 za0>5xEg)$@3e<2o3$o)Xr2}Y&A5Zc01G8DrCpetqDXF&ATSwg~WGa3BafO20WWyF& ztFE8&e{sVf$^6zL$z|9MxF@o90_+U0FEGEF=x8IT zSDi!%0**s32-3+A0VmFsml~H8iIxo(p+F*_JjaR4XA|`Kjh_hW4+`U;O@mC#xbk3y z0l)iCooDsm0u{#1vT9TpNyh}o3smJz@KR;YA2iK8K zh0xBwz1iEjPe#NP6zbdB#V=Vk5=846p6Nl;iyRo)kWI2m8g-NYOqS0di@E;R7V(}r z-E{V@r(14ygfGuTO4P-QE_+J5vk9`Yy7BA4BfgEOQ9dlBr59AfH_CqcBHWmn0)z{q z`N1q?Es6(v0ucq}66b;L>V$bE(cXU~!T?5aCFVqp$V@t<&C zL;z6TvgdBr{Vou0eo^L7oiKFPD`ER=>DQ}Ov&KZu{2sk7aW*Brv)n=d#l~3p688LJ zf219|B}cEn4h1BTe;8;>EzP9kwnz^JPKl#L)t>gP_(lhWS`1FbO%}MLOH|r$(8WQ{ zQFI^=Et~`#TW2fjYF9d>lOg{hbz-I<+8bf5Vo4o;TE9sJZ|^NtuVAph^-xfG#sIPD zFuzoCKHsNL^8#vB2A36u+glyKp#+O4g*k4bOLHMQD4EbGV$GaPne1SRJ3E`dTOQ?6 z+6Uf7H$q3s_Q&fIyUEEn;78DnP-Lwddj%Q}O+S^!9TV1oq+p%$wz`12=X3e99KnP1 zY>4{7btInf=l&Yr@cKu<{iwPZ;XiPEc8bSK)lJ8R+kvF9jZCoL(ZOX`Xk|``<^T{& zkBJ>CZpRlndzM31wJTt^87M&>l*H^ck(94h9LL(T)IeLa@H6sT)$(NW1huWN_U1p7 zg7pZPW^GO;7E!A)N2z882d zR@v_4WM$oP3YhP)r@;V3XMa9%(tl=to@a32{BmU!a18vf4rX>JP@>GXp_E3j{~j(s zx-OiE{Ed@I(x`H8-`=i+hjHUR#d+zA5blF=X~sf;x~t(cha9Ny>9LGuv7=82LHMx~ zAZFV;JTQED*6JuYd6lRn+pp7Ds!(fqTt%|?VJsLven3~T|;#Ct-gFIUZE z`4wKqs6s`Xm~MEukIeyd_zfignCTw%(sZ~jynCP zQre7MMP74Tg{BD)?;Flu14K-+C$*Ph@FN0PM*^4+=XP z#6REngoSLsw^`s=qbjTHfX5X|mZ~$FKl@%kRJUKe;8XGx0c3CHI}Q3=0VMP1+3))%k&B{vtK#}H)?>9{f!|_$s4lls>V%+t!Xl8GL;#UUoEE= z)VFZw^PZ4(8MpWnQ8NhWd4PLOSHsso9p6V1D+E$xh$qU6yc1{8u>6JWG>HT>7`-xg zvL7ghwAF*9Yda34cx-rQXHgEGU8K0z5We`;^k@jX_{}S-ZZAMD#)~U4=i-3tT#Ber zpl^BCQyQgaNeqmh0t@aCs@ymeWv49ZN!+9F1o)$rOF}cRMxAOS&l_#YqXkAQ);BZ; zr(=>E9Gy@v%}?ep=&c^qUM`+R7l`wWkcc^Ayo}B3q30{(0-?KhD|d1Ql?Ymo2TRoR zaqUxtMjLqWl#Y&$zAZ&LpE|4#1-N=QIb^UtEU&qLIm6zUPbGM^7D`AEbedmvwJ&!C zh~w<-!FG1V{{H9P+-)>S@YE_`lnlO-y!5euG%(I#L@}EiYD%Vlfk$(yA7mw5*b4#zU++m?|n~YRmQ6EpurNjk?F*g~l zIKAetg~vK&ZogzGs(Yl!7RTRC!F=+9oh^b|HC`dbF5l6tdE$NgJwXZ)99bpBi2(y` zONhbb=aMteqtE_m2anMzGCgn!rM6;9I!*}O*|gGeDdF&$d<^B{iLe%3gKXd9hFDI} zBg-+~3LpvbK-ivITTmYi!NB45lkYmSaGFNSu4Jz@Jj&5nf1O~rV9(&W=e9rdNLK=n znZuL!saQ2;e=E9FY$fChtF9XJ=&^ycw~A8op`piS;85~t7H!s$r)|g4BEhxK>oix& zt3aS{Uti|=)HYs@s4UhH2qJm4wxW#EkK(qCTdTjqCofI17nQYd&X2NAW7N4>LzGG) zBUN9+4{WY{3A%{bXqEI}VvBgM+}(d=I=MKz%KP~PwJP5ZJ&mv7^631Jy5BRW<8im{ zn`Y)@ebbUHk)`Kil7F7gP6w-?^i9T#AVKjn7J7sfzU$>1Vumz0uP;l5Q=~VLhtnrc<=l9o&U}`yK}y~ zvu9^!cV|Xurf}uKQ>NGLpI|~*m1^`AG$7Yf#fld?<-snzb%PiV4nB5pjn#eF zgZfa`+Q|0hF>Lkq#Q&0Jjpr)9(#;N*3|ad#!_w0r(I$zpfwTcAju8XZ#^5W>y-qdm zjwJ6~ozQ;`4v?WP4FjIyQyqkhpQwg?AFk$X>2(ws)tEBhtu=ePs+TD2Y}r1?Hy%gTq&BRA1(GJj9hDkIEhP!M_Ov zLf^(_|NoJk`5aeiBQXp3{^ic)&hONghk9+)IbZhi`OyXgzF4#t6xgu=tlMzKskSmL-un&9~wW(%s zAr8(IE)1%z656HPX>@gYmGA^#%X*iN9>5QYRm*&?RHhvF$Vc82+wb|~p!WYqo%6;X zogX^=CcxFuP%jPsz|6@+*R<mOkb&^m^@1vH(^DVVTQY~OB>aLH1GL7F>y4hHy7 zI^=Kx2#kt)X`WbcnDl0)l=l)plnARp0k7Gidk;4{R{-Q?7SYNPR%atB0qj zfxB|p#I_U@%(#_V;Azbe|)Ew=qjR$9?6M@nD{6O z^K+rbg7ex}mv(K?kJZ!UjoE>HCrUm}2D??Uz$ikNMwQyNPfpHpx}SQ|)8pa`zhiP% znIp*}B);XcG1xLivd8$s>6$>t#VnH865efC8&=|e>ji>KHi_)(^(p=MMp{c{9~0#=2m!Eg7G>Q_Wq#9a#8r( zy&*dt%-&0cX)#FvYSNnwd-r|xCpz`%=-l_E8N2I=r9*;7ng6^Cz~&Q_nFvdKh5zX z9#gU2xC!XI%QGIJL^mF-Qe_ipKLfXydvE+AEkn~j1+QRGovm3YFs{#BtZ#>iV<|2u zlt@7pm~~3WL)7uoHQc7$N@|Q(KdmdbaPIop!`bL8p59BmdqHyVSf63}WVfLX3wTtr zLU-yF@A68wHgy02aokwrDv>yxFd$S@`_aCjTPg3Hev3OS2XA_v(lS&==T`&c5S;~J z;0FyQeNgs-^jO~kS4BTkIak3jr_H8g>+o1w4fXUZCRqK&&28bA`xasxe!P6&8Ewb{ zluXm##P3118BLPdvNA}SUX6!Iw`?xH zrZv8mfLl;yN5_(d0+I zr~-fDM<&xYeW@xHDmO7Q`OnNW$`lQgji3GSDV@Dxh(M2cZ5fl#VE%$VfqlYY!SdPW zb1Dk9u+3-pQ^wTtD=Nk(U#_52kMfwK^M9mE-iZu1y`_|Il5a0$Yn)mugce4pI0OQK#$kGzi&2(_{;r6ew=)A%0+@+7MoJ!m|Zy}N?8w}ohu@;HbMdfC?_ zx61K;SC#8{Njyg zrxZbRQwxh>gaFv?u6kz()Vn5tyC>s_DP|8!`x=!$TaBgeOx82b_Sy2C;>wm`O=WM> z$Fc9h#8`gzQhDLX1#+ET(sQxXah(}m1{mKqJ1 zKb(jv2`isppg9NX98hRGp1Oc7n|&17Ep}Z6uJ1>q%gEQsU8oBsWH)=*SrBaOmW+%W zEl{g`YEX6|s+0*`sGZsXkUD9*%D*#8wYF%`n#+efR-y`AtZjD>vUupGLRHd9qlvSB z6D;e<$jllM5s<4ZDk(QUU?N*)TBbiQ@{@@zTwM8n7I(3pP3&#&cX6H=m{82{M?b$j z{yQIV^aK1-l)b%GgujOPaM{H(pjP;{#JBKzvzAP6<+_#0gB3yII*;?EcC?#c;iDvy zq{lz#WU>iO+JdPIS?s!|K)7K#`e$snDn!QmdlbL8F@VQ&bkX}a?iLST1E;w`}FQyo3!Qce)HfAY;eWV+0g!l6eCrW!U}zlvr3C#gC3d zkkRA{c470de&?~v<5FMULZvjmb#__F01YpEHYIvfOM%FX$gdM>%Nn zmfRB0o_jpj%~7A4G^F%NG&-LYJNRV$X%T=MctV-{)I?b>bS z-UtS(=Ly+f*5W!GIIc3kkS|FO6t~ZOx8DYh_Jm}*(oS(#de#W4z>E!{6o)mW_93;y zO2QXfek3GWPnT6Tl>ytAqTU;mLOW}{(*$I=^p)beEn?Bc549U-bt`>n8N3tWC}=Js z8tkz&udQ&PhJguhz5bFME0MDcW&#>ZdhY%aw9dF`nDy*U(1o*xcuZcO`8u>Q@|w$k zb=EJtvYbkfHVHn(YsgBIQ(C@OxJv!75=*0du6C`JOpKmy`ll*8>XT zWlJJ2e@-5?aiB4H#rvOQo<6>2185rzZ)g+!gF69F`%6);>wNq!9IoVz>44rBS5E#ZJV@OideXi?)oh(nU@z3&U1)1sJBKfDhgNMl z_j{#uUgTH5ug=~5x;Wo>D1;f~-Y>-?096DcAgBihz{=pjLWu!(KkC`9u0Hm+=tO&j z{gQl(O=SKQ$$Ww!c_+pu1q|_TPM+LIdhF71y??tq%lfV>3pVGv88X|nB zrW4f@8F?Z%g&;34XAWnUOJPC;H8%~;*!X3TRDi~9wLCvrX`aj?1RRI{I@!1KI+Ari zsmLpNmfuJwr)aN=ST+|3XB9fJBFS3gn{o&>?uW6Fcoy{E|c&9e)^$rROR3zbqgmYXCP|g`mPCj3Fgq zl+g)tm?ea;zc$-qu|HkivLtYdUw*(sGfVF7fsJKY8m-BV)GlwwZ6oLAj*KBfhIF&J z^&n70gDc#7D9ysdx=QCDTz%Vav8$fJWJR2e55E(i@FG#>GSb$jSoGR5SH(4WBE%_O z7=?_rz*fUF9p%_2LFd}q5yA%YX*T7&o;mVxMc zQn80YaoxtlzkCUF*d?bOrHQ75xOAKJnb1+aX))O^-|Xv`iWKc_9D){0E_A!DE@S$` z+597HDry^RYnp1n3#+;9GW7ZJ-6#&26*Wk&25-~$s1_o?3dx2Gg4%7wZ}W7gY`>BZ zgfA-cEr&E#52b{Zj{uR1E{tQd+-i45nstnVDi1utE5}>arzg!{12j3lv3)asVs`l) zR?S%4BX>T|)0G);#wK%!-HCgH9!FeafnI^?2j48-@k`0>GObQ9P4ZhpIsI1VpaJ@z4$iZk}oMr6|Gavz(<=z=wGhqY%F`g8XqeW z&KbprH=J;D_bREzHp-5XL@hEn4QEXI7VrjYk0+uZy$H4QODXyy&?K|j8v7uy{B%F^ zBj-`!VaY1{BAFi1P|M?qFPRx!+77x(_l^>fi*kiM+dlY;(%^$k=x>T>)XZ+?v) z|9k!sPlLQ}#c>YgCrneyex;n`0BMGMl^8Cyp@{0HC2iI}0#8pX$<3 z%+_$jVTYvA8=EX_EzOLGEBesf7BtxcZ#ppbfgOLpC0O&znW)H zY6Fg^S{HXPx3cAS+H0^sTYj9hDtt0I{t^5f8eQ;gsKsGr&*^KtYlAQzW<>op zY2{U`a@ZLY)2aLd>P|De_pEm*9^M?rR^6Ls!K^9cDzJarmOPyx*_ zx?)+}eRlO#%HuMIJ~&tEd7GE(3yk4c=nf(jzpk?bbwTl9HM(Sq;Zm7hV_5v{1SRxk zqn!ycn7;0q*%lqOC7UG{BSWrrq^#5rrP8Y#$7>A?q90pyLdk>maP7Kx(`!9D%2t;r zDrBP$lQv_5n%9opyUn(nt&l#u2OXmB58Z?MaXe*@-xwQUCr~gK%JjqmXYz z`Qu??X+sH7HT(2rh`2s}G9s!#TrTJK^(^0Qh=S0U#jpCxk`qlSTDA8Ouj zP@H{jVX`F*RZxT&sxi+VppUy@DZj4#qlwcobM=={Gs2T12bn!mj_~y84`0Yar2Z z@!BEcdn=GhYQ=TVXB`<%S zTA2-~MoGd(TObIhKlBxgiNvwDsYyerKoU`hc6BpLQ+kW|A~5~EI`HA%DdaSe?^kw# zJ{{8fw=(XX(^E4aT5$wftq7&^Yk}#k1vtHu%;Cm_O~2nGenc$pa1!fByq_i@D%2#s z+6x9B>iLbH93wf2Zox-{sae-_;rK_X4zKe4CGXtWJqYYj?GudoA1b z4FkD~>bellv;LKPyFHCR(1HA(pLB=(R`h`Pyi8v9%ol4hvpkqag8#fFH-DX!<`_}; zIaZssB~NYFwVA9M|HMrgg z>)3()R=-NH_}2L8pE<@%sGTTnpe{(aRH;*1Cevf#aWRY0*X4v6$&5;Su+cG>8bhzY zT868ylyB<}48EJxZJGryhoL6_G>3X{t@+*iYj6QJ-cRIo2EW&dj!K`-Y0nu{BJK0- z5PDDMa!z~~+66^NQ;+rbk;Gs7e~2xo?zB0R;OT(X3aTI;=DTNH1WeVu)Ffo4yWd!~ zuLB>?k61QsD6)P|jEQRUpNk0H!MFTKP`L5AYWaY2&=mJpMbYnk00X46ubs4-1o1e9 zfDJAG5E&6qhb)Zh`Se0V)+4G6oqUG_W>;E&2Dyo?RcPIHxm4J?cXEUIOqZW(%Y-`o zo7T4-iV_gqM@0#^E+N4{1QPH0RhXCegQ%!kkgbQ$pG^>1l@nkBT zkzfv_RFVEXM%KcZbQ;3Jl)50$L$zb@^PEoT8jJC<+h$Af;kTC4eD~woel&__qlr7(}n~QD}zo*<&*XI|kqpWu#Lmn&=n2 zRZiUZ0v7K-kb;2^66#JT`aXxLJYeU1x0y?DJqwMsPfF@zS&x@1b+ivY*B7&sg(@#{ zu;|5pR!r&Pq7VfDvMcPpge_a|-7S;ReE)tq{rn-ogY&-vm$q_Q#)A}9^54hrZc+?c zN2C+((%A#YXvR&S?n_u!9OJ!)g3 zA)%DuI$B&5fS_ULCv#@OPoW0V%;iEmL?f|naNG-pRzyfDl z`$WpiB z;Sn%@01;kjb182|h)$PKn0{6eFm?TmiFJn&E2xG8C&JE^v0{dgPE6p`FkPIWPWpnEO{*({BK~;^(oRQQ(P-Wd2h^Z$9 z9n3ldGo=hFn>dD#Eq($M3YXfn_Ab&p4JU|)U6g_!C5v~459KF|h0TA|CHSxC~Wer9XBK(|mu6C08{Jt%4F)aJSpxrlxymAz!xqP5N4oK5Tsl#Wk}l`gekebGT2DW5jv_l#zD$|}y!mU9&qc`K=t`8BmVU_)J}o;vpMh`@iGm295nQuk gW)b~OVb#CHi`RlHybQT+p7(~Dk`|;)(dza81N!exKmY&$ diff --git a/planning/behavior_velocity_out_of_lane_module/package.xml b/planning/behavior_velocity_out_of_lane_module/package.xml deleted file mode 100644 index 6ea60dd1398f5..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/package.xml +++ /dev/null @@ -1,40 +0,0 @@ - - - - behavior_velocity_out_of_lane_module - 0.1.0 - The behavior_velocity_out_of_lane_module package - - Maxime Clement - Tomoya Kimura - Shumpei Wakabayashi - Takayuki Murooka - - Apache License 2.0 - - ament_cmake_auto - autoware_cmake - autoware_behavior_velocity_planner_common - autoware_perception_msgs - autoware_planning_msgs - geometry_msgs - lanelet2_extension - libboost-dev - motion_utils - pluginlib - rclcpp - route_handler - tf2 - tier4_autoware_utils - tier4_planning_msgs - traffic_light_utils - vehicle_info_util - visualization_msgs - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/planning/behavior_velocity_out_of_lane_module/plugins.xml b/planning/behavior_velocity_out_of_lane_module/plugins.xml deleted file mode 100644 index f85eb50367ccc..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/plugins.xml +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/planning/behavior_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp b/planning/behavior_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp deleted file mode 100644 index 5e3877753d203..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp +++ /dev/null @@ -1,106 +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 CALCULATE_SLOWDOWN_POINTS_HPP_ -#define CALCULATE_SLOWDOWN_POINTS_HPP_ - -#include "footprint.hpp" -#include "types.hpp" - -#include -#include - -#include - -#include -#include - -namespace autoware::behavior_velocity_planner::out_of_lane -{ - -/// @brief estimate whether ego can decelerate without breaking the deceleration limit -/// @details assume ego wants to reach the target point at the target velocity -/// @param [in] ego_data ego data -/// @param [in] point target point -/// @param [in] target_vel target_velocity -bool can_decelerate( - const EgoData & ego_data, const PathPointWithLaneId & point, const double target_vel) -{ - if (ego_data.velocity < 0.5) return true; - const auto dist_ahead_of_ego = motion_utils::calcSignedArcLength( - ego_data.path.points, ego_data.pose.position, point.point.pose.position); - const auto acc_to_target_vel = - (ego_data.velocity * ego_data.velocity - target_vel * target_vel) / (2 * dist_ahead_of_ego); - return acc_to_target_vel < std::abs(ego_data.max_decel); -} - -/// @brief calculate the last pose along the path where ego does not overlap the lane to avoid -/// @param [in] ego_data ego data -/// @param [in] decision the input decision (i.e., which lane to avoid and at what speed) -/// @param [in] footprint the ego footprint -/// @param [in] prev_slowdown_point previous slowdown point. If set, ignore deceleration limits -/// @param [in] params parameters -/// @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 Polygon2d & footprint, - const std::optional & prev_slowdown_point, const PlannerParam & params) -{ - const auto from_arc_length = - motion_utils::calcSignedArcLength(ego_data.path.points, 0, ego_data.first_path_idx); - const auto to_arc_length = - motion_utils::calcSignedArcLength(ego_data.path.points, 0, decision.target_path_idx); - PathPointWithLaneId interpolated_point; - for (auto l = to_arc_length - params.precision; l > from_arc_length; l -= params.precision) { - // TODO(Maxime): binary search - interpolated_point.point.pose = motion_utils::calcInterpolatedPose(ego_data.path.points, l); - const auto respect_decel_limit = - !params.skip_if_over_max_decel || prev_slowdown_point || - can_decelerate(ego_data, interpolated_point, decision.velocity); - const auto interpolated_footprint = project_to_pose(footprint, interpolated_point.point.pose); - const auto is_overlap_lane = boost::geometry::overlaps( - interpolated_footprint, decision.lane_to_avoid.polygon2d().basicPolygon()); - const auto is_overlap_extra_lane = - prev_slowdown_point && - boost::geometry::overlaps( - interpolated_footprint, - prev_slowdown_point->slowdown.lane_to_avoid.polygon2d().basicPolygon()); - if (respect_decel_limit && !is_overlap_lane && !is_overlap_extra_lane) - return interpolated_point; - } - return std::nullopt; -} - -/// @brief calculate the slowdown point to insert in the path -/// @param ego_data ego data (path, velocity, etc) -/// @param decisions decision (before which point to stop, what lane to avoid entering, etc) -/// @param prev_slowdown_point previously calculated slowdown point -/// @param params parameters -/// @return optional slowdown point to insert in the path -std::optional calculate_slowdown_point( - const EgoData & ego_data, const std::vector & decisions, - const std::optional prev_slowdown_point, PlannerParam params) -{ - params.extra_front_offset += params.dist_buffer; - const auto base_footprint = make_base_footprint(params); - - // search for the first slowdown decision for which a stop point can be inserted - for (const auto & decision : decisions) { - const auto last_in_lane_pose = - calculate_last_in_lane_pose(ego_data, decision, base_footprint, prev_slowdown_point, params); - if (last_in_lane_pose) return SlowdownToInsert{decision, *last_in_lane_pose}; - } - return std::nullopt; -} -} // namespace autoware::behavior_velocity_planner::out_of_lane -#endif // CALCULATE_SLOWDOWN_POINTS_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/debug.cpp b/planning/behavior_velocity_out_of_lane_module/src/debug.cpp deleted file mode 100644 index 08e66f99e2a0c..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/debug.cpp +++ /dev/null @@ -1,187 +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 "debug.hpp" - -#include - -#include - -namespace autoware::behavior_velocity_planner::out_of_lane::debug -{ -namespace -{ -visualization_msgs::msg::Marker get_base_marker() -{ - visualization_msgs::msg::Marker base_marker; - base_marker.header.frame_id = "map"; - base_marker.header.stamp = rclcpp::Time(0); - 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 = tier4_autoware_utils::createMarkerPosition(0.0, 0.0, 0); - base_marker.pose.orientation = tier4_autoware_utils::createMarkerOrientation(0, 0, 0, 1.0); - base_marker.scale = tier4_autoware_utils::createMarkerScale(0.1, 0.1, 0.1); - base_marker.color = tier4_autoware_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); - return base_marker; -} -} // namespace -void add_footprint_markers( - visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::BasicPolygons2d & footprints, const double z, const size_t prev_nb) -{ - auto debug_marker = get_base_marker(); - debug_marker.ns = "footprints"; - for (const auto & f : footprints) { - debug_marker.points.clear(); - for (const auto & p : f) - debug_marker.points.push_back( - tier4_autoware_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++; - debug_marker.points.clear(); - } - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) - debug_marker_array.markers.push_back(debug_marker); -} - -void add_current_overlap_marker( - visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::BasicPolygon2d & current_footprint, - const lanelet::ConstLanelets & current_overlapped_lanelets, const double z, const size_t prev_nb) -{ - auto debug_marker = get_base_marker(); - debug_marker.ns = "current_overlap"; - debug_marker.points.clear(); - for (const auto & p : current_footprint) - debug_marker.points.push_back(tier4_autoware_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 = tier4_autoware_utils::createMarkerColor(0.1, 1.0, 0.1, 0.5); - else - debug_marker.color = tier4_autoware_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( - tier4_autoware_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++; - } - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) - debug_marker_array.markers.push_back(debug_marker); -} - -void add_lanelet_markers( - visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::ConstLanelets & lanelets, const std::string & ns, - const std_msgs::msg::ColorRGBA & color, const size_t prev_nb) -{ - auto debug_marker = get_base_marker(); - debug_marker.ns = ns; - debug_marker.color = color; - for (const auto & ll : lanelets) { - debug_marker.points.clear(); - - // add a small z offset to draw above the lanelet map - for (const auto & p : ll.polygon3d()) - debug_marker.points.push_back( - tier4_autoware_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++; - } - debug_marker.action = debug_marker.DELETE; - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) - debug_marker_array.markers.push_back(debug_marker); -} - -void add_range_markers( - visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges, - const tier4_planning_msgs::msg::PathWithLaneId & path, const size_t first_ego_idx, const double z, - const size_t prev_nb) -{ - auto debug_marker = get_base_marker(); - debug_marker.ns = "ranges"; - debug_marker.color = tier4_autoware_utils::createMarkerColor(0.2, 0.9, 0.1, 0.5); - for (const auto & range : ranges) { - debug_marker.points.clear(); - debug_marker.points.push_back( - path.points[first_ego_idx + range.entering_path_idx].point.pose.position); - debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition( - range.entering_point.x(), range.entering_point.y(), z)); - for (const auto & overlap : range.debug.overlaps) { - debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition( - overlap.min_overlap_point.x(), overlap.min_overlap_point.y(), z)); - debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition( - overlap.max_overlap_point.x(), overlap.max_overlap_point.y(), z)); - } - debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition( - range.exiting_point.x(), range.exiting_point.y(), z)); - debug_marker.points.push_back( - path.points[first_ego_idx + range.exiting_path_idx].point.pose.position); - debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; - } - debug_marker.action = debug_marker.DELETE; - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) - debug_marker_array.markers.push_back(debug_marker); - debug_marker.action = debug_marker.ADD; - debug_marker.id = 0; - debug_marker.ns = "decisions"; - debug_marker.color = tier4_autoware_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(tier4_autoware_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); - } - debug_marker_array.markers.push_back(debug_marker); - debug_marker.points.clear(); - debug_marker.id++; - - debug_marker.type = debug_marker.TEXT_VIEW_FACING; - debug_marker.pose.position.x = range.entering_point.x(); - debug_marker.pose.position.y = range.entering_point.y(); - debug_marker.pose.position.z = z; - std::stringstream ss; - ss << "Ego: " << range.debug.times.ego.enter_time << " - " << range.debug.times.ego.exit_time - << "\n"; - if (range.debug.object) { - debug_marker.pose.position.x += - range.debug.object->kinematics.initial_pose_with_covariance.pose.position.x; - debug_marker.pose.position.y += - range.debug.object->kinematics.initial_pose_with_covariance.pose.position.y; - debug_marker.pose.position.x /= 2; - debug_marker.pose.position.y /= 2; - ss << "Obj: " << range.debug.times.object.enter_time << " - " - << range.debug.times.object.exit_time << "\n"; - } - debug_marker.scale.z = 1.0; - debug_marker.text = ss.str(); - debug_marker_array.markers.push_back(debug_marker); - debug_marker.id++; - } - for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) - debug_marker_array.markers.push_back(debug_marker); -} - -} // namespace autoware::behavior_velocity_planner::out_of_lane::debug diff --git a/planning/behavior_velocity_out_of_lane_module/src/debug.hpp b/planning/behavior_velocity_out_of_lane_module/src/debug.hpp deleted file mode 100644 index 05eed6b35c13c..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/debug.hpp +++ /dev/null @@ -1,69 +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 DEBUG_HPP_ -#define DEBUG_HPP_ - -#include "types.hpp" - -#include - -#include - -#include - -namespace autoware::behavior_velocity_planner::out_of_lane::debug -{ -/// @brief add footprint markers to the given marker array -/// @param [inout] debug_marker_array marker array -/// @param [in] footprints footprints to turn into markers -/// @param [in] z z value to use for the markers -/// @param [in] prev_nb previous number of markers (used to delete the extra ones) -void add_footprint_markers( - visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::BasicPolygons2d & footprints, const double z, const size_t prev_nb); -/// @brief add footprint markers to the given marker array -/// @param [inout] debug_marker_array marker array -/// @param [in] current_footprint footprint to turn into a marker -/// @param [in] current_overlapped_lanelets lanelets to turn into markers -/// @param [in] z z value to use for the markers -/// @param [in] prev_nb previous number of markers (used to delete the extra ones) -void add_current_overlap_marker( - visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::BasicPolygon2d & current_footprint, - const lanelet::ConstLanelets & current_overlapped_lanelets, const double z, const size_t prev_nb); -/// @brief add footprint markers to the given marker array -/// @param [inout] debug_marker_array marker array -/// @param [in] lanelets lanelets to turn into markers -/// @param [in] ns namespace of the markers -/// @param [in] color namespace of the markers -/// @param [in] prev_nb previous number of markers (used to delete the extra ones) -void add_lanelet_markers( - visualization_msgs::msg::MarkerArray & debug_marker_array, - const lanelet::ConstLanelets & lanelets, const std::string & ns, - const std_msgs::msg::ColorRGBA & color, const size_t prev_nb); -/// @brief add ranges markers to the given marker array -/// @param [inout] debug_marker_array marker array -/// @param [in] ranges ranges to turn into markers -/// @param [in] path modified ego path that was used to calculate the ranges -/// @param [in] first_path_idx first idx of ego on the path -/// @param [in] z z value to use for the markers -/// @param [in] prev_nb previous number of markers (used to delete the extra ones) -void add_range_markers( - visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges, - const tier4_planning_msgs::msg::PathWithLaneId & path, const size_t first_path_idx, - const double z, const size_t prev_nb); -} // namespace autoware::behavior_velocity_planner::out_of_lane::debug - -#endif // DEBUG_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp b/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp deleted file mode 100644 index 62416c8d38ed6..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp +++ /dev/null @@ -1,383 +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 "decisions.hpp" - -#include -#include -#include -#include - -#include - -#include -#include -#include - -#include -#include -#include -#include -namespace autoware::behavior_velocity_planner::out_of_lane -{ -double distance_along_path(const EgoData & ego_data, const size_t target_idx) -{ - return motion_utils::calcSignedArcLength( - ego_data.path.points, ego_data.pose.position, ego_data.first_path_idx + target_idx); -} - -double time_along_path(const EgoData & ego_data, const size_t target_idx, const double min_velocity) -{ - const auto dist = distance_along_path(ego_data, target_idx); - const auto v = std::max( - std::max(ego_data.velocity, min_velocity), - ego_data.path.points[ego_data.first_path_idx + target_idx].point.longitudinal_velocity_mps * - 0.5); - return dist / v; -} - -bool object_is_incoming( - const lanelet::BasicPoint2d & object_position, - const std::shared_ptr route_handler, - const lanelet::ConstLanelet & lane) -{ - const auto lanelets = route_handler->getPrecedingLaneletSequence(lane, 50.0); - if (boost::geometry::within(object_position, lane.polygon2d().basicPolygon())) return true; - for (const auto & lls : lanelets) - for (const auto & ll : lls) - if (boost::geometry::within(object_position, ll.polygon2d().basicPolygon())) return true; - return false; -} - -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const std::shared_ptr route_handler, const double dist_buffer, - const rclcpp::Logger & logger) -{ - // skip the dynamic object if it is not in a lane preceding the overlapped lane - // lane changes are intentionally not considered - const auto object_point = lanelet::BasicPoint2d( - object.kinematics.initial_pose_with_covariance.pose.position.x, - object.kinematics.initial_pose_with_covariance.pose.position.y); - if (!object_is_incoming(object_point, route_handler, range.lane)) return {}; - - const auto max_deviation = object.shape.dimensions.y + range.inside_distance + dist_buffer; - const auto max_lon_deviation = object.shape.dimensions.x / 2.0; - auto worst_enter_time = std::optional(); - auto worst_exit_time = std::optional(); - - for (const auto & predicted_path : object.kinematics.predicted_paths) { - const auto unique_path_points = 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 = - motion_utils::findNearestSegmentIndex(unique_path_points, enter_point); - const auto enter_offset = motion_utils::calcLongitudinalOffsetToSegment( - unique_path_points, enter_segment_idx, enter_point); - const auto enter_lat_dist = - std::abs(motion_utils::calcLateralOffset(unique_path_points, enter_point, enter_segment_idx)); - const auto enter_segment_length = tier4_autoware_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 = - static_cast(enter_segment_idx) * time_step + enter_offset_ratio * time_step; - - 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 = - motion_utils::findNearestSegmentIndex(unique_path_points, exit_point); - const auto exit_offset = motion_utils::calcLongitudinalOffsetToSegment( - unique_path_points, exit_segment_idx, exit_point); - const auto exit_lat_dist = - std::abs(motion_utils::calcLateralOffset(unique_path_points, exit_point, exit_segment_idx)); - const auto exit_segment_length = tier4_autoware_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 = - static_cast(exit_segment_idx) * time_step + exit_offset_ratio * time_step; - - RCLCPP_DEBUG( - logger, "\t\t\tPredicted path (time step = %2.2fs): enter @ %2.2fs, exit @ %2.2fs", time_step, - enter_time, exit_time); - // predicted path is too far from the overlapping range to be relevant - const auto is_far_from_entering_point = enter_lat_dist > max_deviation; - const auto is_far_from_exiting_point = exit_lat_dist > max_deviation; - if (is_far_from_entering_point && is_far_from_exiting_point) { - RCLCPP_DEBUG( - logger, - " * far_from_enter (%d) = %2.2fm | far_from_exit (%d) = %2.2fm | max_dev = %2.2fm\n", - is_far_from_entering_point, enter_lat_dist, is_far_from_exiting_point, exit_lat_dist, - max_deviation); - continue; - } - const auto is_last_predicted_path_point = - (exit_segment_idx + 2 == unique_path_points.size() || - enter_segment_idx + 2 == unique_path_points.size()); - const auto does_not_reach_overlap = - is_last_predicted_path_point && (std::min(exit_offset, enter_offset) > max_lon_deviation); - if (does_not_reach_overlap) { - RCLCPP_DEBUG( - logger, " * does not reach the overlap = %2.2fm | max_dev = %2.2fm\n", - std::min(exit_offset, enter_offset), max_lon_deviation); - continue; - } - - const auto same_driving_direction_as_ego = enter_time < exit_time; - if (same_driving_direction_as_ego) { - worst_enter_time = worst_enter_time ? std::min(*worst_enter_time, enter_time) : enter_time; - worst_exit_time = worst_exit_time ? std::max(*worst_exit_time, exit_time) : exit_time; - } else { - worst_enter_time = worst_enter_time ? std::max(*worst_enter_time, enter_time) : enter_time; - worst_exit_time = worst_exit_time ? std::min(*worst_exit_time, exit_time) : exit_time; - } - } - if (worst_enter_time && worst_exit_time) { - RCLCPP_DEBUG( - logger, "\t\t\t * found enter/exit time [%2.2f, %2.2f]\n", *worst_enter_time, - *worst_exit_time); - return std::make_pair(*worst_enter_time, *worst_exit_time); - } - RCLCPP_DEBUG(logger, "\t\t\t * enter/exit time not found\n"); - return {}; -} - -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const DecisionInputs & inputs, const rclcpp::Logger & logger) -{ - const auto & p = object.kinematics.initial_pose_with_covariance.pose.position; - const auto object_point = lanelet::BasicPoint2d(p.x, p.y); - const auto half_size = object.shape.dimensions.x / 2.0; - lanelet::ConstLanelets object_lanelets; - for (const auto & ll : inputs.lanelets) - if (boost::geometry::within(object_point, ll.polygon2d().basicPolygon())) - object_lanelets.push_back(ll); - - geometry_msgs::msg::Pose pose; - pose.position.set__x(range.entering_point.x()).set__y(range.entering_point.y()); - const auto range_enter_length = lanelet::utils::getArcCoordinates({range.lane}, pose).length; - pose.position.set__x(range.exiting_point.x()).set__y(range.exiting_point.y()); - const auto range_exit_length = lanelet::utils::getArcCoordinates({range.lane}, pose).length; - const auto range_size = std::abs(range_enter_length - range_exit_length); - auto worst_enter_dist = std::optional(); - auto worst_exit_dist = std::optional(); - for (const auto & lane : object_lanelets) { - const auto path = inputs.route_handler->getRoutingGraphPtr()->shortestPath(lane, range.lane); - RCLCPP_DEBUG( - logger, "\t\t\tPath ? %d [from %ld to %ld]\n", path.has_value(), lane.id(), range.lane.id()); - if (path) { - lanelet::ConstLanelets lls; - for (const auto & ll : *path) lls.push_back(ll); - pose.position.set__x(object_point.x()).set__y(object_point.y()); - const auto object_curr_length = lanelet::utils::getArcCoordinates(lls, pose).length; - pose.position.set__x(range.entering_point.x()).set__y(range.entering_point.y()); - const auto enter_dist = - lanelet::utils::getArcCoordinates(lls, pose).length - object_curr_length; - pose.position.set__x(range.exiting_point.x()).set__y(range.exiting_point.y()); - const auto exit_dist = - lanelet::utils::getArcCoordinates(lls, pose).length - object_curr_length; - RCLCPP_DEBUG( - logger, "\t\t\t%2.2f -> [%2.2f(%2.2f, %2.2f) - %2.2f(%2.2f, %2.2f)]\n", object_curr_length, - enter_dist, range.entering_point.x(), range.entering_point.y(), exit_dist, - range.exiting_point.x(), range.exiting_point.y()); - const auto already_entered_range = std::abs(enter_dist - exit_dist) > range_size * 2.0; - if (already_entered_range) continue; - // multiple paths to the overlap -> be conservative and use the "worst" case - // "worst" = min/max arc length depending on if the lane is running opposite to the ego path - const auto is_opposite = enter_dist > exit_dist; - if (!worst_enter_dist) - worst_enter_dist = enter_dist; - else if (is_opposite) - worst_enter_dist = std::max(*worst_enter_dist, enter_dist); - else - worst_enter_dist = std::min(*worst_enter_dist, enter_dist); - if (!worst_exit_dist) - worst_exit_dist = exit_dist; - else if (is_opposite) - worst_exit_dist = std::max(*worst_exit_dist, exit_dist); - else - worst_exit_dist = std::min(*worst_exit_dist, exit_dist); - } - } - if (worst_enter_dist && worst_exit_dist) { - const auto v = object.kinematics.initial_twist_with_covariance.twist.linear.x; - return std::make_pair((*worst_enter_dist - half_size) / v, (*worst_exit_dist + half_size) / v); - } - return {}; -} - -bool threshold_condition(const RangeTimes & range_times, const PlannerParam & params) -{ - const auto enter_within_threshold = - range_times.object.enter_time > 0.0 && range_times.object.enter_time < params.time_threshold; - const auto exit_within_threshold = - range_times.object.exit_time > 0.0 && range_times.object.exit_time < params.time_threshold; - return enter_within_threshold || exit_within_threshold; -} - -bool intervals_condition( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) -{ - const auto opposite_way_condition = [&]() -> bool { - const auto ego_exits_before_object_enters = - range_times.ego.exit_time + params.intervals_ego_buffer < - range_times.object.enter_time + params.intervals_obj_buffer; - RCLCPP_DEBUG( - logger, - "\t\t\t[Intervals] (opposite way) ego exit %2.2fs < obj enter %2.2fs ? -> should not " - "enter = %d\n", - range_times.ego.exit_time + params.intervals_ego_buffer, - range_times.object.enter_time + params.intervals_obj_buffer, ego_exits_before_object_enters); - return ego_exits_before_object_enters; - }; - const auto same_way_condition = [&]() -> bool { - const auto object_enters_during_overlap = - range_times.ego.enter_time - params.intervals_ego_buffer < - range_times.object.enter_time + params.intervals_obj_buffer && - range_times.object.enter_time - params.intervals_obj_buffer - range_times.ego.exit_time < - range_times.ego.exit_time + params.intervals_ego_buffer; - const auto object_exits_during_overlap = - range_times.ego.enter_time - params.intervals_ego_buffer < - range_times.object.exit_time + params.intervals_obj_buffer && - range_times.object.exit_time - params.intervals_obj_buffer - range_times.ego.exit_time < - range_times.ego.exit_time + params.intervals_ego_buffer; - RCLCPP_DEBUG( - logger, - "\t\t\t[Intervals] obj enters during overlap ? %d OR obj exits during overlap %d ? -> should " - "not " - "enter = %d\n", - object_enters_during_overlap, object_exits_during_overlap, - object_enters_during_overlap || object_exits_during_overlap); - return object_enters_during_overlap || object_exits_during_overlap; - }; - - const auto object_is_going_same_way = - range_times.object.enter_time < range_times.object.exit_time; - return (object_is_going_same_way && same_way_condition()) || - (!object_is_going_same_way && opposite_way_condition()); -} - -bool ttc_condition( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) -{ - const auto ttc_at_enter = range_times.ego.enter_time - range_times.object.enter_time; - const auto ttc_at_exit = range_times.ego.exit_time - range_times.object.exit_time; - const auto collision_during_overlap = (ttc_at_enter < 0.0) != (ttc_at_exit < 0.0); - const auto ttc_is_bellow_threshold = - std::min(std::abs(ttc_at_enter), std::abs(ttc_at_exit)) <= params.ttc_threshold; - RCLCPP_DEBUG( - logger, "\t\t\t[TTC] (%2.2fs - %2.2fs) -> %d\n", ttc_at_enter, ttc_at_exit, - (collision_during_overlap || ttc_is_bellow_threshold)); - return collision_during_overlap || ttc_is_bellow_threshold; -} - -bool will_collide_on_range( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) -{ - RCLCPP_DEBUG( - logger, " enter at %2.2fs, exits at %2.2fs\n", range_times.object.enter_time, - range_times.object.exit_time); - return (params.mode == "threshold" && threshold_condition(range_times, params)) || - (params.mode == "intervals" && intervals_condition(range_times, params, logger)) || - (params.mode == "ttc" && ttc_condition(range_times, params, logger)); -} - -bool should_not_enter( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger) -{ - RangeTimes range_times{}; - range_times.ego.enter_time = - time_along_path(inputs.ego_data, range.entering_path_idx, params.ego_min_velocity); - range_times.ego.exit_time = - time_along_path(inputs.ego_data, range.exiting_path_idx, params.ego_min_velocity); - RCLCPP_DEBUG( - logger, "\t[%lu -> %lu] %ld | ego enters at %2.2f, exits at %2.2f\n", range.entering_path_idx, - range.exiting_path_idx, range.lane.id(), range_times.ego.enter_time, range_times.ego.exit_time); - for (const auto & object : inputs.objects.objects) { - RCLCPP_DEBUG( - logger, "\t\t[%s] going at %2.2fm/s", - tier4_autoware_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); - continue; // skip objects with velocity bellow a threshold - } - // skip objects that are already on the interval - const auto enter_exit_time = - params.objects_use_predicted_paths - ? object_time_to_range( - object, range, inputs.route_handler, params.objects_dist_buffer, logger) - : object_time_to_range(object, range, inputs, logger); - if (!enter_exit_time) { - RCLCPP_DEBUG(logger, " SKIP (no enter/exit times found)\n"); - continue; // skip objects that are not driving towards the overlapping range - } - - range_times.object.enter_time = enter_exit_time->first; - range_times.object.exit_time = enter_exit_time->second; - if (will_collide_on_range(range_times, params, logger)) { - range.debug.times = range_times; - range.debug.object = object; - return true; - } - } - range.debug.times = range_times; - return false; -} - -void set_decision_velocity( - std::optional & decision, const double distance, const PlannerParam & params) -{ - if (distance < params.stop_dist_threshold) { - decision->velocity = 0.0; - } else if (distance < params.slow_dist_threshold) { - decision->velocity = params.slow_velocity; - } else { - decision.reset(); - } -} - -std::optional calculate_decision( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger) -{ - std::optional decision; - if (should_not_enter(range, inputs, params, logger)) { - decision.emplace(); - decision->target_path_idx = - inputs.ego_data.first_path_idx + range.entering_path_idx; // add offset from curr pose - decision->lane_to_avoid = range.lane; - const auto ego_dist_to_range = distance_along_path(inputs.ego_data, range.entering_path_idx); - set_decision_velocity(decision, ego_dist_to_range, params); - } - return decision; -} - -std::vector calculate_decisions( - const DecisionInputs & inputs, const PlannerParam & params, const rclcpp::Logger & logger) -{ - std::vector decisions; - for (const auto & range : inputs.ranges) { - if (range.entering_path_idx == 0UL) continue; // skip if we already entered the range - const auto optional_decision = calculate_decision(range, inputs, params, logger); - range.debug.decision = optional_decision; - if (optional_decision) decisions.push_back(*optional_decision); - } - return decisions; -} - -} // namespace autoware::behavior_velocity_planner::out_of_lane diff --git a/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp b/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp deleted file mode 100644 index 27c5b00c96b3f..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp +++ /dev/null @@ -1,115 +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 DECISIONS_HPP_ -#define DECISIONS_HPP_ - -#include "types.hpp" - -#include -#include - -#include - -#include - -#include -#include -#include -#include - -namespace autoware::behavior_velocity_planner::out_of_lane -{ -/// @brief calculate the distance along the ego path between ego and some target path index -/// @param [in] ego_data data related to the ego vehicle -/// @param [in] target_idx target ego path index -/// @return distance between ego and the target [m] -double distance_along_path(const EgoData & ego_data, const size_t target_idx); -/// @brief estimate the time when ego will reach some target path index -/// @param [in] ego_data data related to the ego vehicle -/// @param [in] target_idx target ego path index -/// @param [in] min_velocity minimum ego velocity used to estimate the time -/// @return time taken by ego to reach the target [s] -double time_along_path(const EgoData & ego_data, const size_t target_idx); -/// @brief use an object's predicted paths to estimate the times it will reach the enter and exit -/// points of an overlapping range -/// @details times when the predicted paths of the object enters/exits the range are calculated -/// but may not exist (e.g,, predicted path ends before reaching the end of the range) -/// @param [in] object dynamic object -/// @param [in] range overlapping range -/// @param [in] route_handler route handler used to estimate the path of the dynamic object -/// @param [in] logger ros logger -/// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in -/// the opposite direction, time at enter > time at exit -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const std::shared_ptr route_handler, const double dist_buffer, - const rclcpp::Logger & logger); -/// @brief use the lanelet map to estimate the times when an object will reach the enter and exit -/// points of an overlapping range -/// @param [in] object dynamic object -/// @param [in] range overlapping range -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] dist_buffer extra distance used to estimate if a collision will occur on the range -/// @param [in] logger ros logger -/// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in -/// the opposite direction, time at enter > time at exit. -std::optional> object_time_to_range( - const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const DecisionInputs & inputs, const rclcpp::Logger & logger); -/// @brief decide whether an object is coming in the range at the same time as ego -/// @details the condition depends on the mode (threshold, intervals, ttc) -/// @param [in] range_times times when ego and the object enter/exit the range -/// @param [in] params parameters -/// @param [in] logger ros logger -bool will_collide_on_range( - const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger); -/// @brief check whether we should avoid entering the given range -/// @param [in] range the range to check -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] params parameters -/// @param [in] logger ros logger -/// @return return true if we should avoid entering the range -bool should_not_enter( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger); -/// @brief set the velocity of a decision (or unset it) based on the distance away from the range -/// @param [out] decision decision to update (either set its velocity or unset the decision) -/// @param [in] distance distance between ego and the range corresponding to the decision -/// @param [in] params parameters -void set_decision_velocity( - std::optional & decision, const double distance, const PlannerParam & params); -/// @brief calculate the decision to slowdown or stop before an overlapping range -/// @param [in] range the range to check -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] params parameters -/// @param [in] logger ros logger -/// @return return an optional decision to slowdown or stop -std::optional calculate_decision( - const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, - const rclcpp::Logger & logger); -/// @brief calculate decisions to slowdown or stop before some overlapping ranges -/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route -/// handler, lanelets) -/// @param [in] params parameters -/// @param [in] logger ros logger -/// @return return the calculated decisions to slowdown or stop -std::vector calculate_decisions( - const DecisionInputs & inputs, const PlannerParam & params, const rclcpp::Logger & logger); -} // namespace autoware::behavior_velocity_planner::out_of_lane - -#endif // DECISIONS_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.cpp b/planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.cpp deleted file mode 100644 index bb352f625580f..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.cpp +++ /dev/null @@ -1,146 +0,0 @@ -// Copyright 2023-2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// 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 "filter_predicted_objects.hpp" - -#include -#include - -#include - -#include -#include - -#include - -namespace autoware::behavior_velocity_planner::out_of_lane -{ -void cut_predicted_path_beyond_line( - autoware_perception_msgs::msg::PredictedPath & predicted_path, - const lanelet::BasicLineString2d & stop_line, const double object_front_overhang) -{ - auto stop_line_idx = 0UL; - bool found = false; - lanelet::BasicSegment2d path_segment; - path_segment.first.x() = predicted_path.path.front().position.x; - path_segment.first.y() = predicted_path.path.front().position.y; - for (stop_line_idx = 1; stop_line_idx < predicted_path.path.size(); ++stop_line_idx) { - path_segment.second.x() = predicted_path.path[stop_line_idx].position.x; - path_segment.second.y() = predicted_path.path[stop_line_idx].position.y; - if (boost::geometry::intersects(stop_line, path_segment)) { - found = true; - break; - } - path_segment.first = path_segment.second; - } - if (found) { - auto cut_idx = stop_line_idx; - double arc_length = 0; - while (cut_idx > 0 && arc_length < object_front_overhang) { - arc_length += tier4_autoware_utils::calcDistance2d( - predicted_path.path[cut_idx], predicted_path.path[cut_idx - 1]); - --cut_idx; - } - predicted_path.path.resize(cut_idx); - } -} - -std::optional find_next_stop_line( - const autoware_perception_msgs::msg::PredictedPath & path, const PlannerData & planner_data) -{ - lanelet::ConstLanelets lanelets; - lanelet::BasicLineString2d query_line; - for (const auto & p : path.path) query_line.emplace_back(p.position.x, p.position.y); - const auto query_results = lanelet::geometry::findWithin2d( - planner_data.route_handler_->getLaneletMapPtr()->laneletLayer, query_line); - for (const auto & r : query_results) lanelets.push_back(r.second); - for (const auto & ll : lanelets) { - for (const auto & element : ll.regulatoryElementsAs()) { - const auto traffic_signal_stamped = planner_data.getTrafficSignal(element->id()); - if ( - traffic_signal_stamped.has_value() && element->stopLine().has_value() && - traffic_light_utils::isTrafficSignalStop(ll, traffic_signal_stamped.value().signal)) { - lanelet::BasicLineString2d stop_line; - for (const auto & p : *(element->stopLine())) stop_line.emplace_back(p.x(), p.y()); - return stop_line; - } - } - } - return std::nullopt; -} - -void cut_predicted_path_beyond_red_lights( - autoware_perception_msgs::msg::PredictedPath & predicted_path, const PlannerData & planner_data, - const double object_front_overhang) -{ - const auto stop_line = find_next_stop_line(predicted_path, planner_data); - if (stop_line) { - // we use a longer stop line to also cut predicted paths that slightly go around the stop line - auto longer_stop_line = *stop_line; - const auto diff = stop_line->back() - stop_line->front(); - longer_stop_line.front() -= diff * 0.5; - longer_stop_line.back() += diff * 0.5; - cut_predicted_path_beyond_line(predicted_path, longer_stop_line, object_front_overhang); - } -} - -autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( - const PlannerData & planner_data, const EgoData & ego_data, const PlannerParam & params) -{ - autoware_perception_msgs::msg::PredictedObjects filtered_objects; - filtered_objects.header = planner_data.predicted_objects->header; - for (const auto & object : planner_data.predicted_objects->objects) { - const auto is_pedestrian = - std::find_if(object.classification.begin(), object.classification.end(), [](const auto & c) { - return c.label == autoware_perception_msgs::msg::ObjectClassification::PEDESTRIAN; - }) != object.classification.end(); - if (is_pedestrian) continue; - - 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 = motion_utils::removeOverlapPoints(predicted_path.path); - if (no_overlap_path.size() <= 1) return true; - const auto lat_offset_to_current_ego = - std::abs(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( - params.left_offset + params.extra_left_offset, - params.right_offset + params.extra_right_offset); - return is_low_confidence || is_crossing_ego; - }; - if (params.objects_use_predicted_paths) { - auto & predicted_paths = filtered_object.kinematics.predicted_paths; - const auto new_end = - std::remove_if(predicted_paths.begin(), predicted_paths.end(), is_invalid_predicted_path); - predicted_paths.erase(new_end, predicted_paths.end()); - if (params.objects_cut_predicted_paths_beyond_red_lights) - for (auto & predicted_path : predicted_paths) - cut_predicted_path_beyond_red_lights( - predicted_path, planner_data, filtered_object.shape.dimensions.x); - predicted_paths.erase( - std::remove_if( - predicted_paths.begin(), predicted_paths.end(), - [](const auto & p) { return p.path.empty(); }), - predicted_paths.end()); - } - - if (!params.objects_use_predicted_paths || !filtered_object.kinematics.predicted_paths.empty()) - filtered_objects.objects.push_back(filtered_object); - } - return filtered_objects; -} - -} // namespace autoware::behavior_velocity_planner::out_of_lane diff --git a/planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.hpp b/planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.hpp deleted file mode 100644 index a12b37e4c7d6d..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.hpp +++ /dev/null @@ -1,57 +0,0 @@ -// Copyright 2023-2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// 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 FILTER_PREDICTED_OBJECTS_HPP_ -#define FILTER_PREDICTED_OBJECTS_HPP_ - -#include "types.hpp" - -#include - -#include - -namespace autoware::behavior_velocity_planner::out_of_lane -{ -/// @brief cut a predicted path beyond the given stop line -/// @param [inout] predicted_path predicted path to cut -/// @param [in] stop_line stop line used for cutting -/// @param [in] object_front_overhang extra distance to cut ahead of the stop line -void cut_predicted_path_beyond_line( - autoware_perception_msgs::msg::PredictedPath & predicted_path, - const lanelet::BasicLineString2d & stop_line, const double object_front_overhang); - -/// @brief find the next red light stop line along the given path -/// @param [in] path predicted path to check for a stop line -/// @param [in] planner_data planner data with stop line information -/// @return the first red light stop line found along the path (if any) -std::optional find_next_stop_line( - const autoware_perception_msgs::msg::PredictedPath & path, const PlannerData & planner_data); - -/// @brief cut predicted path beyond stop lines of red lights -/// @param [inout] predicted_path predicted path to cut -/// @param [in] planner_data planner data to get the map and traffic light information -void cut_predicted_path_beyond_red_lights( - autoware_perception_msgs::msg::PredictedPath & predicted_path, const PlannerData & planner_data, - const double object_front_overhang); - -/// @brief filter predicted objects and their predicted paths -/// @param [in] planner_data planner data -/// @param [in] ego_data ego data -/// @param [in] params parameters -/// @return filtered predicted objects -autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( - const PlannerData & planner_data, const EgoData & ego_data, const PlannerParam & params); -} // namespace autoware::behavior_velocity_planner::out_of_lane - -#endif // FILTER_PREDICTED_OBJECTS_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/footprint.cpp b/planning/behavior_velocity_out_of_lane_module/src/footprint.cpp deleted file mode 100644 index 48992e46ec74f..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/footprint.cpp +++ /dev/null @@ -1,90 +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 "footprint.hpp" - -#include - -#include - -#include -#include - -#include -#include - -namespace autoware::behavior_velocity_planner::out_of_lane -{ -tier4_autoware_utils::Polygon2d make_base_footprint( - const PlannerParam & p, const bool ignore_offset) -{ - tier4_autoware_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; - const auto left_offset = ignore_offset ? 0.0 : p.extra_left_offset; - base_footprint.outer() = { - {p.front_offset + front_offset, p.left_offset + left_offset}, - {p.front_offset + front_offset, p.right_offset - right_offset}, - {p.rear_offset - rear_offset, p.right_offset - right_offset}, - {p.rear_offset - rear_offset, p.left_offset + left_offset}}; - return base_footprint; -} - -lanelet::BasicPolygon2d project_to_pose( - const tier4_autoware_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose) -{ - const auto angle = tf2::getYaw(pose.orientation); - const auto rotated_footprint = tier4_autoware_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); - return footprint; -} - -std::vector calculate_path_footprints( - const EgoData & ego_data, const PlannerParam & params) -{ - const auto base_footprint = make_base_footprint(params); - std::vector path_footprints; - path_footprints.reserve(ego_data.path.points.size()); - double length = 0.0; - const auto range = std::max(params.slow_dist_threshold, params.stop_dist_threshold) + - params.front_offset + params.extra_front_offset; - for (auto i = ego_data.first_path_idx; i < ego_data.path.points.size() && length < range; ++i) { - const auto & path_pose = ego_data.path.points[i].point.pose; - const auto angle = tf2::getYaw(path_pose.orientation); - const auto rotated_footprint = tier4_autoware_utils::rotatePolygon(base_footprint, angle); - lanelet::BasicPolygon2d footprint; - for (const auto & p : rotated_footprint.outer()) - footprint.emplace_back(p.x() + path_pose.position.x, p.y() + path_pose.position.y); - path_footprints.push_back(footprint); - if (i + 1 < ego_data.path.points.size()) - length += tier4_autoware_utils::calcDistance2d(path_pose, ego_data.path.points[i + 1].point); - } - return path_footprints; -} - -lanelet::BasicPolygon2d calculate_current_ego_footprint( - const EgoData & ego_data, const PlannerParam & params, const bool ignore_offset) -{ - const auto base_footprint = make_base_footprint(params, ignore_offset); - const auto angle = tf2::getYaw(ego_data.pose.orientation); - const auto rotated_footprint = tier4_autoware_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); - return footprint; -} -} // namespace autoware::behavior_velocity_planner::out_of_lane diff --git a/planning/behavior_velocity_out_of_lane_module/src/footprint.hpp b/planning/behavior_velocity_out_of_lane_module/src/footprint.hpp deleted file mode 100644 index 1a0d38600fe73..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/footprint.hpp +++ /dev/null @@ -1,59 +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 FOOTPRINT_HPP_ -#define FOOTPRINT_HPP_ - -#include "types.hpp" - -#include - -#include - -namespace autoware::behavior_velocity_planner -{ -namespace out_of_lane -{ -/// @brief create the base footprint of ego -/// @param [in] p parameters used to create the footprint -/// @param [in] ignore_offset optional parameter, if true, ignore the "extra offsets" to build the -/// footprint -/// @return base ego footprint -tier4_autoware_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 tier4_autoware_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose); -/// @brief calculate the path footprints -/// @details the resulting polygon follows the format used by the lanelet library: clockwise order -/// and implicit closing edge -/// @param [in] ego_data data related to the ego vehicle (includes its path) -/// @param [in] params parameters -/// @return polygon footprints for each path point starting from ego's current position -std::vector calculate_path_footprints( - const EgoData & ego_data, const PlannerParam & params); -/// @brief calculate the current ego footprint -/// @param [in] ego_data data related to the ego vehicle -/// @param [in] params parameters -/// @param [in] ignore_offset optional parameter, if true, ignore the "extra offsets" to build the -/// footprint -lanelet::BasicPolygon2d calculate_current_ego_footprint( - const EgoData & ego_data, const PlannerParam & params, const bool ignore_offset = false); -} // namespace out_of_lane -} // namespace autoware::behavior_velocity_planner - -#endif // FOOTPRINT_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp deleted file mode 100644 index 42df39853f4f5..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp +++ /dev/null @@ -1,130 +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 "lanelets_selection.hpp" - -#include - -#include -#include - -#include -#include - -namespace autoware::behavior_velocity_planner::out_of_lane -{ - -lanelet::ConstLanelets consecutive_lanelets( - const route_handler::RouteHandler & route_handler, const lanelet::ConstLanelet & lanelet) -{ - lanelet::ConstLanelets consecutives = route_handler.getRoutingGraphPtr()->following(lanelet); - const auto previous = route_handler.getRoutingGraphPtr()->previous(lanelet); - consecutives.insert(consecutives.end(), previous.begin(), previous.end()); - return consecutives; -} - -lanelet::ConstLanelets get_missing_lane_change_lanelets( - lanelet::ConstLanelets & path_lanelets, const route_handler::RouteHandler & route_handler) -{ - lanelet::ConstLanelets missing_lane_change_lanelets; - const auto & routing_graph = *route_handler.getRoutingGraphPtr(); - lanelet::ConstLanelets adjacents; - lanelet::ConstLanelets consecutives; - for (const auto & ll : path_lanelets) { - const auto consecutives_of_ll = consecutive_lanelets(route_handler, ll); - std::copy_if( - consecutives_of_ll.begin(), consecutives_of_ll.end(), std::back_inserter(consecutives), - [&](const auto & l) { return !contains_lanelet(consecutives, l.id()); }); - const auto adjacents_of_ll = routing_graph.besides(ll); - std::copy_if( - adjacents_of_ll.begin(), adjacents_of_ll.end(), std::back_inserter(adjacents), - [&](const auto & l) { return !contains_lanelet(adjacents, l.id()); }); - } - std::copy_if( - adjacents.begin(), adjacents.end(), std::back_inserter(missing_lane_change_lanelets), - [&](const auto & l) { - return !contains_lanelet(missing_lane_change_lanelets, l.id()) && - !contains_lanelet(path_lanelets, l.id()) && contains_lanelet(consecutives, l.id()); - }); - return missing_lane_change_lanelets; -} - -lanelet::ConstLanelets calculate_path_lanelets( - const EgoData & ego_data, const route_handler::RouteHandler & route_handler) -{ - const auto lanelet_map_ptr = route_handler.getLaneletMapPtr(); - lanelet::ConstLanelets path_lanelets; - lanelet::BasicLineString2d path_ls; - for (const auto & p : ego_data.path.points) - path_ls.emplace_back(p.point.pose.position.x, p.point.pose.position.y); - for (const auto & dist_lanelet : - lanelet::geometry::findWithin2d(lanelet_map_ptr->laneletLayer, path_ls)) { - if (!contains_lanelet(path_lanelets, dist_lanelet.second.id())) - path_lanelets.push_back(dist_lanelet.second); - } - const auto missing_lanelets = get_missing_lane_change_lanelets(path_lanelets, route_handler); - path_lanelets.insert(path_lanelets.end(), missing_lanelets.begin(), missing_lanelets.end()); - return path_lanelets; -} - -void add_lane_changeable_lanelets( - lanelet::ConstLanelets & lanelets_to_ignore, const lanelet::ConstLanelets & path_lanelets, - const route_handler::RouteHandler & route_handler) -{ - for (const auto & path_lanelet : path_lanelets) - for (const auto & ll : route_handler.getLaneChangeableNeighbors(path_lanelet)) - if (!contains_lanelet(lanelets_to_ignore, ll.id())) lanelets_to_ignore.push_back(ll); -} - -lanelet::ConstLanelets calculate_ignored_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & path_lanelets, - const route_handler::RouteHandler & route_handler, const PlannerParam & params) -{ - lanelet::ConstLanelets ignored_lanelets; - // ignore lanelets directly behind ego - const auto behind = - planning_utils::calculateOffsetPoint2d(ego_data.pose, params.rear_offset, 0.0); - const lanelet::BasicPoint2d behind_point(behind.x(), behind.y()); - const auto behind_lanelets = lanelet::geometry::findWithin2d( - route_handler.getLaneletMapPtr()->laneletLayer, behind_point, 0.0); - for (const auto & l : behind_lanelets) { - const auto is_path_lanelet = contains_lanelet(path_lanelets, l.second.id()); - if (!is_path_lanelet) ignored_lanelets.push_back(l.second); - } - if (params.ignore_overlaps_over_lane_changeable_lanelets) - add_lane_changeable_lanelets(ignored_lanelets, path_lanelets, route_handler); - return ignored_lanelets; -} - -lanelet::ConstLanelets calculate_other_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & path_lanelets, - const lanelet::ConstLanelets & ignored_lanelets, - const route_handler::RouteHandler & route_handler, const PlannerParam & params) -{ - lanelet::ConstLanelets other_lanelets; - const lanelet::BasicPoint2d ego_point(ego_data.pose.position.x, ego_data.pose.position.y); - const auto lanelets_within_range = lanelet::geometry::findWithin2d( - route_handler.getLaneletMapPtr()->laneletLayer, ego_point, - std::max(params.slow_dist_threshold, params.stop_dist_threshold) + params.front_offset + - params.extra_front_offset); - for (const auto & ll : lanelets_within_range) { - if (std::string(ll.second.attributeOr(lanelet::AttributeName::Subtype, "none")) != "road") - continue; - const auto is_path_lanelet = contains_lanelet(path_lanelets, ll.second.id()); - const auto is_ignored_lanelet = contains_lanelet(ignored_lanelets, ll.second.id()); - if (!is_path_lanelet && !is_ignored_lanelet) other_lanelets.push_back(ll.second); - } - return other_lanelets; -} -} // namespace autoware::behavior_velocity_planner::out_of_lane diff --git a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp deleted file mode 100644 index 8985a49a12853..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp +++ /dev/null @@ -1,73 +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 LANELETS_SELECTION_HPP_ -#define LANELETS_SELECTION_HPP_ - -#include "types.hpp" - -#include - -#include - -namespace autoware::behavior_velocity_planner::out_of_lane -{ -/// @brief checks if a lanelet is already contained in a vector of lanelets -/// @param [in] lanelets vector to check -/// @param [in] id lanelet id to check -/// @return true if the given vector contains a lanelet of the given id -inline bool contains_lanelet(const lanelet::ConstLanelets & lanelets, const lanelet::Id id) -{ - return std::find_if(lanelets.begin(), lanelets.end(), [&](const auto & l) { - return l.id() == id; - }) != lanelets.end(); -}; - -/// @brief calculate lanelets crossed by the ego path -/// @details calculated from the ids of the path msg, the lanelets containing path points -/// @param [in] ego_data data about the ego vehicle -/// @param [in] route_handler route handler -/// @return lanelets crossed by the ego vehicle -lanelet::ConstLanelets calculate_path_lanelets( - const EgoData & ego_data, const route_handler::RouteHandler & route_handler); -/// @brief calculate lanelets that may not be crossed by the path but may be overlapped during a -/// lane change -/// @param [in] path_lanelets lanelets driven by the ego vehicle -/// @param [in] route_handler route handler -/// @return lanelets that may be overlapped by a lane change (and are not already in path_lanelets) -lanelet::ConstLanelets get_missing_lane_change_lanelets( - lanelet::ConstLanelets & path_lanelets, const route_handler::RouteHandler & route_handler); -/// @brief calculate lanelets that should be ignored -/// @param [in] ego_data data about the ego vehicle -/// @param [in] path_lanelets lanelets driven by the ego vehicle -/// @param [in] route_handler route handler -/// @param [in] params parameters -/// @return lanelets to ignore -lanelet::ConstLanelets calculate_ignored_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & path_lanelets, - const route_handler::RouteHandler & route_handler, const PlannerParam & params); -/// @brief calculate lanelets that should be checked by the module -/// @param [in] ego_data data about the ego vehicle -/// @param [in] path_lanelets lanelets driven by the ego vehicle -/// @param [in] ignored_lanelets lanelets to ignore -/// @param [in] route_handler route handler -/// @param [in] params parameters -/// @return lanelets to check for overlaps -lanelet::ConstLanelets calculate_other_lanelets( - const EgoData & ego_data, const lanelet::ConstLanelets & path_lanelets, - const lanelet::ConstLanelets & ignored_lanelets, - const route_handler::RouteHandler & route_handler, const PlannerParam & params); -} // namespace autoware::behavior_velocity_planner::out_of_lane - -#endif // LANELETS_SELECTION_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/manager.cpp b/planning/behavior_velocity_out_of_lane_module/src/manager.cpp deleted file mode 100644 index 61ec1a832bf8e..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/manager.cpp +++ /dev/null @@ -1,108 +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 "manager.hpp" - -#include "scene_out_of_lane.hpp" - -#include -#include - -#include - -#include -#include -#include - -namespace autoware::behavior_velocity_planner -{ -using tier4_autoware_utils::getOrDeclareParameter; - -OutOfLaneModuleManager::OutOfLaneModuleManager(rclcpp::Node & node) -: SceneModuleManagerInterface(node, getModuleName()), module_id_(0UL) -{ - const std::string ns(getModuleName()); - auto & pp = planner_param_; - - pp.mode = getOrDeclareParameter(node, ns + ".mode"); - pp.skip_if_already_overlapping = - getOrDeclareParameter(node, ns + ".skip_if_already_overlapping"); - pp.ignore_overlaps_over_lane_changeable_lanelets = - getOrDeclareParameter(node, ns + ".ignore_overlaps_over_lane_changeable_lanelets"); - - pp.time_threshold = getOrDeclareParameter(node, ns + ".threshold.time_threshold"); - pp.intervals_ego_buffer = getOrDeclareParameter(node, ns + ".intervals.ego_time_buffer"); - pp.intervals_obj_buffer = - getOrDeclareParameter(node, ns + ".intervals.objects_time_buffer"); - pp.ttc_threshold = getOrDeclareParameter(node, ns + ".ttc.threshold"); - - pp.objects_min_vel = getOrDeclareParameter(node, ns + ".objects.minimum_velocity"); - pp.objects_use_predicted_paths = - getOrDeclareParameter(node, ns + ".objects.use_predicted_paths"); - pp.objects_min_confidence = - getOrDeclareParameter(node, ns + ".objects.predicted_path_min_confidence"); - pp.objects_dist_buffer = getOrDeclareParameter(node, ns + ".objects.distance_buffer"); - pp.objects_cut_predicted_paths_beyond_red_lights = - getOrDeclareParameter(node, ns + ".objects.cut_predicted_paths_beyond_red_lights"); - - pp.overlap_min_dist = getOrDeclareParameter(node, ns + ".overlap.minimum_distance"); - pp.overlap_extra_length = getOrDeclareParameter(node, ns + ".overlap.extra_length"); - - pp.skip_if_over_max_decel = - getOrDeclareParameter(node, ns + ".action.skip_if_over_max_decel"); - pp.precision = getOrDeclareParameter(node, ns + ".action.precision"); - pp.min_decision_duration = getOrDeclareParameter(node, ns + ".action.min_duration"); - pp.dist_buffer = getOrDeclareParameter(node, ns + ".action.distance_buffer"); - pp.slow_velocity = getOrDeclareParameter(node, ns + ".action.slowdown.velocity"); - pp.slow_dist_threshold = - getOrDeclareParameter(node, ns + ".action.slowdown.distance_threshold"); - pp.stop_dist_threshold = - getOrDeclareParameter(node, ns + ".action.stop.distance_threshold"); - - pp.ego_min_velocity = getOrDeclareParameter(node, ns + ".ego.min_assumed_velocity"); - pp.extra_front_offset = getOrDeclareParameter(node, ns + ".ego.extra_front_offset"); - pp.extra_rear_offset = getOrDeclareParameter(node, ns + ".ego.extra_rear_offset"); - pp.extra_left_offset = getOrDeclareParameter(node, ns + ".ego.extra_left_offset"); - pp.extra_right_offset = getOrDeclareParameter(node, ns + ".ego.extra_right_offset"); - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); - pp.front_offset = vehicle_info.max_longitudinal_offset_m; - pp.rear_offset = vehicle_info.min_longitudinal_offset_m; - pp.left_offset = vehicle_info.max_lateral_offset_m; - pp.right_offset = vehicle_info.min_lateral_offset_m; -} - -void OutOfLaneModuleManager::launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) -{ - if (path.points.empty()) return; - // general - if (!isModuleRegistered(module_id_)) { - registerModule(std::make_shared( - module_id_, planner_param_, logger_.get_child("out_of_lane_module"), clock_)); - } -} - -std::function &)> -OutOfLaneModuleManager::getModuleExpiredFunction( - const tier4_planning_msgs::msg::PathWithLaneId & path) -{ - return [path]([[maybe_unused]] const std::shared_ptr & scene_module) { - return false; - }; -} -} // namespace autoware::behavior_velocity_planner - -#include -PLUGINLIB_EXPORT_CLASS( - autoware::behavior_velocity_planner::OutOfLaneModulePlugin, - autoware::behavior_velocity_planner::PluginInterface) diff --git a/planning/behavior_velocity_out_of_lane_module/src/manager.hpp b/planning/behavior_velocity_out_of_lane_module/src/manager.hpp deleted file mode 100644 index 5ab7126d88d4d..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/manager.hpp +++ /dev/null @@ -1,66 +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 MANAGER_HPP_ -#define MANAGER_HPP_ - -#include "scene_out_of_lane.hpp" - -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -#include -#include - -#include -#include -#include -#include - -namespace autoware::behavior_velocity_planner -{ -class OutOfLaneModuleManager : public SceneModuleManagerInterface -{ -public: - explicit OutOfLaneModuleManager(rclcpp::Node & node); - - const char * getModuleName() override { return "out_of_lane"; } - -private: - using PlannerParam = out_of_lane::PlannerParam; - - PlannerParam planner_param_; - int64_t module_id_; - - void launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override; - - std::function &)> getModuleExpiredFunction( - const tier4_planning_msgs::msg::PathWithLaneId & path) override; -}; - -class OutOfLaneModulePlugin : public PluginWrapper -{ -}; - -} // namespace autoware::behavior_velocity_planner - -#endif // MANAGER_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.cpp b/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.cpp deleted file mode 100644 index a081df0b52028..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.cpp +++ /dev/null @@ -1,126 +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 "overlapping_range.hpp" - -#include -#include - -#include - -#include -#include - -#include - -namespace autoware::behavior_velocity_planner::out_of_lane -{ - -Overlap calculate_overlap( - const lanelet::BasicPolygon2d & path_footprint, const lanelet::ConstLanelets & path_lanelets, - const lanelet::ConstLanelet & lanelet) -{ - Overlap overlap; - const auto & left_bound = lanelet.leftBound2d().basicLineString(); - const auto & right_bound = lanelet.rightBound2d().basicLineString(); - // TODO(Maxime): these intersects (for each path footprint, for each lanelet) are too expensive - const auto overlap_left = boost::geometry::intersects(path_footprint, left_bound); - const auto overlap_right = boost::geometry::intersects(path_footprint, right_bound); - - lanelet::BasicPolygons2d overlapping_polygons; - if (overlap_left || overlap_right) - boost::geometry::intersection( - path_footprint, lanelet.polygon2d().basicPolygon(), overlapping_polygons); - for (const auto & overlapping_polygon : overlapping_polygons) { - for (const auto & point : overlapping_polygon) { - if (overlap_left && overlap_right) - overlap.inside_distance = boost::geometry::distance(left_bound, right_bound); - else if (overlap_left) - overlap.inside_distance = - std::max(overlap.inside_distance, boost::geometry::distance(point, left_bound)); - else if (overlap_right) - overlap.inside_distance = - std::max(overlap.inside_distance, boost::geometry::distance(point, right_bound)); - geometry_msgs::msg::Pose p; - p.position.x = point.x(); - p.position.y = point.y(); - const auto length = lanelet::utils::getArcCoordinates(path_lanelets, p).length; - if (length > overlap.max_arc_length) { - overlap.max_arc_length = length; - overlap.max_overlap_point = point; - } - if (length < overlap.min_arc_length) { - overlap.min_arc_length = length; - overlap.min_overlap_point = point; - } - } - } - return overlap; -} - -OverlapRanges calculate_overlapping_ranges( - const std::vector & path_footprints, - const lanelet::ConstLanelets & path_lanelets, const lanelet::ConstLanelet & lanelet, - const PlannerParam & params) -{ - OverlapRanges ranges; - OtherLane other_lane(lanelet); - std::vector overlaps; - for (auto i = 0UL; i < path_footprints.size(); ++i) { - const auto overlap = calculate_overlap(path_footprints[i], path_lanelets, lanelet); - const auto has_overlap = overlap.inside_distance > params.overlap_min_dist; - if (has_overlap) { // open/update the range - overlaps.push_back(overlap); - if (!other_lane.range_is_open) { - other_lane.first_range_bound.index = i; - other_lane.first_range_bound.point = overlap.min_overlap_point; - other_lane.first_range_bound.arc_length = - overlap.min_arc_length - params.overlap_extra_length; - other_lane.first_range_bound.inside_distance = overlap.inside_distance; - other_lane.range_is_open = true; - } - other_lane.last_range_bound.index = i; - other_lane.last_range_bound.point = overlap.max_overlap_point; - other_lane.last_range_bound.arc_length = overlap.max_arc_length + params.overlap_extra_length; - other_lane.last_range_bound.inside_distance = overlap.inside_distance; - } else if (other_lane.range_is_open) { // !has_overlap: close the range if it is open - ranges.push_back(other_lane.close_range()); - ranges.back().debug.overlaps = overlaps; - overlaps.clear(); - } - } - // close the range if it is still open - if (other_lane.range_is_open) { - ranges.push_back(other_lane.close_range()); - ranges.back().debug.overlaps = overlaps; - overlaps.clear(); - } - return ranges; -} - -OverlapRanges calculate_overlapping_ranges( - const std::vector & path_footprints, - const lanelet::ConstLanelets & path_lanelets, const lanelet::ConstLanelets & lanelets, - const PlannerParam & params) -{ - OverlapRanges ranges; - for (auto & lanelet : lanelets) { - const auto lanelet_ranges = - calculate_overlapping_ranges(path_footprints, path_lanelets, lanelet, params); - ranges.insert(ranges.end(), lanelet_ranges.begin(), lanelet_ranges.end()); - } - return ranges; -} - -} // namespace autoware::behavior_velocity_planner::out_of_lane diff --git a/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp b/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp deleted file mode 100644 index afb71c11b3ae4..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/overlapping_range.hpp +++ /dev/null @@ -1,60 +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 OVERLAPPING_RANGE_HPP_ -#define OVERLAPPING_RANGE_HPP_ - -#include "types.hpp" - -#include - -#include - -#include - -namespace autoware::behavior_velocity_planner::out_of_lane -{ - -/// @brief calculate the overlap between the given footprint and lanelet -/// @param [in] path_footprint footprint used to calculate the overlap -/// @param [in] path_lanelets path lanelets used to calculate arc length along the ego path -/// @param [in] lanelet lanelet used to calculate the overlap -/// @return the found overlap between the footprint and the lanelet -Overlap calculate_overlap( - const lanelet::BasicPolygon2d & path_footprint, const lanelet::ConstLanelets & path_lanelets, - const lanelet::ConstLanelet & lanelet); -/// @brief calculate the overlapping ranges between the path footprints and a lanelet -/// @param [in] path_footprints footprints used to calculate the overlaps -/// @param [in] path_lanelets path lanelets used to calculate arc length along the ego path -/// @param [in] lanelet lanelet used to calculate the overlaps -/// @param [in] params parameters -/// @return the overlapping ranges found between the footprints and the lanelet -OverlapRanges calculate_overlapping_ranges( - const std::vector & path_footprints, - const lanelet::ConstLanelets & path_lanelets, const lanelet::ConstLanelet & lanelet, - const PlannerParam & params); -/// @brief calculate the overlapping ranges between the path footprints and some lanelets -/// @param [in] path_footprints footprints used to calculate the overlaps -/// @param [in] path_lanelets path lanelets used to calculate arc length along the ego path -/// @param [in] lanelets lanelets used to calculate the overlaps -/// @param [in] params parameters -/// @return the overlapping ranges found between the footprints and the lanelets, sorted by -/// increasing arc length along the path -OverlapRanges calculate_overlapping_ranges( - const std::vector & path_footprints, - const lanelet::ConstLanelets & path_lanelets, const lanelet::ConstLanelets & lanelets, - const PlannerParam & params); -} // namespace autoware::behavior_velocity_planner::out_of_lane - -#endif // OVERLAPPING_RANGE_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp deleted file mode 100644 index 3f34e8441e8be..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp +++ /dev/null @@ -1,244 +0,0 @@ -// Copyright 2023 TIER IV, Inc. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// 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 "scene_out_of_lane.hpp" - -#include "calculate_slowdown_points.hpp" -#include "debug.hpp" -#include "decisions.hpp" -#include "filter_predicted_objects.hpp" -#include "footprint.hpp" -#include "lanelets_selection.hpp" -#include "overlapping_range.hpp" -#include "types.hpp" - -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -#include - -#include -#include -#include -#include - -namespace autoware::behavior_velocity_planner::out_of_lane -{ - -using visualization_msgs::msg::Marker; -using visualization_msgs::msg::MarkerArray; - -OutOfLaneModule::OutOfLaneModule( - const int64_t module_id, PlannerParam planner_param, const rclcpp::Logger & logger, - const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), params_(std::move(planner_param)) -{ - velocity_factor_.init(PlanningBehavior::ROUTE_OBSTACLE); -} - -bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) -{ - debug_data_.reset_data(); - *stop_reason = planning_utils::initializeStopReason(StopReason::OUT_OF_LANE); - if (!path || path->points.size() < 2) return true; - tier4_autoware_utils::StopWatch stopwatch; - stopwatch.tic(); - EgoData ego_data; - ego_data.pose = planner_data_->current_odometry->pose; - ego_data.path.points = path->points; - ego_data.first_path_idx = - motion_utils::findNearestSegmentIndex(path->points, ego_data.pose.position); - motion_utils::removeOverlapPoints(ego_data.path.points); - ego_data.velocity = planner_data_->current_velocity->twist.linear.x; - ego_data.max_decel = -planner_data_->max_stop_acceleration_threshold; - stopwatch.tic("calculate_path_footprints"); - const auto current_ego_footprint = calculate_current_ego_footprint(ego_data, params_, true); - const auto path_footprints = calculate_path_footprints(ego_data, params_); - const auto calculate_path_footprints_us = stopwatch.toc("calculate_path_footprints"); - // Calculate lanelets to ignore and consider - stopwatch.tic("calculate_lanelets"); - const auto path_lanelets = calculate_path_lanelets(ego_data, *planner_data_->route_handler_); - const auto ignored_lanelets = - calculate_ignored_lanelets(ego_data, path_lanelets, *planner_data_->route_handler_, params_); - const auto other_lanelets = calculate_other_lanelets( - ego_data, path_lanelets, ignored_lanelets, *planner_data_->route_handler_, params_); - const auto calculate_lanelets_us = stopwatch.toc("calculate_lanelets"); - - debug_data_.footprints = path_footprints; - debug_data_.path_lanelets = path_lanelets; - debug_data_.ignored_lanelets = ignored_lanelets; - debug_data_.other_lanelets = other_lanelets; - debug_data_.path = ego_data.path; - debug_data_.first_path_idx = ego_data.first_path_idx; - - if (params_.skip_if_already_overlapping) { - debug_data_.current_footprint = current_ego_footprint; - const auto overlapped_lanelet_it = - std::find_if(other_lanelets.begin(), other_lanelets.end(), [&](const auto & ll) { - return boost::geometry::intersects(ll.polygon2d().basicPolygon(), current_ego_footprint); - }); - if (overlapped_lanelet_it != other_lanelets.end()) { - debug_data_.current_overlapped_lanelets.push_back(*overlapped_lanelet_it); - // TODO(Maxime): we may want to just add the overlapped lane to the ignored lanelets - RCLCPP_DEBUG(logger_, "Ego is already overlapping a lane, skipping the module ()\n"); - return true; - } - } - // Calculate overlapping ranges - stopwatch.tic("calculate_overlapping_ranges"); - const auto ranges = - calculate_overlapping_ranges(path_footprints, path_lanelets, other_lanelets, params_); - const auto calculate_overlapping_ranges_us = stopwatch.toc("calculate_overlapping_ranges"); - // Calculate stop and slowdown points - DecisionInputs inputs; - inputs.ranges = ranges; - inputs.ego_data = ego_data; - stopwatch.tic("filter_predicted_objects"); - inputs.objects = filter_predicted_objects(*planner_data_, ego_data, params_); - const auto filter_predicted_objects_ms = stopwatch.toc("filter_predicted_objects"); - inputs.route_handler = planner_data_->route_handler_; - inputs.lanelets = other_lanelets; - stopwatch.tic("calculate_decisions"); - const auto decisions = calculate_decisions(inputs, params_, logger_); - const auto calculate_decisions_us = stopwatch.toc("calculate_decisions"); - stopwatch.tic("calc_slowdown_points"); - if ( // reset the previous inserted point if the timer expired - prev_inserted_point_ && - (clock_->now() - prev_inserted_point_time_).seconds() > params_.min_decision_duration) - prev_inserted_point_.reset(); - auto point_to_insert = - calculate_slowdown_point(ego_data, decisions, prev_inserted_point_, params_); - const auto calc_slowdown_points_us = stopwatch.toc("calc_slowdown_points"); - stopwatch.tic("insert_slowdown_points"); - debug_data_.slowdowns.clear(); - if ( // reset the timer if there is no previous inserted point or if we avoid the same lane - point_to_insert && - (!prev_inserted_point_ || prev_inserted_point_->slowdown.lane_to_avoid.id() == - point_to_insert->slowdown.lane_to_avoid.id())) - prev_inserted_point_time_ = clock_->now(); - // reuse previous stop point if there is no new one or if its velocity is not higher than the new - // one and its arc length is lower - const auto should_use_prev_inserted_point = [&]() { - if ( - point_to_insert && prev_inserted_point_ && - prev_inserted_point_->slowdown.velocity <= point_to_insert->slowdown.velocity) { - const auto arc_length = motion_utils::calcSignedArcLength( - path->points, 0LU, point_to_insert->point.point.pose.position); - const auto prev_arc_length = motion_utils::calcSignedArcLength( - path->points, 0LU, prev_inserted_point_->point.point.pose.position); - return prev_arc_length < arc_length; - } - return !point_to_insert && prev_inserted_point_; - }(); - if (should_use_prev_inserted_point) { - // if the path changed the prev point is no longer on the path so we project it - const auto insert_arc_length = motion_utils::calcSignedArcLength( - path->points, 0LU, prev_inserted_point_->point.point.pose.position); - prev_inserted_point_->point.point.pose = - motion_utils::calcInterpolatedPose(path->points, insert_arc_length); - point_to_insert = prev_inserted_point_; - } - if (point_to_insert) { - prev_inserted_point_ = point_to_insert; - RCLCPP_DEBUG(logger_, "Avoiding lane %lu", point_to_insert->slowdown.lane_to_avoid.id()); - debug_data_.slowdowns = {*point_to_insert}; - auto path_idx = motion_utils::findNearestSegmentIndex( - path->points, point_to_insert->point.point.pose.position) + - 1; - planning_utils::insertVelocity( - *path, point_to_insert->point, point_to_insert->slowdown.velocity, path_idx); - auto stop_pose_reached = false; - if (point_to_insert->slowdown.velocity == 0.0) { - const auto dist_to_stop_pose = motion_utils::calcSignedArcLength( - path->points, ego_data.pose.position, point_to_insert->point.point.pose.position); - if (ego_data.velocity < 1e-3 && dist_to_stop_pose < 1e-3) stop_pose_reached = true; - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = point_to_insert->point.point.pose; - stop_factor.dist_to_stop_pose = dist_to_stop_pose; - planning_utils::appendStopReason(stop_factor, stop_reason); - } - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, point_to_insert->point.point.pose, - stop_pose_reached ? VelocityFactor::STOPPED : VelocityFactor::APPROACHING, "out_of_lane"); - } else if (!decisions.empty()) { - RCLCPP_WARN(logger_, "Could not insert stop point (would violate max deceleration limits)"); - } - const auto insert_slowdown_points_us = stopwatch.toc("insert_slowdown_points"); - debug_data_.ranges = inputs.ranges; - - const auto total_time_us = stopwatch.toc(); - RCLCPP_DEBUG( - logger_, - "Total time = %2.2fus\n" - "\tcalculate_lanelets = %2.0fus\n" - "\tcalculate_path_footprints = %2.0fus\n" - "\tcalculate_overlapping_ranges = %2.0fus\n" - "\tfilter_pred_objects = %2.0fus\n" - "\tcalculate_decisions = %2.0fus\n" - "\tcalc_slowdown_points = %2.0fus\n" - "\tinsert_slowdown_points = %2.0fus\n", - total_time_us, calculate_lanelets_us, calculate_path_footprints_us, - calculate_overlapping_ranges_us, filter_predicted_objects_ms, calculate_decisions_us, - calc_slowdown_points_us, insert_slowdown_points_us); - return true; -} - -MarkerArray OutOfLaneModule::createDebugMarkerArray() -{ - constexpr auto z = 0.0; - MarkerArray debug_marker_array; - - debug::add_footprint_markers( - debug_marker_array, debug_data_.footprints, z, debug_data_.prev_footprints); - debug::add_current_overlap_marker( - debug_marker_array, debug_data_.current_footprint, debug_data_.current_overlapped_lanelets, z, - debug_data_.prev_current_overlapped_lanelets); - debug::add_lanelet_markers( - debug_marker_array, debug_data_.path_lanelets, "path_lanelets", - tier4_autoware_utils::createMarkerColor(0.1, 0.1, 1.0, 0.5), debug_data_.prev_path_lanelets); - debug::add_lanelet_markers( - debug_marker_array, debug_data_.ignored_lanelets, "ignored_lanelets", - tier4_autoware_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", - tier4_autoware_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_.path, debug_data_.first_path_idx, z, - debug_data_.prev_ranges); - return debug_marker_array; -} - -motion_utils::VirtualWalls OutOfLaneModule::createVirtualWalls() -{ - motion_utils::VirtualWalls virtual_walls; - motion_utils::VirtualWall wall; - wall.text = "out_of_lane"; - wall.longitudinal_offset = params_.front_offset; - wall.style = motion_utils::VirtualWallType::slowdown; - for (const auto & slowdown : debug_data_.slowdowns) { - wall.pose = slowdown.point.point.pose; - virtual_walls.push_back(wall); - } - return virtual_walls; -} - -} // namespace autoware::behavior_velocity_planner::out_of_lane diff --git a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp b/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp deleted file mode 100644 index 38101d6a9ba1d..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.hpp +++ /dev/null @@ -1,65 +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 SCENE_OUT_OF_LANE_HPP_ -#define SCENE_OUT_OF_LANE_HPP_ - -#include "types.hpp" - -#include -#include -#include - -#include -#include -#include - -#include - -#include -#include -#include - -namespace autoware::behavior_velocity_planner::out_of_lane -{ -class OutOfLaneModule : public SceneModuleInterface -{ -public: - OutOfLaneModule( - const int64_t module_id, PlannerParam planner_param, const rclcpp::Logger & logger, - const rclcpp::Clock::SharedPtr clock); - - /// @brief insert stop or slow down points to prevent dangerously entering another lane - /// @param [inout] path the path to update - /// @param [inout] stop_reason reason for stopping - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; - - visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; - motion_utils::VirtualWalls createVirtualWalls() override; - -private: - PlannerParam params_; - - std::optional prev_inserted_point_{}; - rclcpp::Time prev_inserted_point_time_{}; - -protected: - int64_t module_id_{}; - - // Debug - mutable DebugData debug_data_; -}; -} // namespace autoware::behavior_velocity_planner::out_of_lane - -#endif // SCENE_OUT_OF_LANE_HPP_ diff --git a/planning/behavior_velocity_out_of_lane_module/src/types.hpp b/planning/behavior_velocity_out_of_lane_module/src/types.hpp deleted file mode 100644 index f1c48a6e96d17..0000000000000 --- a/planning/behavior_velocity_out_of_lane_module/src/types.hpp +++ /dev/null @@ -1,235 +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 TYPES_HPP_ -#define TYPES_HPP_ - -#include - -#include -#include -#include - -#include - -#include -#include -#include -#include -#include -#include -#include - -namespace autoware::behavior_velocity_planner::out_of_lane -{ -/// @brief parameters for the "out of lane" module -struct PlannerParam -{ - std::string mode; // mode used to consider a conflict with an object - bool skip_if_already_overlapping; // if true, do not run the module when ego already overlaps - // another lane - bool ignore_overlaps_over_lane_changeable_lanelets; // if true, overlaps on lane changeable - // lanelets are ignored - - double time_threshold; // [s](mode="threshold") objects time threshold - double intervals_ego_buffer; // [s](mode="intervals") buffer to extend the ego time range - double intervals_obj_buffer; // [s](mode="intervals") buffer to extend the objects time range - double ttc_threshold; // [s](mode="ttc") threshold on time to collision between ego and an object - double ego_min_velocity; // [m/s] minimum velocity of ego used to calculate its ttc or time range - - bool objects_use_predicted_paths; // whether to use the objects' predicted paths - bool objects_cut_predicted_paths_beyond_red_lights; // whether to cut predicted paths beyond red - // lights' stop lines - double objects_min_vel; // [m/s] objects lower than this velocity will be ignored - double objects_min_confidence; // minimum confidence to consider a predicted path - double objects_dist_buffer; // [m] distance buffer used to determine if a collision will occur in - // the other lane - - double overlap_extra_length; // [m] extra length to add around an overlap range - double overlap_min_dist; // [m] min distance inside another lane to consider an overlap - // action to insert in the path if an object causes a conflict at an overlap - bool skip_if_over_max_decel; // if true, skip the action if it causes more than the max decel - double dist_buffer; - double slow_velocity; - double slow_dist_threshold; - double stop_dist_threshold; - double precision; // [m] precision when inserting a stop pose in the path - double min_decision_duration; // [s] minimum duration needed a decision can be canceled - // ego dimensions used to create its polygon footprint - double front_offset; // [m] front offset (from vehicle info) - double rear_offset; // [m] rear offset (from vehicle info) - double right_offset; // [m] right offset (from vehicle info) - double left_offset; // [m] left offset (from vehicle info) - double extra_front_offset; // [m] extra front distance - double extra_rear_offset; // [m] extra rear distance - double extra_right_offset; // [m] extra right distance - double extra_left_offset; // [m] extra left distance -}; - -struct EnterExitTimes -{ - double enter_time{}; - double exit_time{}; -}; -struct RangeTimes -{ - EnterExitTimes ego{}; - EnterExitTimes object{}; -}; - -/// @brief action taken by the "out of lane" module -struct Slowdown -{ - size_t target_path_idx{}; // we want to slowdown before this path index - double velocity{}; // desired slow down velocity - lanelet::ConstLanelet lane_to_avoid; // we want to slowdown before entering this lane -}; -/// @brief slowdown to insert in a path -struct SlowdownToInsert -{ - Slowdown slowdown; - tier4_planning_msgs::msg::PathWithLaneId::_points_type::value_type point; -}; - -/// @brief bound of an overlap range (either the first, or last bound) -struct RangeBound -{ - size_t index; - lanelet::BasicPoint2d point; - double arc_length; - double inside_distance; -}; - -/// @brief representation of an overlap between the ego footprint and some other lane -struct Overlap -{ - double inside_distance = 0.0; ///!< distance inside the overlap - double min_arc_length = std::numeric_limits::infinity(); - double max_arc_length = 0.0; - lanelet::BasicPoint2d min_overlap_point{}; ///!< point with min arc length - lanelet::BasicPoint2d max_overlap_point{}; ///!< point with max arc length -}; - -/// @brief range along the path where ego overlaps another lane -struct OverlapRange -{ - lanelet::ConstLanelet lane; - size_t entering_path_idx{}; - size_t exiting_path_idx{}; - lanelet::BasicPoint2d entering_point; // pose of the overlapping point closest along the lane - lanelet::BasicPoint2d exiting_point; // pose of the overlapping point furthest along the lane - double inside_distance{}; // [m] how much ego footprint enters the lane - mutable struct - { - std::vector overlaps; - std::optional decision; - RangeTimes times; - std::optional object{}; - } debug; -}; -using OverlapRanges = std::vector; -/// @brief representation of a lane and its current overlap range -struct OtherLane -{ - bool range_is_open = false; - RangeBound first_range_bound{}; - RangeBound last_range_bound{}; - lanelet::ConstLanelet lanelet; - lanelet::BasicPolygon2d polygon; - - explicit OtherLane(lanelet::ConstLanelet ll) : lanelet(std::move(ll)) - { - polygon = lanelet.polygon2d().basicPolygon(); - } - - [[nodiscard]] OverlapRange close_range() - { - OverlapRange range; - range.lane = lanelet; - range.entering_path_idx = first_range_bound.index; - range.entering_point = first_range_bound.point; - range.exiting_path_idx = last_range_bound.index; - range.exiting_point = last_range_bound.point; - range.inside_distance = - std::max(first_range_bound.inside_distance, last_range_bound.inside_distance); - range_is_open = false; - last_range_bound = {}; - return range; - } -}; - -/// @brief data related to the ego vehicle -struct EgoData -{ - tier4_planning_msgs::msg::PathWithLaneId path{}; - size_t first_path_idx{}; - double velocity{}; // [m/s] - double max_decel{}; // [m/s²] - geometry_msgs::msg::Pose pose; -}; - -/// @brief data needed to make decisions -struct DecisionInputs -{ - OverlapRanges ranges{}; - EgoData ego_data; - autoware_perception_msgs::msg::PredictedObjects objects{}; - std::shared_ptr route_handler{}; - lanelet::ConstLanelets lanelets{}; -}; - -/// @brief debug data -struct DebugData -{ - std::vector footprints; - std::vector slowdowns; - geometry_msgs::msg::Pose ego_pose; - OverlapRanges ranges; - lanelet::BasicPolygon2d current_footprint; - lanelet::ConstLanelets current_overlapped_lanelets; - lanelet::ConstLanelets path_lanelets; - lanelet::ConstLanelets ignored_lanelets; - lanelet::ConstLanelets other_lanelets; - tier4_planning_msgs::msg::PathWithLaneId path; - size_t first_path_idx; - - size_t prev_footprints = 0; - size_t prev_slowdowns = 0; - size_t prev_ranges = 0; - size_t prev_current_overlapped_lanelets = 0; - size_t prev_ignored_lanelets = 0; - size_t prev_path_lanelets = 0; - size_t prev_other_lanelets = 0; - void reset_data() - { - prev_footprints = footprints.size(); - footprints.clear(); - prev_slowdowns = slowdowns.size(); - slowdowns.clear(); - prev_ranges = ranges.size(); - ranges.clear(); - prev_current_overlapped_lanelets = current_overlapped_lanelets.size(); - current_overlapped_lanelets.clear(); - prev_ignored_lanelets = ignored_lanelets.size(); - ignored_lanelets.clear(); - prev_path_lanelets = path_lanelets.size(); - path_lanelets.clear(); - prev_other_lanelets = other_lanelets.size(); - other_lanelets.clear(); - } -}; - -} // namespace autoware::behavior_velocity_planner::out_of_lane - -#endif // TYPES_HPP_ From 09f76761f206e756f9e81cdf9dbcfc90c93c289e Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Mon, 10 Jun 2024 09:12:10 +0900 Subject: [PATCH 41/65] fix(multi_object_tracker): fix segmentation fault bug of the debug object process (#7347) fix: finish the process when the object data list is empty Signed-off-by: Taekjin LEE --- perception/multi_object_tracker/src/debugger/debug_object.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/perception/multi_object_tracker/src/debugger/debug_object.cpp b/perception/multi_object_tracker/src/debugger/debug_object.cpp index f166e83e136af..e6a0b6242a168 100644 --- a/perception/multi_object_tracker/src/debugger/debug_object.cpp +++ b/perception/multi_object_tracker/src/debugger/debug_object.cpp @@ -134,6 +134,9 @@ void TrackerObjectDebugger::process() { if (!is_initialized_) return; + // Check if object_data_list_ is empty + if (object_data_list_.empty()) return; + // update uuid_int for (auto & object_data : object_data_list_) { current_ids_.insert(object_data.uuid_int); From a1375602e7a70c903b7345da5052cbb056e41b72 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Mon, 10 Jun 2024 10:09:24 +0900 Subject: [PATCH 42/65] chore(vehicle_cmd_gate): add prefix autoware_ to vehicle_cmd_gate (#7327) * add prefix autoware_ to vehicle_cmd_gate package Signed-off-by: Go Sakayori * fix Signed-off-by: Go Sakayori * fix include guard Signed-off-by: Go Sakayori * fix pre-commit Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori Signed-off-by: Go Sakayori --- .github/CODEOWNERS | 2 +- .../CMakeLists.txt | 4 ++-- .../README.md | 0 .../config/vehicle_cmd_gate.param.yaml | 0 .../image/filter.png | Bin .../launch/vehicle_cmd_gate.launch.xml | 4 ++-- .../msg/IsFilterActivated.msg | 0 .../package.xml | 2 +- .../schema/vehicle_cmd_gate.json | 0 .../script/delays_checker.py | 0 .../src/adapi_pause_interface.cpp | 4 ++-- .../src/adapi_pause_interface.hpp | 4 ++-- .../src/marker_helper.hpp | 4 ++-- .../src/moderate_stop_interface.cpp | 4 ++-- .../src/moderate_stop_interface.hpp | 4 ++-- .../src/vehicle_cmd_filter.cpp | 4 ++-- .../src/vehicle_cmd_filter.hpp | 8 ++++---- .../src/vehicle_cmd_gate.cpp | 6 +++--- .../src/vehicle_cmd_gate.hpp | 8 ++++---- .../src/test_filter_in_vehicle_cmd_gate_node.cpp | 4 ++-- .../test/src/test_main.cpp | 0 .../test/src/test_vehicle_cmd_filter.cpp | 12 ++++++------ .../tier4_control_launch/launch/control.launch.py | 4 ++-- launch/tier4_control_launch/package.xml | 2 +- 24 files changed, 40 insertions(+), 40 deletions(-) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/CMakeLists.txt (93%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/README.md (100%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/config/vehicle_cmd_gate.param.yaml (100%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/image/filter.png (100%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/launch/vehicle_cmd_gate.launch.xml (92%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/msg/IsFilterActivated.msg (100%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/package.xml (97%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/schema/vehicle_cmd_gate.json (100%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/script/delays_checker.py (100%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/src/adapi_pause_interface.cpp (95%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/src/adapi_pause_interface.hpp (95%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/src/marker_helper.hpp (97%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/src/moderate_stop_interface.cpp (95%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/src/moderate_stop_interface.hpp (95%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/src/vehicle_cmd_filter.cpp (99%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/src/vehicle_cmd_filter.hpp (94%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/src/vehicle_cmd_gate.cpp (99%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/src/vehicle_cmd_gate.hpp (98%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/test/src/test_filter_in_vehicle_cmd_gate_node.cpp (99%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/test/src/test_main.cpp (100%) rename control/{vehicle_cmd_gate => autoware_vehicle_cmd_gate}/test/src/test_vehicle_cmd_filter.cpp (98%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 95ddb97d2bbb0..084349cda0af3 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -60,7 +60,7 @@ control/shift_decider/** takamasa.horibe@tier4.jp control/autoware_smart_mpc_trajectory_follower/** masayuki.aino@proxima-ai-tech.com control/trajectory_follower_base/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/trajectory_follower_node/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp -control/vehicle_cmd_gate/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp +control/autoware_vehicle_cmd_gate/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp evaluator/control_evaluator/** daniel.sanchez@tier4.jp takayuki.murooka@tier4.jp evaluator/diagnostic_converter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp evaluator/kinematic_evaluator/** dominik.jargot@robotec.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 diff --git a/control/vehicle_cmd_gate/CMakeLists.txt b/control/autoware_vehicle_cmd_gate/CMakeLists.txt similarity index 93% rename from control/vehicle_cmd_gate/CMakeLists.txt rename to control/autoware_vehicle_cmd_gate/CMakeLists.txt index c5db663ccc77e..7233608a5d25f 100644 --- a/control/vehicle_cmd_gate/CMakeLists.txt +++ b/control/autoware_vehicle_cmd_gate/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(vehicle_cmd_gate) +project(autoware_vehicle_cmd_gate) find_package(autoware_cmake REQUIRED) autoware_package() @@ -12,7 +12,7 @@ ament_auto_add_library(vehicle_cmd_gate_node SHARED ) rclcpp_components_register_node(vehicle_cmd_gate_node - PLUGIN "vehicle_cmd_gate::VehicleCmdGate" + PLUGIN "autoware::vehicle_cmd_gate::VehicleCmdGate" EXECUTABLE vehicle_cmd_gate_exe ) diff --git a/control/vehicle_cmd_gate/README.md b/control/autoware_vehicle_cmd_gate/README.md similarity index 100% rename from control/vehicle_cmd_gate/README.md rename to control/autoware_vehicle_cmd_gate/README.md diff --git a/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml b/control/autoware_vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml similarity index 100% rename from control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml rename to control/autoware_vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml diff --git a/control/vehicle_cmd_gate/image/filter.png b/control/autoware_vehicle_cmd_gate/image/filter.png similarity index 100% rename from control/vehicle_cmd_gate/image/filter.png rename to control/autoware_vehicle_cmd_gate/image/filter.png diff --git a/control/vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml b/control/autoware_vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml similarity index 92% rename from control/vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml rename to control/autoware_vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml index c5368276b488a..c9e83bf9878b8 100644 --- a/control/vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml +++ b/control/autoware_vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml @@ -1,11 +1,11 @@ - + - + diff --git a/control/vehicle_cmd_gate/msg/IsFilterActivated.msg b/control/autoware_vehicle_cmd_gate/msg/IsFilterActivated.msg similarity index 100% rename from control/vehicle_cmd_gate/msg/IsFilterActivated.msg rename to control/autoware_vehicle_cmd_gate/msg/IsFilterActivated.msg diff --git a/control/vehicle_cmd_gate/package.xml b/control/autoware_vehicle_cmd_gate/package.xml similarity index 97% rename from control/vehicle_cmd_gate/package.xml rename to control/autoware_vehicle_cmd_gate/package.xml index e01d566c37df9..da0e885cc564a 100644 --- a/control/vehicle_cmd_gate/package.xml +++ b/control/autoware_vehicle_cmd_gate/package.xml @@ -1,7 +1,7 @@ - vehicle_cmd_gate + autoware_vehicle_cmd_gate 0.1.0 The vehicle_cmd_gate package Takamasa Horibe diff --git a/control/vehicle_cmd_gate/schema/vehicle_cmd_gate.json b/control/autoware_vehicle_cmd_gate/schema/vehicle_cmd_gate.json similarity index 100% rename from control/vehicle_cmd_gate/schema/vehicle_cmd_gate.json rename to control/autoware_vehicle_cmd_gate/schema/vehicle_cmd_gate.json diff --git a/control/vehicle_cmd_gate/script/delays_checker.py b/control/autoware_vehicle_cmd_gate/script/delays_checker.py similarity index 100% rename from control/vehicle_cmd_gate/script/delays_checker.py rename to control/autoware_vehicle_cmd_gate/script/delays_checker.py diff --git a/control/vehicle_cmd_gate/src/adapi_pause_interface.cpp b/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.cpp similarity index 95% rename from control/vehicle_cmd_gate/src/adapi_pause_interface.cpp rename to control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.cpp index f4cf28d337a09..f14a62fba9661 100644 --- a/control/vehicle_cmd_gate/src/adapi_pause_interface.cpp +++ b/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.cpp @@ -14,7 +14,7 @@ #include "adapi_pause_interface.hpp" -namespace vehicle_cmd_gate +namespace autoware::vehicle_cmd_gate { AdapiPauseInterface::AdapiPauseInterface(rclcpp::Node * node) : node_(node) @@ -65,4 +65,4 @@ void AdapiPauseInterface::on_pause( res->status.success = true; } -} // namespace vehicle_cmd_gate +} // namespace autoware::vehicle_cmd_gate diff --git a/control/vehicle_cmd_gate/src/adapi_pause_interface.hpp b/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp similarity index 95% rename from control/vehicle_cmd_gate/src/adapi_pause_interface.hpp rename to control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp index 1d5f05e98975e..d75b544752e3f 100644 --- a/control/vehicle_cmd_gate/src/adapi_pause_interface.hpp +++ b/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp @@ -21,7 +21,7 @@ #include -namespace vehicle_cmd_gate +namespace autoware::vehicle_cmd_gate { class AdapiPauseInterface @@ -55,6 +55,6 @@ class AdapiPauseInterface const SetPause::Service::Response::SharedPtr res); }; -} // namespace vehicle_cmd_gate +} // namespace autoware::vehicle_cmd_gate #endif // ADAPI_PAUSE_INTERFACE_HPP_ diff --git a/control/vehicle_cmd_gate/src/marker_helper.hpp b/control/autoware_vehicle_cmd_gate/src/marker_helper.hpp similarity index 97% rename from control/vehicle_cmd_gate/src/marker_helper.hpp rename to control/autoware_vehicle_cmd_gate/src/marker_helper.hpp index 44c43a3630151..c9d7e86fa23dd 100644 --- a/control/vehicle_cmd_gate/src/marker_helper.hpp +++ b/control/autoware_vehicle_cmd_gate/src/marker_helper.hpp @@ -21,7 +21,7 @@ #include -namespace vehicle_cmd_gate +namespace autoware::vehicle_cmd_gate { inline geometry_msgs::msg::Point createMarkerPosition(double x, double y, double z) { @@ -114,6 +114,6 @@ inline void appendMarkerArray( marker_array->markers.push_back(marker); } } -} // namespace vehicle_cmd_gate +} // namespace autoware::vehicle_cmd_gate #endif // MARKER_HELPER_HPP_ diff --git a/control/vehicle_cmd_gate/src/moderate_stop_interface.cpp b/control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.cpp similarity index 95% rename from control/vehicle_cmd_gate/src/moderate_stop_interface.cpp rename to control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.cpp index 72dbdfd26a6b3..0fe90adfd0a72 100644 --- a/control/vehicle_cmd_gate/src/moderate_stop_interface.cpp +++ b/control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.cpp @@ -14,7 +14,7 @@ #include "moderate_stop_interface.hpp" -namespace vehicle_cmd_gate +namespace autoware::vehicle_cmd_gate { ModerateStopInterface::ModerateStopInterface(rclcpp::Node * node) : node_(node) @@ -66,4 +66,4 @@ void ModerateStopInterface::update_stop_state() } } -} // namespace vehicle_cmd_gate +} // namespace autoware::vehicle_cmd_gate diff --git a/control/vehicle_cmd_gate/src/moderate_stop_interface.hpp b/control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.hpp similarity index 95% rename from control/vehicle_cmd_gate/src/moderate_stop_interface.hpp rename to control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.hpp index b643afc212f61..012e75d0c207e 100644 --- a/control/vehicle_cmd_gate/src/moderate_stop_interface.hpp +++ b/control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.hpp @@ -22,7 +22,7 @@ #include #include -namespace vehicle_cmd_gate +namespace autoware::vehicle_cmd_gate { class ModerateStopInterface @@ -53,6 +53,6 @@ class ModerateStopInterface void update_stop_state(); }; -} // namespace vehicle_cmd_gate +} // namespace autoware::vehicle_cmd_gate #endif // MODERATE_STOP_INTERFACE_HPP_ diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.cpp similarity index 99% rename from control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp rename to control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.cpp index bd9955e773020..cec23b05b8191 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.cpp @@ -17,7 +17,7 @@ #include #include -namespace vehicle_cmd_gate +namespace autoware::vehicle_cmd_gate { VehicleCmdFilter::VehicleCmdFilter() @@ -319,4 +319,4 @@ double VehicleCmdFilter::getSteerDiffLim() const return interpolateFromSpeed(param_.actual_steer_diff_lim); } -} // namespace vehicle_cmd_gate +} // namespace autoware::vehicle_cmd_gate diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_filter.hpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.hpp similarity index 94% rename from control/vehicle_cmd_gate/src/vehicle_cmd_filter.hpp rename to control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.hpp index d9b8383a1de51..96663474f47a4 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_filter.hpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.hpp @@ -15,17 +15,17 @@ #ifndef VEHICLE_CMD_FILTER_HPP_ #define VEHICLE_CMD_FILTER_HPP_ +#include #include -#include #include #include -namespace vehicle_cmd_gate +namespace autoware::vehicle_cmd_gate { using autoware_control_msgs::msg::Control; -using vehicle_cmd_gate::msg::IsFilterActivated; +using autoware_vehicle_cmd_gate::msg::IsFilterActivated; using LimitArray = std::vector; struct VehicleCmdFilterParam @@ -98,6 +98,6 @@ class VehicleCmdFilter double getSteerRateLim() const; double getSteerDiffLim() const; }; -} // namespace vehicle_cmd_gate +} // namespace autoware::vehicle_cmd_gate #endif // VEHICLE_CMD_FILTER_HPP_ diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp similarity index 99% rename from control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp rename to control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp index cc9d7813083f4..e8d35beb94b1f 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -28,7 +28,7 @@ #include #include -namespace vehicle_cmd_gate +namespace autoware::vehicle_cmd_gate { namespace @@ -906,7 +906,7 @@ void VehicleCmdGate::publishMarkers(const IsFilterActivated & filter_activated) filter_activated_flag_pub_->publish(filter_activated_flag); filter_activated_marker_raw_pub_->publish(createMarkerArray(filter_activated)); } -} // namespace vehicle_cmd_gate +} // namespace autoware::vehicle_cmd_gate #include -RCLCPP_COMPONENTS_REGISTER_NODE(vehicle_cmd_gate::VehicleCmdGate) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::vehicle_cmd_gate::VehicleCmdGate) diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp similarity index 98% rename from control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp rename to control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp index f45280d9d2e48..22613de5d1f07 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp @@ -20,11 +20,11 @@ #include "tier4_autoware_utils/ros/logger_level_configure.hpp" #include "vehicle_cmd_filter.hpp" +#include #include #include #include #include -#include #include #include @@ -51,13 +51,14 @@ #include #include -namespace vehicle_cmd_gate +namespace autoware::vehicle_cmd_gate { using autoware_adapi_v1_msgs::msg::MrmState; using autoware_adapi_v1_msgs::msg::OperationModeState; using autoware_control_msgs::msg::Control; using autoware_control_msgs::msg::Longitudinal; +using autoware_vehicle_cmd_gate::msg::IsFilterActivated; using autoware_vehicle_msgs::msg::GearCommand; using autoware_vehicle_msgs::msg::HazardLightsCommand; using autoware_vehicle_msgs::msg::SteeringReport; @@ -71,7 +72,6 @@ using tier4_external_api_msgs::msg::Heartbeat; using tier4_external_api_msgs::srv::SetEmergency; using tier4_system_msgs::msg::MrmBehaviorStatus; using tier4_vehicle_msgs::msg::VehicleEmergencyStamped; -using vehicle_cmd_gate::msg::IsFilterActivated; using visualization_msgs::msg::MarkerArray; using diagnostic_msgs::msg::DiagnosticStatus; @@ -257,5 +257,5 @@ class VehicleCmdGate : public rclcpp::Node std::unique_ptr published_time_publisher_; }; -} // namespace vehicle_cmd_gate +} // namespace autoware::vehicle_cmd_gate #endif // VEHICLE_CMD_GATE_HPP_ diff --git a/control/vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp b/control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp similarity index 99% rename from control/vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp rename to control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp index d51db90c8a260..6f148fe6c8140 100644 --- a/control/vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp +++ b/control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp @@ -54,7 +54,7 @@ const std::vector lat_jerk_lim = {1.7, 1.3, 0.9, 0.6}; const std::vector actual_steer_diff_lim = {0.5, 0.4, 0.2, 0.1}; const double wheelbase = 2.89; -using vehicle_cmd_gate::VehicleCmdGate; +using autoware::vehicle_cmd_gate::VehicleCmdGate; using autoware_adapi_v1_msgs::msg::MrmState; using autoware_adapi_v1_msgs::msg::OperationModeState; @@ -369,7 +369,7 @@ std::shared_ptr generateNode() auto node_options = rclcpp::NodeOptions{}; const auto vehicle_cmd_gate_dir = - ament_index_cpp::get_package_share_directory("vehicle_cmd_gate"); + ament_index_cpp::get_package_share_directory("autoware_vehicle_cmd_gate"); const auto vehicle_info_util_dir = ament_index_cpp::get_package_share_directory("vehicle_info_util"); diff --git a/control/vehicle_cmd_gate/test/src/test_main.cpp b/control/autoware_vehicle_cmd_gate/test/src/test_main.cpp similarity index 100% rename from control/vehicle_cmd_gate/test/src/test_main.cpp rename to control/autoware_vehicle_cmd_gate/test/src/test_main.cpp diff --git a/control/vehicle_cmd_gate/test/src/test_vehicle_cmd_filter.cpp b/control/autoware_vehicle_cmd_gate/test/src/test_vehicle_cmd_filter.cpp similarity index 98% rename from control/vehicle_cmd_gate/test/src/test_vehicle_cmd_filter.cpp rename to control/autoware_vehicle_cmd_gate/test/src/test_vehicle_cmd_filter.cpp index 5fbab1c5cfb4f..528253671b38a 100644 --- a/control/vehicle_cmd_gate/test/src/test_vehicle_cmd_filter.cpp +++ b/control/autoware_vehicle_cmd_gate/test/src/test_vehicle_cmd_filter.cpp @@ -24,17 +24,17 @@ #define ASSERT_LT_NEAR(x, y) ASSERT_LT(x, y + THRESHOLD) #define ASSERT_GT_NEAR(x, y) ASSERT_GT(x, y - THRESHOLD) +using autoware::vehicle_cmd_gate::LimitArray; using autoware_control_msgs::msg::Control; -using vehicle_cmd_gate::LimitArray; constexpr double NOMINAL_INTERVAL = 1.0; void setFilterParams( - vehicle_cmd_gate::VehicleCmdFilter & f, double v, LimitArray speed_points, LimitArray a, + autoware::vehicle_cmd_gate::VehicleCmdFilter & f, double v, LimitArray speed_points, LimitArray a, LimitArray j, LimitArray lat_a, LimitArray lat_j, LimitArray steer_diff, LimitArray steer_lim, LimitArray steer_rate_lim, const double wheelbase) { - vehicle_cmd_gate::VehicleCmdFilterParam p; + autoware::vehicle_cmd_gate::VehicleCmdFilterParam p; p.vel_lim = v; p.wheel_base = wheelbase; p.reference_speed_points = speed_points; @@ -105,7 +105,7 @@ void test_1d_limit( const double WHEELBASE = 3.0; const double DT = 0.1; // [s] - vehicle_cmd_gate::VehicleCmdFilter filter; + autoware::vehicle_cmd_gate::VehicleCmdFilter filter; filter.setCurrentSpeed(ego_v); setFilterParams( filter, V_LIM, {0.0}, {A_LIM}, {J_LIM}, {LAT_A_LIM}, {LAT_J_LIM}, {STEER_DIFF}, {STEER_LIM}, @@ -275,9 +275,9 @@ TEST(VehicleCmdFilter, VehicleCmdFilter) TEST(VehicleCmdFilter, VehicleCmdFilterInterpolate) { constexpr double WHEELBASE = 2.8; - vehicle_cmd_gate::VehicleCmdFilter filter; + autoware::vehicle_cmd_gate::VehicleCmdFilter filter; - vehicle_cmd_gate::VehicleCmdFilterParam p; + autoware::vehicle_cmd_gate::VehicleCmdFilterParam p; p.wheel_base = WHEELBASE; p.vel_lim = 20.0; p.reference_speed_points = std::vector{2.0, 4.0, 10.0}; diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index a4f896048739f..dea0bc1d7c442 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -194,8 +194,8 @@ def launch_setup(context, *args, **kwargs): # vehicle cmd gate vehicle_cmd_gate_component = ComposableNode( - package="vehicle_cmd_gate", - plugin="vehicle_cmd_gate::VehicleCmdGate", + package="autoware_vehicle_cmd_gate", + plugin="autoware::vehicle_cmd_gate::VehicleCmdGate", name="vehicle_cmd_gate", remappings=[ ("input/steering", "/vehicle/status/steering_status"), diff --git a/launch/tier4_control_launch/package.xml b/launch/tier4_control_launch/package.xml index fda612f05436c..cfa1a07d4ea45 100644 --- a/launch/tier4_control_launch/package.xml +++ b/launch/tier4_control_launch/package.xml @@ -12,12 +12,12 @@ autoware_cmake autoware_lane_departure_checker + autoware_vehicle_cmd_gate control_evaluator external_cmd_converter external_cmd_selector shift_decider trajectory_follower_node - vehicle_cmd_gate ament_lint_auto autoware_lint_common From 2235e20be19cd59ae394cbac4d86a36f8b3b0176 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Mon, 10 Jun 2024 10:24:17 +0900 Subject: [PATCH 43/65] feat(autoware_lane_departure_checker): use polling subscriber (#7358) * use polling subscriber Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../lane_departure_checker_node.hpp | 16 +++-- .../lane_departure_checker_node.cpp | 62 +++++-------------- 2 files changed, 27 insertions(+), 51 deletions(-) diff --git a/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker_node.hpp b/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker_node.hpp index be7126944f767..d37ef30d6b8e8 100644 --- a/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker_node.hpp +++ b/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker_node.hpp @@ -16,6 +16,7 @@ #define AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_NODE_HPP_ #include "autoware_lane_departure_checker/lane_departure_checker.hpp" +#include "tier4_autoware_utils/ros/polling_subscriber.hpp" #include #include @@ -66,11 +67,16 @@ class LaneDepartureCheckerNode : public rclcpp::Node private: // Subscriber - rclcpp::Subscription::SharedPtr sub_odom_; - rclcpp::Subscription::SharedPtr sub_lanelet_map_bin_; - rclcpp::Subscription::SharedPtr sub_route_; - rclcpp::Subscription::SharedPtr sub_reference_trajectory_; - rclcpp::Subscription::SharedPtr sub_predicted_trajectory_; + tier4_autoware_utils::InterProcessPollingSubscriber sub_odom_{ + this, "~/input/odometry"}; + tier4_autoware_utils::InterProcessPollingSubscriber sub_lanelet_map_bin_{ + this, "~/input/lanelet_map_bin", rclcpp::QoS{1}.transient_local()}; + tier4_autoware_utils::InterProcessPollingSubscriber sub_route_{ + this, "~/input/route"}; + tier4_autoware_utils::InterProcessPollingSubscriber sub_reference_trajectory_{ + this, "~/input/reference_trajectory"}; + tier4_autoware_utils::InterProcessPollingSubscriber sub_predicted_trajectory_{ + this, "~/input/predicted_trajectory"}; // Data Buffer nav_msgs::msg::Odometry::ConstSharedPtr current_odom_; diff --git a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index 2b919f89e6e95..7956410fdf898 100644 --- a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -169,22 +169,6 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o lane_departure_checker_ = std::make_unique(); lane_departure_checker_->setParam(param_, vehicle_info); - // Subscriber - sub_odom_ = this->create_subscription( - "~/input/odometry", 1, std::bind(&LaneDepartureCheckerNode::onOdometry, this, _1)); - sub_lanelet_map_bin_ = this->create_subscription( - "~/input/lanelet_map_bin", rclcpp::QoS{1}.transient_local(), - std::bind(&LaneDepartureCheckerNode::onLaneletMapBin, this, _1)); - sub_route_ = this->create_subscription( - "~/input/route", rclcpp::QoS{1}.transient_local(), - std::bind(&LaneDepartureCheckerNode::onRoute, this, _1)); - sub_reference_trajectory_ = this->create_subscription( - "~/input/reference_trajectory", 1, - std::bind(&LaneDepartureCheckerNode::onReferenceTrajectory, this, _1)); - sub_predicted_trajectory_ = this->create_subscription( - "~/input/predicted_trajectory", 1, - std::bind(&LaneDepartureCheckerNode::onPredictedTrajectory, this, _1)); - // Publisher // Nothing @@ -201,36 +185,6 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o this, get_clock(), period_ns, std::bind(&LaneDepartureCheckerNode::onTimer, this)); } -void LaneDepartureCheckerNode::onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg) -{ - current_odom_ = msg; -} - -void LaneDepartureCheckerNode::onLaneletMapBin(const LaneletMapBin::ConstSharedPtr msg) -{ - lanelet_map_ = std::make_shared(); - lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_, &traffic_rules_, &routing_graph_); - - // get all shoulder lanes - lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_); - shoulder_lanelets_ = lanelet::utils::query::shoulderLanelets(all_lanelets); -} - -void LaneDepartureCheckerNode::onRoute(const LaneletRoute::ConstSharedPtr msg) -{ - route_ = msg; -} - -void LaneDepartureCheckerNode::onReferenceTrajectory(const Trajectory::ConstSharedPtr msg) -{ - reference_trajectory_ = msg; -} - -void LaneDepartureCheckerNode::onPredictedTrajectory(const Trajectory::ConstSharedPtr msg) -{ - predicted_trajectory_ = msg; -} - bool LaneDepartureCheckerNode::isDataReady() { if (!current_odom_) { @@ -300,6 +254,22 @@ void LaneDepartureCheckerNode::onTimer() tier4_autoware_utils::StopWatch stop_watch; stop_watch.tic("Total"); + current_odom_ = sub_odom_.takeData(); + route_ = sub_route_.takeData(); + reference_trajectory_ = sub_reference_trajectory_.takeData(); + predicted_trajectory_ = sub_predicted_trajectory_.takeData(); + + const auto lanelet_map_bin_msg = sub_lanelet_map_bin_.takeData(); + if (lanelet_map_bin_msg) { + lanelet_map_ = std::make_shared(); + lanelet::utils::conversion::fromBinMsg( + *lanelet_map_bin_msg, lanelet_map_, &traffic_rules_, &routing_graph_); + + // get all shoulder lanes + lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_); + shoulder_lanelets_ = lanelet::utils::query::shoulderLanelets(all_lanelets); + } + if (!isDataReady()) { return; } From af9194eb00b3aedc13e70f0e05ef1aaae45690a1 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 10 Jun 2024 10:26:26 +0900 Subject: [PATCH 44/65] chore(control): add maintainer for several control modules (#7389) add maintainer Signed-off-by: Zulfaqar Azmi --- control/operation_mode_transition_manager/package.xml | 1 + control/pure_pursuit/package.xml | 1 + control/shift_decider/package.xml | 1 + 3 files changed, 3 insertions(+) diff --git a/control/operation_mode_transition_manager/package.xml b/control/operation_mode_transition_manager/package.xml index 99439aa7e3ab7..81517675281c3 100644 --- a/control/operation_mode_transition_manager/package.xml +++ b/control/operation_mode_transition_manager/package.xml @@ -4,6 +4,7 @@ The vehicle_cmd_gate package Takamasa Horibe Tomoya Kimura + Takayuki Murooka Apache License 2.0 Takamasa Horibe diff --git a/control/pure_pursuit/package.xml b/control/pure_pursuit/package.xml index b4820aee5cec4..0747766af54c8 100644 --- a/control/pure_pursuit/package.xml +++ b/control/pure_pursuit/package.xml @@ -5,6 +5,7 @@ 0.1.0 The pure_pursuit package Takamasa Horibe + Takayuki Murooka Apache License 2.0 Berkay Karaman diff --git a/control/shift_decider/package.xml b/control/shift_decider/package.xml index 885e780c90bcc..a175a6ae9e599 100644 --- a/control/shift_decider/package.xml +++ b/control/shift_decider/package.xml @@ -5,6 +5,7 @@ 0.1.0 The shift_decider package Takamasa Horibe + Takayuki Murooka Apache License 2.0 Takamasa Horibe From ddce1de8053feef5c409e04cec648e25e021dc73 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Mon, 10 Jun 2024 03:51:19 +0200 Subject: [PATCH 45/65] refactor(behavior_velocity_stop_line_module): prefix package and namespace with autoware_ (#7285) * refactor(behavior_velocity_stop_line_module): prefix package and namespace with autoware_ Signed-off-by: Esteve Fernandez * style(pre-commit): autofix --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .github/CODEOWNERS | 2 +- planning/.pages | 2 +- planning/autoware_behavior_velocity_planner/README.md | 2 +- planning/autoware_behavior_velocity_planner/package.xml | 2 +- .../test/src/test_node_interface.cpp | 2 +- .../CMakeLists.txt | 2 +- .../README.md | 0 .../config/stop_line.param.yaml | 0 .../docs/calculate_stop_pose.drawio.svg | 0 .../docs/find_collision_segment.drawio.svg | 0 .../docs/find_offset_segment.drawio.svg | 0 .../docs/keep_stopping.svg | 0 .../docs/node_and_segment.drawio.svg | 0 .../docs/restart.svg | 0 .../docs/restart_prevention.svg | 0 .../docs/stop_line.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 23 files changed, 9 insertions(+), 9 deletions(-) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/CMakeLists.txt (86%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/README.md (100%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/config/stop_line.param.yaml (100%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/docs/calculate_stop_pose.drawio.svg (100%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/docs/find_collision_segment.drawio.svg (100%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/docs/find_offset_segment.drawio.svg (100%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/docs/keep_stopping.svg (100%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/docs/node_and_segment.drawio.svg (100%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/docs/restart.svg (100%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/docs/restart_prevention.svg (100%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/docs/stop_line.svg (100%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/package.xml (90%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/plugins.xml (72%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/src/debug.cpp (100%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/src/manager.cpp (100%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/src/manager.hpp (100%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/src/scene.cpp (100%) rename planning/{behavior_velocity_stop_line_module => autoware_behavior_velocity_stop_line_module}/src/scene.hpp (100%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 084349cda0af3..f0fb702f594ea 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -151,6 +151,7 @@ planning/autoware_behavior_path_planner_common/** daniel.sanchez@tier4.jp fumiya planning/autoware_behavior_path_static_obstacle_avoidance_module/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/autoware_behavior_velocity_planner/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/autoware_behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/autoware_behavior_velocity_stop_line_module/** fumiya.watanabe@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp zhe.shen@tier4.jp planning/autoware_behavior_velocity_template_module/** daniel.sanchez@tier4.jp planning/autoware_behavior_velocity_virtual_traffic_light_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/autoware_behavior_velocity_walkway_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp @@ -181,7 +182,6 @@ planning/behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp planning/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 planning/autoware_behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -planning/behavior_velocity_stop_line_module/** fumiya.watanabe@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp zhe.shen@tier4.jp planning/behavior_velocity_traffic_light_module/** mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/freespace_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/freespace_planning_algorithms/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp diff --git a/planning/.pages b/planning/.pages index c144941662a5d..efb5e677ab6c6 100644 --- a/planning/.pages +++ b/planning/.pages @@ -31,7 +31,7 @@ nav: - 'Occlusion Spot': planning/behavior_velocity_occlusion_spot_module - 'Run Out': planning/autoware_behavior_velocity_run_out_module - 'Speed Bump': planning/behavior_velocity_speed_bump_module - - 'Stop Line': planning/behavior_velocity_stop_line_module + - 'Stop Line': planning/autoware_behavior_velocity_stop_line_module - 'Traffic Light': planning/behavior_velocity_traffic_light_module - 'Virtual Traffic Light': planning/autoware_behavior_velocity_virtual_traffic_light_module - 'Walkway': planning/autoware_behavior_velocity_walkway_module diff --git a/planning/autoware_behavior_velocity_planner/README.md b/planning/autoware_behavior_velocity_planner/README.md index acf4c1ce78e56..400768dd978d9 100644 --- a/planning/autoware_behavior_velocity_planner/README.md +++ b/planning/autoware_behavior_velocity_planner/README.md @@ -13,7 +13,7 @@ It loads modules as plugins. Please refer to the links listed below for detail o - [Detection Area](../behavior_velocity_detection_area_module/README.md) - [Intersection](../autoware_behavior_velocity_intersection_module/README.md) - [MergeFromPrivate](../behavior_velocity_intersection_module/README.md#merge-from-private) -- [Stop Line](../behavior_velocity_stop_line_module/README.md) +- [Stop Line](../autoware_behavior_velocity_stop_line_module/README.md) - [Virtual Traffic Light](../autoware_behavior_velocity_virtual_traffic_light_module/README.md) - [Traffic Light](../behavior_velocity_traffic_light_module/README.md) - [Occlusion Spot](../behavior_velocity_occlusion_spot_module/README.md) diff --git a/planning/autoware_behavior_velocity_planner/package.xml b/planning/autoware_behavior_velocity_planner/package.xml index 70fd92fd9e072..4dcaf22306c22 100644 --- a/planning/autoware_behavior_velocity_planner/package.xml +++ b/planning/autoware_behavior_velocity_planner/package.xml @@ -67,6 +67,7 @@ ament_lint_auto autoware_behavior_velocity_intersection_module autoware_behavior_velocity_run_out_module + autoware_behavior_velocity_stop_line_module autoware_behavior_velocity_virtual_traffic_light_module autoware_behavior_velocity_walkway_module autoware_lint_common @@ -77,7 +78,6 @@ behavior_velocity_no_stopping_area_module behavior_velocity_occlusion_spot_module behavior_velocity_speed_bump_module - behavior_velocity_stop_line_module behavior_velocity_traffic_light_module diff --git a/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp index cf8b918418c53..a10ad86e4fb00 100644 --- a/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp @@ -104,7 +104,7 @@ std::shared_ptr generateNode() get_behavior_velocity_module_config_no_prefix("occlusion_spot"), get_behavior_velocity_module_config("run_out"), get_behavior_velocity_module_config_no_prefix("speed_bump"), - get_behavior_velocity_module_config_no_prefix("stop_line"), + get_behavior_velocity_module_config("stop_line"), get_behavior_velocity_module_config_no_prefix("traffic_light"), get_behavior_velocity_module_config("virtual_traffic_light"), get_behavior_velocity_module_config_no_prefix("no_drivable_lane")}); diff --git a/planning/behavior_velocity_stop_line_module/CMakeLists.txt b/planning/autoware_behavior_velocity_stop_line_module/CMakeLists.txt similarity index 86% rename from planning/behavior_velocity_stop_line_module/CMakeLists.txt rename to planning/autoware_behavior_velocity_stop_line_module/CMakeLists.txt index bef98aafe6f75..402eb5e20aa24 100644 --- a/planning/behavior_velocity_stop_line_module/CMakeLists.txt +++ b/planning/autoware_behavior_velocity_stop_line_module/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(behavior_velocity_stop_line_module) +project(autoware_behavior_velocity_stop_line_module) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/planning/behavior_velocity_stop_line_module/README.md b/planning/autoware_behavior_velocity_stop_line_module/README.md similarity index 100% rename from planning/behavior_velocity_stop_line_module/README.md rename to planning/autoware_behavior_velocity_stop_line_module/README.md diff --git a/planning/behavior_velocity_stop_line_module/config/stop_line.param.yaml b/planning/autoware_behavior_velocity_stop_line_module/config/stop_line.param.yaml similarity index 100% rename from planning/behavior_velocity_stop_line_module/config/stop_line.param.yaml rename to planning/autoware_behavior_velocity_stop_line_module/config/stop_line.param.yaml diff --git a/planning/behavior_velocity_stop_line_module/docs/calculate_stop_pose.drawio.svg b/planning/autoware_behavior_velocity_stop_line_module/docs/calculate_stop_pose.drawio.svg similarity index 100% rename from planning/behavior_velocity_stop_line_module/docs/calculate_stop_pose.drawio.svg rename to planning/autoware_behavior_velocity_stop_line_module/docs/calculate_stop_pose.drawio.svg diff --git a/planning/behavior_velocity_stop_line_module/docs/find_collision_segment.drawio.svg b/planning/autoware_behavior_velocity_stop_line_module/docs/find_collision_segment.drawio.svg similarity index 100% rename from planning/behavior_velocity_stop_line_module/docs/find_collision_segment.drawio.svg rename to planning/autoware_behavior_velocity_stop_line_module/docs/find_collision_segment.drawio.svg diff --git a/planning/behavior_velocity_stop_line_module/docs/find_offset_segment.drawio.svg b/planning/autoware_behavior_velocity_stop_line_module/docs/find_offset_segment.drawio.svg similarity index 100% rename from planning/behavior_velocity_stop_line_module/docs/find_offset_segment.drawio.svg rename to planning/autoware_behavior_velocity_stop_line_module/docs/find_offset_segment.drawio.svg diff --git a/planning/behavior_velocity_stop_line_module/docs/keep_stopping.svg b/planning/autoware_behavior_velocity_stop_line_module/docs/keep_stopping.svg similarity index 100% rename from planning/behavior_velocity_stop_line_module/docs/keep_stopping.svg rename to planning/autoware_behavior_velocity_stop_line_module/docs/keep_stopping.svg diff --git a/planning/behavior_velocity_stop_line_module/docs/node_and_segment.drawio.svg b/planning/autoware_behavior_velocity_stop_line_module/docs/node_and_segment.drawio.svg similarity index 100% rename from planning/behavior_velocity_stop_line_module/docs/node_and_segment.drawio.svg rename to planning/autoware_behavior_velocity_stop_line_module/docs/node_and_segment.drawio.svg diff --git a/planning/behavior_velocity_stop_line_module/docs/restart.svg b/planning/autoware_behavior_velocity_stop_line_module/docs/restart.svg similarity index 100% rename from planning/behavior_velocity_stop_line_module/docs/restart.svg rename to planning/autoware_behavior_velocity_stop_line_module/docs/restart.svg diff --git a/planning/behavior_velocity_stop_line_module/docs/restart_prevention.svg b/planning/autoware_behavior_velocity_stop_line_module/docs/restart_prevention.svg similarity index 100% rename from planning/behavior_velocity_stop_line_module/docs/restart_prevention.svg rename to planning/autoware_behavior_velocity_stop_line_module/docs/restart_prevention.svg diff --git a/planning/behavior_velocity_stop_line_module/docs/stop_line.svg b/planning/autoware_behavior_velocity_stop_line_module/docs/stop_line.svg similarity index 100% rename from planning/behavior_velocity_stop_line_module/docs/stop_line.svg rename to planning/autoware_behavior_velocity_stop_line_module/docs/stop_line.svg diff --git a/planning/behavior_velocity_stop_line_module/package.xml b/planning/autoware_behavior_velocity_stop_line_module/package.xml similarity index 90% rename from planning/behavior_velocity_stop_line_module/package.xml rename to planning/autoware_behavior_velocity_stop_line_module/package.xml index 3132f60d1f342..c3d3baa965834 100644 --- a/planning/behavior_velocity_stop_line_module/package.xml +++ b/planning/autoware_behavior_velocity_stop_line_module/package.xml @@ -1,9 +1,9 @@ - behavior_velocity_stop_line_module + autoware_behavior_velocity_stop_line_module 0.1.0 - The behavior_velocity_stop_line_module package + The autoware_behavior_velocity_stop_line_module package Fumiya Watanabe Zhe Shen diff --git a/planning/behavior_velocity_stop_line_module/plugins.xml b/planning/autoware_behavior_velocity_stop_line_module/plugins.xml similarity index 72% rename from planning/behavior_velocity_stop_line_module/plugins.xml rename to planning/autoware_behavior_velocity_stop_line_module/plugins.xml index 4b8ce9852fcec..6765a4bc1bb13 100644 --- a/planning/behavior_velocity_stop_line_module/plugins.xml +++ b/planning/autoware_behavior_velocity_stop_line_module/plugins.xml @@ -1,3 +1,3 @@ - + diff --git a/planning/behavior_velocity_stop_line_module/src/debug.cpp b/planning/autoware_behavior_velocity_stop_line_module/src/debug.cpp similarity index 100% rename from planning/behavior_velocity_stop_line_module/src/debug.cpp rename to planning/autoware_behavior_velocity_stop_line_module/src/debug.cpp diff --git a/planning/behavior_velocity_stop_line_module/src/manager.cpp b/planning/autoware_behavior_velocity_stop_line_module/src/manager.cpp similarity index 100% rename from planning/behavior_velocity_stop_line_module/src/manager.cpp rename to planning/autoware_behavior_velocity_stop_line_module/src/manager.cpp diff --git a/planning/behavior_velocity_stop_line_module/src/manager.hpp b/planning/autoware_behavior_velocity_stop_line_module/src/manager.hpp similarity index 100% rename from planning/behavior_velocity_stop_line_module/src/manager.hpp rename to planning/autoware_behavior_velocity_stop_line_module/src/manager.hpp diff --git a/planning/behavior_velocity_stop_line_module/src/scene.cpp b/planning/autoware_behavior_velocity_stop_line_module/src/scene.cpp similarity index 100% rename from planning/behavior_velocity_stop_line_module/src/scene.cpp rename to planning/autoware_behavior_velocity_stop_line_module/src/scene.cpp diff --git a/planning/behavior_velocity_stop_line_module/src/scene.hpp b/planning/autoware_behavior_velocity_stop_line_module/src/scene.hpp similarity index 100% rename from planning/behavior_velocity_stop_line_module/src/scene.hpp rename to planning/autoware_behavior_velocity_stop_line_module/src/scene.hpp From 7ef10892bc64c58a10cc20a2277498f3996a4f7c Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 10 Jun 2024 10:54:44 +0900 Subject: [PATCH 46/65] feat(tier4_autoware_utils): add InterProcessPollingSubscriber helper factory (#7349) Signed-off-by: Mamoru Sobue --- .../tier4_autoware_utils/ros/polling_subscriber.hpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp index b842261d56cfa..20b67ed13dfb5 100644 --- a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp @@ -27,6 +27,14 @@ namespace tier4_autoware_utils template class InterProcessPollingSubscriber { +public: + using SharedPtr = std::shared_ptr>; + static SharedPtr create_subscription( + rclcpp::Node * node, const std::string & topic_name, const rclcpp::QoS & qos = rclcpp::QoS{1}) + { + return std::make_shared>(node, topic_name, qos); + } + private: typename rclcpp::Subscription::SharedPtr subscriber_; typename T::SharedPtr data_; From 8743bc0999153028dc1651f98cb15ec499fda0ab Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 10 Jun 2024 10:59:47 +0900 Subject: [PATCH 47/65] feat(route_hanler): handle waypoints in lanelet2 map (#7222) * feat(route_hanler): handle waypoints in lanelet2 map Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../include/route_handler/route_handler.hpp | 23 +- planning/route_handler/src/route_handler.cpp | 288 ++++++++++++++++-- 2 files changed, 292 insertions(+), 19 deletions(-) diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index 24a20f86ed718..d692337b10bd6 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -1,4 +1,4 @@ -// Copyright 2021-2023 Tier IV, Inc. +// Copyright 2021-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. @@ -51,6 +51,20 @@ enum class Direction { NONE, LEFT, RIGHT }; enum class PullOverDirection { NONE, LEFT, RIGHT }; enum class PullOutDirection { NONE, LEFT, RIGHT }; +struct ReferencePoint +{ + bool is_waypoint{false}; + geometry_msgs::msg::Point point; +}; +using PiecewiseReferencePoints = std::vector; + +struct PiecewiseWaypoints +{ + lanelet::Id lanelet_id; + std::vector piecewise_waypoints; +}; +using Waypoints = std::vector; + class RouteHandler { public: @@ -270,6 +284,13 @@ class RouteHandler PathWithLaneId getCenterLinePath( const lanelet::ConstLanelets & lanelet_sequence, const double s_start, const double s_end, bool use_exact = true) const; + std::vector calcWaypointsVector(const lanelet::ConstLanelets & lanelet_sequence) const; + void removeOverlappedCenterlineWithWaypoints( + std::vector & piecewise_ref_points_vec, + const std::vector & piecewise_waypoints, + const lanelet::ConstLanelets & lanelet_sequence, + const size_t piecewise_waypoints_lanelet_sequence_index, + const bool is_removing_direction_forward) const; std::optional getLaneChangeTarget( const lanelet::ConstLanelets & lanelets, const Direction direction = Direction::NONE) const; std::optional getLaneChangeTargetExceptPreferredLane( diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index d410cb2668175..1fd0dd7747e49 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -1,4 +1,4 @@ -// Copyright 2021-2023 Tier IV, Inc. +// Copyright 2021-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. @@ -38,9 +38,12 @@ #include #include #include +#include #include #include +namespace route_handler +{ namespace { using autoware_planning_msgs::msg::LaneletPrimitive; @@ -129,10 +132,49 @@ std::string toString(const geometry_msgs::msg::Pose & pose) return ss.str(); } -} // namespace +bool isClose( + const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2, const double epsilon) +{ + return std::abs(p1.x - p2.x) < epsilon && std::abs(p1.y - p2.y) < epsilon; +} -namespace route_handler +PiecewiseReferencePoints convertWaypointsToReferencePoints( + const std::vector & piecewise_waypoints) { + PiecewiseReferencePoints piecewise_ref_points; + for (const auto & piecewise_waypoint : piecewise_waypoints) { + piecewise_ref_points.push_back(ReferencePoint{true, piecewise_waypoint}); + } + return piecewise_ref_points; +} + +template +bool isIndexWithinVector(const std::vector & vec, const int index) +{ + return 0 <= index && index < static_cast(vec.size()); +} + +template +void removeIndicesFromVector(std::vector & vec, std::vector indices) +{ + // sort indices in a descending order + std::sort(indices.begin(), indices.end(), std::greater()); + + // remove indices from vector + for (const size_t index : indices) { + vec.erase(vec.begin() + index); + } +} + +lanelet::ArcCoordinates calcArcCoordinates( + const lanelet::ConstLanelet & lanelet, const geometry_msgs::msg::Point & point) +{ + return lanelet::geometry::toArcCoordinates( + to2D(lanelet.centerline()), + to2D(lanelet::utils::conversion::toLaneletPoint(point)).basicPoint()); +} +} // namespace + RouteHandler::RouteHandler(const LaneletMapBin & map_msg) { setMap(map_msg); @@ -1494,21 +1536,21 @@ PathWithLaneId RouteHandler::getCenterLinePath( const lanelet::ConstLanelets & lanelet_sequence, const double s_start, const double s_end, bool use_exact) const { - PathWithLaneId reference_path{}; - double s = 0; + using lanelet::utils::to2D; + using lanelet::utils::conversion::toLaneletPoint; + // 1. calculate reference points by lanelets' centerline + // NOTE: This vector aligns the vector lanelet_sequence. + std::vector piecewise_ref_points_vec; + const auto add_ref_point = [&](const auto & pt) { + piecewise_ref_points_vec.back().push_back( + ReferencePoint{false, lanelet::utils::conversion::toGeomMsgPt(pt)}); + }; + double s = 0; for (const auto & llt : lanelet_sequence) { - const lanelet::traffic_rules::SpeedLimitInformation limit = traffic_rules_ptr_->speedLimit(llt); - const lanelet::ConstLineString3d centerline = llt.centerline(); - - const auto add_path_point = [&reference_path, &limit, &llt](const auto & pt) { - PathPointWithLaneId p{}; - p.point.pose.position = lanelet::utils::conversion::toGeomMsgPt(pt); - p.lane_ids.push_back(llt.id()); - p.point.longitudinal_velocity_mps = static_cast(limit.speedLimit.value()); - reference_path.points.push_back(p); - }; + piecewise_ref_points_vec.push_back(std::vector{}); + const lanelet::ConstLineString3d centerline = llt.centerline(); for (size_t i = 0; i < centerline.size(); i++) { const auto & pt = centerline[i]; const lanelet::ConstPoint3d next_pt = @@ -1517,19 +1559,102 @@ PathWithLaneId RouteHandler::getCenterLinePath( if (s < s_start && s + distance > s_start) { const auto p = use_exact ? get3DPointFrom2DArcLength(lanelet_sequence, s_start) : pt; - add_path_point(p); + add_ref_point(p); } if (s >= s_start && s <= s_end) { - add_path_point(pt); + add_ref_point(pt); } if (s < s_end && s + distance > s_end) { const auto p = use_exact ? get3DPointFrom2DArcLength(lanelet_sequence, s_end) : next_pt; - add_path_point(p); + add_ref_point(p); } s += distance; } } + // 2. calculate waypoints + const auto waypoints_vec = calcWaypointsVector(lanelet_sequence); + + // 3. remove points in the margin of the waypoint + for (const auto & waypoints : waypoints_vec) { + for (auto piecewise_waypoints_itr = waypoints.begin(); + piecewise_waypoints_itr != waypoints.end(); ++piecewise_waypoints_itr) { + const auto & piecewise_waypoints = piecewise_waypoints_itr->piecewise_waypoints; + const auto lanelet_id = piecewise_waypoints_itr->lanelet_id; + + // calculate index of lanelet_sequence which corresponds to piecewise_waypoints. + const auto lanelet_sequence_itr = std::find_if( + lanelet_sequence.begin(), lanelet_sequence.end(), + [&](const auto & lanelet) { return lanelet.id() == lanelet_id; }); + if (lanelet_sequence_itr == lanelet_sequence.end()) { + continue; + } + const size_t piecewise_waypoints_lanelet_sequence_index = + std::distance(lanelet_sequence.begin(), lanelet_sequence_itr); + + // calculate reference points by waypoints + const auto ref_points_by_waypoints = convertWaypointsToReferencePoints(piecewise_waypoints); + + // update reference points by waypoints + const bool is_first_waypoint_contained = piecewise_waypoints_itr == waypoints.begin(); + const bool is_last_waypoint_contained = piecewise_waypoints_itr == waypoints.end() - 1; + if (is_first_waypoint_contained || is_last_waypoint_contained) { + // If piecewise_waypoints_itr is the end (first or last) of piecewise_waypoints + + const auto original_piecewise_ref_points = + piecewise_ref_points_vec.at(piecewise_waypoints_lanelet_sequence_index); + + // define current_piecewise_ref_points, and initialize it with waypoints + auto & current_piecewise_ref_points = + piecewise_ref_points_vec.at(piecewise_waypoints_lanelet_sequence_index); + current_piecewise_ref_points = ref_points_by_waypoints; + if (is_first_waypoint_contained) { + // add original reference points to current reference points, and remove reference points + // overlapped with waypoints + current_piecewise_ref_points.insert( + current_piecewise_ref_points.begin(), original_piecewise_ref_points.begin(), + original_piecewise_ref_points.end()); + const bool is_removing_direction_forward = false; + removeOverlappedCenterlineWithWaypoints( + piecewise_ref_points_vec, piecewise_waypoints, lanelet_sequence, + piecewise_waypoints_lanelet_sequence_index, is_removing_direction_forward); + } + if (is_last_waypoint_contained) { + // add original reference points to current reference points, and remove reference points + // overlapped with waypoints + current_piecewise_ref_points.insert( + current_piecewise_ref_points.end(), original_piecewise_ref_points.begin(), + original_piecewise_ref_points.end()); + const bool is_removing_direction_forward = true; + removeOverlappedCenterlineWithWaypoints( + piecewise_ref_points_vec, piecewise_waypoints, lanelet_sequence, + piecewise_waypoints_lanelet_sequence_index, is_removing_direction_forward); + } + } else { + // If piecewise_waypoints_itr is not the end (first or last) of piecewise_waypoints, + // remove all the reference points and add waypoints. + piecewise_ref_points_vec.at(piecewise_waypoints_lanelet_sequence_index) = + ref_points_by_waypoints; + } + } + } + + // 4. convert to PathPointsWithLaneIds + PathWithLaneId reference_path{}; + for (size_t lanelet_idx = 0; lanelet_idx < lanelet_sequence.size(); ++lanelet_idx) { + const auto & lanelet = lanelet_sequence.at(lanelet_idx); + const float speed_limit = + static_cast(traffic_rules_ptr_->speedLimit(lanelet).speedLimit.value()); + + const auto & piecewise_ref_points = piecewise_ref_points_vec.at(lanelet_idx); + for (const auto & ref_point : piecewise_ref_points) { + PathPointWithLaneId p{}; + p.point.pose.position = ref_point.point; + p.lane_ids.push_back(lanelet.id()); + p.point.longitudinal_velocity_mps = speed_limit; + reference_path.points.push_back(p); + } + } reference_path = removeOverlappingPoints(reference_path); // append a point only when having one point so that yaw calculation would work @@ -1565,6 +1690,133 @@ PathWithLaneId RouteHandler::getCenterLinePath( return reference_path; } +std::vector RouteHandler::calcWaypointsVector( + const lanelet::ConstLanelets & lanelet_sequence) const +{ + std::vector waypoints_vec; + for (size_t lanelet_idx = 0; lanelet_idx < lanelet_sequence.size(); ++lanelet_idx) { + const auto & lanelet = lanelet_sequence.at(lanelet_idx); + if (!lanelet.hasAttribute("waypoints")) { + continue; + } + + // generate piecewise waypoints + PiecewiseWaypoints piecewise_waypoints{lanelet.id(), {}}; + const auto waypoints_id = lanelet.attribute("waypoints").asId().value(); + for (const auto & waypoint : lanelet_map_ptr_->lineStringLayer.get(waypoints_id)) { + piecewise_waypoints.piecewise_waypoints.push_back( + lanelet::utils::conversion::toGeomMsgPt(waypoint)); + } + if (piecewise_waypoints.piecewise_waypoints.empty()) { + continue; + } + + // check if the piecewise waypoints are connected to the previous piecewise waypoints + if ( + !waypoints_vec.empty() && isClose( + waypoints_vec.back().back().piecewise_waypoints.back(), + piecewise_waypoints.piecewise_waypoints.front(), 1.0)) { + waypoints_vec.back().push_back(piecewise_waypoints); + } else { + // add new waypoints + Waypoints new_waypoints; + new_waypoints.push_back(piecewise_waypoints); + waypoints_vec.push_back(new_waypoints); + } + } + + return waypoints_vec; +} + +void RouteHandler::removeOverlappedCenterlineWithWaypoints( + std::vector & piecewise_ref_points_vec, + const std::vector & piecewise_waypoints, + const lanelet::ConstLanelets & lanelet_sequence, + const size_t piecewise_waypoints_lanelet_sequence_index, + const bool is_removing_direction_forward) const +{ + const double waypoints_interpolation_arc_margin_ratio = 10.0; + + // calculate arc length threshold + const double front_arc_length_threshold = [&]() { + const auto front_waypoint_arc_coordinates = calcArcCoordinates( + lanelet_sequence.at(piecewise_waypoints_lanelet_sequence_index), piecewise_waypoints.front()); + const double lanelet_arc_length = boost::geometry::length( + lanelet::utils::to2D(lanelet_sequence.at(piecewise_waypoints_lanelet_sequence_index) + .centerline() + .basicLineString())); + return -lanelet_arc_length + front_waypoint_arc_coordinates.length - + std::abs(front_waypoint_arc_coordinates.distance) * + waypoints_interpolation_arc_margin_ratio; + }(); + const double back_arc_length_threshold = [&]() { + const auto back_waypoint_arc_coordinates = calcArcCoordinates( + lanelet_sequence.at(piecewise_waypoints_lanelet_sequence_index), piecewise_waypoints.back()); + return back_waypoint_arc_coordinates.length + std::abs(back_waypoint_arc_coordinates.distance) * + waypoints_interpolation_arc_margin_ratio; + }(); + + double offset_arc_length = 0.0; + int target_lanelet_sequence_index = static_cast(piecewise_waypoints_lanelet_sequence_index); + while (isIndexWithinVector(lanelet_sequence, target_lanelet_sequence_index)) { + auto & target_piecewise_ref_points = piecewise_ref_points_vec.at(target_lanelet_sequence_index); + const double target_lanelet_arc_length = boost::geometry::length(lanelet::utils::to2D( + lanelet_sequence.at(target_lanelet_sequence_index).centerline().basicLineString())); + + // search overlapped ref points in the target lanelet + std::vector overlapped_ref_points_indices{}; + const bool is_search_finished = [&]() { + for (size_t ref_point_unsigned_index = 0; + ref_point_unsigned_index < target_piecewise_ref_points.size(); + ++ref_point_unsigned_index) { + const size_t ref_point_index = + is_removing_direction_forward + ? ref_point_unsigned_index + : target_piecewise_ref_points.size() - 1 - ref_point_unsigned_index; + const auto & ref_point = target_piecewise_ref_points.at(ref_point_index); + + // skip waypoints + if (ref_point.is_waypoint) { + if ( + target_lanelet_sequence_index == + static_cast(piecewise_waypoints_lanelet_sequence_index)) { + overlapped_ref_points_indices.clear(); + } + continue; + } + + const double ref_point_arc_length = + (is_removing_direction_forward ? 0 : -target_lanelet_arc_length) + + calcArcCoordinates(lanelet_sequence.at(target_lanelet_sequence_index), ref_point.point) + .length; + if (is_removing_direction_forward) { + if (back_arc_length_threshold < offset_arc_length + ref_point_arc_length) { + return true; + } + } else { + if (offset_arc_length + ref_point_arc_length < front_arc_length_threshold) { + return true; + } + } + + overlapped_ref_points_indices.push_back(ref_point_index); + } + return false; + }(); + + // remove overlapped indices from ref_points + removeIndicesFromVector(target_piecewise_ref_points, overlapped_ref_points_indices); + + // break if searching overlapped centerline is finished. + if (is_search_finished) { + break; + } + + target_lanelet_sequence_index += is_removing_direction_forward ? 1 : -1; + offset_arc_length = (is_removing_direction_forward ? 1 : -1) * target_lanelet_arc_length; + } +} + bool RouteHandler::isMapMsgReady() const { return is_map_msg_ready_; From 2507944ed24b7e5b9b63598f2e72c65f5cb3eace Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 10 Jun 2024 11:06:01 +0900 Subject: [PATCH 48/65] refactor(freespace_planning_algorithms)!: add autoware prefix (#7375) Signed-off-by: kosuke55 --- .github/CODEOWNERS | 2 +- .../utils/path_utils.hpp | 6 +++--- .../package.xml | 2 +- .../src/utils/path_utils.cpp | 4 ++-- .../data_structs.hpp | 12 ++++++------ .../freespace_pull_out.hpp | 12 ++++++------ .../src/freespace_pull_out.cpp | 2 +- .../CMakeLists.txt | 14 +++++++------- .../README.md | 4 ++-- .../__init__.py | 0 .../astar_search.py | 2 +- .../figs/summary-astar_single.png | Bin .../figs/summary-rrtstar_fastest.png | Bin .../figs/summary-rrtstar_informed_update.png | Bin .../abstract_algorithm.hpp | 10 +++++----- .../astar_search.hpp | 14 +++++++------- .../reeds_shepp.hpp | 10 +++++----- .../rrtstar.hpp | 14 +++++++------- .../rrtstar_core.hpp | 18 +++++++++--------- .../package.xml | 4 ++-- .../rrtstar.md | 0 .../scripts/bind/astar_search_pybind.cpp | 11 +++++++---- .../scripts/example/example.py | 2 +- .../src/abstract_algorithm.cpp | 6 +++--- .../src/astar_search.cpp | 6 +++--- .../src/reeds_shepp.cpp | 8 ++++---- .../src/rrtstar.cpp | 11 +++-------- .../src/rrtstar_core.cpp | 6 +++--- .../test/debug_plot.py | 0 .../test/debug_plot_rrtstar_core.py | 0 .../test_freespace_planning_algorithms.cpp | 8 ++++---- .../test/src/test_rrtstar_core_informed.cpp | 5 ++++- .../freespace_pull_over.hpp | 12 ++++++------ .../goal_planner_module.hpp | 16 ++++++++-------- .../goal_planner_parameters.hpp | 12 ++++++------ .../src/freespace_pull_over.cpp | 2 +- planning/behavior_path_planner/package.xml | 2 +- .../freespace_planner_node.hpp | 18 +++++++++--------- planning/freespace_planner/package.xml | 2 +- .../freespace_planner_node.cpp | 12 ++++++------ 40 files changed, 135 insertions(+), 134 deletions(-) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/CMakeLists.txt (79%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/README.md (96%) rename planning/{freespace_planning_algorithms/freespace_planning_algorithms => autoware_freespace_planning_algorithms/autoware_freespace_planning_algorithms}/__init__.py (100%) rename planning/{freespace_planning_algorithms/freespace_planning_algorithms => autoware_freespace_planning_algorithms/autoware_freespace_planning_algorithms}/astar_search.py (95%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/figs/summary-astar_single.png (100%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/figs/summary-rrtstar_fastest.png (100%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/figs/summary-rrtstar_informed_update.png (100%) rename planning/{freespace_planning_algorithms/include/freespace_planning_algorithms => autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms}/abstract_algorithm.hpp (94%) rename planning/{freespace_planning_algorithms/include/freespace_planning_algorithms => autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms}/astar_search.hpp (91%) rename planning/{freespace_planning_algorithms/include/freespace_planning_algorithms => autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms}/reeds_shepp.hpp (94%) rename planning/{freespace_planning_algorithms/include/freespace_planning_algorithms => autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms}/rrtstar.hpp (83%) rename planning/{freespace_planning_algorithms/include/freespace_planning_algorithms => autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms}/rrtstar_core.hpp (90%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/package.xml (90%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/rrtstar.md (100%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/scripts/bind/astar_search_pybind.cpp (95%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/scripts/example/example.py (97%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/src/abstract_algorithm.cpp (97%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/src/astar_search.cpp (98%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/src/reeds_shepp.cpp (99%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/src/rrtstar.cpp (97%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/src/rrtstar_core.cpp (98%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/test/debug_plot.py (100%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/test/debug_plot_rrtstar_core.py (100%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/test/src/test_freespace_planning_algorithms.cpp (97%) rename planning/{freespace_planning_algorithms => autoware_freespace_planning_algorithms}/test/src/test_rrtstar_core_informed.cpp (94%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index f0fb702f594ea..57fc951f0608c 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -184,7 +184,7 @@ planning/autoware_behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp m planning/behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_traffic_light_module/** mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/freespace_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp -planning/freespace_planning_algorithms/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp +planning/autoware_freespace_planning_algorithms/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/mission_planner/** isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp ryohsuke.mitsudome@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/** maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/motion_velocity_planner/autoware_motion_velocity_planner_common/** maxime.clement@tier4.jp diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/path_utils.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/path_utils.hpp index e58190fa49650..a0bc681144670 100644 --- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/path_utils.hpp +++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/path_utils.hpp @@ -19,7 +19,7 @@ #include #include -#include +#include #include #include @@ -73,8 +73,8 @@ std::pair getPathTurnSignal( const BehaviorPathPlannerParameters & common_parameter); PathWithLaneId convertWayPointsToPathWithLaneId( - const freespace_planning_algorithms::PlannerWaypoints & waypoints, const double velocity, - const lanelet::ConstLanelets & lanelets); + const autoware::freespace_planning_algorithms::PlannerWaypoints & waypoints, + const double velocity, const lanelet::ConstLanelets & lanelets); std::vector getReversingIndices(const PathWithLaneId & path); diff --git a/planning/autoware_behavior_path_planner_common/package.xml b/planning/autoware_behavior_path_planner_common/package.xml index b6fb6a352e91e..03391063b14fc 100644 --- a/planning/autoware_behavior_path_planner_common/package.xml +++ b/planning/autoware_behavior_path_planner_common/package.xml @@ -43,11 +43,11 @@ autoware_cmake autoware_adapi_v1_msgs + autoware_freespace_planning_algorithms autoware_lane_departure_checker autoware_perception_msgs autoware_planning_msgs autoware_rtc_interface - freespace_planning_algorithms geometry_msgs interpolation lanelet2_extension diff --git a/planning/autoware_behavior_path_planner_common/src/utils/path_utils.cpp b/planning/autoware_behavior_path_planner_common/src/utils/path_utils.cpp index 9193db9df11e5..a453ba947331d 100644 --- a/planning/autoware_behavior_path_planner_common/src/utils/path_utils.cpp +++ b/planning/autoware_behavior_path_planner_common/src/utils/path_utils.cpp @@ -330,8 +330,8 @@ std::pair getPathTurnSignal( } PathWithLaneId convertWayPointsToPathWithLaneId( - const freespace_planning_algorithms::PlannerWaypoints & waypoints, const double velocity, - const lanelet::ConstLanelets & lanelets) + const autoware::freespace_planning_algorithms::PlannerWaypoints & waypoints, + const double velocity, const lanelet::ConstLanelets & lanelets) { PathWithLaneId path; path.header = waypoints.header; diff --git a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/data_structs.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/data_structs.hpp index 95c98c3c89733..7959c4aeec111 100644 --- a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/data_structs.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/data_structs.hpp @@ -19,9 +19,9 @@ #include "autoware_behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include "autoware_behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -34,9 +34,9 @@ using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebugMap; using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; using behavior_path_planner::utils::path_safety_checker::TargetObjectsOnLane; -using freespace_planning_algorithms::AstarParam; -using freespace_planning_algorithms::PlannerCommonParam; -using freespace_planning_algorithms::RRTStarParam; +using autoware::freespace_planning_algorithms::AstarParam; +using autoware::freespace_planning_algorithms::PlannerCommonParam; +using autoware::freespace_planning_algorithms::RRTStarParam; struct StartPlannerDebugData { diff --git a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/freespace_pull_out.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/freespace_pull_out.hpp index df640b04e5a72..613911ba33460 100644 --- a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/freespace_pull_out.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/freespace_pull_out.hpp @@ -17,9 +17,9 @@ #include "autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp" -#include -#include -#include +#include +#include +#include #include @@ -27,9 +27,9 @@ namespace behavior_path_planner { -using freespace_planning_algorithms::AbstractPlanningAlgorithm; -using freespace_planning_algorithms::AstarSearch; -using freespace_planning_algorithms::RRTStar; +using autoware::freespace_planning_algorithms::AbstractPlanningAlgorithm; +using autoware::freespace_planning_algorithms::AstarSearch; +using autoware::freespace_planning_algorithms::RRTStar; class FreespacePullOut : public PullOutPlannerBase { diff --git a/planning/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp b/planning/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp index 1dfacd45b5218..f0a83741212b8 100644 --- a/planning/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp +++ b/planning/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp @@ -31,7 +31,7 @@ FreespacePullOut::FreespacePullOut( const vehicle_info_util::VehicleInfo & vehicle_info) : PullOutPlannerBase{node, parameters}, velocity_{parameters.freespace_planner_velocity} { - freespace_planning_algorithms::VehicleShape vehicle_shape( + autoware::freespace_planning_algorithms::VehicleShape vehicle_shape( vehicle_info, parameters.vehicle_shape_margin); if (parameters.freespace_planner_algorithm == "astar") { use_back_ = parameters.astar_parameters.use_back; diff --git a/planning/freespace_planning_algorithms/CMakeLists.txt b/planning/autoware_freespace_planning_algorithms/CMakeLists.txt similarity index 79% rename from planning/freespace_planning_algorithms/CMakeLists.txt rename to planning/autoware_freespace_planning_algorithms/CMakeLists.txt index 726aa47f7a5e5..4f678cd9fdec5 100644 --- a/planning/freespace_planning_algorithms/CMakeLists.txt +++ b/planning/autoware_freespace_planning_algorithms/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(freespace_planning_algorithms) +project(autoware_freespace_planning_algorithms) find_package(autoware_cmake REQUIRED) find_package(python_cmake_module REQUIRED) @@ -19,23 +19,23 @@ target_link_libraries(rrtstar_core reeds_shepp ) -ament_auto_add_library(freespace_planning_algorithms SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED src/abstract_algorithm.cpp src/astar_search.cpp src/rrtstar.cpp ) -target_link_libraries(freespace_planning_algorithms +target_link_libraries(${PROJECT_NAME} reeds_shepp ) if(BUILD_TESTING) find_package(ament_cmake_ros REQUIRED) - ament_add_ros_isolated_gtest(freespace_planning_algorithms-test + ament_add_ros_isolated_gtest(${PROJECT_NAME}-test test/src/test_freespace_planning_algorithms.cpp ) - target_link_libraries(freespace_planning_algorithms-test - freespace_planning_algorithms + target_link_libraries(${PROJECT_NAME}-test + ${PROJECT_NAME} ) find_package(ament_cmake_ros REQUIRED) @@ -43,7 +43,7 @@ if(BUILD_TESTING) test/src/test_rrtstar_core_informed.cpp ) target_link_libraries(rrtstar_core_informed-test - freespace_planning_algorithms + ${PROJECT_NAME} ) endif() diff --git a/planning/freespace_planning_algorithms/README.md b/planning/autoware_freespace_planning_algorithms/README.md similarity index 96% rename from planning/freespace_planning_algorithms/README.md rename to planning/autoware_freespace_planning_algorithms/README.md index 8bd015589d58d..c5ea6b3df8183 100644 --- a/planning/freespace_planning_algorithms/README.md +++ b/planning/autoware_freespace_planning_algorithms/README.md @@ -46,8 +46,8 @@ Some selection criteria would be: Building the package with ros-test and run tests: ```sh -colcon build --packages-select freespace_planning_algorithms -colcon test --packages-select freespace_planning_algorithms +colcon build --packages-select autoware_freespace_planning_algorithms +colcon test --packages-select autoware_freespace_planning_algorithms ``` diff --git a/planning/freespace_planning_algorithms/freespace_planning_algorithms/__init__.py b/planning/autoware_freespace_planning_algorithms/autoware_freespace_planning_algorithms/__init__.py similarity index 100% rename from planning/freespace_planning_algorithms/freespace_planning_algorithms/__init__.py rename to planning/autoware_freespace_planning_algorithms/autoware_freespace_planning_algorithms/__init__.py diff --git a/planning/freespace_planning_algorithms/freespace_planning_algorithms/astar_search.py b/planning/autoware_freespace_planning_algorithms/autoware_freespace_planning_algorithms/astar_search.py similarity index 95% rename from planning/freespace_planning_algorithms/freespace_planning_algorithms/astar_search.py rename to planning/autoware_freespace_planning_algorithms/autoware_freespace_planning_algorithms/astar_search.py index c9dcc351e3ce2..2ffa20150fb0c 100644 --- a/planning/freespace_planning_algorithms/freespace_planning_algorithms/astar_search.py +++ b/planning/autoware_freespace_planning_algorithms/autoware_freespace_planning_algorithms/astar_search.py @@ -12,7 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -import freespace_planning_algorithms.freespace_planning_algorithms_pybind as _fp +import autoware_freespace_planning_algorithms.autoware_freespace_planning_algorithms_pybind as _fp from geometry_msgs.msg import Point from geometry_msgs.msg import Pose from geometry_msgs.msg import Quaternion diff --git a/planning/freespace_planning_algorithms/figs/summary-astar_single.png b/planning/autoware_freespace_planning_algorithms/figs/summary-astar_single.png similarity index 100% rename from planning/freespace_planning_algorithms/figs/summary-astar_single.png rename to planning/autoware_freespace_planning_algorithms/figs/summary-astar_single.png diff --git a/planning/freespace_planning_algorithms/figs/summary-rrtstar_fastest.png b/planning/autoware_freespace_planning_algorithms/figs/summary-rrtstar_fastest.png similarity index 100% rename from planning/freespace_planning_algorithms/figs/summary-rrtstar_fastest.png rename to planning/autoware_freespace_planning_algorithms/figs/summary-rrtstar_fastest.png diff --git a/planning/freespace_planning_algorithms/figs/summary-rrtstar_informed_update.png b/planning/autoware_freespace_planning_algorithms/figs/summary-rrtstar_informed_update.png similarity index 100% rename from planning/freespace_planning_algorithms/figs/summary-rrtstar_informed_update.png rename to planning/autoware_freespace_planning_algorithms/figs/summary-rrtstar_informed_update.png diff --git a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/abstract_algorithm.hpp b/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/abstract_algorithm.hpp similarity index 94% rename from planning/freespace_planning_algorithms/include/freespace_planning_algorithms/abstract_algorithm.hpp rename to planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/abstract_algorithm.hpp index b4e3b2befae40..27a563f4ec1af 100644 --- a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/abstract_algorithm.hpp +++ b/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/abstract_algorithm.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FREESPACE_PLANNING_ALGORITHMS__ABSTRACT_ALGORITHM_HPP_ -#define FREESPACE_PLANNING_ALGORITHMS__ABSTRACT_ALGORITHM_HPP_ +#ifndef AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__ABSTRACT_ALGORITHM_HPP_ +#define AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__ABSTRACT_ALGORITHM_HPP_ #include #include @@ -25,7 +25,7 @@ #include -namespace freespace_planning_algorithms +namespace autoware::freespace_planning_algorithms { int discretizeAngle(const double theta, const int theta_size); @@ -187,6 +187,6 @@ class AbstractPlanningAlgorithm PlannerWaypoints waypoints_; }; -} // namespace freespace_planning_algorithms +} // namespace autoware::freespace_planning_algorithms -#endif // FREESPACE_PLANNING_ALGORITHMS__ABSTRACT_ALGORITHM_HPP_ +#endif // AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__ABSTRACT_ALGORITHM_HPP_ diff --git a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/astar_search.hpp b/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/astar_search.hpp similarity index 91% rename from planning/freespace_planning_algorithms/include/freespace_planning_algorithms/astar_search.hpp rename to planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/astar_search.hpp index 3dced3eb1d01d..99cf3fc743a82 100644 --- a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/astar_search.hpp +++ b/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/astar_search.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FREESPACE_PLANNING_ALGORITHMS__ASTAR_SEARCH_HPP_ -#define FREESPACE_PLANNING_ALGORITHMS__ASTAR_SEARCH_HPP_ +#ifndef AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__ASTAR_SEARCH_HPP_ +#define AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__ASTAR_SEARCH_HPP_ -#include "freespace_planning_algorithms/abstract_algorithm.hpp" -#include "freespace_planning_algorithms/reeds_shepp.hpp" +#include "autoware_freespace_planning_algorithms/abstract_algorithm.hpp" +#include "autoware_freespace_planning_algorithms/reeds_shepp.hpp" #include @@ -32,7 +32,7 @@ #include #include -namespace freespace_planning_algorithms +namespace autoware::freespace_planning_algorithms { enum class NodeStatus : uint8_t { None, Open, Closed }; @@ -169,6 +169,6 @@ class AstarSearch : public AbstractPlanningAlgorithm int x_scale_; int y_scale_; }; -} // namespace freespace_planning_algorithms +} // namespace autoware::freespace_planning_algorithms -#endif // FREESPACE_PLANNING_ALGORITHMS__ASTAR_SEARCH_HPP_ +#endif // AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__ASTAR_SEARCH_HPP_ diff --git a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/reeds_shepp.hpp b/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/reeds_shepp.hpp similarity index 94% rename from planning/freespace_planning_algorithms/include/freespace_planning_algorithms/reeds_shepp.hpp rename to planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/reeds_shepp.hpp index f14fef33d26da..ece30175fad86 100644 --- a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/reeds_shepp.hpp +++ b/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/reeds_shepp.hpp @@ -78,14 +78,14 @@ // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE // POSSIBILITY OF SUCH DAMAGE. -#ifndef FREESPACE_PLANNING_ALGORITHMS__REEDS_SHEPP_HPP_ -#define FREESPACE_PLANNING_ALGORITHMS__REEDS_SHEPP_HPP_ +#ifndef AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__REEDS_SHEPP_HPP_ +#define AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__REEDS_SHEPP_HPP_ #include #include #include -namespace freespace_planning_algorithms +namespace autoware::freespace_planning_algorithms { using ReedsSheppPathSamplingCallback = std::function; using ReedsSheppPathTypeCallback = std::function; @@ -137,6 +137,6 @@ class ReedsSheppStateSpace /** \brief Turning radius */ double rho_; }; -} // namespace freespace_planning_algorithms +} // namespace autoware::freespace_planning_algorithms -#endif // FREESPACE_PLANNING_ALGORITHMS__REEDS_SHEPP_HPP_ +#endif // AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__REEDS_SHEPP_HPP_ diff --git a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/rrtstar.hpp b/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/rrtstar.hpp similarity index 83% rename from planning/freespace_planning_algorithms/include/freespace_planning_algorithms/rrtstar.hpp rename to planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/rrtstar.hpp index ac21f7333df37..6a203d84a47c9 100644 --- a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/rrtstar.hpp +++ b/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/rrtstar.hpp @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FREESPACE_PLANNING_ALGORITHMS__RRTSTAR_HPP_ -#define FREESPACE_PLANNING_ALGORITHMS__RRTSTAR_HPP_ +#ifndef AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__RRTSTAR_HPP_ +#define AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__RRTSTAR_HPP_ -#include "freespace_planning_algorithms/abstract_algorithm.hpp" -#include "freespace_planning_algorithms/rrtstar_core.hpp" +#include "autoware_freespace_planning_algorithms/abstract_algorithm.hpp" +#include "autoware_freespace_planning_algorithms/rrtstar_core.hpp" #include #include -namespace freespace_planning_algorithms +namespace autoware::freespace_planning_algorithms { struct RRTStarParam { @@ -69,6 +69,6 @@ class RRTStar : public AbstractPlanningAlgorithm const VehicleShape original_vehicle_shape_; }; -} // namespace freespace_planning_algorithms +} // namespace autoware::freespace_planning_algorithms -#endif // FREESPACE_PLANNING_ALGORITHMS__RRTSTAR_HPP_ +#endif // AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__RRTSTAR_HPP_ diff --git a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/rrtstar_core.hpp b/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/rrtstar_core.hpp similarity index 90% rename from planning/freespace_planning_algorithms/include/freespace_planning_algorithms/rrtstar_core.hpp rename to planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/rrtstar_core.hpp index 257a5693e118a..633da7a86a8c6 100644 --- a/planning/freespace_planning_algorithms/include/freespace_planning_algorithms/rrtstar_core.hpp +++ b/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/rrtstar_core.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FREESPACE_PLANNING_ALGORITHMS__RRTSTAR_CORE_HPP_ -#define FREESPACE_PLANNING_ALGORITHMS__RRTSTAR_CORE_HPP_ +#ifndef AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__RRTSTAR_CORE_HPP_ +#define AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__RRTSTAR_CORE_HPP_ -#include "freespace_planning_algorithms/reeds_shepp.hpp" +#include "autoware_freespace_planning_algorithms/reeds_shepp.hpp" #include @@ -28,11 +28,11 @@ #include #include -namespace rrtstar_core +namespace autoware::freespace_planning_algorithms::rrtstar_core { -using Path = freespace_planning_algorithms::ReedsSheppStateSpace::ReedsSheppPath; -using Pose = freespace_planning_algorithms::ReedsSheppStateSpace::StateXYT; -using ReedsSheppStateSpace = freespace_planning_algorithms::ReedsSheppStateSpace; +using Path = ReedsSheppStateSpace::ReedsSheppPath; +using Pose = ReedsSheppStateSpace::StateXYT; +using ReedsSheppStateSpace = ReedsSheppStateSpace; const double inf = std::numeric_limits::infinity(); // cspell: ignore rsspace @@ -156,6 +156,6 @@ class RRTStar CSpace cspace_; }; -} // namespace rrtstar_core +} // namespace autoware::freespace_planning_algorithms::rrtstar_core -#endif // FREESPACE_PLANNING_ALGORITHMS__RRTSTAR_CORE_HPP_ +#endif // AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__RRTSTAR_CORE_HPP_ diff --git a/planning/freespace_planning_algorithms/package.xml b/planning/autoware_freespace_planning_algorithms/package.xml similarity index 90% rename from planning/freespace_planning_algorithms/package.xml rename to planning/autoware_freespace_planning_algorithms/package.xml index 9b19d8a81bb51..d2b7ddc7c620a 100644 --- a/planning/freespace_planning_algorithms/package.xml +++ b/planning/autoware_freespace_planning_algorithms/package.xml @@ -1,9 +1,9 @@ - freespace_planning_algorithms + autoware_freespace_planning_algorithms 0.1.0 - The freespace_planning_algorithms package + The autoware_freespace_planning_algorithms package Kosuke Takeuchi Takamasa Horibe Takayuki Murooka diff --git a/planning/freespace_planning_algorithms/rrtstar.md b/planning/autoware_freespace_planning_algorithms/rrtstar.md similarity index 100% rename from planning/freespace_planning_algorithms/rrtstar.md rename to planning/autoware_freespace_planning_algorithms/rrtstar.md diff --git a/planning/freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp b/planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp similarity index 95% rename from planning/freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp rename to planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp index 9d10cf311fb16..b872ee993c5e8 100644 --- a/planning/freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp +++ b/planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "freespace_planning_algorithms/abstract_algorithm.hpp" -#include "freespace_planning_algorithms/astar_search.hpp" +#include "autoware_freespace_planning_algorithms/abstract_algorithm.hpp" +#include "autoware_freespace_planning_algorithms/astar_search.hpp" #include #include @@ -24,6 +24,8 @@ #include #include +namespace autoware::freespace_planning_algorithms +{ struct PlannerWaypointsVector { std::vector> waypoints; @@ -32,7 +34,7 @@ struct PlannerWaypointsVector class AstarSearchPython : public freespace_planning_algorithms::AstarSearch { - using freespace_planning_algorithms::AstarSearch::AstarSearch; + using AstarSearch::AstarSearch; public: void setMapByte(const std::string & costmap_byte) @@ -97,7 +99,7 @@ class AstarSearchPython : public freespace_planning_algorithms::AstarSearch namespace py = pybind11; -PYBIND11_MODULE(freespace_planning_algorithms_pybind, p) +PYBIND11_MODULE(autoware_freespace_planning_algorithms_pybind, p) { auto pyPlannerWaypointsVector = py::class_(p, "PlannerWaypointsVector", py::dynamic_attr()) @@ -165,3 +167,4 @@ PYBIND11_MODULE(freespace_planning_algorithms_pybind, p) .def("makePlan", &AstarSearchPython::makePlanByte) .def("getWaypoints", &AstarSearchPython::getWaypointsAsVector); } +} // namespace autoware::freespace_planning_algorithms diff --git a/planning/freespace_planning_algorithms/scripts/example/example.py b/planning/autoware_freespace_planning_algorithms/scripts/example/example.py similarity index 97% rename from planning/freespace_planning_algorithms/scripts/example/example.py rename to planning/autoware_freespace_planning_algorithms/scripts/example/example.py index 73f53e23bc540..c0cdf8c2ec6ba 100644 --- a/planning/freespace_planning_algorithms/scripts/example/example.py +++ b/planning/autoware_freespace_planning_algorithms/scripts/example/example.py @@ -12,7 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -import freespace_planning_algorithms.astar_search as fp +import autoware_freespace_planning_algorithms.astar_search as fp from geometry_msgs.msg import Pose from nav_msgs.msg import OccupancyGrid from pyquaternion import Quaternion diff --git a/planning/freespace_planning_algorithms/src/abstract_algorithm.cpp b/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp similarity index 97% rename from planning/freespace_planning_algorithms/src/abstract_algorithm.cpp rename to planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp index 2c7340072eb53..d946ea87cff81 100644 --- a/planning/freespace_planning_algorithms/src/abstract_algorithm.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "freespace_planning_algorithms/abstract_algorithm.hpp" +#include "autoware_freespace_planning_algorithms/abstract_algorithm.hpp" #include #include #include -namespace freespace_planning_algorithms +namespace autoware::freespace_planning_algorithms { using tier4_autoware_utils::createQuaternionFromYaw; using tier4_autoware_utils::normalizeRadian; @@ -250,4 +250,4 @@ bool AbstractPlanningAlgorithm::hasObstacleOnTrajectory( return false; } -} // namespace freespace_planning_algorithms +} // namespace autoware::freespace_planning_algorithms diff --git a/planning/freespace_planning_algorithms/src/astar_search.cpp b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp similarity index 98% rename from planning/freespace_planning_algorithms/src/astar_search.cpp rename to planning/autoware_freespace_planning_algorithms/src/astar_search.cpp index 3cc3801575116..1a7b23251111c 100644 --- a/planning/freespace_planning_algorithms/src/astar_search.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "freespace_planning_algorithms/astar_search.hpp" +#include "autoware_freespace_planning_algorithms/astar_search.hpp" #include #include @@ -27,7 +27,7 @@ #include -namespace freespace_planning_algorithms +namespace autoware::freespace_planning_algorithms { double calcReedsSheppDistance( const geometry_msgs::msg::Pose & p1, const geometry_msgs::msg::Pose & p2, double radius) @@ -368,4 +368,4 @@ geometry_msgs::msg::Pose AstarSearch::node2pose(const AstarNode & node) const return pose_local; } -} // namespace freespace_planning_algorithms +} // namespace autoware::freespace_planning_algorithms diff --git a/planning/freespace_planning_algorithms/src/reeds_shepp.cpp b/planning/autoware_freespace_planning_algorithms/src/reeds_shepp.cpp similarity index 99% rename from planning/freespace_planning_algorithms/src/reeds_shepp.cpp rename to planning/autoware_freespace_planning_algorithms/src/reeds_shepp.cpp index c6e0b0002ace8..e8e846dde5681 100644 --- a/planning/freespace_planning_algorithms/src/reeds_shepp.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/reeds_shepp.cpp @@ -78,7 +78,7 @@ // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE // POSSIBILITY OF SUCH DAMAGE. -#include "freespace_planning_algorithms/reeds_shepp.hpp" +#include "autoware_freespace_planning_algorithms/reeds_shepp.hpp" #include #include @@ -87,7 +87,7 @@ namespace { // The comments, variable names, etc. use the nomenclature from the Reeds & Shepp paper. -using freespace_planning_algorithms::ReedsSheppStateSpace; +using autoware::freespace_planning_algorithms::ReedsSheppStateSpace; const double pi = M_PI; const double twopi = 2. * pi; @@ -617,7 +617,7 @@ ReedsSheppStateSpace::ReedsSheppPath reedsShepp(double x, double y, double phi) } } // namespace -namespace freespace_planning_algorithms +namespace autoware::freespace_planning_algorithms { const ReedsSheppStateSpace::ReedsSheppPathSegmentType ReedsSheppStateSpace::reedsSheppPathType[18][5] = { @@ -716,4 +716,4 @@ ReedsSheppStateSpace::StateXYT ReedsSheppStateSpace::interpolate( s_out.y = s_out.y * rho_ + s0.y; return s_out; } -} // namespace freespace_planning_algorithms +} // namespace autoware::freespace_planning_algorithms diff --git a/planning/freespace_planning_algorithms/src/rrtstar.cpp b/planning/autoware_freespace_planning_algorithms/src/rrtstar.cpp similarity index 97% rename from planning/freespace_planning_algorithms/src/rrtstar.cpp rename to planning/autoware_freespace_planning_algorithms/src/rrtstar.cpp index ae1f0c10e74a8..587771c35d4df 100644 --- a/planning/freespace_planning_algorithms/src/rrtstar.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/rrtstar.cpp @@ -12,21 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "freespace_planning_algorithms/rrtstar.hpp" +#include "autoware_freespace_planning_algorithms/rrtstar.hpp" -namespace +namespace autoware::freespace_planning_algorithms { - rrtstar_core::Pose poseMsgToPose(const geometry_msgs::msg::Pose & pose_msg) { return rrtstar_core::Pose{ pose_msg.position.x, pose_msg.position.y, tf2::getYaw(pose_msg.orientation)}; } -} // namespace - -namespace freespace_planning_algorithms -{ RRTStar::RRTStar( const PlannerCommonParam & planner_common_param, const VehicleShape & original_vehicle_shape, const RRTStarParam & rrtstar_param) @@ -167,4 +162,4 @@ void RRTStar::setRRTPath(const std::vector & waypoints) } } -} // namespace freespace_planning_algorithms +} // namespace autoware::freespace_planning_algorithms diff --git a/planning/freespace_planning_algorithms/src/rrtstar_core.cpp b/planning/autoware_freespace_planning_algorithms/src/rrtstar_core.cpp similarity index 98% rename from planning/freespace_planning_algorithms/src/rrtstar_core.cpp rename to planning/autoware_freespace_planning_algorithms/src/rrtstar_core.cpp index e638a3733adb5..8f6405bab80cf 100644 --- a/planning/freespace_planning_algorithms/src/rrtstar_core.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/rrtstar_core.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "freespace_planning_algorithms/rrtstar_core.hpp" +#include "autoware_freespace_planning_algorithms/rrtstar_core.hpp" #include @@ -26,7 +26,7 @@ // cspell: ignore rsspace // In this case, RSSpace means "Reeds Shepp state Space" -namespace rrtstar_core +namespace autoware::freespace_planning_algorithms::rrtstar_core { CSpace::CSpace( const Pose & lo, const Pose & hi, double r, std::function is_obstacle_free) @@ -459,4 +459,4 @@ void RRTStar::reconnect(const NodeSharedPtr & node_new, const NodeSharedPtr & no } } -} // namespace rrtstar_core +} // namespace autoware::freespace_planning_algorithms::rrtstar_core diff --git a/planning/freespace_planning_algorithms/test/debug_plot.py b/planning/autoware_freespace_planning_algorithms/test/debug_plot.py similarity index 100% rename from planning/freespace_planning_algorithms/test/debug_plot.py rename to planning/autoware_freespace_planning_algorithms/test/debug_plot.py diff --git a/planning/freespace_planning_algorithms/test/debug_plot_rrtstar_core.py b/planning/autoware_freespace_planning_algorithms/test/debug_plot_rrtstar_core.py similarity index 100% rename from planning/freespace_planning_algorithms/test/debug_plot_rrtstar_core.py rename to planning/autoware_freespace_planning_algorithms/test/debug_plot_rrtstar_core.py diff --git a/planning/freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp b/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp similarity index 97% rename from planning/freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp rename to planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp index c11c3df73d467..5cfb004a3b1c3 100644 --- a/planning/freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp +++ b/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "freespace_planning_algorithms/abstract_algorithm.hpp" -#include "freespace_planning_algorithms/astar_search.hpp" -#include "freespace_planning_algorithms/rrtstar.hpp" +#include "autoware_freespace_planning_algorithms/abstract_algorithm.hpp" +#include "autoware_freespace_planning_algorithms/astar_search.hpp" +#include "autoware_freespace_planning_algorithms/rrtstar.hpp" #include #include @@ -33,7 +33,7 @@ #include #include -namespace fpa = freespace_planning_algorithms; +namespace fpa = autoware::freespace_planning_algorithms; const double length_lexus = 5.5; const double width_lexus = 2.75; diff --git a/planning/freespace_planning_algorithms/test/src/test_rrtstar_core_informed.cpp b/planning/autoware_freespace_planning_algorithms/test/src/test_rrtstar_core_informed.cpp similarity index 94% rename from planning/freespace_planning_algorithms/test/src/test_rrtstar_core_informed.cpp rename to planning/autoware_freespace_planning_algorithms/test/src/test_rrtstar_core_informed.cpp index 40527e51f8436..e08afdb236192 100644 --- a/planning/freespace_planning_algorithms/test/src/test_rrtstar_core_informed.cpp +++ b/planning/autoware_freespace_planning_algorithms/test/src/test_rrtstar_core_informed.cpp @@ -12,13 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "freespace_planning_algorithms/rrtstar_core.hpp" +#include "autoware_freespace_planning_algorithms/rrtstar_core.hpp" #include #include #include +namespace autoware::freespace_planning_algorithms::rrtstar_core +{ bool checkAllNodeConnected(const rrtstar_core::RRTStar & tree) { const auto & nodes = tree.getNodes(); @@ -111,3 +113,4 @@ int main(int argc, char ** argv) testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } +} // namespace autoware::freespace_planning_algorithms::rrtstar_core diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/freespace_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/freespace_pull_over.hpp index ae1ee8c66a990..b1c4a705ae94d 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/freespace_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/freespace_pull_over.hpp @@ -17,9 +17,9 @@ #include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" -#include -#include -#include +#include +#include +#include #include @@ -28,9 +28,9 @@ namespace behavior_path_planner { -using freespace_planning_algorithms::AbstractPlanningAlgorithm; -using freespace_planning_algorithms::AstarSearch; -using freespace_planning_algorithms::RRTStar; +using autoware::freespace_planning_algorithms::AbstractPlanningAlgorithm; +using autoware::freespace_planning_algorithms::AstarSearch; +using autoware::freespace_planning_algorithms::RRTStar; class FreespacePullOver : public PullOverPlannerBase { diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp index b7c4a24e52974..f41de932bb006 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -28,9 +28,9 @@ #include "behavior_path_goal_planner_module/goal_searcher.hpp" #include "behavior_path_goal_planner_module/shift_pull_over.hpp" +#include +#include #include -#include -#include #include #include @@ -57,12 +57,12 @@ using nav_msgs::msg::OccupancyGrid; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; -using freespace_planning_algorithms::AbstractPlanningAlgorithm; -using freespace_planning_algorithms::AstarParam; -using freespace_planning_algorithms::AstarSearch; -using freespace_planning_algorithms::PlannerCommonParam; -using freespace_planning_algorithms::RRTStar; -using freespace_planning_algorithms::RRTStarParam; +using autoware::freespace_planning_algorithms::AbstractPlanningAlgorithm; +using autoware::freespace_planning_algorithms::AstarParam; +using autoware::freespace_planning_algorithms::AstarSearch; +using autoware::freespace_planning_algorithms::PlannerCommonParam; +using autoware::freespace_planning_algorithms::RRTStar; +using autoware::freespace_planning_algorithms::RRTStarParam; using behavior_path_planner::utils::path_safety_checker::EgoPredictedPathParams; using behavior_path_planner::utils::path_safety_checker::ObjectsFilteringParams; diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_parameters.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_parameters.hpp index e5b284d03d9c4..dc992b7ed4967 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_parameters.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_parameters.hpp @@ -19,9 +19,9 @@ #include "autoware_behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include "autoware_behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" -#include -#include -#include +#include +#include +#include #include #include @@ -29,9 +29,9 @@ namespace behavior_path_planner { -using freespace_planning_algorithms::AstarParam; -using freespace_planning_algorithms::PlannerCommonParam; -using freespace_planning_algorithms::RRTStarParam; +using autoware::freespace_planning_algorithms::AstarParam; +using autoware::freespace_planning_algorithms::PlannerCommonParam; +using autoware::freespace_planning_algorithms::RRTStarParam; enum class ParkingPolicy { LEFT_SIDE = 0, diff --git a/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp index c17d7d38709e5..360707003f7ca 100644 --- a/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp @@ -32,7 +32,7 @@ FreespacePullOver::FreespacePullOver( velocity_{parameters.freespace_parking_velocity}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { - freespace_planning_algorithms::VehicleShape vehicle_shape( + autoware::freespace_planning_algorithms::VehicleShape vehicle_shape( vehicle_info, parameters.vehicle_shape_margin); if (parameters.freespace_parking_algorithm == "astar") { use_back_ = parameters.astar_parameters.use_back; diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index f51fa99578d7b..1ce6e65bee219 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -38,6 +38,7 @@ autoware_adapi_v1_msgs autoware_behavior_path_planner_common + autoware_freespace_planning_algorithms autoware_frenet_planner autoware_lane_departure_checker autoware_path_sampler @@ -46,7 +47,6 @@ autoware_planning_test_manager autoware_vehicle_msgs behaviortree_cpp_v3 - freespace_planning_algorithms geometry_msgs interpolation lanelet2_extension diff --git a/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp b/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp index 25f3bca215063..fbaef46c43511 100644 --- a/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp +++ b/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp @@ -33,8 +33,8 @@ #include "tier4_autoware_utils/ros/logger_level_configure.hpp" -#include -#include +#include +#include #include #include @@ -65,15 +65,15 @@ namespace freespace_planner { +using autoware::freespace_planning_algorithms::AbstractPlanningAlgorithm; +using autoware::freespace_planning_algorithms::AstarParam; +using autoware::freespace_planning_algorithms::AstarSearch; +using autoware::freespace_planning_algorithms::PlannerCommonParam; +using autoware::freespace_planning_algorithms::RRTStar; +using autoware::freespace_planning_algorithms::RRTStarParam; +using autoware::freespace_planning_algorithms::VehicleShape; using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::Trajectory; -using freespace_planning_algorithms::AbstractPlanningAlgorithm; -using freespace_planning_algorithms::AstarParam; -using freespace_planning_algorithms::AstarSearch; -using freespace_planning_algorithms::PlannerCommonParam; -using freespace_planning_algorithms::RRTStar; -using freespace_planning_algorithms::RRTStarParam; -using freespace_planning_algorithms::VehicleShape; using geometry_msgs::msg::PoseArray; using geometry_msgs::msg::PoseStamped; using geometry_msgs::msg::TransformStamped; diff --git a/planning/freespace_planner/package.xml b/planning/freespace_planner/package.xml index 8445bd2355b25..a29202060a640 100644 --- a/planning/freespace_planner/package.xml +++ b/planning/freespace_planner/package.xml @@ -15,9 +15,9 @@ ament_cmake_auto autoware_cmake + autoware_freespace_planning_algorithms autoware_planning_msgs autoware_planning_test_manager - freespace_planning_algorithms geometry_msgs motion_utils nav_msgs diff --git a/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp b/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp index b0d9e9cf3edcd..322bf2697a1f6 100644 --- a/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp +++ b/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp @@ -30,7 +30,7 @@ #include "freespace_planner/freespace_planner_node.hpp" -#include "freespace_planning_algorithms/abstract_algorithm.hpp" +#include "autoware_freespace_planning_algorithms/abstract_algorithm.hpp" #include #include @@ -47,10 +47,10 @@ namespace using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; using TrajectoryPoints = std::vector; -using freespace_planning_algorithms::AstarSearch; -using freespace_planning_algorithms::PlannerWaypoint; -using freespace_planning_algorithms::PlannerWaypoints; -using freespace_planning_algorithms::RRTStar; +using autoware::freespace_planning_algorithms::AstarSearch; +using autoware::freespace_planning_algorithms::PlannerWaypoint; +using autoware::freespace_planning_algorithms::PlannerWaypoints; +using autoware::freespace_planning_algorithms::RRTStar; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseArray; using geometry_msgs::msg::PoseStamped; @@ -562,7 +562,7 @@ TransformStamped FreespacePlannerNode::getTransform( void FreespacePlannerNode::initializePlanningAlgorithm() { // Extend robot shape - freespace_planning_algorithms::VehicleShape extended_vehicle_shape = vehicle_shape_; + autoware::freespace_planning_algorithms::VehicleShape extended_vehicle_shape = vehicle_shape_; const double margin = node_param_.vehicle_shape_margin_m; extended_vehicle_shape.length += margin; extended_vehicle_shape.width += margin; From 1580aba31e2cfb6464c9a37b2befd1775c81936b Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 10 Jun 2024 11:35:21 +0900 Subject: [PATCH 49/65] fix(motion_planning.launch): fix input traj of obstacle_velocity_limiter (#7386) Signed-off-by: Maxime CLEMENT --- .../lane_driving/motion_planning/motion_planning.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 196e7b2c7262c..eba79b905db16 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -146,7 +146,7 @@ - + From 895b07bfbed44b05927d9a48240c116d925f6f4a Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 10 Jun 2024 11:57:55 +0900 Subject: [PATCH 50/65] feat(motion_velocity_planner): use polling subscriber to efficiently get messages (#7223) * feat(motion_velocity_planner): use polling subscriber for odometry topic Signed-off-by: Maxime CLEMENT * use polling subscribers for more topics Signed-off-by: Maxime CLEMENT * remove blocking mutex lock when processing traffic lights Signed-off-by: Maxime CLEMENT * fix assign after return Signed-off-by: Maxime CLEMENT --------- Signed-off-by: Maxime CLEMENT --- .../src/filter_predicted_objects.cpp | 4 +- .../src/out_of_lane_module.cpp | 4 +- .../planner_data.hpp | 16 +- .../src/node.cpp | 147 ++++++------------ .../src/node.hpp | 46 +++--- 5 files changed, 85 insertions(+), 132 deletions(-) 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 ce993dc1cedb0..77292a41b9cf1 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 @@ -103,8 +103,8 @@ autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( const PlannerParam & params) { autoware_perception_msgs::msg::PredictedObjects filtered_objects; - filtered_objects.header = planner_data->predicted_objects->header; - for (const auto & object : planner_data->predicted_objects->objects) { + filtered_objects.header = planner_data->predicted_objects.header; + for (const auto & object : planner_data->predicted_objects.objects) { const auto is_pedestrian = std::find_if(object.classification.begin(), object.classification.end(), [](const auto & c) { return c.label == autoware_perception_msgs::msg::ObjectClassification::PEDESTRIAN; 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 2cd050d15dd9b..0fe7b783adf31 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 @@ -154,11 +154,11 @@ VelocityPlanningResult OutOfLaneModule::plan( tier4_autoware_utils::StopWatch stopwatch; stopwatch.tic(); out_of_lane::EgoData ego_data; - ego_data.pose = planner_data->current_odometry->pose; + ego_data.pose = planner_data->current_odometry.pose.pose; ego_data.trajectory_points = ego_trajectory_points; ego_data.first_trajectory_idx = motion_utils::findNearestSegmentIndex(ego_trajectory_points, ego_data.pose.position); - ego_data.velocity = planner_data->current_velocity->twist.linear.x; + 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"); const auto current_ego_footprint = diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp index 87aa4ac483feb..73d71e0d0f955 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp @@ -24,9 +24,8 @@ #include #include #include -#include -#include #include +#include #include #include #include @@ -60,12 +59,11 @@ struct PlannerData } // msgs from callbacks that are used for data-ready - geometry_msgs::msg::PoseStamped::ConstSharedPtr current_odometry; - geometry_msgs::msg::TwistStamped::ConstSharedPtr current_velocity; - geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr current_acceleration; - autoware_perception_msgs::msg::PredictedObjects::ConstSharedPtr predicted_objects; - pcl::PointCloud::ConstPtr no_ground_pointcloud; - nav_msgs::msg::OccupancyGrid::ConstSharedPtr occupancy_grid; + nav_msgs::msg::Odometry current_odometry{}; + geometry_msgs::msg::AccelWithCovarianceStamped current_acceleration{}; + autoware_perception_msgs::msg::PredictedObjects predicted_objects{}; + pcl::PointCloud no_ground_pointcloud{}; + nav_msgs::msg::OccupancyGrid occupancy_grid{}; std::shared_ptr route_handler; // nearest search @@ -78,7 +76,7 @@ struct PlannerData std::map traffic_light_id_map_raw_; std::map traffic_light_id_map_last_observed_; std::optional external_velocity_limit; - tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr virtual_traffic_light_states; + tier4_v2x_msgs::msg::VirtualTrafficLightStateArray virtual_traffic_light_states; // velocity smoother std::shared_ptr velocity_smoother_{}; 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 262c32fe1ea47..c53de15d67ebb 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 @@ -63,38 +63,10 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions & sub_trajectory_ = this->create_subscription( "~/input/trajectory", 1, std::bind(&MotionVelocityPlannerNode::on_trajectory, this, _1), create_subscription_options(this)); - sub_predicted_objects_ = - this->create_subscription( - "~/input/dynamic_objects", 1, - std::bind(&MotionVelocityPlannerNode::on_predicted_objects, this, _1), - create_subscription_options(this)); - sub_no_ground_pointcloud_ = this->create_subscription( - "~/input/no_ground_pointcloud", rclcpp::SensorDataQoS(), - std::bind(&MotionVelocityPlannerNode::on_no_ground_pointcloud, this, _1), - create_subscription_options(this)); - sub_vehicle_odometry_ = this->create_subscription( - "~/input/vehicle_odometry", 1, std::bind(&MotionVelocityPlannerNode::on_odometry, this, _1), - create_subscription_options(this)); - sub_acceleration_ = this->create_subscription( - "~/input/accel", 1, std::bind(&MotionVelocityPlannerNode::on_acceleration, this, _1), - create_subscription_options(this)); sub_lanelet_map_ = this->create_subscription( "~/input/vector_map", rclcpp::QoS(10).transient_local(), std::bind(&MotionVelocityPlannerNode::on_lanelet_map, this, _1), create_subscription_options(this)); - sub_traffic_signals_ = - this->create_subscription( - "~/input/traffic_signals", 1, - std::bind(&MotionVelocityPlannerNode::on_traffic_signals, this, _1), - create_subscription_options(this)); - sub_virtual_traffic_light_states_ = - this->create_subscription( - "~/input/virtual_traffic_light_states", 1, - std::bind(&MotionVelocityPlannerNode::on_virtual_traffic_light_states, this, _1), - create_subscription_options(this)); - sub_occupancy_grid_ = this->create_subscription( - "~/input/occupancy_grid", 1, std::bind(&MotionVelocityPlannerNode::on_occupancy_grid, this, _1), - create_subscription_options(this)); srv_load_plugin_ = create_service( "~/service/load_plugin", std::bind(&MotionVelocityPlannerNode::on_load_plugin, this, _1, _2)); @@ -151,45 +123,59 @@ void MotionVelocityPlannerNode::on_unload_plugin( } // NOTE: argument planner_data must not be referenced for multithreading -bool MotionVelocityPlannerNode::is_data_ready() const +bool MotionVelocityPlannerNode::update_planner_data() { - const auto & d = planner_data_; auto clock = *get_clock(); - const auto check_with_msg = [&](const auto ptr, const auto & msg) { + auto is_ready = true; + const auto check_with_log = [&](const auto ptr, const auto & log) { constexpr auto throttle_duration = 3000; // [ms] if (!ptr) { - RCLCPP_INFO_THROTTLE(get_logger(), clock, throttle_duration, msg); + RCLCPP_INFO_THROTTLE(get_logger(), clock, throttle_duration, log); + is_ready = false; return false; } return true; }; - return check_with_msg(d.current_odometry, "Waiting for current odometry") && - check_with_msg(d.current_velocity, "Waiting for current velocity") && - check_with_msg(d.current_acceleration, "Waiting for current acceleration") && - check_with_msg(d.predicted_objects, "Waiting for predicted objects") && - check_with_msg(d.no_ground_pointcloud, "Waiting for pointcloud") && - check_with_msg(map_ptr_, "Waiting for the map") && - check_with_msg( - d.velocity_smoother_, "Waiting for the initialization of the velocity smoother") && - check_with_msg(d.occupancy_grid, "Waiting for the occupancy grid"); -} + const auto ego_state_ptr = sub_vehicle_odometry_.takeData(); + if (check_with_log(ego_state_ptr, "Waiting for current odometry")) + planner_data_.current_odometry = *ego_state_ptr; -void MotionVelocityPlannerNode::on_occupancy_grid( - const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg) -{ - std::lock_guard lock(mutex_); - planner_data_.occupancy_grid = msg; -} + const auto ego_accel_ptr = sub_acceleration_.takeData(); + if (check_with_log(ego_accel_ptr, "Waiting for current acceleration")) + planner_data_.current_acceleration = *ego_accel_ptr; -void MotionVelocityPlannerNode::on_predicted_objects( - const autoware_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg) -{ - std::lock_guard lock(mutex_); - planner_data_.predicted_objects = msg; + const auto predicted_objects_ptr = sub_predicted_objects_.takeData(); + if (check_with_log(predicted_objects_ptr, "Waiting for predicted objects")) + planner_data_.predicted_objects = *predicted_objects_ptr; + + const auto no_ground_pointcloud_ptr = sub_no_ground_pointcloud_.takeData(); + if (check_with_log(no_ground_pointcloud_ptr, "Waiting for pointcloud")) { + const auto no_ground_pointcloud = process_no_ground_pointcloud(no_ground_pointcloud_ptr); + if (no_ground_pointcloud) planner_data_.no_ground_pointcloud = *no_ground_pointcloud; + } + + const auto occupancy_grid_ptr = sub_occupancy_grid_.takeData(); + if (check_with_log(occupancy_grid_ptr, "Waiting for the occupancy grid")) + planner_data_.occupancy_grid = *occupancy_grid_ptr; + + // here we use bitwise operator to not short-circuit the logging messages + is_ready &= check_with_log(map_ptr_, "Waiting for the map"); + is_ready &= check_with_log( + planner_data_.velocity_smoother_, "Waiting for the initialization of the velocity smoother"); + + // optional data + const auto traffic_signals_ptr = sub_traffic_signals_.takeData(); + if (traffic_signals_ptr) process_traffic_signals(traffic_signals_ptr); + const auto virtual_traffic_light_states_ptr = sub_virtual_traffic_light_states_.takeData(); + if (virtual_traffic_light_states_ptr) + planner_data_.virtual_traffic_light_states = *virtual_traffic_light_states_ptr; + + return is_ready; } -void MotionVelocityPlannerNode::on_no_ground_pointcloud( +std::optional> +MotionVelocityPlannerNode::process_no_ground_pointcloud( const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg) { geometry_msgs::msg::TransformStamped transform; @@ -198,7 +184,7 @@ void MotionVelocityPlannerNode::on_no_ground_pointcloud( "map", msg->header.frame_id, msg->header.stamp, rclcpp::Duration::from_seconds(0.1)); } catch (tf2::TransformException & e) { RCLCPP_WARN(get_logger(), "no transform found for no_ground_pointcloud: %s", e.what()); - return; + return {}; } pcl::PointCloud pc; @@ -206,36 +192,8 @@ void MotionVelocityPlannerNode::on_no_ground_pointcloud( Eigen::Affine3f affine = tf2::transformToEigen(transform.transform).cast(); pcl::PointCloud::Ptr pc_transformed(new pcl::PointCloud); - if (!pc.empty()) { - tier4_autoware_utils::transformPointCloud(pc, *pc_transformed, affine); - } - - { - std::lock_guard lock(mutex_); - planner_data_.no_ground_pointcloud = pc_transformed; - } -} - -void MotionVelocityPlannerNode::on_odometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg) -{ - std::lock_guard lock(mutex_); - - auto current_odometry = std::make_shared(); - current_odometry->header = msg->header; - current_odometry->pose = msg->pose.pose; - planner_data_.current_odometry = current_odometry; - - auto current_velocity = std::make_shared(); - current_velocity->header = msg->header; - current_velocity->twist = msg->twist.twist; - planner_data_.current_velocity = current_velocity; -} - -void MotionVelocityPlannerNode::on_acceleration( - const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg) -{ - std::lock_guard lock(mutex_); - planner_data_.current_acceleration = msg; + if (!pc.empty()) tier4_autoware_utils::transformPointCloud(pc, *pc_transformed, affine); + return *pc_transformed; } void MotionVelocityPlannerNode::set_velocity_smoother_params() @@ -253,11 +211,9 @@ void MotionVelocityPlannerNode::on_lanelet_map( has_received_map_ = true; } -void MotionVelocityPlannerNode::on_traffic_signals( +void MotionVelocityPlannerNode::process_traffic_signals( const autoware_perception_msgs::msg::TrafficLightGroupArray::ConstSharedPtr msg) { - std::lock_guard lock(mutex_); - // clear previous observation planner_data_.traffic_light_id_map_raw_.clear(); const auto traffic_light_id_map_last_observed_old = @@ -290,19 +246,12 @@ void MotionVelocityPlannerNode::on_traffic_signals( } } -void MotionVelocityPlannerNode::on_virtual_traffic_light_states( - const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg) -{ - std::lock_guard lock(mutex_); - planner_data_.virtual_traffic_light_states = msg; -} - void MotionVelocityPlannerNode::on_trajectory( const autoware_planning_msgs::msg::Trajectory::ConstSharedPtr input_trajectory_msg) { std::unique_lock lk(mutex_); - if (!is_data_ready()) { + if (!update_planner_data()) { return; } @@ -367,9 +316,9 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s const autoware::motion_velocity_planner::TrajectoryPoints & trajectory_points, const autoware::motion_velocity_planner::PlannerData & planner_data) const { - const geometry_msgs::msg::Pose current_pose = planner_data.current_odometry->pose; - const double v0 = planner_data.current_velocity->twist.linear.x; - const double a0 = planner_data.current_acceleration->accel.accel.linear.x; + const geometry_msgs::msg::Pose current_pose = planner_data.current_odometry.pose.pose; + const double v0 = planner_data.current_odometry.twist.twist.linear.x; + const double a0 = planner_data.current_acceleration.accel.accel.linear.x; const auto & external_v_limit = planner_data.external_velocity_limit; const auto & smoother = planner_data.velocity_smoother_; 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 4b943dcbb67f2..799f80db25ad2 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 @@ -22,10 +22,12 @@ #include #include #include +#include #include #include #include +#include #include #include #include @@ -60,31 +62,33 @@ class MotionVelocityPlannerNode : public rclcpp::Node // subscriber rclcpp::Subscription::SharedPtr sub_trajectory_; - rclcpp::Subscription::SharedPtr - sub_predicted_objects_; - rclcpp::Subscription::SharedPtr sub_no_ground_pointcloud_; - rclcpp::Subscription::SharedPtr sub_vehicle_odometry_; - rclcpp::Subscription::SharedPtr sub_acceleration_; + tier4_autoware_utils::InterProcessPollingSubscriber< + autoware_perception_msgs::msg::PredictedObjects> + sub_predicted_objects_{this, "~/input/dynamic_objects"}; + tier4_autoware_utils::InterProcessPollingSubscriber + sub_no_ground_pointcloud_{this, "~/input/no_ground_pointcloud"}; + tier4_autoware_utils::InterProcessPollingSubscriber + sub_vehicle_odometry_{this, "~/input/vehicle_odometry"}; + tier4_autoware_utils::InterProcessPollingSubscriber< + geometry_msgs::msg::AccelWithCovarianceStamped> + sub_acceleration_{this, "~/input/accel"}; + tier4_autoware_utils::InterProcessPollingSubscriber + sub_occupancy_grid_{this, "~/input/occupancy_grid"}; + tier4_autoware_utils::InterProcessPollingSubscriber< + autoware_perception_msgs::msg::TrafficLightGroupArray> + sub_traffic_signals_{this, "~/input/traffic_signals"}; + tier4_autoware_utils::InterProcessPollingSubscriber< + tier4_v2x_msgs::msg::VirtualTrafficLightStateArray> + sub_virtual_traffic_light_states_{this, "~/input/virtual_traffic_light_states"}; rclcpp::Subscription::SharedPtr sub_lanelet_map_; - rclcpp::Subscription::SharedPtr - sub_traffic_signals_; - rclcpp::Subscription::SharedPtr - sub_virtual_traffic_light_states_; - rclcpp::Subscription::SharedPtr sub_occupancy_grid_; void on_trajectory( const autoware_planning_msgs::msg::Trajectory::ConstSharedPtr input_trajectory_msg); - void on_predicted_objects( - const autoware_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg); - void on_no_ground_pointcloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg); - void on_odometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg); - void on_acceleration(const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg); + std::optional> process_no_ground_pointcloud( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg); void on_lanelet_map(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg); - void on_traffic_signals( + void process_traffic_signals( const autoware_perception_msgs::msg::TrafficLightGroupArray::ConstSharedPtr msg); - void on_virtual_traffic_light_states( - const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg); - void on_occupancy_grid(const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg); // publishers rclcpp::Publisher::SharedPtr trajectory_pub_; @@ -118,7 +122,9 @@ class MotionVelocityPlannerNode : public rclcpp::Node std::mutex mutex_; // function - bool is_data_ready() const; + /// @brief update the PlannerData instance with the latest messages received + /// @return false if some data is not available + bool update_planner_data(); void insert_stop( autoware_planning_msgs::msg::Trajectory & trajectory, const geometry_msgs::msg::Point & stop_point) const; From fdea913f291dc58c487bc07e669373db524684f0 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 10 Jun 2024 12:47:21 +0900 Subject: [PATCH 51/65] refactor(occlusion_spot): add autoware prefix (#7357) Signed-off-by: Maxime CLEMENT --- .../CMakeLists.txt | 2 +- .../README.md | 0 .../config/occlusion_spot.param.yaml | 0 .../docs/behavior_after_safe_margin.drawio.svg | 0 .../docs/collision_free.drawio.svg | 0 .../docs/da.drawio.svg | 0 .../docs/maximum_slowdown_velocity.drawio.svg | 0 .../docs/object_info_partition.drawio.svg | 0 .../docs/occlusion_spot.drawio.svg | 0 .../docs/occlusion_spot.svg | 0 .../docs/raycast_shadow.drawio.svg | 0 .../docs/safe_motion.drawio.svg | 0 .../docs/velocity_planning.drawio.svg | 0 .../package.xml | 4 ++-- .../plugins.xml | 3 +++ .../src/debug.cpp | 0 .../src/grid_utils.cpp | 4 ++-- .../src/grid_utils.hpp | 4 ++++ .../src/manager.cpp | 0 .../src/manager.hpp | 0 .../src/occlusion_spot_utils.cpp | 0 .../src/occlusion_spot_utils.hpp | 0 .../src/risk_predictive_braking.cpp | 0 .../src/risk_predictive_braking.hpp | 0 .../src/scene_occlusion_spot.cpp | 0 .../src/scene_occlusion_spot.hpp | 0 .../test/src/test_grid_utils.cpp | 0 .../test/src/test_occlusion_spot_utils.cpp | 0 .../test/src/test_risk_predictive_braking.cpp | 0 .../test/src/utils.hpp | 0 30 files changed, 12 insertions(+), 5 deletions(-) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/CMakeLists.txt (93%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/README.md (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/config/occlusion_spot.param.yaml (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/docs/behavior_after_safe_margin.drawio.svg (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/docs/collision_free.drawio.svg (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/docs/da.drawio.svg (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/docs/maximum_slowdown_velocity.drawio.svg (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/docs/object_info_partition.drawio.svg (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/docs/occlusion_spot.drawio.svg (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/docs/occlusion_spot.svg (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/docs/raycast_shadow.drawio.svg (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/docs/safe_motion.drawio.svg (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/docs/velocity_planning.drawio.svg (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/package.xml (90%) create mode 100644 planning/autoware_behavior_velocity_occlusion_spot_module/plugins.xml rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/src/debug.cpp (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/src/grid_utils.cpp (99%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/src/grid_utils.hpp (97%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/src/manager.cpp (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/src/manager.hpp (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/src/occlusion_spot_utils.cpp (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/src/occlusion_spot_utils.hpp (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/src/risk_predictive_braking.cpp (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/src/risk_predictive_braking.hpp (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/src/scene_occlusion_spot.cpp (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/src/scene_occlusion_spot.hpp (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/test/src/test_grid_utils.cpp (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/test/src/test_occlusion_spot_utils.cpp (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/test/src/test_risk_predictive_braking.cpp (100%) rename planning/{behavior_velocity_occlusion_spot_module => autoware_behavior_velocity_occlusion_spot_module}/test/src/utils.hpp (100%) diff --git a/planning/behavior_velocity_occlusion_spot_module/CMakeLists.txt b/planning/autoware_behavior_velocity_occlusion_spot_module/CMakeLists.txt similarity index 93% rename from planning/behavior_velocity_occlusion_spot_module/CMakeLists.txt rename to planning/autoware_behavior_velocity_occlusion_spot_module/CMakeLists.txt index 8b327291a60f1..4e53e7bd1790b 100644 --- a/planning/behavior_velocity_occlusion_spot_module/CMakeLists.txt +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(behavior_velocity_occlusion_spot_module) +project(autoware_behavior_velocity_occlusion_spot_module) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/planning/behavior_velocity_occlusion_spot_module/README.md b/planning/autoware_behavior_velocity_occlusion_spot_module/README.md similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/README.md rename to planning/autoware_behavior_velocity_occlusion_spot_module/README.md diff --git a/planning/behavior_velocity_occlusion_spot_module/config/occlusion_spot.param.yaml b/planning/autoware_behavior_velocity_occlusion_spot_module/config/occlusion_spot.param.yaml similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/config/occlusion_spot.param.yaml rename to planning/autoware_behavior_velocity_occlusion_spot_module/config/occlusion_spot.param.yaml diff --git a/planning/behavior_velocity_occlusion_spot_module/docs/behavior_after_safe_margin.drawio.svg b/planning/autoware_behavior_velocity_occlusion_spot_module/docs/behavior_after_safe_margin.drawio.svg similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/docs/behavior_after_safe_margin.drawio.svg rename to planning/autoware_behavior_velocity_occlusion_spot_module/docs/behavior_after_safe_margin.drawio.svg diff --git a/planning/behavior_velocity_occlusion_spot_module/docs/collision_free.drawio.svg b/planning/autoware_behavior_velocity_occlusion_spot_module/docs/collision_free.drawio.svg similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/docs/collision_free.drawio.svg rename to planning/autoware_behavior_velocity_occlusion_spot_module/docs/collision_free.drawio.svg diff --git a/planning/behavior_velocity_occlusion_spot_module/docs/da.drawio.svg b/planning/autoware_behavior_velocity_occlusion_spot_module/docs/da.drawio.svg similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/docs/da.drawio.svg rename to planning/autoware_behavior_velocity_occlusion_spot_module/docs/da.drawio.svg diff --git a/planning/behavior_velocity_occlusion_spot_module/docs/maximum_slowdown_velocity.drawio.svg b/planning/autoware_behavior_velocity_occlusion_spot_module/docs/maximum_slowdown_velocity.drawio.svg similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/docs/maximum_slowdown_velocity.drawio.svg rename to planning/autoware_behavior_velocity_occlusion_spot_module/docs/maximum_slowdown_velocity.drawio.svg diff --git a/planning/behavior_velocity_occlusion_spot_module/docs/object_info_partition.drawio.svg b/planning/autoware_behavior_velocity_occlusion_spot_module/docs/object_info_partition.drawio.svg similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/docs/object_info_partition.drawio.svg rename to planning/autoware_behavior_velocity_occlusion_spot_module/docs/object_info_partition.drawio.svg diff --git a/planning/behavior_velocity_occlusion_spot_module/docs/occlusion_spot.drawio.svg b/planning/autoware_behavior_velocity_occlusion_spot_module/docs/occlusion_spot.drawio.svg similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/docs/occlusion_spot.drawio.svg rename to planning/autoware_behavior_velocity_occlusion_spot_module/docs/occlusion_spot.drawio.svg diff --git a/planning/behavior_velocity_occlusion_spot_module/docs/occlusion_spot.svg b/planning/autoware_behavior_velocity_occlusion_spot_module/docs/occlusion_spot.svg similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/docs/occlusion_spot.svg rename to planning/autoware_behavior_velocity_occlusion_spot_module/docs/occlusion_spot.svg diff --git a/planning/behavior_velocity_occlusion_spot_module/docs/raycast_shadow.drawio.svg b/planning/autoware_behavior_velocity_occlusion_spot_module/docs/raycast_shadow.drawio.svg similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/docs/raycast_shadow.drawio.svg rename to planning/autoware_behavior_velocity_occlusion_spot_module/docs/raycast_shadow.drawio.svg diff --git a/planning/behavior_velocity_occlusion_spot_module/docs/safe_motion.drawio.svg b/planning/autoware_behavior_velocity_occlusion_spot_module/docs/safe_motion.drawio.svg similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/docs/safe_motion.drawio.svg rename to planning/autoware_behavior_velocity_occlusion_spot_module/docs/safe_motion.drawio.svg diff --git a/planning/behavior_velocity_occlusion_spot_module/docs/velocity_planning.drawio.svg b/planning/autoware_behavior_velocity_occlusion_spot_module/docs/velocity_planning.drawio.svg similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/docs/velocity_planning.drawio.svg rename to planning/autoware_behavior_velocity_occlusion_spot_module/docs/velocity_planning.drawio.svg diff --git a/planning/behavior_velocity_occlusion_spot_module/package.xml b/planning/autoware_behavior_velocity_occlusion_spot_module/package.xml similarity index 90% rename from planning/behavior_velocity_occlusion_spot_module/package.xml rename to planning/autoware_behavior_velocity_occlusion_spot_module/package.xml index ceddd48b045a0..2f56bce7155b5 100644 --- a/planning/behavior_velocity_occlusion_spot_module/package.xml +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/package.xml @@ -1,9 +1,9 @@ - behavior_velocity_occlusion_spot_module + autoware_behavior_velocity_occlusion_spot_module 0.1.0 - The behavior_velocity_occlusion_spot_module package + The autoware_behavior_velocity_occlusion_spot_module package Taiki Tanaka Tomoya Kimura diff --git a/planning/autoware_behavior_velocity_occlusion_spot_module/plugins.xml b/planning/autoware_behavior_velocity_occlusion_spot_module/plugins.xml new file mode 100644 index 0000000000000..53a2c460c2e44 --- /dev/null +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/debug.cpp similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/src/debug.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/debug.cpp diff --git a/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.cpp similarity index 99% rename from planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.cpp index 427a6f27be3c4..6ab88baf77b20 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.cpp @@ -39,7 +39,7 @@ Polygon2d pointsToPoly(const Point2d p0, const Point2d p1, const double radius) // std::cout << boost::geometry::wkt(line_poly) << std::endl; // std::cout << boost::geometry::wkt(line) << std::endl; - bg::correct(line_poly); + boost::geometry::correct(line_poly); return line_poly; } @@ -142,7 +142,7 @@ Polygon2d generateOccupancyPolygon(const nav_msgs::msg::MapMetaData & info, cons poly.outer().emplace_back(to_bg2d(calcOffsetPose(info.origin, r, r, 0).position)); poly.outer().emplace_back(to_bg2d(calcOffsetPose(info.origin, 0, r, 0).position)); - bg::correct(poly); + boost::geometry::correct(poly); return poly; } diff --git a/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.hpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.hpp similarity index 97% rename from planning/behavior_velocity_occlusion_spot_module/src/grid_utils.hpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.hpp index 5c8d77fc831df..8dc59d07173dc 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.hpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.hpp @@ -61,6 +61,10 @@ using geometry_msgs::msg::Point; using geometry_msgs::msg::TransformStamped; using nav_msgs::msg::MapMetaData; using nav_msgs::msg::OccupancyGrid; +using tier4_autoware_utils::LineString2d; +using tier4_autoware_utils::Point2d; +using tier4_autoware_utils::Polygon2d; + namespace occlusion_cost_value { static constexpr unsigned char FREE_SPACE = 0; diff --git a/planning/behavior_velocity_occlusion_spot_module/src/manager.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/src/manager.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp diff --git a/planning/behavior_velocity_occlusion_spot_module/src/manager.hpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.hpp similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/src/manager.hpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.hpp diff --git a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp diff --git a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp diff --git a/planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.cpp similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.cpp diff --git a/planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.hpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.hpp similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.hpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/risk_predictive_braking.hpp diff --git a/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp diff --git a/planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp diff --git a/planning/behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp diff --git a/planning/behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp diff --git a/planning/behavior_velocity_occlusion_spot_module/test/src/test_risk_predictive_braking.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/test/src/test_risk_predictive_braking.cpp similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/test/src/test_risk_predictive_braking.cpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/test/src/test_risk_predictive_braking.cpp diff --git a/planning/behavior_velocity_occlusion_spot_module/test/src/utils.hpp b/planning/autoware_behavior_velocity_occlusion_spot_module/test/src/utils.hpp similarity index 100% rename from planning/behavior_velocity_occlusion_spot_module/test/src/utils.hpp rename to planning/autoware_behavior_velocity_occlusion_spot_module/test/src/utils.hpp From 251dfb55aae5de7da1dd15c8eb3d5483aa2cc432 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Mon, 10 Jun 2024 13:17:01 +0900 Subject: [PATCH 52/65] refactor(scenario_selector): prefix package and namespace with autoware_ (#7379) Signed-off-by: Y.Hisaki --- .github/CODEOWNERS | 2 +- .../scenario_planning.launch.xml | 2 +- launch/tier4_planning_launch/package.xml | 2 +- planning/.pages | 2 +- .../CMakeLists.txt | 15 +++++++-------- .../README.md | 8 ++++---- .../config/scenario_selector.param.yaml | 0 .../include/autoware_scenario_selector/node.hpp} | 10 ++++++---- ...ummy_scenario_selector_lane_driving.launch.xml | 0 .../dummy_scenario_selector_parking.launch.xml | 0 .../launch/scenario_selector.launch.xml | 4 ++-- .../package.xml | 4 ++-- .../schema/scenario_selector.schema.json | 4 ++-- .../src/node.cpp} | 8 +++++--- ...autoware_scenario_selector_node_interface.cpp} | 6 ++++-- 15 files changed, 36 insertions(+), 31 deletions(-) rename planning/{scenario_selector => autoware_scenario_selector}/CMakeLists.txt (54%) rename planning/{scenario_selector => autoware_scenario_selector}/README.md (91%) rename planning/{scenario_selector => autoware_scenario_selector}/config/scenario_selector.param.yaml (100%) rename planning/{scenario_selector/include/scenario_selector/scenario_selector_node.hpp => autoware_scenario_selector/include/autoware_scenario_selector/node.hpp} (94%) rename planning/{scenario_selector => autoware_scenario_selector}/launch/dummy_scenario_selector_lane_driving.launch.xml (100%) rename planning/{scenario_selector => autoware_scenario_selector}/launch/dummy_scenario_selector_parking.launch.xml (100%) rename planning/{scenario_selector => autoware_scenario_selector}/launch/scenario_selector.launch.xml (80%) rename planning/{scenario_selector => autoware_scenario_selector}/package.xml (93%) rename planning/{scenario_selector => autoware_scenario_selector}/schema/scenario_selector.schema.json (94%) rename planning/{scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp => autoware_scenario_selector/src/node.cpp} (98%) rename planning/{scenario_selector/test/test_scenario_selector_node_interface.cpp => autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp} (97%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 57fc951f0608c..863d9565571ab 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -203,7 +203,7 @@ planning/sampling_based_planner/autoware_bezier_sampler/** maxime.clement@tier4. planning/sampling_based_planner/autoware_frenet_planner/** maxime.clement@tier4.jp planning/sampling_based_planner/autoware_path_sampler/** maxime.clement@tier4.jp planning/sampling_based_planner/autoware_sampler_common/** maxime.clement@tier4.jp -planning/scenario_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp +planning/autoware_scenario_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/autoware_surround_obstacle_checker/** go.sakayori@tier4.jp satoshi.ota@tier4.jp sensing/gnss_poser/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/image_diagnostics/** dai.nguyen@tier4.jp yoshi.ri@tier4.jp diff --git a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml index f96cac4f017a6..a252986f9d957 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -3,7 +3,7 @@ - + diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index e5def4c7aed0c..798ee7675acaa 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -64,6 +64,7 @@ autoware_planning_topic_converter autoware_planning_validator autoware_remaining_distance_time_calculator + autoware_scenario_selector autoware_surround_obstacle_checker autoware_velocity_smoother behavior_path_planner @@ -74,7 +75,6 @@ obstacle_cruise_planner obstacle_stop_planner planning_evaluator - scenario_selector ament_lint_auto autoware_lint_common diff --git a/planning/.pages b/planning/.pages index efb5e677ab6c6..03b7ec910f2a1 100644 --- a/planning/.pages +++ b/planning/.pages @@ -69,7 +69,7 @@ nav: - 'Velocity Smoother': - 'About Velocity Smoother': planning/autoware_velocity_smoother - 'About Velocity Smoother (Japanese)': planning/autoware_velocity_smoother/README.ja - - 'Scenario Selector': planning/scenario_selector + - 'Scenario Selector': planning/autoware_scenario_selector - 'Static Centerline Generator': planning/autoware_static_centerline_generator - 'API and Library': - 'Costmap Generator': planning/costmap_generator diff --git a/planning/scenario_selector/CMakeLists.txt b/planning/autoware_scenario_selector/CMakeLists.txt similarity index 54% rename from planning/scenario_selector/CMakeLists.txt rename to planning/autoware_scenario_selector/CMakeLists.txt index d2e9e051d721a..e615ed69d61bf 100644 --- a/planning/scenario_selector/CMakeLists.txt +++ b/planning/autoware_scenario_selector/CMakeLists.txt @@ -1,16 +1,16 @@ cmake_minimum_required(VERSION 3.14) -project(scenario_selector) +project(autoware_scenario_selector) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_library(scenario_selector_node SHARED - src/scenario_selector_node/scenario_selector_node.cpp +ament_auto_add_library(${PROJECT_NAME} SHARED + src/node.cpp ) -rclcpp_components_register_node(scenario_selector_node - PLUGIN "ScenarioSelectorNode" - EXECUTABLE scenario_selector +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::scenario_selector::ScenarioSelectorNode" + EXECUTABLE ${PROJECT_NAME}_node ) if(BUILD_TESTING) @@ -18,11 +18,10 @@ if(BUILD_TESTING) test/test_${PROJECT_NAME}_node_interface.cpp ) target_link_libraries(test_${PROJECT_NAME} - ${PROJECT_NAME}_node + ${PROJECT_NAME} ) endif() - ament_auto_package(INSTALL_TO_SHARE launch config diff --git a/planning/scenario_selector/README.md b/planning/autoware_scenario_selector/README.md similarity index 91% rename from planning/scenario_selector/README.md rename to planning/autoware_scenario_selector/README.md index 373ac164e5057..a0b78a572c734 100644 --- a/planning/scenario_selector/README.md +++ b/planning/autoware_scenario_selector/README.md @@ -1,4 +1,4 @@ -# scenario_selector +# autoware_scenario_selector ## scenario_selector_node @@ -29,12 +29,12 @@ None ### How to launch 1. Write your remapping info in `scenario_selector.launch` or add args when executing `roslaunch` -2. `roslaunch scenario_selector scenario_selector.launch` - - If you would like to use only a single scenario, `roslaunch scenario_selector dummy_scenario_selector_{scenario_name}.launch` +2. `roslaunch autoware_scenario_selector scenario_selector.launch` + - If you would like to use only a single scenario, `roslaunch autoware_scenario_selector dummy_scenario_selector_{scenario_name}.launch` ### Parameters -{{ json_to_markdown("planning/scenario_selector/schema/scenario_selector.schema.json") }} +{{ json_to_markdown("planning/autoware_scenario_selector/schema/scenario_selector.schema.json") }} ### Flowchart diff --git a/planning/scenario_selector/config/scenario_selector.param.yaml b/planning/autoware_scenario_selector/config/scenario_selector.param.yaml similarity index 100% rename from planning/scenario_selector/config/scenario_selector.param.yaml rename to planning/autoware_scenario_selector/config/scenario_selector.param.yaml diff --git a/planning/scenario_selector/include/scenario_selector/scenario_selector_node.hpp b/planning/autoware_scenario_selector/include/autoware_scenario_selector/node.hpp similarity index 94% rename from planning/scenario_selector/include/scenario_selector/scenario_selector_node.hpp rename to planning/autoware_scenario_selector/include/autoware_scenario_selector/node.hpp index 7162a435d8852..5551db45bba37 100644 --- a/planning/scenario_selector/include/scenario_selector/scenario_selector_node.hpp +++ b/planning/autoware_scenario_selector/include/autoware_scenario_selector/node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SCENARIO_SELECTOR__SCENARIO_SELECTOR_NODE_HPP_ -#define SCENARIO_SELECTOR__SCENARIO_SELECTOR_NODE_HPP_ +#ifndef AUTOWARE_SCENARIO_SELECTOR__NODE_HPP_ +#define AUTOWARE_SCENARIO_SELECTOR__NODE_HPP_ #include #include @@ -43,6 +43,8 @@ #include #include +namespace autoware::scenario_selector +{ class ScenarioSelectorNode : public rclcpp::Node { public: @@ -100,5 +102,5 @@ class ScenarioSelectorNode : public rclcpp::Node double th_stopped_velocity_mps_; bool is_parking_completed_; }; - -#endif // SCENARIO_SELECTOR__SCENARIO_SELECTOR_NODE_HPP_ +} // namespace autoware::scenario_selector +#endif // AUTOWARE_SCENARIO_SELECTOR__NODE_HPP_ diff --git a/planning/scenario_selector/launch/dummy_scenario_selector_lane_driving.launch.xml b/planning/autoware_scenario_selector/launch/dummy_scenario_selector_lane_driving.launch.xml similarity index 100% rename from planning/scenario_selector/launch/dummy_scenario_selector_lane_driving.launch.xml rename to planning/autoware_scenario_selector/launch/dummy_scenario_selector_lane_driving.launch.xml diff --git a/planning/scenario_selector/launch/dummy_scenario_selector_parking.launch.xml b/planning/autoware_scenario_selector/launch/dummy_scenario_selector_parking.launch.xml similarity index 100% rename from planning/scenario_selector/launch/dummy_scenario_selector_parking.launch.xml rename to planning/autoware_scenario_selector/launch/dummy_scenario_selector_parking.launch.xml diff --git a/planning/scenario_selector/launch/scenario_selector.launch.xml b/planning/autoware_scenario_selector/launch/scenario_selector.launch.xml similarity index 80% rename from planning/scenario_selector/launch/scenario_selector.launch.xml rename to planning/autoware_scenario_selector/launch/scenario_selector.launch.xml index fdf176405d7b0..8c35451ee19dc 100644 --- a/planning/scenario_selector/launch/scenario_selector.launch.xml +++ b/planning/autoware_scenario_selector/launch/scenario_selector.launch.xml @@ -9,9 +9,9 @@ - + - + diff --git a/planning/scenario_selector/package.xml b/planning/autoware_scenario_selector/package.xml similarity index 93% rename from planning/scenario_selector/package.xml rename to planning/autoware_scenario_selector/package.xml index f910c09dbb070..ee58eac35c8ae 100644 --- a/planning/scenario_selector/package.xml +++ b/planning/autoware_scenario_selector/package.xml @@ -1,9 +1,9 @@ - scenario_selector + autoware_scenario_selector 0.1.0 - The scenario_selector ROS 2 package + The autoware_scenario_selector ROS 2 package Taiki Tanaka Tomoya Kimura Shumpei Wakabayashi diff --git a/planning/scenario_selector/schema/scenario_selector.schema.json b/planning/autoware_scenario_selector/schema/scenario_selector.schema.json similarity index 94% rename from planning/scenario_selector/schema/scenario_selector.schema.json rename to planning/autoware_scenario_selector/schema/scenario_selector.schema.json index 8ccb75106c6a5..a9e6411084a88 100644 --- a/planning/scenario_selector/schema/scenario_selector.schema.json +++ b/planning/autoware_scenario_selector/schema/scenario_selector.schema.json @@ -3,7 +3,7 @@ "title": "Parameters for Scenario Selector Node", "type": "object", "definitions": { - "scenario_selector": { + "autoware_scenario_selector": { "type": "object", "properties": { "update_rate": { @@ -51,7 +51,7 @@ "type": "object", "properties": { "ros__parameters": { - "$ref": "#/definitions/scenario_selector" + "$ref": "#/definitions/autoware_scenario_selector" } }, "required": ["ros__parameters"] diff --git a/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp b/planning/autoware_scenario_selector/src/node.cpp similarity index 98% rename from planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp rename to planning/autoware_scenario_selector/src/node.cpp index 2ba56a911bbeb..1f1a22cf08deb 100644 --- a/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp +++ b/planning/autoware_scenario_selector/src/node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "scenario_selector/scenario_selector_node.hpp" +#include "autoware_scenario_selector/node.hpp" #include #include @@ -28,7 +28,8 @@ #include #include #include - +namespace autoware::scenario_selector +{ namespace { template @@ -373,6 +374,7 @@ ScenarioSelectorNode::ScenarioSelectorNode(const rclcpp::NodeOptions & node_opti this, get_clock(), period_ns, std::bind(&ScenarioSelectorNode::onTimer, this)); published_time_publisher_ = std::make_unique(this); } +} // namespace autoware::scenario_selector #include -RCLCPP_COMPONENTS_REGISTER_NODE(ScenarioSelectorNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::scenario_selector::ScenarioSelectorNode) diff --git a/planning/scenario_selector/test/test_scenario_selector_node_interface.cpp b/planning/autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp similarity index 97% rename from planning/scenario_selector/test/test_scenario_selector_node_interface.cpp rename to planning/autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp index 90995e4e2ae72..052c455c477a7 100644 --- a/planning/scenario_selector/test/test_scenario_selector_node_interface.cpp +++ b/planning/autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "scenario_selector/scenario_selector_node.hpp" +#include "autoware_scenario_selector/node.hpp" #include #include @@ -22,7 +22,8 @@ #include #include - +namespace autoware::scenario_selector +{ using planning_test_utils::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() @@ -121,3 +122,4 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) ASSERT_NO_THROW(test_manager->testTrajectoryWithInvalidEgoPose(test_target_node)); rclcpp::shutdown(); } +} // namespace autoware::scenario_selector From 038a8c47d12428d03fc9b2d7548a68f75636f029 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Mon, 10 Jun 2024 14:07:54 +0900 Subject: [PATCH 53/65] =?UTF-8?q?refactor(external=5Fcmd=5Fselector):=20pr?= =?UTF-8?q?efix=20package=20and=20namespace=20with=20au=E2=80=A6=20(#7384)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit refactor(external_cmd_selector): prefix package and namespace with autoware_ Signed-off-by: Y.Hisaki --- .github/CODEOWNERS | 2 +- .../CMakeLists.txt | 19 +++++++++++++++++++ .../README.md | 4 ++-- .../config/external_cmd_selector.param.yaml | 0 .../external_cmd_selector_node.hpp | 11 ++++++----- .../launch/external_cmd_selector.launch.py | 4 ++-- .../launch/external_cmd_selector.launch.xml | 2 +- .../package.xml | 4 ++-- .../external_cmd_selector_node.cpp | 7 +++++-- control/external_cmd_selector/CMakeLists.txt | 19 ------------------- .../launch/control.launch.py | 5 ++++- launch/tier4_control_launch/package.xml | 2 +- launch/tier4_planning_launch/package.xml | 2 +- 13 files changed, 44 insertions(+), 37 deletions(-) create mode 100644 control/autoware_external_cmd_selector/CMakeLists.txt rename control/{external_cmd_selector => autoware_external_cmd_selector}/README.md (91%) rename control/{external_cmd_selector => autoware_external_cmd_selector}/config/external_cmd_selector.param.yaml (100%) rename control/{external_cmd_selector/include/external_cmd_selector => autoware_external_cmd_selector/include/autoware_external_cmd_selector}/external_cmd_selector_node.hpp (93%) rename control/{external_cmd_selector => autoware_external_cmd_selector}/launch/external_cmd_selector.launch.py (97%) rename control/{external_cmd_selector => autoware_external_cmd_selector}/launch/external_cmd_selector.launch.xml (95%) rename control/{external_cmd_selector => autoware_external_cmd_selector}/package.xml (92%) rename control/{external_cmd_selector/src/external_cmd_selector => autoware_external_cmd_selector/src/autoware_external_cmd_selector}/external_cmd_selector_node.cpp (96%) delete mode 100644 control/external_cmd_selector/CMakeLists.txt diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 863d9565571ab..46a5aac18a689 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -47,7 +47,7 @@ common/tvm_utility/** ambroise.vincent@arm.com xinyu.wang@tier4.jp control/autoware_autonomous_emergency_braking/** daniel.sanchez@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp control/control_performance_analysis/** berkay@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/control_validator/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp -control/external_cmd_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp +control/autoware_external_cmd_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/autoware_joy_controller/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/autoware_lane_departure_checker/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp control/mpc_lateral_controller/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp diff --git a/control/autoware_external_cmd_selector/CMakeLists.txt b/control/autoware_external_cmd_selector/CMakeLists.txt new file mode 100644 index 0000000000000..4dccabcd85d8e --- /dev/null +++ b/control/autoware_external_cmd_selector/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_external_cmd_selector) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME}_node SHARED + src/autoware_external_cmd_selector/external_cmd_selector_node.cpp +) + +rclcpp_components_register_node(${PROJECT_NAME}_node + PLUGIN "autoware::external_cmd_selector::ExternalCmdSelector" + EXECUTABLE autoware_external_cmd_selector +) + +ament_auto_package(INSTALL_TO_SHARE + launch + config +) diff --git a/control/external_cmd_selector/README.md b/control/autoware_external_cmd_selector/README.md similarity index 91% rename from control/external_cmd_selector/README.md rename to control/autoware_external_cmd_selector/README.md index ca0f4f0954dbf..0495004b68b84 100644 --- a/control/external_cmd_selector/README.md +++ b/control/autoware_external_cmd_selector/README.md @@ -1,8 +1,8 @@ -# external_cmd_selector +# autoware_external_cmd_selector ## Purpose -`external_cmd_selector` is the package to publish `external_control_cmd`, `gear_cmd`, `hazard_lights_cmd`, `heartbeat` and `turn_indicators_cmd`, according to the current mode, which is `remote` or `local`. +`autoware_external_cmd_selector` is the package to publish `external_control_cmd`, `gear_cmd`, `hazard_lights_cmd`, `heartbeat` and `turn_indicators_cmd`, according to the current mode, which is `remote` or `local`. The current mode is set via service, `remote` is remotely operated, `local` is to use the values calculated by Autoware. diff --git a/control/external_cmd_selector/config/external_cmd_selector.param.yaml b/control/autoware_external_cmd_selector/config/external_cmd_selector.param.yaml similarity index 100% rename from control/external_cmd_selector/config/external_cmd_selector.param.yaml rename to control/autoware_external_cmd_selector/config/external_cmd_selector.param.yaml diff --git a/control/external_cmd_selector/include/external_cmd_selector/external_cmd_selector_node.hpp b/control/autoware_external_cmd_selector/include/autoware_external_cmd_selector/external_cmd_selector_node.hpp similarity index 93% rename from control/external_cmd_selector/include/external_cmd_selector/external_cmd_selector_node.hpp rename to control/autoware_external_cmd_selector/include/autoware_external_cmd_selector/external_cmd_selector_node.hpp index 6a4fb897b57bc..1517ca83ad1f0 100644 --- a/control/external_cmd_selector/include/external_cmd_selector/external_cmd_selector_node.hpp +++ b/control/autoware_external_cmd_selector/include/autoware_external_cmd_selector/external_cmd_selector_node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef EXTERNAL_CMD_SELECTOR__EXTERNAL_CMD_SELECTOR_NODE_HPP_ -#define EXTERNAL_CMD_SELECTOR__EXTERNAL_CMD_SELECTOR_NODE_HPP_ +#ifndef AUTOWARE_EXTERNAL_CMD_SELECTOR__EXTERNAL_CMD_SELECTOR_NODE_HPP_ +#define AUTOWARE_EXTERNAL_CMD_SELECTOR__EXTERNAL_CMD_SELECTOR_NODE_HPP_ #include #include @@ -30,7 +30,8 @@ #include #include - +namespace autoware::external_cmd_selector +{ class ExternalCmdSelector : public rclcpp::Node { public: @@ -101,5 +102,5 @@ class ExternalCmdSelector : public rclcpp::Node // Diagnostics Updater diagnostic_updater::Updater updater_{this}; }; - -#endif // EXTERNAL_CMD_SELECTOR__EXTERNAL_CMD_SELECTOR_NODE_HPP_ +} // namespace autoware::external_cmd_selector +#endif // AUTOWARE_EXTERNAL_CMD_SELECTOR__EXTERNAL_CMD_SELECTOR_NODE_HPP_ diff --git a/control/external_cmd_selector/launch/external_cmd_selector.launch.py b/control/autoware_external_cmd_selector/launch/external_cmd_selector.launch.py similarity index 97% rename from control/external_cmd_selector/launch/external_cmd_selector.launch.py rename to control/autoware_external_cmd_selector/launch/external_cmd_selector.launch.py index 358cc135996f7..95673502e2b51 100644 --- a/control/external_cmd_selector/launch/external_cmd_selector.launch.py +++ b/control/autoware_external_cmd_selector/launch/external_cmd_selector.launch.py @@ -32,8 +32,8 @@ def launch_setup(context, *args, **kwargs): external_cmd_selector_param = yaml.safe_load(f)["/**"]["ros__parameters"] component = ComposableNode( - package="external_cmd_selector", - plugin="ExternalCmdSelector", + package="autoware_external_cmd_selector", + plugin="autoware::external_cmd_selector::ExternalCmdSelector", name="external_cmd_selector", remappings=[ _create_mapping_tuple("service/select_external_command"), diff --git a/control/external_cmd_selector/launch/external_cmd_selector.launch.xml b/control/autoware_external_cmd_selector/launch/external_cmd_selector.launch.xml similarity index 95% rename from control/external_cmd_selector/launch/external_cmd_selector.launch.xml rename to control/autoware_external_cmd_selector/launch/external_cmd_selector.launch.xml index cb373802e5183..7e8b32ac68d8d 100644 --- a/control/external_cmd_selector/launch/external_cmd_selector.launch.xml +++ b/control/autoware_external_cmd_selector/launch/external_cmd_selector.launch.xml @@ -26,7 +26,7 @@ - + diff --git a/control/external_cmd_selector/package.xml b/control/autoware_external_cmd_selector/package.xml similarity index 92% rename from control/external_cmd_selector/package.xml rename to control/autoware_external_cmd_selector/package.xml index b3520839e3b51..19881f06c96e5 100644 --- a/control/external_cmd_selector/package.xml +++ b/control/autoware_external_cmd_selector/package.xml @@ -1,9 +1,9 @@ - external_cmd_selector + autoware_external_cmd_selector 0.1.0 - The external_cmd_selector package + The autoware_external_cmd_selector package Taiki Tanaka Tomoya Kimura Shumpei Wakabayashi diff --git a/control/external_cmd_selector/src/external_cmd_selector/external_cmd_selector_node.cpp b/control/autoware_external_cmd_selector/src/autoware_external_cmd_selector/external_cmd_selector_node.cpp similarity index 96% rename from control/external_cmd_selector/src/external_cmd_selector/external_cmd_selector_node.cpp rename to control/autoware_external_cmd_selector/src/autoware_external_cmd_selector/external_cmd_selector_node.cpp index 0039ec9cd1547..59a8caa5c1568 100644 --- a/control/external_cmd_selector/src/external_cmd_selector/external_cmd_selector_node.cpp +++ b/control/autoware_external_cmd_selector/src/autoware_external_cmd_selector/external_cmd_selector_node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "external_cmd_selector/external_cmd_selector_node.hpp" +#include "autoware_external_cmd_selector/external_cmd_selector_node.hpp" #include @@ -21,6 +21,8 @@ #include #include +namespace autoware::external_cmd_selector +{ ExternalCmdSelector::ExternalCmdSelector(const rclcpp::NodeOptions & node_options) : Node("external_cmd_selector", node_options) { @@ -202,6 +204,7 @@ ExternalCmdSelector::InternalHeartbeat ExternalCmdSelector::convert( { return command; } +} // namespace autoware::external_cmd_selector #include -RCLCPP_COMPONENTS_REGISTER_NODE(ExternalCmdSelector) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::external_cmd_selector::ExternalCmdSelector) diff --git a/control/external_cmd_selector/CMakeLists.txt b/control/external_cmd_selector/CMakeLists.txt deleted file mode 100644 index 5c4860b7441f3..0000000000000 --- a/control/external_cmd_selector/CMakeLists.txt +++ /dev/null @@ -1,19 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(external_cmd_selector) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_add_library(external_cmd_selector_node SHARED - src/external_cmd_selector/external_cmd_selector_node.cpp -) - -rclcpp_components_register_node(external_cmd_selector_node - PLUGIN "ExternalCmdSelector" - EXECUTABLE external_cmd_selector -) - -ament_auto_package(INSTALL_TO_SHARE - launch - config -) diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index dea0bc1d7c442..1183514e9a3cb 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -272,7 +272,10 @@ def launch_setup(context, *args, **kwargs): # external cmd selector external_cmd_selector_loader = IncludeLaunchDescription( PythonLaunchDescriptionSource( - [FindPackageShare("external_cmd_selector"), "/launch/external_cmd_selector.launch.py"] + [ + FindPackageShare("autoware_external_cmd_selector"), + "/launch/external_cmd_selector.launch.py", + ] ), launch_arguments=[ ("use_intra_process", LaunchConfiguration("use_intra_process")), diff --git a/launch/tier4_control_launch/package.xml b/launch/tier4_control_launch/package.xml index cfa1a07d4ea45..f02ec0aee47b6 100644 --- a/launch/tier4_control_launch/package.xml +++ b/launch/tier4_control_launch/package.xml @@ -11,11 +11,11 @@ ament_cmake_auto autoware_cmake + autoware_external_cmd_selector autoware_lane_departure_checker autoware_vehicle_cmd_gate control_evaluator external_cmd_converter - external_cmd_selector shift_decider trajectory_follower_node diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 798ee7675acaa..cc2d2903005cb 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -59,6 +59,7 @@ autoware_behavior_velocity_planner autoware_costmap_generator + autoware_external_cmd_selector autoware_external_velocity_limit_selector autoware_path_optimizer autoware_planning_topic_converter @@ -68,7 +69,6 @@ autoware_surround_obstacle_checker autoware_velocity_smoother behavior_path_planner - external_cmd_selector freespace_planner glog_component mission_planner From d2a8b16ebe27a50adccf52d9ae378d0261c03f72 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 10 Jun 2024 14:11:02 +0900 Subject: [PATCH 54/65] refactor(map_based_prediction): prefix map based prediction (#7391) Signed-off-by: Mamoru Sobue --- .../prediction/prediction.launch.xml | 2 +- .../CMakeLists.txt | 4 +-- .../README.md | 0 .../config/map_based_prediction.param.yaml | 0 .../images/exception.svg | 0 .../images/inside_road.svg | 0 .../images/outside_road.svg | 0 .../images/target_objects.svg | 0 .../map_based_prediction_node.hpp | 4 +-- .../map_based_prediction/path_generator.hpp | 4 +-- .../launch/map_based_prediction.launch.xml | 4 +-- .../media/lane_change_detection.drawio.svg | 0 .../lanechange_detection_right_to_left.png | Bin .../map_based_prediction_flow.drawio.svg | 0 .../media/object_history.drawio.svg | 0 .../package.xml | 2 +- .../schema/map_based_prediction.schema.json | 0 .../src/debug.cpp | 4 +-- .../src/map_based_prediction_node.cpp | 6 ++-- .../src/path_generator.cpp | 4 +-- .../test_path_generator.cpp | 34 ++++++++++-------- .../test/test_map_based_prediction.cpp | 0 22 files changed, 37 insertions(+), 31 deletions(-) rename perception/{map_based_prediction => autoware_map_based_prediction}/CMakeLists.txt (90%) rename perception/{map_based_prediction => autoware_map_based_prediction}/README.md (100%) rename perception/{map_based_prediction => autoware_map_based_prediction}/config/map_based_prediction.param.yaml (100%) rename perception/{map_based_prediction => autoware_map_based_prediction}/images/exception.svg (100%) rename perception/{map_based_prediction => autoware_map_based_prediction}/images/inside_road.svg (100%) rename perception/{map_based_prediction => autoware_map_based_prediction}/images/outside_road.svg (100%) rename perception/{map_based_prediction => autoware_map_based_prediction}/images/target_objects.svg (100%) rename perception/{map_based_prediction => autoware_map_based_prediction}/include/map_based_prediction/map_based_prediction_node.hpp (99%) rename perception/{map_based_prediction => autoware_map_based_prediction}/include/map_based_prediction/path_generator.hpp (98%) rename perception/{map_based_prediction => autoware_map_based_prediction}/launch/map_based_prediction.launch.xml (72%) rename perception/{map_based_prediction => autoware_map_based_prediction}/media/lane_change_detection.drawio.svg (100%) rename perception/{map_based_prediction => autoware_map_based_prediction}/media/lanechange_detection_right_to_left.png (100%) rename perception/{map_based_prediction => autoware_map_based_prediction}/media/map_based_prediction_flow.drawio.svg (100%) rename perception/{map_based_prediction => autoware_map_based_prediction}/media/object_history.drawio.svg (100%) rename perception/{map_based_prediction => autoware_map_based_prediction}/package.xml (96%) rename perception/{map_based_prediction => autoware_map_based_prediction}/schema/map_based_prediction.schema.json (100%) rename perception/{map_based_prediction => autoware_map_based_prediction}/src/debug.cpp (94%) rename perception/{map_based_prediction => autoware_map_based_prediction}/src/map_based_prediction_node.cpp (99%) rename perception/{map_based_prediction => autoware_map_based_prediction}/src/path_generator.cpp (99%) rename perception/{map_based_prediction => autoware_map_based_prediction}/test/map_based_prediction/test_path_generator.cpp (84%) rename perception/{map_based_prediction => autoware_map_based_prediction}/test/test_map_based_prediction.cpp (100%) diff --git a/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml index fa343f49840ad..a9ba980b3ce47 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/prediction/prediction.launch.xml @@ -5,7 +5,7 @@ - + diff --git a/perception/map_based_prediction/CMakeLists.txt b/perception/autoware_map_based_prediction/CMakeLists.txt similarity index 90% rename from perception/map_based_prediction/CMakeLists.txt rename to perception/autoware_map_based_prediction/CMakeLists.txt index 786446457143f..9a1d9a1947c7c 100644 --- a/perception/map_based_prediction/CMakeLists.txt +++ b/perception/autoware_map_based_prediction/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(map_based_prediction) +project(autoware_map_based_prediction) find_package(autoware_cmake REQUIRED) autoware_package() @@ -22,7 +22,7 @@ ament_auto_add_library(map_based_prediction_node SHARED target_link_libraries(map_based_prediction_node glog::glog) rclcpp_components_register_node(map_based_prediction_node - PLUGIN "map_based_prediction::MapBasedPredictionNode" + PLUGIN "autoware::map_based_prediction::MapBasedPredictionNode" EXECUTABLE map_based_prediction ) diff --git a/perception/map_based_prediction/README.md b/perception/autoware_map_based_prediction/README.md similarity index 100% rename from perception/map_based_prediction/README.md rename to perception/autoware_map_based_prediction/README.md diff --git a/perception/map_based_prediction/config/map_based_prediction.param.yaml b/perception/autoware_map_based_prediction/config/map_based_prediction.param.yaml similarity index 100% rename from perception/map_based_prediction/config/map_based_prediction.param.yaml rename to perception/autoware_map_based_prediction/config/map_based_prediction.param.yaml diff --git a/perception/map_based_prediction/images/exception.svg b/perception/autoware_map_based_prediction/images/exception.svg similarity index 100% rename from perception/map_based_prediction/images/exception.svg rename to perception/autoware_map_based_prediction/images/exception.svg diff --git a/perception/map_based_prediction/images/inside_road.svg b/perception/autoware_map_based_prediction/images/inside_road.svg similarity index 100% rename from perception/map_based_prediction/images/inside_road.svg rename to perception/autoware_map_based_prediction/images/inside_road.svg diff --git a/perception/map_based_prediction/images/outside_road.svg b/perception/autoware_map_based_prediction/images/outside_road.svg similarity index 100% rename from perception/map_based_prediction/images/outside_road.svg rename to perception/autoware_map_based_prediction/images/outside_road.svg diff --git a/perception/map_based_prediction/images/target_objects.svg b/perception/autoware_map_based_prediction/images/target_objects.svg similarity index 100% rename from perception/map_based_prediction/images/target_objects.svg rename to perception/autoware_map_based_prediction/images/target_objects.svg diff --git a/perception/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 similarity index 99% rename from perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp rename to perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index 7a0010637c2f4..22b28b00d645e 100644 --- a/perception/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 @@ -51,7 +51,7 @@ #include #include -namespace map_based_prediction +namespace autoware::map_based_prediction { struct LateralKinematicsToLanelet { @@ -416,6 +416,6 @@ class MapBasedPredictionNode : public rclcpp::Node return true; }; }; -} // namespace map_based_prediction +} // namespace autoware::map_based_prediction #endif // MAP_BASED_PREDICTION__MAP_BASED_PREDICTION_NODE_HPP_ diff --git a/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp b/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp similarity index 98% rename from perception/map_based_prediction/include/map_based_prediction/path_generator.hpp rename to perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp index 0c1642600f4b1..bd098894f8a88 100644 --- a/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp +++ b/perception/autoware_map_based_prediction/include/map_based_prediction/path_generator.hpp @@ -28,7 +28,7 @@ #include #include -namespace map_based_prediction +namespace autoware::map_based_prediction { using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObject; @@ -145,6 +145,6 @@ class PathGenerator const TrackedObject & object, const PosePath & ref_path, const double duration, const double speed_limit = 0.0) const; }; -} // namespace map_based_prediction +} // namespace autoware::map_based_prediction #endif // MAP_BASED_PREDICTION__PATH_GENERATOR_HPP_ diff --git a/perception/map_based_prediction/launch/map_based_prediction.launch.xml b/perception/autoware_map_based_prediction/launch/map_based_prediction.launch.xml similarity index 72% rename from perception/map_based_prediction/launch/map_based_prediction.launch.xml rename to perception/autoware_map_based_prediction/launch/map_based_prediction.launch.xml index 7f81971b2f8d7..b65f0de892dcc 100644 --- a/perception/map_based_prediction/launch/map_based_prediction.launch.xml +++ b/perception/autoware_map_based_prediction/launch/map_based_prediction.launch.xml @@ -1,13 +1,13 @@ - + - + diff --git a/perception/map_based_prediction/media/lane_change_detection.drawio.svg b/perception/autoware_map_based_prediction/media/lane_change_detection.drawio.svg similarity index 100% rename from perception/map_based_prediction/media/lane_change_detection.drawio.svg rename to perception/autoware_map_based_prediction/media/lane_change_detection.drawio.svg diff --git a/perception/map_based_prediction/media/lanechange_detection_right_to_left.png b/perception/autoware_map_based_prediction/media/lanechange_detection_right_to_left.png similarity index 100% rename from perception/map_based_prediction/media/lanechange_detection_right_to_left.png rename to perception/autoware_map_based_prediction/media/lanechange_detection_right_to_left.png diff --git a/perception/map_based_prediction/media/map_based_prediction_flow.drawio.svg b/perception/autoware_map_based_prediction/media/map_based_prediction_flow.drawio.svg similarity index 100% rename from perception/map_based_prediction/media/map_based_prediction_flow.drawio.svg rename to perception/autoware_map_based_prediction/media/map_based_prediction_flow.drawio.svg diff --git a/perception/map_based_prediction/media/object_history.drawio.svg b/perception/autoware_map_based_prediction/media/object_history.drawio.svg similarity index 100% rename from perception/map_based_prediction/media/object_history.drawio.svg rename to perception/autoware_map_based_prediction/media/object_history.drawio.svg diff --git a/perception/map_based_prediction/package.xml b/perception/autoware_map_based_prediction/package.xml similarity index 96% rename from perception/map_based_prediction/package.xml rename to perception/autoware_map_based_prediction/package.xml index 70ad1ec8519d9..3671c1a01b0a2 100644 --- a/perception/map_based_prediction/package.xml +++ b/perception/autoware_map_based_prediction/package.xml @@ -1,7 +1,7 @@ - map_based_prediction + autoware_map_based_prediction 0.1.0 This package implements a map_based_prediction Tomoya Kimura diff --git a/perception/map_based_prediction/schema/map_based_prediction.schema.json b/perception/autoware_map_based_prediction/schema/map_based_prediction.schema.json similarity index 100% rename from perception/map_based_prediction/schema/map_based_prediction.schema.json rename to perception/autoware_map_based_prediction/schema/map_based_prediction.schema.json diff --git a/perception/map_based_prediction/src/debug.cpp b/perception/autoware_map_based_prediction/src/debug.cpp similarity index 94% rename from perception/map_based_prediction/src/debug.cpp rename to perception/autoware_map_based_prediction/src/debug.cpp index f78879ba209a1..0c58d4aae1638 100644 --- a/perception/map_based_prediction/src/debug.cpp +++ b/perception/autoware_map_based_prediction/src/debug.cpp @@ -15,7 +15,7 @@ #include "map_based_prediction/map_based_prediction_node.hpp" #include "tier4_autoware_utils/ros/marker_helper.hpp" -namespace map_based_prediction +namespace autoware::map_based_prediction { visualization_msgs::msg::Marker MapBasedPredictionNode::getDebugMarker( const TrackedObject & object, const Maneuver & maneuver, const size_t obj_num) @@ -46,4 +46,4 @@ visualization_msgs::msg::Marker MapBasedPredictionNode::getDebugMarker( return marker; } -} // namespace map_based_prediction +} // namespace autoware::map_based_prediction diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp similarity index 99% rename from perception/map_based_prediction/src/map_based_prediction_node.cpp rename to perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp index a00a43545cf23..c23e78d243f9c 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp @@ -50,7 +50,7 @@ #include #include -namespace map_based_prediction +namespace autoware::map_based_prediction { namespace @@ -2495,7 +2495,7 @@ bool MapBasedPredictionNode::calcIntentionToCrossWithTrafficSignal( return true; } -} // namespace map_based_prediction +} // namespace autoware::map_based_prediction #include -RCLCPP_COMPONENTS_REGISTER_NODE(map_based_prediction::MapBasedPredictionNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::map_based_prediction::MapBasedPredictionNode) diff --git a/perception/map_based_prediction/src/path_generator.cpp b/perception/autoware_map_based_prediction/src/path_generator.cpp similarity index 99% rename from perception/map_based_prediction/src/path_generator.cpp rename to perception/autoware_map_based_prediction/src/path_generator.cpp index 52e104f572f76..873219ffcf130 100644 --- a/perception/map_based_prediction/src/path_generator.cpp +++ b/perception/autoware_map_based_prediction/src/path_generator.cpp @@ -20,7 +20,7 @@ #include -namespace map_based_prediction +namespace autoware::map_based_prediction { PathGenerator::PathGenerator( const double sampling_time_interval, const double min_crosswalk_user_velocity) @@ -487,4 +487,4 @@ FrenetPoint PathGenerator::getFrenetPoint( return frenet_point; } -} // namespace map_based_prediction +} // namespace autoware::map_based_prediction diff --git a/perception/map_based_prediction/test/map_based_prediction/test_path_generator.cpp b/perception/autoware_map_based_prediction/test/map_based_prediction/test_path_generator.cpp similarity index 84% rename from perception/map_based_prediction/test/map_based_prediction/test_path_generator.cpp rename to perception/autoware_map_based_prediction/test/map_based_prediction/test_path_generator.cpp index 518b28a555849..08e5b4977e583 100644 --- a/perception/map_based_prediction/test/map_based_prediction/test_path_generator.cpp +++ b/perception/autoware_map_based_prediction/test/map_based_prediction/test_path_generator.cpp @@ -54,8 +54,9 @@ TEST(PathGenerator, test_generatePathForNonVehicleObject) const double prediction_time_horizon = 10.0; const double prediction_sampling_time_interval = 0.5; const double min_crosswalk_user_velocity = 0.1; - const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator( - prediction_sampling_time_interval, min_crosswalk_user_velocity); + const autoware::map_based_prediction::PathGenerator path_generator = + autoware::map_based_prediction::PathGenerator( + prediction_sampling_time_interval, min_crosswalk_user_velocity); // Generate pedestrian object TrackedObject tracked_object = generate_static_object(ObjectClassification::PEDESTRIAN); @@ -77,8 +78,9 @@ TEST(PathGenerator, test_generatePathForLowSpeedVehicle) const double prediction_time_horizon = 10.0; const double prediction_sampling_time_interval = 0.5; const double min_crosswalk_user_velocity = 0.1; - const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator( - prediction_sampling_time_interval, min_crosswalk_user_velocity); + const autoware::map_based_prediction::PathGenerator path_generator = + autoware::map_based_prediction::PathGenerator( + prediction_sampling_time_interval, min_crosswalk_user_velocity); // Generate dummy object TrackedObject tracked_object = generate_static_object(ObjectClassification::CAR); @@ -100,8 +102,9 @@ TEST(PathGenerator, test_generatePathForOffLaneVehicle) const double prediction_time_horizon = 10.0; const double prediction_sampling_time_interval = 0.5; const double min_crosswalk_user_velocity = 0.1; - const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator( - prediction_sampling_time_interval, min_crosswalk_user_velocity); + const autoware::map_based_prediction::PathGenerator path_generator = + autoware::map_based_prediction::PathGenerator( + prediction_sampling_time_interval, min_crosswalk_user_velocity); // Generate dummy object TrackedObject tracked_object = generate_static_object(ObjectClassification::CAR); @@ -123,14 +126,15 @@ TEST(PathGenerator, test_generatePathForOnLaneVehicle) const double lateral_control_time_horizon = 5.0; const double prediction_sampling_time_interval = 0.5; const double min_crosswalk_user_velocity = 0.1; - const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator( - prediction_sampling_time_interval, min_crosswalk_user_velocity); + const autoware::map_based_prediction::PathGenerator path_generator = + autoware::map_based_prediction::PathGenerator( + prediction_sampling_time_interval, min_crosswalk_user_velocity); // Generate dummy object TrackedObject tracked_object = generate_static_object(ObjectClassification::CAR); // Generate reference path - map_based_prediction::PosePath ref_paths; + autoware::map_based_prediction::PosePath ref_paths; geometry_msgs::msg::Pose pose; pose.position.x = 0.0; pose.position.y = 0.0; @@ -154,14 +158,15 @@ TEST(PathGenerator, test_generatePathForCrosswalkUser) const double prediction_time_horizon = 10.0; const double prediction_sampling_time_interval = 0.5; const double min_crosswalk_user_velocity = 0.1; - const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator( - prediction_sampling_time_interval, min_crosswalk_user_velocity); + const autoware::map_based_prediction::PathGenerator path_generator = + autoware::map_based_prediction::PathGenerator( + prediction_sampling_time_interval, min_crosswalk_user_velocity); // Generate dummy object TrackedObject tracked_object = generate_static_object(ObjectClassification::PEDESTRIAN); // Generate dummy crosswalk - map_based_prediction::CrosswalkEdgePoints reachable_crosswalk; + autoware::map_based_prediction::CrosswalkEdgePoints reachable_crosswalk; reachable_crosswalk.front_center_point << 0.0, 0.0; reachable_crosswalk.front_right_point << 1.0, 0.0; reachable_crosswalk.front_left_point << -1.0, 0.0; @@ -185,8 +190,9 @@ TEST(PathGenerator, test_generatePathToTargetPoint) // Generate Path generator const double prediction_sampling_time_interval = 0.5; const double min_crosswalk_user_velocity = 0.1; - const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator( - prediction_sampling_time_interval, min_crosswalk_user_velocity); + const autoware::map_based_prediction::PathGenerator path_generator = + autoware::map_based_prediction::PathGenerator( + prediction_sampling_time_interval, min_crosswalk_user_velocity); // Generate dummy object TrackedObject tracked_object = generate_static_object(ObjectClassification::CAR); diff --git a/perception/map_based_prediction/test/test_map_based_prediction.cpp b/perception/autoware_map_based_prediction/test/test_map_based_prediction.cpp similarity index 100% rename from perception/map_based_prediction/test/test_map_based_prediction.cpp rename to perception/autoware_map_based_prediction/test/test_map_based_prediction.cpp From 9a357a4f440a28ed4664a3535866ced743743ae8 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 10 Jun 2024 14:45:34 +0900 Subject: [PATCH 55/65] fix(occlusion_spot_module): fix dependencies, docs, codeowners (#7393) Signed-off-by: Maxime CLEMENT --- .github/CODEOWNERS | 2 +- planning/.pages | 2 +- planning/autoware_behavior_velocity_planner/README.md | 2 +- planning/autoware_behavior_velocity_planner/package.xml | 2 +- .../test/src/test_node_interface.cpp | 2 +- planning/autoware_behavior_velocity_run_out_module/README.md | 2 +- planning/behavior_velocity_occlusion_spot_module/plugins.xml | 2 +- 7 files changed, 7 insertions(+), 7 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 46a5aac18a689..9c64b64645c6f 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -178,7 +178,7 @@ planning/behavior_velocity_dynamic_obstacle_stop_module/** mamoru.sobue@tier4.jp planning/behavior_velocity_intersection_module/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/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_no_stopping_area_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -planning/behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp +planning/autoware_behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp planning/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 planning/autoware_behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp diff --git a/planning/.pages b/planning/.pages index 03b7ec910f2a1..ce08c389c17f5 100644 --- a/planning/.pages +++ b/planning/.pages @@ -28,7 +28,7 @@ nav: - 'Intersection': planning/autoware_behavior_velocity_intersection_module - 'No Drivable Lane': planning/behavior_velocity_no_drivable_lane_module - 'No Stopping Area': planning/behavior_velocity_no_stopping_area_module - - 'Occlusion Spot': planning/behavior_velocity_occlusion_spot_module + - 'Occlusion Spot': planning/autoware_behavior_velocity_occlusion_spot_module - 'Run Out': planning/autoware_behavior_velocity_run_out_module - 'Speed Bump': planning/behavior_velocity_speed_bump_module - 'Stop Line': planning/autoware_behavior_velocity_stop_line_module diff --git a/planning/autoware_behavior_velocity_planner/README.md b/planning/autoware_behavior_velocity_planner/README.md index 400768dd978d9..e792860239119 100644 --- a/planning/autoware_behavior_velocity_planner/README.md +++ b/planning/autoware_behavior_velocity_planner/README.md @@ -16,7 +16,7 @@ It loads modules as plugins. Please refer to the links listed below for detail o - [Stop Line](../autoware_behavior_velocity_stop_line_module/README.md) - [Virtual Traffic Light](../autoware_behavior_velocity_virtual_traffic_light_module/README.md) - [Traffic Light](../behavior_velocity_traffic_light_module/README.md) -- [Occlusion Spot](../behavior_velocity_occlusion_spot_module/README.md) +- [Occlusion Spot](../autoware_behavior_velocity_occlusion_spot_module/README.md) - [No Stopping Area](../behavior_velocity_no_stopping_area_module/README.md) - [Run Out](../autoware_behavior_velocity_run_out_module/README.md) - [Speed Bump](../behavior_velocity_speed_bump_module/README.md) diff --git a/planning/autoware_behavior_velocity_planner/package.xml b/planning/autoware_behavior_velocity_planner/package.xml index 4dcaf22306c22..dcec42f80691f 100644 --- a/planning/autoware_behavior_velocity_planner/package.xml +++ b/planning/autoware_behavior_velocity_planner/package.xml @@ -66,6 +66,7 @@ ament_cmake_ros ament_lint_auto autoware_behavior_velocity_intersection_module + autoware_behavior_velocity_occlusion_spot_module autoware_behavior_velocity_run_out_module autoware_behavior_velocity_stop_line_module autoware_behavior_velocity_virtual_traffic_light_module @@ -76,7 +77,6 @@ behavior_velocity_detection_area_module behavior_velocity_no_drivable_lane_module behavior_velocity_no_stopping_area_module - behavior_velocity_occlusion_spot_module behavior_velocity_speed_bump_module behavior_velocity_traffic_light_module diff --git a/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp index a10ad86e4fb00..58e7a86e01302 100644 --- a/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp @@ -101,7 +101,7 @@ std::shared_ptr generateNode() get_behavior_velocity_module_config_no_prefix("detection_area"), get_behavior_velocity_module_config("intersection"), get_behavior_velocity_module_config_no_prefix("no_stopping_area"), - get_behavior_velocity_module_config_no_prefix("occlusion_spot"), + get_behavior_velocity_module_config("occlusion_spot"), get_behavior_velocity_module_config("run_out"), get_behavior_velocity_module_config_no_prefix("speed_bump"), get_behavior_velocity_module_config("stop_line"), diff --git a/planning/autoware_behavior_velocity_run_out_module/README.md b/planning/autoware_behavior_velocity_run_out_module/README.md index d3e2d813c3799..acc1260723f2f 100644 --- a/planning/autoware_behavior_velocity_run_out_module/README.md +++ b/planning/autoware_behavior_velocity_run_out_module/README.md @@ -182,7 +182,7 @@ APPROACH --> APPROACH : Approach duration is less than threshold ##### Limit velocity with specified jerk and acc limit The maximum slowdown velocity is calculated in order not to slowdown too much. -See the [Occlusion Spot document](../behavior_velocity_occlusion_spot_module/#maximum-slowdown-velocity) for more details. +See the [Occlusion Spot document](../autoware_behavior_velocity_occlusion_spot_module/#maximum-slowdown-velocity) for more details. You can choose whether to use this feature by parameter of `slow_down_limit.enable`. ### Module Parameters diff --git a/planning/behavior_velocity_occlusion_spot_module/plugins.xml b/planning/behavior_velocity_occlusion_spot_module/plugins.xml index 2d85752cf2b3d..53a2c460c2e44 100644 --- a/planning/behavior_velocity_occlusion_spot_module/plugins.xml +++ b/planning/behavior_velocity_occlusion_spot_module/plugins.xml @@ -1,3 +1,3 @@ - + From 087e02d74e361fb1622ec9c2c297d3ecc205d88e Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 10 Jun 2024 14:52:09 +0900 Subject: [PATCH 56/65] chore(tier4_perception_launch): rename autoware_map_based_prediction_depend (#7395) Signed-off-by: Mamoru Sobue --- launch/tier4_perception_launch/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/tier4_perception_launch/package.xml b/launch/tier4_perception_launch/package.xml index 2d007ae8c5ff0..c74ef297aba6b 100644 --- a/launch/tier4_perception_launch/package.xml +++ b/launch/tier4_perception_launch/package.xml @@ -12,6 +12,7 @@ ament_cmake_auto autoware_cmake + autoware_map_based_prediction cluster_merger compare_map_segmentation crosswalk_traffic_light_estimator @@ -23,7 +24,6 @@ image_projection_based_fusion image_transport_decompressor lidar_apollo_instance_segmentation - map_based_prediction multi_object_tracker object_merger object_range_splitter From 2334f63cf099075d741702aabbf4a3e15641f541 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 10 Jun 2024 09:28:02 +0300 Subject: [PATCH 57/65] ci(clang-tidy-differential): fix tag requirement (#7396) 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/clang-tidy-differential.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/clang-tidy-differential.yaml b/.github/workflows/clang-tidy-differential.yaml index f7ec81e3394e5..26c5314d4b119 100644 --- a/.github/workflows/clang-tidy-differential.yaml +++ b/.github/workflows/clang-tidy-differential.yaml @@ -14,6 +14,8 @@ jobs: label: tag:run-clang-tidy-differential clang-tidy-differential: + needs: prevent-no-label-execution + if: ${{ needs.prevent-no-label-execution.outputs.run == 'true' }} runs-on: ubuntu-latest container: ghcr.io/autowarefoundation/autoware:latest-prebuilt-cuda steps: From 3b90dc0b6159354d2529139fb4b09d3f24befeda Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Mon, 10 Jun 2024 16:00:14 +0900 Subject: [PATCH 58/65] refactor(ndt scan matcher): apply static analysis (#7278) * to snake_case Signed-off-by: Yamato Ando * fix line length Signed-off-by: Yamato Ando * add nodiscard Signed-off-by: Yamato Ando * to non member func Signed-off-by: Yamato Ando * initilize param Signed-off-by: Yamato Ando * add header Signed-off-by: Yamato Ando * add const Signed-off-by: Yamato Ando * style(pre-commit): autofix --------- Signed-off-by: Yamato Ando Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: SakodaShintaro --- .../ndt_scan_matcher/diagnostics_module.hpp | 16 +- .../ndt_scan_matcher/hyper_parameters.hpp | 64 ++++---- .../ndt_scan_matcher_core.hpp | 2 - .../src/diagnostics_module.cpp | 16 +- .../src/map_update_module.cpp | 42 ++--- .../src/ndt_scan_matcher_core.cpp | 150 +++++++++--------- .../ndt_scan_matcher/test/test_util.hpp | 5 + 7 files changed, 150 insertions(+), 145 deletions(-) diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/diagnostics_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/diagnostics_module.hpp index 4f7b5eff6521b..6dfea386abaf8 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/diagnostics_module.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/diagnostics_module.hpp @@ -27,14 +27,14 @@ class DiagnosticsModule public: DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name); void clear(); - void addKeyValue(const diagnostic_msgs::msg::KeyValue & key_value_msg); + void add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg); template - void addKeyValue(const std::string & key, const T & value); - void updateLevelAndMessage(const int8_t level, const std::string & message); + void add_key_value(const std::string & key, const T & value); + void update_level_and_message(const int8_t level, const std::string & message); void publish(const rclcpp::Time & publish_time_stamp); private: - diagnostic_msgs::msg::DiagnosticArray createDiagnosticsArray( + [[nodiscard]] diagnostic_msgs::msg::DiagnosticArray create_diagnostics_array( const rclcpp::Time & publish_time_stamp) const; rclcpp::Clock::SharedPtr clock_; @@ -44,17 +44,17 @@ class DiagnosticsModule }; template -void DiagnosticsModule::addKeyValue(const std::string & key, const T & value) +void DiagnosticsModule::add_key_value(const std::string & key, const T & value) { diagnostic_msgs::msg::KeyValue key_value; key_value.key = key; key_value.value = std::to_string(value); - addKeyValue(key_value); + add_key_value(key_value); } template <> -void DiagnosticsModule::addKeyValue(const std::string & key, const std::string & value); +void DiagnosticsModule::add_key_value(const std::string & key, const std::string & value); template <> -void DiagnosticsModule::addKeyValue(const std::string & key, const bool & value); +void DiagnosticsModule::add_key_value(const std::string & key, const bool & value); #endif // NDT_SCAN_MATCHER__DIAGNOSTICS_MODULE_HPP_ diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp index bc7bf1fe40d36..7002b4bf43a73 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp @@ -33,62 +33,62 @@ struct HyperParameters { struct Frame { - std::string base_frame; - std::string ndt_base_frame; - std::string map_frame; - } frame; + std::string base_frame{}; + std::string ndt_base_frame{}; + std::string map_frame{}; + } frame{}; struct SensorPoints { - double required_distance; - } sensor_points; + double required_distance{}; + } sensor_points{}; - pclomp::NdtParams ndt; - bool ndt_regularization_enable; + pclomp::NdtParams ndt{}; + bool ndt_regularization_enable{}; struct InitialPoseEstimation { - int64_t particles_num; - int64_t n_startup_trials; - } initial_pose_estimation; + int64_t particles_num{}; + int64_t n_startup_trials{}; + } initial_pose_estimation{}; struct Validation { - double lidar_topic_timeout_sec; - double initial_pose_timeout_sec; - double initial_pose_distance_tolerance_m; - double critical_upper_bound_exe_time_ms; - } validation; + double lidar_topic_timeout_sec{}; + double initial_pose_timeout_sec{}; + double initial_pose_distance_tolerance_m{}; + double critical_upper_bound_exe_time_ms{}; + } validation{}; struct ScoreEstimation { - ConvergedParamType converged_param_type; - double converged_param_transform_probability; - double converged_param_nearest_voxel_transformation_likelihood; + ConvergedParamType converged_param_type{}; + double converged_param_transform_probability{}; + double converged_param_nearest_voxel_transformation_likelihood{}; struct NoGroundPoints { - bool enable; - double z_margin_for_ground_removal; - } no_ground_points; - } score_estimation; + bool enable{}; + double z_margin_for_ground_removal{}; + } no_ground_points{}; + } score_estimation{}; struct Covariance { - std::array output_pose_covariance; + std::array output_pose_covariance{}; struct CovarianceEstimation { - bool enable; - std::vector initial_pose_offset_model; - } covariance_estimation; - } covariance; + bool enable{}; + std::vector initial_pose_offset_model{}; + } covariance_estimation{}; + } covariance{}; struct DynamicMapLoading { - double update_distance; - double map_radius; - double lidar_radius; - } dynamic_map_loading; + double update_distance{}; + double map_radius{}; + double lidar_radius{}; + } dynamic_map_loading{}; public: explicit HyperParameters(rclcpp::Node * node) 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 4f8042d106c75..cbd2797c57922 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 @@ -131,8 +131,6 @@ class NDTScanMatcher : public rclcpp::Node static int count_oscillation(const std::vector & result_pose_msg_array); - std::array rotate_covariance( - const std::array & src_covariance, const Eigen::Matrix3d & rotation) const; std::array estimate_covariance( const pclomp::NdtResult & ndt_result, const Eigen::Matrix4f & initial_pose_matrix, const rclcpp::Time & sensor_ros_time); diff --git a/localization/ndt_scan_matcher/src/diagnostics_module.cpp b/localization/ndt_scan_matcher/src/diagnostics_module.cpp index 1e08ebb89f51e..805ee676c5e04 100644 --- a/localization/ndt_scan_matcher/src/diagnostics_module.cpp +++ b/localization/ndt_scan_matcher/src/diagnostics_module.cpp @@ -41,7 +41,7 @@ void DiagnosticsModule::clear() diagnostics_status_msg_.message = ""; } -void DiagnosticsModule::addKeyValue(const diagnostic_msgs::msg::KeyValue & key_value_msg) +void DiagnosticsModule::add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg) { auto it = std::find_if( std::begin(diagnostics_status_msg_.values), std::end(diagnostics_status_msg_.values), @@ -55,24 +55,24 @@ void DiagnosticsModule::addKeyValue(const diagnostic_msgs::msg::KeyValue & key_v } template <> -void DiagnosticsModule::addKeyValue(const std::string & key, const std::string & value) +void DiagnosticsModule::add_key_value(const std::string & key, const std::string & value) { diagnostic_msgs::msg::KeyValue key_value; key_value.key = key; key_value.value = value; - addKeyValue(key_value); + add_key_value(key_value); } template <> -void DiagnosticsModule::addKeyValue(const std::string & key, const bool & value) +void DiagnosticsModule::add_key_value(const std::string & key, const bool & value) { diagnostic_msgs::msg::KeyValue key_value; key_value.key = key; key_value.value = value ? "True" : "False"; - addKeyValue(key_value); + add_key_value(key_value); } -void DiagnosticsModule::updateLevelAndMessage(const int8_t level, const std::string & message) +void DiagnosticsModule::update_level_and_message(const int8_t level, const std::string & message) { if ((level > diagnostic_msgs::msg::DiagnosticStatus::OK)) { if (!diagnostics_status_msg_.message.empty()) { @@ -87,10 +87,10 @@ void DiagnosticsModule::updateLevelAndMessage(const int8_t level, const std::str void DiagnosticsModule::publish(const rclcpp::Time & publish_time_stamp) { - diagnostics_pub_->publish(createDiagnosticsArray(publish_time_stamp)); + diagnostics_pub_->publish(create_diagnostics_array(publish_time_stamp)); } -diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::createDiagnosticsArray( +diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::create_diagnostics_array( const rclcpp::Time & publish_time_stamp) const { diagnostic_msgs::msg::DiagnosticArray diagnostics_msg; diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index 40f0b1f4465fa..32e5a0f2a7c3c 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -53,23 +53,23 @@ void MapUpdateModule::callback_timer( std::unique_ptr & diagnostics_ptr) { // check is_activated - diagnostics_ptr->addKeyValue("is_activated", is_activated); + diagnostics_ptr->add_key_value("is_activated", is_activated); if (!is_activated) { std::stringstream message; message << "Node is not activated."; - diagnostics_ptr->updateLevelAndMessage( + diagnostics_ptr->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return; } // check is_set_last_update_position const bool is_set_last_update_position = (position != std::nullopt); - diagnostics_ptr->addKeyValue("is_set_last_update_position", is_set_last_update_position); + diagnostics_ptr->add_key_value("is_set_last_update_position", is_set_last_update_position); if (!is_set_last_update_position) { std::stringstream message; message << "Cannot find the reference position for map update." << "Please check if the EKF odometry is provided to NDT."; - diagnostics_ptr->updateLevelAndMessage( + diagnostics_ptr->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return; } @@ -92,11 +92,11 @@ bool MapUpdateModule::should_update_map( const double distance = std::hypot(dx, dy); // check distance_last_update_position_to_current_position - diagnostics_ptr->addKeyValue("distance_last_update_position_to_current_position", distance); + diagnostics_ptr->add_key_value("distance_last_update_position_to_current_position", distance); if (distance + param_.lidar_radius > param_.map_radius) { std::stringstream message; message << "Dynamic map loading is not keeping up."; - diagnostics_ptr->updateLevelAndMessage( + diagnostics_ptr->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); // If the map does not keep up with the current position, @@ -110,7 +110,7 @@ bool MapUpdateModule::should_update_map( void MapUpdateModule::update_map( const geometry_msgs::msg::Point & position, std::unique_ptr & diagnostics_ptr) { - diagnostics_ptr->addKeyValue("is_need_rebuild", need_rebuild_); + diagnostics_ptr->add_key_value("is_need_rebuild", need_rebuild_); // If the current position is super far from the previous loading position, // lock and rebuild ndt_ptr_ @@ -130,14 +130,14 @@ void MapUpdateModule::update_map( const bool updated = update_ndt(position, *ndt_ptr_, diagnostics_ptr); // check is_updated_map - diagnostics_ptr->addKeyValue("is_updated_map", updated); + diagnostics_ptr->add_key_value("is_updated_map", updated); if (!updated) { std::stringstream message; message << "update_ndt failed. If this happens with initial position estimation, make sure that" << "(1) the initial position matches the pcd map and (2) the map_loader is working " "properly."; - diagnostics_ptr->updateLevelAndMessage( + diagnostics_ptr->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, message.str()); last_update_position_ = position; @@ -157,7 +157,7 @@ void MapUpdateModule::update_map( const bool updated = update_ndt(position, *secondary_ndt_ptr_, diagnostics_ptr); // check is_updated_map - diagnostics_ptr->addKeyValue("is_updated_map", updated); + diagnostics_ptr->add_key_value("is_updated_map", updated); if (!updated) { last_update_position_ = position; return; @@ -189,7 +189,7 @@ bool MapUpdateModule::update_ndt( const geometry_msgs::msg::Point & position, NdtType & ndt, std::unique_ptr & diagnostics_ptr) { - diagnostics_ptr->addKeyValue("maps_size_before", ndt.getCurrentMapIDs().size()); + diagnostics_ptr->add_key_value("maps_size_before", ndt.getCurrentMapIDs().size()); auto request = std::make_shared(); @@ -199,11 +199,11 @@ bool MapUpdateModule::update_ndt( request->cached_ids = ndt.getCurrentMapIDs(); while (!pcd_loader_client_->wait_for_service(std::chrono::seconds(1)) && rclcpp::ok()) { - diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", false); + diagnostics_ptr->add_key_value("is_succeed_call_pcd_loader", false); std::stringstream message; message << "Waiting for pcd loader service. Check the pointcloud_map_loader."; - diagnostics_ptr->updateLevelAndMessage( + diagnostics_ptr->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; } @@ -217,23 +217,23 @@ bool MapUpdateModule::update_ndt( while (status != std::future_status::ready) { // check is_succeed_call_pcd_loader if (!rclcpp::ok()) { - diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", false); + diagnostics_ptr->add_key_value("is_succeed_call_pcd_loader", false); std::stringstream message; message << "pcd_loader service is not working."; - diagnostics_ptr->updateLevelAndMessage( + diagnostics_ptr->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; // No update } status = result.wait_for(std::chrono::seconds(1)); } - diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", true); + diagnostics_ptr->add_key_value("is_succeed_call_pcd_loader", true); auto & maps_to_add = result.get()->new_pointcloud_with_ids; auto & map_ids_to_remove = result.get()->ids_to_remove; - diagnostics_ptr->addKeyValue("maps_to_add_size", maps_to_add.size()); - diagnostics_ptr->addKeyValue("maps_to_remove_size", map_ids_to_remove.size()); + diagnostics_ptr->add_key_value("maps_to_add_size", maps_to_add.size()); + diagnostics_ptr->add_key_value("maps_to_remove_size", map_ids_to_remove.size()); if (maps_to_add.empty() && map_ids_to_remove.empty()) { return false; // No update @@ -261,9 +261,9 @@ bool MapUpdateModule::update_ndt( const auto duration_micro_sec = std::chrono::duration_cast(exe_end_time - exe_start_time).count(); const auto exe_time = static_cast(duration_micro_sec) / 1000.0; - diagnostics_ptr->addKeyValue("map_update_execution_time", exe_time); - diagnostics_ptr->addKeyValue("maps_size_after", ndt.getCurrentMapIDs().size()); - diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", true); + diagnostics_ptr->add_key_value("map_update_execution_time", exe_time); + diagnostics_ptr->add_key_value("maps_size_after", ndt.getCurrentMapIDs().size()); + diagnostics_ptr->add_key_value("is_succeed_call_pcd_loader", true); return true; // Updated } 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 349f924019c28..c61e243caab31 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -62,6 +62,28 @@ Eigen::Matrix2d find_rotation_matrix_aligning_covariance_to_principal_axes( throw std::runtime_error("Eigen solver failed. Return output_pose_covariance value."); } +std::array rotate_covariance( + const std::array & src_covariance, const Eigen::Matrix3d & rotation) +{ + std::array ret_covariance = src_covariance; + + Eigen::Matrix3d src_cov; + src_cov << src_covariance[0], src_covariance[1], src_covariance[2], src_covariance[6], + src_covariance[7], src_covariance[8], src_covariance[12], src_covariance[13], + src_covariance[14]; + + Eigen::Matrix3d ret_cov; + ret_cov = rotation * src_cov * rotation.transpose(); + + for (Eigen::Index i = 0; i < 3; ++i) { + ret_covariance[i] = ret_cov(0, i); + ret_covariance[i + 6] = ret_cov(1, i); + ret_covariance[i + 12] = ret_cov(2, i); + } + + return ret_covariance; +} + NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) : Node("ndt_scan_matcher", options), tf2_broadcaster_(*this), @@ -197,7 +219,7 @@ void NDTScanMatcher::callback_timer() diagnostics_map_update_->clear(); - diagnostics_map_update_->addKeyValue("timer_callback_time_stamp", ros_time_now.nanoseconds()); + diagnostics_map_update_->add_key_value("timer_callback_time_stamp", ros_time_now.nanoseconds()); map_update_module_->callback_timer(is_activated_, latest_ekf_position_, diagnostics_map_update_); @@ -217,16 +239,16 @@ void NDTScanMatcher::callback_initial_pose( void NDTScanMatcher::callback_initial_pose_main( const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr initial_pose_msg_ptr) { - diagnostics_initial_pose_->addKeyValue( + diagnostics_initial_pose_->add_key_value( "topic_time_stamp", static_cast(initial_pose_msg_ptr->header.stamp).nanoseconds()); // check is_activated - diagnostics_initial_pose_->addKeyValue("is_activated", static_cast(is_activated_)); + diagnostics_initial_pose_->add_key_value("is_activated", static_cast(is_activated_)); if (!is_activated_) { std::stringstream message; message << "Node is not activated."; - diagnostics_initial_pose_->updateLevelAndMessage( + diagnostics_initial_pose_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return; } @@ -234,13 +256,13 @@ void NDTScanMatcher::callback_initial_pose_main( // check is_expected_frame_id const bool is_expected_frame_id = (initial_pose_msg_ptr->header.frame_id == param_.frame.map_frame); - diagnostics_initial_pose_->addKeyValue("is_expected_frame_id", is_expected_frame_id); + diagnostics_initial_pose_->add_key_value("is_expected_frame_id", is_expected_frame_id); if (!is_expected_frame_id) { std::stringstream message; message << "Received initial pose message with frame_id " << initial_pose_msg_ptr->header.frame_id << ", but expected " << param_.frame.map_frame << ". Please check the frame_id in the input topic and ensure it is correct."; - diagnostics_initial_pose_->updateLevelAndMessage( + diagnostics_initial_pose_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); return; } @@ -259,7 +281,7 @@ void NDTScanMatcher::callback_regularization_pose( { diagnostics_regularization_pose_->clear(); - diagnostics_regularization_pose_->addKeyValue( + diagnostics_regularization_pose_->add_key_value( "topic_time_stamp", static_cast(pose_conv_msg_ptr->header.stamp).nanoseconds()); regularization_pose_buffer_->push_back(pose_conv_msg_ptr); @@ -282,11 +304,11 @@ void NDTScanMatcher::callback_sensor_points( const size_t error_skipping_publish_num = 5; skipping_publish_num = ((is_succeed_scan_matching || !is_activated_) ? 0 : (skipping_publish_num + 1)); - diagnostics_scan_points_->addKeyValue("skipping_publish_num", skipping_publish_num); + diagnostics_scan_points_->add_key_value("skipping_publish_num", skipping_publish_num); if (skipping_publish_num >= error_skipping_publish_num) { std::stringstream message; message << "skipping_publish_num exceed limit (" << skipping_publish_num << " times)."; - diagnostics_scan_points_->updateLevelAndMessage( + diagnostics_scan_points_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } @@ -300,15 +322,15 @@ bool NDTScanMatcher::callback_sensor_points_main( // check topic_time_stamp const rclcpp::Time sensor_ros_time = sensor_points_msg_in_sensor_frame->header.stamp; - diagnostics_scan_points_->addKeyValue("topic_time_stamp", sensor_ros_time.nanoseconds()); + diagnostics_scan_points_->add_key_value("topic_time_stamp", sensor_ros_time.nanoseconds()); // check sensor_points_size const size_t sensor_points_size = sensor_points_msg_in_sensor_frame->width; - diagnostics_scan_points_->addKeyValue("sensor_points_size", sensor_points_size); + diagnostics_scan_points_->add_key_value("sensor_points_size", sensor_points_size); if (sensor_points_size == 0) { std::stringstream message; message << "Sensor points is empty."; - diagnostics_scan_points_->updateLevelAndMessage( + diagnostics_scan_points_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; } @@ -316,14 +338,14 @@ bool NDTScanMatcher::callback_sensor_points_main( // check sensor_points_delay_time_sec const double sensor_points_delay_time_sec = (this->now() - sensor_points_msg_in_sensor_frame->header.stamp).seconds(); - diagnostics_scan_points_->addKeyValue( + diagnostics_scan_points_->add_key_value( "sensor_points_delay_time_sec", sensor_points_delay_time_sec); if (sensor_points_delay_time_sec > param_.validation.lidar_topic_timeout_sec) { std::stringstream message; message << "sensor points is experiencing latency." << "The delay time is " << sensor_points_delay_time_sec << "[sec] " << "(the tolerance is " << param_.validation.lidar_topic_timeout_sec << "[sec])."; - diagnostics_scan_points_->updateLevelAndMessage( + diagnostics_scan_points_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); // If the delay time of the LiDAR topic exceeds the delay compensation time of ekf_localizer, @@ -352,13 +374,13 @@ bool NDTScanMatcher::callback_sensor_points_main( std::stringstream message; message << ex.what() << ". Please publish TF " << sensor_frame << " to " << param_.frame.base_frame; - diagnostics_scan_points_->updateLevelAndMessage( + diagnostics_scan_points_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); RCLCPP_ERROR_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); - diagnostics_scan_points_->addKeyValue("is_succeed_transform_sensor_points", false); + diagnostics_scan_points_->add_key_value("is_succeed_transform_sensor_points", false); return false; } - diagnostics_scan_points_->addKeyValue("is_succeed_transform_sensor_points", true); + diagnostics_scan_points_->add_key_value("is_succeed_transform_sensor_points", true); // check sensor_points_max_distance double max_distance = 0.0; @@ -367,12 +389,12 @@ bool NDTScanMatcher::callback_sensor_points_main( max_distance = std::max(max_distance, distance); } - diagnostics_scan_points_->addKeyValue("sensor_points_max_distance", max_distance); + diagnostics_scan_points_->add_key_value("sensor_points_max_distance", max_distance); if (max_distance < param_.sensor_points.required_distance) { std::stringstream message; message << "Max distance of sensor points = " << std::fixed << std::setprecision(3) << max_distance << " [m] < " << param_.sensor_points.required_distance << " [m]"; - diagnostics_scan_points_->updateLevelAndMessage( + diagnostics_scan_points_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; } @@ -384,11 +406,11 @@ bool NDTScanMatcher::callback_sensor_points_main( ndt_ptr_->setInputSource(sensor_points_in_baselink_frame); // check is_activated - diagnostics_scan_points_->addKeyValue("is_activated", static_cast(is_activated_)); + diagnostics_scan_points_->add_key_value("is_activated", static_cast(is_activated_)); if (!is_activated_) { std::stringstream message; message << "Node is not activated."; - diagnostics_scan_points_->updateLevelAndMessage( + diagnostics_scan_points_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; } @@ -399,12 +421,12 @@ bool NDTScanMatcher::callback_sensor_points_main( // check is_succeed_interpolate_initial_pose const bool is_succeed_interpolate_initial_pose = (interpolation_result_opt != std::nullopt); - diagnostics_scan_points_->addKeyValue( + diagnostics_scan_points_->add_key_value( "is_succeed_interpolate_initial_pose", is_succeed_interpolate_initial_pose); if (!is_succeed_interpolate_initial_pose) { std::stringstream message; message << "Couldn't interpolate pose. Please check the initial pose topic"; - diagnostics_scan_points_->updateLevelAndMessage( + diagnostics_scan_points_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; } @@ -420,11 +442,11 @@ bool NDTScanMatcher::callback_sensor_points_main( // check is_set_map_points const bool is_set_map_points = (ndt_ptr_->getInputTarget() != nullptr); - diagnostics_scan_points_->addKeyValue("is_set_map_points", is_set_map_points); + diagnostics_scan_points_->add_key_value("is_set_map_points", is_set_map_points); if (!is_set_map_points) { std::stringstream message; message << "Map points is not set."; - diagnostics_scan_points_->updateLevelAndMessage( + diagnostics_scan_points_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; } @@ -444,31 +466,33 @@ bool NDTScanMatcher::callback_sensor_points_main( } // check iteration_num - diagnostics_scan_points_->addKeyValue("iteration_num", ndt_result.iteration_num); + diagnostics_scan_points_->add_key_value("iteration_num", ndt_result.iteration_num); const bool is_ok_iteration_num = (ndt_result.iteration_num < ndt_ptr_->getMaximumIterations()); if (!is_ok_iteration_num) { std::stringstream message; message << "The number of iterations has reached its upper limit. The number of iterations: " << ndt_result.iteration_num << ", Limit: " << ndt_ptr_->getMaximumIterations() << "."; - diagnostics_scan_points_->updateLevelAndMessage( + diagnostics_scan_points_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } // check local_optimal_solution_oscillation_num constexpr int oscillation_num_threshold = 10; const int oscillation_num = count_oscillation(transformation_msg_array); - diagnostics_scan_points_->addKeyValue("local_optimal_solution_oscillation_num", oscillation_num); + diagnostics_scan_points_->add_key_value( + "local_optimal_solution_oscillation_num", oscillation_num); const bool is_local_optimal_solution_oscillation = (oscillation_num > oscillation_num_threshold); if (is_local_optimal_solution_oscillation) { std::stringstream message; message << "There is a possibility of oscillation in a local minimum"; - diagnostics_scan_points_->updateLevelAndMessage( + diagnostics_scan_points_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } // check score - diagnostics_scan_points_->addKeyValue("transform_probability", ndt_result.transform_probability); - diagnostics_scan_points_->addKeyValue( + diagnostics_scan_points_->add_key_value( + "transform_probability", ndt_result.transform_probability); + diagnostics_scan_points_->add_key_value( "nearest_voxel_transformation_likelihood", ndt_result.nearest_voxel_transformation_likelihood); double score = 0.0; double score_threshold = 0.0; @@ -484,7 +508,7 @@ bool NDTScanMatcher::callback_sensor_points_main( } else { std::stringstream message; message << "Unknown converged param type. Please check `score_estimation.converged_param_type`"; - diagnostics_scan_points_->updateLevelAndMessage( + diagnostics_scan_points_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); return false; } @@ -526,7 +550,7 @@ bool NDTScanMatcher::callback_sensor_points_main( std::stringstream message; message << "Score is below the threshold. Score: " << score << ", Threshold: " << score_threshold; - diagnostics_scan_points_->updateLevelAndMessage( + diagnostics_scan_points_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); RCLCPP_WARN_STREAM(this->get_logger(), message.str()); } @@ -553,13 +577,13 @@ bool NDTScanMatcher::callback_sensor_points_main( // check distance_initial_to_result const auto distance_initial_to_result = static_cast( norm(interpolation_result.interpolated_pose.pose.pose.position, result_pose_msg.position)); - diagnostics_scan_points_->addKeyValue("distance_initial_to_result", distance_initial_to_result); + diagnostics_scan_points_->add_key_value("distance_initial_to_result", distance_initial_to_result); const double warn_distance_initial_to_result = 3.0; if (distance_initial_to_result > warn_distance_initial_to_result) { std::stringstream message; message << "distance_initial_to_result is too large (" << distance_initial_to_result << " [m])."; - diagnostics_scan_points_->updateLevelAndMessage( + diagnostics_scan_points_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } @@ -568,11 +592,11 @@ bool NDTScanMatcher::callback_sensor_points_main( const auto duration_micro_sec = std::chrono::duration_cast(exe_end_time - exe_start_time).count(); const auto exe_time = static_cast(duration_micro_sec) / 1000.0f; - diagnostics_scan_points_->addKeyValue("execution_time", exe_time); + diagnostics_scan_points_->add_key_value("execution_time", exe_time); if (exe_time > param_.validation.critical_upper_bound_exe_time_ms) { std::stringstream message; message << "NDT exe time is too long (took " << exe_time << " [ms])."; - diagnostics_scan_points_->updateLevelAndMessage( + diagnostics_scan_points_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } @@ -644,7 +668,7 @@ void NDTScanMatcher::transform_sensor_measurement( geometry_msgs::msg::TransformStamped transform; try { transform = tf2_buffer_.lookupTransform(target_frame, source_frame, tf2::TimePointZero); - } catch (tf2::TransformException & ex) { + } catch (const tf2::TransformException & ex) { throw; } @@ -785,28 +809,6 @@ int NDTScanMatcher::count_oscillation( return max_oscillation_cnt; } -std::array NDTScanMatcher::rotate_covariance( - const std::array & src_covariance, const Eigen::Matrix3d & rotation) const -{ - std::array ret_covariance = src_covariance; - - Eigen::Matrix3d src_cov; - src_cov << src_covariance[0], src_covariance[1], src_covariance[2], src_covariance[6], - src_covariance[7], src_covariance[8], src_covariance[12], src_covariance[13], - src_covariance[14]; - - Eigen::Matrix3d ret_cov; - ret_cov = rotation * src_cov * rotation.transpose(); - - for (Eigen::Index i = 0; i < 3; ++i) { - ret_covariance[i] = ret_cov(0, i); - ret_covariance[i + 6] = ret_cov(1, i); - ret_covariance[i + 12] = ret_cov(2, i); - } - - return ret_covariance; -} - std::array NDTScanMatcher::estimate_covariance( const pclomp::NdtResult & ndt_result, const Eigen::Matrix4f & initial_pose_matrix, const rclcpp::Time & sensor_ros_time) @@ -906,7 +908,7 @@ void NDTScanMatcher::service_trigger_node( const rclcpp::Time ros_time_now = this->now(); diagnostics_trigger_node_->clear(); - diagnostics_trigger_node_->addKeyValue("service_call_time_stamp", ros_time_now.nanoseconds()); + diagnostics_trigger_node_->add_key_value("service_call_time_stamp", ros_time_now.nanoseconds()); is_activated_ = req->data; if (is_activated_) { @@ -914,8 +916,8 @@ void NDTScanMatcher::service_trigger_node( } res->success = true; - diagnostics_trigger_node_->addKeyValue("is_activated", static_cast(is_activated_)); - diagnostics_trigger_node_->addKeyValue("is_succeed_service", res->success); + diagnostics_trigger_node_->add_key_value("is_activated", static_cast(is_activated_)); + diagnostics_trigger_node_->add_key_value("is_succeed_service", res->success); diagnostics_trigger_node_->publish(ros_time_now); } @@ -927,17 +929,17 @@ void NDTScanMatcher::service_ndt_align( diagnostics_ndt_align_->clear(); - diagnostics_ndt_align_->addKeyValue("service_call_time_stamp", ros_time_now.nanoseconds()); + diagnostics_ndt_align_->add_key_value("service_call_time_stamp", ros_time_now.nanoseconds()); service_ndt_align_main(req, res); // check is_succeed_service bool is_succeed_service = res->success; - diagnostics_ndt_align_->addKeyValue("is_succeed_service", is_succeed_service); + diagnostics_ndt_align_->add_key_value("is_succeed_service", is_succeed_service); if (!is_succeed_service) { std::stringstream message; message << "ndt_align_service is failed."; - diagnostics_ndt_align_->updateLevelAndMessage( + diagnostics_ndt_align_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } @@ -960,17 +962,17 @@ void NDTScanMatcher::service_ndt_align_main( // "gnss_link" instead of "map". The ndt_align is designed to return identity when this issue // occurs. However, in the future, converting to a non-existent frame_id should be prohibited. - diagnostics_ndt_align_->addKeyValue("is_succeed_transform_initial_pose", false); + diagnostics_ndt_align_->add_key_value("is_succeed_transform_initial_pose", false); std::stringstream message; message << "Please publish TF " << target_frame.c_str() << " to " << source_frame.c_str(); - diagnostics_ndt_align_->updateLevelAndMessage( + diagnostics_ndt_align_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); RCLCPP_ERROR_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); res->success = false; return; } - diagnostics_ndt_align_->addKeyValue("is_succeed_transform_initial_pose", true); + diagnostics_ndt_align_->add_key_value("is_succeed_transform_initial_pose", true); // transform pose_frame to map_frame const auto initial_pose_msg_in_map_frame = transform(req->pose_with_covariance, transform_s2t); @@ -982,11 +984,11 @@ void NDTScanMatcher::service_ndt_align_main( // check is_set_map_points bool is_set_map_points = (ndt_ptr_->getInputTarget() != nullptr); - diagnostics_ndt_align_->addKeyValue("is_set_map_points", is_set_map_points); + diagnostics_ndt_align_->add_key_value("is_set_map_points", is_set_map_points); if (!is_set_map_points) { std::stringstream message; message << "No InputTarget. Please check the map file and the map_loader service"; - diagnostics_ndt_align_->updateLevelAndMessage( + diagnostics_ndt_align_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); res->success = false; @@ -995,11 +997,11 @@ void NDTScanMatcher::service_ndt_align_main( // check is_set_sensor_points bool is_set_sensor_points = (ndt_ptr_->getInputSource() != nullptr); - diagnostics_ndt_align_->addKeyValue("is_set_sensor_points", is_set_sensor_points); + diagnostics_ndt_align_->add_key_value("is_set_sensor_points", is_set_sensor_points); if (!is_set_sensor_points) { std::stringstream message; message << "No InputSource. Please check the input lidar topic"; - diagnostics_ndt_align_->updateLevelAndMessage( + diagnostics_ndt_align_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); res->success = false; @@ -1107,7 +1109,7 @@ geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_pose( result_pose_with_cov_msg.pose.pose = best_particle_ptr->result_pose; output_pose_with_cov_to_log(get_logger(), "align_pose_output", result_pose_with_cov_msg); - diagnostics_ndt_align_->addKeyValue("best_particle_score", best_particle_ptr->score); + diagnostics_ndt_align_->add_key_value("best_particle_score", best_particle_ptr->score); return result_pose_with_cov_msg; } diff --git a/localization/ndt_scan_matcher/test/test_util.hpp b/localization/ndt_scan_matcher/test/test_util.hpp index 2f78827abf891..dbf055d3c95d3 100644 --- a/localization/ndt_scan_matcher/test/test_util.hpp +++ b/localization/ndt_scan_matcher/test/test_util.hpp @@ -15,8 +15,13 @@ #ifndef TEST_UTIL_HPP_ #define TEST_UTIL_HPP_ +#include +#include + +#include #include #include +#include inline pcl::PointCloud make_sample_half_cubic_pcd() { From d227f7c87f2df54a553bbd1570d09ac65e1ec40e Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Mon, 10 Jun 2024 16:00:33 +0900 Subject: [PATCH 59/65] refactor(ekf localizer): apply static analysis (#7324) * rename to snake_case Signed-off-by: Yamato Ando * add nodiscard Signed-off-by: Yamato Ando * initilize variables Signed-off-by: Yamato Ando * fix math.h to cmath Signed-off-by: Yamato Ando * fix data type Signed-off-by: Yamato Ando * remove redundant return statement Signed-off-by: Yamato Ando * add &, remove t_curr Signed-off-by: Yamato Ando * fix string empty Signed-off-by: Yamato Ando * fix data type Signed-off-by: Yamato Ando * remove unused variable Signed-off-by: Yamato Ando * readability-else-after-return Signed-off-by: Yamato Ando * add nolint Signed-off-by: Yamato Ando * rename varibles Signed-off-by: Yamato Ando * fix cast Signed-off-by: Yamato Ando * style(pre-commit): autofix --------- Signed-off-by: Yamato Ando Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: SakodaShintaro --- .../ekf_localizer/aged_object_queue.hpp | 14 +- .../include/ekf_localizer/covariance.hpp | 4 +- .../include/ekf_localizer/diagnostics.hpp | 12 +- .../include/ekf_localizer/ekf_localizer.hpp | 49 +++-- .../include/ekf_localizer/ekf_module.hpp | 48 ++--- .../ekf_localizer/hyper_parameters.hpp | 6 +- .../include/ekf_localizer/mahalanobis.hpp | 2 +- .../include/ekf_localizer/measurement.hpp | 8 +- .../include/ekf_localizer/numeric.hpp | 4 +- .../ekf_localizer/state_transition.hpp | 8 +- .../include/ekf_localizer/string.hpp | 2 +- .../include/ekf_localizer/warning.hpp | 2 +- .../include/ekf_localizer/warning_message.hpp | 11 +- localization/ekf_localizer/src/covariance.cpp | 8 +- .../ekf_localizer/src/diagnostics.cpp | 12 +- .../ekf_localizer/src/ekf_localizer.cpp | 143 ++++++------- localization/ekf_localizer/src/ekf_module.cpp | 190 +++++++++--------- .../ekf_localizer/src/mahalanobis.cpp | 4 +- .../ekf_localizer/src/measurement.cpp | 38 ++-- .../ekf_localizer/src/state_transition.cpp | 58 +++--- .../ekf_localizer/src/warning_message.cpp | 12 +- .../ekf_localizer/test/test_covariance.cpp | 42 ++-- .../ekf_localizer/test/test_diagnostics.cpp | 54 ++--- .../ekf_localizer/test/test_mahalanobis.cpp | 28 +-- .../ekf_localizer/test/test_measurement.cpp | 36 ++-- .../ekf_localizer/test/test_numeric.cpp | 24 +-- .../test/test_state_transition.cpp | 69 +++---- .../ekf_localizer/test/test_string.cpp | 10 +- .../test/test_warning_message.cpp | 24 +-- 29 files changed, 458 insertions(+), 464 deletions(-) diff --git a/localization/ekf_localizer/include/ekf_localizer/aged_object_queue.hpp b/localization/ekf_localizer/include/ekf_localizer/aged_object_queue.hpp index 737c25f8ce024..880ab82418e06 100644 --- a/localization/ekf_localizer/include/ekf_localizer/aged_object_queue.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/aged_object_queue.hpp @@ -22,11 +22,11 @@ template class AgedObjectQueue { public: - explicit AgedObjectQueue(const int max_age) : max_age_(max_age) {} + explicit AgedObjectQueue(const size_t max_age) : max_age_(max_age) {} - bool empty() const { return this->size() == 0; } + [[nodiscard]] bool empty() const { return this->size() == 0; } - size_t size() const { return objects_.size(); } + [[nodiscard]] size_t size() const { return objects_.size(); } Object back() const { return objects_.back(); } @@ -39,7 +39,7 @@ class AgedObjectQueue Object pop_increment_age() { const Object object = objects_.front(); - const int age = ages_.front() + 1; + const size_t age = ages_.front() + 1; objects_.pop(); ages_.pop(); @@ -54,13 +54,13 @@ class AgedObjectQueue void clear() { objects_ = std::queue(); - ages_ = std::queue(); + ages_ = std::queue(); } private: - const int max_age_; + const size_t max_age_; std::queue objects_; - std::queue ages_; + std::queue ages_; }; #endif // EKF_LOCALIZER__AGED_OBJECT_QUEUE_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/covariance.hpp b/localization/ekf_localizer/include/ekf_localizer/covariance.hpp index a4448ecda2f45..713877c1307d2 100644 --- a/localization/ekf_localizer/include/ekf_localizer/covariance.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/covariance.hpp @@ -17,7 +17,7 @@ #include "ekf_localizer/matrix_types.hpp" -std::array ekfCovarianceToPoseMessageCovariance(const Matrix6d & P); -std::array ekfCovarianceToTwistMessageCovariance(const Matrix6d & P); +std::array ekf_covariance_to_pose_message_covariance(const Matrix6d & P); +std::array ekf_covariance_to_twist_message_covariance(const Matrix6d & P); #endif // EKF_LOCALIZER__COVARIANCE_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp b/localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp index f4dc6436f6a40..4c92b2947642b 100644 --- a/localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp @@ -20,21 +20,21 @@ #include #include -diagnostic_msgs::msg::DiagnosticStatus checkProcessActivated(const bool is_activated); +diagnostic_msgs::msg::DiagnosticStatus check_process_activated(const bool is_activated); -diagnostic_msgs::msg::DiagnosticStatus checkMeasurementUpdated( +diagnostic_msgs::msg::DiagnosticStatus check_measurement_updated( const std::string & measurement_type, const size_t no_update_count, const size_t no_update_count_threshold_warn, const size_t no_update_count_threshold_error); -diagnostic_msgs::msg::DiagnosticStatus checkMeasurementQueueSize( +diagnostic_msgs::msg::DiagnosticStatus check_measurement_queue_size( const std::string & measurement_type, const size_t queue_size); -diagnostic_msgs::msg::DiagnosticStatus checkMeasurementDelayGate( +diagnostic_msgs::msg::DiagnosticStatus check_measurement_delay_gate( const std::string & measurement_type, const bool is_passed_delay_gate, const double delay_time, const double delay_time_threshold); -diagnostic_msgs::msg::DiagnosticStatus checkMeasurementMahalanobisGate( +diagnostic_msgs::msg::DiagnosticStatus check_measurement_mahalanobis_gate( const std::string & measurement_type, const bool is_passed_mahalanobis_gate, const double mahalanobis_distance, const double mahalanobis_distance_threshold); -diagnostic_msgs::msg::DiagnosticStatus mergeDiagnosticStatus( +diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status( const std::vector & stat_array); #endif // EKF_LOCALIZER__DIAGNOSTICS_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index 8ed925c1bc228..b78e9b1ee0469 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -58,17 +58,15 @@ class Simple1DFilter x_ = 0; dev_ = 1e9; proc_dev_x_c_ = 0.0; - return; }; - void init(const double init_obs, const double obs_dev, const rclcpp::Time time) + void init(const double init_obs, const double obs_dev, const rclcpp::Time & time) { x_ = init_obs; dev_ = obs_dev; latest_time_ = time; initialized_ = true; - return; }; - void update(const double obs, const double obs_dev, const rclcpp::Time time) + void update(const double obs, const double obs_dev, const rclcpp::Time & time) { if (!initialized_) { init(obs, obs_dev, time); @@ -86,10 +84,9 @@ class Simple1DFilter dev_ = (1 - kalman_gain) * dev_; latest_time_ = time; - return; }; void set_proc_dev(const double proc_dev) { proc_dev_x_c_ = proc_dev; } - double get_x() const { return x_; } + [[nodiscard]] double get_x() const { return x_; } private: bool initialized_; @@ -158,10 +155,9 @@ class EKFLocalizer : public rclcpp::Node double ekf_dt_; /* process noise variance for discrete model */ - double proc_cov_yaw_d_; //!< @brief discrete yaw process noise - double proc_cov_yaw_bias_d_; //!< @brief discrete yaw bias process noise - double proc_cov_vx_d_; //!< @brief discrete process noise in d_vx=0 - double proc_cov_wz_d_; //!< @brief discrete process noise in d_wz=0 + double proc_cov_yaw_d_; //!< @brief discrete yaw process noise + double proc_cov_vx_d_; //!< @brief discrete process noise in d_vx=0 + double proc_cov_wz_d_; //!< @brief discrete process noise in d_wz=0 bool is_activated_; @@ -174,44 +170,45 @@ class EKFLocalizer : public rclcpp::Node /** * @brief computes update & prediction of EKF for each ekf_dt_[s] time */ - void timerCallback(); + void timer_callback(); /** * @brief publish tf for tf_rate [Hz] */ - void timerTFCallback(); + void timer_tf_callback(); /** - * @brief set poseWithCovariance measurement + * @brief set pose with covariance measurement */ - void callbackPoseWithCovariance(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); + void callback_pose_with_covariance(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); /** - * @brief set twistWithCovariance measurement + * @brief set twist with covariance measurement */ - void callbackTwistWithCovariance(geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg); + void callback_twist_with_covariance( + geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg); /** * @brief set initial_pose to current EKF pose */ - void callbackInitialPose(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); + void callback_initial_pose(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); /** * @brief update predict frequency */ - void updatePredictFrequency(const rclcpp::Time & current_time); + void update_predict_frequency(const rclcpp::Time & current_time); /** * @brief get transform from frame_id */ - bool getTransformFromTF( + bool get_transform_from_tf( std::string parent_frame, std::string child_frame, geometry_msgs::msg::TransformStamped & transform); /** * @brief publish current EKF estimation result */ - void publishEstimateResult( + void publish_estimate_result( const geometry_msgs::msg::PoseStamped & current_ekf_pose, const geometry_msgs::msg::PoseStamped & current_biased_ekf_pose, const geometry_msgs::msg::TwistStamped & current_ekf_twist); @@ -219,23 +216,23 @@ class EKFLocalizer : public rclcpp::Node /** * @brief publish diagnostics message */ - void publishDiagnostics(const rclcpp::Time & current_time); + void publish_diagnostics(const rclcpp::Time & current_time); /** - * @brief update simple1DFilter + * @brief update simple 1d filter */ - void updateSimple1DFilters( + void update_simple_1d_filters( const geometry_msgs::msg::PoseWithCovarianceStamped & pose, const size_t smoothing_step); /** - * @brief initialize simple1DFilter + * @brief initialize simple 1d filter */ - void initSimple1DFilters(const geometry_msgs::msg::PoseWithCovarianceStamped & pose); + void init_simple_1d_filters(const geometry_msgs::msg::PoseWithCovarianceStamped & pose); /** * @brief trigger node */ - void serviceTriggerNode( + void service_trigger_node( const std_srvs::srv::SetBool::Request::SharedPtr req, std_srvs::srv::SetBool::Response::SharedPtr res); diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp index e88a59ffdfab9..ee360e798f492 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp @@ -34,24 +34,13 @@ struct EKFDiagnosticInfo { - EKFDiagnosticInfo() - : no_update_count(0), - queue_size(0), - is_passed_delay_gate(true), - delay_time(0), - delay_time_threshold(0), - is_passed_mahalanobis_gate(true), - mahalanobis_distance(0) - { - } - - size_t no_update_count; - size_t queue_size; - bool is_passed_delay_gate; - double delay_time; - double delay_time_threshold; - bool is_passed_mahalanobis_gate; - double mahalanobis_distance; + size_t no_update_count{0}; + size_t queue_size{0}; + bool is_passed_delay_gate{true}; + double delay_time{0.0}; + double delay_time_threshold{0.0}; + bool is_passed_mahalanobis_gate{true}; + double mahalanobis_distance{0.0}; }; class EKFModule @@ -63,31 +52,32 @@ class EKFModule using Twist = geometry_msgs::msg::TwistStamped; public: - EKFModule(std::shared_ptr warning, const HyperParameters params); + EKFModule(std::shared_ptr warning, const HyperParameters & params); void initialize( const PoseWithCovariance & initial_pose, const geometry_msgs::msg::TransformStamped & transform); - geometry_msgs::msg::PoseStamped getCurrentPose( + [[nodiscard]] geometry_msgs::msg::PoseStamped get_current_pose( const rclcpp::Time & current_time, const double z, const double roll, const double pitch, bool get_biased_yaw) const; - geometry_msgs::msg::TwistStamped getCurrentTwist(const rclcpp::Time & current_time) const; - double getYawBias() const; - std::array getCurrentPoseCovariance() const; - std::array getCurrentTwistCovariance() const; + [[nodiscard]] geometry_msgs::msg::TwistStamped get_current_twist( + const rclcpp::Time & current_time) const; + [[nodiscard]] double get_yaw_bias() const; + [[nodiscard]] std::array get_current_pose_covariance() const; + [[nodiscard]] std::array get_current_twist_covariance() const; - size_t find_closest_delay_time_index(double target_value) const; + [[nodiscard]] size_t find_closest_delay_time_index(double target_value) const; void accumulate_delay_time(const double dt); - void predictWithDelay(const double dt); - bool measurementUpdatePose( + void predict_with_delay(const double dt); + bool measurement_update_pose( const PoseWithCovariance & pose, const rclcpp::Time & t_curr, EKFDiagnosticInfo & pose_diag_info); - bool measurementUpdateTwist( + bool measurement_update_twist( const TwistWithCovariance & twist, const rclcpp::Time & t_curr, EKFDiagnosticInfo & twist_diag_info); - geometry_msgs::msg::PoseWithCovarianceStamped compensatePoseWithZDelay( + geometry_msgs::msg::PoseWithCovarianceStamped compensate_pose_with_z_delay( const PoseWithCovariance & pose, const double delay_time); private: diff --git a/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp b/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp index 56a13d1ecaf55..8d76102e5d64d 100644 --- a/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp @@ -68,14 +68,14 @@ class HyperParameters const double tf_rate_; const bool publish_tf_; const bool enable_yaw_bias_estimation; - const int extend_state_step; + const size_t extend_state_step; const std::string pose_frame_id; const double pose_additional_delay; const double pose_gate_dist; - const int pose_smoothing_steps; + const size_t pose_smoothing_steps; const double twist_additional_delay; const double twist_gate_dist; - const int twist_smoothing_steps; + const size_t twist_smoothing_steps; const double proc_stddev_vx_c; //!< @brief vx process noise const double proc_stddev_wz_c; //!< @brief wz process noise const double proc_stddev_yaw_c; //!< @brief yaw process noise diff --git a/localization/ekf_localizer/include/ekf_localizer/mahalanobis.hpp b/localization/ekf_localizer/include/ekf_localizer/mahalanobis.hpp index f2b9dc626e67a..1f0d75c5958d4 100644 --- a/localization/ekf_localizer/include/ekf_localizer/mahalanobis.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/mahalanobis.hpp @@ -18,7 +18,7 @@ #include #include -double squaredMahalanobis( +double squared_mahalanobis( const Eigen::VectorXd & x, const Eigen::VectorXd & y, const Eigen::MatrixXd & C); double mahalanobis(const Eigen::VectorXd & x, const Eigen::VectorXd & y, const Eigen::MatrixXd & C); diff --git a/localization/ekf_localizer/include/ekf_localizer/measurement.hpp b/localization/ekf_localizer/include/ekf_localizer/measurement.hpp index 4b2169f1b182f..396aaf7b9a1b4 100644 --- a/localization/ekf_localizer/include/ekf_localizer/measurement.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/measurement.hpp @@ -17,11 +17,11 @@ #include -Eigen::Matrix poseMeasurementMatrix(); -Eigen::Matrix twistMeasurementMatrix(); -Eigen::Matrix3d poseMeasurementCovariance( +Eigen::Matrix pose_measurement_matrix(); +Eigen::Matrix twist_measurement_matrix(); +Eigen::Matrix3d pose_measurement_covariance( const std::array & covariance, const size_t smoothing_step); -Eigen::Matrix2d twistMeasurementCovariance( +Eigen::Matrix2d twist_measurement_covariance( const std::array & covariance, const size_t smoothing_step); #endif // EKF_LOCALIZER__MEASUREMENT_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/numeric.hpp b/localization/ekf_localizer/include/ekf_localizer/numeric.hpp index 6554f80aee014..358a2750bd3a8 100644 --- a/localization/ekf_localizer/include/ekf_localizer/numeric.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/numeric.hpp @@ -19,12 +19,12 @@ #include -inline bool hasInf(const Eigen::MatrixXd & v) +inline bool has_inf(const Eigen::MatrixXd & v) { return v.array().isInf().any(); } -inline bool hasNan(const Eigen::MatrixXd & v) +inline bool has_nan(const Eigen::MatrixXd & v) { return v.array().isNaN().any(); } diff --git a/localization/ekf_localizer/include/ekf_localizer/state_transition.hpp b/localization/ekf_localizer/include/ekf_localizer/state_transition.hpp index 85a65828e4ee4..09a87e5fe154b 100644 --- a/localization/ekf_localizer/include/ekf_localizer/state_transition.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/state_transition.hpp @@ -17,10 +17,10 @@ #include "ekf_localizer/matrix_types.hpp" -double normalizeYaw(const double & yaw); -Vector6d predictNextState(const Vector6d & X_curr, const double dt); -Matrix6d createStateTransitionMatrix(const Vector6d & X_curr, const double dt); -Matrix6d processNoiseCovariance( +double normalize_yaw(const double & yaw); +Vector6d predict_next_state(const Vector6d & X_curr, const double dt); +Matrix6d create_state_transition_matrix(const Vector6d & X_curr, const double dt); +Matrix6d process_noise_covariance( const double proc_cov_yaw_d, const double proc_cov_vx_d, const double proc_cov_wz_d); #endif // EKF_LOCALIZER__STATE_TRANSITION_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/string.hpp b/localization/ekf_localizer/include/ekf_localizer/string.hpp index a4cd1f320367c..0154e84b88004 100644 --- a/localization/ekf_localizer/include/ekf_localizer/string.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/string.hpp @@ -17,7 +17,7 @@ #include -inline std::string eraseLeadingSlash(const std::string & s) +inline std::string erase_leading_slash(const std::string & s) { std::string a = s; if (a.front() == '/') { diff --git a/localization/ekf_localizer/include/ekf_localizer/warning.hpp b/localization/ekf_localizer/include/ekf_localizer/warning.hpp index a3c8800242e2b..e7456d73ecfdd 100644 --- a/localization/ekf_localizer/include/ekf_localizer/warning.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/warning.hpp @@ -29,7 +29,7 @@ class Warning RCLCPP_WARN(node_->get_logger(), "%s", message.c_str()); } - void warnThrottle(const std::string & message, const int duration_milliseconds) const + void warn_throttle(const std::string & message, const int duration_milliseconds) const { RCLCPP_WARN_THROTTLE( node_->get_logger(), *(node_->get_clock()), diff --git a/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp b/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp index e1eafdc6f7948..36c0eabd588fa 100644 --- a/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/warning_message.hpp @@ -17,11 +17,12 @@ #include -std::string poseDelayStepWarningMessage(const double delay_time, const double delay_time_threshold); -std::string twistDelayStepWarningMessage( +std::string pose_delay_step_warning_message( const double delay_time, const double delay_time_threshold); -std::string poseDelayTimeWarningMessage(const double delay_time); -std::string twistDelayTimeWarningMessage(const double delay_time); -std::string mahalanobisWarningMessage(const double distance, const double max_distance); +std::string twist_delay_step_warning_message( + const double delay_time, const double delay_time_threshold); +std::string pose_delay_time_warning_message(const double delay_time); +std::string twist_delay_time_warning_message(const double delay_time); +std::string mahalanobis_warning_message(const double distance, const double max_distance); #endif // EKF_LOCALIZER__WARNING_MESSAGE_HPP_ diff --git a/localization/ekf_localizer/src/covariance.cpp b/localization/ekf_localizer/src/covariance.cpp index 0c98ac6857ea5..fc16abf429d93 100644 --- a/localization/ekf_localizer/src/covariance.cpp +++ b/localization/ekf_localizer/src/covariance.cpp @@ -19,9 +19,9 @@ using COV_IDX = tier4_autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; -std::array ekfCovarianceToPoseMessageCovariance(const Matrix6d & P) +std::array ekf_covariance_to_pose_message_covariance(const Matrix6d & P) { - std::array covariance; + std::array covariance{}; covariance.fill(0.); covariance[COV_IDX::X_X] = P(IDX::X, IDX::X); @@ -37,9 +37,9 @@ std::array ekfCovarianceToPoseMessageCovariance(const Matrix6d & P) return covariance; } -std::array ekfCovarianceToTwistMessageCovariance(const Matrix6d & P) +std::array ekf_covariance_to_twist_message_covariance(const Matrix6d & P) { - std::array covariance; + std::array covariance{}; covariance.fill(0.); covariance[COV_IDX::X_X] = P(IDX::VX, IDX::VX); diff --git a/localization/ekf_localizer/src/diagnostics.cpp b/localization/ekf_localizer/src/diagnostics.cpp index 9ff36561abaa9..ecbeaf8b2445a 100644 --- a/localization/ekf_localizer/src/diagnostics.cpp +++ b/localization/ekf_localizer/src/diagnostics.cpp @@ -19,7 +19,7 @@ #include #include -diagnostic_msgs::msg::DiagnosticStatus checkProcessActivated(const bool is_activated) +diagnostic_msgs::msg::DiagnosticStatus check_process_activated(const bool is_activated) { diagnostic_msgs::msg::DiagnosticStatus stat; @@ -38,7 +38,7 @@ diagnostic_msgs::msg::DiagnosticStatus checkProcessActivated(const bool is_activ return stat; } -diagnostic_msgs::msg::DiagnosticStatus checkMeasurementUpdated( +diagnostic_msgs::msg::DiagnosticStatus check_measurement_updated( const std::string & measurement_type, const size_t no_update_count, const size_t no_update_count_threshold_warn, const size_t no_update_count_threshold_error) { @@ -69,7 +69,7 @@ diagnostic_msgs::msg::DiagnosticStatus checkMeasurementUpdated( return stat; } -diagnostic_msgs::msg::DiagnosticStatus checkMeasurementQueueSize( +diagnostic_msgs::msg::DiagnosticStatus check_measurement_queue_size( const std::string & measurement_type, const size_t queue_size) { diagnostic_msgs::msg::DiagnosticStatus stat; @@ -85,7 +85,7 @@ diagnostic_msgs::msg::DiagnosticStatus checkMeasurementQueueSize( return stat; } -diagnostic_msgs::msg::DiagnosticStatus checkMeasurementDelayGate( +diagnostic_msgs::msg::DiagnosticStatus check_measurement_delay_gate( const std::string & measurement_type, const bool is_passed_delay_gate, const double delay_time, const double delay_time_threshold) { @@ -112,7 +112,7 @@ diagnostic_msgs::msg::DiagnosticStatus checkMeasurementDelayGate( return stat; } -diagnostic_msgs::msg::DiagnosticStatus checkMeasurementMahalanobisGate( +diagnostic_msgs::msg::DiagnosticStatus check_measurement_mahalanobis_gate( const std::string & measurement_type, const bool is_passed_mahalanobis_gate, const double mahalanobis_distance, const double mahalanobis_distance_threshold) { @@ -141,7 +141,7 @@ diagnostic_msgs::msg::DiagnosticStatus checkMeasurementMahalanobisGate( // The highest level within the stat_array will be reflected in the merged_stat. // When all stat_array entries are 'OK,' the message of merged_stat will be "OK" -diagnostic_msgs::msg::DiagnosticStatus mergeDiagnosticStatus( +diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status( const std::vector & stat_array) { diagnostic_msgs::msg::DiagnosticStatus merged_stat; diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 687e812679574..8e7121ec73a12 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -34,8 +34,8 @@ #include // clang-format off -#define PRINT_MAT(X) std::cout << #X << ":\n" << X << std::endl << std::endl -#define DEBUG_INFO(...) {if (params_.show_debug_info) {RCLCPP_INFO(__VA_ARGS__);}} +#define PRINT_MAT(X) std::cout << #X << ":\n" << X << std::endl << std::endl // NOLINT +#define DEBUG_INFO(...) {if (params_.show_debug_info) {RCLCPP_INFO(__VA_ARGS__);}} // NOLINT // clang-format on using std::placeholders::_1; @@ -58,12 +58,12 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options) /* initialize ros system */ timer_control_ = rclcpp::create_timer( this, get_clock(), rclcpp::Duration::from_seconds(ekf_dt_), - std::bind(&EKFLocalizer::timerCallback, this)); + std::bind(&EKFLocalizer::timer_callback, this)); if (params_.publish_tf_) { timer_tf_ = rclcpp::create_timer( this, get_clock(), rclcpp::Rate(params_.tf_rate_).period(), - std::bind(&EKFLocalizer::timerTFCallback, this)); + std::bind(&EKFLocalizer::timer_tf_callback, this)); } pub_pose_ = create_publisher("ekf_pose", 1); @@ -79,15 +79,17 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options) "ekf_biased_pose_with_covariance", 1); pub_diag_ = this->create_publisher("/diagnostics", 10); sub_initialpose_ = create_subscription( - "initialpose", 1, std::bind(&EKFLocalizer::callbackInitialPose, this, _1)); + "initialpose", 1, std::bind(&EKFLocalizer::callback_initial_pose, this, _1)); sub_pose_with_cov_ = create_subscription( - "in_pose_with_covariance", 1, std::bind(&EKFLocalizer::callbackPoseWithCovariance, this, _1)); + "in_pose_with_covariance", 1, + std::bind(&EKFLocalizer::callback_pose_with_covariance, this, _1)); sub_twist_with_cov_ = create_subscription( - "in_twist_with_covariance", 1, std::bind(&EKFLocalizer::callbackTwistWithCovariance, this, _1)); + "in_twist_with_covariance", 1, + std::bind(&EKFLocalizer::callback_twist_with_covariance, this, _1)); service_trigger_node_ = create_service( "trigger_node_srv", std::bind( - &EKFLocalizer::serviceTriggerNode, this, std::placeholders::_1, std::placeholders::_2), + &EKFLocalizer::service_trigger_node, this, std::placeholders::_1, std::placeholders::_2), rclcpp::ServicesQoS().get_rmw_qos_profile()); tf_br_ = std::make_shared( @@ -102,9 +104,9 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options) } /* - * updatePredictFrequency + * update_predict_frequency */ -void EKFLocalizer::updatePredictFrequency(const rclcpp::Time & current_time) +void EKFLocalizer::update_predict_frequency(const rclcpp::Time & current_time) { if (last_predict_time_) { if (current_time < *last_predict_time_) { @@ -119,7 +121,7 @@ void EKFLocalizer::updatePredictFrequency(const rclcpp::Time & current_time) ekf_dt_ = 10.0; RCLCPP_WARN( get_logger(), "Large ekf_dt_ detected!! (%f sec) Capped to 10.0 seconds", ekf_dt_); - } else if (ekf_dt_ > params_.pose_smoothing_steps / params_.ekf_rate) { + } else if (ekf_dt_ > static_cast(params_.pose_smoothing_steps) / params_.ekf_rate) { RCLCPP_WARN( get_logger(), "EKF period may be too slow to finish pose smoothing!! (%f sec) ", ekf_dt_); } @@ -137,28 +139,28 @@ void EKFLocalizer::updatePredictFrequency(const rclcpp::Time & current_time) } /* - * timerCallback + * timer_callback */ -void EKFLocalizer::timerCallback() +void EKFLocalizer::timer_callback() { const rclcpp::Time current_time = this->now(); if (!is_activated_) { - warning_->warnThrottle( + warning_->warn_throttle( "The node is not activated. Provide initial pose to pose_initializer", 2000); - publishDiagnostics(current_time); + publish_diagnostics(current_time); return; } DEBUG_INFO(get_logger(), "========================= timer called ========================="); /* update predict frequency with measured timer rate */ - updatePredictFrequency(current_time); + update_predict_frequency(current_time); /* predict model in EKF */ stop_watch_.tic(); DEBUG_INFO(get_logger(), "------------------------- start prediction -------------------------"); - ekf_module_->predictWithDelay(ekf_dt_); + ekf_module_->predict_with_delay(ekf_dt_); DEBUG_INFO(get_logger(), "[EKF] predictKinematicsModel calc time = %f [ms]", stop_watch_.toc()); DEBUG_INFO(get_logger(), "------------------------- end prediction -------------------------\n"); @@ -177,22 +179,22 @@ void EKFLocalizer::timerCallback() stop_watch_.tic(); // save the initial size because the queue size can change in the loop - const auto t_curr = current_time; const size_t n = pose_queue_.size(); for (size_t i = 0; i < n; ++i) { const auto pose = pose_queue_.pop_increment_age(); - bool is_updated = ekf_module_->measurementUpdatePose(*pose, t_curr, pose_diag_info_); + bool is_updated = ekf_module_->measurement_update_pose(*pose, current_time, pose_diag_info_); if (is_updated) { pose_is_updated = true; // Update Simple 1D filter with considering change of z value due to measurement pose delay const double delay_time = - (t_curr - pose->header.stamp).seconds() + params_.pose_additional_delay; - const auto pose_with_z_delay = ekf_module_->compensatePoseWithZDelay(*pose, delay_time); - updateSimple1DFilters(pose_with_z_delay, params_.pose_smoothing_steps); + (current_time - pose->header.stamp).seconds() + params_.pose_additional_delay; + const auto pose_with_z_delay = ekf_module_->compensate_pose_with_z_delay(*pose, delay_time); + update_simple_1d_filters(pose_with_z_delay, params_.pose_smoothing_steps); } } - DEBUG_INFO(get_logger(), "[EKF] measurementUpdatePose calc time = %f [ms]", stop_watch_.toc()); + DEBUG_INFO( + get_logger(), "[EKF] measurement_update_pose calc time = %f [ms]", stop_watch_.toc()); DEBUG_INFO(get_logger(), "------------------------- end Pose -------------------------\n"); } pose_diag_info_.no_update_count = pose_is_updated ? 0 : (pose_diag_info_.no_update_count + 1); @@ -212,16 +214,17 @@ void EKFLocalizer::timerCallback() stop_watch_.tic(); // save the initial size because the queue size can change in the loop - const auto t_curr = current_time; const size_t n = twist_queue_.size(); for (size_t i = 0; i < n; ++i) { const auto twist = twist_queue_.pop_increment_age(); - bool is_updated = ekf_module_->measurementUpdateTwist(*twist, t_curr, twist_diag_info_); + bool is_updated = + ekf_module_->measurement_update_twist(*twist, current_time, twist_diag_info_); if (is_updated) { twist_is_updated = true; } } - DEBUG_INFO(get_logger(), "[EKF] measurementUpdateTwist calc time = %f [ms]", stop_watch_.toc()); + DEBUG_INFO( + get_logger(), "[EKF] measurement_update_twist calc time = %f [ms]", stop_watch_.toc()); DEBUG_INFO(get_logger(), "------------------------- end Twist -------------------------\n"); } twist_diag_info_.no_update_count = twist_is_updated ? 0 : (twist_diag_info_.no_update_count + 1); @@ -230,27 +233,27 @@ void EKFLocalizer::timerCallback() const double roll = roll_filter_.get_x(); const double pitch = pitch_filter_.get_x(); const geometry_msgs::msg::PoseStamped current_ekf_pose = - ekf_module_->getCurrentPose(current_time, z, roll, pitch, false); + ekf_module_->get_current_pose(current_time, z, roll, pitch, false); const geometry_msgs::msg::PoseStamped current_biased_ekf_pose = - ekf_module_->getCurrentPose(current_time, z, roll, pitch, true); + ekf_module_->get_current_pose(current_time, z, roll, pitch, true); const geometry_msgs::msg::TwistStamped current_ekf_twist = - ekf_module_->getCurrentTwist(current_time); + ekf_module_->get_current_twist(current_time); /* publish ekf result */ - publishEstimateResult(current_ekf_pose, current_biased_ekf_pose, current_ekf_twist); - publishDiagnostics(current_time); + publish_estimate_result(current_ekf_pose, current_biased_ekf_pose, current_ekf_twist); + publish_diagnostics(current_time); } /* - * timerTFCallback + * timer_tf_callback */ -void EKFLocalizer::timerTFCallback() +void EKFLocalizer::timer_tf_callback() { if (!is_activated_) { return; } - if (params_.pose_frame_id == "") { + if (params_.pose_frame_id.empty()) { return; } @@ -262,15 +265,15 @@ void EKFLocalizer::timerTFCallback() geometry_msgs::msg::TransformStamped transform_stamped; transform_stamped = tier4_autoware_utils::pose2transform( - ekf_module_->getCurrentPose(current_time, z, roll, pitch, false), "base_link"); + ekf_module_->get_current_pose(current_time, z, roll, pitch, false), "base_link"); transform_stamped.header.stamp = current_time; tf_br_->sendTransform(transform_stamped); } /* - * getTransformFromTF + * get_transform_from_tf */ -bool EKFLocalizer::getTransformFromTF( +bool EKFLocalizer::get_transform_from_tf( std::string parent_frame, std::string child_frame, geometry_msgs::msg::TransformStamped & transform) { @@ -278,8 +281,8 @@ bool EKFLocalizer::getTransformFromTF( tf2_ros::TransformListener tf_listener(tf_buffer); rclcpp::sleep_for(std::chrono::milliseconds(100)); - parent_frame = eraseLeadingSlash(parent_frame); - child_frame = eraseLeadingSlash(child_frame); + parent_frame = erase_leading_slash(parent_frame); + child_frame = erase_leading_slash(child_frame); for (int i = 0; i < 50; ++i) { try { @@ -294,25 +297,25 @@ bool EKFLocalizer::getTransformFromTF( } /* - * callbackInitialPose + * callback_initial_pose */ -void EKFLocalizer::callbackInitialPose( - geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr initialpose) +void EKFLocalizer::callback_initial_pose( + geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg) { geometry_msgs::msg::TransformStamped transform; - if (!getTransformFromTF(params_.pose_frame_id, initialpose->header.frame_id, transform)) { + if (!get_transform_from_tf(params_.pose_frame_id, msg->header.frame_id, transform)) { RCLCPP_ERROR( get_logger(), "[EKF] TF transform failed. parent = %s, child = %s", - params_.pose_frame_id.c_str(), initialpose->header.frame_id.c_str()); + params_.pose_frame_id.c_str(), msg->header.frame_id.c_str()); } - ekf_module_->initialize(*initialpose, transform); - initSimple1DFilters(*initialpose); + ekf_module_->initialize(*msg, transform); + init_simple_1d_filters(*msg); } /* - * callbackPoseWithCovariance + * callback_pose_with_covariance */ -void EKFLocalizer::callbackPoseWithCovariance( +void EKFLocalizer::callback_pose_with_covariance( geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg) { if (!is_activated_) { @@ -323,9 +326,9 @@ void EKFLocalizer::callbackPoseWithCovariance( } /* - * callbackTwistWithCovariance + * callback_twist_with_covariance */ -void EKFLocalizer::callbackTwistWithCovariance( +void EKFLocalizer::callback_twist_with_covariance( geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { // Ignore twist if velocity is too small. @@ -337,9 +340,9 @@ void EKFLocalizer::callbackTwistWithCovariance( } /* - * publishEstimateResult + * publish_estimate_result */ -void EKFLocalizer::publishEstimateResult( +void EKFLocalizer::publish_estimate_result( const geometry_msgs::msg::PoseStamped & current_ekf_pose, const geometry_msgs::msg::PoseStamped & current_biased_ekf_pose, const geometry_msgs::msg::TwistStamped & current_ekf_twist) @@ -353,7 +356,7 @@ void EKFLocalizer::publishEstimateResult( pose_cov.header.stamp = current_ekf_pose.header.stamp; pose_cov.header.frame_id = current_ekf_pose.header.frame_id; pose_cov.pose.pose = current_ekf_pose.pose; - pose_cov.pose.covariance = ekf_module_->getCurrentPoseCovariance(); + pose_cov.pose.covariance = ekf_module_->get_current_pose_covariance(); pub_pose_cov_->publish(pose_cov); geometry_msgs::msg::PoseWithCovarianceStamped biased_pose_cov = pose_cov; @@ -368,13 +371,13 @@ void EKFLocalizer::publishEstimateResult( twist_cov.header.stamp = current_ekf_twist.header.stamp; twist_cov.header.frame_id = current_ekf_twist.header.frame_id; twist_cov.twist.twist = current_ekf_twist.twist; - twist_cov.twist.covariance = ekf_module_->getCurrentTwistCovariance(); + twist_cov.twist.covariance = ekf_module_->get_current_twist_covariance(); pub_twist_cov_->publish(twist_cov); /* publish yaw bias */ tier4_debug_msgs::msg::Float64Stamped yawb; yawb.stamp = current_ekf_twist.header.stamp; - yawb.data = ekf_module_->getYawBias(); + yawb.data = ekf_module_->get_yaw_bias(); pub_yaw_bias_->publish(yawb); /* publish latest odometry */ @@ -387,38 +390,38 @@ void EKFLocalizer::publishEstimateResult( pub_odom_->publish(odometry); } -void EKFLocalizer::publishDiagnostics(const rclcpp::Time & current_time) +void EKFLocalizer::publish_diagnostics(const rclcpp::Time & current_time) { std::vector diag_status_array; - diag_status_array.push_back(checkProcessActivated(is_activated_)); + diag_status_array.push_back(check_process_activated(is_activated_)); if (is_activated_) { - diag_status_array.push_back(checkMeasurementUpdated( + diag_status_array.push_back(check_measurement_updated( "pose", pose_diag_info_.no_update_count, params_.pose_no_update_count_threshold_warn, params_.pose_no_update_count_threshold_error)); - diag_status_array.push_back(checkMeasurementQueueSize("pose", pose_diag_info_.queue_size)); - diag_status_array.push_back(checkMeasurementDelayGate( + diag_status_array.push_back(check_measurement_queue_size("pose", pose_diag_info_.queue_size)); + diag_status_array.push_back(check_measurement_delay_gate( "pose", pose_diag_info_.is_passed_delay_gate, pose_diag_info_.delay_time, pose_diag_info_.delay_time_threshold)); - diag_status_array.push_back(checkMeasurementMahalanobisGate( + diag_status_array.push_back(check_measurement_mahalanobis_gate( "pose", pose_diag_info_.is_passed_mahalanobis_gate, pose_diag_info_.mahalanobis_distance, params_.pose_gate_dist)); - diag_status_array.push_back(checkMeasurementUpdated( + diag_status_array.push_back(check_measurement_updated( "twist", twist_diag_info_.no_update_count, params_.twist_no_update_count_threshold_warn, params_.twist_no_update_count_threshold_error)); - diag_status_array.push_back(checkMeasurementQueueSize("twist", twist_diag_info_.queue_size)); - diag_status_array.push_back(checkMeasurementDelayGate( + diag_status_array.push_back(check_measurement_queue_size("twist", twist_diag_info_.queue_size)); + diag_status_array.push_back(check_measurement_delay_gate( "twist", twist_diag_info_.is_passed_delay_gate, twist_diag_info_.delay_time, twist_diag_info_.delay_time_threshold)); - diag_status_array.push_back(checkMeasurementMahalanobisGate( + diag_status_array.push_back(check_measurement_mahalanobis_gate( "twist", twist_diag_info_.is_passed_mahalanobis_gate, twist_diag_info_.mahalanobis_distance, params_.twist_gate_dist)); } diagnostic_msgs::msg::DiagnosticStatus diag_merged_status; - diag_merged_status = mergeDiagnosticStatus(diag_status_array); + diag_merged_status = merge_diagnostic_status(diag_status_array); diag_merged_status.name = "localization: " + std::string(this->get_name()); diag_merged_status.hardware_id = this->get_name(); @@ -428,7 +431,7 @@ void EKFLocalizer::publishDiagnostics(const rclcpp::Time & current_time) pub_diag_->publish(diag_msg); } -void EKFLocalizer::updateSimple1DFilters( +void EKFLocalizer::update_simple_1d_filters( const geometry_msgs::msg::PoseWithCovarianceStamped & pose, const size_t smoothing_step) { double z = pose.pose.pose.position.z; @@ -446,7 +449,8 @@ void EKFLocalizer::updateSimple1DFilters( pitch_filter_.update(rpy.y, pitch_dev, pose.header.stamp); } -void EKFLocalizer::initSimple1DFilters(const geometry_msgs::msg::PoseWithCovarianceStamped & pose) +void EKFLocalizer::init_simple_1d_filters( + const geometry_msgs::msg::PoseWithCovarianceStamped & pose) { double z = pose.pose.pose.position.z; @@ -465,7 +469,7 @@ void EKFLocalizer::initSimple1DFilters(const geometry_msgs::msg::PoseWithCovaria /** * @brief trigger node */ -void EKFLocalizer::serviceTriggerNode( +void EKFLocalizer::service_trigger_node( const std_srvs::srv::SetBool::Request::SharedPtr req, std_srvs::srv::SetBool::Response::SharedPtr res) { @@ -477,7 +481,6 @@ void EKFLocalizer::serviceTriggerNode( is_activated_ = false; } res->success = true; - return; } #include diff --git a/localization/ekf_localizer/src/ekf_module.cpp b/localization/ekf_localizer/src/ekf_module.cpp index 8977d82f34138..8703d8754eaaf 100644 --- a/localization/ekf_localizer/src/ekf_module.cpp +++ b/localization/ekf_localizer/src/ekf_module.cpp @@ -30,58 +30,56 @@ #include // clang-format off -#define DEBUG_PRINT_MAT(X) {\ - if (params_.show_debug_info) {std::cout << #X << ": " << X << std::endl;}\ -} +#define DEBUG_PRINT_MAT(X) {if (params_.show_debug_info) {std::cout << #X << ": " << X << std::endl;}} // NOLINT // clang-format on -EKFModule::EKFModule(std::shared_ptr warning, const HyperParameters params) +EKFModule::EKFModule(std::shared_ptr warning, const HyperParameters & params) : warning_(std::move(warning)), dim_x_(6), // x, y, yaw, yaw_bias, vx, wz accumulated_delay_times_(params.extend_state_step, 1.0E15), params_(params) { - Eigen::MatrixXd X = Eigen::MatrixXd::Zero(dim_x_, 1); - Eigen::MatrixXd P = Eigen::MatrixXd::Identity(dim_x_, dim_x_) * 1.0E15; // for x & y - P(IDX::YAW, IDX::YAW) = 50.0; // for yaw + Eigen::MatrixXd x = Eigen::MatrixXd::Zero(dim_x_, 1); + Eigen::MatrixXd p = Eigen::MatrixXd::Identity(dim_x_, dim_x_) * 1.0E15; // for x & y + p(IDX::YAW, IDX::YAW) = 50.0; // for yaw if (params_.enable_yaw_bias_estimation) { - P(IDX::YAWB, IDX::YAWB) = 50.0; // for yaw bias + p(IDX::YAWB, IDX::YAWB) = 50.0; // for yaw bias } - P(IDX::VX, IDX::VX) = 1000.0; // for vx - P(IDX::WZ, IDX::WZ) = 50.0; // for wz + p(IDX::VX, IDX::VX) = 1000.0; // for vx + p(IDX::WZ, IDX::WZ) = 50.0; // for wz - kalman_filter_.init(X, P, params_.extend_state_step); + kalman_filter_.init(x, p, static_cast(params_.extend_state_step)); } void EKFModule::initialize( const PoseWithCovariance & initial_pose, const geometry_msgs::msg::TransformStamped & transform) { - Eigen::MatrixXd X(dim_x_, 1); - Eigen::MatrixXd P = Eigen::MatrixXd::Zero(dim_x_, dim_x_); + Eigen::MatrixXd x(dim_x_, 1); + Eigen::MatrixXd p = Eigen::MatrixXd::Zero(dim_x_, dim_x_); - X(IDX::X) = initial_pose.pose.pose.position.x + transform.transform.translation.x; - X(IDX::Y) = initial_pose.pose.pose.position.y + transform.transform.translation.y; - X(IDX::YAW) = + x(IDX::X) = initial_pose.pose.pose.position.x + transform.transform.translation.x; + x(IDX::Y) = initial_pose.pose.pose.position.y + transform.transform.translation.y; + x(IDX::YAW) = tf2::getYaw(initial_pose.pose.pose.orientation) + tf2::getYaw(transform.transform.rotation); - X(IDX::YAWB) = 0.0; - X(IDX::VX) = 0.0; - X(IDX::WZ) = 0.0; + x(IDX::YAWB) = 0.0; + x(IDX::VX) = 0.0; + x(IDX::WZ) = 0.0; using COV_IDX = tier4_autoware_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]; + 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]; if (params_.enable_yaw_bias_estimation) { - P(IDX::YAWB, IDX::YAWB) = 0.0001; + p(IDX::YAWB, IDX::YAWB) = 0.0001; } - P(IDX::VX, IDX::VX) = 0.01; - P(IDX::WZ, IDX::WZ) = 0.01; + p(IDX::VX, IDX::VX) = 0.01; + p(IDX::WZ, IDX::WZ) = 0.01; - kalman_filter_.init(X, P, params_.extend_state_step); + kalman_filter_.init(x, p, static_cast(params_.extend_state_step)); } -geometry_msgs::msg::PoseStamped EKFModule::getCurrentPose( +geometry_msgs::msg::PoseStamped EKFModule::get_current_pose( const rclcpp::Time & current_time, const double z, const double roll, const double pitch, bool get_biased_yaw) const { @@ -110,7 +108,8 @@ geometry_msgs::msg::PoseStamped EKFModule::getCurrentPose( return current_ekf_pose; } -geometry_msgs::msg::TwistStamped EKFModule::getCurrentTwist(const rclcpp::Time & current_time) const +geometry_msgs::msg::TwistStamped EKFModule::get_current_twist( + const rclcpp::Time & current_time) const { const double vx = kalman_filter_.getXelement(IDX::VX); const double wz = kalman_filter_.getXelement(IDX::WZ); @@ -123,17 +122,17 @@ geometry_msgs::msg::TwistStamped EKFModule::getCurrentTwist(const rclcpp::Time & return current_ekf_twist; } -std::array EKFModule::getCurrentPoseCovariance() const +std::array EKFModule::get_current_pose_covariance() const { - return ekfCovarianceToPoseMessageCovariance(kalman_filter_.getLatestP()); + return ekf_covariance_to_pose_message_covariance(kalman_filter_.getLatestP()); } -std::array EKFModule::getCurrentTwistCovariance() const +std::array EKFModule::get_current_twist_covariance() const { - return ekfCovarianceToTwistMessageCovariance(kalman_filter_.getLatestP()); + return ekf_covariance_to_twist_message_covariance(kalman_filter_.getLatestP()); } -double EKFModule::getYawBias() const +double EKFModule::get_yaw_bias() const { return kalman_filter_.getLatestX()(IDX::YAWB); } @@ -153,17 +152,17 @@ size_t EKFModule::find_closest_delay_time_index(double target_value) const // If else, take the closest element. if (lower == accumulated_delay_times_.begin()) { return 0; - } else if (lower == accumulated_delay_times_.end()) { + } + if (lower == accumulated_delay_times_.end()) { return accumulated_delay_times_.size() - 1; - } else { - // Compare the target with the lower bound and the previous element. - auto prev = lower - 1; - bool is_closer_to_prev = (target_value - *prev) < (*lower - target_value); - - // Return the index of the closer element. - return is_closer_to_prev ? std::distance(accumulated_delay_times_.begin(), prev) - : std::distance(accumulated_delay_times_.begin(), lower); } + // Compare the target with the lower bound and the previous element. + auto prev = lower - 1; + bool is_closer_to_prev = (target_value - *prev) < (*lower - target_value); + + // Return the index of the closer element. + return is_closer_to_prev ? std::distance(accumulated_delay_times_.begin(), prev) + : std::distance(accumulated_delay_times_.begin(), lower); } void EKFModule::accumulate_delay_time(const double dt) @@ -180,69 +179,70 @@ void EKFModule::accumulate_delay_time(const double dt) } } -void EKFModule::predictWithDelay(const double dt) +void EKFModule::predict_with_delay(const double dt) { - const Eigen::MatrixXd X_curr = kalman_filter_.getLatestX(); - const Eigen::MatrixXd P_curr = kalman_filter_.getLatestP(); + const Eigen::MatrixXd x_curr = kalman_filter_.getLatestX(); + const Eigen::MatrixXd p_curr = kalman_filter_.getLatestP(); const double proc_cov_vx_d = std::pow(params_.proc_stddev_vx_c * dt, 2.0); const double proc_cov_wz_d = std::pow(params_.proc_stddev_wz_c * dt, 2.0); const double proc_cov_yaw_d = std::pow(params_.proc_stddev_yaw_c * dt, 2.0); - const Vector6d X_next = predictNextState(X_curr, dt); - const Matrix6d A = createStateTransitionMatrix(X_curr, dt); - const Matrix6d Q = processNoiseCovariance(proc_cov_yaw_d, proc_cov_vx_d, proc_cov_wz_d); - kalman_filter_.predictWithDelay(X_next, A, Q); + const Vector6d x_next = predict_next_state(x_curr, dt); + const Matrix6d a = create_state_transition_matrix(x_curr, dt); + const Matrix6d q = process_noise_covariance(proc_cov_yaw_d, proc_cov_vx_d, proc_cov_wz_d); + kalman_filter_.predictWithDelay(x_next, a, q); } -bool EKFModule::measurementUpdatePose( +bool EKFModule::measurement_update_pose( const PoseWithCovariance & pose, const rclcpp::Time & t_curr, EKFDiagnosticInfo & pose_diag_info) { if (pose.header.frame_id != params_.pose_frame_id) { - warning_->warnThrottle( + warning_->warn_throttle( fmt::format( "pose frame_id is %s, but pose_frame is set as %s. They must be same.", pose.header.frame_id.c_str(), params_.pose_frame_id.c_str()), 2000); } - const Eigen::MatrixXd X_curr = kalman_filter_.getLatestX(); - DEBUG_PRINT_MAT(X_curr.transpose()); + const Eigen::MatrixXd x_curr = kalman_filter_.getLatestX(); + DEBUG_PRINT_MAT(x_curr.transpose()); constexpr int dim_y = 3; // pos_x, pos_y, yaw, depending on Pose output /* Calculate delay step */ double delay_time = (t_curr - pose.header.stamp).seconds() + params_.pose_additional_delay; if (delay_time < 0.0) { - warning_->warnThrottle(poseDelayTimeWarningMessage(delay_time), 1000); + warning_->warn_throttle(pose_delay_time_warning_message(delay_time), 1000); } delay_time = std::max(delay_time, 0.0); - const int delay_step = static_cast(find_closest_delay_time_index(delay_time)); + const size_t delay_step = find_closest_delay_time_index(delay_time); pose_diag_info.delay_time = std::max(delay_time, pose_diag_info.delay_time); pose_diag_info.delay_time_threshold = accumulated_delay_times_.back(); if (delay_step >= params_.extend_state_step) { pose_diag_info.is_passed_delay_gate = false; - warning_->warnThrottle( - poseDelayStepWarningMessage(pose_diag_info.delay_time, pose_diag_info.delay_time_threshold), + warning_->warn_throttle( + pose_delay_step_warning_message( + pose_diag_info.delay_time, pose_diag_info.delay_time_threshold), 2000); return false; } /* Since the kalman filter cannot handle the rotation angle directly, - offset the yaw angle so that the difference from the yaw angle that ekf holds internally is less - than 2 pi. */ + offset the yaw angle so that the difference from the yaw angle that ekf holds internally + is less than 2 pi. */ double yaw = tf2::getYaw(pose.pose.pose.orientation); const double ekf_yaw = kalman_filter_.getXelement(delay_step * dim_x_ + IDX::YAW); - const double yaw_error = normalizeYaw(yaw - ekf_yaw); // normalize the error not to exceed 2 pi + const double yaw_error = normalize_yaw(yaw - ekf_yaw); // normalize the error not to exceed 2 pi yaw = yaw_error + ekf_yaw; /* Set measurement matrix */ Eigen::MatrixXd y(dim_y, 1); y << pose.pose.pose.position.x, pose.pose.pose.position.y, yaw; - if (hasNan(y) || hasInf(y)) { + if (has_nan(y) || has_inf(y)) { warning_->warn( "[EKF] pose measurement matrix includes NaN of Inf. ignore update. check pose message."); return false; @@ -252,15 +252,15 @@ bool EKFModule::measurementUpdatePose( const Eigen::Vector3d y_ekf( kalman_filter_.getXelement(delay_step * dim_x_ + IDX::X), kalman_filter_.getXelement(delay_step * dim_x_ + IDX::Y), ekf_yaw); - const Eigen::MatrixXd P_curr = kalman_filter_.getLatestP(); - const Eigen::MatrixXd P_y = P_curr.block(0, 0, dim_y, dim_y); + const Eigen::MatrixXd p_curr = kalman_filter_.getLatestP(); + const Eigen::MatrixXd p_y = p_curr.block(0, 0, dim_y, dim_y); - const double distance = mahalanobis(y_ekf, y, P_y); + const double distance = mahalanobis(y_ekf, y, p_y); pose_diag_info.mahalanobis_distance = std::max(distance, pose_diag_info.mahalanobis_distance); if (distance > params_.pose_gate_dist) { pose_diag_info.is_passed_mahalanobis_gate = false; - warning_->warnThrottle(mahalanobisWarningMessage(distance, params_.pose_gate_dist), 2000); - warning_->warnThrottle("Ignore the measurement data.", 2000); + warning_->warn_throttle(mahalanobis_warning_message(distance, params_.pose_gate_dist), 2000); + warning_->warn_throttle("Ignore the measurement data.", 2000); return false; } @@ -268,21 +268,21 @@ bool EKFModule::measurementUpdatePose( DEBUG_PRINT_MAT(y_ekf.transpose()); DEBUG_PRINT_MAT((y - y_ekf).transpose()); - const Eigen::Matrix C = poseMeasurementMatrix(); - const Eigen::Matrix3d R = - poseMeasurementCovariance(pose.pose.covariance, params_.pose_smoothing_steps); + const Eigen::Matrix c = pose_measurement_matrix(); + const Eigen::Matrix3d r = + pose_measurement_covariance(pose.pose.covariance, params_.pose_smoothing_steps); - kalman_filter_.updateWithDelay(y, C, R, delay_step); + kalman_filter_.updateWithDelay(y, c, r, static_cast(delay_step)); // debug - const Eigen::MatrixXd X_result = kalman_filter_.getLatestX(); - DEBUG_PRINT_MAT(X_result.transpose()); - DEBUG_PRINT_MAT((X_result - X_curr).transpose()); + const Eigen::MatrixXd x_result = kalman_filter_.getLatestX(); + DEBUG_PRINT_MAT(x_result.transpose()); + DEBUG_PRINT_MAT((x_result - x_curr).transpose()); return true; } -geometry_msgs::msg::PoseWithCovarianceStamped EKFModule::compensatePoseWithZDelay( +geometry_msgs::msg::PoseWithCovarianceStamped EKFModule::compensate_pose_with_z_delay( const PoseWithCovariance & pose, const double delay_time) { const auto rpy = tier4_autoware_utils::getRPY(pose.pose.pose.orientation); @@ -293,34 +293,34 @@ geometry_msgs::msg::PoseWithCovarianceStamped EKFModule::compensatePoseWithZDela return pose_with_z_delay; } -bool EKFModule::measurementUpdateTwist( +bool EKFModule::measurement_update_twist( const TwistWithCovariance & twist, const rclcpp::Time & t_curr, EKFDiagnosticInfo & twist_diag_info) { if (twist.header.frame_id != "base_link") { - warning_->warnThrottle("twist frame_id must be base_link", 2000); + warning_->warn_throttle("twist frame_id must be base_link", 2000); } - const Eigen::MatrixXd X_curr = kalman_filter_.getLatestX(); - DEBUG_PRINT_MAT(X_curr.transpose()); + const Eigen::MatrixXd x_curr = kalman_filter_.getLatestX(); + DEBUG_PRINT_MAT(x_curr.transpose()); constexpr int dim_y = 2; // vx, wz /* Calculate delay step */ double delay_time = (t_curr - twist.header.stamp).seconds() + params_.twist_additional_delay; if (delay_time < 0.0) { - warning_->warnThrottle(twistDelayTimeWarningMessage(delay_time), 1000); + warning_->warn_throttle(twist_delay_time_warning_message(delay_time), 1000); } delay_time = std::max(delay_time, 0.0); - const int delay_step = static_cast(find_closest_delay_time_index(delay_time)); + const size_t delay_step = find_closest_delay_time_index(delay_time); twist_diag_info.delay_time = std::max(delay_time, twist_diag_info.delay_time); twist_diag_info.delay_time_threshold = accumulated_delay_times_.back(); if (delay_step >= params_.extend_state_step) { twist_diag_info.is_passed_delay_gate = false; - warning_->warnThrottle( - twistDelayStepWarningMessage( + warning_->warn_throttle( + twist_delay_step_warning_message( twist_diag_info.delay_time, twist_diag_info.delay_time_threshold), 2000); return false; @@ -330,7 +330,7 @@ bool EKFModule::measurementUpdateTwist( Eigen::MatrixXd y(dim_y, 1); y << twist.twist.twist.linear.x, twist.twist.twist.angular.z; - if (hasNan(y) || hasInf(y)) { + if (has_nan(y) || has_inf(y)) { warning_->warn( "[EKF] twist measurement matrix includes NaN of Inf. ignore update. check twist message."); return false; @@ -339,15 +339,15 @@ bool EKFModule::measurementUpdateTwist( const Eigen::Vector2d y_ekf( kalman_filter_.getXelement(delay_step * dim_x_ + IDX::VX), kalman_filter_.getXelement(delay_step * dim_x_ + IDX::WZ)); - const Eigen::MatrixXd P_curr = kalman_filter_.getLatestP(); - const Eigen::MatrixXd P_y = P_curr.block(4, 4, dim_y, dim_y); + const Eigen::MatrixXd p_curr = kalman_filter_.getLatestP(); + const Eigen::MatrixXd p_y = p_curr.block(4, 4, dim_y, dim_y); - const double distance = mahalanobis(y_ekf, y, P_y); + const double distance = mahalanobis(y_ekf, y, p_y); twist_diag_info.mahalanobis_distance = std::max(distance, twist_diag_info.mahalanobis_distance); if (distance > params_.twist_gate_dist) { twist_diag_info.is_passed_mahalanobis_gate = false; - warning_->warnThrottle(mahalanobisWarningMessage(distance, params_.twist_gate_dist), 2000); - warning_->warnThrottle("Ignore the measurement data.", 2000); + warning_->warn_throttle(mahalanobis_warning_message(distance, params_.twist_gate_dist), 2000); + warning_->warn_throttle("Ignore the measurement data.", 2000); return false; } @@ -355,16 +355,16 @@ bool EKFModule::measurementUpdateTwist( DEBUG_PRINT_MAT(y_ekf.transpose()); DEBUG_PRINT_MAT((y - y_ekf).transpose()); - const Eigen::Matrix C = twistMeasurementMatrix(); - const Eigen::Matrix2d R = - twistMeasurementCovariance(twist.twist.covariance, params_.twist_smoothing_steps); + const Eigen::Matrix c = twist_measurement_matrix(); + const Eigen::Matrix2d r = + twist_measurement_covariance(twist.twist.covariance, params_.twist_smoothing_steps); - kalman_filter_.updateWithDelay(y, C, R, delay_step); + kalman_filter_.updateWithDelay(y, c, r, static_cast(delay_step)); // debug - const Eigen::MatrixXd X_result = kalman_filter_.getLatestX(); - DEBUG_PRINT_MAT(X_result.transpose()); - DEBUG_PRINT_MAT((X_result - X_curr).transpose()); + const Eigen::MatrixXd x_result = kalman_filter_.getLatestX(); + DEBUG_PRINT_MAT(x_result.transpose()); + DEBUG_PRINT_MAT((x_result - x_curr).transpose()); return true; } diff --git a/localization/ekf_localizer/src/mahalanobis.cpp b/localization/ekf_localizer/src/mahalanobis.cpp index ff5ef13892b73..a71482ab696f6 100644 --- a/localization/ekf_localizer/src/mahalanobis.cpp +++ b/localization/ekf_localizer/src/mahalanobis.cpp @@ -14,7 +14,7 @@ #include "ekf_localizer/mahalanobis.hpp" -double squaredMahalanobis( +double squared_mahalanobis( const Eigen::VectorXd & x, const Eigen::VectorXd & y, const Eigen::MatrixXd & C) { const Eigen::VectorXd d = x - y; @@ -23,5 +23,5 @@ double squaredMahalanobis( double mahalanobis(const Eigen::VectorXd & x, const Eigen::VectorXd & y, const Eigen::MatrixXd & C) { - return std::sqrt(squaredMahalanobis(x, y, C)); + return std::sqrt(squared_mahalanobis(x, y, C)); } diff --git a/localization/ekf_localizer/src/measurement.cpp b/localization/ekf_localizer/src/measurement.cpp index 0b3e65bd60f5d..4533bacbee991 100644 --- a/localization/ekf_localizer/src/measurement.cpp +++ b/localization/ekf_localizer/src/measurement.cpp @@ -17,40 +17,40 @@ #include "ekf_localizer/state_index.hpp" #include "tier4_autoware_utils/ros/msg_covariance.hpp" -Eigen::Matrix poseMeasurementMatrix() +Eigen::Matrix pose_measurement_matrix() { - Eigen::Matrix C = Eigen::Matrix::Zero(); - C(0, IDX::X) = 1.0; // for pos x - C(1, IDX::Y) = 1.0; // for pos y - C(2, IDX::YAW) = 1.0; // for yaw - return C; + Eigen::Matrix c = Eigen::Matrix::Zero(); + c(0, IDX::X) = 1.0; // for pos x + c(1, IDX::Y) = 1.0; // for pos y + c(2, IDX::YAW) = 1.0; // for yaw + return c; } -Eigen::Matrix twistMeasurementMatrix() +Eigen::Matrix twist_measurement_matrix() { - Eigen::Matrix C = Eigen::Matrix::Zero(); - C(0, IDX::VX) = 1.0; // for vx - C(1, IDX::WZ) = 1.0; // for wz - return C; + Eigen::Matrix c = Eigen::Matrix::Zero(); + c(0, IDX::VX) = 1.0; // for vx + c(1, IDX::WZ) = 1.0; // for wz + return c; } -Eigen::Matrix3d poseMeasurementCovariance( +Eigen::Matrix3d pose_measurement_covariance( const std::array & covariance, const size_t smoothing_step) { - Eigen::Matrix3d R; + Eigen::Matrix3d r; using COV_IDX = tier4_autoware_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), + 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); - return R * static_cast(smoothing_step); + return r * static_cast(smoothing_step); } -Eigen::Matrix2d twistMeasurementCovariance( +Eigen::Matrix2d twist_measurement_covariance( const std::array & covariance, const size_t smoothing_step) { - Eigen::Matrix2d R; + Eigen::Matrix2d r; using COV_IDX = tier4_autoware_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), + 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); + return r * static_cast(smoothing_step); } diff --git a/localization/ekf_localizer/src/state_transition.cpp b/localization/ekf_localizer/src/state_transition.cpp index 88fc9f76d7168..22b1f2f8a1c67 100644 --- a/localization/ekf_localizer/src/state_transition.cpp +++ b/localization/ekf_localizer/src/state_transition.cpp @@ -17,7 +17,7 @@ #include -double normalizeYaw(const double & yaw) +double normalize_yaw(const double & yaw) { // FIXME(IshitaTakeshi) I think the computation here can be simplified // FIXME(IshitaTakeshi) Rename the function. This is not normalization @@ -36,7 +36,7 @@ double normalizeYaw(const double & yaw) * (b_k : yaw_bias_k) */ -Vector6d predictNextState(const Vector6d & X_curr, const double dt) +Vector6d predict_next_state(const Vector6d & X_curr, const double dt) { const double x = X_curr(IDX::X); const double y = X_curr(IDX::Y); @@ -45,14 +45,14 @@ Vector6d predictNextState(const Vector6d & X_curr, const double dt) const double vx = X_curr(IDX::VX); const double wz = X_curr(IDX::WZ); - Vector6d X_next; - X_next(IDX::X) = x + vx * std::cos(yaw + yaw_bias) * dt; // dx = v * cos(yaw) - X_next(IDX::Y) = y + vx * std::sin(yaw + yaw_bias) * dt; // dy = v * sin(yaw) - X_next(IDX::YAW) = normalizeYaw(yaw + wz * dt); // dyaw = omega + omega_bias - X_next(IDX::YAWB) = yaw_bias; - X_next(IDX::VX) = vx; - X_next(IDX::WZ) = wz; - return X_next; + Vector6d x_next; + x_next(IDX::X) = x + vx * std::cos(yaw + yaw_bias) * dt; // dx = v * cos(yaw) + x_next(IDX::Y) = y + vx * std::sin(yaw + yaw_bias) * dt; // dy = v * sin(yaw) + x_next(IDX::YAW) = normalize_yaw(yaw + wz * dt); // dyaw = omega + omega_bias + x_next(IDX::YAWB) = yaw_bias; + x_next(IDX::VX) = vx; + x_next(IDX::WZ) = wz; + return x_next; } /* == Linearized model == @@ -64,32 +64,32 @@ Vector6d predictNextState(const Vector6d & X_curr, const double dt) * [ 0, 0, 0, 0, 1, 0] * [ 0, 0, 0, 0, 0, 1] */ -Matrix6d createStateTransitionMatrix(const Vector6d & X_curr, const double dt) +Matrix6d create_state_transition_matrix(const Vector6d & X_curr, const double dt) { const double yaw = X_curr(IDX::YAW); const double yaw_bias = X_curr(IDX::YAWB); const double vx = X_curr(IDX::VX); - Matrix6d A = Matrix6d::Identity(); - A(IDX::X, IDX::YAW) = -vx * sin(yaw + yaw_bias) * dt; - A(IDX::X, IDX::YAWB) = -vx * sin(yaw + yaw_bias) * dt; - A(IDX::X, IDX::VX) = cos(yaw + yaw_bias) * dt; - A(IDX::Y, IDX::YAW) = vx * cos(yaw + yaw_bias) * dt; - A(IDX::Y, IDX::YAWB) = vx * cos(yaw + yaw_bias) * dt; - A(IDX::Y, IDX::VX) = sin(yaw + yaw_bias) * dt; - A(IDX::YAW, IDX::WZ) = dt; - return A; + Matrix6d a = Matrix6d::Identity(); + a(IDX::X, IDX::YAW) = -vx * sin(yaw + yaw_bias) * dt; + a(IDX::X, IDX::YAWB) = -vx * sin(yaw + yaw_bias) * dt; + a(IDX::X, IDX::VX) = cos(yaw + yaw_bias) * dt; + a(IDX::Y, IDX::YAW) = vx * cos(yaw + yaw_bias) * dt; + a(IDX::Y, IDX::YAWB) = vx * cos(yaw + yaw_bias) * dt; + a(IDX::Y, IDX::VX) = sin(yaw + yaw_bias) * dt; + a(IDX::YAW, IDX::WZ) = dt; + return a; } -Matrix6d processNoiseCovariance( +Matrix6d process_noise_covariance( const double proc_cov_yaw_d, const double proc_cov_vx_d, const double proc_cov_wz_d) { - Matrix6d Q = Matrix6d::Zero(); - Q(IDX::X, IDX::X) = 0.0; - Q(IDX::Y, IDX::Y) = 0.0; - Q(IDX::YAW, IDX::YAW) = proc_cov_yaw_d; // for yaw - Q(IDX::YAWB, IDX::YAWB) = 0.0; - Q(IDX::VX, IDX::VX) = proc_cov_vx_d; // for vx - Q(IDX::WZ, IDX::WZ) = proc_cov_wz_d; // for wz - return Q; + Matrix6d q = Matrix6d::Zero(); + q(IDX::X, IDX::X) = 0.0; + q(IDX::Y, IDX::Y) = 0.0; + q(IDX::YAW, IDX::YAW) = proc_cov_yaw_d; // for yaw + q(IDX::YAWB, IDX::YAWB) = 0.0; + q(IDX::VX, IDX::VX) = proc_cov_vx_d; // for vx + q(IDX::WZ, IDX::WZ) = proc_cov_wz_d; // for wz + return q; } diff --git a/localization/ekf_localizer/src/warning_message.cpp b/localization/ekf_localizer/src/warning_message.cpp index c69f30b2d6601..ae74c6bfb5fbc 100644 --- a/localization/ekf_localizer/src/warning_message.cpp +++ b/localization/ekf_localizer/src/warning_message.cpp @@ -18,7 +18,8 @@ #include -std::string poseDelayStepWarningMessage(const double delay_time, const double delay_time_threshold) +std::string pose_delay_step_warning_message( + const double delay_time, const double delay_time_threshold) { const std::string s = "Pose delay exceeds the compensation limit, ignored. " @@ -26,7 +27,8 @@ std::string poseDelayStepWarningMessage(const double delay_time, const double de return fmt::format(s, delay_time, delay_time_threshold); } -std::string twistDelayStepWarningMessage(const double delay_time, const double delay_time_threshold) +std::string twist_delay_step_warning_message( + const double delay_time, const double delay_time_threshold) { const std::string s = "Twist delay exceeds the compensation limit, ignored. " @@ -34,19 +36,19 @@ std::string twistDelayStepWarningMessage(const double delay_time, const double d return fmt::format(s, delay_time, delay_time_threshold); } -std::string poseDelayTimeWarningMessage(const double delay_time) +std::string pose_delay_time_warning_message(const double delay_time) { const std::string s = "Pose time stamp is inappropriate, set delay to 0[s]. delay = {:.3f}"; return fmt::format(s, delay_time); } -std::string twistDelayTimeWarningMessage(const double delay_time) +std::string twist_delay_time_warning_message(const double delay_time) { const std::string s = "Twist time stamp is inappropriate, set delay to 0[s]. delay = {:.3f}"; return fmt::format(s, delay_time); } -std::string mahalanobisWarningMessage(const double distance, const double max_distance) +std::string mahalanobis_warning_message(const double distance, const double max_distance) { const std::string s = "The Mahalanobis distance {:.4f} is over the limit {:.4f}."; return fmt::format(s, distance, max_distance); diff --git a/localization/ekf_localizer/test/test_covariance.cpp b/localization/ekf_localizer/test/test_covariance.cpp index 23458fb18a838..ed87ebdea029b 100644 --- a/localization/ekf_localizer/test/test_covariance.cpp +++ b/localization/ekf_localizer/test/test_covariance.cpp @@ -19,18 +19,18 @@ TEST(EKFCovarianceToPoseMessageCovariance, SmokeTest) { { - Matrix6d P = Matrix6d::Zero(); - P(0, 0) = 1.; - P(0, 1) = 2.; - P(0, 2) = 3.; - P(1, 0) = 4.; - P(1, 1) = 5.; - P(1, 2) = 6.; - P(2, 0) = 7.; - P(2, 1) = 8.; - P(2, 2) = 9.; + Matrix6d p = Matrix6d::Zero(); + p(0, 0) = 1.; + p(0, 1) = 2.; + p(0, 2) = 3.; + p(1, 0) = 4.; + p(1, 1) = 5.; + p(1, 2) = 6.; + p(2, 0) = 7.; + p(2, 1) = 8.; + p(2, 2) = 9.; - std::array covariance = ekfCovarianceToPoseMessageCovariance(P); + std::array covariance = ekf_covariance_to_pose_message_covariance(p); EXPECT_EQ(covariance[0], 1.); EXPECT_EQ(covariance[1], 2.); EXPECT_EQ(covariance[5], 3.); @@ -44,8 +44,8 @@ TEST(EKFCovarianceToPoseMessageCovariance, SmokeTest) // ensure other elements are zero { - Matrix6d P = Matrix6d::Zero(); - std::array covariance = ekfCovarianceToPoseMessageCovariance(P); + Matrix6d p = Matrix6d::Zero(); + std::array covariance = ekf_covariance_to_pose_message_covariance(p); for (double e : covariance) { EXPECT_EQ(e, 0.); } @@ -55,13 +55,13 @@ TEST(EKFCovarianceToPoseMessageCovariance, SmokeTest) TEST(EKFCovarianceToTwistMessageCovariance, SmokeTest) { { - Matrix6d P = Matrix6d::Zero(); - P(4, 4) = 1.; - P(4, 5) = 2.; - P(5, 4) = 3.; - P(5, 5) = 4.; + Matrix6d p = Matrix6d::Zero(); + p(4, 4) = 1.; + p(4, 5) = 2.; + p(5, 4) = 3.; + p(5, 5) = 4.; - std::array covariance = ekfCovarianceToTwistMessageCovariance(P); + std::array covariance = ekf_covariance_to_twist_message_covariance(p); EXPECT_EQ(covariance[0], 1.); EXPECT_EQ(covariance[5], 2.); EXPECT_EQ(covariance[30], 3.); @@ -70,8 +70,8 @@ TEST(EKFCovarianceToTwistMessageCovariance, SmokeTest) // ensure other elements are zero { - Matrix6d P = Matrix6d::Zero(); - std::array covariance = ekfCovarianceToTwistMessageCovariance(P); + Matrix6d p = Matrix6d::Zero(); + std::array covariance = ekf_covariance_to_twist_message_covariance(p); for (double e : covariance) { EXPECT_EQ(e, 0.); } diff --git a/localization/ekf_localizer/test/test_diagnostics.cpp b/localization/ekf_localizer/test/test_diagnostics.cpp index f506dca1cb230..ef0d7a6493756 100644 --- a/localization/ekf_localizer/test/test_diagnostics.cpp +++ b/localization/ekf_localizer/test/test_diagnostics.cpp @@ -16,20 +16,20 @@ #include -TEST(TestEkfDiagnostics, CheckProcessActivated) +TEST(TestEkfDiagnostics, check_process_activated) { diagnostic_msgs::msg::DiagnosticStatus stat; bool is_activated = true; - stat = checkProcessActivated(is_activated); + stat = check_process_activated(is_activated); EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); is_activated = false; - stat = checkProcessActivated(is_activated); + stat = check_process_activated(is_activated); EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); } -TEST(TestEkfDiagnostics, checkMeasurementUpdated) +TEST(TestEkfDiagnostics, check_measurement_updated) { diagnostic_msgs::msg::DiagnosticStatus stat; @@ -38,58 +38,58 @@ TEST(TestEkfDiagnostics, checkMeasurementUpdated) const size_t no_update_count_threshold_error = 250; size_t no_update_count = 0; - stat = checkMeasurementUpdated( + stat = check_measurement_updated( measurement_type, no_update_count, no_update_count_threshold_warn, no_update_count_threshold_error); EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); no_update_count = 1; - stat = checkMeasurementUpdated( + stat = check_measurement_updated( measurement_type, no_update_count, no_update_count_threshold_warn, no_update_count_threshold_error); EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); no_update_count = 49; - stat = checkMeasurementUpdated( + stat = check_measurement_updated( measurement_type, no_update_count, no_update_count_threshold_warn, no_update_count_threshold_error); EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); no_update_count = 50; - stat = checkMeasurementUpdated( + stat = check_measurement_updated( measurement_type, no_update_count, no_update_count_threshold_warn, no_update_count_threshold_error); EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); no_update_count = 249; - stat = checkMeasurementUpdated( + stat = check_measurement_updated( measurement_type, no_update_count, no_update_count_threshold_warn, no_update_count_threshold_error); EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); no_update_count = 250; - stat = checkMeasurementUpdated( + stat = check_measurement_updated( measurement_type, no_update_count, no_update_count_threshold_warn, no_update_count_threshold_error); EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); } -TEST(TestEkfDiagnostics, CheckMeasurementQueueSize) +TEST(TestEkfDiagnostics, check_measurement_queue_size) { diagnostic_msgs::msg::DiagnosticStatus stat; const std::string measurement_type = "pose"; // not effect for stat.level size_t queue_size = 0; // not effect for stat.level - stat = checkMeasurementQueueSize(measurement_type, queue_size); + stat = check_measurement_queue_size(measurement_type, queue_size); EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); queue_size = 1; // not effect for stat.level - stat = checkMeasurementQueueSize(measurement_type, queue_size); + stat = check_measurement_queue_size(measurement_type, queue_size); EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); } -TEST(TestEkfDiagnostics, CheckMeasurementDelayGate) +TEST(TestEkfDiagnostics, check_measurement_delay_gate) { diagnostic_msgs::msg::DiagnosticStatus stat; @@ -98,17 +98,17 @@ TEST(TestEkfDiagnostics, CheckMeasurementDelayGate) const double delay_time_threshold = 1.0; // not effect for stat.level bool is_passed_delay_gate = true; - stat = checkMeasurementDelayGate( + stat = check_measurement_delay_gate( measurement_type, is_passed_delay_gate, delay_time, delay_time_threshold); EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); is_passed_delay_gate = false; - stat = checkMeasurementDelayGate( + stat = check_measurement_delay_gate( measurement_type, is_passed_delay_gate, delay_time, delay_time_threshold); EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); } -TEST(TestEkfDiagnostics, CheckMeasurementMahalanobisGate) +TEST(TestEkfDiagnostics, check_measurement_mahalanobis_gate) { diagnostic_msgs::msg::DiagnosticStatus stat; @@ -117,19 +117,19 @@ TEST(TestEkfDiagnostics, CheckMeasurementMahalanobisGate) const double mahalanobis_distance_threshold = 1.0; // not effect for stat.level bool is_passed_mahalanobis_gate = true; - stat = checkMeasurementMahalanobisGate( + stat = check_measurement_mahalanobis_gate( measurement_type, is_passed_mahalanobis_gate, mahalanobis_distance, mahalanobis_distance_threshold); EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); is_passed_mahalanobis_gate = false; - stat = checkMeasurementMahalanobisGate( + stat = check_measurement_mahalanobis_gate( measurement_type, is_passed_mahalanobis_gate, mahalanobis_distance, mahalanobis_distance_threshold); EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); } -TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus) +TEST(TestLocalizationErrorMonitorDiagnostics, merge_diagnostic_status) { diagnostic_msgs::msg::DiagnosticStatus merged_stat; std::vector stat_array(2); @@ -138,7 +138,7 @@ TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus) stat_array.at(0).message = "OK"; stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::OK; stat_array.at(1).message = "OK"; - merged_stat = mergeDiagnosticStatus(stat_array); + merged_stat = merge_diagnostic_status(stat_array); EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); EXPECT_EQ(merged_stat.message, "OK"); @@ -146,7 +146,7 @@ TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus) stat_array.at(0).message = "WARN0"; stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::OK; stat_array.at(1).message = "OK"; - merged_stat = mergeDiagnosticStatus(stat_array); + merged_stat = merge_diagnostic_status(stat_array); EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); EXPECT_EQ(merged_stat.message, "WARN0"); @@ -154,7 +154,7 @@ TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus) stat_array.at(0).message = "OK"; stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; stat_array.at(1).message = "WARN1"; - merged_stat = mergeDiagnosticStatus(stat_array); + merged_stat = merge_diagnostic_status(stat_array); EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); EXPECT_EQ(merged_stat.message, "WARN1"); @@ -162,7 +162,7 @@ TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus) stat_array.at(0).message = "WARN0"; stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; stat_array.at(1).message = "WARN1"; - merged_stat = mergeDiagnosticStatus(stat_array); + merged_stat = merge_diagnostic_status(stat_array); EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); EXPECT_EQ(merged_stat.message, "WARN0; WARN1"); @@ -170,7 +170,7 @@ TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus) stat_array.at(0).message = "OK"; stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; stat_array.at(1).message = "ERROR1"; - merged_stat = mergeDiagnosticStatus(stat_array); + merged_stat = merge_diagnostic_status(stat_array); EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); EXPECT_EQ(merged_stat.message, "ERROR1"); @@ -178,7 +178,7 @@ TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus) stat_array.at(0).message = "WARN0"; stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; stat_array.at(1).message = "ERROR1"; - merged_stat = mergeDiagnosticStatus(stat_array); + merged_stat = merge_diagnostic_status(stat_array); EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); EXPECT_EQ(merged_stat.message, "WARN0; ERROR1"); @@ -186,7 +186,7 @@ TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus) stat_array.at(0).message = "ERROR0"; stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; stat_array.at(1).message = "ERROR1"; - merged_stat = mergeDiagnosticStatus(stat_array); + merged_stat = merge_diagnostic_status(stat_array); EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); EXPECT_EQ(merged_stat.message, "ERROR0; ERROR1"); } diff --git a/localization/ekf_localizer/test/test_mahalanobis.cpp b/localization/ekf_localizer/test/test_mahalanobis.cpp index d208c1e8da06b..db7d538b533c3 100644 --- a/localization/ekf_localizer/test/test_mahalanobis.cpp +++ b/localization/ekf_localizer/test/test_mahalanobis.cpp @@ -18,44 +18,44 @@ constexpr double tolerance = 1e-8; -TEST(SquaredMahalanobis, SmokeTest) +TEST(squared_mahalanobis, SmokeTest) { { Eigen::Vector2d x(0, 1); Eigen::Vector2d y(3, 2); - Eigen::Matrix2d C; - C << 10, 0, 0, 10; + Eigen::Matrix2d c; + c << 10, 0, 0, 10; - EXPECT_NEAR(squaredMahalanobis(x, y, C), 1.0, tolerance); + EXPECT_NEAR(squared_mahalanobis(x, y, c), 1.0, tolerance); } { Eigen::Vector2d x(4, 1); Eigen::Vector2d y(1, 5); - Eigen::Matrix2d C; - C << 5, 0, 0, 5; + Eigen::Matrix2d c; + c << 5, 0, 0, 5; - EXPECT_NEAR(squaredMahalanobis(x, y, C), 5.0, tolerance); + EXPECT_NEAR(squared_mahalanobis(x, y, c), 5.0, tolerance); } } -TEST(Mahalanobis, SmokeTest) +TEST(mahalanobis, SmokeTest) { { Eigen::Vector2d x(0, 1); Eigen::Vector2d y(3, 2); - Eigen::Matrix2d C; - C << 10, 0, 0, 10; + Eigen::Matrix2d c; + c << 10, 0, 0, 10; - EXPECT_NEAR(mahalanobis(x, y, C), 1.0, tolerance); + EXPECT_NEAR(mahalanobis(x, y, c), 1.0, tolerance); } { Eigen::Vector2d x(4, 1); Eigen::Vector2d y(1, 5); - Eigen::Matrix2d C; - C << 5, 0, 0, 5; + Eigen::Matrix2d c; + c << 5, 0, 0, 5; - EXPECT_NEAR(mahalanobis(x, y, C), std::sqrt(5.0), tolerance); + EXPECT_NEAR(mahalanobis(x, y, c), std::sqrt(5.0), tolerance); } } diff --git a/localization/ekf_localizer/test/test_measurement.cpp b/localization/ekf_localizer/test/test_measurement.cpp index 9d63cb056d9d3..c77e39a67d15c 100644 --- a/localization/ekf_localizer/test/test_measurement.cpp +++ b/localization/ekf_localizer/test/test_measurement.cpp @@ -16,66 +16,66 @@ #include -TEST(Measurement, PoseMeasurementMatrix) +TEST(Measurement, pose_measurement_matrix) { - const Eigen::Matrix M = poseMeasurementMatrix(); + const Eigen::Matrix m = pose_measurement_matrix(); Eigen::Matrix expected; expected << 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0; - EXPECT_EQ((M - expected).norm(), 0); + EXPECT_EQ((m - expected).norm(), 0); } -TEST(Measurement, TwistMeasurementMatrix) +TEST(Measurement, twist_measurement_matrix) { - const Eigen::Matrix M = twistMeasurementMatrix(); + const Eigen::Matrix m = twist_measurement_matrix(); Eigen::Matrix expected; expected << 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1; - EXPECT_EQ((M - expected).norm(), 0); + EXPECT_EQ((m - expected).norm(), 0); } -TEST(Measurement, PoseMeasurementCovariance) +TEST(Measurement, pose_measurement_covariance) { { const std::array covariance = {1, 2, 0, 0, 0, 3, 4, 5, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 8, 0, 0, 0, 9}; - const Eigen::Matrix3d M = poseMeasurementCovariance(covariance, 2); + const Eigen::Matrix3d m = pose_measurement_covariance(covariance, 2); Eigen::Matrix3d expected; expected << 2, 4, 6, 8, 10, 12, 14, 16, 18; - EXPECT_EQ((M - expected).norm(), 0.); + EXPECT_EQ((m - expected).norm(), 0.); } { // Make sure that other elements are not changed - std::array covariance; + std::array covariance{}; covariance.fill(0); - const Eigen::Matrix3d M = poseMeasurementCovariance(covariance, 2.); - EXPECT_EQ(M.norm(), 0); + const Eigen::Matrix3d m = pose_measurement_covariance(covariance, 2.); + EXPECT_EQ(m.norm(), 0); } } -TEST(Measurement, TwistMeasurementCovariance) +TEST(Measurement, twist_measurement_covariance) { { const std::array covariance = {1, 0, 0, 0, 0, 2, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 3, 0, 0, 0, 0, 4}; - const Eigen::Matrix2d M = twistMeasurementCovariance(covariance, 2); + const Eigen::Matrix2d m = twist_measurement_covariance(covariance, 2); Eigen::Matrix2d expected; expected << 2, 4, 6, 8; - EXPECT_EQ((M - expected).norm(), 0.); + EXPECT_EQ((m - expected).norm(), 0.); } { // Make sure that other elements are not changed - std::array covariance; + std::array covariance{}; covariance.fill(0); - const Eigen::Matrix2d M = twistMeasurementCovariance(covariance, 2.); - EXPECT_EQ(M.norm(), 0); + const Eigen::Matrix2d m = twist_measurement_covariance(covariance, 2.); + EXPECT_EQ(m.norm(), 0); } } diff --git a/localization/ekf_localizer/test/test_numeric.cpp b/localization/ekf_localizer/test/test_numeric.cpp index baf4f46db79a9..f84c9aa1d0bf2 100644 --- a/localization/ekf_localizer/test/test_numeric.cpp +++ b/localization/ekf_localizer/test/test_numeric.cpp @@ -18,30 +18,30 @@ #include -TEST(Numeric, HasNan) +TEST(Numeric, has_nan) { const Eigen::VectorXd empty(0); const double inf = std::numeric_limits::infinity(); const double nan = std::nan(""); - EXPECT_FALSE(hasNan(empty)); - EXPECT_FALSE(hasNan(Eigen::Vector3d(0., 0., 1.))); - EXPECT_FALSE(hasNan(Eigen::Vector3d(1e16, 0., 1.))); - EXPECT_FALSE(hasNan(Eigen::Vector3d(0., 1., inf))); + EXPECT_FALSE(has_nan(empty)); + EXPECT_FALSE(has_nan(Eigen::Vector3d(0., 0., 1.))); + EXPECT_FALSE(has_nan(Eigen::Vector3d(1e16, 0., 1.))); + EXPECT_FALSE(has_nan(Eigen::Vector3d(0., 1., inf))); - EXPECT_TRUE(hasNan(Eigen::Vector3d(nan, 1., 0.))); + EXPECT_TRUE(has_nan(Eigen::Vector3d(nan, 1., 0.))); } -TEST(Numeric, HasInf) +TEST(Numeric, has_inf) { const Eigen::VectorXd empty(0); const double inf = std::numeric_limits::infinity(); const double nan = std::nan(""); - EXPECT_FALSE(hasInf(empty)); - EXPECT_FALSE(hasInf(Eigen::Vector3d(0., 0., 1.))); - EXPECT_FALSE(hasInf(Eigen::Vector3d(1e16, 0., 1.))); - EXPECT_FALSE(hasInf(Eigen::Vector3d(nan, 1., 0.))); + EXPECT_FALSE(has_inf(empty)); + EXPECT_FALSE(has_inf(Eigen::Vector3d(0., 0., 1.))); + EXPECT_FALSE(has_inf(Eigen::Vector3d(1e16, 0., 1.))); + EXPECT_FALSE(has_inf(Eigen::Vector3d(nan, 1., 0.))); - EXPECT_TRUE(hasInf(Eigen::Vector3d(0., 1., inf))); + EXPECT_TRUE(has_inf(Eigen::Vector3d(0., 1., inf))); } diff --git a/localization/ekf_localizer/test/test_state_transition.cpp b/localization/ekf_localizer/test/test_state_transition.cpp index 9cb7975a964a9..3b6bd93fd3dd8 100644 --- a/localization/ekf_localizer/test/test_state_transition.cpp +++ b/localization/ekf_localizer/test/test_state_transition.cpp @@ -17,43 +17,44 @@ #include "ekf_localizer/state_transition.hpp" #include -#include -TEST(StateTransition, NormalizeYaw) +#include + +TEST(StateTransition, normalize_yaw) { const double tolerance = 1e-6; - EXPECT_NEAR(normalizeYaw(M_PI * 4 / 3), -M_PI * 2 / 3, tolerance); - EXPECT_NEAR(normalizeYaw(-M_PI * 4 / 3), M_PI * 2 / 3, tolerance); - EXPECT_NEAR(normalizeYaw(M_PI * 9 / 2), M_PI * 1 / 2, tolerance); - EXPECT_NEAR(normalizeYaw(M_PI * 4), M_PI * 0, tolerance); + EXPECT_NEAR(normalize_yaw(M_PI * 4 / 3), -M_PI * 2 / 3, tolerance); + EXPECT_NEAR(normalize_yaw(-M_PI * 4 / 3), M_PI * 2 / 3, tolerance); + EXPECT_NEAR(normalize_yaw(M_PI * 9 / 2), M_PI * 1 / 2, tolerance); + EXPECT_NEAR(normalize_yaw(M_PI * 4), M_PI * 0, tolerance); } -TEST(PredictNextState, PredictNextState) +TEST(predict_next_state, predict_next_state) { // This function is the definition of state transition so we just check // if the calculation is done according to the formula - Vector6d X_curr; - X_curr(0) = 2.; - X_curr(1) = 3.; - X_curr(2) = M_PI / 2.; - X_curr(3) = M_PI / 4.; - X_curr(4) = 10.; - X_curr(5) = 2. * M_PI / 3.; + Vector6d x_curr; + x_curr(0) = 2.; + x_curr(1) = 3.; + x_curr(2) = M_PI / 2.; + x_curr(3) = M_PI / 4.; + x_curr(4) = 10.; + x_curr(5) = 2. * M_PI / 3.; const double dt = 0.5; - const Vector6d X_next = predictNextState(X_curr, dt); + const Vector6d x_next = predict_next_state(x_curr, dt); const double tolerance = 1e-10; - EXPECT_NEAR(X_next(0), 2. + 10. * std::cos(M_PI / 2. + M_PI / 4.) * 0.5, tolerance); - EXPECT_NEAR(X_next(1), 3. + 10. * std::sin(M_PI / 2. + M_PI / 4.) * 0.5, tolerance); - EXPECT_NEAR(X_next(2), normalizeYaw(M_PI / 2. + M_PI / 3.), tolerance); - EXPECT_NEAR(X_next(3), X_curr(3), tolerance); - EXPECT_NEAR(X_next(4), X_curr(4), tolerance); - EXPECT_NEAR(X_next(5), X_curr(5), tolerance); + EXPECT_NEAR(x_next(0), 2. + 10. * std::cos(M_PI / 2. + M_PI / 4.) * 0.5, tolerance); + EXPECT_NEAR(x_next(1), 3. + 10. * std::sin(M_PI / 2. + M_PI / 4.) * 0.5, tolerance); + EXPECT_NEAR(x_next(2), normalize_yaw(M_PI / 2. + M_PI / 3.), tolerance); + EXPECT_NEAR(x_next(3), x_curr(3), tolerance); + EXPECT_NEAR(x_next(4), x_curr(4), tolerance); + EXPECT_NEAR(x_next(5), x_curr(5), tolerance); } -TEST(CreateStateTransitionMatrix, NumericalApproximation) +TEST(create_state_transition_matrix, NumericalApproximation) { // The transition matrix A = df / dx // We check if df = A * dx approximates f(x + dx) - f(x) @@ -64,10 +65,10 @@ TEST(CreateStateTransitionMatrix, NumericalApproximation) const Vector6d dx = 0.1 * Vector6d::Ones(); const Vector6d x = Vector6d::Zero(); - const Matrix6d A = createStateTransitionMatrix(x, dt); - const Vector6d df = predictNextState(x + dx, dt) - predictNextState(x, dt); + const Matrix6d a = create_state_transition_matrix(x, dt); + const Vector6d df = predict_next_state(x + dx, dt) - predict_next_state(x, dt); - EXPECT_LT((df - A * dx).norm(), 2e-3); + EXPECT_LT((df - a * dx).norm(), 2e-3); } { @@ -76,20 +77,20 @@ TEST(CreateStateTransitionMatrix, NumericalApproximation) const Vector6d dx = 0.1 * Vector6d::Ones(); const Vector6d x = (Vector6d() << 0.1, 0.2, 0.1, 0.4, 0.1, 0.3).finished(); - const Matrix6d A = createStateTransitionMatrix(x, dt); - const Vector6d df = predictNextState(x + dx, dt) - predictNextState(x, dt); + const Matrix6d a = create_state_transition_matrix(x, dt); + const Vector6d df = predict_next_state(x + dx, dt) - predict_next_state(x, dt); - EXPECT_LT((df - A * dx).norm(), 5e-3); + EXPECT_LT((df - a * dx).norm(), 5e-3); } } -TEST(ProcessNoiseCovariance, ProcessNoiseCovariance) +TEST(process_noise_covariance, process_noise_covariance) { - const Matrix6d Q = processNoiseCovariance(1., 2., 3.); - EXPECT_EQ(Q(2, 2), 1.); // for yaw - EXPECT_EQ(Q(4, 4), 2.); // for vx - EXPECT_EQ(Q(5, 5), 3.); // for wz + const Matrix6d q = process_noise_covariance(1., 2., 3.); + EXPECT_EQ(q(2, 2), 1.); // for yaw + EXPECT_EQ(q(4, 4), 2.); // for vx + EXPECT_EQ(q(5, 5), 3.); // for wz // Make sure other elements are zero - EXPECT_EQ(processNoiseCovariance(0, 0, 0).norm(), 0.); + EXPECT_EQ(process_noise_covariance(0, 0, 0).norm(), 0.); } diff --git a/localization/ekf_localizer/test/test_string.cpp b/localization/ekf_localizer/test/test_string.cpp index 7b35a56d889e9..013072e5145c7 100644 --- a/localization/ekf_localizer/test/test_string.cpp +++ b/localization/ekf_localizer/test/test_string.cpp @@ -16,11 +16,11 @@ #include -TEST(EraseLeadingSlash, SmokeTest) +TEST(erase_leading_slash, SmokeTest) { - EXPECT_EQ(eraseLeadingSlash("/topic"), "topic"); - EXPECT_EQ(eraseLeadingSlash("topic"), "topic"); // do nothing + EXPECT_EQ(erase_leading_slash("/topic"), "topic"); + EXPECT_EQ(erase_leading_slash("topic"), "topic"); // do nothing - EXPECT_EQ(eraseLeadingSlash(""), ""); - EXPECT_EQ(eraseLeadingSlash("/"), ""); + EXPECT_EQ(erase_leading_slash(""), ""); + EXPECT_EQ(erase_leading_slash("/"), ""); } diff --git a/localization/ekf_localizer/test/test_warning_message.cpp b/localization/ekf_localizer/test/test_warning_message.cpp index 2069969e0ae5e..ec7d3420d7f79 100644 --- a/localization/ekf_localizer/test/test_warning_message.cpp +++ b/localization/ekf_localizer/test/test_warning_message.cpp @@ -18,45 +18,45 @@ #include -TEST(PoseDelayStepWarningMessage, SmokeTest) +TEST(pose_delay_step_warning_message, SmokeTest) { EXPECT_STREQ( - poseDelayStepWarningMessage(6.0, 4.0).c_str(), + pose_delay_step_warning_message(6.0, 4.0).c_str(), "Pose delay exceeds the compensation limit, ignored. " "delay: 6.000[s], limit: 4.000[s]"); } -TEST(TwistDelayStepWarningMessage, SmokeTest) +TEST(twist_delay_step_warning_message, SmokeTest) { EXPECT_STREQ( - twistDelayStepWarningMessage(10.0, 6.0).c_str(), + twist_delay_step_warning_message(10.0, 6.0).c_str(), "Twist delay exceeds the compensation limit, ignored. " "delay: 10.000[s], limit: 6.000[s]"); } -TEST(PoseDelayTimeWarningMessage, SmokeTest) +TEST(pose_delay_time_warning_message, SmokeTest) { EXPECT_STREQ( - poseDelayTimeWarningMessage(-1.0).c_str(), + pose_delay_time_warning_message(-1.0).c_str(), "Pose time stamp is inappropriate, set delay to 0[s]. delay = -1.000"); EXPECT_STREQ( - poseDelayTimeWarningMessage(-0.4).c_str(), + pose_delay_time_warning_message(-0.4).c_str(), "Pose time stamp is inappropriate, set delay to 0[s]. delay = -0.400"); } -TEST(TwistDelayTimeWarningMessage, SmokeTest) +TEST(twist_delay_time_warning_message, SmokeTest) { EXPECT_STREQ( - twistDelayTimeWarningMessage(-1.0).c_str(), + twist_delay_time_warning_message(-1.0).c_str(), "Twist time stamp is inappropriate, set delay to 0[s]. delay = -1.000"); EXPECT_STREQ( - twistDelayTimeWarningMessage(-0.4).c_str(), + twist_delay_time_warning_message(-0.4).c_str(), "Twist time stamp is inappropriate, set delay to 0[s]. delay = -0.400"); } -TEST(MahalanobisWarningMessage, SmokeTest) +TEST(mahalanobis_warning_message, SmokeTest) { EXPECT_STREQ( - mahalanobisWarningMessage(1.0, 0.5).c_str(), + mahalanobis_warning_message(1.0, 0.5).c_str(), "The Mahalanobis distance 1.0000 is over the limit 0.5000."); } From a78822bab0f249da382cdfdba4588d2ba2da88dc Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Mon, 10 Jun 2024 16:18:22 +0900 Subject: [PATCH 60/65] refactor(ndt scan matcher): apply static analysis revert (#7398) Revert "refactor(ndt scan matcher): apply static analysis (#7278)" This reverts commit 3b90dc0b6159354d2529139fb4b09d3f24befeda. --- .../ndt_scan_matcher/diagnostics_module.hpp | 16 +- .../ndt_scan_matcher/hyper_parameters.hpp | 64 ++++---- .../ndt_scan_matcher_core.hpp | 2 + .../src/diagnostics_module.cpp | 16 +- .../src/map_update_module.cpp | 42 ++--- .../src/ndt_scan_matcher_core.cpp | 150 +++++++++--------- .../ndt_scan_matcher/test/test_util.hpp | 5 - 7 files changed, 145 insertions(+), 150 deletions(-) diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/diagnostics_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/diagnostics_module.hpp index 6dfea386abaf8..4f7b5eff6521b 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/diagnostics_module.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/diagnostics_module.hpp @@ -27,14 +27,14 @@ class DiagnosticsModule public: DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name); void clear(); - void add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg); + void addKeyValue(const diagnostic_msgs::msg::KeyValue & key_value_msg); template - void add_key_value(const std::string & key, const T & value); - void update_level_and_message(const int8_t level, const std::string & message); + void addKeyValue(const std::string & key, const T & value); + void updateLevelAndMessage(const int8_t level, const std::string & message); void publish(const rclcpp::Time & publish_time_stamp); private: - [[nodiscard]] diagnostic_msgs::msg::DiagnosticArray create_diagnostics_array( + diagnostic_msgs::msg::DiagnosticArray createDiagnosticsArray( const rclcpp::Time & publish_time_stamp) const; rclcpp::Clock::SharedPtr clock_; @@ -44,17 +44,17 @@ class DiagnosticsModule }; template -void DiagnosticsModule::add_key_value(const std::string & key, const T & value) +void DiagnosticsModule::addKeyValue(const std::string & key, const T & value) { diagnostic_msgs::msg::KeyValue key_value; key_value.key = key; key_value.value = std::to_string(value); - add_key_value(key_value); + addKeyValue(key_value); } template <> -void DiagnosticsModule::add_key_value(const std::string & key, const std::string & value); +void DiagnosticsModule::addKeyValue(const std::string & key, const std::string & value); template <> -void DiagnosticsModule::add_key_value(const std::string & key, const bool & value); +void DiagnosticsModule::addKeyValue(const std::string & key, const bool & value); #endif // NDT_SCAN_MATCHER__DIAGNOSTICS_MODULE_HPP_ diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp index 7002b4bf43a73..bc7bf1fe40d36 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp @@ -33,62 +33,62 @@ struct HyperParameters { struct Frame { - std::string base_frame{}; - std::string ndt_base_frame{}; - std::string map_frame{}; - } frame{}; + std::string base_frame; + std::string ndt_base_frame; + std::string map_frame; + } frame; struct SensorPoints { - double required_distance{}; - } sensor_points{}; + double required_distance; + } sensor_points; - pclomp::NdtParams ndt{}; - bool ndt_regularization_enable{}; + pclomp::NdtParams ndt; + bool ndt_regularization_enable; struct InitialPoseEstimation { - int64_t particles_num{}; - int64_t n_startup_trials{}; - } initial_pose_estimation{}; + int64_t particles_num; + int64_t n_startup_trials; + } initial_pose_estimation; struct Validation { - double lidar_topic_timeout_sec{}; - double initial_pose_timeout_sec{}; - double initial_pose_distance_tolerance_m{}; - double critical_upper_bound_exe_time_ms{}; - } validation{}; + double lidar_topic_timeout_sec; + double initial_pose_timeout_sec; + double initial_pose_distance_tolerance_m; + double critical_upper_bound_exe_time_ms; + } validation; struct ScoreEstimation { - ConvergedParamType converged_param_type{}; - double converged_param_transform_probability{}; - double converged_param_nearest_voxel_transformation_likelihood{}; + ConvergedParamType converged_param_type; + double converged_param_transform_probability; + double converged_param_nearest_voxel_transformation_likelihood; struct NoGroundPoints { - bool enable{}; - double z_margin_for_ground_removal{}; - } no_ground_points{}; - } score_estimation{}; + bool enable; + double z_margin_for_ground_removal; + } no_ground_points; + } score_estimation; struct Covariance { - std::array output_pose_covariance{}; + std::array output_pose_covariance; struct CovarianceEstimation { - bool enable{}; - std::vector initial_pose_offset_model{}; - } covariance_estimation{}; - } covariance{}; + bool enable; + std::vector initial_pose_offset_model; + } covariance_estimation; + } covariance; struct DynamicMapLoading { - double update_distance{}; - double map_radius{}; - double lidar_radius{}; - } dynamic_map_loading{}; + double update_distance; + double map_radius; + double lidar_radius; + } dynamic_map_loading; public: explicit HyperParameters(rclcpp::Node * node) 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 cbd2797c57922..4f8042d106c75 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 @@ -131,6 +131,8 @@ class NDTScanMatcher : public rclcpp::Node static int count_oscillation(const std::vector & result_pose_msg_array); + std::array rotate_covariance( + const std::array & src_covariance, const Eigen::Matrix3d & rotation) const; std::array estimate_covariance( const pclomp::NdtResult & ndt_result, const Eigen::Matrix4f & initial_pose_matrix, const rclcpp::Time & sensor_ros_time); diff --git a/localization/ndt_scan_matcher/src/diagnostics_module.cpp b/localization/ndt_scan_matcher/src/diagnostics_module.cpp index 805ee676c5e04..1e08ebb89f51e 100644 --- a/localization/ndt_scan_matcher/src/diagnostics_module.cpp +++ b/localization/ndt_scan_matcher/src/diagnostics_module.cpp @@ -41,7 +41,7 @@ void DiagnosticsModule::clear() diagnostics_status_msg_.message = ""; } -void DiagnosticsModule::add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg) +void DiagnosticsModule::addKeyValue(const diagnostic_msgs::msg::KeyValue & key_value_msg) { auto it = std::find_if( std::begin(diagnostics_status_msg_.values), std::end(diagnostics_status_msg_.values), @@ -55,24 +55,24 @@ void DiagnosticsModule::add_key_value(const diagnostic_msgs::msg::KeyValue & key } template <> -void DiagnosticsModule::add_key_value(const std::string & key, const std::string & value) +void DiagnosticsModule::addKeyValue(const std::string & key, const std::string & value) { diagnostic_msgs::msg::KeyValue key_value; key_value.key = key; key_value.value = value; - add_key_value(key_value); + addKeyValue(key_value); } template <> -void DiagnosticsModule::add_key_value(const std::string & key, const bool & value) +void DiagnosticsModule::addKeyValue(const std::string & key, const bool & value) { diagnostic_msgs::msg::KeyValue key_value; key_value.key = key; key_value.value = value ? "True" : "False"; - add_key_value(key_value); + addKeyValue(key_value); } -void DiagnosticsModule::update_level_and_message(const int8_t level, const std::string & message) +void DiagnosticsModule::updateLevelAndMessage(const int8_t level, const std::string & message) { if ((level > diagnostic_msgs::msg::DiagnosticStatus::OK)) { if (!diagnostics_status_msg_.message.empty()) { @@ -87,10 +87,10 @@ void DiagnosticsModule::update_level_and_message(const int8_t level, const std:: void DiagnosticsModule::publish(const rclcpp::Time & publish_time_stamp) { - diagnostics_pub_->publish(create_diagnostics_array(publish_time_stamp)); + diagnostics_pub_->publish(createDiagnosticsArray(publish_time_stamp)); } -diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::create_diagnostics_array( +diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::createDiagnosticsArray( const rclcpp::Time & publish_time_stamp) const { diagnostic_msgs::msg::DiagnosticArray diagnostics_msg; diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index 32e5a0f2a7c3c..40f0b1f4465fa 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -53,23 +53,23 @@ void MapUpdateModule::callback_timer( std::unique_ptr & diagnostics_ptr) { // check is_activated - diagnostics_ptr->add_key_value("is_activated", is_activated); + diagnostics_ptr->addKeyValue("is_activated", is_activated); if (!is_activated) { std::stringstream message; message << "Node is not activated."; - diagnostics_ptr->update_level_and_message( + diagnostics_ptr->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return; } // check is_set_last_update_position const bool is_set_last_update_position = (position != std::nullopt); - diagnostics_ptr->add_key_value("is_set_last_update_position", is_set_last_update_position); + diagnostics_ptr->addKeyValue("is_set_last_update_position", is_set_last_update_position); if (!is_set_last_update_position) { std::stringstream message; message << "Cannot find the reference position for map update." << "Please check if the EKF odometry is provided to NDT."; - diagnostics_ptr->update_level_and_message( + diagnostics_ptr->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return; } @@ -92,11 +92,11 @@ bool MapUpdateModule::should_update_map( const double distance = std::hypot(dx, dy); // check distance_last_update_position_to_current_position - diagnostics_ptr->add_key_value("distance_last_update_position_to_current_position", distance); + diagnostics_ptr->addKeyValue("distance_last_update_position_to_current_position", distance); if (distance + param_.lidar_radius > param_.map_radius) { std::stringstream message; message << "Dynamic map loading is not keeping up."; - diagnostics_ptr->update_level_and_message( + diagnostics_ptr->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); // If the map does not keep up with the current position, @@ -110,7 +110,7 @@ bool MapUpdateModule::should_update_map( void MapUpdateModule::update_map( const geometry_msgs::msg::Point & position, std::unique_ptr & diagnostics_ptr) { - diagnostics_ptr->add_key_value("is_need_rebuild", need_rebuild_); + diagnostics_ptr->addKeyValue("is_need_rebuild", need_rebuild_); // If the current position is super far from the previous loading position, // lock and rebuild ndt_ptr_ @@ -130,14 +130,14 @@ void MapUpdateModule::update_map( const bool updated = update_ndt(position, *ndt_ptr_, diagnostics_ptr); // check is_updated_map - diagnostics_ptr->add_key_value("is_updated_map", updated); + diagnostics_ptr->addKeyValue("is_updated_map", updated); if (!updated) { std::stringstream message; message << "update_ndt failed. If this happens with initial position estimation, make sure that" << "(1) the initial position matches the pcd map and (2) the map_loader is working " "properly."; - diagnostics_ptr->update_level_and_message( + diagnostics_ptr->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, message.str()); last_update_position_ = position; @@ -157,7 +157,7 @@ void MapUpdateModule::update_map( const bool updated = update_ndt(position, *secondary_ndt_ptr_, diagnostics_ptr); // check is_updated_map - diagnostics_ptr->add_key_value("is_updated_map", updated); + diagnostics_ptr->addKeyValue("is_updated_map", updated); if (!updated) { last_update_position_ = position; return; @@ -189,7 +189,7 @@ bool MapUpdateModule::update_ndt( const geometry_msgs::msg::Point & position, NdtType & ndt, std::unique_ptr & diagnostics_ptr) { - diagnostics_ptr->add_key_value("maps_size_before", ndt.getCurrentMapIDs().size()); + diagnostics_ptr->addKeyValue("maps_size_before", ndt.getCurrentMapIDs().size()); auto request = std::make_shared(); @@ -199,11 +199,11 @@ bool MapUpdateModule::update_ndt( request->cached_ids = ndt.getCurrentMapIDs(); while (!pcd_loader_client_->wait_for_service(std::chrono::seconds(1)) && rclcpp::ok()) { - diagnostics_ptr->add_key_value("is_succeed_call_pcd_loader", false); + diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", false); std::stringstream message; message << "Waiting for pcd loader service. Check the pointcloud_map_loader."; - diagnostics_ptr->update_level_and_message( + diagnostics_ptr->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; } @@ -217,23 +217,23 @@ bool MapUpdateModule::update_ndt( while (status != std::future_status::ready) { // check is_succeed_call_pcd_loader if (!rclcpp::ok()) { - diagnostics_ptr->add_key_value("is_succeed_call_pcd_loader", false); + diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", false); std::stringstream message; message << "pcd_loader service is not working."; - diagnostics_ptr->update_level_and_message( + diagnostics_ptr->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; // No update } status = result.wait_for(std::chrono::seconds(1)); } - diagnostics_ptr->add_key_value("is_succeed_call_pcd_loader", true); + diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", true); auto & maps_to_add = result.get()->new_pointcloud_with_ids; auto & map_ids_to_remove = result.get()->ids_to_remove; - diagnostics_ptr->add_key_value("maps_to_add_size", maps_to_add.size()); - diagnostics_ptr->add_key_value("maps_to_remove_size", map_ids_to_remove.size()); + diagnostics_ptr->addKeyValue("maps_to_add_size", maps_to_add.size()); + diagnostics_ptr->addKeyValue("maps_to_remove_size", map_ids_to_remove.size()); if (maps_to_add.empty() && map_ids_to_remove.empty()) { return false; // No update @@ -261,9 +261,9 @@ bool MapUpdateModule::update_ndt( const auto duration_micro_sec = std::chrono::duration_cast(exe_end_time - exe_start_time).count(); const auto exe_time = static_cast(duration_micro_sec) / 1000.0; - diagnostics_ptr->add_key_value("map_update_execution_time", exe_time); - diagnostics_ptr->add_key_value("maps_size_after", ndt.getCurrentMapIDs().size()); - diagnostics_ptr->add_key_value("is_succeed_call_pcd_loader", true); + diagnostics_ptr->addKeyValue("map_update_execution_time", exe_time); + diagnostics_ptr->addKeyValue("maps_size_after", ndt.getCurrentMapIDs().size()); + diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", true); return true; // Updated } 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 c61e243caab31..349f924019c28 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -62,28 +62,6 @@ Eigen::Matrix2d find_rotation_matrix_aligning_covariance_to_principal_axes( throw std::runtime_error("Eigen solver failed. Return output_pose_covariance value."); } -std::array rotate_covariance( - const std::array & src_covariance, const Eigen::Matrix3d & rotation) -{ - std::array ret_covariance = src_covariance; - - Eigen::Matrix3d src_cov; - src_cov << src_covariance[0], src_covariance[1], src_covariance[2], src_covariance[6], - src_covariance[7], src_covariance[8], src_covariance[12], src_covariance[13], - src_covariance[14]; - - Eigen::Matrix3d ret_cov; - ret_cov = rotation * src_cov * rotation.transpose(); - - for (Eigen::Index i = 0; i < 3; ++i) { - ret_covariance[i] = ret_cov(0, i); - ret_covariance[i + 6] = ret_cov(1, i); - ret_covariance[i + 12] = ret_cov(2, i); - } - - return ret_covariance; -} - NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) : Node("ndt_scan_matcher", options), tf2_broadcaster_(*this), @@ -219,7 +197,7 @@ void NDTScanMatcher::callback_timer() diagnostics_map_update_->clear(); - diagnostics_map_update_->add_key_value("timer_callback_time_stamp", ros_time_now.nanoseconds()); + diagnostics_map_update_->addKeyValue("timer_callback_time_stamp", ros_time_now.nanoseconds()); map_update_module_->callback_timer(is_activated_, latest_ekf_position_, diagnostics_map_update_); @@ -239,16 +217,16 @@ void NDTScanMatcher::callback_initial_pose( void NDTScanMatcher::callback_initial_pose_main( const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr initial_pose_msg_ptr) { - diagnostics_initial_pose_->add_key_value( + diagnostics_initial_pose_->addKeyValue( "topic_time_stamp", static_cast(initial_pose_msg_ptr->header.stamp).nanoseconds()); // check is_activated - diagnostics_initial_pose_->add_key_value("is_activated", static_cast(is_activated_)); + diagnostics_initial_pose_->addKeyValue("is_activated", static_cast(is_activated_)); if (!is_activated_) { std::stringstream message; message << "Node is not activated."; - diagnostics_initial_pose_->update_level_and_message( + diagnostics_initial_pose_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return; } @@ -256,13 +234,13 @@ void NDTScanMatcher::callback_initial_pose_main( // check is_expected_frame_id const bool is_expected_frame_id = (initial_pose_msg_ptr->header.frame_id == param_.frame.map_frame); - diagnostics_initial_pose_->add_key_value("is_expected_frame_id", is_expected_frame_id); + diagnostics_initial_pose_->addKeyValue("is_expected_frame_id", is_expected_frame_id); if (!is_expected_frame_id) { std::stringstream message; message << "Received initial pose message with frame_id " << initial_pose_msg_ptr->header.frame_id << ", but expected " << param_.frame.map_frame << ". Please check the frame_id in the input topic and ensure it is correct."; - diagnostics_initial_pose_->update_level_and_message( + diagnostics_initial_pose_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); return; } @@ -281,7 +259,7 @@ void NDTScanMatcher::callback_regularization_pose( { diagnostics_regularization_pose_->clear(); - diagnostics_regularization_pose_->add_key_value( + diagnostics_regularization_pose_->addKeyValue( "topic_time_stamp", static_cast(pose_conv_msg_ptr->header.stamp).nanoseconds()); regularization_pose_buffer_->push_back(pose_conv_msg_ptr); @@ -304,11 +282,11 @@ void NDTScanMatcher::callback_sensor_points( const size_t error_skipping_publish_num = 5; skipping_publish_num = ((is_succeed_scan_matching || !is_activated_) ? 0 : (skipping_publish_num + 1)); - diagnostics_scan_points_->add_key_value("skipping_publish_num", skipping_publish_num); + diagnostics_scan_points_->addKeyValue("skipping_publish_num", skipping_publish_num); if (skipping_publish_num >= error_skipping_publish_num) { std::stringstream message; message << "skipping_publish_num exceed limit (" << skipping_publish_num << " times)."; - diagnostics_scan_points_->update_level_and_message( + diagnostics_scan_points_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } @@ -322,15 +300,15 @@ bool NDTScanMatcher::callback_sensor_points_main( // check topic_time_stamp const rclcpp::Time sensor_ros_time = sensor_points_msg_in_sensor_frame->header.stamp; - diagnostics_scan_points_->add_key_value("topic_time_stamp", sensor_ros_time.nanoseconds()); + diagnostics_scan_points_->addKeyValue("topic_time_stamp", sensor_ros_time.nanoseconds()); // check sensor_points_size const size_t sensor_points_size = sensor_points_msg_in_sensor_frame->width; - diagnostics_scan_points_->add_key_value("sensor_points_size", sensor_points_size); + diagnostics_scan_points_->addKeyValue("sensor_points_size", sensor_points_size); if (sensor_points_size == 0) { std::stringstream message; message << "Sensor points is empty."; - diagnostics_scan_points_->update_level_and_message( + diagnostics_scan_points_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; } @@ -338,14 +316,14 @@ bool NDTScanMatcher::callback_sensor_points_main( // check sensor_points_delay_time_sec const double sensor_points_delay_time_sec = (this->now() - sensor_points_msg_in_sensor_frame->header.stamp).seconds(); - diagnostics_scan_points_->add_key_value( + diagnostics_scan_points_->addKeyValue( "sensor_points_delay_time_sec", sensor_points_delay_time_sec); if (sensor_points_delay_time_sec > param_.validation.lidar_topic_timeout_sec) { std::stringstream message; message << "sensor points is experiencing latency." << "The delay time is " << sensor_points_delay_time_sec << "[sec] " << "(the tolerance is " << param_.validation.lidar_topic_timeout_sec << "[sec])."; - diagnostics_scan_points_->update_level_and_message( + diagnostics_scan_points_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); // If the delay time of the LiDAR topic exceeds the delay compensation time of ekf_localizer, @@ -374,13 +352,13 @@ bool NDTScanMatcher::callback_sensor_points_main( std::stringstream message; message << ex.what() << ". Please publish TF " << sensor_frame << " to " << param_.frame.base_frame; - diagnostics_scan_points_->update_level_and_message( + diagnostics_scan_points_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); RCLCPP_ERROR_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); - diagnostics_scan_points_->add_key_value("is_succeed_transform_sensor_points", false); + diagnostics_scan_points_->addKeyValue("is_succeed_transform_sensor_points", false); return false; } - diagnostics_scan_points_->add_key_value("is_succeed_transform_sensor_points", true); + diagnostics_scan_points_->addKeyValue("is_succeed_transform_sensor_points", true); // check sensor_points_max_distance double max_distance = 0.0; @@ -389,12 +367,12 @@ bool NDTScanMatcher::callback_sensor_points_main( max_distance = std::max(max_distance, distance); } - diagnostics_scan_points_->add_key_value("sensor_points_max_distance", max_distance); + diagnostics_scan_points_->addKeyValue("sensor_points_max_distance", max_distance); if (max_distance < param_.sensor_points.required_distance) { std::stringstream message; message << "Max distance of sensor points = " << std::fixed << std::setprecision(3) << max_distance << " [m] < " << param_.sensor_points.required_distance << " [m]"; - diagnostics_scan_points_->update_level_and_message( + diagnostics_scan_points_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; } @@ -406,11 +384,11 @@ bool NDTScanMatcher::callback_sensor_points_main( ndt_ptr_->setInputSource(sensor_points_in_baselink_frame); // check is_activated - diagnostics_scan_points_->add_key_value("is_activated", static_cast(is_activated_)); + diagnostics_scan_points_->addKeyValue("is_activated", static_cast(is_activated_)); if (!is_activated_) { std::stringstream message; message << "Node is not activated."; - diagnostics_scan_points_->update_level_and_message( + diagnostics_scan_points_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; } @@ -421,12 +399,12 @@ bool NDTScanMatcher::callback_sensor_points_main( // check is_succeed_interpolate_initial_pose const bool is_succeed_interpolate_initial_pose = (interpolation_result_opt != std::nullopt); - diagnostics_scan_points_->add_key_value( + diagnostics_scan_points_->addKeyValue( "is_succeed_interpolate_initial_pose", is_succeed_interpolate_initial_pose); if (!is_succeed_interpolate_initial_pose) { std::stringstream message; message << "Couldn't interpolate pose. Please check the initial pose topic"; - diagnostics_scan_points_->update_level_and_message( + diagnostics_scan_points_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; } @@ -442,11 +420,11 @@ bool NDTScanMatcher::callback_sensor_points_main( // check is_set_map_points const bool is_set_map_points = (ndt_ptr_->getInputTarget() != nullptr); - diagnostics_scan_points_->add_key_value("is_set_map_points", is_set_map_points); + diagnostics_scan_points_->addKeyValue("is_set_map_points", is_set_map_points); if (!is_set_map_points) { std::stringstream message; message << "Map points is not set."; - diagnostics_scan_points_->update_level_and_message( + diagnostics_scan_points_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; } @@ -466,33 +444,31 @@ bool NDTScanMatcher::callback_sensor_points_main( } // check iteration_num - diagnostics_scan_points_->add_key_value("iteration_num", ndt_result.iteration_num); + diagnostics_scan_points_->addKeyValue("iteration_num", ndt_result.iteration_num); const bool is_ok_iteration_num = (ndt_result.iteration_num < ndt_ptr_->getMaximumIterations()); if (!is_ok_iteration_num) { std::stringstream message; message << "The number of iterations has reached its upper limit. The number of iterations: " << ndt_result.iteration_num << ", Limit: " << ndt_ptr_->getMaximumIterations() << "."; - diagnostics_scan_points_->update_level_and_message( + diagnostics_scan_points_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } // check local_optimal_solution_oscillation_num constexpr int oscillation_num_threshold = 10; const int oscillation_num = count_oscillation(transformation_msg_array); - diagnostics_scan_points_->add_key_value( - "local_optimal_solution_oscillation_num", oscillation_num); + diagnostics_scan_points_->addKeyValue("local_optimal_solution_oscillation_num", oscillation_num); const bool is_local_optimal_solution_oscillation = (oscillation_num > oscillation_num_threshold); if (is_local_optimal_solution_oscillation) { std::stringstream message; message << "There is a possibility of oscillation in a local minimum"; - diagnostics_scan_points_->update_level_and_message( + diagnostics_scan_points_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } // check score - diagnostics_scan_points_->add_key_value( - "transform_probability", ndt_result.transform_probability); - diagnostics_scan_points_->add_key_value( + diagnostics_scan_points_->addKeyValue("transform_probability", ndt_result.transform_probability); + diagnostics_scan_points_->addKeyValue( "nearest_voxel_transformation_likelihood", ndt_result.nearest_voxel_transformation_likelihood); double score = 0.0; double score_threshold = 0.0; @@ -508,7 +484,7 @@ bool NDTScanMatcher::callback_sensor_points_main( } else { std::stringstream message; message << "Unknown converged param type. Please check `score_estimation.converged_param_type`"; - diagnostics_scan_points_->update_level_and_message( + diagnostics_scan_points_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); return false; } @@ -550,7 +526,7 @@ bool NDTScanMatcher::callback_sensor_points_main( std::stringstream message; message << "Score is below the threshold. Score: " << score << ", Threshold: " << score_threshold; - diagnostics_scan_points_->update_level_and_message( + diagnostics_scan_points_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); RCLCPP_WARN_STREAM(this->get_logger(), message.str()); } @@ -577,13 +553,13 @@ bool NDTScanMatcher::callback_sensor_points_main( // check distance_initial_to_result const auto distance_initial_to_result = static_cast( norm(interpolation_result.interpolated_pose.pose.pose.position, result_pose_msg.position)); - diagnostics_scan_points_->add_key_value("distance_initial_to_result", distance_initial_to_result); + diagnostics_scan_points_->addKeyValue("distance_initial_to_result", distance_initial_to_result); const double warn_distance_initial_to_result = 3.0; if (distance_initial_to_result > warn_distance_initial_to_result) { std::stringstream message; message << "distance_initial_to_result is too large (" << distance_initial_to_result << " [m])."; - diagnostics_scan_points_->update_level_and_message( + diagnostics_scan_points_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } @@ -592,11 +568,11 @@ bool NDTScanMatcher::callback_sensor_points_main( const auto duration_micro_sec = std::chrono::duration_cast(exe_end_time - exe_start_time).count(); const auto exe_time = static_cast(duration_micro_sec) / 1000.0f; - diagnostics_scan_points_->add_key_value("execution_time", exe_time); + diagnostics_scan_points_->addKeyValue("execution_time", exe_time); if (exe_time > param_.validation.critical_upper_bound_exe_time_ms) { std::stringstream message; message << "NDT exe time is too long (took " << exe_time << " [ms])."; - diagnostics_scan_points_->update_level_and_message( + diagnostics_scan_points_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } @@ -668,7 +644,7 @@ void NDTScanMatcher::transform_sensor_measurement( geometry_msgs::msg::TransformStamped transform; try { transform = tf2_buffer_.lookupTransform(target_frame, source_frame, tf2::TimePointZero); - } catch (const tf2::TransformException & ex) { + } catch (tf2::TransformException & ex) { throw; } @@ -809,6 +785,28 @@ int NDTScanMatcher::count_oscillation( return max_oscillation_cnt; } +std::array NDTScanMatcher::rotate_covariance( + const std::array & src_covariance, const Eigen::Matrix3d & rotation) const +{ + std::array ret_covariance = src_covariance; + + Eigen::Matrix3d src_cov; + src_cov << src_covariance[0], src_covariance[1], src_covariance[2], src_covariance[6], + src_covariance[7], src_covariance[8], src_covariance[12], src_covariance[13], + src_covariance[14]; + + Eigen::Matrix3d ret_cov; + ret_cov = rotation * src_cov * rotation.transpose(); + + for (Eigen::Index i = 0; i < 3; ++i) { + ret_covariance[i] = ret_cov(0, i); + ret_covariance[i + 6] = ret_cov(1, i); + ret_covariance[i + 12] = ret_cov(2, i); + } + + return ret_covariance; +} + std::array NDTScanMatcher::estimate_covariance( const pclomp::NdtResult & ndt_result, const Eigen::Matrix4f & initial_pose_matrix, const rclcpp::Time & sensor_ros_time) @@ -908,7 +906,7 @@ void NDTScanMatcher::service_trigger_node( const rclcpp::Time ros_time_now = this->now(); diagnostics_trigger_node_->clear(); - diagnostics_trigger_node_->add_key_value("service_call_time_stamp", ros_time_now.nanoseconds()); + diagnostics_trigger_node_->addKeyValue("service_call_time_stamp", ros_time_now.nanoseconds()); is_activated_ = req->data; if (is_activated_) { @@ -916,8 +914,8 @@ void NDTScanMatcher::service_trigger_node( } res->success = true; - diagnostics_trigger_node_->add_key_value("is_activated", static_cast(is_activated_)); - diagnostics_trigger_node_->add_key_value("is_succeed_service", res->success); + diagnostics_trigger_node_->addKeyValue("is_activated", static_cast(is_activated_)); + diagnostics_trigger_node_->addKeyValue("is_succeed_service", res->success); diagnostics_trigger_node_->publish(ros_time_now); } @@ -929,17 +927,17 @@ void NDTScanMatcher::service_ndt_align( diagnostics_ndt_align_->clear(); - diagnostics_ndt_align_->add_key_value("service_call_time_stamp", ros_time_now.nanoseconds()); + diagnostics_ndt_align_->addKeyValue("service_call_time_stamp", ros_time_now.nanoseconds()); service_ndt_align_main(req, res); // check is_succeed_service bool is_succeed_service = res->success; - diagnostics_ndt_align_->add_key_value("is_succeed_service", is_succeed_service); + diagnostics_ndt_align_->addKeyValue("is_succeed_service", is_succeed_service); if (!is_succeed_service) { std::stringstream message; message << "ndt_align_service is failed."; - diagnostics_ndt_align_->update_level_and_message( + diagnostics_ndt_align_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } @@ -962,17 +960,17 @@ void NDTScanMatcher::service_ndt_align_main( // "gnss_link" instead of "map". The ndt_align is designed to return identity when this issue // occurs. However, in the future, converting to a non-existent frame_id should be prohibited. - diagnostics_ndt_align_->add_key_value("is_succeed_transform_initial_pose", false); + diagnostics_ndt_align_->addKeyValue("is_succeed_transform_initial_pose", false); std::stringstream message; message << "Please publish TF " << target_frame.c_str() << " to " << source_frame.c_str(); - diagnostics_ndt_align_->update_level_and_message( + diagnostics_ndt_align_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); RCLCPP_ERROR_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); res->success = false; return; } - diagnostics_ndt_align_->add_key_value("is_succeed_transform_initial_pose", true); + diagnostics_ndt_align_->addKeyValue("is_succeed_transform_initial_pose", true); // transform pose_frame to map_frame const auto initial_pose_msg_in_map_frame = transform(req->pose_with_covariance, transform_s2t); @@ -984,11 +982,11 @@ void NDTScanMatcher::service_ndt_align_main( // check is_set_map_points bool is_set_map_points = (ndt_ptr_->getInputTarget() != nullptr); - diagnostics_ndt_align_->add_key_value("is_set_map_points", is_set_map_points); + diagnostics_ndt_align_->addKeyValue("is_set_map_points", is_set_map_points); if (!is_set_map_points) { std::stringstream message; message << "No InputTarget. Please check the map file and the map_loader service"; - diagnostics_ndt_align_->update_level_and_message( + diagnostics_ndt_align_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); res->success = false; @@ -997,11 +995,11 @@ void NDTScanMatcher::service_ndt_align_main( // check is_set_sensor_points bool is_set_sensor_points = (ndt_ptr_->getInputSource() != nullptr); - diagnostics_ndt_align_->add_key_value("is_set_sensor_points", is_set_sensor_points); + diagnostics_ndt_align_->addKeyValue("is_set_sensor_points", is_set_sensor_points); if (!is_set_sensor_points) { std::stringstream message; message << "No InputSource. Please check the input lidar topic"; - diagnostics_ndt_align_->update_level_and_message( + diagnostics_ndt_align_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); res->success = false; @@ -1109,7 +1107,7 @@ geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_pose( result_pose_with_cov_msg.pose.pose = best_particle_ptr->result_pose; output_pose_with_cov_to_log(get_logger(), "align_pose_output", result_pose_with_cov_msg); - diagnostics_ndt_align_->add_key_value("best_particle_score", best_particle_ptr->score); + diagnostics_ndt_align_->addKeyValue("best_particle_score", best_particle_ptr->score); return result_pose_with_cov_msg; } diff --git a/localization/ndt_scan_matcher/test/test_util.hpp b/localization/ndt_scan_matcher/test/test_util.hpp index dbf055d3c95d3..2f78827abf891 100644 --- a/localization/ndt_scan_matcher/test/test_util.hpp +++ b/localization/ndt_scan_matcher/test/test_util.hpp @@ -15,13 +15,8 @@ #ifndef TEST_UTIL_HPP_ #define TEST_UTIL_HPP_ -#include -#include - -#include #include #include -#include inline pcl::PointCloud make_sample_half_cubic_pcd() { From badc3e779b8ff64e130cae09fb7dfb9a52bd4df3 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Mon, 10 Jun 2024 16:47:15 +0900 Subject: [PATCH 61/65] refactor(pose_initializer): apply static analysis (#7355) * apply clang-tidy and cpplint Signed-off-by: Yamato Ando * apply cppcheck Signed-off-by: Yamato Ando * style(pre-commit): autofix --------- Signed-off-by: Yamato Ando Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../pose_initializer/copy_vector_to_array.hpp | 2 +- .../src/pose_initializer/gnss_module.cpp | 13 ++++--- .../src/pose_initializer/gnss_module.hpp | 2 ++ .../src/pose_initializer/ndt_module.cpp | 4 +-- .../pose_initializer_core.cpp | 34 ++++++++----------- .../pose_initializer_core.hpp | 5 ++- .../src/pose_initializer/yabloc_module.cpp | 4 +-- .../test/test_copy_vector_to_array.cpp | 6 ++-- 8 files changed, 36 insertions(+), 34 deletions(-) diff --git a/localization/pose_initializer/src/pose_initializer/copy_vector_to_array.hpp b/localization/pose_initializer/src/pose_initializer/copy_vector_to_array.hpp index 1274092ae4993..33d95c58a726b 100644 --- a/localization/pose_initializer/src/pose_initializer/copy_vector_to_array.hpp +++ b/localization/pose_initializer/src/pose_initializer/copy_vector_to_array.hpp @@ -40,7 +40,7 @@ template std::array get_covariance_parameter(NodeT * node, const std::string & name) { const auto parameter = node->template declare_parameter>(name); - std::array covariance; + std::array covariance{}; copy_vector_to_array(parameter, covariance); return covariance; } diff --git a/localization/pose_initializer/src/pose_initializer/gnss_module.cpp b/localization/pose_initializer/src/pose_initializer/gnss_module.cpp index e8762c8c6f493..b746828e33b1c 100644 --- a/localization/pose_initializer/src/pose_initializer/gnss_module.cpp +++ b/localization/pose_initializer/src/pose_initializer/gnss_module.cpp @@ -19,13 +19,18 @@ #include -GnssModule::GnssModule(rclcpp::Node * node) : fitter_(node) +GnssModule::GnssModule(rclcpp::Node * node) +: fitter_(node), + clock_(node->get_clock()), + timeout_(node->declare_parameter("gnss_pose_timeout")) { sub_gnss_pose_ = node->create_subscription( - "gnss_pose_cov", 1, [this](PoseWithCovarianceStamped::ConstSharedPtr msg) { pose_ = msg; }); + "gnss_pose_cov", 1, std::bind(&GnssModule::on_pose, this, std::placeholders::_1)); +} - clock_ = node->get_clock(); - timeout_ = node->declare_parameter("gnss_pose_timeout"); +void GnssModule::on_pose(PoseWithCovarianceStamped::ConstSharedPtr msg) +{ + pose_ = msg; } geometry_msgs::msg::PoseWithCovarianceStamped GnssModule::get_pose() diff --git a/localization/pose_initializer/src/pose_initializer/gnss_module.hpp b/localization/pose_initializer/src/pose_initializer/gnss_module.hpp index 8c3bc658e7e7a..fd490b00d0f70 100644 --- a/localization/pose_initializer/src/pose_initializer/gnss_module.hpp +++ b/localization/pose_initializer/src/pose_initializer/gnss_module.hpp @@ -30,6 +30,8 @@ class GnssModule PoseWithCovarianceStamped get_pose(); private: + void on_pose(PoseWithCovarianceStamped::ConstSharedPtr msg); + map_height_fitter::MapHeightFitter fitter_; rclcpp::Clock::SharedPtr clock_; rclcpp::Subscription::SharedPtr sub_gnss_pose_; diff --git a/localization/pose_initializer/src/pose_initializer/ndt_module.cpp b/localization/pose_initializer/src/pose_initializer/ndt_module.cpp index 6e11f8fe74212..1f657545e687c 100644 --- a/localization/pose_initializer/src/pose_initializer/ndt_module.cpp +++ b/localization/pose_initializer/src/pose_initializer/ndt_module.cpp @@ -23,9 +23,9 @@ using ServiceException = component_interface_utils::ServiceException; using Initialize = localization_interface::Initialize; using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; -NdtModule::NdtModule(rclcpp::Node * node) : logger_(node->get_logger()) +NdtModule::NdtModule(rclcpp::Node * node) +: logger_(node->get_logger()), cli_align_(node->create_client("ndt_align")) { - cli_align_ = node->create_client("ndt_align"); } PoseWithCovarianceStamped NdtModule::align_pose(const PoseWithCovarianceStamped & pose) 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 2fc7d61890837..1111547b393e7 100644 --- a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp +++ b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp @@ -67,28 +67,24 @@ PoseInitializer::PoseInitializer(const rclcpp::NodeOptions & options) throw std::invalid_argument( "Could not set user defined initial pose. The size of initial_pose is " + std::to_string(initial_pose_array.size()) + ". It must be 7."); - } else if ( + } + if ( std::abs(initial_pose_array[3]) < 1e-6 && std::abs(initial_pose_array[4]) < 1e-6 && std::abs(initial_pose_array[5]) < 1e-6 && std::abs(initial_pose_array[6]) < 1e-6) { throw std::invalid_argument("Input quaternion is invalid. All elements are close to zero."); - } else { - geometry_msgs::msg::Pose initial_pose; - initial_pose.position.x = initial_pose_array[0]; - initial_pose.position.y = initial_pose_array[1]; - initial_pose.position.z = initial_pose_array[2]; - initial_pose.orientation.x = initial_pose_array[3]; - initial_pose.orientation.y = initial_pose_array[4]; - initial_pose.orientation.z = initial_pose_array[5]; - initial_pose.orientation.w = initial_pose_array[6]; - - set_user_defined_initial_pose(initial_pose, true); } - } -} -PoseInitializer::~PoseInitializer() -{ - // to delete gnss module + geometry_msgs::msg::Pose initial_pose; + initial_pose.position.x = initial_pose_array[0]; + initial_pose.position.y = initial_pose_array[1]; + initial_pose.position.z = initial_pose_array[2]; + initial_pose.orientation.x = initial_pose_array[3]; + initial_pose.orientation.y = initial_pose_array[4]; + initial_pose.orientation.z = initial_pose_array[5]; + initial_pose.orientation.w = initial_pose_array[6]; + + set_user_defined_initial_pose(initial_pose, true); + } } void PoseInitializer::change_state(State::Message::_state_type state) @@ -175,7 +171,7 @@ void PoseInitializer::on_initialize( std::stringstream message; message << "No input pose_with_covariance. If you want to use DIRECT method, please input " "pose_with_covariance."; - RCLCPP_ERROR(get_logger(), message.str().c_str()); + RCLCPP_ERROR_STREAM(get_logger(), message.str()); throw ServiceException( autoware_common_msgs::msg::ResponseStatus::PARAMETER_ERROR, message.str()); } @@ -186,7 +182,7 @@ void PoseInitializer::on_initialize( } else { std::stringstream message; message << "Unknown method type (=" << std::to_string(req->method) << ")"; - RCLCPP_ERROR(get_logger(), message.str().c_str()); + RCLCPP_ERROR_STREAM(get_logger(), message.str()); throw ServiceException( autoware_common_msgs::msg::ResponseStatus::PARAMETER_ERROR, message.str()); } 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 eeba71b90129b..d80fb26fdd41f 100644 --- a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp +++ b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp @@ -35,7 +35,6 @@ class PoseInitializer : public rclcpp::Node { public: explicit PoseInitializer(const rclcpp::NodeOptions & options); - ~PoseInitializer(); private: using ServiceException = component_interface_utils::ServiceException; @@ -48,8 +47,8 @@ class PoseInitializer : public rclcpp::Node component_interface_utils::Publisher::SharedPtr pub_state_; component_interface_utils::Service::SharedPtr srv_initialize_; State::Message state_; - std::array output_pose_covariance_; - std::array gnss_particle_covariance_; + std::array output_pose_covariance_{}; + std::array gnss_particle_covariance_{}; std::unique_ptr gnss_; std::unique_ptr ndt_; std::unique_ptr yabloc_; diff --git a/localization/pose_initializer/src/pose_initializer/yabloc_module.cpp b/localization/pose_initializer/src/pose_initializer/yabloc_module.cpp index f79f1e58e8d62..204f2289adbf4 100644 --- a/localization/pose_initializer/src/pose_initializer/yabloc_module.cpp +++ b/localization/pose_initializer/src/pose_initializer/yabloc_module.cpp @@ -23,9 +23,9 @@ using ServiceException = component_interface_utils::ServiceException; using Initialize = localization_interface::Initialize; using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; -YabLocModule::YabLocModule(rclcpp::Node * node) : logger_(node->get_logger()) +YabLocModule::YabLocModule(rclcpp::Node * node) +: logger_(node->get_logger()), cli_align_(node->create_client("yabloc_align")) { - cli_align_ = node->create_client("yabloc_align"); } PoseWithCovarianceStamped YabLocModule::align_pose(const PoseWithCovarianceStamped & pose) diff --git a/localization/pose_initializer/test/test_copy_vector_to_array.cpp b/localization/pose_initializer/test/test_copy_vector_to_array.cpp index 65b1d7e7d2711..f372a40076ffb 100644 --- a/localization/pose_initializer/test/test_copy_vector_to_array.cpp +++ b/localization/pose_initializer/test/test_copy_vector_to_array.cpp @@ -19,7 +19,7 @@ TEST(CopyVectorToArray, CopyAllElements) { const std::vector vector{0, 1, 2, 3, 4}; - std::array array; + std::array array{}; copy_vector_to_array(vector, array); EXPECT_THAT(array, testing::ElementsAre(0, 1, 2, 3, 4)); } @@ -28,7 +28,7 @@ TEST(CopyVectorToArray, CopyZeroElements) { const std::vector vector{}; // just confirm that this works - std::array array; + std::array array{}; copy_vector_to_array(vector, array); } @@ -36,7 +36,7 @@ TEST(CopyVectorToArray, ThrowsInvalidArgumentIfMoreElementsExpected) { auto f = [] { const std::vector vector{0, 1, 2, 3, 4}; - std::array array; + std::array array{}; copy_vector_to_array(vector, array); }; From ed6022932f5075e3479daa9a14c20c37379989ac Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 10 Jun 2024 16:51:44 +0900 Subject: [PATCH 62/65] refactor(vehicle_info_utils)!: prefix package and namespace with autoware (#7353) * chore(autoware_vehicle_info_utils): rename header Signed-off-by: satoshi-ota * chore(bpp-common): vehicle info Signed-off-by: satoshi-ota * chore(path_optimizer): vehicle info Signed-off-by: satoshi-ota * chore(velocity_smoother): vehicle info Signed-off-by: satoshi-ota * chore(bvp-common): vehicle info Signed-off-by: satoshi-ota * chore(static_centerline_generator): vehicle info Signed-off-by: satoshi-ota * chore(obstacle_cruise_planner): vehicle info Signed-off-by: satoshi-ota * chore(obstacle_velocity_limiter): vehicle info Signed-off-by: satoshi-ota * chore(mission_planner): vehicle info Signed-off-by: satoshi-ota * chore(obstacle_stop_planner): vehicle info Signed-off-by: satoshi-ota * chore(planning_validator): vehicle info Signed-off-by: satoshi-ota * chore(surround_obstacle_checker): vehicle info Signed-off-by: satoshi-ota * chore(goal_planner): vehicle info Signed-off-by: satoshi-ota * chore(start_planner): vehicle info Signed-off-by: satoshi-ota * chore(control_performance_analysis): vehicle info Signed-off-by: satoshi-ota * chore(lane_departure_checker): vehicle info Signed-off-by: satoshi-ota * chore(predicted_path_checker): vehicle info Signed-off-by: satoshi-ota * chore(vehicle_cmd_gate): vehicle info Signed-off-by: satoshi-ota * chore(obstacle_collision_checker): vehicle info Signed-off-by: satoshi-ota * chore(operation_mode_transition_manager): vehicle info Signed-off-by: satoshi-ota * chore(mpc): vehicle info Signed-off-by: satoshi-ota * chore(control): vehicle info Signed-off-by: satoshi-ota * chore(common): vehicle info Signed-off-by: satoshi-ota * chore(perception): vehicle info Signed-off-by: satoshi-ota * chore(evaluator): vehicle info Signed-off-by: satoshi-ota * chore(freespace): vehicle info Signed-off-by: satoshi-ota * chore(planning): vehicle info Signed-off-by: satoshi-ota * chore(vehicle): vehicle info Signed-off-by: satoshi-ota * chore(simulator): vehicle info Signed-off-by: satoshi-ota * chore(launch): vehicle info Signed-off-by: satoshi-ota * chore(system): vehicle info Signed-off-by: satoshi-ota * chore(sensing): vehicle info Signed-off-by: satoshi-ota * fix(autoware_joy_controller): remove unused deps Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .github/CODEOWNERS | 3 ++- .../launch/global_params.launch.py | 2 +- common/global_parameter_loader/package.xml | 2 +- .../tier4_localization_rviz_plugin/package.xml | 2 +- .../src/pose_history_footprint/display.cpp | 2 +- .../src/pose_history_footprint/display.hpp | 6 +++--- .../path/display_base.hpp | 6 +++--- common/tier4_planning_rviz_plugin/package.xml | 2 +- .../src/path/display.cpp | 6 +++--- .../node.hpp | 4 ++-- .../package.xml | 2 +- .../src/node.cpp | 4 ++-- .../autoware_mpc_lateral_controller/package.xml | 2 +- .../src/mpc_lateral_controller.cpp | 4 ++-- .../pid_longitudinal_controller.hpp | 2 +- .../package.xml | 2 +- .../src/pid_longitudinal_controller.cpp | 8 +++++--- .../launch/vehicle_cmd_gate.launch.xml | 2 +- control/autoware_vehicle_cmd_gate/package.xml | 2 +- .../src/vehicle_cmd_gate.cpp | 4 ++-- .../src/vehicle_cmd_gate.hpp | 2 +- .../src/test_filter_in_vehicle_cmd_gate_node.cpp | 2 +- .../control_performance_analysis.launch.xml | 2 +- control/control_performance_analysis/package.xml | 2 +- .../src/control_performance_analysis_node.cpp | 6 +++--- .../control_validator/control_validator.hpp | 4 ++-- control/control_validator/package.xml | 2 +- .../control_validator/src/control_validator.cpp | 2 +- .../lane_departure_checker.hpp | 12 ++++++------ .../util/create_vehicle_footprint.hpp | 2 +- .../launch/lane_departure_checker.launch.xml | 2 +- control/lane_departure_checker/package.xml | 2 +- .../lane_departure_checker_node.cpp | 2 +- .../obstacle_collision_checker.hpp | 6 +++--- .../launch/obstacle_collision_checker.launch.xml | 2 +- control/obstacle_collision_checker/package.xml | 2 +- .../obstacle_collision_checker.cpp | 4 ++-- .../obstacle_collision_checker_node.cpp | 2 +- .../operation_mode_transition_manager.launch.xml | 2 +- .../package.xml | 2 +- .../src/state.cpp | 2 +- .../src/state.hpp | 4 ++-- .../predicted_path_checker/collision_checker.hpp | 4 ++-- .../predicted_path_checker_node.hpp | 6 +++--- .../include/predicted_path_checker/utils.hpp | 8 ++++---- .../launch/predicted_path_checker.launch.xml | 2 +- control/predicted_path_checker/package.xml | 2 +- .../collision_checker.cpp | 2 +- .../predicted_path_checker_node.cpp | 2 +- .../src/predicted_path_checker_node/utils.cpp | 4 ++-- control/pure_pursuit/package.xml | 2 +- .../pure_pursuit_lateral_controller.cpp | 4 ++-- .../src/pure_pursuit/pure_pursuit_node.cpp | 4 ++-- control/trajectory_follower_base/package.xml | 2 +- .../trajectory_follower_node/controller_node.hpp | 2 +- control/trajectory_follower_node/package.xml | 2 +- .../utils/marker_utils.hpp | 6 +++--- .../perception_online_evaluator/package.xml | 2 +- .../src/utils/marker_utils.cpp | 4 ++-- .../launch/sensing.launch.xml | 2 +- launch/tier4_sensing_launch/package.xml | 2 +- .../scan_ground_filter_nodelet.hpp | 4 ++-- .../launch/scan_ground_filter.launch.py | 2 +- .../launch/scan_ground_filter.launch.xml | 2 +- perception/ground_segmentation/package.xml | 2 +- .../src/scan_ground_filter_nodelet.cpp | 6 +++--- .../marker_utils/utils.hpp | 11 ++++++----- .../parameters.hpp | 4 ++-- .../turn_signal_decider.hpp | 2 +- .../utils/drivable_area_expansion/parameters.hpp | 6 +++--- .../utils/path_safety_checker/safety_check.hpp | 8 ++++---- .../package.xml | 2 +- .../src/marker_utils/utils.cpp | 9 +++++---- .../utils/path_safety_checker/safety_check.cpp | 8 ++++---- .../test/test_safety_check.cpp | 2 +- .../freespace_pull_out.hpp | 2 +- .../pull_out_planner_base.hpp | 4 ++-- .../start_planner_module.hpp | 6 +++--- .../src/freespace_pull_out.cpp | 2 +- .../src/start_planner_module.cpp | 2 +- .../package.xml | 2 +- .../src/utils.cpp | 2 +- .../package.xml | 2 +- .../package.xml | 2 +- .../src/manager.cpp | 2 +- .../planner_data.hpp | 6 +++--- .../package.xml | 2 +- .../package.xml | 2 +- .../src/manager.cpp | 2 +- .../src/utils.hpp | 4 ++-- .../package.xml | 2 +- .../src/scene.hpp | 2 +- .../package.xml | 2 +- .../abstract_algorithm.hpp | 6 +++--- .../package.xml | 2 +- .../autoware_path_optimizer/debug_marker.hpp | 4 ++-- .../autoware_path_optimizer/mpt_optimizer.hpp | 11 ++++++----- .../include/autoware_path_optimizer/node.hpp | 4 ++-- .../utils/geometry_utils.hpp | 4 ++-- planning/autoware_path_optimizer/package.xml | 2 +- .../autoware_path_optimizer/src/debug_marker.cpp | 15 ++++++++------- .../src/mpt_optimizer.cpp | 12 ++++++------ planning/autoware_path_optimizer/src/node.cpp | 2 +- .../src/utils/geometry_utils.cpp | 2 +- .../package.xml | 2 +- .../src/static_centerline_generator_node.cpp | 9 +++++---- .../src/static_centerline_generator_node.hpp | 4 ++-- .../debug_marker.hpp | 8 ++++---- .../autoware_surround_obstacle_checker/node.hpp | 6 +++--- .../package.xml | 2 +- .../src/debug_marker.cpp | 2 +- .../src/node.cpp | 2 +- planning/autoware_velocity_smoother/package.xml | 2 +- planning/autoware_velocity_smoother/src/node.cpp | 4 ++-- .../freespace_pull_over.hpp | 2 +- .../goal_planner_module.hpp | 2 +- .../pull_over_planner_base.hpp | 4 ++-- .../behavior_path_goal_planner_module/util.hpp | 5 +++-- .../src/freespace_pull_over.cpp | 2 +- .../src/goal_planner_module.cpp | 4 ++-- .../src/util.cpp | 5 +++-- .../utils/utils.hpp | 4 ++-- .../src/utils/utils.cpp | 6 +++--- planning/behavior_path_planner/package.xml | 2 +- .../src/behavior_path_planner_node.cpp | 6 +++--- .../sampling_planner_module.hpp | 4 ++-- .../package.xml | 2 +- .../src/sampling_planner_module.cpp | 2 +- .../package.xml | 2 +- .../src/scene_crosswalk.cpp | 2 +- .../src/scene_crosswalk.hpp | 2 +- .../package.xml | 2 +- .../src/manager.cpp | 2 +- .../package.xml | 2 +- .../src/manager.cpp | 2 +- .../freespace_planner/freespace_planner_node.hpp | 2 +- .../launch/freespace_planner.launch.xml | 2 +- planning/freespace_planner/package.xml | 2 +- .../freespace_planner/freespace_planner_node.cpp | 3 ++- planning/mission_planner/package.xml | 2 +- .../src/lanelet2_plugins/default_planner.cpp | 6 +++--- .../src/lanelet2_plugins/default_planner.hpp | 4 ++-- .../src/lanelet2_plugins/utility_functions.hpp | 2 +- .../package.xml | 2 +- .../src/out_of_lane_module.cpp | 2 +- .../planner_data.hpp | 6 +++--- .../include/obstacle_cruise_planner/node.hpp | 2 +- .../optimization_based_planner.hpp | 6 +++--- .../pid_based_planner/pid_based_planner.hpp | 4 ++-- .../planner_interface.hpp | 6 +++--- .../obstacle_cruise_planner/polygon_utils.hpp | 6 +++--- .../obstacle_cruise_planner/type_alias.hpp | 4 ++-- .../launch/obstacle_cruise_planner.launch.xml | 2 +- planning/obstacle_cruise_planner/package.xml | 2 +- planning/obstacle_cruise_planner/src/node.cpp | 4 ++-- .../optimization_based_planner.cpp | 4 ++-- .../src/pid_based_planner/pid_based_planner.cpp | 4 ++-- .../src/polygon_utils.cpp | 2 +- .../include/obstacle_stop_planner/node.hpp | 4 ++-- .../obstacle_stop_planner/planner_utils.hpp | 4 ++-- .../launch/obstacle_stop_planner.launch.xml | 2 +- planning/obstacle_stop_planner/package.xml | 2 +- planning/obstacle_stop_planner/src/node.cpp | 2 +- .../launch/obstacle_velocity_limiter.launch.xml | 2 +- planning/obstacle_velocity_limiter/package.xml | 2 +- .../src/obstacle_velocity_limiter_node.cpp | 4 ++-- .../planning_validator.hpp | 4 ++-- planning/planning_validator/package.xml | 2 +- .../src/planning_validator.cpp | 2 +- .../include/autoware_path_sampler/node.hpp | 4 ++-- .../utils/geometry_utils.hpp | 2 +- .../autoware_path_sampler/package.xml | 2 +- .../autoware_path_sampler/src/node.cpp | 2 +- .../launch/polygon_remover.launch.py | 2 +- .../launch/simple_planning_simulator.launch.py | 2 +- simulator/simple_planning_simulator/package.xml | 2 +- .../simple_planning_simulator_core.cpp | 4 ++-- system/default_ad_api/package.xml | 2 +- system/default_ad_api/src/vehicle_info.cpp | 4 ++-- .../autoware_steer_offset_estimator/package.xml | 2 +- .../src/steer_offset_estimator_node.cpp | 4 ++-- .../CMakeLists.txt | 6 +++--- .../Readme.md | 6 +++--- .../config/polygon_remover.yaml | 0 .../config/vehicle_info.param.yaml | 0 .../config/vehicle_mirror.param.yaml | 0 .../vehicle_info.hpp | 10 +++++----- .../vehicle_info_utils.hpp} | 16 ++++++++-------- .../launch/sample.launch.py | 4 ++-- .../launch/vehicle_info.launch.py | 0 .../package.xml | 4 ++-- .../scripts/min_turning_radius_calculator.py | 3 ++- .../src/vehicle_info.cpp | 6 +++--- .../src/vehicle_info_utils.cpp} | 10 +++++----- 194 files changed, 350 insertions(+), 338 deletions(-) rename vehicle/{vehicle_info_util => autoware_vehicle_info_utils}/CMakeLists.txt (71%) rename vehicle/{vehicle_info_util => autoware_vehicle_info_utils}/Readme.md (89%) rename vehicle/{vehicle_info_util => autoware_vehicle_info_utils}/config/polygon_remover.yaml (100%) rename vehicle/{vehicle_info_util => autoware_vehicle_info_utils}/config/vehicle_info.param.yaml (100%) rename vehicle/{vehicle_info_util => autoware_vehicle_info_utils}/config/vehicle_mirror.param.yaml (100%) rename vehicle/{vehicle_info_util/include/vehicle_info_util => autoware_vehicle_info_utils/include/autoware_vehicle_info_utils}/vehicle_info.hpp (89%) rename vehicle/{vehicle_info_util/include/vehicle_info_util/vehicle_info_util.hpp => autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info_utils.hpp} (71%) rename vehicle/{vehicle_info_util => autoware_vehicle_info_utils}/launch/sample.launch.py (91%) rename vehicle/{vehicle_info_util => autoware_vehicle_info_utils}/launch/vehicle_info.launch.py (100%) rename vehicle/{vehicle_info_util => autoware_vehicle_info_utils}/package.xml (88%) rename vehicle/{vehicle_info_util => autoware_vehicle_info_utils}/scripts/min_turning_radius_calculator.py (93%) rename vehicle/{vehicle_info_util => autoware_vehicle_info_utils}/src/vehicle_info.cpp (95%) rename vehicle/{vehicle_info_util/src/vehicle_info_util.cpp => autoware_vehicle_info_utils/src/vehicle_info_utils.cpp} (90%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 9c64b64645c6f..b241c8c45bb3e 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -248,6 +248,7 @@ vehicle/accel_brake_map_calibrator/** taiki.tanaka@tier4.jp takeshi.miura@tier4. vehicle/autoware_steer_offset_estimator/** taiki.tanaka@tier4.jp vehicle/external_cmd_converter/** takamasa.horibe@tier4.jp vehicle/raw_vehicle_cmd_converter/** makoto.kurihara@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp -vehicle/vehicle_info_util/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp +vehicle/autoware_steer_offset_estimator/** taiki.tanaka@tier4.jp +vehicle/autoware_vehicle_info_utils/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp ### Copied from .github/CODEOWNERS-manual ### diff --git a/common/global_parameter_loader/launch/global_params.launch.py b/common/global_parameter_loader/launch/global_params.launch.py index 06f807aaa4609..8f9092b10fa37 100644 --- a/common/global_parameter_loader/launch/global_params.launch.py +++ b/common/global_parameter_loader/launch/global_params.launch.py @@ -33,7 +33,7 @@ def launch_setup(context, *args, **kwargs): load_vehicle_info = IncludeLaunchDescription( PythonLaunchDescriptionSource( - [FindPackageShare("vehicle_info_util"), "/launch/vehicle_info.launch.py"] + [FindPackageShare("autoware_vehicle_info_utils"), "/launch/vehicle_info.launch.py"] ), launch_arguments={ "vehicle_info_param_file": [vehicle_description_pkg, "/config/vehicle_info.param.yaml"] diff --git a/common/global_parameter_loader/package.xml b/common/global_parameter_loader/package.xml index 4c2568b9aec98..472ef0c063430 100644 --- a/common/global_parameter_loader/package.xml +++ b/common/global_parameter_loader/package.xml @@ -10,7 +10,7 @@ ament_cmake_auto autoware_cmake - vehicle_info_util + autoware_vehicle_info_utils ament_lint_auto autoware_lint_common diff --git a/common/tier4_localization_rviz_plugin/package.xml b/common/tier4_localization_rviz_plugin/package.xml index f2482b2d45a3b..1c1c4ad6d8ba1 100644 --- a/common/tier4_localization_rviz_plugin/package.xml +++ b/common/tier4_localization_rviz_plugin/package.xml @@ -11,6 +11,7 @@ ament_cmake_auto autoware_cmake + autoware_vehicle_info_utils geometry_msgs libqt5-core libqt5-gui @@ -20,7 +21,6 @@ rviz_common rviz_default_plugins tf2_ros - vehicle_info_util ament_lint_auto autoware_lint_common diff --git a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp index c4233bd6305e3..cd32df498bfd4 100644 --- a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp +++ b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp @@ -172,7 +172,7 @@ void PoseHistoryFootprint::updateFootprint() if (!vehicle_info_) { try { vehicle_info_ = std::make_shared( - VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo()); + VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo()); updateVehicleInfo(); } catch (const std::exception & e) { RCLCPP_WARN_THROTTLE( diff --git a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp index d957054bd479e..44625ad7deb41 100644 --- a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp +++ b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp @@ -15,8 +15,8 @@ #ifndef POSE_HISTORY_FOOTPRINT__DISPLAY_HPP_ #define POSE_HISTORY_FOOTPRINT__DISPLAY_HPP_ +#include #include -#include #include @@ -39,8 +39,8 @@ class BoolProperty; namespace rviz_plugins { -using vehicle_info_util::VehicleInfo; -using vehicle_info_util::VehicleInfoUtil; +using autoware::vehicle_info_utils::VehicleInfo; +using autoware::vehicle_info_utils::VehicleInfoUtils; class PoseHistoryFootprint : public rviz_common::MessageFilterDisplay 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 ed79e122c0a01..9cb710c239029 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 @@ -15,6 +15,7 @@ #ifndef TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_BASE_HPP_ #define TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_BASE_HPP_ +#include #include #include #include @@ -25,7 +26,6 @@ #include #include #include -#include #include @@ -97,8 +97,8 @@ bool validateFloats(const typename T::ConstSharedPtr & msg_ptr) namespace rviz_plugins { -using vehicle_info_util::VehicleInfo; -using vehicle_info_util::VehicleInfoUtil; +using autoware::vehicle_info_utils::VehicleInfo; +using autoware::vehicle_info_utils::VehicleInfoUtils; template class AutowarePathBaseDisplay : public rviz_common::MessageFilterDisplay { diff --git a/common/tier4_planning_rviz_plugin/package.xml b/common/tier4_planning_rviz_plugin/package.xml index 5d755d212c859..95edcb7a96c56 100644 --- a/common/tier4_planning_rviz_plugin/package.xml +++ b/common/tier4_planning_rviz_plugin/package.xml @@ -12,6 +12,7 @@ autoware_cmake autoware_planning_msgs + autoware_vehicle_info_utils libqt5-core libqt5-gui libqt5-widgets @@ -25,7 +26,6 @@ tf2_ros tier4_autoware_utils tier4_planning_msgs - vehicle_info_util ament_lint_auto autoware_lint_common diff --git a/common/tier4_planning_rviz_plugin/src/path/display.cpp b/common/tier4_planning_rviz_plugin/src/path/display.cpp index 4a297b47bcfcc..342e72d66c5f9 100644 --- a/common/tier4_planning_rviz_plugin/src/path/display.cpp +++ b/common/tier4_planning_rviz_plugin/src/path/display.cpp @@ -31,7 +31,7 @@ void AutowarePathWithLaneIdDisplay::preProcessMessageDetail() if (!vehicle_info_) { try { vehicle_info_ = std::make_shared( - VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo()); + VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo()); updateVehicleInfo(); } catch (const std::exception & e) { RCLCPP_WARN_ONCE( @@ -107,7 +107,7 @@ void AutowarePathDisplay::preProcessMessageDetail() if (!vehicle_info_) { try { vehicle_info_ = std::make_shared( - VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo()); + VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo()); updateVehicleInfo(); } catch (const std::exception & e) { RCLCPP_WARN_ONCE( @@ -124,7 +124,7 @@ void AutowareTrajectoryDisplay::preProcessMessageDetail() if (!vehicle_info_) { try { vehicle_info_ = std::make_shared( - VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo()); + VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo()); updateVehicleInfo(); } catch (const std::exception & e) { RCLCPP_WARN_ONCE( 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 b87f421de7c8c..3e72d72cb9946 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 @@ -15,13 +15,13 @@ #ifndef AUTOWARE_AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_ #define AUTOWARE_AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_ +#include #include #include #include #include #include #include -#include #include #include @@ -59,11 +59,11 @@ using nav_msgs::msg::Odometry; using sensor_msgs::msg::Imu; using sensor_msgs::msg::PointCloud2; using PointCloud = pcl::PointCloud; +using autoware::vehicle_info_utils::VehicleInfo; using diagnostic_updater::DiagnosticStatusWrapper; using diagnostic_updater::Updater; using tier4_autoware_utils::Point2d; using tier4_autoware_utils::Polygon2d; -using vehicle_info_util::VehicleInfo; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; using Path = std::vector; diff --git a/control/autoware_autonomous_emergency_braking/package.xml b/control/autoware_autonomous_emergency_braking/package.xml index 221fc2c000826..0404eec7ca308 100644 --- a/control/autoware_autonomous_emergency_braking/package.xml +++ b/control/autoware_autonomous_emergency_braking/package.xml @@ -17,6 +17,7 @@ autoware_control_msgs autoware_planning_msgs autoware_system_msgs + autoware_vehicle_info_utils autoware_vehicle_msgs diagnostic_updater geometry_msgs @@ -34,7 +35,6 @@ tf2_geometry_msgs tf2_ros tier4_autoware_utils - vehicle_info_util visualization_msgs ament_lint_auto diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index 3ec8cc68df9b1..d01855bc8ab5d 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -60,7 +60,7 @@ void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point & Polygon2d createPolygon( const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Pose & next_pose, - const vehicle_info_util::VehicleInfo & vehicle_info, const double expand_width) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double expand_width) { Polygon2d polygon; @@ -102,7 +102,7 @@ Polygon2d createPolygon( AEB::AEB(const rclcpp::NodeOptions & node_options) : Node("AEB", node_options), - vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()), + vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo()), collision_data_keeper_(this->get_clock()) { // Publisher diff --git a/control/autoware_mpc_lateral_controller/package.xml b/control/autoware_mpc_lateral_controller/package.xml index 3e62d69f6ebb6..673d9d7896745 100644 --- a/control/autoware_mpc_lateral_controller/package.xml +++ b/control/autoware_mpc_lateral_controller/package.xml @@ -19,6 +19,7 @@ autoware_control_msgs autoware_planning_msgs + autoware_vehicle_info_utils autoware_vehicle_msgs diagnostic_msgs diagnostic_updater @@ -35,7 +36,6 @@ tier4_autoware_utils tier4_debug_msgs trajectory_follower_base - vehicle_info_util ament_cmake_ros ament_lint_auto 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 3d66078eed1f2..cf8a4ed5a251b 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -19,10 +19,10 @@ #include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp" #include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp" #include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "tf2/utils.h" #include "tf2_ros/create_timer_ros.h" -#include "vehicle_info_util/vehicle_info_util.hpp" #include #include @@ -69,7 +69,7 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node) m_mpc_converged_threshold_rps = dp_double("mpc_converged_threshold_rps"); // [rad/s] /* mpc parameters */ - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); const double wheelbase = vehicle_info.wheel_base_m; constexpr double deg2rad = static_cast(M_PI) / 180.0; m_mpc->m_steer_lim = vehicle_info.max_steer_angle_rad; 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 7b9d999a3decb..08a6a51d3098b 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 @@ -20,6 +20,7 @@ #include "autoware_pid_longitudinal_controller/lowpass_filter.hpp" #include "autoware_pid_longitudinal_controller/pid.hpp" #include "autoware_pid_longitudinal_controller/smooth_stop.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "diagnostic_updater/diagnostic_updater.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2/utils.h" @@ -27,7 +28,6 @@ #include "tf2_ros/transform_listener.h" #include "tier4_autoware_utils/ros/marker_helper.hpp" #include "trajectory_follower_base/longitudinal_controller_base.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" #include #include diff --git a/control/autoware_pid_longitudinal_controller/package.xml b/control/autoware_pid_longitudinal_controller/package.xml index 50ae7ccaf2e55..66f6a6dfcda8b 100644 --- a/control/autoware_pid_longitudinal_controller/package.xml +++ b/control/autoware_pid_longitudinal_controller/package.xml @@ -21,6 +21,7 @@ autoware_adapi_v1_msgs autoware_control_msgs autoware_planning_msgs + autoware_vehicle_info_utils autoware_vehicle_msgs diagnostic_msgs diagnostic_updater @@ -36,7 +37,6 @@ tier4_autoware_utils tier4_debug_msgs trajectory_follower_base - vehicle_info_util ament_cmake_ros ament_lint_auto 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 e1dd414b2446d..4cca525f6ebf3 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -38,9 +38,11 @@ PidLongitudinalController::PidLongitudinalController(rclcpp::Node & node) // parameters timer m_longitudinal_ctrl_period = node.get_parameter("ctrl_period").as_double(); - m_wheel_base = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo().wheel_base_m; - m_vehicle_width = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo().vehicle_width_m; - m_front_overhang = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo().front_overhang_m; + m_wheel_base = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo().wheel_base_m; + m_vehicle_width = + autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo().vehicle_width_m; + m_front_overhang = + autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo().front_overhang_m; // parameters for delay compensation m_delay_compensation_time = node.declare_parameter("delay_compensation_time"); // [s] diff --git a/control/autoware_vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml b/control/autoware_vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml index c9e83bf9878b8..c9df4e67c2647 100644 --- a/control/autoware_vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml +++ b/control/autoware_vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml @@ -3,7 +3,7 @@ - + diff --git a/control/autoware_vehicle_cmd_gate/package.xml b/control/autoware_vehicle_cmd_gate/package.xml index da0e885cc564a..f67d01a5593ae 100644 --- a/control/autoware_vehicle_cmd_gate/package.xml +++ b/control/autoware_vehicle_cmd_gate/package.xml @@ -17,6 +17,7 @@ autoware_adapi_v1_msgs autoware_control_msgs + autoware_vehicle_info_utils autoware_vehicle_msgs component_interface_specs component_interface_utils @@ -33,7 +34,6 @@ tier4_external_api_msgs tier4_system_msgs tier4_vehicle_msgs - vehicle_info_util visualization_msgs rosidl_default_runtime 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 e8d35beb94b1f..bb50dcb586e83 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -170,7 +170,7 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) declare_parameter("filter_activated_velocity_threshold"); // Vehicle Parameter - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); { VehicleCmdFilterParam p; p.wheel_base = vehicle_info.wheel_base_m; @@ -276,7 +276,7 @@ rcl_interfaces::msg::SetParametersResult VehicleCmdGate::onParameter( parameters, "filter_activated_velocity_threshold", filter_activated_velocity_threshold_); // Vehicle Parameter - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); { VehicleCmdFilterParam p = filter_.getParam(); p.wheel_base = vehicle_info.wheel_base_m; 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 22613de5d1f07..06dad536d842d 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp @@ -21,11 +21,11 @@ #include "vehicle_cmd_filter.hpp" #include +#include #include #include #include #include -#include #include #include diff --git a/control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp b/control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp index 6f148fe6c8140..46130fc8f9941 100644 --- a/control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp +++ b/control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp @@ -371,7 +371,7 @@ std::shared_ptr generateNode() const auto vehicle_cmd_gate_dir = ament_index_cpp::get_package_share_directory("autoware_vehicle_cmd_gate"); const auto vehicle_info_util_dir = - ament_index_cpp::get_package_share_directory("vehicle_info_util"); + ament_index_cpp::get_package_share_directory("autoware_vehicle_info_utils"); node_options.arguments( {"--ros-args", "--params-file", vehicle_cmd_gate_dir + "/config/vehicle_cmd_gate.param.yaml", diff --git a/control/control_performance_analysis/launch/control_performance_analysis.launch.xml b/control/control_performance_analysis/launch/control_performance_analysis.launch.xml index be2b30bdf1bf9..f2997f0e10b83 100644 --- a/control/control_performance_analysis/launch/control_performance_analysis.launch.xml +++ b/control/control_performance_analysis/launch/control_performance_analysis.launch.xml @@ -8,7 +8,7 @@ - + diff --git a/control/control_performance_analysis/package.xml b/control/control_performance_analysis/package.xml index a26f4164a177b..b18fb8c98ccdc 100644 --- a/control/control_performance_analysis/package.xml +++ b/control/control_performance_analysis/package.xml @@ -26,6 +26,7 @@ autoware_control_msgs autoware_planning_msgs + autoware_vehicle_info_utils autoware_vehicle_msgs geometry_msgs libboost-dev @@ -41,7 +42,6 @@ tf2_ros tier4_autoware_utils tier4_debug_msgs - vehicle_info_util builtin_interfaces global_parameter_loader rosidl_default_runtime diff --git a/control/control_performance_analysis/src/control_performance_analysis_node.cpp b/control/control_performance_analysis/src/control_performance_analysis_node.cpp index 693194e8b70a6..47ce3ce07e83c 100644 --- a/control/control_performance_analysis/src/control_performance_analysis_node.cpp +++ b/control/control_performance_analysis/src/control_performance_analysis_node.cpp @@ -17,7 +17,7 @@ #include "control_performance_analysis/msg/driving_monitor_stamped.hpp" #include "control_performance_analysis/msg/error_stamped.hpp" -#include +#include #include #include @@ -32,7 +32,7 @@ using control_performance_analysis::msg::ErrorStamped; namespace control_performance_analysis { -using vehicle_info_util::VehicleInfoUtil; +using autoware::vehicle_info_utils::VehicleInfoUtils; ControlPerformanceAnalysisNode::ControlPerformanceAnalysisNode( const rclcpp::NodeOptions & node_options) @@ -41,7 +41,7 @@ ControlPerformanceAnalysisNode::ControlPerformanceAnalysisNode( using std::placeholders::_1; // Implement Reading Global and Local Variables. - const auto & vehicle_info = VehicleInfoUtil(*this).getVehicleInfo(); + const auto & vehicle_info = VehicleInfoUtils(*this).getVehicleInfo(); param_.wheelbase_ = vehicle_info.wheel_base_m; // Node Parameters. diff --git a/control/control_validator/include/control_validator/control_validator.hpp b/control/control_validator/include/control_validator/control_validator.hpp index e048ef03bf11a..56125cc40b74e 100644 --- a/control/control_validator/include/control_validator/control_validator.hpp +++ b/control/control_validator/include/control_validator/control_validator.hpp @@ -15,9 +15,9 @@ #ifndef CONTROL_VALIDATOR__CONTROL_VALIDATOR_HPP_ #define CONTROL_VALIDATOR__CONTROL_VALIDATOR_HPP_ +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "control_validator/debug_marker.hpp" #include "control_validator/msg/control_validator_status.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" #include #include @@ -83,7 +83,7 @@ class ControlValidator : public rclcpp::Node ControlValidatorStatus validation_status_; ValidationParams validation_params_; // for thresholds - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; bool isAllValid(const ControlValidatorStatus & status); diff --git a/control/control_validator/package.xml b/control/control_validator/package.xml index 2f4400d6ebc57..93779d28d6218 100644 --- a/control/control_validator/package.xml +++ b/control/control_validator/package.xml @@ -21,6 +21,7 @@ rosidl_default_generators autoware_planning_msgs + autoware_vehicle_info_utils diagnostic_updater geometry_msgs motion_utils @@ -28,7 +29,6 @@ rclcpp rclcpp_components tier4_autoware_utils - vehicle_info_util visualization_msgs ament_cmake_ros diff --git a/control/control_validator/src/control_validator.cpp b/control/control_validator/src/control_validator.cpp index 5282e31fef898..be103647f1b36 100644 --- a/control/control_validator/src/control_validator.cpp +++ b/control/control_validator/src/control_validator.cpp @@ -61,7 +61,7 @@ void ControlValidator::setupParameters() } try { - vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); } catch (...) { RCLCPP_ERROR(get_logger(), "failed to get vehicle info. use default value."); vehicle_info_.front_overhang_m = 0.5; diff --git a/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker.hpp b/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker.hpp index d90dbc9474fd8..e29623bf69891 100644 --- a/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker.hpp +++ b/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker.hpp @@ -15,10 +15,10 @@ #ifndef AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_ #define AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_ +#include #include #include #include -#include #include #include @@ -103,17 +103,17 @@ class LaneDepartureChecker public: Output update(const Input & input); - void setParam(const Param & param, const vehicle_info_util::VehicleInfo vehicle_info) + void setParam(const Param & param, const autoware::vehicle_info_utils::VehicleInfo vehicle_info) { param_ = param; - vehicle_info_ptr_ = std::make_shared(vehicle_info); + vehicle_info_ptr_ = std::make_shared(vehicle_info); } void setParam(const Param & param) { param_ = param; } - void setVehicleInfo(const vehicle_info_util::VehicleInfo vehicle_info) + void setVehicleInfo(const autoware::vehicle_info_utils::VehicleInfo vehicle_info) { - vehicle_info_ptr_ = std::make_shared(vehicle_info); + vehicle_info_ptr_ = std::make_shared(vehicle_info); } bool checkPathWillLeaveLane( @@ -137,7 +137,7 @@ class LaneDepartureChecker private: Param param_; - std::shared_ptr vehicle_info_ptr_; + std::shared_ptr vehicle_info_ptr_; static PoseDeviation calcTrajectoryDeviation( const Trajectory & trajectory, const geometry_msgs::msg::Pose & pose, diff --git a/control/lane_departure_checker/include/autoware_lane_departure_checker/util/create_vehicle_footprint.hpp b/control/lane_departure_checker/include/autoware_lane_departure_checker/util/create_vehicle_footprint.hpp index 917317361d702..c85e37212b16f 100644 --- a/control/lane_departure_checker/include/autoware_lane_departure_checker/util/create_vehicle_footprint.hpp +++ b/control/lane_departure_checker/include/autoware_lane_departure_checker/util/create_vehicle_footprint.hpp @@ -29,8 +29,8 @@ #define AUTOWARE_LANE_DEPARTURE_CHECKER__UTIL__CREATE_VEHICLE_FOOTPRINT_HPP_ #include +#include #include -#include #include diff --git a/control/lane_departure_checker/launch/lane_departure_checker.launch.xml b/control/lane_departure_checker/launch/lane_departure_checker.launch.xml index 7ea2e8b2de60a..b9f820f66690b 100644 --- a/control/lane_departure_checker/launch/lane_departure_checker.launch.xml +++ b/control/lane_departure_checker/launch/lane_departure_checker.launch.xml @@ -7,7 +7,7 @@ - + diff --git a/control/lane_departure_checker/package.xml b/control/lane_departure_checker/package.xml index 466dc7351cd9e..7a08cd2907120 100644 --- a/control/lane_departure_checker/package.xml +++ b/control/lane_departure_checker/package.xml @@ -15,6 +15,7 @@ autoware_map_msgs autoware_planning_msgs + autoware_vehicle_info_utils boost diagnostic_updater eigen @@ -30,7 +31,6 @@ tf2_ros tier4_autoware_utils tier4_debug_msgs - vehicle_info_util ament_lint_auto autoware_lint_common diff --git a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index 7956410fdf898..b25b3fd843f4b 100644 --- a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -145,7 +145,7 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o declare_parameter>("boundary_types_to_detect"); // Vehicle Info - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); vehicle_length_m_ = vehicle_info.vehicle_length_m; // Core Parameter 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 a65d818056bd7..efaefd765e793 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 @@ -15,8 +15,8 @@ #ifndef OBSTACLE_COLLISION_CHECKER__OBSTACLE_COLLISION_CHECKER_HPP_ #define OBSTACLE_COLLISION_CHECKER__OBSTACLE_COLLISION_CHECKER_HPP_ +#include #include -#include #include #include @@ -75,7 +75,7 @@ class ObstacleCollisionChecker private: Param param_; - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; //! This function assumes the input trajectory is sampled dense enough static autoware_planning_msgs::msg::Trajectory resampleTrajectory( @@ -86,7 +86,7 @@ class ObstacleCollisionChecker static std::vector createVehicleFootprints( const autoware_planning_msgs::msg::Trajectory & trajectory, const Param & param, - const vehicle_info_util::VehicleInfo & vehicle_info); + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info); static std::vector createVehiclePassingAreas( const std::vector & vehicle_footprints); diff --git a/control/obstacle_collision_checker/launch/obstacle_collision_checker.launch.xml b/control/obstacle_collision_checker/launch/obstacle_collision_checker.launch.xml index 078993d064064..f82384534e040 100755 --- a/control/obstacle_collision_checker/launch/obstacle_collision_checker.launch.xml +++ b/control/obstacle_collision_checker/launch/obstacle_collision_checker.launch.xml @@ -6,7 +6,7 @@ - + diff --git a/control/obstacle_collision_checker/package.xml b/control/obstacle_collision_checker/package.xml index ef7560755a122..795302abe75f4 100644 --- a/control/obstacle_collision_checker/package.xml +++ b/control/obstacle_collision_checker/package.xml @@ -19,6 +19,7 @@ autoware_cmake autoware_planning_msgs + autoware_vehicle_info_utils boost diagnostic_updater eigen @@ -33,7 +34,6 @@ tf2_geometry_msgs tf2_ros tier4_autoware_utils - vehicle_info_util ament_cmake_ros ament_lint_auto 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 6887be4cedd77..a844fe6a50cbf 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 @@ -83,7 +83,7 @@ double calcBrakingDistance( namespace obstacle_collision_checker { ObstacleCollisionChecker::ObstacleCollisionChecker(rclcpp::Node & node) -: vehicle_info_(vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()) +: vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()) { } @@ -188,7 +188,7 @@ autoware_planning_msgs::msg::Trajectory ObstacleCollisionChecker::cutTrajectory( std::vector ObstacleCollisionChecker::createVehicleFootprints( const autoware_planning_msgs::msg::Trajectory & trajectory, const Param & param, - const vehicle_info_util::VehicleInfo & vehicle_info) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) { // Create vehicle footprint in base_link coordinate const auto local_vehicle_footprint = vehicle_info.createFootprint(param.footprint_margin); 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 cfde4ee849728..402123c81d361 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 @@ -14,10 +14,10 @@ #include "obstacle_collision_checker/obstacle_collision_checker_node.hpp" +#include #include #include #include -#include #include #include diff --git a/control/operation_mode_transition_manager/launch/operation_mode_transition_manager.launch.xml b/control/operation_mode_transition_manager/launch/operation_mode_transition_manager.launch.xml index 569d743ba2c4f..c6f03db0fcacc 100644 --- a/control/operation_mode_transition_manager/launch/operation_mode_transition_manager.launch.xml +++ b/control/operation_mode_transition_manager/launch/operation_mode_transition_manager.launch.xml @@ -1,6 +1,6 @@ - + diff --git a/control/operation_mode_transition_manager/package.xml b/control/operation_mode_transition_manager/package.xml index 81517675281c3..40232469fdb6a 100644 --- a/control/operation_mode_transition_manager/package.xml +++ b/control/operation_mode_transition_manager/package.xml @@ -13,6 +13,7 @@ rosidl_default_generators autoware_control_msgs + autoware_vehicle_info_utils autoware_vehicle_msgs component_interface_specs component_interface_utils @@ -25,7 +26,6 @@ tier4_control_msgs tier4_system_msgs tier4_vehicle_msgs - vehicle_info_util ament_cmake_gtest ament_lint_auto diff --git a/control/operation_mode_transition_manager/src/state.cpp b/control/operation_mode_transition_manager/src/state.cpp index 635ead2430677..82270875b2e17 100644 --- a/control/operation_mode_transition_manager/src/state.cpp +++ b/control/operation_mode_transition_manager/src/state.cpp @@ -33,7 +33,7 @@ using tier4_autoware_utils::calcYawDeviation; AutonomousMode::AutonomousMode(rclcpp::Node * node) : logger_(node->get_logger()), clock_(node->get_clock()) { - vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*node).getVehicleInfo(); + vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*node).getVehicleInfo(); sub_control_cmd_ = node->create_subscription( "control_cmd", 1, [this](const Control::SharedPtr msg) { control_cmd_ = *msg; }); diff --git a/control/operation_mode_transition_manager/src/state.hpp b/control/operation_mode_transition_manager/src/state.hpp index e5abd4285ad5f..54434690f2147 100644 --- a/control/operation_mode_transition_manager/src/state.hpp +++ b/control/operation_mode_transition_manager/src/state.hpp @@ -18,8 +18,8 @@ #include "data.hpp" #include "operation_mode_transition_manager/msg/operation_mode_transition_manager_debug.hpp" +#include #include -#include #include #include @@ -83,7 +83,7 @@ class AutonomousMode : public ModeChangeBase Control trajectory_follower_control_cmd_; Odometry kinematics_; Trajectory trajectory_; - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; DebugInfo debug_info_; std::shared_ptr stable_start_time_; // Reset every transition start. 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 8410e7c78f723..2a7a552c1973d 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 @@ -15,6 +15,7 @@ #ifndef PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_ #define PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_ +#include #include #include #include @@ -23,7 +24,6 @@ #include #include #include -#include #include #include @@ -120,7 +120,7 @@ class CollisionChecker // Variables std::shared_ptr debug_ptr_; rclcpp::Node * node_; - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; std::vector predicted_object_history_{}; }; } // namespace autoware::motion::control::predicted_path_checker 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 23696887c7051..6c4832a0dac3e 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 @@ -15,6 +15,8 @@ #ifndef PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_ #define PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_ +#include +#include #include #include #include @@ -24,8 +26,6 @@ #include #include #include -#include -#include #include #include @@ -116,7 +116,7 @@ class PredictedPathCheckerNode : public rclcpp::Node // Variables State current_state_{State::DRIVE}; - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; bool is_calling_set_stop_{false}; bool is_stopped_by_node_{false}; 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 957800ad04305..d9299f09dfb6b 100644 --- a/control/predicted_path_checker/include/predicted_path_checker/utils.hpp +++ b/control/predicted_path_checker/include/predicted_path_checker/utils.hpp @@ -15,10 +15,10 @@ #ifndef PREDICTED_PATH_CHECKER__UTILS_HPP_ #define PREDICTED_PATH_CHECKER__UTILS_HPP_ +#include #include #include #include -#include #include #include @@ -39,6 +39,7 @@ namespace utils { +using autoware::vehicle_info_utils::VehicleInfo; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; using autoware_planning_msgs::msg::TrajectoryPoint; @@ -48,7 +49,6 @@ using geometry_msgs::msg::TransformStamped; using std_msgs::msg::Header; using tier4_autoware_utils::Point2d; using tier4_autoware_utils::Polygon2d; -using vehicle_info_util::VehicleInfo; using PointArray = std::vector; using TrajectoryPoints = std::vector; @@ -57,7 +57,7 @@ void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point & Polygon2d createOneStepPolygon( const geometry_msgs::msg::Pose & base_step_pose, const geometry_msgs::msg::Pose & next_step_pose, - const vehicle_info_util::VehicleInfo & vehicle_info, const double expand_width); + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double expand_width); TrajectoryPoint calcInterpolatedPoint( const TrajectoryPoints & trajectory, const geometry_msgs::msg::Point & target_point, @@ -65,7 +65,7 @@ TrajectoryPoint calcInterpolatedPoint( std::pair findStopPoint( TrajectoryPoints & predicted_trajectory_array, const size_t collision_idx, - const double stop_margin, vehicle_info_util::VehicleInfo & vehicle_info); + const double stop_margin, autoware::vehicle_info_utils::VehicleInfo & vehicle_info); bool isInBrakeDistance( const TrajectoryPoints & trajectory, const size_t stop_idx, const double relative_velocity, diff --git a/control/predicted_path_checker/launch/predicted_path_checker.launch.xml b/control/predicted_path_checker/launch/predicted_path_checker.launch.xml index a35c11b80c1f7..6af1372a5bb4a 100755 --- a/control/predicted_path_checker/launch/predicted_path_checker.launch.xml +++ b/control/predicted_path_checker/launch/predicted_path_checker.launch.xml @@ -7,7 +7,7 @@ - + diff --git a/control/predicted_path_checker/package.xml b/control/predicted_path_checker/package.xml index bca65302dba55..911344c578414 100644 --- a/control/predicted_path_checker/package.xml +++ b/control/predicted_path_checker/package.xml @@ -14,6 +14,7 @@ autoware_perception_msgs autoware_planning_msgs + autoware_vehicle_info_utils boost component_interface_specs component_interface_utils @@ -34,7 +35,6 @@ tier4_control_msgs tier4_external_api_msgs tier4_planning_msgs - vehicle_info_util ament_cmake_ros ament_lint_auto 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 5e8d96805b832..7d392571546b4 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 @@ -27,7 +27,7 @@ CollisionChecker::CollisionChecker( rclcpp::Node * node, std::shared_ptr debug_ptr) : debug_ptr_(std::move(debug_ptr)), node_(node), - vehicle_info_(vehicle_info_util::VehicleInfoUtil(*node).getVehicleInfo()) + vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(*node).getVehicleInfo()) { } 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 28ea21f639a0e..38717a1849ad9 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 @@ -38,7 +38,7 @@ PredictedPathCheckerNode::PredictedPathCheckerNode(const rclcpp::NodeOptions & n group_cli_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); adaptor.init_cli(cli_set_stop_, group_cli_); adaptor.init_sub(sub_stop_state_, this, &PredictedPathCheckerNode::onIsStopped); - vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); // Node Parameter node_param_.update_rate = declare_parameter("update_rate", 10.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 f1c76ce6eef8f..a9c3e2b24f9a5 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 @@ -29,7 +29,7 @@ using tier4_autoware_utils::getRPY; // Utils Functions Polygon2d createOneStepPolygon( const geometry_msgs::msg::Pose & base_step_pose, const geometry_msgs::msg::Pose & next_step_pose, - const vehicle_info_util::VehicleInfo & vehicle_info, const double expand_width) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double expand_width) { Polygon2d polygon; @@ -146,7 +146,7 @@ TrajectoryPoint calcInterpolatedPoint( std::pair findStopPoint( TrajectoryPoints & trajectory_array, const size_t collision_idx, const double stop_margin, - vehicle_info_util::VehicleInfo & vehicle_info) + autoware::vehicle_info_utils::VehicleInfo & vehicle_info) { // It returns the stop point and segment of the point on trajectory. diff --git a/control/pure_pursuit/package.xml b/control/pure_pursuit/package.xml index 0747766af54c8..32744d744f95f 100644 --- a/control/pure_pursuit/package.xml +++ b/control/pure_pursuit/package.xml @@ -16,6 +16,7 @@ autoware_control_msgs autoware_planning_msgs + autoware_vehicle_info_utils boost geometry_msgs libboost-dev @@ -32,7 +33,6 @@ tier4_autoware_utils tier4_debug_msgs trajectory_follower_base - vehicle_info_util visualization_msgs ament_lint_auto diff --git a/control/pure_pursuit/src/pure_pursuit/pure_pursuit_lateral_controller.cpp b/control/pure_pursuit/src/pure_pursuit/pure_pursuit_lateral_controller.cpp index a8232cce5d08d..eddcdb5e362df 100644 --- a/control/pure_pursuit/src/pure_pursuit/pure_pursuit_lateral_controller.cpp +++ b/control/pure_pursuit/src/pure_pursuit/pure_pursuit_lateral_controller.cpp @@ -34,7 +34,7 @@ #include "pure_pursuit/util/planning_utils.hpp" #include "pure_pursuit/util/tf_utils.hpp" -#include +#include #include #include @@ -65,7 +65,7 @@ PurePursuitLateralController::PurePursuitLateralController(rclcpp::Node & node) pure_pursuit_ = std::make_unique(); // Vehicle Parameters - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); param_.wheel_base = vehicle_info.wheel_base_m; param_.max_steering_angle = vehicle_info.max_steer_angle_rad; diff --git a/control/pure_pursuit/src/pure_pursuit/pure_pursuit_node.cpp b/control/pure_pursuit/src/pure_pursuit/pure_pursuit_node.cpp index a4b491930df1e..d629c8f549f52 100644 --- a/control/pure_pursuit/src/pure_pursuit/pure_pursuit_node.cpp +++ b/control/pure_pursuit/src/pure_pursuit/pure_pursuit_node.cpp @@ -34,7 +34,7 @@ #include "pure_pursuit/util/planning_utils.hpp" #include "pure_pursuit/util/tf_utils.hpp" -#include +#include #include #include @@ -59,7 +59,7 @@ PurePursuitNode::PurePursuitNode(const rclcpp::NodeOptions & node_options) pure_pursuit_ = std::make_unique(); // Vehicle Parameters - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); param_.wheel_base = vehicle_info.wheel_base_m; // Node Parameters diff --git a/control/trajectory_follower_base/package.xml b/control/trajectory_follower_base/package.xml index 6f2e9c3e8ebc2..b36b4669be04e 100644 --- a/control/trajectory_follower_base/package.xml +++ b/control/trajectory_follower_base/package.xml @@ -22,6 +22,7 @@ autoware_adapi_v1_msgs autoware_control_msgs autoware_planning_msgs + autoware_vehicle_info_utils autoware_vehicle_msgs diagnostic_msgs diagnostic_updater @@ -37,7 +38,6 @@ tf2_ros tier4_autoware_utils tier4_debug_msgs - vehicle_info_util ament_cmake_ros ament_lint_auto diff --git a/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp b/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp index 8e9752ba19f66..b342aace69bde 100644 --- a/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp +++ b/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp @@ -15,6 +15,7 @@ #ifndef TRAJECTORY_FOLLOWER_NODE__CONTROLLER_NODE_HPP_ #define TRAJECTORY_FOLLOWER_NODE__CONTROLLER_NODE_HPP_ +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2/utils.h" #include "tf2_ros/buffer.h" @@ -24,7 +25,6 @@ #include "trajectory_follower_base/lateral_controller_base.hpp" #include "trajectory_follower_base/longitudinal_controller_base.hpp" #include "trajectory_follower_node/visibility_control.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" #include #include diff --git a/control/trajectory_follower_node/package.xml b/control/trajectory_follower_node/package.xml index 92b99e690931f..c57a07155128a 100644 --- a/control/trajectory_follower_node/package.xml +++ b/control/trajectory_follower_node/package.xml @@ -24,6 +24,7 @@ autoware_mpc_lateral_controller autoware_pid_longitudinal_controller autoware_planning_msgs + autoware_vehicle_info_utils autoware_vehicle_msgs motion_utils pure_pursuit @@ -31,7 +32,6 @@ rclcpp_components tier4_autoware_utils trajectory_follower_base - vehicle_info_util visualization_msgs ros2launch 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 be335a2d78fa3..b05bb5e1d8ad3 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 @@ -15,7 +15,7 @@ #ifndef PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_ #define PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_ -#include +#include #include "autoware_perception_msgs/msg/predicted_objects.hpp" #include @@ -45,10 +45,10 @@ inline int64_t bitShift(int64_t original_id) void addFootprintMarker( visualization_msgs::msg::Marker & marker, const geometry_msgs::msg::Pose & pose, - const vehicle_info_util::VehicleInfo & vehicle_info); + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info); MarkerArray createFootprintMarkerArray( - const Pose & base_link_pose, const vehicle_info_util::VehicleInfo vehicle_info, + const Pose & base_link_pose, const autoware::vehicle_info_utils::VehicleInfo vehicle_info, const std::string && ns, const int32_t & id, const float & r, const float & g, const float & b); MarkerArray createPointsMarkerArray( diff --git a/evaluator/perception_online_evaluator/package.xml b/evaluator/perception_online_evaluator/package.xml index 3f855e2f1f887..d64d3a5ec4957 100644 --- a/evaluator/perception_online_evaluator/package.xml +++ b/evaluator/perception_online_evaluator/package.xml @@ -18,6 +18,7 @@ autoware_cmake autoware_perception_msgs + autoware_vehicle_info_utils diagnostic_msgs eigen geometry_msgs @@ -32,7 +33,6 @@ tf2 tf2_ros tier4_autoware_utils - vehicle_info_util ament_cmake_ros ament_lint_auto diff --git a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp b/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp index 523e11883e755..eddeadc331101 100644 --- a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp +++ b/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp @@ -39,7 +39,7 @@ using visualization_msgs::msg::Marker; void addFootprintMarker( visualization_msgs::msg::Marker & marker, const geometry_msgs::msg::Pose & pose, - const vehicle_info_util::VehicleInfo & vehicle_info) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) { const double half_width = vehicle_info.vehicle_width_m / 2.0; const double base_to_front = vehicle_info.vehicle_length_m - vehicle_info.rear_overhang_m; @@ -57,7 +57,7 @@ void addFootprintMarker( } MarkerArray createFootprintMarkerArray( - const Pose & base_link_pose, const vehicle_info_util::VehicleInfo vehicle_info, + const Pose & base_link_pose, const autoware::vehicle_info_utils::VehicleInfo vehicle_info, const std::string && ns, const int32_t & id, const float & r, const float & g, const float & b) { const auto current_time = rclcpp::Clock{RCL_ROS_TIME}.now(); diff --git a/launch/tier4_sensing_launch/launch/sensing.launch.xml b/launch/tier4_sensing_launch/launch/sensing.launch.xml index 391a1f8bad641..9981c99a8f3fc 100644 --- a/launch/tier4_sensing_launch/launch/sensing.launch.xml +++ b/launch/tier4_sensing_launch/launch/sensing.launch.xml @@ -1,7 +1,7 @@ - + diff --git a/launch/tier4_sensing_launch/package.xml b/launch/tier4_sensing_launch/package.xml index a1f10ee743db5..410f685285b7d 100644 --- a/launch/tier4_sensing_launch/package.xml +++ b/launch/tier4_sensing_launch/package.xml @@ -10,7 +10,7 @@ ament_cmake_auto autoware_cmake - vehicle_info_util + autoware_vehicle_info_utils ament_lint_auto autoware_lint_common 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 d97bbaa2118e5..314c9cfb97a75 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 @@ -18,7 +18,7 @@ #include "pointcloud_preprocessor/filter.hpp" #include "pointcloud_preprocessor/transform_info.hpp" -#include +#include #include @@ -43,7 +43,7 @@ class ScanGroundFilterTest; namespace ground_segmentation { -using vehicle_info_util::VehicleInfo; +using autoware::vehicle_info_utils::VehicleInfo; class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter { diff --git a/perception/ground_segmentation/launch/scan_ground_filter.launch.py b/perception/ground_segmentation/launch/scan_ground_filter.launch.py index d3d856925b9db..df8290997315e 100644 --- a/perception/ground_segmentation/launch/scan_ground_filter.launch.py +++ b/perception/ground_segmentation/launch/scan_ground_filter.launch.py @@ -85,7 +85,7 @@ def add_launch_arg(name: str, default_value=None): return DeclareLaunchArgument(name, default_value=default_value) default_vehicle_info_param = os.path.join( - get_package_share_directory("vehicle_info_util"), "config/vehicle_info.param.yaml" + get_package_share_directory("autoware_vehicle_info_utils"), "config/vehicle_info.param.yaml" ) vehicle_info_param = DeclareLaunchArgument( diff --git a/perception/ground_segmentation/launch/scan_ground_filter.launch.xml b/perception/ground_segmentation/launch/scan_ground_filter.launch.xml index 2a9e4983ecb56..1146138211211 100644 --- a/perception/ground_segmentation/launch/scan_ground_filter.launch.xml +++ b/perception/ground_segmentation/launch/scan_ground_filter.launch.xml @@ -3,7 +3,7 @@ - + diff --git a/perception/ground_segmentation/package.xml b/perception/ground_segmentation/package.xml index 05d5d18baf29e..1b807b393b739 100644 --- a/perception/ground_segmentation/package.xml +++ b/perception/ground_segmentation/package.xml @@ -19,6 +19,7 @@ ament_cmake_auto autoware_cmake + autoware_vehicle_info_utils libopencv-dev pcl_conversions pcl_ros @@ -31,7 +32,6 @@ tf2_eigen tf2_ros tf2_sensor_msgs - vehicle_info_util yaml-cpp ament_lint_auto diff --git a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp index a63d218df62de..e638baba12521 100644 --- a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp @@ -14,10 +14,10 @@ #include "ground_segmentation/scan_ground_filter_nodelet.hpp" +#include #include #include #include -#include #include #include @@ -25,12 +25,12 @@ namespace ground_segmentation { +using autoware::vehicle_info_utils::VehicleInfoUtils; using pointcloud_preprocessor::get_param; using tier4_autoware_utils::calcDistance3d; using tier4_autoware_utils::deg2rad; using tier4_autoware_utils::normalizeDegree; using tier4_autoware_utils::normalizeRadian; -using vehicle_info_util::VehicleInfoUtil; ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & options) : Filter("ScanGroundFilter", options) @@ -59,7 +59,7 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & use_recheck_ground_cluster_ = declare_parameter("use_recheck_ground_cluster"); use_lowest_point_ = declare_parameter("use_lowest_point"); radial_dividers_num_ = std::ceil(2.0 * M_PI / radial_divider_angle_rad_); - vehicle_info_ = VehicleInfoUtil(*this).getVehicleInfo(); + vehicle_info_ = VehicleInfoUtils(*this).getVehicleInfo(); grid_mode_switch_grid_id_ = grid_mode_switch_radius_ / grid_size_m_; // changing the mode of grid division diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/marker_utils/utils.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/marker_utils/utils.hpp index 4abbfd419c43b..04873d9ebcfab 100644 --- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/marker_utils/utils.hpp +++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/marker_utils/utils.hpp @@ -18,7 +18,7 @@ #include "autoware_behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "autoware_behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" -#include +#include #include #include @@ -60,10 +60,10 @@ inline int64_t bitShift(int64_t original_id) void addFootprintMarker( visualization_msgs::msg::Marker & marker, const geometry_msgs::msg::Pose & pose, - const vehicle_info_util::VehicleInfo & vehicle_info); + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info); MarkerArray createFootprintMarkerArray( - const Pose & base_link_pose, const vehicle_info_util::VehicleInfo vehicle_info, + const Pose & base_link_pose, const autoware::vehicle_info_utils::VehicleInfo vehicle_info, const std::string && ns, const int32_t & id, const float & r, const float & g, const float & b); MarkerArray createPointsMarkerArray( @@ -107,8 +107,9 @@ MarkerArray createDrivableLanesMarkerArray( const std::vector & drivable_lanes, std::string && ns); MarkerArray createPredictedPathMarkerArray( - const PredictedPath & ego_predicted_path, const vehicle_info_util::VehicleInfo & vehicle_info, - std::string && ns, const int32_t & id, const float & r, const float & g, const float & b); + const PredictedPath & ego_predicted_path, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, std::string && ns, + const int32_t & id, const float & r, const float & g, const float & b); MarkerArray showPolygon(const CollisionCheckDebugMap & obj_debug_vec, std::string && ns); diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/parameters.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/parameters.hpp index 21d4906380b59..2f14e227d05ef 100644 --- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/parameters.hpp +++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/parameters.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE_BEHAVIOR_PATH_PLANNER_COMMON__PARAMETERS_HPP_ #define AUTOWARE_BEHAVIOR_PATH_PLANNER_COMMON__PARAMETERS_HPP_ -#include +#include struct ModuleConfigParameters { @@ -66,7 +66,7 @@ struct BehaviorPathPlannerParameters double ego_nearest_yaw_threshold; // vehicle info - vehicle_info_util::VehicleInfo vehicle_info; + autoware::vehicle_info_utils::VehicleInfo vehicle_info; double wheel_base; double front_overhang; double rear_overhang; diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/turn_signal_decider.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/turn_signal_decider.hpp index 4dda036fecdb7..d658d29710704 100644 --- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/turn_signal_decider.hpp +++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/turn_signal_decider.hpp @@ -237,7 +237,7 @@ class TurnSignalDecider inline bool straddleRoadBound( const ShiftedPath & path, const ShiftLine & shift_line, const lanelet::ConstLanelets & lanes, - const vehicle_info_util::VehicleInfo & vehicle_info) const + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) const { using boost::geometry::intersects; using tier4_autoware_utils::pose2transform; diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp index 32613948814ae..35da7e4e24382 100644 --- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp +++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp @@ -15,8 +15,8 @@ #ifndef AUTOWARE_BEHAVIOR_PATH_PLANNER_COMMON__UTILS__DRIVABLE_AREA_EXPANSION__PARAMETERS_HPP_ #define AUTOWARE_BEHAVIOR_PATH_PLANNER_COMMON__UTILS__DRIVABLE_AREA_EXPANSION__PARAMETERS_HPP_ +#include #include -#include #include #include @@ -83,7 +83,7 @@ struct DrivableAreaExpansionParameters bool avoid_dynamic_objects{}; bool print_runtime{}; std::vector avoid_linestring_types{}; - vehicle_info_util::VehicleInfo vehicle_info; + autoware::vehicle_info_utils::VehicleInfo vehicle_info; DrivableAreaExpansionParameters() = default; explicit DrivableAreaExpansionParameters(rclcpp::Node & node) { init(node); } @@ -121,7 +121,7 @@ struct DrivableAreaExpansionParameters avoid_linestring_dist = node.declare_parameter(AVOID_LINESTRING_DIST_PARAM); print_runtime = node.declare_parameter(PRINT_RUNTIME_PARAM); - vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); + vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); } }; diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp index d0693a271379e..018e1c87e2302 100644 --- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp +++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp @@ -31,6 +31,7 @@ namespace behavior_path_planner::utils::path_safety_checker { +using autoware::vehicle_info_utils::VehicleInfo; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedPath; using autoware_perception_msgs::msg::Shape; @@ -40,7 +41,6 @@ using geometry_msgs::msg::Twist; using tier4_autoware_utils::calcYawDeviation; using tier4_autoware_utils::Point2d; using tier4_autoware_utils::Polygon2d; -using vehicle_info_util::VehicleInfo; bool isTargetObjectOncoming( const geometry_msgs::msg::Pose & vehicle_pose, const geometry_msgs::msg::Pose & object_pose, @@ -48,13 +48,13 @@ bool isTargetObjectOncoming( bool isTargetObjectFront( const geometry_msgs::msg::Pose & ego_pose, const Polygon2d & obj_polygon, - const vehicle_info_util::VehicleInfo & vehicle_info); + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info); bool isTargetObjectFront( const PathWithLaneId & path, const geometry_msgs::msg::Pose & ego_pose, - const vehicle_info_util::VehicleInfo & vehicle_info, const Polygon2d & obj_polygon); + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const Polygon2d & obj_polygon); Polygon2d createExtendedPolygon( - const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info, + const Pose & base_link_pose, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double lon_length, const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug); Polygon2d createExtendedPolygon( diff --git a/planning/autoware_behavior_path_planner_common/package.xml b/planning/autoware_behavior_path_planner_common/package.xml index 03391063b14fc..e9b33f3e71d6f 100644 --- a/planning/autoware_behavior_path_planner_common/package.xml +++ b/planning/autoware_behavior_path_planner_common/package.xml @@ -48,6 +48,7 @@ autoware_perception_msgs autoware_planning_msgs autoware_rtc_interface + autoware_vehicle_info_utils geometry_msgs interpolation lanelet2_extension @@ -61,7 +62,6 @@ tier4_autoware_utils tier4_planning_msgs traffic_light_utils - vehicle_info_util visualization_msgs ament_cmake_ros ament_lint_auto diff --git a/planning/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp b/planning/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp index 2b150b807c6ce..a22a63ba0fe6d 100644 --- a/planning/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp +++ b/planning/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp @@ -42,7 +42,7 @@ using visualization_msgs::msg::Marker; void addFootprintMarker( visualization_msgs::msg::Marker & marker, const geometry_msgs::msg::Pose & pose, - const vehicle_info_util::VehicleInfo & vehicle_info) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) { const double half_width = vehicle_info.vehicle_width_m / 2.0; const double base_to_front = vehicle_info.vehicle_length_m - vehicle_info.rear_overhang_m; @@ -60,7 +60,7 @@ void addFootprintMarker( } MarkerArray createFootprintMarkerArray( - const Pose & base_link_pose, const vehicle_info_util::VehicleInfo vehicle_info, + const Pose & base_link_pose, const autoware::vehicle_info_utils::VehicleInfo vehicle_info, const std::string && ns, const int32_t & id, const float & r, const float & g, const float & b) { const auto current_time = rclcpp::Clock{RCL_ROS_TIME}.now(); @@ -388,8 +388,9 @@ MarkerArray createDrivableLanesMarkerArray( return msg; } MarkerArray createPredictedPathMarkerArray( - const PredictedPath & predicted_path, const vehicle_info_util::VehicleInfo & vehicle_info, - std::string && ns, const int32_t & id, const float & r, const float & g, const float & b) + const PredictedPath & predicted_path, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, std::string && ns, + const int32_t & id, const float & r, const float & g, const float & b) { if (predicted_path.path.empty()) { return MarkerArray{}; diff --git a/planning/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp b/planning/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp index 233e6f47b92cc..7951be43aa799 100644 --- a/planning/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp @@ -51,7 +51,7 @@ bool isTargetObjectOncoming( bool isTargetObjectFront( const geometry_msgs::msg::Pose & ego_pose, const Polygon2d & obj_polygon, - const vehicle_info_util::VehicleInfo & vehicle_info) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) { const double base_to_front = vehicle_info.max_longitudinal_offset_m; const auto ego_offset_pose = @@ -71,7 +71,7 @@ bool isTargetObjectFront( bool isTargetObjectFront( const PathWithLaneId & path, const geometry_msgs::msg::Pose & ego_pose, - const vehicle_info_util::VehicleInfo & vehicle_info, const Polygon2d & obj_polygon) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const Polygon2d & obj_polygon) { const double base_to_front = vehicle_info.max_longitudinal_offset_m; const auto ego_point = @@ -90,7 +90,7 @@ bool isTargetObjectFront( } Polygon2d createExtendedPolygon( - const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info, + const Pose & base_link_pose, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double lon_length, const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug) { @@ -189,7 +189,7 @@ Polygon2d createExtendedPolygon( Polygon2d createExtendedPolygonAlongPath( const PathWithLaneId & planned_path, const Pose & base_link_pose, - const vehicle_info_util::VehicleInfo & vehicle_info, const double lon_length, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double lon_length, const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug) { const double & base_to_front = vehicle_info.max_longitudinal_offset_m; diff --git a/planning/autoware_behavior_path_planner_common/test/test_safety_check.cpp b/planning/autoware_behavior_path_planner_common/test/test_safety_check.cpp index 3cb71b1f9c4e2..4f23c9f6c07c0 100644 --- a/planning/autoware_behavior_path_planner_common/test/test_safety_check.cpp +++ b/planning/autoware_behavior_path_planner_common/test/test_safety_check.cpp @@ -39,7 +39,7 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon) { using behavior_path_planner::utils::path_safety_checker::createExtendedPolygon; - vehicle_info_util::VehicleInfo vehicle_info; + autoware::vehicle_info_utils::VehicleInfo vehicle_info; vehicle_info.max_longitudinal_offset_m = 4.0; vehicle_info.vehicle_width_m = 2.0; vehicle_info.rear_overhang_m = 1.0; diff --git a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/freespace_pull_out.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/freespace_pull_out.hpp index 613911ba33460..0c8eb1850b9d5 100644 --- a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/freespace_pull_out.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/freespace_pull_out.hpp @@ -36,7 +36,7 @@ class FreespacePullOut : public PullOutPlannerBase public: FreespacePullOut( rclcpp::Node & node, const StartPlannerParameters & parameters, - const vehicle_info_util::VehicleInfo & vehicle_info); + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info); PlannerType getPlannerType() const override { return PlannerType::FREESPACE; } diff --git a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp index 8cbe3569d13fe..38eeb558e85eb 100644 --- a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp @@ -45,7 +45,7 @@ class PullOutPlannerBase public: explicit PullOutPlannerBase(rclcpp::Node & node, const StartPlannerParameters & parameters) { - vehicle_info_ = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); + vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); vehicle_footprint_ = vehicle_info_.createFootprint(); parameters_ = parameters; } @@ -95,7 +95,7 @@ class PullOutPlannerBase collision_check_margin_); }; std::shared_ptr planner_data_; - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; LinearRing2d vehicle_footprint_; StartPlannerParameters parameters_; double collision_check_margin_; diff --git a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/start_planner_module.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/start_planner_module.hpp index 7a98a43efec5b..ccbf1eada7378 100644 --- a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/start_planner_module.hpp @@ -28,8 +28,8 @@ #include "autoware_behavior_path_start_planner_module/shift_pull_out.hpp" #include -#include -#include +#include +#include #include @@ -255,7 +255,7 @@ class StartPlannerModule : public SceneModuleInterface mutable std::shared_ptr ego_predicted_path_params_; mutable std::shared_ptr objects_filtering_params_; mutable std::shared_ptr safety_check_params_; - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; std::vector> start_planners_; PullOutStatus status_; diff --git a/planning/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp b/planning/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp index f0a83741212b8..1b154138d427e 100644 --- a/planning/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp +++ b/planning/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp @@ -28,7 +28,7 @@ namespace behavior_path_planner { FreespacePullOut::FreespacePullOut( rclcpp::Node & node, const StartPlannerParameters & parameters, - const vehicle_info_util::VehicleInfo & vehicle_info) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) : PullOutPlannerBase{node, parameters}, velocity_{parameters.freespace_planner_velocity} { autoware::freespace_planning_algorithms::VehicleShape vehicle_shape( diff --git a/planning/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index b30af17eaa898..2efd2bc17e6ab 100644 --- a/planning/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -60,7 +60,7 @@ StartPlannerModule::StartPlannerModule( objects_of_interest_marker_interface_ptr_map) : SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT parameters_{parameters}, - vehicle_info_{vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()}, + vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, is_freespace_planner_cb_running_{false} { lane_departure_checker_ = std::make_shared(); diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/package.xml b/planning/autoware_behavior_path_static_obstacle_avoidance_module/package.xml index e3699306df1f3..5a47bed4c712a 100644 --- a/planning/autoware_behavior_path_static_obstacle_avoidance_module/package.xml +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/package.xml @@ -24,6 +24,7 @@ autoware_behavior_path_planner_common autoware_perception_msgs autoware_rtc_interface + autoware_vehicle_info_utils behavior_path_planner geometry_msgs lanelet2_extension @@ -41,7 +42,6 @@ tf2_ros tier4_autoware_utils tier4_planning_msgs - vehicle_info_util visualization_msgs ament_cmake_ros diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 8671c71430b3d..1408c096c7e4e 100644 --- a/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -138,7 +138,7 @@ double calcSignedArcLengthToFirstNearestPoint( } geometry_msgs::msg::Polygon createVehiclePolygon( - const vehicle_info_util::VehicleInfo & vehicle_info, const double offset) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double offset) { const auto & i = vehicle_info; const auto & front_m = i.max_longitudinal_offset_m; diff --git a/planning/autoware_behavior_velocity_intersection_module/package.xml b/planning/autoware_behavior_velocity_intersection_module/package.xml index 0655867951ed8..5ce1ff206a1a9 100644 --- a/planning/autoware_behavior_velocity_intersection_module/package.xml +++ b/planning/autoware_behavior_velocity_intersection_module/package.xml @@ -22,6 +22,7 @@ autoware_perception_msgs autoware_planning_msgs autoware_rtc_interface + autoware_vehicle_info_utils fmt geometry_msgs interpolation @@ -36,7 +37,6 @@ tf2_geometry_msgs tier4_autoware_utils tier4_planning_msgs - vehicle_info_util visualization_msgs ament_lint_auto diff --git a/planning/autoware_behavior_velocity_occlusion_spot_module/package.xml b/planning/autoware_behavior_velocity_occlusion_spot_module/package.xml index 2f56bce7155b5..d8177ddc908f3 100644 --- a/planning/autoware_behavior_velocity_occlusion_spot_module/package.xml +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/package.xml @@ -19,6 +19,7 @@ autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs + autoware_vehicle_info_utils geometry_msgs grid_map_ros grid_map_utils @@ -34,7 +35,6 @@ tf2 tf2_geometry_msgs tier4_autoware_utils - vehicle_info_util visualization_msgs ament_cmake_ros diff --git a/planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp index b1757c4142212..c1d345cbc9aac 100644 --- a/planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp +++ b/planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp @@ -109,7 +109,7 @@ OcclusionSpotModuleManager::OcclusionSpotModuleManager(rclcpp::Node & node) pp.grid.free_space_max = getOrDeclareParameter(node, ns + ".grid.free_space_max"); pp.grid.occupied_min = getOrDeclareParameter(node, ns + ".grid.occupied_min"); - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); pp.baselink_to_front = vehicle_info.max_longitudinal_offset_m; pp.wheel_tread = vehicle_info.wheel_tread_m; pp.right_overhang = vehicle_info.right_overhang_m; diff --git a/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp index c69f23215a369..df5d083f5dcb1 100644 --- a/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp +++ b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp @@ -18,8 +18,8 @@ #include "route_handler/route_handler.hpp" #include +#include #include -#include #include #include @@ -51,7 +51,7 @@ class BehaviorVelocityPlannerNode; struct PlannerData { explicit PlannerData(rclcpp::Node & node) - : vehicle_info_(vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()) + : vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()) { max_stop_acceleration_threshold = node.declare_parameter( "max_accel"); // TODO(someone): read min_acc in velocity_controller.param.yaml? @@ -92,7 +92,7 @@ struct PlannerData // route handler std::shared_ptr route_handler_; // parameters - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; // additional parameters double max_stop_acceleration_threshold; diff --git a/planning/autoware_behavior_velocity_planner_common/package.xml b/planning/autoware_behavior_velocity_planner_common/package.xml index 7ab991a247a63..0e317ceb5db66 100644 --- a/planning/autoware_behavior_velocity_planner_common/package.xml +++ b/planning/autoware_behavior_velocity_planner_common/package.xml @@ -24,6 +24,7 @@ autoware_perception_msgs autoware_planning_msgs autoware_rtc_interface + autoware_vehicle_info_utils autoware_velocity_smoother diagnostic_msgs eigen @@ -46,7 +47,6 @@ tier4_autoware_utils tier4_planning_msgs tier4_v2x_msgs - vehicle_info_util visualization_msgs ament_cmake_ros diff --git a/planning/autoware_behavior_velocity_run_out_module/package.xml b/planning/autoware_behavior_velocity_run_out_module/package.xml index 330880b77d3da..284797cbed0a8 100644 --- a/planning/autoware_behavior_velocity_run_out_module/package.xml +++ b/planning/autoware_behavior_velocity_run_out_module/package.xml @@ -22,6 +22,7 @@ autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs + autoware_vehicle_info_utils behavior_velocity_crosswalk_module eigen geometry_msgs @@ -38,7 +39,6 @@ tf2_eigen tf2_ros tier4_autoware_utils - vehicle_info_util visualization_msgs ament_lint_auto diff --git a/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp b/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp index 002a49abae611..4da58522165d6 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp @@ -28,7 +28,7 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node) { // Vehicle Parameters { - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); auto & p = planner_param_.vehicle_param; p.base_to_front = vehicle_info.wheel_base_m + vehicle_info.front_overhang_m; p.base_to_rear = vehicle_info.rear_overhang_m; diff --git a/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp b/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp index 28bfa9569c66d..90f8238d0d543 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp @@ -19,7 +19,7 @@ #include #include -#include +#include #include #include @@ -34,6 +34,7 @@ namespace autoware::behavior_velocity_planner namespace run_out_utils { namespace bg = boost::geometry; +using autoware::vehicle_info_utils::VehicleInfo; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::Shape; @@ -44,7 +45,6 @@ using tier4_autoware_utils::Point2d; using tier4_autoware_utils::Polygon2d; using tier4_debug_msgs::msg::Float32Stamped; using tier4_planning_msgs::msg::PathWithLaneId; -using vehicle_info_util::VehicleInfo; using PathPointsWithLaneId = std::vector; struct CommonParam { diff --git a/planning/autoware_behavior_velocity_virtual_traffic_light_module/package.xml b/planning/autoware_behavior_velocity_virtual_traffic_light_module/package.xml index cda3abbd0eee9..415dcd983a8df 100644 --- a/planning/autoware_behavior_velocity_virtual_traffic_light_module/package.xml +++ b/planning/autoware_behavior_velocity_virtual_traffic_light_module/package.xml @@ -19,6 +19,7 @@ autoware_adapi_v1_msgs autoware_behavior_velocity_planner_common autoware_planning_msgs + autoware_vehicle_info_utils geometry_msgs lanelet2_extension motion_utils @@ -29,7 +30,6 @@ tier4_autoware_utils tier4_planning_msgs tier4_v2x_msgs - vehicle_info_util visualization_msgs ament_lint_auto diff --git a/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp b/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp index 9775e64145529..d413a8721c09e 100644 --- a/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp +++ b/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp @@ -16,13 +16,13 @@ #define SCENE_HPP_ #include +#include #include #include #include #include #include #include -#include #include #include diff --git a/planning/autoware_behavior_velocity_walkway_module/package.xml b/planning/autoware_behavior_velocity_walkway_module/package.xml index bbe87ffb8b2cd..60ef7593ab8ff 100644 --- a/planning/autoware_behavior_velocity_walkway_module/package.xml +++ b/planning/autoware_behavior_velocity_walkway_module/package.xml @@ -19,6 +19,7 @@ autoware_behavior_velocity_planner_common autoware_planning_msgs + autoware_vehicle_info_utils behavior_velocity_crosswalk_module geometry_msgs lanelet2_extension @@ -28,7 +29,6 @@ rclcpp route_handler tier4_autoware_utils - vehicle_info_util visualization_msgs ament_lint_auto diff --git a/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/abstract_algorithm.hpp b/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/abstract_algorithm.hpp index 27a563f4ec1af..394900c9a704c 100644 --- a/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/abstract_algorithm.hpp +++ b/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/abstract_algorithm.hpp @@ -15,8 +15,8 @@ #ifndef AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__ABSTRACT_ALGORITHM_HPP_ #define AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__ABSTRACT_ALGORITHM_HPP_ +#include #include -#include #include #include @@ -69,7 +69,7 @@ struct VehicleShape } explicit VehicleShape( - const vehicle_info_util::VehicleInfo & vehicle_info, const double margin = 0.0) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double margin = 0.0) : length(vehicle_info.vehicle_length_m + margin), width(vehicle_info.vehicle_width_m + margin), base2back(vehicle_info.rear_overhang_m + margin / 2.0) @@ -125,7 +125,7 @@ class AbstractPlanningAlgorithm AbstractPlanningAlgorithm( const PlannerCommonParam & planner_common_param, - const vehicle_info_util::VehicleInfo & vehicle_info, const double margin = 0.0) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double margin = 0.0) : planner_common_param_(planner_common_param), collision_vehicle_shape_(vehicle_info, margin) { } diff --git a/planning/autoware_freespace_planning_algorithms/package.xml b/planning/autoware_freespace_planning_algorithms/package.xml index d2b7ddc7c620a..61173f0a877e4 100644 --- a/planning/autoware_freespace_planning_algorithms/package.xml +++ b/planning/autoware_freespace_planning_algorithms/package.xml @@ -16,6 +16,7 @@ autoware_cmake python_cmake_module + autoware_vehicle_info_utils geometry_msgs nav_msgs nlohmann-json-dev @@ -25,7 +26,6 @@ tf2 tf2_geometry_msgs tier4_autoware_utils - vehicle_info_util ament_cmake_ros ament_lint_auto diff --git a/planning/autoware_path_optimizer/include/autoware_path_optimizer/debug_marker.hpp b/planning/autoware_path_optimizer/include/autoware_path_optimizer/debug_marker.hpp index edca8d706047b..cea58a11a530a 100644 --- a/planning/autoware_path_optimizer/include/autoware_path_optimizer/debug_marker.hpp +++ b/planning/autoware_path_optimizer/include/autoware_path_optimizer/debug_marker.hpp @@ -16,10 +16,10 @@ #include "autoware_path_optimizer/common_structs.hpp" #include "autoware_path_optimizer/type_alias.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "rclcpp/clock.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" #include "tier4_autoware_utils/ros/marker_helper.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" #include #include @@ -30,6 +30,6 @@ namespace autoware::path_optimizer MarkerArray getDebugMarker( const DebugData & debug_data, const std::vector & optimized_points, - const vehicle_info_util::VehicleInfo & vehicle_info, const bool publish_extra_marker); + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const bool publish_extra_marker); } // namespace autoware::path_optimizer #endif // AUTOWARE_PATH_OPTIMIZER__DEBUG_MARKER_HPP_ 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 8c207a9a3830f..98d7e131f4bdc 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 @@ -18,12 +18,12 @@ #include "autoware_path_optimizer/common_structs.hpp" #include "autoware_path_optimizer/state_equation_generator.hpp" #include "autoware_path_optimizer/type_alias.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "gtest/gtest.h" #include "interpolation/linear_interpolation.hpp" #include "interpolation/spline_interpolation_points_2d.hpp" #include "osqp_interface/osqp_interface.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" #include #include @@ -105,8 +105,8 @@ class MPTOptimizer public: MPTOptimizer( rclcpp::Node * node, const bool enable_debug_info, const EgoNearestParam ego_nearest_param, - const vehicle_info_util::VehicleInfo & vehicle_info, const TrajectoryParam & traj_param, - const std::shared_ptr debug_data_ptr, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, + const TrajectoryParam & traj_param, const std::shared_ptr debug_data_ptr, const std::shared_ptr time_keeper_ptr); std::vector optimizeTrajectory(const PlannerData & planner_data); @@ -142,7 +142,8 @@ class MPTOptimizer struct MPTParam { - explicit MPTParam(rclcpp::Node * node, const vehicle_info_util::VehicleInfo & vehicle_info); + explicit MPTParam( + rclcpp::Node * node, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info); MPTParam() = default; void onParam(const std::vector & parameters); @@ -218,7 +219,7 @@ class MPTOptimizer // argument bool enable_debug_info_; EgoNearestParam ego_nearest_param_; - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; TrajectoryParam traj_param_; mutable std::shared_ptr debug_data_ptr_; mutable std::shared_ptr time_keeper_ptr_; 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 30c95debe11cb..c1f644d31aa9a 100644 --- a/planning/autoware_path_optimizer/include/autoware_path_optimizer/node.hpp +++ b/planning/autoware_path_optimizer/include/autoware_path_optimizer/node.hpp @@ -19,11 +19,11 @@ #include "autoware_path_optimizer/mpt_optimizer.hpp" #include "autoware_path_optimizer/replan_checker.hpp" #include "autoware_path_optimizer/type_alias.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "rclcpp/rclcpp.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" #include "tier4_autoware_utils/ros/polling_subscriber.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" #include @@ -63,7 +63,7 @@ class PathOptimizer : public rclcpp::Node DrivingDirectionChecker driving_direction_checker_{}; // argument variables - vehicle_info_util::VehicleInfo vehicle_info_{}; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_{}; mutable std::shared_ptr debug_data_ptr_{nullptr}; mutable std::shared_ptr time_keeper_ptr_{nullptr}; 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 588b68f52a094..aa44a515a08ec 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 @@ -17,11 +17,11 @@ #include "autoware_path_optimizer/common_structs.hpp" #include "autoware_path_optimizer/type_alias.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "interpolation/linear_interpolation.hpp" #include "interpolation/spline_interpolation.hpp" #include "interpolation/spline_interpolation_points_2d.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" #include @@ -65,7 +65,7 @@ bool isSamePoint(const T1 & t1, const T2 & t2) bool isOutsideDrivableAreaFromRectangleFootprint( const geometry_msgs::msg::Pose & pose, const std::vector & left_bound, const std::vector & right_bound, - const vehicle_info_util::VehicleInfo & vehicle_info, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const bool use_footprint_polygon_for_outside_drivable_area_check); } // namespace geometry_utils } // namespace autoware::path_optimizer diff --git a/planning/autoware_path_optimizer/package.xml b/planning/autoware_path_optimizer/package.xml index f02473ebd015e..c158815999398 100644 --- a/planning/autoware_path_optimizer/package.xml +++ b/planning/autoware_path_optimizer/package.xml @@ -16,6 +16,7 @@ autoware_planning_msgs autoware_planning_test_manager + autoware_vehicle_info_utils geometry_msgs interpolation motion_utils @@ -28,7 +29,6 @@ tier4_autoware_utils tier4_debug_msgs tier4_planning_msgs - vehicle_info_util visualization_msgs ament_cmake_ros diff --git a/planning/autoware_path_optimizer/src/debug_marker.cpp b/planning/autoware_path_optimizer/src/debug_marker.cpp index 7c644f4448a0c..c97d5c5adec46 100644 --- a/planning/autoware_path_optimizer/src/debug_marker.cpp +++ b/planning/autoware_path_optimizer/src/debug_marker.cpp @@ -29,7 +29,7 @@ namespace { MarkerArray getFootprintsMarkerArray( const std::vector & mpt_traj, - const vehicle_info_util::VehicleInfo & vehicle_info, const size_t sampling_num) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const size_t sampling_num) { auto marker = createDefaultMarker( "map", rclcpp::Clock().now(), "mpt_footprints", 0, Marker::LINE_STRIP, @@ -73,7 +73,7 @@ MarkerArray getFootprintsMarkerArray( MarkerArray getBoundsWidthMarkerArray( const std::vector & ref_points, - const vehicle_info_util::VehicleInfo & vehicle_info, const size_t sampling_num) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const size_t sampling_num) { const auto current_time = rclcpp::Clock().now(); MarkerArray marker_array; @@ -146,7 +146,7 @@ MarkerArray getBoundsWidthMarkerArray( MarkerArray getBoundsLineMarkerArray( const std::vector & ref_points, - const vehicle_info_util::VehicleInfo & vehicle_info) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) { MarkerArray marker_array; @@ -183,7 +183,7 @@ MarkerArray getBoundsLineMarkerArray( MarkerArray getVehicleCircleLinesMarkerArray( const std::vector & ref_points, const std::vector & vehicle_circle_longitudinal_offsets, - const vehicle_info_util::VehicleInfo & vehicle_info, const size_t sampling_num, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const size_t sampling_num, const std::string & ns) { const auto current_time = rclcpp::Clock().now(); @@ -339,8 +339,9 @@ visualization_msgs::msg::MarkerArray getPointsTextMarkerArray( } visualization_msgs::msg::MarkerArray getFootprintByDrivableAreaMarkerArray( - const geometry_msgs::msg::Pose & stop_pose, const vehicle_info_util::VehicleInfo & vehicle_info, - const std::string & ns, const double r, const double g, const double b) + const geometry_msgs::msg::Pose & stop_pose, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const std::string & ns, + const double r, const double g, const double b) { visualization_msgs::msg::MarkerArray msg; @@ -373,7 +374,7 @@ visualization_msgs::msg::MarkerArray getFootprintByDrivableAreaMarkerArray( MarkerArray getDebugMarker( const DebugData & debug_data, const std::vector & optimized_points, - const vehicle_info_util::VehicleInfo & vehicle_info, const bool publish_extra_marker) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const bool publish_extra_marker) { MarkerArray marker_array; diff --git a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp index 2ab622c6b4b58..0652085d85c48 100644 --- a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp +++ b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp @@ -34,7 +34,7 @@ namespace autoware::path_optimizer namespace { std::tuple, std::vector> calcVehicleCirclesByUniformCircle( - const vehicle_info_util::VehicleInfo & vehicle_info, const size_t circle_num, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const size_t circle_num, const double radius_ratio) { const double lateral_offset = @@ -56,7 +56,7 @@ std::tuple, std::vector> calcVehicleCirclesByUniform } std::tuple, std::vector> calcVehicleCirclesByBicycleModel( - const vehicle_info_util::VehicleInfo & vehicle_info, const size_t circle_num, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const size_t circle_num, const double rear_radius_ratio, const double front_radius_ratio) { if (circle_num < 2) { @@ -84,7 +84,7 @@ std::tuple, std::vector> calcVehicleCirclesByBicycle } std::tuple, std::vector> calcVehicleCirclesByFittingUniformCircle( - const vehicle_info_util::VehicleInfo & vehicle_info, const size_t circle_num) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const size_t circle_num) { if (circle_num < 2) { throw std::invalid_argument("circle_num is less than 2."); @@ -169,7 +169,7 @@ double calcLateralDistToBounds( } // namespace MPTOptimizer::MPTParam::MPTParam( - rclcpp::Node * node, const vehicle_info_util::VehicleInfo & vehicle_info) + rclcpp::Node * node, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) { { // option steer_limit_constraint = node->declare_parameter("mpt.option.steer_limit_constraint"); @@ -393,8 +393,8 @@ void MPTOptimizer::MPTParam::onParam(const std::vector & para MPTOptimizer::MPTOptimizer( rclcpp::Node * node, const bool enable_debug_info, const EgoNearestParam ego_nearest_param, - const vehicle_info_util::VehicleInfo & vehicle_info, const TrajectoryParam & traj_param, - const std::shared_ptr debug_data_ptr, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, + const TrajectoryParam & traj_param, const std::shared_ptr debug_data_ptr, const std::shared_ptr time_keeper_ptr) : enable_debug_info_(enable_debug_info), ego_nearest_param_(ego_nearest_param), diff --git a/planning/autoware_path_optimizer/src/node.cpp b/planning/autoware_path_optimizer/src/node.cpp index 816c0d459d95f..d9df26938a9f8 100644 --- a/planning/autoware_path_optimizer/src/node.cpp +++ b/planning/autoware_path_optimizer/src/node.cpp @@ -84,7 +84,7 @@ std::vector calcSegmentLengthVector(const std::vector & PathOptimizer::PathOptimizer(const rclcpp::NodeOptions & node_options) : Node("path_optimizer", node_options), - vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()), + vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo()), debug_data_ptr_(std::make_shared()), time_keeper_ptr_(std::make_shared()) { diff --git a/planning/autoware_path_optimizer/src/utils/geometry_utils.cpp b/planning/autoware_path_optimizer/src/utils/geometry_utils.cpp index 45302c0b729a9..99eb85d27e054 100644 --- a/planning/autoware_path_optimizer/src/utils/geometry_utils.cpp +++ b/planning/autoware_path_optimizer/src/utils/geometry_utils.cpp @@ -120,7 +120,7 @@ namespace geometry_utils bool isOutsideDrivableAreaFromRectangleFootprint( const geometry_msgs::msg::Pose & pose, const std::vector & left_bound, const std::vector & right_bound, - const vehicle_info_util::VehicleInfo & vehicle_info, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const bool use_footprint_polygon_for_outside_drivable_area_check) { if (left_bound.empty() || right_bound.empty()) { diff --git a/planning/autoware_static_centerline_generator/package.xml b/planning/autoware_static_centerline_generator/package.xml index 26eb41ca1de23..a5e09ceb6270b 100644 --- a/planning/autoware_static_centerline_generator/package.xml +++ b/planning/autoware_static_centerline_generator/package.xml @@ -21,6 +21,7 @@ autoware_path_smoother autoware_perception_msgs autoware_planning_msgs + autoware_vehicle_info_utils geography_utils geometry_msgs global_parameter_loader @@ -36,7 +37,6 @@ route_handler tier4_autoware_utils tier4_map_msgs - vehicle_info_util python3-flask-cors rosidl_default_runtime 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 24e95353eec93..b8a3a8baf67a3 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 @@ -77,8 +77,8 @@ lanelet::BasicPoint2d convert_to_lanelet_point(const geometry_msgs::msg::Point & } LinearRing2d create_vehicle_footprint( - const geometry_msgs::msg::Pose & pose, const vehicle_info_util::VehicleInfo & vehicle_info, - const double margin = 0.0) + const geometry_msgs::msg::Pose & pose, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double margin = 0.0) { const auto & i = vehicle_info; @@ -105,7 +105,8 @@ LinearRing2d create_vehicle_footprint( } geometry_msgs::msg::Pose get_text_pose( - const geometry_msgs::msg::Pose & pose, const vehicle_info_util::VehicleInfo & vehicle_info) + const geometry_msgs::msg::Pose & pose, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) { const auto & i = vehicle_info; @@ -238,7 +239,7 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( rmw_qos_profile_services_default, callback_group_); // vehicle info - vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); centerline_source_ = [&]() { const auto centerline_source_param = declare_parameter("centerline_source"); diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp index f8a65f2794809..2f25a064dca2a 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp @@ -18,10 +18,10 @@ #include "autoware_static_centerline_generator/srv/load_map.hpp" #include "autoware_static_centerline_generator/srv/plan_path.hpp" #include "autoware_static_centerline_generator/srv/plan_route.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "centerline_source/optimization_trajectory_based_centerline.hpp" #include "rclcpp/rclcpp.hpp" #include "type_alias.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" #include "std_msgs/msg/bool.hpp" #include "std_msgs/msg/float32.hpp" @@ -115,7 +115,7 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr callback_group_; // vehicle info - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; }; } // namespace autoware::static_centerline_generator #endif // STATIC_CENTERLINE_GENERATOR_NODE_HPP_ diff --git a/planning/autoware_surround_obstacle_checker/include/autoware_surround_obstacle_checker/debug_marker.hpp b/planning/autoware_surround_obstacle_checker/include/autoware_surround_obstacle_checker/debug_marker.hpp index d2e055bbccaa2..c7ec2e5b564e6 100644 --- a/planning/autoware_surround_obstacle_checker/include/autoware_surround_obstacle_checker/debug_marker.hpp +++ b/planning/autoware_surround_obstacle_checker/include/autoware_surround_obstacle_checker/debug_marker.hpp @@ -15,8 +15,8 @@ #ifndef AUTOWARE_SURROUND_OBSTACLE_CHECKER__DEBUG_MARKER_HPP_ #define AUTOWARE_SURROUND_OBSTACLE_CHECKER__DEBUG_MARKER_HPP_ +#include #include -#include #include #include @@ -34,6 +34,7 @@ namespace autoware::surround_obstacle_checker { +using autoware::vehicle_info_utils::VehicleInfo; using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::VelocityFactor; using autoware_adapi_v1_msgs::msg::VelocityFactorArray; @@ -41,7 +42,6 @@ using geometry_msgs::msg::PolygonStamped; using tier4_planning_msgs::msg::StopFactor; using tier4_planning_msgs::msg::StopReason; using tier4_planning_msgs::msg::StopReasonArray; -using vehicle_info_util::VehicleInfo; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; @@ -56,7 +56,7 @@ class SurroundObstacleCheckerDebugNode { public: explicit SurroundObstacleCheckerDebugNode( - const vehicle_info_util::VehicleInfo & vehicle_info, const double base_link2front, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double base_link2front, const std::string & object_label, const double & surround_check_front_distance, const double & surround_check_side_distance, const double & surround_check_back_distance, const double & surround_check_hysteresis_distance, const geometry_msgs::msg::Pose & self_pose, @@ -79,7 +79,7 @@ class SurroundObstacleCheckerDebugNode rclcpp::Publisher::SharedPtr vehicle_footprint_offset_pub_; rclcpp::Publisher::SharedPtr vehicle_footprint_recover_offset_pub_; - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; double base_link2front_; std::string object_label_; double surround_check_front_distance_; diff --git a/planning/autoware_surround_obstacle_checker/include/autoware_surround_obstacle_checker/node.hpp b/planning/autoware_surround_obstacle_checker/include/autoware_surround_obstacle_checker/node.hpp index 4ccd097b40837..4eb094e6617a4 100644 --- a/planning/autoware_surround_obstacle_checker/include/autoware_surround_obstacle_checker/node.hpp +++ b/planning/autoware_surround_obstacle_checker/include/autoware_surround_obstacle_checker/node.hpp @@ -19,9 +19,9 @@ #include "tier4_autoware_utils/ros/logger_level_configure.hpp" #include "tier4_autoware_utils/ros/polling_subscriber.hpp" +#include #include #include -#include #include #include @@ -46,12 +46,12 @@ namespace autoware::surround_obstacle_checker { +using autoware::vehicle_info_utils::VehicleInfo; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::Shape; using motion_utils::VehicleStopChecker; using tier4_planning_msgs::msg::VelocityLimit; using tier4_planning_msgs::msg::VelocityLimitClearCommand; -using vehicle_info_util::VehicleInfo; using Obstacle = std::pair; @@ -132,7 +132,7 @@ class SurroundObstacleCheckerNode : public rclcpp::Node // parameter NodeParam node_param_; - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; // data nav_msgs::msg::Odometry::ConstSharedPtr odometry_ptr_; diff --git a/planning/autoware_surround_obstacle_checker/package.xml b/planning/autoware_surround_obstacle_checker/package.xml index 3bb961766e9f3..530f850a3c34a 100644 --- a/planning/autoware_surround_obstacle_checker/package.xml +++ b/planning/autoware_surround_obstacle_checker/package.xml @@ -17,6 +17,7 @@ autoware_adapi_v1_msgs autoware_perception_msgs autoware_planning_msgs + autoware_vehicle_info_utils diagnostic_msgs eigen libpcl-all-dev @@ -32,7 +33,6 @@ tf2_ros tier4_autoware_utils tier4_planning_msgs - vehicle_info_util visualization_msgs ament_lint_auto diff --git a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp index ba561a4b8cf35..b676673128269 100644 --- a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp +++ b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp @@ -59,7 +59,7 @@ using tier4_autoware_utils::createMarkerScale; using tier4_autoware_utils::createPoint; SurroundObstacleCheckerDebugNode::SurroundObstacleCheckerDebugNode( - const vehicle_info_util::VehicleInfo & vehicle_info, const double base_link2front, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double base_link2front, const std::string & object_label, const double & surround_check_front_distance, const double & surround_check_side_distance, const double & surround_check_back_distance, const double & surround_check_hysteresis_distance, const geometry_msgs::msg::Pose & self_pose, diff --git a/planning/autoware_surround_obstacle_checker/src/node.cpp b/planning/autoware_surround_obstacle_checker/src/node.cpp index 0744ebecd370c..8d6279eeefb22 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.cpp +++ b/planning/autoware_surround_obstacle_checker/src/node.cpp @@ -196,7 +196,7 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio logger_configure_ = std::make_unique(this); } - vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); // Publishers pub_stop_reason_ = diff --git a/planning/autoware_velocity_smoother/package.xml b/planning/autoware_velocity_smoother/package.xml index 4b5a46e495545..2bfc32ec90a5f 100644 --- a/planning/autoware_velocity_smoother/package.xml +++ b/planning/autoware_velocity_smoother/package.xml @@ -22,6 +22,7 @@ autoware_planning_msgs autoware_planning_test_manager + autoware_vehicle_info_utils geometry_msgs interpolation motion_utils @@ -33,7 +34,6 @@ tier4_autoware_utils tier4_debug_msgs tier4_planning_msgs - vehicle_info_util ament_cmake_ros ament_lint_auto diff --git a/planning/autoware_velocity_smoother/src/node.cpp b/planning/autoware_velocity_smoother/src/node.cpp index 1541b19d70a1c..be1f77fc951b1 100644 --- a/planning/autoware_velocity_smoother/src/node.cpp +++ b/planning/autoware_velocity_smoother/src/node.cpp @@ -20,7 +20,7 @@ #include "motion_utils/marker/marker_helper.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" -#include +#include #include #include @@ -40,7 +40,7 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti using std::placeholders::_1; // set common params - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); wheelbase_ = vehicle_info.wheel_base_m; base_link2front_ = vehicle_info.max_longitudinal_offset_m; initCommonParam(); diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/freespace_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/freespace_pull_over.hpp index b1c4a705ae94d..f05d0b9b3b973 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/freespace_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/freespace_pull_over.hpp @@ -37,7 +37,7 @@ class FreespacePullOver : public PullOverPlannerBase public: FreespacePullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, - const vehicle_info_util::VehicleInfo & vehicle_info); + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info); PullOverPlannerType getPlannerType() const override { return PullOverPlannerType::FREESPACE; } diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp index f41de932bb006..66f7274f888be 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -465,7 +465,7 @@ class GoalPlannerModule : public SceneModuleInterface mutable std::shared_ptr objects_filtering_params_; mutable std::shared_ptr safety_check_params_; - vehicle_info_util::VehicleInfo vehicle_info_{}; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_{}; // planner std::vector> pull_over_planners_; diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp index ca84e7256a01f..c916e6be10d9f 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/pull_over_planner_base.hpp @@ -112,7 +112,7 @@ class PullOverPlannerBase public: PullOverPlannerBase(rclcpp::Node & node, const GoalPlannerParameters & parameters) { - vehicle_info_ = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); + vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); vehicle_footprint_ = vehicle_info_.createFootprint(); parameters_ = parameters; } @@ -133,7 +133,7 @@ class PullOverPlannerBase protected: std::shared_ptr planner_data_; - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; LinearRing2d vehicle_footprint_; GoalPlannerParameters parameters_; diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp index d6c9215e495ae..3de0ba0c99a35 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp @@ -58,8 +58,9 @@ lanelet::ConstLanelets generateExpandedPullOverLanes( lanelet::ConstLanelets generateBetweenEgoAndExpandedPullOverLanes( const lanelet::ConstLanelets & pull_over_lanes, const bool left_side, - const geometry_msgs::msg::Pose ego_pose, const vehicle_info_util::VehicleInfo & vehicle_info, - const double outer_road_offset, const double inner_road_offset); + const geometry_msgs::msg::Pose ego_pose, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double outer_road_offset, + const double inner_road_offset); PredictedObjects extractObjectsInExpandedPullOverLanes( const RouteHandler & route_handler, const bool left_side, const double backward_distance, const double forward_distance, double bound_offset, const PredictedObjects & objects); diff --git a/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp index 360707003f7ca..0a75e5ce94f79 100644 --- a/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp @@ -27,7 +27,7 @@ namespace behavior_path_planner { FreespacePullOver::FreespacePullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, - const vehicle_info_util::VehicleInfo & vehicle_info) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) : PullOverPlannerBase{node, parameters}, velocity_{parameters.freespace_parking_velocity}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index d85205e001d0b..20fe808f51433 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -60,7 +60,7 @@ GoalPlannerModule::GoalPlannerModule( objects_of_interest_marker_interface_ptr_map) : SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT parameters_{parameters}, - vehicle_info_{vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()}, + vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, thread_safe_data_{mutex_, clock_}, is_lane_parking_cb_running_{false}, is_freespace_parking_cb_running_{false}, @@ -95,7 +95,7 @@ GoalPlannerModule::GoalPlannerModule( // set selected goal searcher // currently there is only one goal_searcher_type - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); vehicle_footprint_ = vehicle_info.createFootprint(); goal_searcher_ = std::make_shared(*parameters, vehicle_footprint_); diff --git a/planning/behavior_path_goal_planner_module/src/util.cpp b/planning/behavior_path_goal_planner_module/src/util.cpp index 202eefe37bd83..6b538b6e9c7f5 100644 --- a/planning/behavior_path_goal_planner_module/src/util.cpp +++ b/planning/behavior_path_goal_planner_module/src/util.cpp @@ -105,8 +105,9 @@ static double getOffsetToLanesBoundary( lanelet::ConstLanelets generateBetweenEgoAndExpandedPullOverLanes( const lanelet::ConstLanelets & pull_over_lanes, const bool left_side, - const geometry_msgs::msg::Pose ego_pose, const vehicle_info_util::VehicleInfo & vehicle_info, - const double outer_road_offset, const double inner_road_offset) + const geometry_msgs::msg::Pose ego_pose, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double outer_road_offset, + const double inner_road_offset) { const double front_overhang = vehicle_info.front_overhang_m, wheel_base = vehicle_info.wheel_base_m, wheel_tread = vehicle_info.wheel_tread_m; diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp index e9a9ab15f6bc0..a7f65f82f4e9e 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp @@ -241,7 +241,7 @@ rclcpp::Logger getLogger(const std::string & type); * @return Polygon2d A polygon representing the current 2D footprint of the ego vehicle. */ Polygon2d getEgoCurrentFootprint( - const Pose & ego_pose, const vehicle_info_util::VehicleInfo & ego_info); + const Pose & ego_pose, const autoware::vehicle_info_utils::VehicleInfo & ego_info); /** * @brief Checks if the given polygon is within an intersection area. @@ -304,7 +304,7 @@ namespace behavior_path_planner::utils::lane_change::debug geometry_msgs::msg::Point32 create_point32(const geometry_msgs::msg::Pose & pose); geometry_msgs::msg::Polygon createExecutionArea( - const vehicle_info_util::VehicleInfo & vehicle_info, const Pose & pose, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const Pose & pose, double additional_lon_offset, double additional_lat_offset); } // namespace behavior_path_planner::utils::lane_change::debug diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index 20b502886ccef..2fafd7c41d4a3 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -25,6 +25,7 @@ #include "object_recognition_utils/predicted_path_utils.hpp" #include "tier4_autoware_utils/math/unit_conversion.hpp" +#include #include #include #include @@ -33,7 +34,6 @@ #include #include #include -#include #include @@ -1159,7 +1159,7 @@ rclcpp::Logger getLogger(const std::string & type) } Polygon2d getEgoCurrentFootprint( - const Pose & ego_pose, const vehicle_info_util::VehicleInfo & ego_info) + const Pose & ego_pose, const autoware::vehicle_info_utils::VehicleInfo & ego_info) { const auto base_to_front = ego_info.max_longitudinal_offset_m; const auto base_to_rear = ego_info.rear_overhang_m; @@ -1240,7 +1240,7 @@ geometry_msgs::msg::Point32 create_point32(const geometry_msgs::msg::Pose & pose }; geometry_msgs::msg::Polygon createExecutionArea( - const vehicle_info_util::VehicleInfo & vehicle_info, const Pose & pose, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const Pose & pose, double additional_lon_offset, double additional_lat_offset) { const double & base_to_front = vehicle_info.max_longitudinal_offset_m; diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index 1ce6e65bee219..2c88a6d156f3d 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -45,6 +45,7 @@ autoware_perception_msgs autoware_planning_msgs autoware_planning_test_manager + autoware_vehicle_info_utils autoware_vehicle_msgs behaviortree_cpp_v3 geometry_msgs @@ -66,7 +67,6 @@ tf2_ros tier4_autoware_utils tier4_planning_msgs - vehicle_info_util visualization_msgs ament_cmake_ros diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index e6ebe66f3f440..d5b49f5efa4d2 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -19,8 +19,8 @@ #include "autoware_behavior_path_planner_common/utils/path_utils.hpp" #include "motion_utils/trajectory/conversion.hpp" +#include #include -#include #include @@ -44,8 +44,8 @@ rclcpp::SubscriptionOptions createSubscriptionOptions(rclcpp::Node * node_ptr) namespace behavior_path_planner { +using autoware::vehicle_info_utils::VehicleInfoUtils; using tier4_planning_msgs::msg::PathChangeModuleId; -using vehicle_info_util::VehicleInfoUtil; BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & node_options) : Node("behavior_path_planner", node_options) @@ -212,7 +212,7 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() p.traffic_light_signal_timeout = declare_parameter("traffic_light_signal_timeout"); // vehicle info - const auto vehicle_info = VehicleInfoUtil(*this).getVehicleInfo(); + const auto vehicle_info = VehicleInfoUtils(*this).getVehicleInfo(); p.vehicle_info = vehicle_info; p.vehicle_width = vehicle_info.vehicle_width_m; p.vehicle_length = vehicle_info.vehicle_length_m; diff --git a/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_module.hpp b/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_module.hpp index 0a5dec8d07b4f..5cf7b1f4e927d 100644 --- a/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_module.hpp +++ b/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_module.hpp @@ -28,6 +28,7 @@ #include "autoware_sampler_common/constraints/soft_constraint.hpp" #include "autoware_sampler_common/structures.hpp" #include "autoware_sampler_common/transform/spline_transform.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "behavior_path_sampling_planner_module/sampling_planner_parameters.hpp" #include "behavior_path_sampling_planner_module/util.hpp" #include "lanelet2_extension/utility/query.hpp" @@ -39,7 +40,6 @@ #include "tier4_autoware_utils/math/constants.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" #include "tier4_planning_msgs/msg/lateral_offset.hpp" #include "tier4_planning_msgs/msg/path_with_lane_id.hpp" @@ -248,7 +248,7 @@ class SamplingPlannerModule : public SceneModuleInterface // member // std::shared_ptr params_; std::shared_ptr internal_params_; - vehicle_info_util::VehicleInfo vehicle_info_{}; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_{}; std::optional prev_sampling_path_ = std::nullopt; // move to utils diff --git a/planning/behavior_path_sampling_planner_module/package.xml b/planning/behavior_path_sampling_planner_module/package.xml index 0583056db4293..c48f3240ab84d 100644 --- a/planning/behavior_path_sampling_planner_module/package.xml +++ b/planning/behavior_path_sampling_planner_module/package.xml @@ -20,6 +20,7 @@ autoware_perception_msgs autoware_planning_msgs autoware_planning_test_manager + autoware_vehicle_info_utils autoware_vehicle_msgs geometry_msgs interpolation @@ -37,7 +38,6 @@ tf2_ros tier4_autoware_utils tier4_planning_msgs - vehicle_info_util visualization_msgs ament_cmake_ros diff --git a/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp b/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp index 22187652bd663..d2cc57d46de30 100644 --- a/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp +++ b/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp @@ -35,7 +35,7 @@ SamplingPlannerModule::SamplingPlannerModule( std::unordered_map> & objects_of_interest_marker_interface_ptr_map) : SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT - vehicle_info_{vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()} + vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()} { internal_params_ = std::make_shared(); updateModuleParams(parameters); diff --git a/planning/behavior_velocity_crosswalk_module/package.xml b/planning/behavior_velocity_crosswalk_module/package.xml index eebf9c4d4a14f..87ccdebd02fcf 100644 --- a/planning/behavior_velocity_crosswalk_module/package.xml +++ b/planning/behavior_velocity_crosswalk_module/package.xml @@ -24,6 +24,7 @@ autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs + autoware_vehicle_info_utils eigen geometry_msgs grid_map_core @@ -42,7 +43,6 @@ tier4_api_msgs tier4_autoware_utils tier4_debug_msgs - vehicle_info_util visualization_msgs ament_lint_auto diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 91893c5224550..0db87508975a0 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -1207,7 +1207,7 @@ geometry_msgs::msg::Polygon CrosswalkModule::createObjectPolygon( } geometry_msgs::msg::Polygon CrosswalkModule::createVehiclePolygon( - const vehicle_info_util::VehicleInfo & vehicle_info) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) { const auto & i = vehicle_info; const auto & front_m = i.max_longitudinal_offset_m; diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 13ecddafb6490..75f75846d4f4b 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -419,7 +419,7 @@ class CrosswalkModule : public SceneModuleInterface const double width_m, const double length_m); static geometry_msgs::msg::Polygon createVehiclePolygon( - const vehicle_info_util::VehicleInfo & vehicle_info); + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info); void recordTime(const int step_num) { diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml b/planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml index 6b9db657d6d8e..f25ded5e1823c 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/package.xml @@ -15,6 +15,7 @@ autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs + autoware_vehicle_info_utils geometry_msgs libboost-dev motion_utils @@ -24,7 +25,6 @@ tf2 tier4_autoware_utils tier4_planning_msgs - vehicle_info_util visualization_msgs ament_lint_auto diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp index ddb8c842fb92d..f594432c9e452 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp @@ -43,7 +43,7 @@ DynamicObstacleStopModuleManager::DynamicObstacleStopModuleManager(rclcpp::Node pp.ignore_unavoidable_collisions = getOrDeclareParameter(node, ns + ".ignore_unavoidable_collisions"); - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); pp.ego_lateral_offset = std::max(std::abs(vehicle_info.min_lateral_offset_m), vehicle_info.max_lateral_offset_m); pp.ego_longitudinal_offset = vehicle_info.max_longitudinal_offset_m; diff --git a/planning/behavior_velocity_no_stopping_area_module/package.xml b/planning/behavior_velocity_no_stopping_area_module/package.xml index baa51d6681490..97b3b01ee31e1 100644 --- a/planning/behavior_velocity_no_stopping_area_module/package.xml +++ b/planning/behavior_velocity_no_stopping_area_module/package.xml @@ -20,6 +20,7 @@ autoware_behavior_velocity_planner_common autoware_perception_msgs autoware_planning_msgs + autoware_vehicle_info_utils eigen geometry_msgs interpolation @@ -34,7 +35,6 @@ tf2_geometry_msgs tier4_autoware_utils tier4_planning_msgs - vehicle_info_util visualization_msgs ament_lint_auto diff --git a/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp b/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp index 6aeac1e9d8dd3..31682fe0419d2 100644 --- a/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp +++ b/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp @@ -39,7 +39,7 @@ NoStoppingAreaModuleManager::NoStoppingAreaModuleManager(rclcpp::Node & node) { const std::string ns(getModuleName()); auto & pp = planner_param_; - const auto & vi = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); + const auto & vi = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); pp.state_clear_time = getOrDeclareParameter(node, ns + ".state_clear_time"); pp.stuck_vehicle_vel_thr = getOrDeclareParameter(node, ns + ".stuck_vehicle_vel_thr"); pp.stop_margin = getOrDeclareParameter(node, ns + ".stop_margin"); diff --git a/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp b/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp index fbaef46c43511..22205ce427632 100644 --- a/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp +++ b/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp @@ -35,8 +35,8 @@ #include #include +#include #include -#include #include #include diff --git a/planning/freespace_planner/launch/freespace_planner.launch.xml b/planning/freespace_planner/launch/freespace_planner.launch.xml index 7c2408b0311f5..3c8cce7a93941 100644 --- a/planning/freespace_planner/launch/freespace_planner.launch.xml +++ b/planning/freespace_planner/launch/freespace_planner.launch.xml @@ -9,7 +9,7 @@ - + diff --git a/planning/freespace_planner/package.xml b/planning/freespace_planner/package.xml index a29202060a640..06004ce9f308f 100644 --- a/planning/freespace_planner/package.xml +++ b/planning/freespace_planner/package.xml @@ -18,6 +18,7 @@ autoware_freespace_planning_algorithms autoware_planning_msgs autoware_planning_test_manager + autoware_vehicle_info_utils geometry_msgs motion_utils nav_msgs @@ -29,7 +30,6 @@ tf2_ros tier4_autoware_utils tier4_planning_msgs - vehicle_info_util visualization_msgs ament_cmake_ros diff --git a/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp b/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp index 322bf2697a1f6..f17b9227c89bc 100644 --- a/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp +++ b/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp @@ -241,7 +241,8 @@ FreespacePlannerNode::FreespacePlannerNode(const rclcpp::NodeOptions & node_opti // set vehicle_info { - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + const auto vehicle_info = + autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); vehicle_shape_.length = vehicle_info.vehicle_length_m; vehicle_shape_.width = vehicle_info.vehicle_width_m; vehicle_shape_.base2back = vehicle_info.rear_overhang_m; diff --git a/planning/mission_planner/package.xml b/planning/mission_planner/package.xml index f878953d50420..6782736c3e173 100644 --- a/planning/mission_planner/package.xml +++ b/planning/mission_planner/package.xml @@ -20,6 +20,7 @@ autoware_adapi_v1_msgs autoware_map_msgs autoware_planning_msgs + autoware_vehicle_info_utils geometry_msgs lanelet2_extension motion_utils @@ -31,7 +32,6 @@ tf2_ros tier4_autoware_utils tier4_planning_msgs - vehicle_info_util ament_lint_auto autoware_lint_common diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index 5ba152af6611d..a7f3cfaa7ee34 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -16,6 +16,7 @@ #include "utility_functions.hpp" +#include #include #include #include @@ -25,7 +26,6 @@ #include #include #include -#include #include #include @@ -108,7 +108,7 @@ double project_goal_to_map( geometry_msgs::msg::Pose get_closest_centerline_pose( const lanelet::ConstLanelets & road_lanelets, const geometry_msgs::msg::Pose & point, - vehicle_info_util::VehicleInfo vehicle_info) + autoware::vehicle_info_utils::VehicleInfo vehicle_info) { lanelet::Lanelet closest_lanelet; if (!lanelet::utils::query::getClosestLaneletWithConstrains( @@ -152,7 +152,7 @@ void DefaultPlanner::initialize_common(rclcpp::Node * node) pub_goal_footprint_marker_ = node_->create_publisher("~/debug/goal_footprint", durable_qos); - vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*node_).getVehicleInfo(); + vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*node_).getVehicleInfo(); param_.goal_angle_threshold_deg = node_->declare_parameter("goal_angle_threshold_deg"); param_.enable_correct_goal_pose = node_->declare_parameter("enable_correct_goal_pose"); param_.consider_no_drivable_lanes = node_->declare_parameter("consider_no_drivable_lanes"); diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp index 60c232162991d..49000a750a9a1 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp @@ -15,10 +15,10 @@ #ifndef LANELET2_PLUGINS__DEFAULT_PLANNER_HPP_ #define LANELET2_PLUGINS__DEFAULT_PLANNER_HPP_ +#include #include #include #include -#include #include #include @@ -52,7 +52,7 @@ class DefaultPlanner : public mission_planner::PlannerPlugin void clearRoute() override; MarkerArray visualize(const LaneletRoute & route) const override; MarkerArray visualize_debug_footprint(tier4_autoware_utils::LinearRing2d goal_footprint_) const; - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; private: using RouteSections = std::vector; diff --git a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp index 428cd979a2526..ed8dbfed63bfe 100644 --- a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp @@ -15,10 +15,10 @@ #ifndef LANELET2_PLUGINS__UTILITY_FUNCTIONS_HPP_ #define LANELET2_PLUGINS__UTILITY_FUNCTIONS_HPP_ +#include #include #include #include -#include #include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml index 051415e9856ed..a6176555ae7af 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml @@ -17,6 +17,7 @@ autoware_motion_velocity_planner_common autoware_perception_msgs autoware_planning_msgs + autoware_vehicle_info_utils geometry_msgs lanelet2_extension libboost-dev @@ -28,7 +29,6 @@ tier4_autoware_utils tier4_planning_msgs traffic_light_utils - vehicle_info_util visualization_msgs ament_cmake_ros 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 0fe7b783adf31..11640f9ad2c8e 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 @@ -100,7 +100,7 @@ void OutOfLaneModule::init_parameters(rclcpp::Node & node) pp.extra_rear_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_rear_offset"); pp.extra_left_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_left_offset"); pp.extra_right_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_right_offset"); - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); pp.front_offset = vehicle_info.max_longitudinal_offset_m; pp.rear_offset = vehicle_info.min_longitudinal_offset_m; pp.left_offset = vehicle_info.max_lateral_offset_m; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp index 73d71e0d0f955..a25ab5d55a910 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp @@ -15,9 +15,9 @@ #ifndef AUTOWARE_MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ #define AUTOWARE_MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ +#include #include #include -#include #include #include @@ -54,7 +54,7 @@ struct TrafficSignalStamped struct PlannerData { explicit PlannerData(rclcpp::Node & node) - : vehicle_info_(vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()) + : vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()) { } @@ -81,7 +81,7 @@ struct PlannerData // velocity smoother std::shared_ptr velocity_smoother_{}; // parameters - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; /** *@fn diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp index 3aea741e3b2f4..8f9724d9c8bed 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp @@ -53,7 +53,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node // main functions std::vector createOneStepPolygons( const std::vector & traj_points, - const vehicle_info_util::VehicleInfo & vehicle_info, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const geometry_msgs::msg::Pose & current_ego_pose, const double lat_margin = 0.0) const; std::vector convertToObstacles( const Odometry & odometry, const PredictedObjects & objects, diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp index 44626206ec038..a832e74c76db0 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp @@ -15,11 +15,11 @@ #ifndef OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ #define OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp" #include "obstacle_cruise_planner/optimization_based_planner/velocity_optimizer.hpp" #include "obstacle_cruise_planner/planner_interface.hpp" #include "obstacle_cruise_planner/type_alias.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" #include #include @@ -35,8 +35,8 @@ class OptimizationBasedPlanner : public PlannerInterface public: OptimizationBasedPlanner( rclcpp::Node & node, const LongitudinalInfo & longitudinal_info, - const vehicle_info_util::VehicleInfo & vehicle_info, const EgoNearestParam & ego_nearest_param, - const std::shared_ptr debug_data_ptr); + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, + const EgoNearestParam & ego_nearest_param, const std::shared_ptr debug_data_ptr); std::vector generateCruiseTrajectory( const PlannerData & planner_data, const std::vector & stop_traj_points, diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp index 26fd3a8ce2ce2..9d688cdac419b 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp @@ -49,8 +49,8 @@ class PIDBasedPlanner : public PlannerInterface PIDBasedPlanner( rclcpp::Node & node, const LongitudinalInfo & longitudinal_info, - const vehicle_info_util::VehicleInfo & vehicle_info, const EgoNearestParam & ego_nearest_param, - const std::shared_ptr debug_data_ptr); + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, + const EgoNearestParam & ego_nearest_param, const std::shared_ptr debug_data_ptr); std::vector generateCruiseTrajectory( const PlannerData & planner_data, const std::vector & stop_traj_points, diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp index 7a060657e16af..f3dadbf5e5e51 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp @@ -38,8 +38,8 @@ class PlannerInterface public: PlannerInterface( rclcpp::Node & node, const LongitudinalInfo & longitudinal_info, - const vehicle_info_util::VehicleInfo & vehicle_info, const EgoNearestParam & ego_nearest_param, - const std::shared_ptr debug_data_ptr) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, + const EgoNearestParam & ego_nearest_param, const std::shared_ptr debug_data_ptr) : longitudinal_info_(longitudinal_info), vehicle_info_(vehicle_info), ego_nearest_param_(ego_nearest_param), @@ -135,7 +135,7 @@ class PlannerInterface rclcpp::Publisher::SharedPtr stop_speed_exceeded_pub_; // Vehicle Parameters - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; EgoNearestParam ego_nearest_param_; diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/polygon_utils.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/polygon_utils.hpp index 71d0f84637abc..455d40a7a7e87 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/polygon_utils.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/polygon_utils.hpp @@ -15,10 +15,10 @@ #ifndef OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_ #define OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_ +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "obstacle_cruise_planner/common_structs.hpp" #include "obstacle_cruise_planner/type_alias.hpp" #include "tier4_autoware_utils/geometry/boost_geometry.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" #include @@ -36,12 +36,12 @@ using tier4_autoware_utils::Polygon2d; Polygon2d createOneStepPolygon( const std::vector & last_poses, const std::vector & current_poses, - const vehicle_info_util::VehicleInfo & vehicle_info, const double lat_margin); + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double lat_margin); std::optional> getCollisionPoint( const std::vector & traj_points, const std::vector & traj_polygons, const Obstacle & obstacle, const bool is_driving_forward, - const vehicle_info_util::VehicleInfo & vehicle_info); + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info); std::vector getCollisionPoints( const std::vector & traj_points, const std::vector & traj_polygons, diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/type_alias.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/type_alias.hpp index 979cef8610cbd..196526c22aac9 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/type_alias.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/type_alias.hpp @@ -15,7 +15,7 @@ #ifndef OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_ #define OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_ -#include "vehicle_info_util/vehicle_info_util.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "autoware_adapi_v1_msgs/msg/planning_behavior.hpp" #include "autoware_adapi_v1_msgs/msg/velocity_factor_array.hpp" @@ -35,6 +35,7 @@ #include "tier4_planning_msgs/msg/velocity_limit_clear_command.hpp" #include "visualization_msgs/msg/marker_array.hpp" +using autoware::vehicle_info_utils::VehicleInfo; using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::VelocityFactor; using autoware_adapi_v1_msgs::msg::VelocityFactorArray; @@ -56,7 +57,6 @@ using tier4_planning_msgs::msg::StopReasonArray; using tier4_planning_msgs::msg::StopSpeedExceeded; using tier4_planning_msgs::msg::VelocityLimit; using tier4_planning_msgs::msg::VelocityLimitClearCommand; -using vehicle_info_util::VehicleInfo; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; namespace bg = boost::geometry; diff --git a/planning/obstacle_cruise_planner/launch/obstacle_cruise_planner.launch.xml b/planning/obstacle_cruise_planner/launch/obstacle_cruise_planner.launch.xml index a6c95d65acc6a..8db1ae8b46223 100644 --- a/planning/obstacle_cruise_planner/launch/obstacle_cruise_planner.launch.xml +++ b/planning/obstacle_cruise_planner/launch/obstacle_cruise_planner.launch.xml @@ -4,7 +4,7 @@ - + diff --git a/planning/obstacle_cruise_planner/package.xml b/planning/obstacle_cruise_planner/package.xml index e394add65b05d..2a6e240093b14 100644 --- a/planning/obstacle_cruise_planner/package.xml +++ b/planning/obstacle_cruise_planner/package.xml @@ -21,6 +21,7 @@ autoware_perception_msgs autoware_planning_msgs autoware_planning_test_manager + autoware_vehicle_info_utils geometry_msgs interpolation lanelet2_extension @@ -37,7 +38,6 @@ tier4_autoware_utils tier4_debug_msgs tier4_planning_msgs - vehicle_info_util visualization_msgs ament_cmake_ros diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index 41ae29b7d470f..866090a3c4696 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -353,7 +353,7 @@ void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam( ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & node_options) : Node("obstacle_cruise_planner", node_options), - vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()), + vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo()), debug_data_ptr_(std::make_shared()) { using std::placeholders::_1; @@ -558,7 +558,7 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms std::vector ObstacleCruisePlannerNode::createOneStepPolygons( const std::vector & traj_points, - const vehicle_info_util::VehicleInfo & vehicle_info, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const geometry_msgs::msg::Pose & current_ego_pose, const double lat_margin) const { const auto & p = behavior_determination_param_; diff --git a/planning/obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp b/planning/obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp index 1b5120eba0a11..a040ac598681f 100644 --- a/planning/obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp +++ b/planning/obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp @@ -38,8 +38,8 @@ constexpr double CLOSE_S_DIST_THRESHOLD = 1e-3; OptimizationBasedPlanner::OptimizationBasedPlanner( rclcpp::Node & node, const LongitudinalInfo & longitudinal_info, - const vehicle_info_util::VehicleInfo & vehicle_info, const EgoNearestParam & ego_nearest_param, - const std::shared_ptr debug_data_ptr) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, + const EgoNearestParam & ego_nearest_param, const std::shared_ptr debug_data_ptr) : PlannerInterface(node, longitudinal_info, vehicle_info, ego_nearest_param, debug_data_ptr) { smoothed_traj_sub_ = node.create_subscription( diff --git a/planning/obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp b/planning/obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp index a5afbe74cc9c4..3084764432c0e 100644 --- a/planning/obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp +++ b/planning/obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp @@ -58,8 +58,8 @@ T getSign(const T val) PIDBasedPlanner::PIDBasedPlanner( rclcpp::Node & node, const LongitudinalInfo & longitudinal_info, - const vehicle_info_util::VehicleInfo & vehicle_info, const EgoNearestParam & ego_nearest_param, - const std::shared_ptr debug_data_ptr) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, + const EgoNearestParam & ego_nearest_param, const std::shared_ptr debug_data_ptr) : PlannerInterface(node, longitudinal_info, vehicle_info, ego_nearest_param, debug_data_ptr) { min_accel_during_cruise_ = diff --git a/planning/obstacle_cruise_planner/src/polygon_utils.cpp b/planning/obstacle_cruise_planner/src/polygon_utils.cpp index 1bd2de0bd985c..f354c53365dc1 100644 --- a/planning/obstacle_cruise_planner/src/polygon_utils.cpp +++ b/planning/obstacle_cruise_planner/src/polygon_utils.cpp @@ -95,7 +95,7 @@ namespace polygon_utils std::optional> getCollisionPoint( const std::vector & traj_points, const std::vector & traj_polygons, const Obstacle & obstacle, const bool is_driving_forward, - const vehicle_info_util::VehicleInfo & vehicle_info) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) { const auto collision_info = getCollisionIndex(traj_points, traj_polygons, obstacle.pose, obstacle.stamp, obstacle.shape); 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 723d7e8d12e56..d7fc83dbdf7ed 100644 --- a/planning/obstacle_stop_planner/include/obstacle_stop_planner/node.hpp +++ b/planning/obstacle_stop_planner/include/obstacle_stop_planner/node.hpp @@ -21,13 +21,13 @@ #include "tier4_autoware_utils/ros/logger_level_configure.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" +#include #include #include #include #include #include #include -#include #include #include @@ -77,6 +77,7 @@ using nav_msgs::msg::Odometry; using sensor_msgs::msg::PointCloud2; using std_msgs::msg::Header; +using autoware::vehicle_info_utils::VehicleInfo; using autoware_perception_msgs::msg::PredictedObjects; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; @@ -90,7 +91,6 @@ using tier4_debug_msgs::msg::Float64Stamped; using tier4_planning_msgs::msg::ExpandStopRange; using tier4_planning_msgs::msg::VelocityLimit; using tier4_planning_msgs::msg::VelocityLimitClearCommand; -using vehicle_info_util::VehicleInfo; using TrajectoryPoints = std::vector; using PointCloud = pcl::PointCloud; 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 b43e51873c09e..7b30ac61af46f 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 @@ -18,8 +18,8 @@ #include "obstacle_stop_planner/planner_data.hpp" +#include #include -#include #include #include @@ -45,10 +45,10 @@ using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseArray; using std_msgs::msg::Header; +using autoware::vehicle_info_utils::VehicleInfo; using autoware_planning_msgs::msg::TrajectoryPoint; using tier4_autoware_utils::Point2d; using tier4_autoware_utils::Polygon2d; -using vehicle_info_util::VehicleInfo; using TrajectoryPoints = std::vector; using PointCloud = pcl::PointCloud; diff --git a/planning/obstacle_stop_planner/launch/obstacle_stop_planner.launch.xml b/planning/obstacle_stop_planner/launch/obstacle_stop_planner.launch.xml index bec3aef6b4558..db38370d36dfb 100644 --- a/planning/obstacle_stop_planner/launch/obstacle_stop_planner.launch.xml +++ b/planning/obstacle_stop_planner/launch/obstacle_stop_planner.launch.xml @@ -4,7 +4,7 @@ - + diff --git a/planning/obstacle_stop_planner/package.xml b/planning/obstacle_stop_planner/package.xml index fcf09b96c1345..39195f2840b81 100644 --- a/planning/obstacle_stop_planner/package.xml +++ b/planning/obstacle_stop_planner/package.xml @@ -24,6 +24,7 @@ autoware_perception_msgs autoware_planning_msgs autoware_planning_test_manager + autoware_vehicle_info_utils diagnostic_msgs motion_utils nav_msgs @@ -41,7 +42,6 @@ tier4_autoware_utils tier4_debug_msgs tier4_planning_msgs - vehicle_info_util visualization_msgs ament_cmake_ros diff --git a/planning/obstacle_stop_planner/src/node.cpp b/planning/obstacle_stop_planner/src/node.cpp index 31c044c93af22..3a269d738e02d 100644 --- a/planning/obstacle_stop_planner/src/node.cpp +++ b/planning/obstacle_stop_planner/src/node.cpp @@ -56,7 +56,7 @@ ObstacleStopPlannerNode::ObstacleStopPlannerNode(const rclcpp::NodeOptions & nod : Node("obstacle_stop_planner", node_options) { // Vehicle Parameters - vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); const auto & i = vehicle_info_; diff --git a/planning/obstacle_velocity_limiter/launch/obstacle_velocity_limiter.launch.xml b/planning/obstacle_velocity_limiter/launch/obstacle_velocity_limiter.launch.xml index 4781ceda528bf..cb6cab3b125e2 100644 --- a/planning/obstacle_velocity_limiter/launch/obstacle_velocity_limiter.launch.xml +++ b/planning/obstacle_velocity_limiter/launch/obstacle_velocity_limiter.launch.xml @@ -10,7 +10,7 @@ - + diff --git a/planning/obstacle_velocity_limiter/package.xml b/planning/obstacle_velocity_limiter/package.xml index 49e424bfbc9ef..ad83f397902fc 100644 --- a/planning/obstacle_velocity_limiter/package.xml +++ b/planning/obstacle_velocity_limiter/package.xml @@ -14,6 +14,7 @@ autoware_perception_msgs autoware_planning_msgs autoware_planning_test_manager + autoware_vehicle_info_utils eigen grid_map_msgs grid_map_ros @@ -31,7 +32,6 @@ tf2_geometry_msgs tier4_autoware_utils tier4_planning_msgs - vehicle_info_util visualization_msgs ament_cmake_ros diff --git a/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter_node.cpp b/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter_node.cpp index 18cf534da8c7e..4b28d9a62759b 100644 --- a/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter_node.cpp +++ b/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter_node.cpp @@ -22,12 +22,12 @@ #include "obstacle_velocity_limiter/trajectory_preprocessing.hpp" #include "obstacle_velocity_limiter/types.hpp" +#include #include #include #include #include #include -#include #include @@ -71,7 +71,7 @@ ObstacleVelocityLimiterNode::ObstacleVelocityLimiterNode(const rclcpp::NodeOptio pub_runtime_ = create_publisher("~/output/runtime_microseconds", 1); - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); vehicle_lateral_offset_ = static_cast(vehicle_info.max_lateral_offset_m); vehicle_front_offset_ = static_cast(vehicle_info.max_longitudinal_offset_m); diff --git a/planning/planning_validator/include/autoware_planning_validator/planning_validator.hpp b/planning/planning_validator/include/autoware_planning_validator/planning_validator.hpp index 113c70fecb62c..fa0b116eafe86 100644 --- a/planning/planning_validator/include/autoware_planning_validator/planning_validator.hpp +++ b/planning/planning_validator/include/autoware_planning_validator/planning_validator.hpp @@ -17,9 +17,9 @@ #include "autoware_planning_validator/debug_marker.hpp" #include "autoware_planning_validator/msg/planning_validator_status.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" #include #include @@ -124,7 +124,7 @@ class PlanningValidator : public rclcpp::Node PlanningValidatorStatus validation_status_; ValidationParams validation_params_; // for thresholds - vehicle_info_util::VehicleInfo vehicle_info_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; bool isAllValid(const PlanningValidatorStatus & status) const; diff --git a/planning/planning_validator/package.xml b/planning/planning_validator/package.xml index 7fe57e68928d9..541396b52b02b 100644 --- a/planning/planning_validator/package.xml +++ b/planning/planning_validator/package.xml @@ -17,6 +17,7 @@ autoware_planning_msgs autoware_planning_test_manager + autoware_vehicle_info_utils diagnostic_updater geometry_msgs motion_utils @@ -24,7 +25,6 @@ rclcpp rclcpp_components tier4_autoware_utils - vehicle_info_util visualization_msgs ament_cmake_ros diff --git a/planning/planning_validator/src/planning_validator.cpp b/planning/planning_validator/src/planning_validator.cpp index aac50e24c5d5c..420ee564cda72 100644 --- a/planning/planning_validator/src/planning_validator.cpp +++ b/planning/planning_validator/src/planning_validator.cpp @@ -92,7 +92,7 @@ void PlanningValidator::setupParameters() } try { - vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); } catch (...) { RCLCPP_ERROR(get_logger(), "failed to get vehicle info. use default value."); vehicle_info_.front_overhang_m = 0.5; 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 e44c38aed2b53..143b9ee30b2c2 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 @@ -19,8 +19,8 @@ #include "autoware_path_sampler/parameters.hpp" #include "autoware_path_sampler/type_alias.hpp" #include "autoware_sampler_common/transform/spline_transform.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "rclcpp/rclcpp.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" #include @@ -39,7 +39,7 @@ class PathSampler : public rclcpp::Node protected: // for the static_centerline_generator package // argument variables - vehicle_info_util::VehicleInfo vehicle_info_{}; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_{}; mutable DebugData debug_data_{}; mutable std::shared_ptr time_keeper_ptr_{nullptr}; 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 abd2fa367bc7b..b6c63eeffed18 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 @@ -17,12 +17,12 @@ #include "autoware_path_sampler/common_structs.hpp" #include "autoware_path_sampler/type_alias.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "eigen3/Eigen/Core" #include "interpolation/linear_interpolation.hpp" #include "interpolation/spline_interpolation.hpp" #include "interpolation/spline_interpolation_points_2d.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" #include "autoware_planning_msgs/msg/path_point.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" diff --git a/planning/sampling_based_planner/autoware_path_sampler/package.xml b/planning/sampling_based_planner/autoware_path_sampler/package.xml index 011da8d469607..a48e6c0b836bc 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/package.xml +++ b/planning/sampling_based_planner/autoware_path_sampler/package.xml @@ -17,6 +17,7 @@ autoware_frenet_planner autoware_perception_msgs autoware_planning_msgs + autoware_vehicle_info_utils geometry_msgs interpolation motion_utils @@ -28,7 +29,6 @@ tier4_autoware_utils tier4_debug_msgs tier4_planning_msgs - vehicle_info_util visualization_msgs ament_cmake_ros 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 a82c1b6a52a26..9a828d23af5cb 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp +++ b/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp @@ -60,7 +60,7 @@ bool hasZeroVelocity(const TrajectoryPoint & traj_point) PathSampler::PathSampler(const rclcpp::NodeOptions & node_options) : Node("path_sampler", node_options), - vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()), + vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo()), time_keeper_ptr_(std::make_shared()) { // interface publisher diff --git a/sensing/pointcloud_preprocessor/launch/polygon_remover.launch.py b/sensing/pointcloud_preprocessor/launch/polygon_remover.launch.py index 175209d49fa8b..98bc5a6dd2699 100644 --- a/sensing/pointcloud_preprocessor/launch/polygon_remover.launch.py +++ b/sensing/pointcloud_preprocessor/launch/polygon_remover.launch.py @@ -26,7 +26,7 @@ def generate_launch_description(): pkg = "pointcloud_preprocessor" param_file = os.path.join( - get_package_share_directory("vehicle_info_util"), "config/polygon_remover.yaml" + get_package_share_directory("autoware_vehicle_info_utils"), "config/polygon_remover.yaml" ) with open(param_file, "r") as f: diff --git a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py index a8eb88f55df19..fd01f42928947 100644 --- a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py +++ b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py @@ -91,7 +91,7 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg( "vehicle_info_param_file", [ - FindPackageShare("vehicle_info_util"), + FindPackageShare("autoware_vehicle_info_utils"), "/config/vehicle_info.param.yaml", ], "path to the parameter file of vehicle information", diff --git a/simulator/simple_planning_simulator/package.xml b/simulator/simple_planning_simulator/package.xml index 5f04fba4fdb8e..b820c5c6c3df0 100644 --- a/simulator/simple_planning_simulator/package.xml +++ b/simulator/simple_planning_simulator/package.xml @@ -18,6 +18,7 @@ autoware_control_msgs autoware_map_msgs autoware_planning_msgs + autoware_vehicle_info_utils autoware_vehicle_msgs geometry_msgs lanelet2_core @@ -35,7 +36,6 @@ tier4_autoware_utils tier4_external_api_msgs tier4_vehicle_msgs - vehicle_info_util autoware_cmake launch_ros 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 3b65218aaf03d..c66a0c6f1f922 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 @@ -14,13 +14,13 @@ #include "simple_planning_simulator/simple_planning_simulator_core.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include "rclcpp_components/register_node_macro.hpp" #include "simple_planning_simulator/vehicle_model/sim_model.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" #include "tier4_autoware_utils/ros/msg_covariance.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" #include #include @@ -232,7 +232,7 @@ void SimplePlanningSimulator::initialize_vehicle_model() const double debug_acc_scaling_factor = declare_parameter("debug_acc_scaling_factor", 1.0); const double debug_steer_scaling_factor = declare_parameter("debug_steer_scaling_factor", 1.0); - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); const double wheelbase = vehicle_info.wheel_base_m; std::vector model_module_paths = declare_parameter>( diff --git a/system/default_ad_api/package.xml b/system/default_ad_api/package.xml index 77276c7acb0e3..315fdea27a3f3 100644 --- a/system/default_ad_api/package.xml +++ b/system/default_ad_api/package.xml @@ -17,6 +17,7 @@ autoware_adapi_version_msgs autoware_planning_msgs autoware_system_msgs + autoware_vehicle_info_utils autoware_vehicle_msgs component_interface_specs component_interface_utils @@ -32,7 +33,6 @@ tier4_api_msgs tier4_control_msgs tier4_system_msgs - vehicle_info_util python3-flask diff --git a/system/default_ad_api/src/vehicle_info.cpp b/system/default_ad_api/src/vehicle_info.cpp index cff7ac5cd5eae..8bf7da65f6e33 100644 --- a/system/default_ad_api/src/vehicle_info.cpp +++ b/system/default_ad_api/src/vehicle_info.cpp @@ -14,7 +14,7 @@ #include "vehicle_info.hpp" -#include +#include namespace { @@ -41,7 +41,7 @@ VehicleInfoNode::VehicleInfoNode(const rclcpp::NodeOptions & options) res->dimensions = dimensions_; }; - const auto vehicle = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + const auto vehicle = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); dimensions_.wheel_radius = vehicle.wheel_radius_m; dimensions_.wheel_width = vehicle.wheel_width_m; dimensions_.wheel_base = vehicle.wheel_base_m; diff --git a/vehicle/autoware_steer_offset_estimator/package.xml b/vehicle/autoware_steer_offset_estimator/package.xml index 4246f8dee8a4e..08db4f5903abe 100644 --- a/vehicle/autoware_steer_offset_estimator/package.xml +++ b/vehicle/autoware_steer_offset_estimator/package.xml @@ -9,6 +9,7 @@ ament_cmake_auto autoware_cmake + autoware_vehicle_info_utils autoware_vehicle_msgs diagnostic_updater geometry_msgs @@ -17,7 +18,6 @@ std_msgs tier4_autoware_utils tier4_debug_msgs - vehicle_info_util global_parameter_loader pose2twist diff --git a/vehicle/autoware_steer_offset_estimator/src/steer_offset_estimator_node.cpp b/vehicle/autoware_steer_offset_estimator/src/steer_offset_estimator_node.cpp index fdb5fdb404c0c..375e989f8f201 100644 --- a/vehicle/autoware_steer_offset_estimator/src/steer_offset_estimator_node.cpp +++ b/vehicle/autoware_steer_offset_estimator/src/steer_offset_estimator_node.cpp @@ -14,7 +14,7 @@ #include "autoware_steer_offset_estimator/steer_offset_estimator_node.hpp" -#include "vehicle_info_util/vehicle_info_util.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include #include @@ -26,7 +26,7 @@ SteerOffsetEstimatorNode::SteerOffsetEstimatorNode(const rclcpp::NodeOptions & n { using std::placeholders::_1; // get parameter - const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); wheel_base_ = vehicle_info.wheel_base_m; covariance_ = this->declare_parameter("initial_covariance"); forgetting_factor_ = this->declare_parameter("forgetting_factor"); diff --git a/vehicle/vehicle_info_util/CMakeLists.txt b/vehicle/autoware_vehicle_info_utils/CMakeLists.txt similarity index 71% rename from vehicle/vehicle_info_util/CMakeLists.txt rename to vehicle/autoware_vehicle_info_utils/CMakeLists.txt index ca72b0ed2db65..6d090ab3ebff7 100644 --- a/vehicle/vehicle_info_util/CMakeLists.txt +++ b/vehicle/autoware_vehicle_info_utils/CMakeLists.txt @@ -1,12 +1,12 @@ cmake_minimum_required(VERSION 3.14) -project(vehicle_info_util) +project(autoware_vehicle_info_utils) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_library(vehicle_info_util SHARED +ament_auto_add_library(vehicle_info_utils SHARED src/vehicle_info.cpp - src/vehicle_info_util.cpp + src/vehicle_info_utils.cpp ) ament_auto_package( diff --git a/vehicle/vehicle_info_util/Readme.md b/vehicle/autoware_vehicle_info_utils/Readme.md similarity index 89% rename from vehicle/vehicle_info_util/Readme.md rename to vehicle/autoware_vehicle_info_utils/Readme.md index 600fd62270d81..537dc04aa8c69 100644 --- a/vehicle/vehicle_info_util/Readme.md +++ b/vehicle/autoware_vehicle_info_utils/Readme.md @@ -42,15 +42,15 @@ We have implemented a versioning system for the `vehicle_info.param.yaml` file t #### Minimum turning radius ```sh -$ ros2 run vehicle_info_util min_turning_radius_calculator.py -yaml path is /home/autoware/pilot-auto/install/vehicle_info_util/share/vehicle_info_util/config/vehicle_info.param.yaml +$ ros2 run autoware_vehicle_info_utils min_turning_radius_calculator.py +yaml path is /home/autoware/pilot-auto/install/autoware_vehicle_info_utils/share/autoware_vehicle_info_utils/config/vehicle_info.param.yaml Minimum turning radius is 3.253042620027102 [m] for rear, 4.253220695862465 [m] for front. ``` You can designate yaml file with `-y` option as follows. ```sh -ros2 run vehicle_info_util min_turning_radius_calculator.py -y +ros2 run autoware_vehicle_info_utils min_turning_radius_calculator.py -y ``` ## Assumptions / Known limits diff --git a/vehicle/vehicle_info_util/config/polygon_remover.yaml b/vehicle/autoware_vehicle_info_utils/config/polygon_remover.yaml similarity index 100% rename from vehicle/vehicle_info_util/config/polygon_remover.yaml rename to vehicle/autoware_vehicle_info_utils/config/polygon_remover.yaml diff --git a/vehicle/vehicle_info_util/config/vehicle_info.param.yaml b/vehicle/autoware_vehicle_info_utils/config/vehicle_info.param.yaml similarity index 100% rename from vehicle/vehicle_info_util/config/vehicle_info.param.yaml rename to vehicle/autoware_vehicle_info_utils/config/vehicle_info.param.yaml diff --git a/vehicle/vehicle_info_util/config/vehicle_mirror.param.yaml b/vehicle/autoware_vehicle_info_utils/config/vehicle_mirror.param.yaml similarity index 100% rename from vehicle/vehicle_info_util/config/vehicle_mirror.param.yaml rename to vehicle/autoware_vehicle_info_utils/config/vehicle_mirror.param.yaml diff --git a/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp b/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp similarity index 89% rename from vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp rename to vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp index cdbbe0427b145..c94ea01224da2 100644 --- a/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info.hpp +++ b/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef VEHICLE_INFO_UTIL__VEHICLE_INFO_HPP_ -#define VEHICLE_INFO_UTIL__VEHICLE_INFO_HPP_ +#ifndef AUTOWARE_VEHICLE_INFO_UTILS__VEHICLE_INFO_HPP_ +#define AUTOWARE_VEHICLE_INFO_UTILS__VEHICLE_INFO_HPP_ #include "tier4_autoware_utils/geometry/boost_geometry.hpp" -namespace vehicle_info_util +namespace autoware::vehicle_info_utils { /// Data class for vehicle info struct VehicleInfo @@ -59,6 +59,6 @@ VehicleInfo createVehicleInfo( const double left_overhang_m, const double right_overhang_m, const double vehicle_height_m, const double max_steer_angle_rad); -} // namespace vehicle_info_util +} // namespace autoware::vehicle_info_utils -#endif // VEHICLE_INFO_UTIL__VEHICLE_INFO_HPP_ +#endif // AUTOWARE_VEHICLE_INFO_UTILS__VEHICLE_INFO_HPP_ diff --git a/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info_util.hpp b/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info_utils.hpp similarity index 71% rename from vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info_util.hpp rename to vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info_utils.hpp index 5e1623ada5ed3..d3ca339f78451 100644 --- a/vehicle/vehicle_info_util/include/vehicle_info_util/vehicle_info_util.hpp +++ b/vehicle/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info_utils.hpp @@ -12,23 +12,23 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef VEHICLE_INFO_UTIL__VEHICLE_INFO_UTIL_HPP_ -#define VEHICLE_INFO_UTIL__VEHICLE_INFO_UTIL_HPP_ +#ifndef AUTOWARE_VEHICLE_INFO_UTILS__VEHICLE_INFO_UTILS_HPP_ +#define AUTOWARE_VEHICLE_INFO_UTILS__VEHICLE_INFO_UTILS_HPP_ -#include "vehicle_info_util/vehicle_info.hpp" +#include "autoware_vehicle_info_utils/vehicle_info.hpp" #include -namespace vehicle_info_util +namespace autoware::vehicle_info_utils { /// This is a convenience class for saving you from declaring all parameters /// manually and calculating derived parameters. /// This class supposes that necessary parameters are set when the node is launched. -class VehicleInfoUtil +class VehicleInfoUtils { public: /// Constructor - explicit VehicleInfoUtil(rclcpp::Node & node); + explicit VehicleInfoUtils(rclcpp::Node & node); /// Get vehicle info VehicleInfo getVehicleInfo(); @@ -38,6 +38,6 @@ class VehicleInfoUtil VehicleInfo vehicle_info_; }; -} // namespace vehicle_info_util +} // namespace autoware::vehicle_info_utils -#endif // VEHICLE_INFO_UTIL__VEHICLE_INFO_UTIL_HPP_ +#endif // AUTOWARE_VEHICLE_INFO_UTILS__VEHICLE_INFO_UTILS_HPP_ diff --git a/vehicle/vehicle_info_util/launch/sample.launch.py b/vehicle/autoware_vehicle_info_utils/launch/sample.launch.py similarity index 91% rename from vehicle/vehicle_info_util/launch/sample.launch.py rename to vehicle/autoware_vehicle_info_utils/launch/sample.launch.py index c0be2bc4c4c48..5f83bc695230e 100644 --- a/vehicle/vehicle_info_util/launch/sample.launch.py +++ b/vehicle/autoware_vehicle_info_utils/launch/sample.launch.py @@ -30,14 +30,14 @@ def launch_setup(context, *args, **kwargs): set_use_sim_time = SetParameter(name="use_sim_time", value=LaunchConfiguration("use_sim_time")) vehicle_info_param_path = os.path.join( - get_package_share_directory("vehicle_info_util"), + get_package_share_directory("autoware_vehicle_info_utils"), "config", "vehicle_info.param.yaml", ) # vehicle_info load_vehicle_info = IncludeLaunchDescription( PythonLaunchDescriptionSource( - [FindPackageShare("vehicle_info_util"), "/launch/vehicle_info.launch.py"] + [FindPackageShare("autoware_vehicle_info_utils"), "/launch/vehicle_info.launch.py"] ), launch_arguments={"vehicle_info_param_file": [vehicle_info_param_path]}.items(), ) diff --git a/vehicle/vehicle_info_util/launch/vehicle_info.launch.py b/vehicle/autoware_vehicle_info_utils/launch/vehicle_info.launch.py similarity index 100% rename from vehicle/vehicle_info_util/launch/vehicle_info.launch.py rename to vehicle/autoware_vehicle_info_utils/launch/vehicle_info.launch.py diff --git a/vehicle/vehicle_info_util/package.xml b/vehicle/autoware_vehicle_info_utils/package.xml similarity index 88% rename from vehicle/vehicle_info_util/package.xml rename to vehicle/autoware_vehicle_info_utils/package.xml index 139f8439d60c9..bd8ec0cb601a0 100644 --- a/vehicle/vehicle_info_util/package.xml +++ b/vehicle/autoware_vehicle_info_utils/package.xml @@ -1,9 +1,9 @@ - vehicle_info_util + autoware_vehicle_info_utils 0.1.0 - The vehicle_info_util package + The autoware_vehicle_info_utils package Taiki Tanaka diff --git a/vehicle/vehicle_info_util/scripts/min_turning_radius_calculator.py b/vehicle/autoware_vehicle_info_utils/scripts/min_turning_radius_calculator.py similarity index 93% rename from vehicle/vehicle_info_util/scripts/min_turning_radius_calculator.py rename to vehicle/autoware_vehicle_info_utils/scripts/min_turning_radius_calculator.py index 9e25b928c8b74..0b581786b25ad 100755 --- a/vehicle/vehicle_info_util/scripts/min_turning_radius_calculator.py +++ b/vehicle/autoware_vehicle_info_utils/scripts/min_turning_radius_calculator.py @@ -41,7 +41,8 @@ def main(yaml_path): if __name__ == "__main__": default_yaml_path = ( - get_package_share_directory("vehicle_info_util") + "/config/vehicle_info.param.yaml" + get_package_share_directory("autoware_vehicle_info_utils") + + "/config/vehicle_info.param.yaml" ) parser = argparse.ArgumentParser() diff --git a/vehicle/vehicle_info_util/src/vehicle_info.cpp b/vehicle/autoware_vehicle_info_utils/src/vehicle_info.cpp similarity index 95% rename from vehicle/vehicle_info_util/src/vehicle_info.cpp rename to vehicle/autoware_vehicle_info_utils/src/vehicle_info.cpp index 1a47252f82d04..c7f587d20b2f4 100644 --- a/vehicle/vehicle_info_util/src/vehicle_info.cpp +++ b/vehicle/autoware_vehicle_info_utils/src/vehicle_info.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "vehicle_info_util/vehicle_info.hpp" +#include "autoware_vehicle_info_utils/vehicle_info.hpp" -namespace vehicle_info_util +namespace autoware::vehicle_info_utils { tier4_autoware_utils::LinearRing2d VehicleInfo::createFootprint(const double margin) const { @@ -85,4 +85,4 @@ VehicleInfo createVehicleInfo( }; } -} // namespace vehicle_info_util +} // namespace autoware::vehicle_info_utils diff --git a/vehicle/vehicle_info_util/src/vehicle_info_util.cpp b/vehicle/autoware_vehicle_info_utils/src/vehicle_info_utils.cpp similarity index 90% rename from vehicle/vehicle_info_util/src/vehicle_info_util.cpp rename to vehicle/autoware_vehicle_info_utils/src/vehicle_info_utils.cpp index 262a4b21c0cf7..e313391f6207a 100644 --- a/vehicle/vehicle_info_util/src/vehicle_info_util.cpp +++ b/vehicle/autoware_vehicle_info_utils/src/vehicle_info_utils.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "vehicle_info_util/vehicle_info_util.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include @@ -36,9 +36,9 @@ T getParameter(rclcpp::Node & node, const std::string & name) } } // namespace -namespace vehicle_info_util +namespace autoware::vehicle_info_utils { -VehicleInfoUtil::VehicleInfoUtil(rclcpp::Node & node) +VehicleInfoUtils::VehicleInfoUtils(rclcpp::Node & node) { vehicle_info_.wheel_radius_m = getParameter(node, "wheel_radius"); vehicle_info_.wheel_width_m = getParameter(node, "wheel_width"); @@ -52,7 +52,7 @@ VehicleInfoUtil::VehicleInfoUtil(rclcpp::Node & node) vehicle_info_.max_steer_angle_rad = getParameter(node, "max_steer_angle"); } -VehicleInfo VehicleInfoUtil::getVehicleInfo() +VehicleInfo VehicleInfoUtils::getVehicleInfo() { return createVehicleInfo( vehicle_info_.wheel_radius_m, vehicle_info_.wheel_width_m, vehicle_info_.wheel_base_m, @@ -60,4 +60,4 @@ VehicleInfo VehicleInfoUtil::getVehicleInfo() vehicle_info_.left_overhang_m, vehicle_info_.right_overhang_m, vehicle_info_.vehicle_height_m, vehicle_info_.max_steer_angle_rad); } -} // namespace vehicle_info_util +} // namespace autoware::vehicle_info_utils From 210513d7694ceb0288fc6c701ff7883421fa3552 Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Mon, 10 Jun 2024 17:02:27 +0900 Subject: [PATCH 63/65] refactor(localization_util): apply static analysis (#7399) * refactor based on linter Signed-off-by: a-maumau * style(pre-commit): autofix * 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> --- localization/localization_util/src/util_func.cpp | 4 ++-- .../localization_util/test/test_smart_pose_buffer.cpp | 10 +--------- 2 files changed, 3 insertions(+), 11 deletions(-) diff --git a/localization/localization_util/src/util_func.cpp b/localization/localization_util/src/util_func.cpp index ae6f0b61f063c..133442df68dcd 100644 --- a/localization/localization_util/src/util_func.cpp +++ b/localization/localization_util/src/util_func.cpp @@ -28,11 +28,11 @@ std_msgs::msg::ColorRGBA exchange_color_crc(double x) color.b = 1.0; color.g = static_cast(std::sin(x * 2.0 * M_PI)); color.r = 0; - } else if (x > 0.25 && x <= 0.5) { + } else if (x <= 0.5) { color.b = static_cast(std::sin(x * 2 * M_PI)); color.g = 1.0; color.r = 0; - } else if (x > 0.5 && x <= 0.75) { + } else if (x <= 0.75) { color.b = 0; color.g = 1.0; color.r = static_cast(-std::sin(x * 2.0 * M_PI)); diff --git a/localization/localization_util/test/test_smart_pose_buffer.cpp b/localization/localization_util/test/test_smart_pose_buffer.cpp index 2520e458f2d33..a8ed6d98b6064 100644 --- a/localization/localization_util/test/test_smart_pose_buffer.cpp +++ b/localization/localization_util/test/test_smart_pose_buffer.cpp @@ -42,15 +42,7 @@ bool compare_pose( pose_a.pose.pose.orientation.w == pose_b.pose.pose.orientation.w; } -class TestSmartPoseBuffer : public ::testing::Test -{ -protected: - void SetUp() override {} - - void TearDown() override {} -}; - -TEST_F(TestSmartPoseBuffer, interpolate_pose) // NOLINT +TEST(TestSmartPoseBuffer, interpolate_pose) // NOLINT { rclcpp::Logger logger = rclcpp::get_logger("test_logger"); const double pose_timeout_sec = 10.0; From 40cc4125bbf2fa5487ed145ceb30d1564fc996f7 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Mon, 10 Jun 2024 17:20:24 +0900 Subject: [PATCH 64/65] feat(planning_validator): use polling subscriber (#7356) * use polling subscriber Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../autoware_planning_validator/planning_validator.hpp | 4 +++- planning/planning_validator/src/planning_validator.cpp | 6 +++--- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/planning/planning_validator/include/autoware_planning_validator/planning_validator.hpp b/planning/planning_validator/include/autoware_planning_validator/planning_validator.hpp index fa0b116eafe86..b2a9c8f2e94a4 100644 --- a/planning/planning_validator/include/autoware_planning_validator/planning_validator.hpp +++ b/planning/planning_validator/include/autoware_planning_validator/planning_validator.hpp @@ -19,6 +19,7 @@ #include "autoware_planning_validator/msg/planning_validator_status.hpp" #include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" +#include "tier4_autoware_utils/ros/polling_subscriber.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" #include @@ -102,7 +103,8 @@ class PlanningValidator : public rclcpp::Node void setStatus(DiagnosticStatusWrapper & stat, const bool & is_ok, const std::string & msg); - rclcpp::Subscription::SharedPtr sub_kinematics_; + tier4_autoware_utils::InterProcessPollingSubscriber sub_kinematics_{ + this, "~/input/kinematics"}; rclcpp::Subscription::SharedPtr sub_traj_; rclcpp::Publisher::SharedPtr pub_traj_; rclcpp::Publisher::SharedPtr pub_status_; diff --git a/planning/planning_validator/src/planning_validator.cpp b/planning/planning_validator/src/planning_validator.cpp index 420ee564cda72..9f54547eb62e1 100644 --- a/planning/planning_validator/src/planning_validator.cpp +++ b/planning/planning_validator/src/planning_validator.cpp @@ -32,9 +32,6 @@ PlanningValidator::PlanningValidator(const rclcpp::NodeOptions & options) { using std::placeholders::_1; - sub_kinematics_ = create_subscription( - "~/input/kinematics", 1, - [this](const Odometry::ConstSharedPtr msg) { current_kinematics_ = msg; }); sub_traj_ = create_subscription( "~/input/trajectory", 1, std::bind(&PlanningValidator::onTrajectory, this, _1)); @@ -195,6 +192,9 @@ void PlanningValidator::onTrajectory(const Trajectory::ConstSharedPtr msg) current_trajectory_ = msg; + // receive data + current_kinematics_ = sub_kinematics_.takeData(); + if (!isDataReady()) return; if (publish_diag_ && !diag_updater_) { From 420c6bda757fed73496dcf807e397dfab1c8b3dc Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 10 Jun 2024 17:27:56 +0900 Subject: [PATCH 65/65] refactor(freespace_planner)!: add autoware prefix (#7376) refactor(freespace_planner)!: add autoawre prefix Signed-off-by: kosuke55 --- .../launch/scenario_planning/parking.launch.xml | 2 +- launch/tier4_planning_launch/package.xml | 2 +- .../README.md | 2 +- .../CMakeLists.txt | 10 +++++----- .../README.md | 2 +- .../config/freespace_planner.param.yaml | 0 .../freespace_planner_node.hpp | 10 +++++----- .../launch/freespace_planner.launch.xml | 2 +- .../package.xml | 4 ++-- .../freespace_planner_node.cpp | 8 ++++---- .../test/test_freespace_planner_node_interface.cpp | 6 +++--- 11 files changed, 24 insertions(+), 24 deletions(-) rename planning/{freespace_planner => autoware_freespace_planner}/CMakeLists.txt (64%) rename planning/{freespace_planner => autoware_freespace_planner}/README.md (99%) rename planning/{freespace_planner => autoware_freespace_planner}/config/freespace_planner.param.yaml (100%) rename planning/{freespace_planner/include/freespace_planner => autoware_freespace_planner/include/autoware_freespace_planner}/freespace_planner_node.hpp (95%) rename planning/{freespace_planner => autoware_freespace_planner}/launch/freespace_planner.launch.xml (91%) rename planning/{freespace_planner => autoware_freespace_planner}/package.xml (93%) rename planning/{freespace_planner/src/freespace_planner => autoware_freespace_planner/src/autoware_freespace_planner}/freespace_planner_node.cpp (98%) rename planning/{freespace_planner => autoware_freespace_planner}/test/test_freespace_planner_node_interface.cpp (94%) diff --git a/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml index db5a9a0093e7c..e0fdcb1e30408 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml @@ -18,7 +18,7 @@ - + diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index cc2d2903005cb..1c881091b0e7d 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -61,6 +61,7 @@ autoware_costmap_generator autoware_external_cmd_selector autoware_external_velocity_limit_selector + autoware_freespace_planner autoware_path_optimizer autoware_planning_topic_converter autoware_planning_validator @@ -69,7 +70,6 @@ autoware_surround_obstacle_checker autoware_velocity_smoother behavior_path_planner - freespace_planner glog_component mission_planner obstacle_cruise_planner diff --git a/planning/autoware_behavior_path_start_planner_module/README.md b/planning/autoware_behavior_path_start_planner_module/README.md index bcb3b1bec1fd9..b2c92f31ded31 100644 --- a/planning/autoware_behavior_path_start_planner_module/README.md +++ b/planning/autoware_behavior_path_start_planner_module/README.md @@ -545,4 +545,4 @@ To run this feature, you need to set `parking_lot` to the map, `activate_by_scen | end_pose_search_end_distance | [m] | double | distance from ego to the end point of the search for the end point in the freespace_pull_out driving lane | 30.0 | | end_pose_search_interval | [m] | bool | interval to search for the end point in the freespace_pull_out driving lane | 2.0 | -See [freespace_planner](../freespace_planner/README.md) for other parameters. +See [freespace_planner](../autoware_freespace_planner/README.md) for other parameters. diff --git a/planning/freespace_planner/CMakeLists.txt b/planning/autoware_freespace_planner/CMakeLists.txt similarity index 64% rename from planning/freespace_planner/CMakeLists.txt rename to planning/autoware_freespace_planner/CMakeLists.txt index a33c9859afe75..7901be70fbc63 100644 --- a/planning/freespace_planner/CMakeLists.txt +++ b/planning/autoware_freespace_planner/CMakeLists.txt @@ -1,24 +1,24 @@ cmake_minimum_required(VERSION 3.14) -project(freespace_planner) +project(autoware_freespace_planner) find_package(autoware_cmake REQUIRED) autoware_package() ament_auto_add_library(freespace_planner_node SHARED - src/freespace_planner/freespace_planner_node.cpp + src/autoware_freespace_planner/freespace_planner_node.cpp ) rclcpp_components_register_node(freespace_planner_node - PLUGIN "freespace_planner::FreespacePlannerNode" + PLUGIN "autoware::freespace_planner::FreespacePlannerNode" EXECUTABLE freespace_planner ) if(BUILD_TESTING) ament_add_ros_isolated_gtest(test_${PROJECT_NAME} - test/test_${PROJECT_NAME}_node_interface.cpp + test/test_freespace_planner_node_interface.cpp ) target_link_libraries(test_${PROJECT_NAME} - ${PROJECT_NAME}_node + freespace_planner_node ) endif() diff --git a/planning/freespace_planner/README.md b/planning/autoware_freespace_planner/README.md similarity index 99% rename from planning/freespace_planner/README.md rename to planning/autoware_freespace_planner/README.md index 6ed0ab605ea05..6bf13a81c0413 100644 --- a/planning/freespace_planner/README.md +++ b/planning/autoware_freespace_planner/README.md @@ -1,4 +1,4 @@ -# The `freespace_planner` +# The `autoware_freespace_planner` ## freespace_planner_node diff --git a/planning/freespace_planner/config/freespace_planner.param.yaml b/planning/autoware_freespace_planner/config/freespace_planner.param.yaml similarity index 100% rename from planning/freespace_planner/config/freespace_planner.param.yaml rename to planning/autoware_freespace_planner/config/freespace_planner.param.yaml diff --git a/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp b/planning/autoware_freespace_planner/include/autoware_freespace_planner/freespace_planner_node.hpp similarity index 95% rename from planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp rename to planning/autoware_freespace_planner/include/autoware_freespace_planner/freespace_planner_node.hpp index 22205ce427632..2084d8a3aad24 100644 --- a/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp +++ b/planning/autoware_freespace_planner/include/autoware_freespace_planner/freespace_planner_node.hpp @@ -28,8 +28,8 @@ * limitations under the License. */ -#ifndef FREESPACE_PLANNER__FREESPACE_PLANNER_NODE_HPP_ -#define FREESPACE_PLANNER__FREESPACE_PLANNER_NODE_HPP_ +#ifndef AUTOWARE_FREESPACE_PLANNER__FREESPACE_PLANNER_NODE_HPP_ +#define AUTOWARE_FREESPACE_PLANNER__FREESPACE_PLANNER_NODE_HPP_ #include "tier4_autoware_utils/ros/logger_level_configure.hpp" @@ -63,7 +63,7 @@ #include #include -namespace freespace_planner +namespace autoware::freespace_planner { using autoware::freespace_planning_algorithms::AbstractPlanningAlgorithm; using autoware::freespace_planning_algorithms::AstarParam; @@ -165,6 +165,6 @@ class FreespacePlannerNode : public rclcpp::Node std::unique_ptr logger_configure_; }; -} // namespace freespace_planner +} // namespace autoware::freespace_planner -#endif // FREESPACE_PLANNER__FREESPACE_PLANNER_NODE_HPP_ +#endif // AUTOWARE_FREESPACE_PLANNER__FREESPACE_PLANNER_NODE_HPP_ diff --git a/planning/freespace_planner/launch/freespace_planner.launch.xml b/planning/autoware_freespace_planner/launch/freespace_planner.launch.xml similarity index 91% rename from planning/freespace_planner/launch/freespace_planner.launch.xml rename to planning/autoware_freespace_planner/launch/freespace_planner.launch.xml index 3c8cce7a93941..e92a04307fed2 100644 --- a/planning/freespace_planner/launch/freespace_planner.launch.xml +++ b/planning/autoware_freespace_planner/launch/freespace_planner.launch.xml @@ -11,7 +11,7 @@ - + diff --git a/planning/freespace_planner/package.xml b/planning/autoware_freespace_planner/package.xml similarity index 93% rename from planning/freespace_planner/package.xml rename to planning/autoware_freespace_planner/package.xml index 06004ce9f308f..8a2ecad429f1b 100644 --- a/planning/freespace_planner/package.xml +++ b/planning/autoware_freespace_planner/package.xml @@ -1,9 +1,9 @@ - freespace_planner + autoware_freespace_planner 0.1.0 - The freespace_planner package + The autoware_freespace_planner package Kosuke Takeuchi Takamasa Horibe Takayuki Murooka diff --git a/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp b/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp similarity index 98% rename from planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp rename to planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp index f17b9227c89bc..797c140aa9dd9 100644 --- a/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp +++ b/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp @@ -28,7 +28,7 @@ * limitations under the License. */ -#include "freespace_planner/freespace_planner_node.hpp" +#include "autoware_freespace_planner/freespace_planner_node.hpp" #include "autoware_freespace_planning_algorithms/abstract_algorithm.hpp" @@ -217,7 +217,7 @@ bool isStopped( } // namespace -namespace freespace_planner +namespace autoware::freespace_planner { FreespacePlannerNode::FreespacePlannerNode(const rclcpp::NodeOptions & node_options) : Node("freespace_planner", node_options) @@ -583,7 +583,7 @@ void FreespacePlannerNode::initializePlanningAlgorithm() } RCLCPP_INFO_STREAM(get_logger(), "initialize planning algorithm: " << algo_name); } -} // namespace freespace_planner +} // namespace autoware::freespace_planner #include -RCLCPP_COMPONENTS_REGISTER_NODE(freespace_planner::FreespacePlannerNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::freespace_planner::FreespacePlannerNode) diff --git a/planning/freespace_planner/test/test_freespace_planner_node_interface.cpp b/planning/autoware_freespace_planner/test/test_freespace_planner_node_interface.cpp similarity index 94% rename from planning/freespace_planner/test/test_freespace_planner_node_interface.cpp rename to planning/autoware_freespace_planner/test/test_freespace_planner_node_interface.cpp index 881ce269a7895..621bed12fdabc 100644 --- a/planning/freespace_planner/test/test_freespace_planner_node_interface.cpp +++ b/planning/autoware_freespace_planner/test/test_freespace_planner_node_interface.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "freespace_planner/freespace_planner_node.hpp" +#include "autoware_freespace_planner/freespace_planner_node.hpp" #include #include @@ -22,7 +22,7 @@ #include -using freespace_planner::FreespacePlannerNode; +using autoware::freespace_planner::FreespacePlannerNode; using planning_test_utils::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() @@ -41,7 +41,7 @@ std::shared_ptr generateNode() const auto planning_test_utils_dir = ament_index_cpp::get_package_share_directory("planning_test_utils"); const auto freespace_planner_dir = - ament_index_cpp::get_package_share_directory("freespace_planner"); + ament_index_cpp::get_package_share_directory("autoware_freespace_planner"); node_options.arguments( {"--ros-args", "--params-file", planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file",