From 8ff2128983765f469293cf9fb85d1e1c6ae7322f Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 10 Aug 2023 11:05:32 +0900 Subject: [PATCH 01/16] feat(map_projection_loader): add map_projection_loader (#3986) * feat(map_projection_loader): add map_projection_loader Signed-off-by: kminoda * style(pre-commit): autofix * Update default algorithm Signed-off-by: kminoda * fix test Signed-off-by: kminoda * style(pre-commit): autofix * add readme Signed-off-by: kminoda * style(pre-commit): autofix * fix launch file and fix map_loader Signed-off-by: kminoda * style(pre-commit): autofix * update lanelet2 Signed-off-by: kminoda * fill yaml file path Signed-off-by: kminoda * style(pre-commit): autofix * update readme Signed-off-by: kminoda * style(pre-commit): autofix * minor fix Signed-off-by: kminoda * style(pre-commit): autofix * fix test Signed-off-by: kminoda * style(pre-commit): autofix * add include guard Signed-off-by: kminoda * style(pre-commit): autofix * update test Signed-off-by: kminoda * update map_loader Signed-off-by: kminoda * style(pre-commit): autofix * update docs * style(pre-commit): autofix * update Signed-off-by: kminoda * add dependency Signed-off-by: kminoda * style(pre-commit): autofix * remove unnecessary parameter Signed-off-by: kminoda * update Signed-off-by: kminoda * update test Signed-off-by: kminoda * style(pre-commit): autofix * add url Signed-off-by: kminoda * enable python tests Signed-off-by: kminoda * style(pre-commit): autofix * small fix Signed-off-by: kminoda * fix grammar Signed-off-by: kminoda * remove transverse mercator Signed-off-by: kminoda * style(pre-commit): autofix * add rule in map Signed-off-by: kminoda * fix readme of map loader Signed-off-by: kminoda * remove transverse mercator for now Signed-off-by: kminoda * add utm Signed-off-by: kminoda * remove altitude from current projection loader Signed-off-by: kminoda * style(pre-commit): autofix * fix pre-commit Signed-off-by: kminoda * fix build error Signed-off-by: kminoda * fix: remove package.xml Signed-off-by: kminoda * fix clang-tidy Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- launch/tier4_map_launch/launch/map.launch.py | 29 +++- launch/tier4_map_launch/package.xml | 1 + map/map_loader/README.md | 46 +++--- .../config/lanelet2_map_loader.param.yaml | 4 - .../map_loader/lanelet2_map_loader_node.hpp | 7 +- .../lanelet2_map_loader_node.cpp | 42 ++--- map/map_projection_loader/CMakeLists.txt | 58 +++++++ map/map_projection_loader/README.md | 62 ++++++++ .../load_info_from_lanelet2_map.hpp | 29 ++++ .../map_projection_loader.hpp | 35 ++++ .../launch/map_projection_loader.launch.xml | 10 ++ map/map_projection_loader/package.xml | 29 ++++ .../src/load_info_from_lanelet2_map.cpp | 39 +++++ .../src/map_projection_loader.cpp | 70 ++++++++ .../src/map_projection_loader_node.cpp | 23 +++ .../test/data/projection_info_local.yaml | 1 + .../test/data/projection_info_mgrs.yaml | 2 + .../test/data/projection_info_utm.yaml | 4 + .../test/test_load_info_from_lanelet2_map.cpp | 70 ++++++++ .../test_node_load_local_from_yaml.test.py | 143 +++++++++++++++++ .../test_node_load_mgrs_from_yaml.test.py | 144 +++++++++++++++++ .../test/test_node_load_utm_from_yaml.test.py | 149 ++++++++++++++++++ 22 files changed, 935 insertions(+), 62 deletions(-) create mode 100644 map/map_projection_loader/CMakeLists.txt create mode 100644 map/map_projection_loader/README.md create mode 100644 map/map_projection_loader/include/map_projection_loader/load_info_from_lanelet2_map.hpp create mode 100644 map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp create mode 100644 map/map_projection_loader/launch/map_projection_loader.launch.xml create mode 100644 map/map_projection_loader/package.xml create mode 100644 map/map_projection_loader/src/load_info_from_lanelet2_map.cpp create mode 100644 map/map_projection_loader/src/map_projection_loader.cpp create mode 100644 map/map_projection_loader/src/map_projection_loader_node.cpp create mode 100644 map/map_projection_loader/test/data/projection_info_local.yaml create mode 100644 map/map_projection_loader/test/data/projection_info_mgrs.yaml create mode 100644 map/map_projection_loader/test/data/projection_info_utm.yaml create mode 100644 map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp create mode 100644 map/map_projection_loader/test/test_node_load_local_from_yaml.test.py create mode 100644 map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py create mode 100644 map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py diff --git a/launch/tier4_map_launch/launch/map.launch.py b/launch/tier4_map_launch/launch/map.launch.py index f9459be3b8924..169c53814df22 100644 --- a/launch/tier4_map_launch/launch/map.launch.py +++ b/launch/tier4_map_launch/launch/map.launch.py @@ -12,13 +12,18 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os + +from ament_index_python import get_package_share_directory import launch from launch.actions import DeclareLaunchArgument from launch.actions import GroupAction +from launch.actions import IncludeLaunchDescription from launch.actions import OpaqueFunction from launch.actions import SetLaunchConfiguration from launch.conditions import IfCondition from launch.conditions import UnlessCondition +from launch.launch_description_sources import AnyLaunchDescriptionSource from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer from launch_ros.actions import Node @@ -57,7 +62,10 @@ def launch_setup(context, *args, **kwargs): package="map_loader", plugin="Lanelet2MapLoaderNode", name="lanelet2_map_loader", - remappings=[("output/lanelet2_map", "vector_map")], + remappings=[ + ("output/lanelet2_map", "vector_map"), + ("input/map_projector_info", "map_projector_type"), + ], parameters=[ { "lanelet2_map_path": LaunchConfiguration("lanelet2_map_path"), @@ -110,6 +118,19 @@ def launch_setup(context, *args, **kwargs): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) + map_projection_loader_launch_file = os.path.join( + get_package_share_directory("map_projection_loader"), + "launch", + "map_projection_loader.launch.xml", + ) + map_projection_loader = IncludeLaunchDescription( + AnyLaunchDescriptionSource(map_projection_loader_launch_file), + launch_arguments={ + "map_projector_info_path": LaunchConfiguration("map_projector_info_path"), + "lanelet2_map_path": LaunchConfiguration("lanelet2_map_path"), + }.items(), + ) + container = ComposableNodeContainer( name="map_container", namespace="", @@ -129,6 +150,7 @@ def launch_setup(context, *args, **kwargs): PushRosNamespace("map"), container, map_hash_generator, + map_projection_loader, ] ) @@ -159,6 +181,11 @@ def add_launch_arg(name: str, default_value=None, description=None): [LaunchConfiguration("map_path"), "/pointcloud_map_metadata.yaml"], "path to pointcloud map metadata file", ), + add_launch_arg( + "map_projector_info_path", + [LaunchConfiguration("map_path"), "/map_projector_info.yaml"], + "path to map projector info yaml file", + ), add_launch_arg( "lanelet2_map_loader_param_path", [ diff --git a/launch/tier4_map_launch/package.xml b/launch/tier4_map_launch/package.xml index 6f75950838267..d8f69c124526a 100644 --- a/launch/tier4_map_launch/package.xml +++ b/launch/tier4_map_launch/package.xml @@ -13,6 +13,7 @@ autoware_cmake map_loader + map_projection_loader map_tf_generator ament_lint_auto diff --git a/map/map_loader/README.md b/map/map_loader/README.md index 0494b57dcfab9..44f215b2d8c01 100644 --- a/map/map_loader/README.md +++ b/map/map_loader/README.md @@ -20,11 +20,12 @@ Currently, it supports the following two types: You may provide either a single .pcd file or multiple .pcd files. If you are using multiple PCD data and either of `enable_partial_load`, `enable_differential_load` or `enable_selected_load` are set true, it MUST obey the following rules: -1. **It must be divided by straight lines parallel to the x-axis and y-axis**. The system does not support division by diagonal lines or curved lines. -2. **The division size along each axis should be equal.** -3. **The division size should be about 20m x 20m.** Particularly, care should be taken as using too large division size (for example, more than 100m) may have adverse effects on dynamic map loading features in [ndt_scan_matcher](https://github.com/autowarefoundation/autoware.universe/tree/main/localization/ndt_scan_matcher) and [compare_map_segmentation](https://github.com/autowarefoundation/autoware.universe/tree/main/perception/compare_map_segmentation). -4. **All the split maps should not overlap with each other.** -5. **Metadata file should also be provided.** The metadata structure description is provided below. +1. **The pointcloud map should be projected on the same coordinate defined in `map_projection_loader`**, in order to be consistent with the lanelet2 map and other packages that converts between local and geodetic coordinates. For more information, please refer to [the readme of `map_projection_loader`](https://github.com/autowarefoundation/autoware.universe/tree/main/map/map_projection_loader/README.md). +2. **It must be divided by straight lines parallel to the x-axis and y-axis**. The system does not support division by diagonal lines or curved lines. +3. **The division size along each axis should be equal.** +4. **The division size should be about 20m x 20m.** Particularly, care should be taken as using too large division size (for example, more than 100m) may have adverse effects on dynamic map loading features in [ndt_scan_matcher](https://github.com/autowarefoundation/autoware.universe/tree/main/localization/ndt_scan_matcher) and [compare_map_segmentation](https://github.com/autowarefoundation/autoware.universe/tree/main/perception/compare_map_segmentation). +5. **All the split maps should not overlap with each other.** +6. **Metadata file should also be provided.** The metadata structure description is provided below. Note that these rules are not applicable when `enable_partial_load`, `enable_differential_load` and `enable_selected_load` are all set false. In this case, however, you also need to disable dynamic map loading mode for other nodes as well ([ndt_scan_matcher](https://github.com/autowarefoundation/autoware.universe/tree/main/localization/ndt_scan_matcher) and [compare_map_segmentation](https://github.com/autowarefoundation/autoware.universe/tree/main/perception/compare_map_segmentation) as of June 2023). @@ -69,6 +70,7 @@ sample-map-rosbag │ ├── B.pcd │ ├── C.pcd │ └── ... +├── map_projector_info.yaml └── pointcloud_map_metadata.yaml ``` @@ -138,27 +140,39 @@ Please see [the description of `GetSelectedPointCloudMap.srv`](https://github.co ### Feature lanelet2_map_loader loads Lanelet2 file and publishes the map data as autoware_auto_mapping_msgs/HADMapBin message. -The node projects lan/lon coordinates into MGRS coordinates. +The node projects lan/lon coordinates into arbitrary coordinates defined in `/map/map_projector_type` from `map_projection_loader`. +The node supports the following three types of coordinate systems: + +- MGRS +- UTM +- local ### How to run `ros2 run map_loader lanelet2_map_loader --ros-args -p lanelet2_map_path:=path/to/map.osm` +### Subscribed Topics + +- ~input/map_projector_info (tier4_map_msgs/MapProjectorInfo) : Projection type for Autoware + ### Published Topics - ~output/lanelet2_map (autoware_auto_mapping_msgs/HADMapBin) : Binary data of loaded Lanelet2 Map +### Parameters + +| Name | Type | Description | Default value | +| :--------------------- | :---------- | :----------------------------------------------- | :------------ | +| center_line_resolution | double | Define the resolution of the lanelet center line | 5.0 | +| lanelet2_map_path | std::string | The lanelet2 map path | None | + --- ## lanelet2_map_visualization ### Feature -lanelet2_map_visualization visualizes autoware_auto_mapping_msgs/HADMapBin messages into visualization_msgs/MarkerArray. There are 3 types of map can be loaded in autoware. Please make sure you selected the correct lanelet2_map_projector_type when you launch this package. - -- MGRS -- UTM -- local +lanelet2_map_visualization visualizes autoware_auto_mapping_msgs/HADMapBin messages into visualization_msgs/MarkerArray. ### How to Run @@ -171,13 +185,3 @@ lanelet2_map_visualization visualizes autoware_auto_mapping_msgs/HADMapBin messa ### Published Topics - ~output/lanelet2_map_marker (visualization_msgs/MarkerArray) : visualization messages for RViz - -### Parameters - -| Name | Type | Description | Default value | -| :-------------------------- | :---------- | :----------------------------------------------------------- | :------------ | -| lanelet2_map_projector_type | std::string | The type of the map projector using, can be MGRS, UTM, local | MGRS | -| latitude | double | Latitude of map_origin, only using in UTM map projector | 0.0 | -| longitude | double | Longitude of map_origin, only using in UTM map projector | 0.0 | -| center_line_resolution | double | Define the resolution of the lanelet center line | 5.0 | -| lanelet2_map_path | std::string | The lanelet2 map path | None | diff --git a/map/map_loader/config/lanelet2_map_loader.param.yaml b/map/map_loader/config/lanelet2_map_loader.param.yaml index 971af0147b0fe..24d2b0e8ed7a8 100755 --- a/map/map_loader/config/lanelet2_map_loader.param.yaml +++ b/map/map_loader/config/lanelet2_map_loader.param.yaml @@ -1,7 +1,3 @@ /**: ros__parameters: - lanelet2_map_projector_type: MGRS # Options: MGRS, UTM, local - latitude: 40.816617984672746 # Latitude of map_origin, using in UTM - longitude: 29.360491808334285 # Longitude of map_origin, using in UTM - center_line_resolution: 5.0 # [m] diff --git a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp index 16681f3bd290d..2fb8b893d8fce 100644 --- a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp +++ b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp @@ -36,16 +36,15 @@ class Lanelet2MapLoaderNode : public rclcpp::Node static lanelet::LaneletMapPtr load_map( const std::string & lanelet2_filename, const std::string & lanelet2_map_projector_type, const double & map_origin_lat = 0.0, const double & map_origin_lon = 0.0); - static const MapProjectorInfo get_map_projector_type( - const std::string & lanelet2_filename, const std::string & lanelet2_map_projector_type, - const double & map_origin_lat, const double & map_origin_lon); static HADMapBin create_map_bin_msg( const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, const rclcpp::Time & now); private: + void on_map_projector_info(const MapProjectorInfo::ConstSharedPtr msg); + + rclcpp::Subscription::SharedPtr sub_map_projector_type_; rclcpp::Publisher::SharedPtr pub_map_bin_; - rclcpp::Publisher::SharedPtr pub_map_projector_type_; }; #endif // MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp index aafa66a35be84..42c46e2b5e96c 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp @@ -36,6 +36,7 @@ #include #include #include +#include #include #include #include @@ -49,16 +50,21 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options) : Node("lanelet2_map_loader", options) +{ + // subscription + sub_map_projector_type_ = create_subscription( + "input/map_projector_info", rclcpp::QoS{1}.transient_local(), + [this](const MapProjectorInfo::ConstSharedPtr msg) { on_map_projector_info(msg); }); +} + +void Lanelet2MapLoaderNode::on_map_projector_info(const MapProjectorInfo::ConstSharedPtr msg) { const auto lanelet2_filename = declare_parameter("lanelet2_map_path", ""); - const auto lanelet2_map_projector_type = declare_parameter("lanelet2_map_projector_type", "MGRS"); const auto center_line_resolution = declare_parameter("center_line_resolution", 5.0); - const double map_origin_lat = declare_parameter("latitude", 0.0); - const double map_origin_lon = declare_parameter("longitude", 0.0); // load map from file const auto map = - load_map(lanelet2_filename, lanelet2_map_projector_type, map_origin_lat, map_origin_lon); + load_map(lanelet2_filename, msg->type, msg->map_origin.latitude, msg->map_origin.longitude); if (!map) { return; } @@ -69,16 +75,10 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options // create map bin msg const auto map_bin_msg = create_map_bin_msg(map, lanelet2_filename, now()); - const auto map_projector_type_msg = get_map_projector_type( - lanelet2_filename, lanelet2_map_projector_type, map_origin_lat, map_origin_lon); // create publisher and publish pub_map_bin_ = create_publisher("output/lanelet2_map", rclcpp::QoS{1}.transient_local()); pub_map_bin_->publish(map_bin_msg); - // create publisher and publish - pub_map_projector_type_ = - create_publisher("map_projector_type", rclcpp::QoS{1}.transient_local()); - pub_map_projector_type_->publish(map_projector_type_msg); } lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map( @@ -96,7 +96,6 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map( lanelet::GPSPoint position{map_origin_lat, map_origin_lon}; lanelet::Origin origin{position}; lanelet::projection::UtmProjector projector{origin}; - const lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors); if (errors.empty()) { return map; @@ -137,27 +136,6 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map( return nullptr; } -const MapProjectorInfo Lanelet2MapLoaderNode::get_map_projector_type( - const std::string & lanelet2_filename, const std::string & lanelet2_map_projector_type, - const double & map_origin_lat, const double & map_origin_lon) -{ - lanelet::ErrorMessages errors{}; - MapProjectorInfo map_projector_type_msg; - if (lanelet2_map_projector_type == "MGRS") { - lanelet::projection::MGRSProjector projector{}; - const lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors); - map_projector_type_msg.type = "MGRS"; - map_projector_type_msg.mgrs_grid = projector.getProjectedMGRSGrid(); - } else if (lanelet2_map_projector_type == "UTM") { - map_projector_type_msg.type = "UTM"; - map_projector_type_msg.map_origin.latitude = map_origin_lat; - map_projector_type_msg.map_origin.longitude = map_origin_lon; - } else { - map_projector_type_msg.type = "local"; - } - return map_projector_type_msg; -} - HADMapBin Lanelet2MapLoaderNode::create_map_bin_msg( const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, const rclcpp::Time & now) { diff --git a/map/map_projection_loader/CMakeLists.txt b/map/map_projection_loader/CMakeLists.txt new file mode 100644 index 0000000000000..a53cdddf93b5b --- /dev/null +++ b/map/map_projection_loader/CMakeLists.txt @@ -0,0 +1,58 @@ +cmake_minimum_required(VERSION 3.14) +project(map_projection_loader) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_find_build_dependencies() + +ament_auto_add_library(map_projection_loader_lib SHARED + src/map_projection_loader.cpp + src/load_info_from_lanelet2_map.cpp +) + +target_link_libraries(map_projection_loader_lib yaml-cpp) + +ament_auto_add_executable(map_projection_loader src/map_projection_loader_node.cpp) + +target_compile_options(map_projection_loader PUBLIC -g -Wall -Wextra -Wpedantic -Werror) + +target_link_libraries(map_projection_loader map_projection_loader_lib) +target_include_directories(map_projection_loader PUBLIC include) + +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}" map_projection_loader_lib) + ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS}) +endfunction() + +if(BUILD_TESTING) + # Test python scripts + add_launch_test( + test/test_node_load_mgrs_from_yaml.test.py + TIMEOUT "30" + ) + add_launch_test( + test/test_node_load_local_from_yaml.test.py + TIMEOUT "30" + ) + add_launch_test( + test/test_node_load_utm_from_yaml.test.py + TIMEOUT "30" + ) + install(DIRECTORY + test/data/ + DESTINATION share/${PROJECT_NAME}/test/data/ + ) + + # Test c++ scripts + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + add_testcase(test/test_load_info_from_lanelet2_map.cpp) +endif() + +ament_auto_package(INSTALL_TO_SHARE + launch +) diff --git a/map/map_projection_loader/README.md b/map/map_projection_loader/README.md new file mode 100644 index 0000000000000..bbf15f34929da --- /dev/null +++ b/map/map_projection_loader/README.md @@ -0,0 +1,62 @@ +# map_projection_loader + +## Feature + +`map_projection_loader` is responsible for publishing `map_projector_info` that defines in which kind of coordinate Autoware is operating. +This is necessary information especially when you want to convert from global (geoid) to local coordinate or the other way around. + +- If `map_projector_info_path` DOES exist, this node loads it and publishes the map projection information accordingly. +- If `map_projector_info_path` does NOT exist, the node assumes that you are using the `MGRS` projection type, and loads the lanelet2 map instead to extract the MGRS grid. + - **DEPRECATED WARNING: This interface that uses the lanelet2 map is not recommended. Please prepare the YAML file instead.** + +## Map projector info file specification + +You need to provide a YAML file, namely `map_projector_info.yaml` under the `map_path` directory. For `pointcloud_map_metadata.yaml`, please refer to the Readme of `map_loader`. + +```bash +sample-map-rosbag +├── lanelet2_map.osm +├── pointcloud_map.pcd +├── map_projector_info.yaml +└── pointcloud_map_metadata.yaml +``` + +### Using local coordinate + +```yaml +# map_projector_info.yaml +type: "Local" +``` + +### Using MGRS + +If you want to use MGRS, please specify the MGRS grid as well. + +```yaml +# map_projector_info.yaml +type: "MGRS" +mgrs_grid: "54SUE" +``` + +### Using UTM + +If you want to use UTM, please specify the map origin as well. + +```yaml +# map_projector_info.yaml +type: "UTM" +map_origin: + latitude: 35.6092 + longitude: 139.7303 +``` + +## Published Topics + +- ~/map_projector_info (tier4_map_msgs/MapProjectorInfo) : Topic for defining map projector information + +## Parameters + +| Name | Type | Description | +| :---------------------- | :---------- | :------------------------------------------------------------------------------- | +| map_projector_info_path | std::string | A path to map_projector_info.yaml (used by default) | +| lanelet2_map_path | std::string | A path to lanelet2 map (used only when `map_projector_info_path` does not exist) | diff --git a/map/map_projection_loader/include/map_projection_loader/load_info_from_lanelet2_map.hpp b/map/map_projection_loader/include/map_projection_loader/load_info_from_lanelet2_map.hpp new file mode 100644 index 0000000000000..746f16e0f6b33 --- /dev/null +++ b/map/map_projection_loader/include/map_projection_loader/load_info_from_lanelet2_map.hpp @@ -0,0 +1,29 @@ +// 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 MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_ +#define MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_ + +#include +#include +#include +#include + +#include "tier4_map_msgs/msg/map_projector_info.hpp" + +#include + +tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::string & filename); + +#endif // MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_ diff --git a/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp b/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp new file mode 100644 index 0000000000000..de19ac5dabda4 --- /dev/null +++ b/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp @@ -0,0 +1,35 @@ +// 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 MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_ +#define MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_ + +#include "rclcpp/rclcpp.hpp" + +#include "tier4_map_msgs/msg/map_projector_info.hpp" + +#include + +tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & filename); + +class MapProjectionLoader : public rclcpp::Node +{ +public: + MapProjectionLoader(); + +private: + rclcpp::Publisher::SharedPtr publisher_; +}; + +#endif // MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_ diff --git a/map/map_projection_loader/launch/map_projection_loader.launch.xml b/map/map_projection_loader/launch/map_projection_loader.launch.xml new file mode 100644 index 0000000000000..6448675c4a75f --- /dev/null +++ b/map/map_projection_loader/launch/map_projection_loader.launch.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/map/map_projection_loader/package.xml b/map/map_projection_loader/package.xml new file mode 100644 index 0000000000000..84f66583ed840 --- /dev/null +++ b/map/map_projection_loader/package.xml @@ -0,0 +1,29 @@ + + + + map_projection_loader + 0.1.0 + map_projection_loader package as a ROS 2 node + Koji Minoda + Yamato Ando + Masahiro Sakamoto + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + lanelet2_extension + rclcpp + rclcpp_components + tier4_map_msgs + + ament_cmake_gmock + ament_cmake_gtest + ament_lint_auto + autoware_lint_common + ros_testing + + + ament_cmake + + diff --git a/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp b/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp new file mode 100644 index 0000000000000..a93a94f296d45 --- /dev/null +++ b/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp @@ -0,0 +1,39 @@ +// 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 "map_projection_loader/load_info_from_lanelet2_map.hpp" + +#include "tier4_map_msgs/msg/map_projector_info.hpp" + +#include +#include +#include +#include + +#include + +tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::string & filename) +{ + lanelet::ErrorMessages errors{}; + lanelet::projection::MGRSProjector projector{}; + const lanelet::LaneletMapPtr map = lanelet::load(filename, projector, &errors); + if (!errors.empty()) { + throw std::runtime_error("Error occurred while loading lanelet2 map"); + } + + tier4_map_msgs::msg::MapProjectorInfo msg; + msg.type = "MGRS"; + msg.mgrs_grid = projector.getProjectedMGRSGrid(); + return msg; +} diff --git a/map/map_projection_loader/src/map_projection_loader.cpp b/map/map_projection_loader/src/map_projection_loader.cpp new file mode 100644 index 0000000000000..ccea8d7417cbc --- /dev/null +++ b/map/map_projection_loader/src/map_projection_loader.cpp @@ -0,0 +1,70 @@ +// 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 "map_projection_loader/map_projection_loader.hpp" + +#include "map_projection_loader/load_info_from_lanelet2_map.hpp" + +#include + +#include + +tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & filename) +{ + YAML::Node data = YAML::LoadFile(filename); + + tier4_map_msgs::msg::MapProjectorInfo msg; + msg.type = data["type"].as(); + if (msg.type == "MGRS") { + msg.mgrs_grid = data["mgrs_grid"].as(); + } else if (msg.type == "UTM") { + msg.map_origin.latitude = data["map_origin"]["latitude"].as(); + msg.map_origin.longitude = data["map_origin"]["longitude"].as(); + } else if (msg.type == "local") { + ; // do nothing + } else { + throw std::runtime_error( + "Invalid map projector type. Currently supported types: MGRS, UTM, and local"); + } + return msg; +} + +MapProjectionLoader::MapProjectionLoader() : Node("map_projection_loader") +{ + std::string yaml_filename = this->declare_parameter("map_projector_info_path"); + std::string lanelet2_map_filename = this->declare_parameter("lanelet2_map_path"); + std::ifstream file(yaml_filename); + + tier4_map_msgs::msg::MapProjectorInfo msg; + + bool use_yaml_file = file.is_open(); + if (use_yaml_file) { + RCLCPP_INFO(this->get_logger(), "Load %s", yaml_filename.c_str()); + msg = load_info_from_yaml(yaml_filename); + } else { + RCLCPP_INFO(this->get_logger(), "Load %s", lanelet2_map_filename.c_str()); + RCLCPP_WARN( + this->get_logger(), + "DEPRECATED WARNING: Loading map projection info from lanelet2 map may soon be deleted. " + "Please use map_projector_info.yaml instead. For more info, visit " + "https://github.com/autowarefoundation/autoware.universe/blob/main/map/map_projection_loader/" + "README.md"); + msg = load_info_from_lanelet2_map(lanelet2_map_filename); + } + + // Publish the message + publisher_ = this->create_publisher( + "~/map_projector_info", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local()); + publisher_->publish(msg); +} diff --git a/map/map_projection_loader/src/map_projection_loader_node.cpp b/map/map_projection_loader/src/map_projection_loader_node.cpp new file mode 100644 index 0000000000000..1d9336be0d9dd --- /dev/null +++ b/map/map_projection_loader/src/map_projection_loader_node.cpp @@ -0,0 +1,23 @@ +// 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 "map_projection_loader/map_projection_loader.hpp" + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/map/map_projection_loader/test/data/projection_info_local.yaml b/map/map_projection_loader/test/data/projection_info_local.yaml new file mode 100644 index 0000000000000..cea4aaf31d439 --- /dev/null +++ b/map/map_projection_loader/test/data/projection_info_local.yaml @@ -0,0 +1 @@ +type: local diff --git a/map/map_projection_loader/test/data/projection_info_mgrs.yaml b/map/map_projection_loader/test/data/projection_info_mgrs.yaml new file mode 100644 index 0000000000000..d7687521be5fa --- /dev/null +++ b/map/map_projection_loader/test/data/projection_info_mgrs.yaml @@ -0,0 +1,2 @@ +type: MGRS +mgrs_grid: 54SUE diff --git a/map/map_projection_loader/test/data/projection_info_utm.yaml b/map/map_projection_loader/test/data/projection_info_utm.yaml new file mode 100644 index 0000000000000..002383c97a474 --- /dev/null +++ b/map/map_projection_loader/test/data/projection_info_utm.yaml @@ -0,0 +1,4 @@ +type: UTM +map_origin: + latitude: 35.6762 + longitude: 139.6503 diff --git a/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp b/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp new file mode 100644 index 0000000000000..52abacf67f344 --- /dev/null +++ b/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp @@ -0,0 +1,70 @@ +// 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 "map_projection_loader/load_info_from_lanelet2_map.hpp" + +#include +#include + +#include + +#include + +void save_dummy_lanelet2_map(const std::string & mgrs_coord, const std::string & output_path) +{ + int zone = std::stoi(mgrs_coord.substr(0, 2)); + bool is_north = false; + int precision = 0; + double utm_x{}; + double utm_y{}; + double lat{}; + double lon{}; + GeographicLib::MGRS::Reverse(mgrs_coord, zone, is_north, utm_x, utm_y, precision, false); + GeographicLib::UTMUPS::Reverse(zone, is_north, utm_x, utm_y, lat, lon); + + std::ofstream file(output_path); + if (!file) { + std::cerr << "Unable to open file.\n"; + return; + } + + file << "\n"; + file << "\n"; + file << " \n"; + file << ""; + + file.close(); +} + +TEST(TestLoadFromLanelet2Map, LoadMGRSGrid) +{ + // Save dummy lanelet2 map + const std::string mgrs_grid = "54SUE"; + const std::string mgrs_coord = mgrs_grid + "1000010000"; + const std::string output_path = "/tmp/test_load_info_from_lanelet2_map.osm"; + save_dummy_lanelet2_map(mgrs_coord, output_path); + + // Test the function + const auto projector_info = load_info_from_lanelet2_map(output_path); + + // Check the result + EXPECT_EQ(projector_info.type, "MGRS"); + EXPECT_EQ(projector_info.mgrs_grid, mgrs_grid); +} + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleMock(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py new file mode 100644 index 0000000000000..aa0e3245565b5 --- /dev/null +++ b/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py @@ -0,0 +1,143 @@ +#!/usr/bin/env python3 + +# 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. + +import os +import unittest + +from ament_index_python import get_package_share_directory +import launch +from launch import LaunchDescription +from launch.logging import get_logger +from launch_ros.actions import Node +import launch_testing +import pytest +import rclpy +from rclpy.qos import QoSDurabilityPolicy +from rclpy.qos import QoSHistoryPolicy +from rclpy.qos import QoSProfile +from tier4_map_msgs.msg import MapProjectorInfo +import yaml + +logger = get_logger(__name__) + +YAML_FILE_PATH = "test/data/projection_info_local.yaml" + + +@pytest.mark.launch_test +def generate_test_description(): + map_projection_info_path = os.path.join( + get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + ) + + map_projection_loader_node = Node( + package="map_projection_loader", + executable="map_projection_loader", + output="screen", + parameters=[ + { + "map_projector_info_path": map_projection_info_path, + "lanelet2_map_path": "", + "use_local_projector": False, + }, + ], + ) + + context = {} + + return ( + LaunchDescription( + [ + map_projection_loader_node, + # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + launch.actions.TimerAction( + period=1.0, actions=[launch_testing.actions.ReadyToTest()] + ), + ] + ), + context, + ) + + +class TestLoadLocalFromYaml(unittest.TestCase): + @classmethod + def setUpClass(cls): + # Initialize the ROS context for the test node + rclpy.init() + + @classmethod + def tearDownClass(cls): + # Shutdown the ROS context + rclpy.shutdown() + + def setUp(self): + # Create a ROS node for tests + self.test_node = rclpy.create_node("test_node") + self.evaluation_time = 0.2 # 200ms + self.received_message = None + + def tearDown(self): + self.test_node.destroy_node() + + def callback(self, msg): + self.received_message = msg + + @staticmethod + def print_message(stat): + logger.debug("===========================") + logger.debug(stat) + + def test_node_link(self): + # Create custom QoS profile for subscription + custom_qos_profile = QoSProfile( + depth=1, + history=QoSHistoryPolicy.KEEP_LAST, + durability=QoSDurabilityPolicy.TRANSIENT_LOCAL, + ) + + # Create subscription to map_projector_info topic + subscription = self.test_node.create_subscription( + MapProjectorInfo, + "/map_projection_loader/map_projector_info", + self.callback, + custom_qos_profile, + ) + + # Give time for the message to be received and processed + rclpy.spin_until_future_complete( + self.test_node, rclpy.task.Future(), timeout_sec=self.evaluation_time + ) + + # Load the yaml file directly + map_projection_info_path = os.path.join( + get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + ) + with open(map_projection_info_path) as f: + yaml_data = yaml.load(f) + + # Test if message received + self.assertIsNotNone( + self.received_message, "No message received on map_projector_info topic" + ) + self.assertEqual(self.received_message.type, yaml_data["type"]) + + self.test_node.destroy_subscription(subscription) + + +@launch_testing.post_shutdown_test() +class TestProcessOutput(unittest.TestCase): + def test_exit_code(self, proc_info): + # Check that process exits with code 0: no error + launch_testing.asserts.assertExitCodes(proc_info) diff --git a/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py new file mode 100644 index 0000000000000..ae29b4b06c61c --- /dev/null +++ b/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py @@ -0,0 +1,144 @@ +#!/usr/bin/env python3 + +# 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. + +import os +import unittest + +from ament_index_python import get_package_share_directory +import launch +from launch import LaunchDescription +from launch.logging import get_logger +from launch_ros.actions import Node +import launch_testing +import pytest +import rclpy +from rclpy.qos import QoSDurabilityPolicy +from rclpy.qos import QoSHistoryPolicy +from rclpy.qos import QoSProfile +from tier4_map_msgs.msg import MapProjectorInfo +import yaml + +logger = get_logger(__name__) + +YAML_FILE_PATH = "test/data/projection_info_mgrs.yaml" + + +@pytest.mark.launch_test +def generate_test_description(): + map_projection_info_path = os.path.join( + get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + ) + + map_projection_loader_node = Node( + package="map_projection_loader", + executable="map_projection_loader", + output="screen", + parameters=[ + { + "map_projector_info_path": map_projection_info_path, + "lanelet2_map_path": "", + "use_local_projector": False, + }, + ], + ) + + context = {} + + return ( + LaunchDescription( + [ + map_projection_loader_node, + # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + launch.actions.TimerAction( + period=1.0, actions=[launch_testing.actions.ReadyToTest()] + ), + ] + ), + context, + ) + + +class TestLoadMGRSFromYaml(unittest.TestCase): + @classmethod + def setUpClass(cls): + # Initialize the ROS context for the test node + rclpy.init() + + @classmethod + def tearDownClass(cls): + # Shutdown the ROS context + rclpy.shutdown() + + def setUp(self): + # Create a ROS node for tests + self.test_node = rclpy.create_node("test_node") + self.evaluation_time = 0.2 # 200ms + self.received_message = None + + def tearDown(self): + self.test_node.destroy_node() + + def callback(self, msg): + self.received_message = msg + + @staticmethod + def print_message(stat): + logger.debug("===========================") + logger.debug(stat) + + def test_node_link(self): + # Create custom QoS profile for subscription + custom_qos_profile = QoSProfile( + depth=1, + history=QoSHistoryPolicy.KEEP_LAST, + durability=QoSDurabilityPolicy.TRANSIENT_LOCAL, + ) + + # Create subscription to map_projector_info topic + subscription = self.test_node.create_subscription( + MapProjectorInfo, + "/map_projection_loader/map_projector_info", + self.callback, + custom_qos_profile, + ) + + # Give time for the message to be received and processed + rclpy.spin_until_future_complete( + self.test_node, rclpy.task.Future(), timeout_sec=self.evaluation_time + ) + + # Load the yaml file directly + map_projection_info_path = os.path.join( + get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + ) + with open(map_projection_info_path) as f: + yaml_data = yaml.load(f) + + # Test if message received + self.assertIsNotNone( + self.received_message, "No message received on map_projector_info topic" + ) + self.assertEqual(self.received_message.type, yaml_data["type"]) + self.assertEqual(self.received_message.mgrs_grid, yaml_data["mgrs_grid"]) + + self.test_node.destroy_subscription(subscription) + + +@launch_testing.post_shutdown_test() +class TestProcessOutput(unittest.TestCase): + def test_exit_code(self, proc_info): + # Check that process exits with code 0: no error + launch_testing.asserts.assertExitCodes(proc_info) diff --git a/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py new file mode 100644 index 0000000000000..8da98bbb8b25d --- /dev/null +++ b/map/map_projection_loader/test/test_node_load_utm_from_yaml.test.py @@ -0,0 +1,149 @@ +#!/usr/bin/env python3 + +# 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. + +import os +import unittest + +from ament_index_python import get_package_share_directory +import launch +from launch import LaunchDescription +from launch.logging import get_logger +from launch_ros.actions import Node +import launch_testing +import pytest +import rclpy +from rclpy.qos import QoSDurabilityPolicy +from rclpy.qos import QoSHistoryPolicy +from rclpy.qos import QoSProfile +from tier4_map_msgs.msg import MapProjectorInfo +import yaml + +logger = get_logger(__name__) + +YAML_FILE_PATH = "test/data/projection_info_utm.yaml" + + +@pytest.mark.launch_test +def generate_test_description(): + map_projection_info_path = os.path.join( + get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + ) + + map_projection_loader_node = Node( + package="map_projection_loader", + executable="map_projection_loader", + output="screen", + parameters=[ + { + "map_projector_info_path": map_projection_info_path, + "lanelet2_map_path": "", + "use_local_projector": False, + }, + ], + ) + + context = {} + + return ( + LaunchDescription( + [ + map_projection_loader_node, + # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + launch.actions.TimerAction( + period=1.0, actions=[launch_testing.actions.ReadyToTest()] + ), + ] + ), + context, + ) + + +class TestLoadUTMFromYaml(unittest.TestCase): + @classmethod + def setUpClass(cls): + # Initialize the ROS context for the test node + rclpy.init() + + @classmethod + def tearDownClass(cls): + # Shutdown the ROS context + rclpy.shutdown() + + def setUp(self): + # Create a ROS node for tests + self.test_node = rclpy.create_node("test_node") + self.evaluation_time = 0.2 # 200ms + self.received_message = None + + def tearDown(self): + self.test_node.destroy_node() + + def callback(self, msg): + self.received_message = msg + + @staticmethod + def print_message(stat): + logger.debug("===========================") + logger.debug(stat) + + def test_node_link(self): + # Create custom QoS profile for subscription + custom_qos_profile = QoSProfile( + depth=1, + history=QoSHistoryPolicy.KEEP_LAST, + durability=QoSDurabilityPolicy.TRANSIENT_LOCAL, + ) + + # Create subscription to map_projector_info topic + subscription = self.test_node.create_subscription( + MapProjectorInfo, + "/map_projection_loader/map_projector_info", + self.callback, + custom_qos_profile, + ) + + # Give time for the message to be received and processed + rclpy.spin_until_future_complete( + self.test_node, rclpy.task.Future(), timeout_sec=self.evaluation_time + ) + + # Load the yaml file directly + map_projection_info_path = os.path.join( + get_package_share_directory("map_projection_loader"), YAML_FILE_PATH + ) + with open(map_projection_info_path) as f: + yaml_data = yaml.load(f) + + # Test if message received + self.assertIsNotNone( + self.received_message, "No message received on map_projector_info topic" + ) + self.assertEqual(self.received_message.type, yaml_data["type"]) + self.assertEqual( + self.received_message.map_origin.latitude, yaml_data["map_origin"]["latitude"] + ) + self.assertEqual( + self.received_message.map_origin.longitude, yaml_data["map_origin"]["longitude"] + ) + + self.test_node.destroy_subscription(subscription) + + +@launch_testing.post_shutdown_test() +class TestProcessOutput(unittest.TestCase): + def test_exit_code(self, proc_info): + # Check that process exits with code 0: no error + launch_testing.asserts.assertExitCodes(proc_info) From 1680656a93ddb58ef50b32a2fa96987966ebd2a0 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 10 Aug 2023 12:05:04 +0900 Subject: [PATCH 02/16] feat(avoidance): output unconfortable path with unsafe state (#4536) * feat(avoidance): output unconfortable path with unsafe state Signed-off-by: satoshi-ota * feat(avoidance): make it selectable avoidance policy Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/avoidance/avoidance.param.yaml | 21 ++++++++-- .../avoidance/avoidance_module.hpp | 9 +++++ .../utils/avoidance/avoidance_module_data.hpp | 18 ++++++++- .../avoidance/avoidance_module.cpp | 40 ++++++++++--------- .../src/scene_module/avoidance/manager.cpp | 17 ++++++-- .../src/utils/avoidance/utils.cpp | 2 +- 6 files changed, 79 insertions(+), 28 deletions(-) diff --git a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml index 22de79f4dc7d0..ac3840baa1c4c 100644 --- a/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml +++ b/planning/behavior_path_planner/config/avoidance/avoidance.param.yaml @@ -175,16 +175,29 @@ max_distance: 20.0 # [m] stop_buffer: 1.0 # [m] - constraints: - # vehicle slows down under longitudinal constraints - use_constraints_for_decel: false # [-] + policy: + # policy for vehicle slow down behavior. select "best_effort" or "reliable". + # "best_effort": slow down deceleration & jerk are limited by constraints. + # but there is a possibility that the vehicle can't stop in front of the vehicle. + # "reliable": insert stop or slow down point with ignoring decel/jerk constraints. + # make it possible to increase chance to avoid but uncomfortable deceleration maybe happen. + deceleration: "best_effort" # [-] + # policy for avoidance lateral margin. select "best_effort" or "reliable". + # "best_effort": output avoidance path with shorten lateral margin when there is no enough longitudinal + # margin to avoid. + # "reliable": module output avoidance path with safe (rtc cooperate) state only when the vehicle can avoid + # with expected lateral margin. + lateral_margin: "best_effort" # [-] + # if true, module doesn't wait deceleration and outputs avoidance path by best effort margin. + use_shorten_margin_immediately: true # [-] + constraints: # lateral constraints lateral: velocity: [1.0, 1.38, 11.1] # [m/s] max_accel_values: [0.5, 0.5, 0.5] # [m/ss] min_jerk_values: [0.2, 0.2, 0.2] # [m/sss] - max_jerk_values: [1.0, 1.0, 1.0] # [m/sss] + max_jerk_values: [1.0, 1.0, 1.0] # [m/sss] # longitudinal constraints longitudinal: diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp index 3095ec2c03251..55ecee17b9778 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/avoidance/avoidance_module.hpp @@ -480,6 +480,15 @@ class AvoidanceModule : public SceneModuleInterface */ bool isSafePath(ShiftedPath & shifted_path, DebugData & debug) const; + bool isComfortable(const AvoidLineArray & shift_lines) const + { + return std::all_of(shift_lines.begin(), shift_lines.end(), [&](const auto & line) { + return PathShifter::calcJerkFromLatLonDistance( + line.getRelativeLength(), line.getRelativeLongitudinal(), + helper_.getAvoidanceEgoSpeed()) < helper_.getLateralMaxJerkLimit(); + }); + } + // post process /** diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp index 0263eee5fe727..94b914b65a067 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/avoidance/avoidance_module_data.hpp @@ -113,8 +113,11 @@ struct AvoidanceParameters // use intersection area for avoidance bool use_intersection_areas{false}; - // constrains - bool use_constraints_for_decel{false}; + // // constrains + // bool use_constraints_for_decel{false}; + + // // policy + // bool use_relaxed_margin_immediately{false}; // max deceleration for double max_deceleration; @@ -274,6 +277,15 @@ struct AvoidanceParameters // For shift line generation process. Remove sharp(=jerky) shift line. double sharp_shift_filter_threshold; + // policy + bool use_shorten_margin_immediately{false}; + + // policy + std::string policy_deceleration{"best_effort"}; + + // policy + std::string policy_lateral_margin{"best_effort"}; + // target velocity matrix std::vector velocity_map; @@ -465,6 +477,8 @@ struct AvoidancePlanningData bool safe{false}; + bool comfortable{false}; + bool avoid_required{false}; bool yield_required{false}; diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index db80bc72f21ad..92f586a1ca70a 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -95,6 +95,11 @@ bool isDrivingSameLane( return !same_ids.empty(); } + +bool isBestEffort(const std::string & policy) +{ + return policy == "best_effort"; +} } // namespace AvoidanceModule::AvoidanceModule( @@ -129,7 +134,7 @@ bool AvoidanceModule::isExecutionRequested() const bool AvoidanceModule::isExecutionReady() const { DEBUG_PRINT("AVOIDANCE isExecutionReady"); - return avoidance_data_.safe; + return avoidance_data_.safe && avoidance_data_.comfortable; } bool AvoidanceModule::canTransitSuccessState() @@ -448,6 +453,7 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de * Check avoidance path safety. For each target objects and the objects in adjacent lanes, * check that there is a certain amount of margin in the lateral and longitudinal direction. */ + data.comfortable = isComfortable(data.unapproved_new_sl); data.safe = isSafePath(data.candidate_path, debug); } @@ -616,7 +622,7 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif return; } - insertPrepareVelocity(path); + // insertPrepareVelocity(path); switch (data.state) { case AvoidanceState::NOT_AVOID: { @@ -624,20 +630,20 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif } case AvoidanceState::YIELD: { insertYieldVelocity(path); - insertWaitPoint(parameters_->use_constraints_for_decel, path); + insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); removeRegisteredShiftLines(); break; } case AvoidanceState::AVOID_PATH_NOT_READY: { - insertWaitPoint(parameters_->use_constraints_for_decel, path); + insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); break; } case AvoidanceState::AVOID_PATH_READY: { - insertWaitPoint(parameters_->use_constraints_for_decel, path); + insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); break; } case AvoidanceState::AVOID_EXECUTE: { - insertStopPoint(parameters_->use_constraints_for_decel, path); + insertStopPoint(isBestEffort(parameters_->policy_deceleration), path); break; } default: @@ -835,6 +841,10 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects( const auto avoiding_shift = desire_shift_length - current_ego_shift; const auto nominal_avoid_distance = helper_.getMaxAvoidanceDistance(avoiding_shift); + if (!isBestEffort(parameters_->policy_lateral_margin)) { + return desire_shift_length; + } + // ego already has enough positive shift. const auto has_enough_positive_shift = avoiding_shift < -1e-3 && desire_shift_length > 1e-3; if (is_object_on_right && has_enough_positive_shift) { @@ -847,6 +857,11 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects( return desire_shift_length; } + // don't relax shift length since it can stop in front of the object. + if (object.is_stoppable && !parameters_->use_shorten_margin_immediately) { + return desire_shift_length; + } + // calculate remaining distance. const auto prepare_distance = helper_.getNominalPrepareDistance(); const auto constant = @@ -883,7 +898,7 @@ AvoidLineArray AvoidanceModule::calcRawShiftLinesFromObjects( } // avoidance distance is not enough. unavoidable. - if (!parameters_->use_constraints_for_decel) { + if (!isBestEffort(parameters_->policy_deceleration)) { object.reason = AvoidanceDebugFactor::TOO_LARGE_JERK; return boost::none; } @@ -2369,13 +2384,6 @@ AvoidLineArray AvoidanceModule::findNewShiftLine(const AvoidLineArray & candidat return subsequent; }; - // check jerk limit. - const auto is_large_jerk = [this](const auto & s) { - const auto jerk = PathShifter::calcJerkFromLatLonDistance( - s.getRelativeLength(), s.getRelativeLongitudinal(), helper_.getAvoidanceEgoSpeed()); - return jerk > helper_.getLateralMaxJerkLimit(); - }; - // check ignore or not. const auto is_ignore_shift = [this](const auto & s) { return std::abs(helper_.getRelativeShiftToPath(s)) < parameters_->lateral_execution_threshold; @@ -2392,10 +2400,6 @@ AvoidLineArray AvoidanceModule::findNewShiftLine(const AvoidLineArray & candidat } if (!is_ignore_shift(candidate)) { - if (is_large_jerk(candidate)) { - break; - } - return get_subsequent_shift(i); } } diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp index a0ae98276c05e..be8c610611422 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/manager.cpp @@ -191,10 +191,21 @@ AvoidanceModuleManager::AvoidanceModuleManager( p.stop_buffer = get_parameter(node, ns + "stop_buffer"); } - // constraints + // policy { - std::string ns = "avoidance.constraints."; - p.use_constraints_for_decel = get_parameter(node, ns + "use_constraints_for_decel"); + std::string ns = "avoidance.policy."; + p.policy_deceleration = get_parameter(node, ns + "deceleration"); + p.policy_lateral_margin = get_parameter(node, ns + "lateral_margin"); + p.use_shorten_margin_immediately = + get_parameter(node, ns + "use_shorten_margin_immediately"); + + if (p.policy_deceleration != "best_effort" && p.policy_deceleration != "reliable") { + throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); + } + + if (p.policy_lateral_margin != "best_effort" && p.policy_lateral_margin != "reliable") { + throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); + } } // constraints (longitudinal) diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index 58beaf9cf3a87..ed38cc663bc84 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -725,7 +725,7 @@ void fillObjectStoppableJudge( ObjectData & object_data, const ObjectDataArray & registered_objects, const double feasible_stop_distance, const std::shared_ptr & parameters) { - if (!parameters->use_constraints_for_decel) { + if (parameters->policy_deceleration == "reliable") { object_data.is_stoppable = true; return; } From 9f22504f4562c826b372fdf1ebec712001f6b9bc Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 10 Aug 2023 12:26:36 +0900 Subject: [PATCH 03/16] fix(scnenario_selector): prevent changing scneario when same uuid route is received (#4569) Signed-off-by: kosuke55 --- .../src/scenario_selector_node/scenario_selector_node.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp b/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp index dfba038dee898..cffb490464de0 100644 --- a/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp +++ b/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp @@ -197,8 +197,13 @@ void ScenarioSelectorNode::onMap( void ScenarioSelectorNode::onRoute( const autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr msg) { + // When the route id is the same (e.g. reporting with modified goal) keep the current scenario. + // Otherwise, reset the scenario. + if (!route_handler_ || route_handler_->getRouteUuid() != msg->uuid) { + current_scenario_ = tier4_planning_msgs::msg::Scenario::EMPTY; + } + route_ = msg; - current_scenario_ = tier4_planning_msgs::msg::Scenario::EMPTY; } void ScenarioSelectorNode::onOdom(const nav_msgs::msg::Odometry::ConstSharedPtr msg) From f52d0aa90b7b6b5a3c3691d9af3ad7ea60fa7e94 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 10 Aug 2023 13:33:24 +0900 Subject: [PATCH 04/16] chore: update CODEOWNERS (#4550) Signed-off-by: GitHub Co-authored-by: kminoda --- .github/CODEOWNERS | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 1c0587f1ac1d5..4b1727e8a67b1 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -79,6 +79,7 @@ launch/tier4_sensing_launch/** yukihiro.saito@tier4.jp launch/tier4_simulator_launch/** keisuke.shima@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp launch/tier4_system_launch/** akihiro.sakurai@tier4.jp fumihito.ito@tier4.jp launch/tier4_vehicle_launch/** yukihiro.saito@tier4.jp +localization/ar_tag_based_localizer/** masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp localization/ekf_localizer/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp localization/gyro_odometer/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp localization/initial_pose_button_panel/** masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp @@ -95,6 +96,7 @@ localization/yabloc/yabloc_particle_filter/** kento.yabuuchi.2@tier4.jp masahiro localization/yabloc/yabloc_pose_initializer/** kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp map/map_height_fitter/** isamu.takagi@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp map/map_loader/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp +map/map_projection_loader/** koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp yamato.ando@tier4.jp map/map_tf_generator/** azumi.suzuki@tier4.jp map/util/lanelet2_map_preprocessor/** ryohsuke.mitsudome@tier4.jp perception/bytetrack/** manato.hirabayashi@tier4.jp From 0c2c703de2e28e1ce52831aec96f74e6e6125e73 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 10 Aug 2023 15:11:15 +0900 Subject: [PATCH 05/16] fix(avoidance): remove unexpected comment out (#4587) Signed-off-by: satoshi-ota --- .../src/scene_module/avoidance/avoidance_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp index 92f586a1ca70a..a763bab7897fb 100644 --- a/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/avoidance/avoidance_module.cpp @@ -622,7 +622,7 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif return; } - // insertPrepareVelocity(path); + insertPrepareVelocity(path); switch (data.state) { case AvoidanceState::NOT_AVOID: { From 715996523f6254e04669d25b7679d5274fcde7a9 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 10 Aug 2023 16:17:19 +0900 Subject: [PATCH 06/16] fix(behavior_path_planner): fix bad dynamic drivable area expansion at path extremities (#4259) Signed-off-by: Maxime CLEMENT --- .../drivable_area_expansion.hpp | 2 +- .../drivable_area_expansion/expansion.hpp | 14 +- .../drivable_area_expansion/footprints.hpp | 4 +- .../drivable_area_expansion/map_utils.hpp | 2 +- .../utils/drivable_area_expansion/types.hpp | 6 +- .../drivable_area_expansion.cpp | 203 +++++++++++------- .../drivable_area_expansion/expansion.cpp | 51 +++-- .../drivable_area_expansion/footprints.cpp | 8 +- .../drivable_area_expansion/map_utils.cpp | 4 +- .../test/test_drivable_area_expansion.cpp | 32 +-- 10 files changed, 202 insertions(+), 124 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp index eadfb72a42afa..53ef91473fe24 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp @@ -40,7 +40,7 @@ void expandDrivableArea( /// @param[in] expansion_polygons polygons to add to the drivable area /// @return expanded drivable area polygon polygon_t createExpandedDrivableAreaPolygon( - const PathWithLaneId & path, const multipolygon_t & expansion_polygons); + const PathWithLaneId & path, const multi_polygon_t & expansion_polygons); /// @brief Update the drivable area of the given path with the given polygon /// @details this function splits the polygon into a left and right bound and sets it in the path diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/expansion.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/expansion.hpp index 33bccf90ffbe8..70cc8a8bc5925 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/expansion.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/expansion.hpp @@ -36,7 +36,7 @@ namespace drivable_area_expansion /// @return distance limit double calculateDistanceLimit( const linestring_t & base_ls, const polygon_t & expansion_polygon, - const multilinestring_t & limit_lines); + const multi_linestring_t & limit_lines); /// @brief Calculate the distance limit required for the polygon to not cross the limit polygons. /// @details Calculate the minimum distance from base_ls to an intersection of limit_polygons and @@ -47,7 +47,7 @@ double calculateDistanceLimit( /// @return distance limit double calculateDistanceLimit( const linestring_t & base_ls, const polygon_t & expansion_polygon, - const multipolygon_t & limit_polygons); + const multi_polygon_t & limit_polygons); /// @brief Create a polygon from a base line with a given expansion distance /// @param[in] base_ls base linestring from which the polygon is created @@ -64,9 +64,9 @@ polygon_t createExpansionPolygon( /// @param[in] uncrossable_lines lines that should not be crossed by the expanded drivable area /// @param[in] params expansion parameters /// @return expansion polygons -multipolygon_t createExpansionPolygons( - const PathWithLaneId & path, const multipolygon_t & path_footprints, - const multipolygon_t & predicted_paths, const multilinestring_t & uncrossable_lines, +multi_polygon_t createExpansionPolygons( + const PathWithLaneId & path, const multi_polygon_t & path_footprints, + const multi_polygon_t & predicted_paths, const multi_linestring_t & uncrossable_lines, const DrivableAreaExpansionParameters & params); /// @brief Create polygons for the area where the drivable area should be expanded @@ -76,9 +76,9 @@ multipolygon_t createExpansionPolygons( /// @param[in] predicted_paths polygons of the dynamic objects' predicted paths /// @param[in] params expansion parameters /// @return expansion polygons -multipolygon_t createExpansionLaneletPolygons( +multi_polygon_t createExpansionLaneletPolygons( const lanelet::ConstLanelets & path_lanes, const route_handler::RouteHandler & route_handler, - const multipolygon_t & path_footprints, const multipolygon_t & predicted_paths, + const multi_polygon_t & path_footprints, const multi_polygon_t & predicted_paths, const DrivableAreaExpansionParameters & params); } // namespace drivable_area_expansion diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp index 25f061affaa48..e5e1c76f2521f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp @@ -55,7 +55,7 @@ polygon_t createFootprint(const geometry_msgs::msg::Pose & pose, const polygon_t /// @param [in] objects objects from which to create polygons /// @param[in] params expansion parameters containing extra offsets to add to the dynamic objects /// @return footprint polygons of the object's predicted paths -multipolygon_t createObjectFootprints( +multi_polygon_t createObjectFootprints( const autoware_auto_perception_msgs::msg::PredictedObjects & objects, const DrivableAreaExpansionParameters & params); @@ -63,7 +63,7 @@ multipolygon_t createObjectFootprints( /// @param[in] path the path for which to create a footprint /// @param[in] params expansion parameters defining how to create the footprint /// @return footprint polygons of the path -multipolygon_t createPathFootprints( +multi_polygon_t createPathFootprints( const PathWithLaneId & path, const DrivableAreaExpansionParameters & params); } // namespace drivable_area_expansion #endif // BEHAVIOR_PATH_PLANNER__UTILS__DRIVABLE_AREA_EXPANSION__FOOTPRINTS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp index 33c4cc8a0eff3..4524bd2be2299 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp @@ -28,7 +28,7 @@ namespace drivable_area_expansion /// @param[in] lanelet_map lanelet map /// @param[in] uncrossable_types types that cannot be crossed /// @return the uncrossable linestrings -multilinestring_t extractUncrossableLines( +multi_linestring_t extractUncrossableLines( const lanelet::LaneletMap & lanelet_map, const std::vector & uncrossable_types); /// @brief Determine if the given linestring has one of the given types diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp index e56ef4961589d..daabfa97598fd 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp @@ -30,13 +30,13 @@ using autoware_auto_planning_msgs::msg::PathWithLaneId; using geometry_msgs::msg::Point; using point_t = tier4_autoware_utils::Point2d; -using multipoint_t = tier4_autoware_utils::MultiPoint2d; +using multi_point_t = tier4_autoware_utils::MultiPoint2d; using polygon_t = tier4_autoware_utils::Polygon2d; using ring_t = tier4_autoware_utils::LinearRing2d; -using multipolygon_t = tier4_autoware_utils::MultiPolygon2d; +using multi_polygon_t = tier4_autoware_utils::MultiPolygon2d; using segment_t = tier4_autoware_utils::Segment2d; using linestring_t = tier4_autoware_utils::LineString2d; -using multilinestring_t = tier4_autoware_utils::MultiLineString2d; +using multi_linestring_t = tier4_autoware_utils::MultiLineString2d; struct PointDistance { diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp index 21e3580c1f19a..617c3cd633cda 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp @@ -21,6 +21,8 @@ #include "behavior_path_planner/utils/drivable_area_expansion/types.hpp" #include "interpolation/linear_interpolation.hpp" +#include + #include namespace drivable_area_expansion @@ -33,7 +35,7 @@ void expandDrivableArea( { const auto uncrossable_lines = extractUncrossableLines(*route_handler.getLaneletMapPtr(), params.avoid_linestring_types); - multilinestring_t uncrossable_lines_in_range; + multi_linestring_t uncrossable_lines_in_range; const auto & p = path.points.front().point.pose.position; for (const auto & line : uncrossable_lines) if (boost::geometry::distance(line, point_t{p.x, p.y}) < params.max_path_arc_length) @@ -61,7 +63,7 @@ Point convert_point(const point_t & p) } polygon_t createExpandedDrivableAreaPolygon( - const PathWithLaneId & path, const multipolygon_t & expansion_polygons) + const PathWithLaneId & path, const multi_polygon_t & expansion_polygons) { polygon_t original_da_poly; original_da_poly.outer().reserve(path.left_bound.size() + path.right_bound.size() + 1); @@ -70,7 +72,7 @@ polygon_t createExpandedDrivableAreaPolygon( original_da_poly.outer().push_back(convert_point(*it)); original_da_poly.outer().push_back(original_da_poly.outer().front()); - multipolygon_t unions; + multi_polygon_t unions; auto expanded_da_poly = original_da_poly; for (const auto & p : expansion_polygons) { unions.clear(); @@ -81,59 +83,6 @@ polygon_t createExpandedDrivableAreaPolygon( return expanded_da_poly; } -std::array findLeftRightRanges( - const PathWithLaneId & path, const ring_t & expanded_drivable_area) -{ - const auto is_left_of_segment = [](const point_t & a, const point_t & b, const point_t & p) { - return (b.x() - a.x()) * (p.y() - a.y()) - (b.y() - a.y()) * (p.x() - a.x()) > 0; - }; - const auto is_left_of_path_start = [&](const point_t & p) { - return is_left_of_segment( - convert_point(path.points[0].point.pose.position), - convert_point(path.points[1].point.pose.position), p); - }; - const auto is_left_of_path_end = [&, size = path.points.size()](const point_t & p) { - return is_left_of_segment( - convert_point(path.points[size - 2].point.pose.position), - convert_point(path.points[size - 1].point.pose.position), p); - }; - const auto dist_to_path_start = [start = convert_point(path.points.front().point.pose.position)]( - const auto & p) { return boost::geometry::distance(start, p); }; - const auto dist_to_path_end = [end = convert_point(path.points.back().point.pose.position)]( - const auto & p) { return boost::geometry::distance(end, p); }; - - double min_start_dist = std::numeric_limits::max(); - auto start_transition = expanded_drivable_area.end(); - double min_end_dist = std::numeric_limits::max(); - auto end_transition = expanded_drivable_area.end(); - for (auto it = expanded_drivable_area.begin(); std::next(it) != expanded_drivable_area.end(); - ++it) { - if (is_left_of_path_start(*it) != is_left_of_path_start(*std::next(it))) { - const auto dist = dist_to_path_start(*it); - if (dist < min_start_dist) { - start_transition = it; - min_start_dist = dist; - } - } - if (is_left_of_path_end(*it) != is_left_of_path_end(*std::next(it))) { - const auto dist = dist_to_path_end(*it); - if (dist < min_end_dist) { - end_transition = it; - min_end_dist = dist; - } - } - } - const auto left_start = - is_left_of_path_start(*start_transition) ? start_transition : std::next(start_transition); - const auto right_start = - is_left_of_path_start(*start_transition) ? std::next(start_transition) : start_transition; - const auto left_end = - is_left_of_path_end(*end_transition) ? end_transition : std::next(end_transition); - const auto right_end = - is_left_of_path_end(*end_transition) ? std::next(end_transition) : end_transition; - return {left_start, left_end, right_start, right_end}; -} - void copy_z_over_arc_length( const std::vector & from, std::vector & to) { @@ -164,32 +113,134 @@ void updateDrivableAreaBounds(PathWithLaneId & path, const polygon_t & expanded_ { const auto original_left_bound = path.left_bound; const auto original_right_bound = path.right_bound; + const auto is_left_of_segment = [](const point_t & a, const point_t & b, const point_t & p) { + return (b.x() - a.x()) * (p.y() - a.y()) - (b.y() - a.y()) * (p.x() - a.x()) > 0; + }; + // prepare delimiting lines: start and end of the original expanded drivable area + const auto start_segment = + segment_t{convert_point(path.left_bound.front()), convert_point(path.right_bound.front())}; + const auto end_segment = + segment_t{convert_point(path.left_bound.back()), convert_point(path.right_bound.back())}; + point_t start_segment_center; + boost::geometry::centroid(start_segment, start_segment_center); + const auto path_start_segment = + segment_t{start_segment_center, convert_point(path.points[1].point.pose.position)}; + point_t end_segment_center; + boost::geometry::centroid(end_segment, end_segment_center); + const auto path_end_segment = + segment_t{convert_point(path.points.back().point.pose.position), end_segment_center}; + const auto segment_to_line_intersection = + [](const auto p1, const auto p2, const auto q1, const auto q2) -> std::optional { + const auto line = Eigen::Hyperplane::Through(q1, q2); + const auto segment = Eigen::Hyperplane::Through(p1, p2); + const auto intersection = line.intersection(segment); + std::optional result; + const auto is_on_segment = + (p1.x() <= p2.x() ? intersection.x() >= p1.x() && intersection.x() <= p2.x() + : intersection.x() <= p1.x() && intersection.x() >= p2.x()) && + (p1.y() <= p2.y() ? intersection.y() >= p1.y() && intersection.y() <= p2.y() + : intersection.y() <= p1.y() && intersection.y() >= p2.y()); + if (is_on_segment) result = point_t{intersection.x(), intersection.y()}; + return result; + }; + // find intersection between the expanded drivable area and the delimiting lines + const auto & da = expanded_drivable_area.outer(); + struct Intersection + { + point_t intersection_point; + ring_t::const_iterator segment_it; + double distance = std::numeric_limits::max(); + explicit Intersection(ring_t::const_iterator it) : segment_it(it) {} + void update(const point_t & p, const ring_t::const_iterator & it, const double dist) + { + intersection_point = p; + segment_it = it; + distance = dist; + } + }; + Intersection start_left(da.end()); + Intersection end_left(da.end()); + Intersection start_right(da.end()); + Intersection end_right(da.end()); + for (auto it = da.begin(); it != da.end(); ++it) { + if (boost::geometry::distance(*it, start_segment.first) < 1e-3) + start_left.update(*it, it, 0.0); + else if (boost::geometry::distance(*it, start_segment.second) < 1e-3) + start_right.update(*it, it, 0.0); + else if (boost::geometry::distance(*it, end_segment.first) < 1e-3) + end_left.update(*it, it, 0.0); + else if (boost::geometry::distance(*it, end_segment.second) < 1e-3) + end_right.update(*it, it, 0.0); + const auto inter_start = + std::next(it) == da.end() + ? segment_to_line_intersection(*it, da.front(), start_segment.first, start_segment.second) + : segment_to_line_intersection( + *it, *std::next(it), start_segment.first, start_segment.second); + if (inter_start) { + const auto dist = boost::geometry::distance(*inter_start, path_start_segment); + const auto is_left_of_path_start = is_left_of_segment( + convert_point(path.points[0].point.pose.position), + convert_point(path.points[1].point.pose.position), *inter_start); + if (is_left_of_path_start && dist < start_left.distance) + start_left.update(*inter_start, it, dist); + else if (!is_left_of_path_start && dist < start_right.distance) + start_right.update(*inter_start, it, dist); + } + const auto inter_end = + std::next(it) == da.end() + ? segment_to_line_intersection(*it, da.front(), end_segment.first, end_segment.second) + : segment_to_line_intersection(*it, *std::next(it), end_segment.first, end_segment.second); + if (inter_end) { + const auto dist = boost::geometry::distance(*inter_end, path_end_segment); + const auto is_left_of_path_end = is_left_of_segment( + convert_point(path.points.back().point.pose.position), end_segment_center, *inter_end); + if (is_left_of_path_end && dist < end_left.distance) + end_left.update(*inter_end, it, dist); + else if (!is_left_of_path_end && dist < end_right.distance) + end_right.update(*inter_end, it, dist); + } + } + if ( // ill-formed expanded drivable area -> keep the original bounds + start_left.segment_it == da.end() || start_right.segment_it == da.end() || + end_left.segment_it == da.end() || end_right.segment_it == da.end()) { + return; + } + // extract the expanded left and right bound from the expanded drivable area path.left_bound.clear(); path.right_bound.clear(); - const auto begin = expanded_drivable_area.outer().begin(); - const auto end = std::prev(expanded_drivable_area.outer().end()); - const auto & [left_start, left_end, right_start, right_end] = - findLeftRightRanges(path, expanded_drivable_area.outer()); - // NOTE: clockwise ordering -> positive increment for left bound, negative for right bound - if (left_start < left_end) { - path.left_bound.reserve(std::distance(left_start, left_end)); - for (auto it = left_start; it <= left_end; ++it) path.left_bound.push_back(convert_point(*it)); - } else { // loop back - path.left_bound.reserve(std::distance(left_start, end) + std::distance(begin, left_end)); - for (auto it = left_start; it != end; ++it) path.left_bound.push_back(convert_point(*it)); - for (auto it = begin; it <= left_end; ++it) path.left_bound.push_back(convert_point(*it)); + path.left_bound.push_back(convert_point(start_left.intersection_point)); + path.right_bound.push_back(convert_point(start_right.intersection_point)); + if (!boost::geometry::equals(start_right.intersection_point, *start_right.segment_it)) + path.right_bound.push_back(convert_point(*start_right.segment_it)); + if (start_left.segment_it < end_left.segment_it) { + for (auto it = std::next(start_left.segment_it); it <= end_left.segment_it; ++it) + path.left_bound.push_back(convert_point(*it)); + } else { + for (auto it = std::next(start_left.segment_it); it < da.end(); ++it) + path.left_bound.push_back(convert_point(*it)); + for (auto it = da.begin(); it <= end_left.segment_it; ++it) + path.left_bound.push_back(convert_point(*it)); } - if (right_start > right_end) { - path.right_bound.reserve(std::distance(right_end, right_start)); - for (auto it = right_start; it >= right_end; --it) + if (!boost::geometry::equals(end_left.intersection_point, *end_left.segment_it)) + path.left_bound.push_back(convert_point(end_left.intersection_point)); + if (start_right.segment_it < end_right.segment_it) { + for (auto it = std::prev(start_right.segment_it); it >= da.begin(); --it) + path.right_bound.push_back(convert_point(*it)); + for (auto it = std::prev(da.end()); it > end_right.segment_it; --it) + path.right_bound.push_back(convert_point(*it)); + } else { + for (auto it = std::prev(start_right.segment_it); it > end_right.segment_it; --it) path.right_bound.push_back(convert_point(*it)); - } else { // loop back - path.right_bound.reserve(std::distance(begin, right_start) + std::distance(right_end, end)); - for (auto it = right_start; it >= begin; --it) path.right_bound.push_back(convert_point(*it)); - for (auto it = end - 1; it >= right_end; --it) path.right_bound.push_back(convert_point(*it)); } + if (!boost::geometry::equals(end_right.intersection_point, *std::next(end_right.segment_it))) + path.right_bound.push_back(convert_point(end_right.intersection_point)); + // remove possible duplicated points + const auto point_cmp = [](const auto & p1, const auto & p2) { + return p1.x == p2.x && p1.y == p2.y; + }; + std::unique(path.left_bound.begin(), path.left_bound.end(), point_cmp); + std::unique(path.right_bound.begin(), path.right_bound.end(), point_cmp); copy_z_over_arc_length(original_left_bound, path.left_bound); copy_z_over_arc_length(original_right_bound, path.right_bound); } - } // namespace drivable_area_expansion diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp index 7bff7bef578ce..035cc579d2a82 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/expansion.cpp @@ -22,10 +22,10 @@ namespace drivable_area_expansion double calculateDistanceLimit( const linestring_t & base_ls, const polygon_t & expansion_polygon, - const multilinestring_t & limit_lines) + const multi_linestring_t & limit_lines) { auto dist_limit = std::numeric_limits::max(); - multipoint_t intersections; + multi_point_t intersections; boost::geometry::intersection(expansion_polygon, limit_lines, intersections); for (const auto & p : intersections) dist_limit = std::min(dist_limit, boost::geometry::distance(p, base_ls)); @@ -34,11 +34,11 @@ double calculateDistanceLimit( double calculateDistanceLimit( const linestring_t & base_ls, const polygon_t & expansion_polygon, - const multipolygon_t & limit_polygons) + const multi_polygon_t & limit_polygons) { auto dist_limit = std::numeric_limits::max(); for (const auto & polygon : limit_polygons) { - multipoint_t intersections; + multi_point_t intersections; boost::geometry::intersection(expansion_polygon, polygon, intersections); for (const auto & p : intersections) dist_limit = std::min(dist_limit, boost::geometry::distance(p, base_ls)); @@ -50,7 +50,7 @@ polygon_t createExpansionPolygon( const linestring_t & base_ls, const double dist, const bool is_left_side) { namespace strategy = boost::geometry::strategy::buffer; - multipolygon_t polygons; + multi_polygon_t polygons; // set a non 0 value for the buffer as it sometimes causes no polygon to be returned by bg:buffer constexpr auto zero = 0.1; const auto left_dist = is_left_side ? dist : zero; @@ -66,7 +66,7 @@ std::array calculate_arc_length_range_and_distance( const linestring_t & path_ls, const polygon_t & footprint, const linestring_t & bound, const bool is_left, const double path_length) { - multipoint_t intersections; + multi_point_t intersections; double expansion_dist = 0.0; double from_arc_length = std::numeric_limits::max(); double to_arc_length = std::numeric_limits::min(); @@ -93,7 +93,7 @@ std::array calculate_arc_length_range_and_distance( polygon_t create_compensation_polygon( const linestring_t & base_ls, const double compensation_dist, const bool is_left, - const multilinestring_t uncrossable_lines, const multipolygon_t & predicted_paths) + const multi_linestring_t uncrossable_lines, const multi_polygon_t & predicted_paths) { polygon_t compensation_polygon = createExpansionPolygon(base_ls, compensation_dist, !is_left); double dist_limit = std::min( @@ -106,9 +106,9 @@ polygon_t create_compensation_polygon( return compensation_polygon; } -multipolygon_t createExpansionPolygons( - const PathWithLaneId & path, const multipolygon_t & path_footprints, - const multipolygon_t & predicted_paths, const multilinestring_t & uncrossable_lines, +multi_polygon_t createExpansionPolygons( + const PathWithLaneId & path, const multi_polygon_t & path_footprints, + const multi_polygon_t & predicted_paths, const multi_linestring_t & uncrossable_lines, const DrivableAreaExpansionParameters & params) { linestring_t path_ls; @@ -118,9 +118,32 @@ multipolygon_t createExpansionPolygons( path_ls.emplace_back(p.point.pose.position.x, p.point.pose.position.y); for (const auto & p : path.left_bound) left_ls.emplace_back(p.x, p.y); for (const auto & p : path.right_bound) right_ls.emplace_back(p.x, p.y); + // extend the path linestring to the beginning and end of the drivable area + if (!right_ls.empty() && !left_ls.empty() && path_ls.size() > 2) { + const auto left_proj_begin = point_to_line_projection(left_ls.front(), path_ls[0], path_ls[1]); + const auto right_proj_begin = + point_to_line_projection(right_ls.front(), path_ls[0], path_ls[1]); + const auto left_ls_proj_begin = point_to_linestring_projection(left_proj_begin.point, path_ls); + const auto right_ls_proj_begin = + point_to_linestring_projection(right_proj_begin.point, path_ls); + if (left_ls_proj_begin.arc_length < right_ls_proj_begin.arc_length) + path_ls.insert(path_ls.begin(), left_proj_begin.point); + else + path_ls.insert(path_ls.begin(), right_proj_begin.point); + const auto left_proj_end = + point_to_line_projection(left_ls.back(), path_ls[path_ls.size() - 2], path_ls.back()); + const auto right_proj_end = + point_to_line_projection(right_ls.back(), path_ls[path_ls.size() - 2], path_ls.back()); + const auto left_ls_proj_end = point_to_linestring_projection(left_proj_end.point, path_ls); + const auto right_ls_proj_end = point_to_linestring_projection(right_proj_end.point, path_ls); + if (left_ls_proj_end.arc_length > right_ls_proj_end.arc_length) + path_ls.push_back(left_proj_end.point); + else + path_ls.push_back(right_proj_end.point); + } const auto path_length = static_cast(boost::geometry::length(path_ls)); - multipolygon_t expansion_polygons; + multi_polygon_t expansion_polygons; for (const auto & footprint : path_footprints) { bool is_left = true; for (const auto & bound : {left_ls, right_ls}) { @@ -161,12 +184,12 @@ multipolygon_t createExpansionPolygons( return expansion_polygons; } -multipolygon_t createExpansionLaneletPolygons( +multi_polygon_t createExpansionLaneletPolygons( const lanelet::ConstLanelets & path_lanes, const route_handler::RouteHandler & route_handler, - const multipolygon_t & path_footprints, const multipolygon_t & predicted_paths, + const multi_polygon_t & path_footprints, const multi_polygon_t & predicted_paths, const DrivableAreaExpansionParameters & params) { - multipolygon_t expansion_polygons; + multi_polygon_t expansion_polygons; lanelet::ConstLanelets candidates; const auto already_added = [&](const auto & ll) { return std::find_if(candidates.begin(), candidates.end(), [&](const auto & l) { diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/footprints.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/footprints.cpp index 77c8b7faa27eb..0c31093a83c0e 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/footprints.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/footprints.cpp @@ -39,11 +39,11 @@ polygon_t createFootprint(const geometry_msgs::msg::Pose & pose, const polygon_t return translatePolygon(rotatePolygon(base_footprint, angle), pose.position.x, pose.position.y); } -multipolygon_t createObjectFootprints( +multi_polygon_t createObjectFootprints( const autoware_auto_perception_msgs::msg::PredictedObjects & objects, const DrivableAreaExpansionParameters & params) { - multipolygon_t footprints; + multi_polygon_t footprints; if (params.avoid_dynamic_objects) { for (const auto & object : objects.objects) { const auto front = object.shape.dimensions.x / 2 + params.dynamic_objects_extra_front_offset; @@ -62,7 +62,7 @@ multipolygon_t createObjectFootprints( return footprints; } -multipolygon_t createPathFootprints( +multi_polygon_t createPathFootprints( const PathWithLaneId & path, const DrivableAreaExpansionParameters & params) { const auto left = params.ego_left_offset + params.ego_extra_left_offset; @@ -73,7 +73,7 @@ multipolygon_t createPathFootprints( base_footprint.outer() = { point_t{front, left}, point_t{front, right}, point_t{rear, right}, point_t{rear, left}, point_t{front, left}}; - multipolygon_t footprints; + multi_polygon_t footprints; // skip the last footprint as its orientation is usually wrong footprints.reserve(path.points.size() - 1); double arc_length = 0.0; diff --git a/planning/behavior_path_planner/src/utils/drivable_area_expansion/map_utils.cpp b/planning/behavior_path_planner/src/utils/drivable_area_expansion/map_utils.cpp index 39a69fbd74914..ded67c251f7ae 100644 --- a/planning/behavior_path_planner/src/utils/drivable_area_expansion/map_utils.cpp +++ b/planning/behavior_path_planner/src/utils/drivable_area_expansion/map_utils.cpp @@ -26,10 +26,10 @@ namespace drivable_area_expansion { -multilinestring_t extractUncrossableLines( +multi_linestring_t extractUncrossableLines( const lanelet::LaneletMap & lanelet_map, const std::vector & uncrossable_types) { - multilinestring_t lines; + multi_linestring_t lines; linestring_t line; for (const auto & ls : lanelet_map.lineStringLayer) { if (hasTypes(ls, uncrossable_types)) { diff --git a/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp b/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp index 7c4967be14bb8..b02df9753e0b5 100644 --- a/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp @@ -165,13 +165,13 @@ TEST(DrivableAreaExpansionProjection, SubLinestring) for (auto i = 0lu; i < ls.size(); ++i) EXPECT_TRUE(boost::geometry::equals(ls[i], sub[i])); } { - // arc lengths equal to existing point: sublinestring with same points + // arc lengths equal to existing point: sub-linestring with same points const auto sub = sub_linestring(ls, 1.0, 5.0); ASSERT_EQ(ls.size() - 2lu, sub.size()); for (auto i = 0lu; i < sub.size(); ++i) EXPECT_TRUE(boost::geometry::equals(ls[i + 1], sub[i])); } { - // arc lengths inside the original: sublinestring with some interpolated points + // arc lengths inside the original: sub-linestring with some interpolated points const auto sub = sub_linestring(ls, 1.5, 2.5); ASSERT_EQ(sub.size(), 3lu); EXPECT_NEAR(sub[0].x(), 1.5, eps); @@ -259,13 +259,14 @@ TEST(DrivableAreaExpansionProjection, expandDrivableArea) params.max_path_arc_length = 0.0; // means no limit params.extra_arc_length = 1.0; params.expansion_method = "polygon"; - // 4m x 4m ego footprint + // 2m x 4m ego footprint params.ego_front_offset = 1.0; params.ego_rear_offset = -1.0; params.ego_left_offset = 2.0; params.ego_right_offset = -2.0; } - // we expect the expand the drivable area by 1m on each side + // we expect the drivable area to be expanded by 1m on each side + // BUT short paths, due to pruning at the edge of the driving area, there is no expansion drivable_area_expansion::expandDrivableArea( path, params, dynamic_objects, route_handler, path_lanes); // unchanged path points @@ -274,18 +275,21 @@ TEST(DrivableAreaExpansionProjection, expandDrivableArea) EXPECT_NEAR(path.points[i].point.pose.position.x, i, eps); EXPECT_NEAR(path.points[i].point.pose.position.y, 0.0, eps); } + // expanded left bound - ASSERT_EQ(path.left_bound.size(), 2ul); + ASSERT_EQ(path.left_bound.size(), 3ul); EXPECT_NEAR(path.left_bound[0].x, 0.0, eps); - EXPECT_NEAR(path.left_bound[0].y, 2.0, eps); - EXPECT_NEAR(path.left_bound[1].x, 2.0, eps); - EXPECT_NEAR(path.left_bound[1].y, 2.0, eps); + EXPECT_NEAR(path.left_bound[0].y, 1.0, eps); + EXPECT_NEAR(path.left_bound[1].x, 1.0, eps); + EXPECT_NEAR(path.left_bound[1].y, 1.0, eps); + EXPECT_NEAR(path.left_bound[2].x, 2.0, eps); + EXPECT_NEAR(path.left_bound[2].y, 1.0, eps); // expanded right bound ASSERT_EQ(path.right_bound.size(), 3ul); EXPECT_NEAR(path.right_bound[0].x, 0.0, eps); - EXPECT_NEAR(path.right_bound[0].y, -2.0, eps); - EXPECT_NEAR(path.right_bound[1].x, 2.0, eps); - EXPECT_NEAR(path.right_bound[1].y, -2.0, eps); + EXPECT_NEAR(path.right_bound[0].y, -1.0, eps); + EXPECT_NEAR(path.right_bound[1].x, 1.0, eps); + EXPECT_NEAR(path.right_bound[1].y, -1.0, eps); EXPECT_NEAR(path.right_bound[2].x, 2.0, eps); EXPECT_NEAR(path.right_bound[2].y, -1.0, eps); } @@ -294,12 +298,12 @@ TEST(DrivableAreaExpansion, calculateDistanceLimit) { using drivable_area_expansion::calculateDistanceLimit; using drivable_area_expansion::linestring_t; - using drivable_area_expansion::multilinestring_t; + using drivable_area_expansion::multi_linestring_t; using drivable_area_expansion::polygon_t; { const linestring_t base_ls = {{0.0, 0.0}, {10.0, 0.0}}; - const multilinestring_t uncrossable_lines = {}; + const multi_linestring_t uncrossable_lines = {}; const polygon_t expansion_polygon = { {{0.0, -4.0}, {0.0, 4.0}, {10.0, 4.0}, {10.0, -4.0}, {10.0, -4.0}}, {}}; const auto limit_distance = @@ -317,7 +321,7 @@ TEST(DrivableAreaExpansion, calculateDistanceLimit) } { const linestring_t base_ls = {{0.0, 0.0}, {10.0, 0.0}}; - const multilinestring_t uncrossable_lines = { + const multi_linestring_t uncrossable_lines = { {{0.0, 2.0}, {10.0, 2.0}}, {{0.0, 1.5}, {10.0, 1.0}}}; const polygon_t expansion_polygon = { {{0.0, -4.0}, {0.0, 4.0}, {10.0, 4.0}, {10.0, -4.0}, {10.0, -4.0}}, {}}; From c0a6c0f6b5fd54df02d0ea6ed604e3f8088f4e3d Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Thu, 10 Aug 2023 16:28:18 +0900 Subject: [PATCH 07/16] fix(behavior_velocity_crosswalk_module): prevent to access null stop_factor (#4589) Signed-off-by: tomoya.kimura --- .../src/scene_crosswalk.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 391b397dd82cd..64410c08a6f80 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -1051,6 +1051,11 @@ void CrosswalkModule::planStop( return std::nullopt; }(); + if (!stop_factor) { + RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 5000, "stop_factor is null"); + return; + } + // Plan stop insertDecelPointWithDebugInfo(stop_factor->stop_pose.position, 0.0, ego_path); planning_utils::appendStopReason(*stop_factor, stop_reason); From 60d001e591af85420e9e89994e5ecc324ddbb260 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 10 Aug 2023 16:31:49 +0900 Subject: [PATCH 08/16] feat(map_projection_loader): add backward compatibility for local map (#4586) * feat(map_projection_loader): add backward compatibility for local map Signed-off-by: kminoda * style(pre-commit): autofix * feat: add dummy typo Signed-off-by: kminoda * update test Signed-off-by: kminoda * revert unnecessary fix Signed-off-by: kminoda * style(pre-commit): autofix * rename test Signed-off-by: kminoda * fix Signed-off-by: kminoda * style(pre-commit): autofix * fix comment Signed-off-by: kminoda * remove comment Signed-off-by: kminoda --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/load_info_from_lanelet2_map.cpp | 20 +++++- .../test/test_load_info_from_lanelet2_map.cpp | 66 ++++++++++++++++++- 2 files changed, 82 insertions(+), 4 deletions(-) diff --git a/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp b/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp index a93a94f296d45..77958c20a9e75 100644 --- a/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp +++ b/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp @@ -32,8 +32,24 @@ tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::str throw std::runtime_error("Error occurred while loading lanelet2 map"); } + // If the lat & lon values in all the points of lanelet2 map are all zeros, + // it will be interpreted as a local map. + // If any single point exists with non-zero lat or lon values, it will be interpreted as MGRS. + bool is_local = true; + for (const auto & point : map->pointLayer) { + const auto gps_point = projector.reverse(point); + if (gps_point.lat != 0.0 || gps_point.lon != 0.0) { + is_local = false; + break; + } + } + tier4_map_msgs::msg::MapProjectorInfo msg; - msg.type = "MGRS"; - msg.mgrs_grid = projector.getProjectedMGRSGrid(); + if (is_local) { + msg.type = "local"; + } else { + msg.type = "MGRS"; + msg.mgrs_grid = projector.getProjectedMGRSGrid(); + } return msg; } diff --git a/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp b/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp index 52abacf67f344..206053fd2e8d2 100644 --- a/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp +++ b/map/map_projection_loader/test/test_load_info_from_lanelet2_map.cpp @@ -21,7 +21,7 @@ #include -void save_dummy_lanelet2_map(const std::string & mgrs_coord, const std::string & output_path) +void save_dummy_mgrs_lanelet2_map(const std::string & mgrs_coord, const std::string & output_path) { int zone = std::stoi(mgrs_coord.substr(0, 2)); bool is_north = false; @@ -47,13 +47,49 @@ void save_dummy_lanelet2_map(const std::string & mgrs_coord, const std::string & file.close(); } +void save_dummy_local_lanelet2_map(const std::string & output_path) +{ + std::ofstream file(output_path); + if (!file) { + std::cerr << "Unable to open file.\n"; + return; + } + + file << "\n"; + file << "\n"; + file << " \n"; + file << " \n"; + file << " \n"; + file << ""; + + file.close(); +} + +void save_dummy_mgrs_lanelet2_map_with_one_zero_point(const std::string & output_path) +{ + std::ofstream file(output_path); + if (!file) { + std::cerr << "Unable to open file.\n"; + return; + } + + file << "\n"; + file << "\n"; + file << " \n"; + file << " \n"; + file << " \n"; + file << ""; + + file.close(); +} + TEST(TestLoadFromLanelet2Map, LoadMGRSGrid) { // Save dummy lanelet2 map const std::string mgrs_grid = "54SUE"; const std::string mgrs_coord = mgrs_grid + "1000010000"; const std::string output_path = "/tmp/test_load_info_from_lanelet2_map.osm"; - save_dummy_lanelet2_map(mgrs_coord, output_path); + save_dummy_mgrs_lanelet2_map(mgrs_coord, output_path); // Test the function const auto projector_info = load_info_from_lanelet2_map(output_path); @@ -63,6 +99,32 @@ TEST(TestLoadFromLanelet2Map, LoadMGRSGrid) EXPECT_EQ(projector_info.mgrs_grid, mgrs_grid); } +TEST(TestLoadFromLanelet2Map, LoadLocalGrid) +{ + // Save dummy lanelet2 map + const std::string output_path = "/tmp/test_load_info_from_lanelet2_map.osm"; + save_dummy_local_lanelet2_map(output_path); + + // Test the function + const auto projector_info = load_info_from_lanelet2_map(output_path); + + // Check the result + EXPECT_EQ(projector_info.type, "local"); +} + +TEST(TestLoadFromLanelet2Map, LoadNoLocalGrid) +{ + // Save dummy lanelet2 map + const std::string output_path = "/tmp/test_load_info_from_lanelet2_map.osm"; + save_dummy_mgrs_lanelet2_map_with_one_zero_point(output_path); + + // Test the function + const auto projector_info = load_info_from_lanelet2_map(output_path); + + // Check the result + EXPECT_EQ(projector_info.type, "MGRS"); +} + int main(int argc, char ** argv) { ::testing::InitGoogleMock(&argc, argv); From 2b7afb176b958fa7041a43898c008204c431592d Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Thu, 10 Aug 2023 19:14:35 +0900 Subject: [PATCH 09/16] refactor(initial_pose_button_panel): delete intial_pose_button_panel (#4519) Signed-off-by: yamato-ando Co-authored-by: yamato-ando --- .../initial_pose_button_panel/CMakeLists.txt | 24 ---- .../initial_pose_button_panel/README.md | 18 --- .../media/initialize_button.png | Bin 164979 -> 0 bytes .../initial_pose_button_panel/package.xml | 30 ----- .../plugins/plugin_description.xml | 9 -- .../src/initial_pose_button_panel.cpp | 123 ------------------ .../src/initial_pose_button_panel.hpp | 65 --------- 7 files changed, 269 deletions(-) delete mode 100644 localization/initial_pose_button_panel/CMakeLists.txt delete mode 100644 localization/initial_pose_button_panel/README.md delete mode 100644 localization/initial_pose_button_panel/media/initialize_button.png delete mode 100644 localization/initial_pose_button_panel/package.xml delete mode 100644 localization/initial_pose_button_panel/plugins/plugin_description.xml delete mode 100644 localization/initial_pose_button_panel/src/initial_pose_button_panel.cpp delete mode 100644 localization/initial_pose_button_panel/src/initial_pose_button_panel.hpp diff --git a/localization/initial_pose_button_panel/CMakeLists.txt b/localization/initial_pose_button_panel/CMakeLists.txt deleted file mode 100644 index 6c1c13e000a51..0000000000000 --- a/localization/initial_pose_button_panel/CMakeLists.txt +++ /dev/null @@ -1,24 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(initial_pose_button_panel) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Qt5 REQUIRED Core Widgets) -set(QT_LIBRARIES Qt5::Widgets) - -add_definitions(-DQT_NO_KEYWORDS -g) -set(CMAKE_AUTOMOC ON) - -ament_auto_add_library(initial_pose_button_panel SHARED - src/initial_pose_button_panel.cpp) -target_link_libraries(initial_pose_button_panel - ${QT_LIBRARIES}) - -# Export the plugin to be imported by rviz2 -pluginlib_export_plugin_description_file(rviz_common plugins/plugin_description.xml) - -ament_auto_package( - INSTALL_TO_SHARE - plugins -) diff --git a/localization/initial_pose_button_panel/README.md b/localization/initial_pose_button_panel/README.md deleted file mode 100644 index cdb4824ada0e2..0000000000000 --- a/localization/initial_pose_button_panel/README.md +++ /dev/null @@ -1,18 +0,0 @@ -# initial_pose_button_panel - -## Role - -`initial_pose_button_panel` is the package to send a request to the localization module to calculate the current ego pose. - -It starts calculating the current ego pose by pushing the button on Rviz, implemented as an Rviz plugin. -You can see the button on the right bottom of Rviz. - -![initialize_button](./media/initialize_button.png) - -## Input / Output - -### Input topics - -| Name | Type | Description | -| ---------------------------------------------- | --------------------------------------------- | -------------------------------------------------------------- | -| `/sensing/gnss/pose_with_covariance` (default) | geometry_msgs::msg::PoseWithCovarianceStamped | initial pose with covariance to calculate the current ego pose | diff --git a/localization/initial_pose_button_panel/media/initialize_button.png b/localization/initial_pose_button_panel/media/initialize_button.png deleted file mode 100644 index f7bfe8aa652ac736f730b493eccbc58e8944d438..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 164979 zcmY(q1yEeU5-yws3+`?qIEydt5@Z*5cXxLS4#C|axVw9BcXxMphoAfYdiCx-HC0=6 zc6Uz8O!qh4-wBnK7DI%?gZuL33nEDTm;9G6kOyDBd@KGA{dwnMQ#|SO1JXeVr1<^w z^89WX^5x5qFQ8w7imvIWYfi~ZB0K-CF3KZX*VejfS{>Pcg5mVP#KPgI>PG+kA)e&- zvzTgFf=X+e7IC@?c4e*I#U^8e*hNj?QUr46jWg?@*&~aW)8ssz(_w#fGzJt)M)KY7 z$NwAMI?~j~`;dYt|8HzvWYbbpKehJ!*Uvux@&UdM))tKU^wzRA>a0~0u6kAD}cX#7?xqqXovc6mT z1kZt<<=;&b&~*_}s1ZQgU*g$N{_aOdxou~0{mo$G$p3^;Ofl9mwYfG4MTNG|`(sG* z82uXN`Rbi!m7Lo1<>@CA52d&av;~e8<4S()BlL5#eau`>gp_jo9Vx6I9DPq(Nigjcw%#U3 zBIfJO77pg{+=re+``z0DrLY9B8412X&NkfP_H5-pkE{>x6+7GgV`M@h<%ylu#@oiX zLs`-ayb%WJiBj{tfY{$_}^6gq{|_kmDy?B5ZDm^g!k!Bsqy_%lr`jqnh&U)J`+ znWl>q?i#nH(6sW7{0FYG4}q_uQ=9{LV)chQTk1E$Yd@jykooQGQh4k_xKCW%4Uzdx zZRtf;Y0WVQV~-LVlb9HKd)M&p1`Eq)3$XC|=hG7$hwQ#8FN^$&d+7x^0d1?AyT27x zBT+s6rWWPO^am%JhbB&cPLc9|>M;{_nkY zS$T=SrcP%zyN9cd;8dKVn|B$xBtPZ>!i0k&%HZ2P86sqi`w9oI>0{DI@S8c0ctja# zpr;Gd!~=f!-@J^;b=LKG*=rjj$YOnOv2xv)CQd`QA~rf44Gtiq?cu^S5!Cuk*Vrr! zoT-K1%_hvhr5d(Fo5`NxtnpIiac7&J&{_FsyiptG`QGDOJ_3TBnSdNybgL!r%P4>XR$FKpa zS*jR-)ufU3jv<&D4b5zTt>$77Rhc0(u-eGwSR>>Q=l{s6{pV_DK&IUz_LrL;(Y@Z- zWg}Z@!A=|6=G?n_NEn{h(E?vzr{BFrr5^u&|PnW~Nwm}%V6 z8Z+QHvZeHQh+w+JBXQ55^VK!pg&Y5Xcp%$yhb{XuXj{aK#A(=TZ4yzY|)Eb?S*b6JHlpK{r3Ej;k`GUFwl|} z>~uIuA{s^Hwc$1pMLaM+f8VH*czgP8_(fulxXQ~iOw1ct_CHJaV}-X}cBR2eLRNNC zYo@!WhxjGZ-mN37 zrl$7f68zsz6GVAWFvN=xtxHG$e|bs}C7{#S)x`I|<@xa{6(8&P5##{v?<VKk1=PIv_Mf=`zy#)sc$L7}7l}gZo3?&GyxVSjS zUi!Zhqu}GpoAF5V=PK6J()!S;Pi@UFDfzR(W&IyfA9W1l$sC_ODwmj35Pl#>cgGN-C+YisYWUzJaJ-jnU%!~>&??EVUt+?T6?mg{p(V7&(dl0tIh7D13szMBM)9I$@jSK2OqkPfb| zXSHv3od$gG=GUp0o|ryM5+9~-zj(bW%~9ohHp9pfndk5B3M(dPj`iM1bYKTcaM;oL zQ{un8A(Fgo$dv;bZFU%X^Dx(3-VgJGAFVZArr@p^VzpGe3W{9eMpzy)I`tQf_&lp| znNv;~kW&6*idP$1$#f1ob0Z`2{r!DKMMYg}>qs&X871Y;_O|>Br1w&dk)fd>3MQsV z7#7|8zAk@iY%E$^TiZEzWlKxySQ>j=OpKs_z;CKwuR+ub1%DS#mg+6Am6Vh$H#*wy zH7XZsolca)MM+;CE(-N}f_z+TiHE!VVL;;I{{{wN62NyZFk+9yG4vx{KX9uA>JT1* zW>a=riNDi!Z(U&ah=pTy*ZUm^+LG_nM)D34W`2%BFqoWlG8%Tj;gE-30it4*RP8pN zVj*##jCdC4f5i)W`;&EHYcN!uNKV_($7QNWYw3vj@t%EjN564{Vtae%2AX5zKmPyO zTAfhL9poy|K0Oui5(81BNJ9oHdF#khD3oUMe6)=u=6?@%p}>vciHun%13fGBhtC{2 z67aZ2(`&V$prHKw40lsUj!|CxAH*!ClfN@%5*hccOj;bNI!{^^EM{&a#|)@wXD1@A#0+p?M1vcDyHof05;z6~3Enu2%VMXrknS%Q*!G6>9tV6@~eul;j$LY-* zS1S>G={~W7`~`yd)Qr&XW$R>Was z=AqX9;BKJP?myd)fgFYrFJjQJ=HvM~SYw2zsHTMR3mBQsjqtRfgH&>!$%7XXr zU%pXg_1Ws#H=Xe%)=%4A#q`A5+5>aN5cC!YnJinCU!$lT-xBLB7W^a;|DZ&-z8$aR z@2`BduuuR*T%Vd^g%b}&tE}s8RWy0P7cCp^ciuoPA(z1eZ4X<5>lov42!C6o zi&$It3()6>27J({a5&K`8U%D_cl?C+kM`5Z0PE466&IMBX$c57r`dti*6RTqiio~y zNgTGpc(#{2gT8Zs%UIHIWv%Wg*dFnRQc{h_2?-q0aR$G;_oFuc!?XSg^)TvlP$ zQ!o#}C$4Lbw-^AGYJ7aX`1&M<;Pr&q@$^Ik4I5dRHS+tNf$6opx@;X?YEEl_QZC&! zcFAB}_j06?$>WX>?1;=ageGHUG8VY9kUrdNfPg=l_0?ZnZ!{c}3|pCh-QQb0EoVE0 zuZ)-f;xWeVEfw|r0O8-`*K$>02c>jFVsa@4&kR>`me2cBg%iNO5@>QN9@P29bTBOu zLj!!$e@$y+(M7R|e2RZd0-m>Ix7As2GTdEEOfHC4yLw^tJ(P2}rjvmgK6(KV&p_Qv zTfQfI(&oL7asv6jiXnf_#OvQM7X3VIV;La(qjpMx?i4Sw#COh4GkIlLZfVNt+!$aM zL-NRqSLzp(t%L4iWwW_zJcf)`w1~SoET~Tc|!(s zvvRjSWK0-rnkWDTxU6wqVeI-iQjW_E3HVD^;M@_M8-uJR; z4j7L)I$e+#E)@DFwcn88=XII@>8YcDw!2{gZ9IZxU{myeh>Woa3PZ`8ZjAfgp&3% zn|fqRR0uCY6e?3t&s9y?{_NI_gD{eUF;*6aH{bh7sE1e5Pi?BnPf$3c9w@h#aMMZ3rwXFKzD!-mY6?#IQ; zSNEx`7NY9vc;Nh4Sagaij|Xe_hx4(y(gMK-asy0kXB#~&N75EnHwYsqysU_~_+EMk zw|omPxEY)1XyxA#CX7xzw4og-GOAiWib`s|1-P*H%Bc8hzw*0%FGEl)6`2Ku;+kSW zVMy2g@n)|0%!9Qog)BhdlTglN?ne~01$-%IwCbUyLrmo+F7@avjgWFN6sK3MsU&O^ z?4;lGtAXxYg5rD4no;ec^P`~!cV6O6jwwIOaY;~7o0ipiy?rdy_P8L8M#-!Qjr(>lRVGi6WQ&2?ATDxz0*TWp)xJ(P$w;+5)t{;4~r|y z6AW?gxdsH;?W}rRtFz^m=z0D0Ta)7n(&q2$>+2mDFtD+i@P&Z+4i8Vt&!4qFmgcbC z3%lH4<>8@cfQ0EBq4qpv8%O^q)fn$_uNk6l%KOa_jWyfY_}uM@0oBRTID4fUrQkik1S zGCSsATyqotZebp#7l?zgjQxo;X%L9j*w}tH5zf(_R0$6Pt{I^||6493IMC16U#Dkm zE;HHS<&mpA++<~PA2m@d9in&0Nh6lx>AUMcov2vu0kfHqlo9VSJ(2MLqJieXGK*-N&vC_UgtXO!3v6~LjWcfsMBuqb<6=v6h=Oztc{S;X zKU{?^;2SQp2Y%AT&()O`^|0);QenU;5a~_Y0ykol1|km@%NA6d%ISc|qH)x$Mpp+A zO*LMeZ!lxKtxm+~e-r(ylNDCzFQ+r9@D9hXy2_qrby~krlPC6`%4>e>{_fnE&9OsK zP3>01dm_8B5i?!(Yg^%_+7_N-bptmLflTV_KqMg9<<&t5Q@5f)P$hG0&LY%wm+jZ{ zo}J~yS5J?C8LBoC!c6Nx2(B8mZSiqBQRAb4Tq9PuKqXg5kL*%dQFdrhUeZqo^=qeHj20(|u)xy2F5QqajmG zZf39a-T{UEE6bNkQ26-Ym$C^rp`_l%ncyq4eI7nSV=f<7k*jdR){sG!eqebd)Dd;U z;GS$|lH_d!!YF}f5&mg}V#>ta$ra8hVQ2^fs}k+1o!9K{`ew+xnY8y@MsL;u&|=TJ z!}Ed~twN_z+(cS@jgeq1f~-#@PRpFENYG0&o(oMshk8l_4NnalCTw8gd17n|58ey) zqU{C=3JNOx^bJABk~1oUBpIrg6j05#ld6$5Hkbrf8^o_t|`1-VALJ;dWJ z^Fb1(Qj~fXj(5Zrl1AoSGWO8JN5@fu_F|oZsOxmH?bsSds#!?U`GK|Ltr-t%JMy^T z27{6QgwbRse+U`J95X^>_eP{obcg9^xsft=Z!YRsI&dhLd$>?Z+|kkTMZ5)!c5UV6 zcIt}c$rBQ|qRyCW&C&>`Qq_Iczb_pZ*)~{w5d94Q#LVVUQomShf`s1@#o{ zW{z-$+qa1$RLiJB#Fo^+qOw&~wwtn`WAdqFxV!a_8@BW=6|Js4coVk@EkYJ`-lZ!O zwMJ_~UXS}St;Q0Lz?L=bgP~yq&pJoI8K2jmxWW=wr?n)=ymZ5^RTn1Dn$*l}q%VdU zS~6M4_squUkfK~lvOm;h^;u#G9DH~7IRiw0ZCjS-Pyu5CW<4$2g}>j}2~A_5;uFeL zOGg9;LW&=j{%OLC6ShsJJhH3CP&}07ewJmQ#fK04rT(fUf5ZA15U_JnMp2_BHd=iNT8bbYc)#DHMT&@^m%Nntj2N9Tc*(wwCBz-J`2xu?nQ z42~0%`CCu7U87uVqHRW<5M758>1B;vG>%8cD;P>}%gL_V`%w?~Q+Zx>=r{t8(9aCI zdA=n$k=UiEbkgK}Pvz~~HGAifqZ7Rp!<-rAHg44FCeTr48zedjU@k6|_DO zGc1BJW(}2KHeb5!A=0ntwR;z};R;q?U#CEebv#)Y$l)@AK`*fU`;k`+iCb|qbTT1Z zV+aF5HYgLe^Js^8{+TxH8_7Sd6VIkwMDvrLB2zv$fjWvkNiH5$MiczC;oQ16E8^!2 z6P(fxBVN-{XrzRw^#Ld@M1ZJ)B{5w~)b42w83j&)Ra0_MxHuXW_woSg#g?x4OZ(P4 zX6*g^{$uOPYw-*AXW8WgjPzHQ%KHZD`zOB1DJu()jz;-%yihq&qEyOZyZOc8V0`bN zFT`jHFgS|u`LN<{y7F}M#Xo5%oV%}SiCML z2cv@wG!*%sxG1lPh)7=M#y=JQi~^bu3J2`6pKO4r)1L|pKXa!-rl@$YXH-G4s;$m+ za&mG3K|wWMFU~Xoz|i=(@kk;ai`jI*-bhld%Z2s~T)(_Lvz9Hjw602I%xqB>hr$7( zreT7qg#6=UT%V>)`;dtNpRR@@SJ=SBfqBBOttpYw=Ly&j;uq)*!ic@yX&1EyKtX|s zUu5nL<&^2>i(~jDX_L2wI#jZpT)d3798oDnl#zlEYhh=~@U?;3FB^@2_&Z5)u|#7g zS&}4`ngjPnGmGBT30a*f12ypEt0C$G0b|s=n2EY9$5d2q~hLm@KXf(6tAxS~Crh)D}EM)U8Ni5QF#Ix|jVII6BRsH%>c6 z^|tj2#x*3s%Jj{9c+q5^r@{V#N&dfWZRx_nNOre}a_Jcvp@05#cXxlQSC2?Yz)WJ$ zq4>l;pPL&6(~0{$em{|ei);H(H&`*X`}PRFDKT+aC9eOn!um z*|0U=vpprI8k3}Eo$qNl4j)-h7S*n4F9DEw$jEhGfAGVObK zS&lv!z+!qmO+DJ$HO-yn~v);vFZr%+9q9sPQUetJs;@_J#820wZ3TW(*&sd9O-nUwx5$@|@w z!!tkr8WK?*=*jNI=Aj@lGz7?|-NBpbg2!bakvrhe&lSLn!q%at`R+{p- zhMR-zBeN0pAb&^6a++fE8uX_~^XKrZs)=ey?)H7MD04ommX2$psGxS!(vqHqNeO}q z)mXKiZQ;$|DTM0f@kn5E;|)U!fdsw=0RcfYew|{x=4KpcDM&iZWH~uSb8txSew3kE zPE%T2j=ZJ&*ZPMo(Sc1r^GQS_XRMn^oFUMXkigE-v3FQ#e2JWN(UUE(W|g+&t^gm| zf9iKNa}-pqN?b8udnJm`XkyIrp4KxBR_BZqs7DMmrY%$i$i-#}tBsQzkEt7)Gg0C) z;UI|jmw1fN4V;OcX|o+a{GBM>-FwZvm2+yg=vd9B{yg7?%lsv#XEWbr#{DtSJq$My zy&tagj@W$QJl}8&XllW|nfG^X^)Pt#?>1X0rk)RC;rqCRknSg|-5W8p3>z2JP?FZR zqZV7B(;cc#e+iN*sQEWPP6Xp&Q8zc&Ym+jpvND0@V+@bpxd>8T72L1j1*^H?8maRp zIeQObzvwqL`5+o}w7%NXnG)$YzrPtcZA3e{)()@IPLDN9q+evzBw!}z7%?`8;=C*Qr*b9V!JMyK(x zH@*jXzj7|0h=Bk@`?YiYdICS62h?bJGzFG3pCq+CB5&bOa9Q24n2w6el7Sh?eqf}J zs$_ICH-dLPBpU`kq3gLf1TQ;^LZq^-GuCPxr_fQ49rRd$bygc3P~!BIpsJQhEO*LY z_m0w%%fVkEE$MPEl(wew)M#-Qk&KKSC8HdsgpcZvTwW<9H5Jug zsWi4mgZ0r&ZH7ChJvz3A#v7~zC^n>XNBnmZ|EEMk6MLHrS&D(_Wu%Yij1*?ZWRb9Y zG!I=)pmPC9w!wj)-0I*$l}+D(rsSyM2m4HN$2kYP_fp>ou~i-!e=4dCJvj+5NCxIk ze=UY1_F-bHl#Y_~>WR_2LtOy0%%^O_sa4x!9%;EcI{2`WXGG|8%yRaNSB5;lIc3*m zfbnK7hCmu%GLYx{`Y3^=2IX_AervwK$mi*Ufr*JZn#qd~(4rsVKkSc6V`DTNM1giH z>DleFTB_26kVvF$w$S4KpgdY;LvtavNhdrPznOQ2WI66HT5!MI>kq3pd++rH-l|uD zHNLd}UoOD!1NFH+?mBA3V^?3pJVu7#S@@Hb#(T!OK9DDu0qhmE-6#Qj@JRyZX(oRp zlmzb*LLASW05EfwAx76B51% zA(`?)nD2(I+N2LK+B1q*R*rMm#|-o45m{ZLlhm|(MBbB#WW%b1ci5d%(Ge+}Ve(pL z335W(zB}KdRj-TAm*6wF4?&uJh_<^wRSQDIzb~arzQ!=QXsLGtD;tr(7ffus>O+?n zh94BBHEMKYWoY*`x$(#1wWb{@U@H`qx>Z@Q=+lN8tWG{~5aACT%Q4ivxP#8z-KCHY zBJ@1j8i2tvZ;dAjz6yYYop}@5wbUTlMkAZVvEzTCRxn=%B|&7sJG_|!+MgpuCM!7; zoU*cGTS~x`&K)jnb_U()<66Z70;BCBnNZLO8K4jc7S=#&$?2p-Bz=q~zv=Lu0q7R( zhEIWZq9@`K8)#rnGJ7pD>|Bx&``(Fcdr7B0W z#ps_8{%bH0S!XsA1dmP6Xgc}B&);8)Jx`uf?Pv(3L#S-mT9A!_l+cS?lNGP@hBthLb zHB`)|iT2mov8QJ##Wo3Td>|ovP7!@FhqAJ53Z2~_pr!2^IREYrrm?o))?~i(UKB0VNcGSD|ixWIKrH3;r;wIGhVWU5cEeO|L$bKVr=IdJxu6NbK7 zsxYO`;*WGmQ-+*{?P0j$uEf7ZC=I=#I<8=ZE}&J?t?;m&8vdRA6amX?-h z?o9lZIbu;nJRj?5aMKUD2q#^a9d9^uYmqh`8x#9ucDK0vnbnIzPt`88x-GY@RCxr{A(Tib6mS$hx;*e#_7#`Fj=? z?zsbktI#@_F4$9S3f|e)Cce2=WR5`Nst2^YJLd}ig{Lv`(OmO0+bty}Eqsib`6BQ@ zxn`z0K~$fQro+HWsL?vv7DMXXK$A{5b|DTiw~M(nnePGcetrG|Ba?2j`{Gp{r=mx- z3=+yF{3;#!s9{*UhfRldPw&dXjlN&9CFDtNE)kmJXYS|UCOex~tl=*L`dv|jPzjxJ zxR#4MMaeK-CQK;w)1O-F0pe&`Oy;7IZ)){#_7c3}vYBZz>gek>vaKA)nu!{3bufFC z#!_5NhUPgBu0VGGh5|@VPEE>!HX1=q5^psFTXei|W~5Tj>lObs^LRqSOJ`f;!*HI6 zPK2(splUf?SBKJGfj;I4M=(I=2c4Dyr#D~eJ$p<^6 z$NS!4t@&rHGhx=c&EmIXabq>06F} zZca{#EH*{c9X2VzFMZA>RD5-nFM(Td!k)a&#`}~D`|Io}l-T>xx3~9~vQP7G5c$@(yl=5P;Ax(Qws6G26BKFz!~so9 zZHs0iv2}<=yjZCh7J9W> z|0!*(LvjpT?7Z(s9ywmT({6}*Txt^|M-oI(tWKo;{^H|I7((&9?UqRZ^zC|kxls(^ zlvm=(VgUUt(#H8(u5N#Gtb~DOPBUCmbqCioFYhaVCNRTxR(xO~r4-0H*7}g6kOyED z^Utp*9lwu!Y$|Gs*N$jV7c@*Vadmri5N~~mwQ_yj0MjSQX=!P3Yj#&?wW_v01NJ9U zMa|5pKjYf&a40YB+ciAj%W3U$lH(hf&C`?FeBfMNcCpRvs%qK@jsNwpVY5dG;4KfJC#ef6nQ`86-{!bj_!#>9 z7#lH~EpUqv?diQT;HYyT1*lYzadM_GV2v7fHzC8q!gftfU1i<@YUryyr`(@ACUH|7 z0a%hZWoPL_6XTUqH~B_f-@In)%T35Z-zzV01#y+c{d;umMb%T;IdC->Od2IZ}<(zW3Q*mkEx zQQ5Zce|OW7y%OE%YPZSliqUJ|XBsJ|5Y#n{i3}q#Zv7EDiQ@C>=^x7Nl-SK5&F~cm z@p+ku?Nd`)HICpri^QuDhR&+b6E)I><|jhTVzydlDJw6(Q2SVL1FH+tRvRg^+}joU znlN!Akl$WOw&HkrShCk&)UhccA62MG#|eOl786goGASLyaYqtCUjFK4cF-x_`2) zI5Gy94KF$|rzxKag_vT2_dDKRYu;e4Q#-n%J0@m|MHs=O-!0~S8&J7$>`qoRt6{)L4k?RIxPV`I@u?e@=a#g#C3%?ZAr z-tuH5IZ>2cnTm3yR2R13ktT|ZDtw(_5zQjkg6132xJj~AG#^ljD1Vw7g@fVNI3?6J zw#1jgDA4$#UI)9sa)@JUa9m?lM5}vW7-l-_LuC$6UJs!nftIZHms!z(Wtfp&At#9} zo(BH()Y8sV{|A8Zt(eQJj*V}oG15dt-U8amR+Qw$i^0@2+UaDT>9J3RSXPj7u0vKZ z+j(oLk#DcKBKYuq`(RMprGI`3OM}~@|FsF17@4;KL-!Yjf`N%mSdtVrpXrg*(}bAM z99a5ZRekL1Cj)4*ObuvnZ$CIPLdwmJpD!P(T-rB0{3kpdVLXdp=HYxTG`x*>(mkV4 z+xWaJ=0}_Y!N-_ZCpU9+xcnH40KJ%+l3>1Ex8yf6TtTk`CZ>Drj?~GdWIGMq*=bA< zV&YSVN|I{BFEP#q-Z;(Joq9)KSsCi>n4LCQ&!AyB6OG;L)Jd5EtYCklTu5cM`%l=- z{Mug4;b5W0h?Q}0=I!97x9(a-8}E`K<1@Qw!Kvx_@6nVwC0!-R>DROcRas4*!Or~c zdj&E;rcwXoJ7C)o4Vr9}uDrUwKL2Des_J33#&!Oi& zckjr*xT36E6`fGLk>-eO=EEKn>AqocsX>2iLT0NxelwdpV$}j$%yq>R>zHiOs1qS7 zvqH7_e4$<==dk-hQYWeJ7K(WD2MlikqxkRYpMhtT;dMmYb{-|G8PuhXSMgb#aLwUu zgay7kF_K5(70!C6qh^}C4H=Dm96fa|->U1Xd&cK8BMmxwh6eiLS;$~hjPUtZZprn) zvQ$cge#)D+Z!BROJ~0(L`~nn5OtXpw$@Gx*jrqwM>bkSa2E7RRXt%f;DSQubq@tZ6 zDbw*3Qa?dGD&Hk2;YNazB-iX`39gn4S0uF%u zH9iwEGE4QS{Q;Y2gIxKaao3!*tp={&$uxzym>+V#AXVse-^Qz4DwR|<$?GxE(lU)eA*tG@fWAM~ zJA+reJMU(c>O=a>JhsxNwQ_bjo-V9`C7d{w_$3fQs~*c>EP|HxsDwf(JKll`hddsP ziOG6|H+1V$UjPS7ZVpe#T#4klXo)3}7(aQs=e9U(-arC^bj= z&rUC|kGhjGyaqW@0+n3=gp|hi-p}`o^6jlo?_x8+cgMs;R2}w!A z#VS3?EIvY;3!N+lv_KPOW-l!g2R?iUv2}eeV}m6`HbRB#S$raw5A|5cSl=1S%FU%? z#Prby`4}xb?uoK77%~ida`p1BpzPjmT>;8DZO1CbwA_Uw0b^KZQs*(9+|vW{Q}Kwx zx%3}19foYPuyv$dz^DSg0xaI;Q;Tqd7ewI={E%fy>ylePu@)pXb@dv||Xw8-mEpf2V4SfxJP z)@<^_0FSsCo9@B(FH_OqaM48nO%FqBXsBqXv%p|`a8gFNw0#ly7AT?cn&%o>m^j(< z>fDwi`y=l5cUeOjC8)rnr`(lUD(>Gj9K1gkh(fHS`Fw#w4J5R*sl@imh~SX`m!c@? zXw^YB5E78!z{{8N$|mOX?02NnG6}9=tgpMd*$X=&e9Fy0B_t$NtJa5_;CrF{w0XWn z()@U7Ma6#m!+Ng8LIsQY>|v(UMN;7-HQDIg{NmE`l;>fgqy5ePvHr|-ELqR;II4yQ zKvXi>KW)s6%mAuC^-xi5#lXZOOktys<@PfXE7I%_ECCiX>Z2qy6np#jYtE0kA6HYB z=DbTyr%RALyq^M(3q5q{7tmX+D2?AQzAczwjcaOpMZX*m6tB3>m$9i4uiNO(<_e=`31v(|zU z#bG#f!IUGx7_>nZtl@Ima^d(NN<>$@uKRJ3e6e|_k5subP`~&4tobKlvA8Kmk>=vr z`v*`1FCekT>F&Xh#m5ip4r0;yk#@|}($40c)DlT8#JnRtT+GH)F5&kki5)T=G%UC?Ffa&>j4b%fl81NhpIjBuo&Jd8 zPi~&oh(K;Z>`zO^{}8=W;>;>cBjk}6Tz^A*OS?(Q4((Es3lvdhA5DN}jHsUVQYEZLqL z!Mafps}BNko@J(o`{!a`w6mweb1U0YXath5Lyz<$9?eciMPXZRDH`!AHlRWVbE0jh zfgJy!S4P;H9CUoPAY*U^u)zO zuo({Ez=6r*GAL@>Fn|eg^|>%4P$Mbrl9BsC&<_l<>e_kcrjT*Ns7C0XWzx};ey~}^Cas3m7OEj1}VCv96ji)Nw0YLBn; zvwd5&(UWy7wZZk$7eFg}DAAk}EuJs|6B8Z#Y~BYcRZ+^{qXhK$@xOE&}o4(TA}MIYhJ;Sc5`t(*Ac(7jxCe$n>)Jp z(^nfGc}WEux+8mTT2hb8fId}aPa{##savK;E{w65(rzI+2?KRkw}@}KKg1Bf6=~~% z?JAw5M%++Bks{cTSzx~xDC|*nd&1CcsSzMjd*6il%Ylj}NI#bxF2!%2aJgptACr1; z)8>30H#P7vEGzzWpCvowvD zA3s##v|-Qu0d2A!FZr@s%7%o=%==l%*-0BA*No&6S`nP7Qd*H4u=PKZ=oE2dMJ^S9 zS~a14_CR{Nhm}Q-N_6x*Alye>8^1=nccEiYpkh*3|6}9ARae@RU9>ZMV@IB2ff6&e zQf)d+mgsEpuU^w3vjNFy)|7w#g7?eT`K;NwXjk7FL36f}4jcV&B zIFtLcfB6(PL#=K>cN-uw9UdrutSR8Oaws?wEZ6luw&5U^)Lo6gKB}{b@o}n&vB9tf z7;x^zQlEZizaG?)X;)HiVHGnw5`}l7xWRnGId?0~uZv}4=~$%%yiPw zEiR&4==F*+KqRI0qSy=_0?9yr7eiszi6rT;@n zP2^~P;wwL_chPdur0N<6T%bvAVl29UT)B14Bwl}y4n4|%wTs@unMWE}7H9HWa^sJ% zS`y0fuI^v%Pda#JF_I0V!SZU0rtH>&MQ{|h#vkNnU^jehYKHW=hU{;fDbs3?EkWl; zw&pZ;9)OF*yYI&h3`%HnEF=im!{ic3E1#f_!VpdBR^10krhwPq)=== zj?VoY;S)DxfhC9W9qRnpbB_)vWHD)+W{M|i4(G~V=B--d+Jb+QmLBDFg_aHt7~dC_M& z2{ghb@ai4QKxBAUQky>c%sino4lQ79)&nfpda~Xj$t*hgZIVmmc*uv+C^zzWeDdqn zv-`W%cHi+uqOR#$qU{OBG&nq2E%hTCo3@#I-McL}exynPKrL7L{l4Y}Lc_!LE78X* z`waYNEt?@WAu$o`-cFPN4wNnw&S!SQ=W@TLLPbS&JY9_W%!XTATXteyr`Caifpu0Z ziGz;fGc&c;@H~bCQBPEFC$FYCe=zf*_y~RPz)WDx ztK_tUge?L zQE&o%R^6!(Su-wuhoEYFzJk$CSg8oEnVFL7Q>#L1T2Ou*Hk=i1vDuL#?&u{FQg<73 zl&0ooZIZ!kQe0{>IAuPhzLx##`NR5O-m>{}jho|3J~9f5t&;;8XJv|WqD%}d3|%XO zu|W8w#oHb4Pln*g`C2R0hy*2RBc%T-feJCd=B)iSP=1iQSjg-IR29XWuoN1f*1BU% z7n7PU-K-s1SjmrM4h5xVwu_;pe}ekE)Qx)qJ+IIm+!h>gkb8<}a|_aQZc`qUcR;Al5AD;UDwKWKCo0}g=D^ayRh zfEk;f86{oN``KqZIi`(u07PpnqHkUVij0l@F)aE?N*<8|M~Brw|LC?9lac-lltatp4~!OT@k9Fh8}s#^tNW5de2S2=AZH@dIiwqRTtZ4);kVYvE>&EAF&BZg}?&;%dL5-8rBQ7I4x=QSa9>Z6tKBb4(3#)p;;Rv+G8AVPW}5u$g$G-pPMZSJPOIBZ-v z*xQc}Ir)g<%5e%K)1g3^;*B}&&9ZTZg29xWG$F^=^6Keua-m0g{ehd7CHXZKP;)pS zV`scB=*d^4KMx6;T#n9sENm&RT0qP(ZOLpV!ve}JE1JT#E|8)=S4nP$VDVL5`~pgP zqG(fTB%B8oE@*33MFll3`Im$f^*kGU!6Z(QQNFHCSwUMvN^-m;TIXFWp2N4eP-3&B z_b&&F?@^7ef2j4)I~+X5R)nTHhW$%#kLV1MCPdB3{?@Dqts9as)2HM$Rgr3wvb05F zm6ROYKL6n0Nv)gxh2g=wHy4rIy)z^pDrU#3psXDxGlQPO6R?ZIke{!NRvV0BJe$pt zN^L&NL`&L|>k?7YR7^vcyJqu~l{7>5G(JIjXGTMOgg`QRT};W1ldTc#sLnFw>^c(FyKf!JphLG^naLrQx5$FYQjsly9XsxWSRyrg7P{*Fsg zd-b21RAa~fAKkg=;?g1gc?-4;s??>{0zgRAtVF4RM(9#BG57S$mSJ~&1$jI6h3sGb zxfb>Mf26v1&9mFqB%Sq9>R-UH(h>vJC#;!j_~XPEZ8bZ|d>V9nXW0m#(8H$jiv~G0 zxxgNiA8vyv`lFMY3W8c;=;2t?wLvHaF7n#yzGLvAW+?$r$JE93dR4y|U2SO=PpHbR zNyz9^eu!~rADR8aaazPHnG&JMsnsYhG86hV!02%Iq;Vf{#;^1)5i>dTp`IDWtj(~n z0<+Wg_Oyb63V?TiZ!e?yY*7V2!<>YZ8LU*KKkqbhXT#}+PQ<6h(QqZq&A;vUWQDRY zu!@MVxUnJ#l8_bT5xo-5y|O4L%A4Hi!bR%Ziqb>|!TIe>Pd00q-3CUZ!S2DNisKMS ziHLBk38P)kp7s%@NNE-YAxg#aVSYd&o=#kLm29 z(Lmaif*SeMbZtpNl3sEObZocXm!P21{K(-J44t22F7E77c8RII!;txZq$0Xoo z1bb(ty*&dRhoVpd(#yDUI7DYA})^H-`9l{LPI6JHQw z%Fa`ABDW2NJ}#%-+Iqn;Re zMl|F6hp)lQym-~c!s376a@wKd0cG=7ke6ul zR@cN;DI+_3j0n6~W^ZNyiV$S#xN)u7r*D6WirPQ={LSSkETOq*e;^Xgy(;SCY+aMK zvt#-sOdL&|Ql6UjadJEg+T0z_C65`8bDfk~Ph5urS6VMRBpe-Cb_Sv-c{G*N(S*`d zKd;4V1DH?HK~6>Wy>mlGNeT1l=!o!Qp`^t5)|H>brX*;}^t9<*@p|t>=5n2nv~k@T z$Z1E}S@Kx?Yvw=iQB|q_e?)y{SXJBiwTdDL0!p_ulG2Bk2I=k)kmk^x(v5)9B}hn0 zH%NDPmvnc-yN=%9`@fGLu5y6A_nLdnImaAhEIPu5BTSL+6%`eVgBF0^gM*yA-R!T5 z!Z_uScUR9U#uT}DLmsfDYBRew8tGOsjy^s!(*yE0cj`$P4QeC?uU3xpYzWVs3)6S zS>-e|+~sl)vlfoxAN|}{15XUnr&>HI`4Q@U4W@YYAYZk3y`XF$BO}A-84}j7kFD?lsKf(6mB1as^ZomGWIWcOS*s@A z-xqpICZ?va_KKXGTux1`>-OpdM%&5FMG%qi0=&nrFC@FuWq|wT^FjZPY0uc#|E?y2Q9d*2Nx#;+y_AL*`6((RDCv~dDY2(-wY@uT|GT5CalaZ z$A*;_(=C8Gr&eQ2fs2bR+r0huHO}a96FC@;vuL%gH-GcVwvf^V;!Xp&#%{aX6p^&CSiA=uiFi z>zxHVKC}uyva|JvL`-f$!5?tLpMW401a;4jCcl}9$x=orLq=m`YF-`zq!ejnixv zTsD9hMMg~x2U?XhGozu!fbH3o2FS$erg*>-WH~ENhm@RL*ptZk*V)b_Xq+GY2C!%3 z^jq+N+5~DVD=VRkxT?iE^TT%gQi}5O0)V2DZh%1Ihep+RaAClTcXV?{9pVFCD4dZT z>JOa{qM5JK1_O194{%(wN4H!X(_KxX4w{&sC&Aag#ip`5oB|2IzQ_La8mxGEukHWtw zO^L2kjP2Vzw01>5AO-FWTi5+n*>vAU(}M?YIJqAhZ@RgqW^pW(SeV9O77pk$jlC%P`T25xG@jm$6 z-w&Vig|78!Oo<_oT+hh64LnvWR3Sj=#ATxrwzhu9#Kd$Q0Q-@DKZ-!|L}qei#CBb2 z;s5^04-$^Ev$F%2BJkg5z?Xs^cdG$`)F!eZf{iF1lm1iCF@28s-_KdWa2$IE`-}a= z$cUh%WG_=ya99{QDe04#?lIY)|NGI&17Ul6dytfYgSjC?=2z(Gqo`4SXe(m|6&eYA z9$dc9QTf qUpe`S0Vqy1MQWDgXPT!a(%Hvyf?;1@vUpDiHJkiaN(f)T z^&d7d+?&C6Ui;>Crv18Iw3$jbn&-|vy5-Eni2!UtkENxhf#w=SQDTNZhm{XTy!@ zZWANsJul40({V!@Kcmmxe3#hgC)SQeNEC(=?z4s}kLH9My0Lyr9kiamQJC{E&~AVg zjj?d!qy*mLfZ07!Wo1_B%(c4*`J>Rq%v#=bQ`Y)xN?$B(u@S=1;iP`&1|2~`!6$_3 z|6Na;>2Cx*_9UhRsY`kzIxO_Wc42@R#p)r!SNW%>zp<|^3a4%IjH!#AwBD-!emRRj ztvl1!)(c&3K@9%W*O=IrE^z1J<%gCrn49;)`>ZBzD9{hh0kB)c`%QEh!;9+$#;%Of zdCYJUv!6kJ{udNMqyDdc>zCN;CYPzbBdC2@tFoaq9!bKK)?37trl*8gS>Ilq<{9=1 zmDk(2-%AbKi<2XQYE}Y$lDV3%8KQnisFe5EEhVw zL_%J?wjct9^`?2t&i^NW>M8XUzA24~=KK{EA#Js@s3E1hmMVMrCIo20pi0 zu-o08O*$nS+=9*T$B!R=ugFBL_bMh=Y-`lOkOI^^kELk*Afq_Q@S@>(?ZEa2jxbAA zDuwGCCansA6E`mb-GDkBmJdA^Afln_prBAr9rv&8yAC*HjH0J;M@lR^d>vzV)Y8^1 z32um0zujVtv^|I%AXCU0QqvLKr*Jx+(k1%iL&D&B)kQTGxoMKY5?^CDTzs`-5NSL9 zj{D*ES914N!tTwnWHJrw{%q@%#PnCod*lZ{eCN}s=U3DInO_pN{m?wN4u7c#Nnv!v zo80!(mwPs1Ng8o+#k|rE$}&i5)MHM7Y$V$upr9CmGR4Cd8N9j~#cb^C$JaZ>C*X0w zeMw5{jb}0dpFpuL{oK2HB&VypxM%5hzWW{U<3Ykps1!mN-oX$NkjE%3Eqy{rkI))eu|mPP4>Z>C zjDu6b&kG|*7d$1A9+gx6*5!Y4$W|eDQk6B`sZt-8B|4qNmph>G+<$0D4rD`+ zt|iilz?SH@X%6-v3=E9JrazCGIbqAQiSl`6N3!82~LK~dU*fq81{YxB8O=+48@!lvyBH^pI63rGf zhq{hzIbU95evs-Aj=jCF(n=t1UnFvlC5=4)hGQBVWh^|zk@@-aU91V+}A1um>ii+kuUtb9wJQz_c=13od zu7po&9#wHDXf5>l^Vj4#v;`x+c(ILBnuml+aXx_`)NmFcGn<O$^;Va8d?EZ9sZ3e;OKk5*w;13=K%xoblOGVZ6USwtXX<>5&N z8szt#TTUIobL^e*0Kw8y!k4NAS0ryB%>m_F2LPFX-N8J&Op+^SB#NnkP++s+x|=+c zaNzSyINO27C_@8`EPzb)P#)=CTh{ahao2S6#}EM@MhKn_vqL9LtCsxxASDI zu5@ZEtu?FX%jKLro5v^BZ_Lm{-|#@GnM%kwFXo1E?BAJ)^TlM&4%^4X6DPg5kQG}5 z_ihss9-dWN8V!ms1L%e|#IOstN!t*B;s^}nSL#m&4E}UQSxlGu$HvCK@5HkPJ%wv| zO13Em7FP6^FTec|(bWJ8l$Z)#5cz3hb_odM0p1HOzT3mr$EuecEzO9R;Qxi}xd`KQ zJvmi%Tqqu$ot@R6&zNhu?N!WUY}!BdZ~uacb+YI21dZU^@8-AK{XdLFJ?(rQtueEI zZ9auJ&LS*&~Bn^Dn4VM?i^zh5{Ao6hT7F^ojw(7e+6Y48Ex1;g(o#w z362bMIo$LIxd4`lg%@W*$0L)24yq2&w!je@zc+(I_s_3e^UEAL9K_t*xM7lw z<3HU$a&j(A`AFIlWaTjuladmcKlONP;Lbpt_UGOkqpf^ZQCFAH(9lRX2pW}=lthA7 zaSt(ptQa&JFuG+3>^JDNs=oj?nG(?1XlQD}5t_f}9Im-9P@x5+KEvzNEj2nUV9Vsn znSiGM<}CvQB_(CR)RY$oa8cLQ z3t?nBF->vU#)~GVs--0*Bm@VV38^IZa8&-=cSBL|Ut@5w3i4>oCkjY7IN|_%si(Ks zjS2RvhFQb+W~*52H-{c8CUY*aDax;h9ePr+3nAbUh&MIJ}{EM7DQHJh(q#i1`Z~U>6xdYGVPoq^0g^q>D)wVFFN$r z*HB0yZ26NeB7MeS9TWw}_d( zh3d#j6|9jMzYpCT1+&WYYp!XT5s`89Yt8)kQJraC-+V?U4E6_go08JzZV{fNNOP~# zU3(*vF&Jvv4H8lPy8+=r%f-eNkfa`gCX~Km_$F#}tL@+-?bP#pcUs8YoE8QrKp@rF z(TF7Q8KAj>ISQ$%sezlQk!i0P85xOSQC@7f81Y>c$!!;Ri1C%Jnpi!*wz*NF%qCua zIX2m4Hz~b#z{n9`5x7orrLNxEw;Wk;dHsx+R7{ZBzy3qrNpd! z5_Kisg7b~}49fV5U_h$ua_R*xHj6bSB?jz)qh&NzYcZ%4YCLt(>ZARdNy_Qu+6Nkt?j+omR(Ao33&aeQk{Lwi)sR<%Z!Qb zK81yPH3i^i>dPyKlh|+-CGz@Vs}Q~Edo58m-@>Rf*OD39;bdBMapHCI{s@Eb{tu^U zNBq!Zjz_tR$i~VZD5=-u^zJigA2N!f;7^|3Uw1JgK1-gBJ;@{{d~Zq9j^)KJ%YVv( z%!co>LToiMqtw|kf{?0t&Pvwgp(p*ZKNPi;bUmlQEG zDPft}K2tSL$6b46mw!^P>g7@eL~|oko@?D6U&SS?y2jvp)+CoRkpouB3s?$g1nv9!!8DPbD2xt5CCPMX|VOL1D*+Wg?jy8ecjyJu!-=X0=^iQAT)>^7oTG4hJ>$V07`EyDieKapyoot-$P`*H+rLlEh{kGu( z+VuG0OBySyDb)8})wC|>)5cewr5rdajmfefc7k!4qjVQfG>M!q`HpF0kJiqMB)!cO z)AqP8SoT-UC0_7;l{O|dUe991g8tA^HmPK{8?cN#IX!t;nT(^f-bmwXd#*>&{BW}> z#B+IL9(>^3rc}vyg+4-**jDT5 ztoh47MyP_tzRgFJ_tvdb(Afl`mS5u>j>raQaqb_CIxeU!Zq}uLYu2X37m&n1w*MYR z93$$|S`{ll=^vefC8C}bI;f-8;!w5NPv&*S%{|j_={|4YKCy*>^fJ3-V#YLrv$%|i zo;761s$nt5Fs#i+kAq&!!|J%i+?Xi=*Ypt%dLR>fX-cfh&8tq4c9sa32zbhZ{ZU64F8UHHobTw??j|QTF7C9AhZV*+3=#VJ zR#E)J2d*s-u(!lcOsIgYFtE8?m=a7r_A|1^^$F>(ev=2vsr-C97M+p%xIY|CX+%>%kWyMmtD#EN3%dYSp@B|I2F;MPD?6Vu3*TT{tW2l+6^O z*y$k)ljru+^Zl9N`K=7o3-}j=!N?&yT4Q5d_UWc39T0~5VGlZwE5zLgx7b2QD^xGx zzi*%*G7l&?0IB!!J6ppz33Fj$d_H&Q&QE1mON&m6Y_;2JD1#IbqdpwbFr3fLLwDk| zp!<*kl)ct~m)r)}h}-tXz{1XL?%kOFpNzL#N*r8QW~zkTy_Qk*`$jtFp9LIZzHx^HrHijWEc(w~UE5-%**)h^Jm=)E-lhq=lt@0M^<;gE zq?q|_YWt#Q{kS66lb?*SF{z9hJ*YvCy{YabkPc}=(IC>uCim6oChZXaHG!21{Ysua zTsoP{K!3e!Q&LXcT$=&(*-PFnMbDNy)wRd;-Yqwg^Bog8d%53zU5>xoF;Tfz-`Juz zHSH_FQ-rO3)*Xb{%btem+_I8+o@o}<+Tw1PF>wGTcNLM8luX;bI2q&z%}b=|Xm*KF zed6(rE)84!5H04a!S>~vBD1q6@k~b5llFoxUUtf3N1a(S_6BP)H#Zkj z)KYzr+*% z_>qJ!tyuN^tsmrMZEa0nNy%P;*X3qp?584NH@4eUai32q|9j8;5YUpwoA=qP(w3!+{+~0-avC#}Mxy~nWs$B@oZ9BrX?u(F|e`IqIf@oJ~I<^h|8^kY4V{$r>-_K@|cd3yUUq` zv`5#G2K$eszt>ox_IIkaD;?G37MOphiuq%Du0gYNZS;DSFY_(y*WHZfbwvBu|9+DU zqGwZ+0Z9;08E1}eJxMmvgY|MJ2IZhvRaNZ-of%Vt;W7_NTgjC>9}LZm;JeoUk&~pu zIM7gc#!Ga)`LQEAqS+7Lr3@Y4IdxC!+$->!BtyX zUFBw|(<38vx{xh%Ep>Q@!>A^ zpxwiTr`QMk4;RK2N{m@Mv39+fNC~`lTr7iJf#$LGBKg_+R%X9fxm_Pi9dZ7&+FuSK z*jKR_uyRc|P5jV3<7Ic0jN2E_8Dqy#9b5H+)@178an-{b+?c^$ZZ4MIsz(w8mF+w%!n!vAG3I547-?4;QQwho^oSkl$# zVk3Gzco%i;>{wLtzk!xY9F>ctjp^#n6AUUkhQ15IP%C?yf$@on<3BO7sYAz8#YJA> z#*NOgP1-jQ+!9=|c|bP9)^fNzz&UFbbJ=M?b#`iRx*C;TNAol!lpW2T`{i?x#-CJ% zrPE2flgD|>zQlR>iobe^&M3u=zPRA6*zoV#RWB{O1*z=5_`&Enj@A95#vEt0`5aV_lG?2=_w>ZVWW(9N<^WOwP!vad zQn2>6-lNELV2*L;%9B6d1DvmLIBgA^h*S}5u74I3kkip2`!=I(Qd1T7{+a+Dp1?=! z?Hu$%9^W)k)WQ5Et&?Y1wyAr$0fpE7p@1jfgG>O`OaAr8RmBfM>u;M3k2uMK!y`y3 z89w)onMAl#H&mwF8g}z1xX!lnTt2KH&FsY;4-fdZYO}4rDY_pg1D1X9834UVMtm>F6*?#N_?uFV5SILMNB4&+RzY3JNN2CY{h8r-SBo$HQ%H z{x@6EbuN}$x)5VS9#P4sLV?)^oLbIfTJ<+=W#oNVkFSJAgMuTB7 z2S=6edOf;ea-*4<*+9_p;rsw6HXfd9Ur%PnTb|Nmd8{UP+Cldt0$KNK^0I(|6*qK- z`vEvE%fhzoEOh(a^*@Zdtzkd;4Le`)wh`3DwN}$suhn-;sULcHy2?=N?m`}UQ;sRyPk6`-bYA`5`}Stj2CJ{p z`=V;{F&8q)@Q>{5Xf#5f&W~#iIbN+VIqttID;JI_Po_VMx)iKk0%+qe%h}3^-kO@4$5N!%zF=P}FaJ86DfS$UgH|w9R8%@(&@2EQ?7zm0 z{DkC;ZpA}vNP(d&*E)_@=0aB*gNHZM+f0|k%s^`wZ65b_-+1IjUdH#f>(+Ubw{f;N z&7boU>%x6n8Xzd)n&U%5nk|R5T7dyBdF8XbYEp|jS}mdd%M`5QoswSH^v&4xAFq-g z3_ofh1gbg>m6HYfZNGc!AI;>7C7F7OD(My5lR4<=m(7xXc}IvOSm3hd*%(pnt*TNm zy+_jWKQ6#h+{OP9+pyayaa(v(gs*EJEnBXVE3GI zl2OmrV^z6cs)V=r2{FCoo)$srGL`X=JK!ou+FZ8KoYNNYEQNK%{i7i9Pd1_PfXY!$$s4v$LImmv}g zK<@j2faYvHhMool>CtM_^>AT$vGYyu%nj|<2la*Z5n8XlkZ)-xTZz(v>oH|$_;AlO z9rbYU;aaL5QquTthz{zl8Jq6XB2JD`QR2?V_m)o>RgWUwidTs#x|6xd5o4NVMU;8z z3)$e7xDWhcMmh<>rq?2RP$iWyY3OrJnqG8mm@ zl+TegJZ_`=AX%X1H#a)&k>}4 z5P-lbr<@-k1}xs~J2i3Nh7X&xncO;}R_t%tb48QJ;H0vK(Vi6lHrf1GmrlK|?ZVbQ zR`#)#vS)@~%ca$!Z-7{0p|5+l_!o<1kMQ~cj>uYv@~&0nDwUV>7j;f~9BHf;Eli8K zdP1>2Vb7~siZGcM25L|S%h@Kw{(y!y8LmjX!Bl~n&7Xek%1cD-2?f7=jmI&>2sJ0X z`Xe&TMvOhuC^%BYw6vaNqTgERsCsj|zl+myL>%s)z0~g)-9?Pye3*0jL*C9}>&&d# zbm`;D7GR1l#=>TWGoGYcQkeVg2wS^*?q{p%{2k_j$2psdHj3nabwC^1FE^ifhy%eg z{3AjxAqWe0s;sd2E6u9Cc3jTbx(91w#pu?d@5_!5iIjJ7Of{pyl?Pco7Ib7QzF$s! zK95dJh#DFWh71Z4tlQQcx;8X$QNh{*tNJ6+;yqcg2|(rnWEg-#7}9O152`^30Sdqm zalz#M5h&b{tXoEPb##b8%LU*aFzIdv<8$!ne}F-Z?nVlCG#E4foywR%p`yxlVe$aX zvL=cQ1XG)BFx5>Yqo)t2Ev`SVp4}=RFyN2uUCtiK(n{{8p`j6%l|{8jwn;RFLOY;U z=&xQ4o8M@`hH6?iBLBOxr_Z0;%{xpkTSKPGP0@ilB#d29Hpqt$tC-1uBg%RKhfhjo z=4ddb2SWusXw#h|Xp%v1iPSYTLDt^U5uK3G4X7G$i9!fAW?aB*Pp!d~4JD9F4>wyT zr6&ZFHlj|u3Q6$vt4vPJ|9bQcT>v5huPRun4iHaodyGv<0RaKR$ODPftxYz7ZUDFK zcaFPL1`K-CemL;}TowWojC6zKFEKR#1v4O$%L{)+*iFAy&7oVij;CywQ}R{253ft}8> zJy)b_olFiH1%*EVi9MxY<3Ve(BZdnD0^pUDKQ;S2bH7{;EEV@ddjgrNa|E7tz!MDKe!pgQ{3pce z(*L5anN^rgy-RJT?@)stH}Kxk z6$3jG;b8buqyJ!|zd~8*^*~{n0cQht4`xoLRq;%oDV~?70n&zSpPq?6j$<9~`|iJ` z7ktF}y3xwY3P9hZbQC?h%qmLVuWWBU0olqv|L4zO!0>$sxH90kzj?+*^7K&>yCo?b z+c%G!^JiQiA{}T30IhpuYN`uRTZVQbbr=*eo>j@NO;^x}wl*)=;0bs;ZrZZ$nyxWE zxFw+y*ZxqPP2tY3z6v*!`feon5>HcujiHZKaVMa<>x~cVw*YoV_|RaJvIvzr)VL>< zF`v~kTk`f^epOq#E&1N&|MZpR@Ur8LsRQliDSSq2SiHlM^|i@`DK(y&&*`QzX5142 z0nrTKmpDHrQy_@Xxr59w2uuvGRG(KHni-{&{oPuTalkP3<9c60TStdJtU=odbIjv! z1X=wN42}mB2(^$3L4=vvSzym5T0EJ?E^-4v=%&R%;7U|7ZISG8J}pK+^ftt2Hq%Ub?m z!|(XQYk#Ril%MORU~7MT10Nm_O_WX4?bbFyc3av|kPg#t7xxzr>e_v~!`*RfUSc+|Lg)wG zA)sm@*e4ThDR`V*xff{F9LKkwprDwa=?(4ts=1xg@|;1vv$DG~wYxT{aNB|^R3DMO z?h0o)Y}uJrzg+QDnY=>4O>T>S$M`U9Xsj#3E$s>yqv-RN2AWMl7qWpJ`Dq%nJ05k9 zftL1LWUSPmdkL(ChabsLn*5vQSrhAW{L5S&aPc+SG-m35go%Gzwd#o8v_WU}gb-_` zi5jGYpH&nsxIJz6&Y0YCKI^@!uXN=PXXnt}D_Y&BrP70l$}0X%qQiAy_;Pr22P|1W zvi3+g*;ogegNA=JTRO(45ba6+_y=ca2%w>WR+CJd<^^avf$2~X;CW@TD=1?YPx|JW zJ>7D69vEbX7m~4ZL<8Y{;VF_?7nNBOEMI@QT2gPTh=T18slHegDLB!H=VT3wmR7zs z*5!`fR1>)&hUB^B$ii<@?)7J9bXRbnB-QUZpZ@p3$#1w`>| zqycY?kq!=Qm~32MNKjf|pK3AjC*2qal(-qg;qP(j`<#|f6YLh+$PJ?yDD<1)#7D*T zMQ&tUPoLT!XK)!GRMT?R(&N0a;ZZPXg-~&X_rP;wOA`@nLjFQ4a1ry+PQd)a!~0QtQC?G15&-P2fvEiJJlldnENP=#P-uSHdC6IDl%59)7At`J`^*)6M^(uF;e6sJ?AQaY?<^wABgN*}!~(9!IPapR?i zha1h#VxsM6t1gS4y3xT5)ip6#D6sJ4=TFkCP)Jp;MB;X37JEs_L0_6AEO?rlmdu|R znuBa)s3Db}`L|y{h7d(Q7metoPh=jVUuM&^iiQT}`!M-j$+cfOMmIgUKKcBBthp~O_z~s7~T|>+r zN_axd3hrzBcQfOvYqn=qGh(Q+M$?A_^RKaWnWNiNu>IHW-Lf6DJXdlQxfqIX6z7~4 z_(^I(+8O!8++7&{i7@WWm6wx~^DgYCM4lX_Vil-SqVI=ZH6d6AKDBN`@G$AgrzlQBeK{4BMD&R)j&NAfTzK z3EPaH7K@o| z4%AsgHhyT2)AMNRoDPft+79{=C8{wyD5#MDsQF5I)Z6!@S2}^&9}Hz3EC8`#Znd4l z4?+mOcod&sZ;~hqIF?LIu*?ktSJ=zCMoU<K`va|Mv0-FkC=607oc+Fgys5 zHIOmd+S`Yxra(YwC(GFsWo7w;mU47#%rAr5B(VdSYQ3eS1EgZWGlX3vBV%#Z$%|L- z7~(<`Sd1NO8pmd2%q*xq)1K#y;(8nYdtVem#S|PI40wPtZ~zG(8Bt(pywqQCJK*IZ zl7&6m>uI3<>F)04qzJW338<(nFF!S*z!#CXuHm(K>m;wXo}E7CKaMR_NEIS#iFWpZ zfR;n$uzUTO!ID?HF!|=U>%jfZW4ycPZVNwU@Hu!c*)oY~bL983+$e>Khjz|V8Z}b* z8Xqn<3g#6jSH~m#|2~cb>zarL@f0*MQ0y6O45X9}C85E6?KdK$rVa`V3j>4248=iC z0P285T655NgMf<4Z$_r9Y*TYby__J0pA_PF317HMtn^an@_>Dy`@lVCPlg}b6jD(h zjQwGxhP(6kc4P>($*5eo%#4!U#kZ16Us1ezu4Aen#~aTO^(tdJlz|zy9=*){tow4iZB%+k8!BvU*+@l`r7r@lV5Zd@g>4*xFIl`#^G~^ z01wiv++1o{q}+)sE5nqO1N;x}03SKLl1XV=uCqTg1&rNpsx8FXTiRoUHS#_(g)RRKex1XzdEiTbIzd<|8aQ-f}lq!A!vf z7Rpp4QNNN;9=MTvM=NF}WqEV$o3Cu7!hOYb7rICE4>*wbOp8Stl8|UHS z;ZB~LAJi|1BJmq!#J-fA#C7KiDYMn{z0~Hon@J|(56N4dJ3@?4+^%`JGt28^a<{U8 znCK7?h1bG!(;^kt*Hri$MGBfWZ0Nlj(9>)FVd&|xpf^J2**G&FpqXcvL7X5B&ybMV z-kWw{@aZE3iGb*Oge0Op-QR2sNHx?nG^C(j2je~%!!{!g^a4>aG3c8(DF74QI&)ng zNa+RqKli?sU| z)9C=?n%duP>+0H_6(v1q0vo9NPsbQ;``SPV8ue!tdMkBOsOcINFfQHs_BCt6?a~&65=PtV zOQPa`Fpyp+$mFcX+KDkS(B9T4)3Ktlne1aBJSvs>tm<;v&u zC1<55#7kupaah>Ul+Vm>`qVQ1;Y`7cO)t8eiGH1_#xp1=LyhBuez}7gSR@;~LUn>{ zC>F@HA(oj?J}VldYH;2K5nX#Kgs%6_dijU&h#)d@cgQE1QUNURR&?l>$SEj1`Mvbc zd3WaHn2M_XToLsPz;FH>0$5(Kn1sma6vqL7AZA$4Wwj922`W%>5@CMWnMxqjs1;7U z7hCrG;Me_gi>IdN`IL!SsY8>2Z)%!0)A!yp)1ORpi8Bs2mp`bXk|A8D+D}yn!#3^R z6w%WsSzIihU}qE68KvGE%OeImQ~ikO*2=-B8EDbTPB%{KuF8!y6+opNH8&gX5&4z_C!7 z)Y>^FKr^Bav;lx_Z}{nx&C>7B-bP!F6%&f`)>2O=Wu@QHYQ=j0y>B!@@7Conq#^(M zVpUZZgAQc-(oL`p3IeDMHhnBIUAS&RbPxiq)yI?d{=a>#QD3}(lF}HH2BM8CEhA&+ zvNge(V~UKJt1A~MPVeIX=59fRVNEl0a|tOaau${{gGN)pIx4KGNdPQM7aH2>^8)=F2CqulsDN`(w5 zoM97-lc9CM?0kjyT3Dg_6)zq=J8HPhvr|`i5zQ_lrl4K|Xh)(0Bt>U?=I&DIWyA1$ z+wugtOcZJPT&t6jb$NkeGSWUN{oKBfR1u5K{#vZ;SmP({5oTCv+{{B!|K1d|hPGvE zppOyv1ipl-#VGa!B*Mg?T7t3ZVq#js)aXg{cSSG_#L)4)`UHd|z?M$9_`tIP$Y`wH zFtQ^D->`8O&05k4xGvn=8^`V7YiKzu5pvMu^sKzX($aZJ_{+r{^TIZV!+4n#XNb7e?K>-SL1R4e=L!(U|f+n9C9{u-B!J_&oHlhjvFL>AV8UfMH)zOx$# zW1y6+JvlB;#!-P>Cz5;U=zll-qogDX$V`CdVyel@D}5D^X5}OmeNnl3Kc<1_rU*_=Ss7Qr}kGPjZZ5VZ6X^&fsiBY(Ho%8B(g}xrsrh|K9 zVPYH~V@Bz)!18B!Plst|WY@Pxe?jq6j-1ip#RFKy3qRZB#Sc_PpuBwwOLdXslauJ+ z?_Ug@-VXQ!2Y8d=41<9*0FCPuKNlH(x8<<;Sb6l2mWCnHXLPSK$DaQ}Q_1})s;3t@ z<2+B;j{ZE)_4?z9T6b1X40|Zm1HDO00$T4W28-A}3HeORo0Ne0%&0Fot&AHe`Wvb@ zSIwby>MASQvzc4r$i#-f_mq$F`DW(ux=ok;oEAysf({H>H(j9taE&M)W{-+cs7FGwN=MfTEzuLVs$N0bX zj|PEG4}S7jc1W&;y~6x%#=?4b_kPyTdEd#!3S$j*5hSbqa`}UipchQ(*O(f2MgeWl zm+f2o<^;5um{RjQM2CLzC!^SV!&iHF!hdSBJ9xIGHpeirSGCGLL&#&#j~wu3Br|+> zL8D)+PUEdZZ_BHdHgaKqYfn$E{yiu|A`b*suKm4qkFK3F1tq06pj!GM_a!+VdqoO# z2@#`Pe;&%57LVkWP2oDdoLr4YklvDiCV!965KNjux|SubNasyU6GC`1Bd0{STNIM7 z_8Y|~_sxsi3?+fB2J|-#7tGybZU;BdqbcwO5zzy_oZPt=$?W%WZX}?!q-^kQBo7TK zGA>TUn-y|SmVW9jgKpZ_Qvb9aX%XZ6G@jW1b18a{XsfQzGGrO~EbBE=A_B$8 z({E#2Rq+YGQln94lfHO)x^yTr=dO&eQFVCY_`icImtIlEY?b4~u^WS=0Q49kfLaf< zZA4aqWC(&}(?I>GU2Ffnx*A8h!CFMSBHAt|KbAXT*ihdsRyeURe(v?oTiwh&8r~J3 z?c{?Qw%CKZj)^@Mo-e9Y4y)r2ocsp~d|tezhj;m^w`Wsvp9V!HJU^6egONw-ioXP>#wH)c?k>3=1D$(|9Ac;p)MoVAuro&rQGO zf#ESY$dT2`v2Nbn{HeAXD_+047o|l6V5J^iTu=da2#_hcauW!k;eDp-1^6t$wpDh1 zo@j>)IIYKxIRI#Uc(3%DGMb1=0!@#JojOS-jd8r*#nii+4jjV( zEv@7#q5qEUycYwx1CYoTP=rh<0X{4aifBX>lA3 zG7E0FFfL<8+pPK*R=kdvvift@R$~8mlq#!8DP7s8UMzTIoZqz$JHKZ47EmP6o}%^+ z3}gdyBLax^qqv<@f74Xbb9&7Ge^9Ak8F?==OyVJ%#%JtV@&-W~#H%5wT*{&I*FNFX z={+@IFbN8e#{gDVRyI_Jab;vuxW?-{1_uv(3RTl-UbwWg(+m$&js;C^2$&#)bN@Ol z*e7r5GpL2d#L!>AwtbulJ024DXAoS>xg!F01!$xJQF;@YN(1Ek%n{=A##s&Yw}7fs zr?<*R&8Z5sd_WTg3^}?=kqKm{_NL38D=UMBR?A^r`E-ANHnVv`tYX&rsuylbQ|#m@ zJj(rI^f6XV%aw&af~RppZp=J$!WvXxFwEq0W}uz(Zk$5ut>)`Vzn~{V%a{7CIoAn% zv6=!>@z18$e&pr#AVvL)0R$iG?}WgH0~lt#0+5ird{kBItEbJapvQ*!PJ{o3JM+Fd zfCEi{sNygz+)%y4$mtiwc=I|2RZ_%scX{BKH3Tx8sptm3S_|b(KiZ7N2cQ>9t*Dun`%t=mvVbbJlHuye((2+kyf_DeO;w-~HXq)@)Vr6q6bng8)E2z&VBoKET$-wg@nJ0Ll6b z5J#*Y9Ozn+iOAArt4m)JV@*Oe2_MHo7b~@P{mTKn^g9qO+%sCJT#(|v{QPr zXt)oDNFrW95LmJ8wToSz2ZbN1e0OK1`Rdij-&6a9gI)vvsD~a=3(8eP6>S<2|9TsR)whAJ0z+r^|NV=Cf8s*p;%o<2LO`wzWqk|RZ(=kkQ5nKys0FefyPtY^G{#P_{%cZ#c6X_3Xp=8 zu&q4f`aUH2&))cbsp3vC-3hVb)~>&s|A@6_isNL-%0cmL<-qud*CYZF4w^`EelnFO zO?sm^8x~7sWYB6!zTnZfH+&@CBv*312S=L9IM(SGtd0=%XxIe9+wSxfdm#f>$E)@h8*vy(oe&oX5dewZC0P36@R zaIu1$E#1|cXrhhOHWgJ+&U+zw`AG~#vljzHUBG7cr<|g6^XS7eD2el&L52XVZLP699kI zl5P^_PuaNW5~5I!6whUf)S{;wXI5YjRWY4*B#%7unHB-xA7H{X4pzFxBLt!PruYiX1gQ%lbJ zxZQTHh4mwgoI8>@dYVkK#9}R zMRkAY^_=*LxGPcONGM5)yNmfaQIQtyvJ%^zhca3tpJbLIM0K4mq2;<{LdJlJ!xB4h8~5PH|Cf=s3v66k3OuxF-1>rpUc7| zzJ3<-Xu)qJG88w& zbt1k7vxV-xVNfo>N@qG~%a^npImV#c^%i!S!h^wz`L4 z!84c>D{K@@r02NJ>eZ&%7rE7a(aq(rByEu5^@DkBx5rAp|*ExB_v;3zMl!tr`I+4Z2 zj98)1h>3}B@9qFa`6ZAw`2_}|0}lg0#RBJKwpy^mTnCPhnoU?qdzpdiWgTRCm|+AU z>Vku+0WMAg6luUV8UWRxoB=ZZ0+syE#mGh2+zCg;aUfCP(p*_ zXu$glXw$-g*#b^CHwJfWu~44?PTxB5)CH3jqRV{*so zSTE7yk_SA%_1>YqdL;mb7KzPPzO7T4r$5M7*wO*w~$bpHcsMFjqd)%!AkVPgi26i;K&gFp|wV(g#^%`Z!R|Rt7kk+G>GKj2&!{~lBz0)D-Y0p0s|&rfLk4&P3mS2n;;+{ya9uspdf@= zr-OltNu6FGbP66fqoAb?E!3>zg$I~gF0n)QX_<00^ju0-RT%M^9g5e3<0zO zz^{4*CKf~oRVua&fN=uOF9&B7d(BkfgL;2m>C!d{MYrtPqq9E`dEdWmug{P3AC86% zSInrWD3zUCb2dla3okF-d;`b4eJ}kp@y>l$COVV=qV#h3BcI=mNp7BFw9d+pnL_I`dik4`@hX;IlPpp6I&{dk` ztN!h>GFLCOTU<+$MTje4Xa-IEmw;f@r_%pN)OUw-*|-0)9 zmP>(*iZNpMh*TMTb%gQ-K?>Fr-+1t!Ds?+LI4taRp$W~P9QP!NR>vP;Vsa8r{v#qz z&BR!2%}6C33!^REh0mj-r?T8{8~-rU9EN`bgR>Wr->og-=(hE`K&a!>1Zn>t;j^rp z^ou;^njaEM@5G&Wq~HB$_lx~*A52NDrfNs5OP?!Kv*dIhbjf>?Y<%8!+Pv!Ne6qrN z4pq96lvBN|7~{?1SI)^3oY%O+pNQPMMe#s}H|)cQ9qO6oQ;)i3Sa{<78)jn|Z+F2?*%WDHkPep4U(dHbwtd(Bqj(u0zB;LH4?*H}K=$>aTs7FJfY6|f;=h-t@&^wxI{zX^ z(OSk^<&1Qr+J=TXhx|~E7qxcPnrf1j#Fd51@OA50cw4`s1leym5(Xa~wmb?Vd3bnc zIpykV{3#Of-PI;J?cK5=#<)(k0=%>}ZXfK__vwvSx#Ji!%&d9hM9#~YyrFl@?N9Z? znCN8uuj~IZQ7h9B;d{HYeazb}CjEwE-RSzg<)1TsYfiVQJTmHU#?*g|tZ~Vn`JVB_ zd|F`M?GEs?WFHdyv_Eja;@K>*Ejgstd!=K!dJOn z+3!m7@Ob~enMtyym1NO;flHNEMf=_rsvlAErY@n-T)iQ@Z9?hXEx*Zk5ywk3Dr3`l zOSN7on7g0Y&3ieF_su@~nFlIlJGic>AJPmV^a{W!K+m+~-tLq?$KxnzV8ELZ zsw&GoK8K0xU3pgeIXP)Zb^OlK9{_vaJgs!d&v`vI+z8Dwnw!d?6Y}{#{Z2#7yj|aY`2;eAj~zYwu{)NeLQoKanDMMS^z_eTi#YlTg_qRDa^t&brQ#cmRn1(c5Zs^n3H(FmKxD_mE_#ym_v) zxo@O%-YiXkZZw>>JaLmosygKOmbXUNRE+O$^h!N$_nduuPHS&=y)n{gc&N|N2kfw9 z_0~{HOPVAB7vtwp+G*J8? zFG}Zl5<61k0cu1>9ueDEGQ>U{zAJL9I;vPhR@uL~;kfJIk;nBz2B1qhv_Cw-e+AtB zm9Xg>HT5BQUW(_w$~Qy`z5oQt2Pq*)UU>(Hb4>T<$X!bE5v}tG5}E9roUy(VVeLH2 ze?U~EPg|QBdLGo~Ke8UVyrvHxJP=u*YlS~K@fvTUo-LtLvQOW$1}3K; zFcFbP6hJ9b(O;9+ob2eTAW7r7-N6BOT~)7R{}<%qoJc4pQ4B$9!rywXTR%Vf?#F$B z15B)q4B^nU>C)s3WmZ=wG)4dhExO+OqNkiHniiWXS=7Tuf^sxv#Gyn)Sl_| zym@TkRsAd|ND^u!lbq#;7In;fBnRJVrGL(T(qcOIxvfL1RSQ9aO)i~#L+j<7gDExD zpR@cvaxl-P?yc^k9~}PE;8+t@Rut*Cd56<1KTTgGb8hz5a^cy8^_Pt+ zZuwRU+PhZ1J5SfdDQxol^j2-28Eg`ISvj6c;`{qs(5mZhgE=1Fu@vixv4Y}a4$lKs ztS87$h*HXYFnkvi;IaNv?usdG>!pi>apW{}l6PMC*xmTPPfG6bocOH&P6;xR3+n37 z#vs4k06aG{k0Ujao(T#Pr z^F>HqHs7A1;jw;ar+!);OU*!FpY?BEo4xskSI=|xxK}M#f8(~H6DYNL{9(|AFRtX9 zhPr7!QWP-Kpdn01N!iHVbwZ9=NQj<^DaJ+r_*o`ELKrpH)VS><095O9g=@L_pC6JdSq zdlYp78AXWzU$mTCU{v>!_NR`r6+fWmYxB{5z2I*OU#MWjeuG4&fv+vu#`46ZD9IOh ziUbt)V5_n?(ZhESoHau$3~AJJ^wDtImOno(Lk#_GZ(7Hk)@Ev)@edn2`_F_3O9M1_ ziY|se`;w8bhOGbD>cdvnBTqJRF) zq6c0^M=K$C@Pki)7s(wYDdsfAze=KDfn1t6!nJZLoZf@71 zp2wk}_7x96fvUT*QHN4S8AF z&&1O(LqBafg#9T=DOx$yO0X*2KI270MrN%f9LL5f;A5N0vpd{usQ>l59kEvsO746A z{(YC2P~%s)US~Jt+4e}zzD;3AJ8}bmS>M5U&ASCU4N=0OwJ%uxb#=Y>{SMK#yotNs z$i#%#=9es<%;4lRPC3*!yXn3tA4ZqQbbKb&Uy~|cCLfJ>XYl&`fq3iBP^dny-KYvW*b^DY=%0Tv8Pwlg zp($})On?F`O*7{a202$@4vD0!JKg7yIp$quFhkI5XD^tWv*Yw3TJVRMd2rIu$jI?} zUKl|C4R!4fyHgJeS=ZO;JE}`IAKs7A{Rro7&9YlLiPofxPbXAU@6no+czGZ~OLHX@+D8>U!0D7^ut0YNJYs zQd>z&`7=Y>JOaNa3Az`nh`K>C2+#Wi2ODJ8jE5hDMWxam58$Pac}TdX{t}q5tK_p<`OSf78?Q zmfxspJ39~Xbo}aKv%fqy*6SzWllzgmJgZVrq=+LTE|~phY^lgyc?!=;{>O4>Dw2~@ z{JyXmHk&n@vrw*M(Ip+z*dNMp5ofB|=ZY+qepb55o0w`_8lG5?4ob zCoSf=jEZWa7+H~J**!T7j3bxRfb&rR7pw%8z#)irB_=t(W*HAxpE}>E3&Cy%-uUuRetkGUwEDNYSb^L+MgMjIi{_m zAtSrJZ=OjyD&6qlkW%HC2JLEfrrT@{PYQ#jdslelc%J@Kx#_AX-<=YsHnP8FGTW-uVf5&@_bhYm?gNNjZ}=^H#`6vPtSZjJy*1P?uc1e5vr@x7#^ zBUnsBls`s>%vfm2-1Hp9cMf>L#6ZYh3EvX3F_0bPC)=RA!(pmNuFQS?8xP5v2CkWxPqPFQ)7TDIA3o_3GOVOmDqw|Lw8f$kErW?tLZhr_F6P`!#++ z^{;m|N4OQ@mpS^!-qhKz75_3cQ3<4`vS|33NWyA=)q>*6^Ns!EQxA7`4lXy|WJ2aqEz$q`YZ2Pfkhs zTek$sFFa)|az9H~rwqS@^PA>wmK0e39o#qcNlg=*ArZ~Hg~*^os1JXHGTr`1e4GUX zX1Mr?peIDG{rP4XsN0<7EiZ%45Gu4dXtR4<#?vjjKYZyvwwDzbJMqLt=G(5ip@1J-ewr$$SE z1`Cu_U9~smmD~Wl9Qr*$1mLXU!?@^FO$KLM6EC)`|0aAJsPVDJba2mfm+?$f2$} z@j`2?;^)if(k+qJ)Q=V(4@B6@INh%0+z?%6|0j2#w5d9DjoY}6D)Y(uSYk{znkRJB zs#gz;1Q_*vf5x)6L{Aww3MP44+RsSnS(U~;%<2BZ|8Qr?& zN@y1v%aL$E06mA>J^NmI`xH_|BB?A2&@& zPH){sJ4W?-DB{qo{Sz-QSiE~Gu5seUBx#D0r{3TgzdlQ$UEq%{hT!6b@0?U0r-tXQ z-rf0NkcpnDxRg(#^wNr>*%(3Em~MkC7;{CMUdhVCr$uOrpvW%=E)=Mdn*K_)OD!@f zB^6fFfeLSq>+gtU9%7#+RO&u~fy!|;WKjR0??!|4vjzEwx10CgdfRSZFdTlH2<#!E zIv4vr#FY}Shb|ZlqgoX^@tB#J5j`moVVlkMMgIWi9hr!ZB$^zjKR4XhW@N6^vh7iP zj5MtQ>$6FB(m5jaGR4OqEg#~Q?l6!1nmo;%>gSiK+{>bWvHr$}V7X6NNN&y7mF3xu zUWV`b317>NepSsd$a32JQ2A)|wUx8(ap3WXc{TNR&7L3RIrt3K3^=sbGW=LOZhln$ z%4=jQTxcH1y1zyz^rLY$xxaM1KPAP??E(M3q@nT_-_ILjqa5_nQOyr3%mr#x|2i3} z(@BWUD_0*17x1sDfU15g_cq6cg~2}$?(sLJrd+nLNDF;KxnsbfBTj}C-A3L%A)+=c zkYiGV9{Qd{bu`*{NKblf>dz>$m$T_O;m8rr zG@L0PsGzU142M4>g4kTf&t|wk(=F2Z47nLrC*}bqx(Dji{m0l2cMz`1c-q zuCFc%Bt^YV`7NkC+>?8YX>;Y+;QP!L^Al4?x}I-{a`qW{>!^MHtjVTEd-mHA-q`fG zFae$rZl2rH=jAS4dL&!8cO>oY+a0Oxer084H7h;;e@>x~NlE!sQeZZTrGh zZ#}R^0+Nc5_6~((veyy>(B(v>C{Ee07LAdDB7Z+0=U2b?(E6c9s`1=t3*mVz#>p>6 z0q8rJ{GG`8*t&HqhhFiw79p;|gq_otsLTXL#IA9Y-tKgXcBoRr^w;ELid^hL9!ITud$*>_ODA?x zF#MKEl5HRqCX6tEfSMy3AR41$3C~?wX00cUG%e4`#ZlgFoyRnU&fa=3K;ZAk?WAXa zhrM7`PQWYNV_kV5R6+X94?2PcfRC3%S!8Ah^q9B;zdWin`s-vM1~?CSGTdm)+}G!? z5n5y1MGw7&Z$|6%%oge&gT z!7pF_`Qb?l7g-b1%PwBO9#&J6ALbh~;4cMH5Joao>woo=UenWZ88GiV^Y)bROn&+U zahC#^&z@~Fe6Y8oY8ZG=VsF9axRz&OVWTZ(Pf)rPi2-(~E;vAlaJvvopfChYFt3DC z2HOEYOO|_jE@U^O(|u0eLSmEr%(~SuF-~e*l@PgCOK51pwf~TS0GRj+h?fIf==m^i z@bW5^y>E&Ki&D{jY>$Va^^YyU-%#W_yJI2UdJMgmys~m4z$*w-sHDpWtlweY!mPFH zK1cm~tNv(o5rMn3{ZkAa*+%E--;Y@5HH=yFdZ_Pe&uZ!EuWc)q-wg?DOpG$P)DtFXJrhs#oKvoccwXm>unyUi|Ybon)QpQiFXNh%@$eiyu zWvC0y)Y`cI=FjBBXo|gsCg#K&f!_?xvaW)0$wiDyGhk<+3uW%}*t`eJ*injW6+4IQ zgxI*aSb2D!qv8KoLFnbuPs@eY+iPg^*JnSeyqO4(2by*C=G+lqP-YO&PE0762-C~9 z=e;ZZPcO-#d8sCILgGjJXmuuLYn25U{uWiA=qr>!f zo)DAZ3HcD5&A5PLI*|aj!vt+lT9wRG1MDM2T=Z8gEjfwQHZXXZr7M?pX7|$cVA~Q> zVJi)?{_#Hec)xV;^TU!QJQy;KRS8#yes!0e>=^Q%m62dMEN^iA6MyP_B0V;SAk3`4yju_Un_PyFy;)ryzoKzoAv9*Opb@Likf{%^6wlxcZ7Xd zyof}zuqbSMJg3_0w1(=~Bd6;f4`r`}9SUWB5vftlg;i<+ky`E#D825zF=rb9->|QB;<4=a)VA@{&qw~?~JEvt)!FE!+ zb8%8toSuOehATCzOIa$HxROs@;%n;ZeYN$Fw8Ap`_S)AwL!X>G<<-Pwx&3}lU1O(* zQHvN)P+u0wX1K@WF9-L=m47M=dbm8BhXF1Ah0cy`jPvWZFUJU-s$ckE?{cdT;)3xkm zOdjm#Clxp7yEjVHO=iF9UAFP;KxKxR12ZEpb{EYKjGl7i|6!fHpT0ZlOq2b9x#G@x zhv3$Q-%1uvrH2P4ji{$j4K%!P*ct2Y67{H9_3&&58 zoFYMQa7;+3Yw+GCa3e&#maZ>o&$teY$OU=zTHZoftjNMQL&oX;{{EO-(ax79k{o^c zBEB?)^Y4S%3D{7URyu~E{Er8Zod1YrhYhG1weYzBUTbb3m|KEz*S-jKaH~42;K=lJ z)A2x&hu2*$IQ3qmkRvhCE|LXb z0{kx4Z`rOD^+3g+TKkpfi>qEI^^c2bd9x?_?PwElzW7zvl!|repzo)S(y%AH3cW6? zsTGi&{<3#ODzW{~#`?7^cMnd(TWfWr^@H!i=Kjga!0!Y*_Bs1_Y=GgL7KStcpk{2V zub-825Q{G&Aqg@waFOBgVPf4`)rxKCJM;s1kR{9$*pAb6Tt3M8ZxWf^52Zw6iIhjNO{3gR@2HnKmMuL`geMZQ850;DT($iif=9}Q&3Vi znZGzW&?6W035^Fd%qBo<87I4etKs%}{<>%ffEv?`vxWMp_uT5E6rJ2H2t^W;)`fvJcrJ!#*w1BcbitxiiSU4MRd0)YuB!(?%Olk=GVE)$B_4MSew8$zst2B z{Px|7y~#-1;Ty17C}FYV*q$#i9zc%ZRNN2j@eeo?f3vgzv_nS@?uG=7215tqqKPNV}K+eQ;LrkP+(!*{&uy2_K22!^k|*l`C&?@EAVz zt}nqn+HT9Dxn6F!$Y1T851k|Z-SM~0b7h%let}aVz4h*%7*T4~aW$20(}hwS0|q80 zjWUXbPQx>c0n>H&SW6tHX zt~+aSP$NaWw6v6e`~cnlU4XuS7oX#Px6tEBsm^VZLl^PIp>9Jt_oEYx0E*oR?lut) zp2dx81eGqn`g*iVG|%B6wk#YwNnq5_GJRGSU;j1v%**5rI6oAA&`T|+1W0yD4?!GF+9i zE?vBMgPYbo3PNN4!O9u_`QQG>MMa|^QF5X5Q2dU0lotFi{uX%F@OBI^=O9pU9L621WNb<78=#1ZWJY^XdEXW9rwI+d}?i9D0N=OmF#*F~lM@oeD5~6^ay>@8tyWU*MY}y&+}e!8m{;0XpK}q&I7=R|}nt z^W6F&w=%JUVV&2R&ohyOzIg5phgSZ33ve>92mWI=Fb_s9@MHMU1yW%rBmM+39v9HeKQGs?C1}id06ro5T+_sdC)=k4w4^vXo z`d(EhY!{@p(~7jDi_?>T)n2|^+~QUvrPTOBTpiW0k*fMQy?h0iNC;U>Ye4e5#aW+% z5%J0E8()s^h*rNDRF}b@%B{!$jAi|M@rIr5_s?HG*Icpn)P5sff4yNPXPrA<)$PV1 z?YhCGveOjjyWdF0-#8PuOXSO}c=~{!hCNrY#LdM*eY2KXA?7m%rzfk2?Sz2d>XtNh zTbxVN7~lCsmdtBkEp~uLCT>J25fDOyt{01(BveND{NVcil^i!t-zTUv)Mv=dLauH& z%Ll3P9a4*HX-m6;2?8LmOo%a@pOB1QNNuN}r`Ku?{9+j)+5)=3S{Y$9P zu-iqM?iOy%C|lqr{5<~!zV5gH1Q{Yr#70p`CtqE5_?Z+~Ka?V;2j;iKMJcuYE8e#^ zadC9#ENGz*M8}6{_6MzF7q3tSo>W$j2l`38S=i|y%m^wz|7=08CBc(qlx?^$y8V$z zP)g64k2-qR4@ysH5&-lI4$;5G**cJ$aej7o7RU1ze=tDsZ!sF5Bb? zMu)F)RNr2W^e^w8toSWoT%aj(TS%&J?DRjeZNLN~%I2@@pVmnG0W5{ex4{1!s^3Rl z$KERJ>=6ChkBNL{c2?>N)ssud#l*xw=8#cQdBI@SYYCnxn`6-WJT$za_3AGk*EKXC zMCLfCwe4+dn>y=OU#Bdhk{X4VH(Af6H;>tYhQ=V2&4I*O^G48OSJl;}_4N8QYdGq8 zp)B3~1KCQiK{P|xhS3lk^swFlbDF|nL?}^X-2VF3tWtC8B8n_A z+QpC9Ocmp?@haf3z`vIU%QZwxT;_k`rJ)Kgeb{`l{c>Y)a4?~%AQC}A!Z-bil{mpE zYg~~OvAie~V>n6gDSV5SYb~A2MTVSM^9C#~z4zkZq2U_+5fdXl**>|SZP)VCy?3T; z-dIz=`c2&;ZgnYi$?h^0rH^<;pQ^V~r+5QvX20~tbdK}rD$6p^j6Y(>h!$Gepa*9OlZ2lYp0+ybtRMNr=aQT8&AjT+Cmd4 zjaE+kCVl%}HYXY#p7l&2kt=S>^})zAy;qCo=O7R98gUwniwDe_q_|4Tz1(NEtci_? z3As<#Cnb*XXm0KmXu7T(eE5yf!5dxOnYQ+6kEUa2tLFM`RMrigT{|j^1!j1nyYpjS z_v`(#;yM#wF;$(XE^gvBcdoOFPNhDG&e5KW@k2W6Uixlpu?Wa zFwV$&pzA8es=d$I6VEqxGyz!`7Z-0Z;X`GH5DLr2ma$_n?EKxIf|L1LL`qu@;1M)z z_~PEi$3w^loadc!Cej-e(JZz#~w&-L|{1J;q9YTsazBSL3D-=a=Rd#;j)ClXj97+t-4 z^XhoPS5D@7-o1Fy3w}WQ&n7uYm4n0n7ijl?1!q?h-?d7N)WGw=LJ1NQ?mMQ8x8nNU#20Jpd@Hzure1^cZRj4}j}&)q z>#g4tGd!a;XLE3|c;!S9`qx>b8-wefNBECLChn~@&jU4J%D!=hg7bR%j}NVojs zdaIMM;;DTh=@(uUJ`&#C*f#0DPIAB0vG~hF8lNAAa|1t~FnkJh3Rz@4eDUvBM_RsL z(-u7|^tIY~w&U-Edu;FQrQRHOuM$MQ5Ziht(ktD2euAw3Q^ zFGAITIzBlg<0K#7?31h4u$pBra`ZkyWC`@I&|%UKv00#0vC0L9%Uy{_n}b?x>Bn}W zAwj`9yio0J@@2sK4;sH5^LF-(!r$z$xD629u>tBJL7U<1@+ZH2cXUrpyIiB$S$g6R z4Ge5DJA66l69QwMfCYWaziX)Yec?Tg{tp~e7H;l8k=t4#*7uMe*hxj=!1=3XWW@S? z^W~c+dnYd|vwyK?on6foKL38ms^RNx6(fQ5)!`hoS&u!_>zuwkiO)|d)OlPfsBHg@yFzY$l*U-jr zfp2!#6IfsKh0QF^%CItch>Mj zS1F-rMrQ<-Bq4CaR34Qb&^>vQg9GtFPi8aNu^0>@Dp)^aOp07iq6QNK3^~(tN3uO02y?VDowS6idR1Un(&(AmUyA4Safe3*xVMQ({ z=%^bx-`{<=NbC)ZL!(RRj{t+eZ|TgX-^Q?^fkb=djPoi<10jR>vGqMx&=lf-k zg(+c?6yD9%rB#J`1(#zCvdW|U@9v-7dPR*)dgr0ezuMHRS{j|%g+*ya-^krMK9D%j z&}1?Df0g$->mn<=RdtV?Y>ZrlO|*EB0xW`Hf0(9@=Xnbi|Y)$lqO=fp`T?9 z3=9xl5(jA&x^0N{xXkSyl$D92I}ijR<(H1 z5fKsmvdD=!0k;z}#2gYW86apE%5JQw*)1R-0L9g1I3ie;qu;{iGB-D;(YZbo=lpN#{pY-s7bLrtBF~pY2XaIgI>OM8CnNX$TXj}k zc_RY{5mPjJl9~DWp^epPnRr!AnQnD8H5D~Am@SB{LAHn3dg%C!&rfgs+1a?$Q|@$% ziPkK8@b-e$joZtWtxeB)ZyjO3$IvOV#u67=Ci^j6dG=HP<-PXy#()1JA-yi5?2JeF zSGn!4);#L-Pjoa`O*@AakgHqtvCmZOHkA0Fo20Iq&%K%Dqq!X6V_mc<{=_c$bpV&r z?k`#umCy73jEIXh(N0sipL;S`60w_{cgS5#Z-q44gNIUD>4=};;@$NdhwNK3-%JEf z&#a6m?qLw~IdycShSW*!#iilW7~0LbafLru-{oEP&}6?9Nc&md<6f|5rBuPxlrZh^ ziG&Zh^}l&?)Dw}l5S?-6*>9{l1EuP;l98W(UrlZUC80vJ$SX{tKx&sk`3M~;|9XDt zYj1DV=%}e0`yt5nh#nB@uMn5hGPFW0{X*|rRp`lp+{_)X;nz2D`3?4IW^V2mh{TiF zn(SGABPyt;BispLx!AK{yE11+>}tYN35ZXiz`X*h1Sm3om7rjW9n;Vx0!5|b)W--% zAo4wTYZ%-h88e_!jID_j_lQ0w_2^l6`0r8G9TKBEaUnvX+M0 zT8R*2Y&*j|U(wq70_0N`h_Z89&jjr!_B6H}|I>M@T@|nv|7UNust+6m_{r!YLxTRJ73B$Q0GaB^*zmbrhk8eHP zs@7z=-o3P$8x?%?g!ZA<_qj89S3I5$vT3S?w|QM6HE!N=?Lq>x_=}efZbnfwJW_^# z95g)R!_y39YR{xrirej3v7cSio{181o~1oIwXvUx&NH>*^DC*{D&Ex;6Y)E31!V@W z?xhpnntVRkjqUO1QBs8yiRWJ)=W$V^9j@EPg}1~NuQOWm5OPrj5ixkn3ga`+H;Ow=Yiy4t}&@y5)u zjXFqmk2(lXNMU-(pZw5`*$0BbYRk+ku74I5Ob{HMc0KDM$cu)SAv;q53xt>wBgbDL z_riro1}M-Z5W^+p$cbVC@mge@yTLINaBWoSR8U31KC`};>tgrAeDyckQ^l6{mbr@E zXrFAc>(Af5Z+EG4plEIFTkVrGEBez_>b(q1Z#h^tCk4_}*S+nV^a3xtX^gkiR|-mu z?k8`YzX$Ujdb-83qMk>y1Sk^9)+P+X|eeehLBg7VL1Z`z??*2>3 zs$_&jM&`(({Z6i~gCirXmzwrI+^%DO{#NHrjb1+H3(R&E_G``)cf1~vPF3H?h|O$i zz5Ddlmrd_SgI~{->)aEU3h}7+SKab6E*vFl8lp@LhsC;GF29o#FK%f)fG_Lu)2G#) zodkgdai<_;6-CE?A;dY1`{p+GU=qy`!gh*9@Br{8-q2jw1T8m7-6)D10cx2p&O3YO z!7H&r`3L~3*HAByCF?cU*Gwb# zX(bCwm=N3%n*-;Y5$|{7PZL-&dft64KdjN5H99&PmQ%nX4?;s}@H*i-`tk58S-Uwu z&TR*|4NzrtLHl=Ao|wLrq;d+)ac=#?v8|C~>Gl7o1=zavb2djbQ!hd|{D>Ra&+oj` zpQ9-0_$CPbDE7JnQssg7SWHWa00-TdmR<6N4M@UUAd(J~CNvwH)_pZ5x zRB==azy7_@{&Zfi!(n}o^?B(#l7ps`0V32ZPeEA|BtNWTM|2^erimr>`sWUA&Ve53 zW~f65r>=RZ!-{b56o<|hAj3C*wa!ug$&Te z6ZxR7Qw53glZ2j?5U?54*^)wqPAIW49HNlmNfFkHvh_(T+&b4C{q7L;nTUGRNWJUe z0FXB$7S91zeG(FqBY#eLm0k)lCQ>aR5d+$L&mjD!>(!6mrGwZo)DR;c10^1LK8YmL z(F#E#U&Yh}M*?zlyMm}Q+8oT*lvX0wbj90D2W2*h~rR2x5P}EbHyZ|z5 zrH9OpG-1zehNb3yf~-Ns;PkP@)%UOX0960!{M8e{%6~RdWWXT~X9VJM1FT|d>*#># zua(`2k3N9Vha+eLK$kC8fMcf<+N1ruw&T`wY>p#ec}RqvTlF^@28vey9ja&0ecG)2 zIa>k7PJAkwTsb(tpPu-?&j3H+ep>F=^^?TvC1&e_izt{x>I>mE17QudbGi3ICTwYj zc-!0B+ld_`(6@3q*Zr;nEeCGj544Q+bjhMaaykH~XLuELo#R;HEMYyeMHPHjNs<%mL-|~Li-vDuhxC|6rY8L zj*QxPxxaz-0YXuk&||Q$lMO@?+WWHrmUItlzjjYA0IKR|ok0mMg@Eb-t0StOFysIJ z{kuz~v!=!eWt*IWLK1EyaV%pE%p82Ha>@yp^5kE)<=L3chPvR>lPbZ@beH3U2vQLS zuBO80vRFBV!h%a;KRoDo9l(+ju16S$BgV0I9t$zB_M8y6VNqm&UM9YKAAH05f0j?r zDepdbPrD@rjH|Wr>~RuJgAsVg=%e6Z?CiSXsAZ8gOOn>Fs6Eeb{_JDMsuI z98dBlCMGf8o?RqcIZfV3NUyfd_j7V-e@LsJOw%umMieoRdB%3!qktW~3JZmxFu8?e z)GeZ%*hfO}NEQadC|R(k$V9 zQV^+Q`rFki8P#|BBToY1{OWRSa}Nqy+h-9JAh zAS?I19RCw87$`8bCcbu)f-fgUt_A!=xDA;xGL&pX zyYN|lES7DSM6pwJ9halP*KHedSi(*kRa1KzSC7u(z|YfKM2DgO!uUI9YduK3 z1ihK^>gWD%0$)u~C5-c_zq(VME#TbRhFWa1 zIgZ!cWIBn2=0Jo&PDXYCjaT0L{_{hq&%qIvg}yk>LBYY&ii!dAk^d!fd`DO!gp@4j z&xawD3Z@qB@&I!K;R(Px%uly9$Xw|DyLQ&2MJoj5f{xIqfT2X_1-^!2=#?)t?Y6%hPvPk3 zi1Lb|0n3rozs%B$PmIs6a0W0UHi9T*xZ{q>QCyDydQ9B2Iyqf;Xng#(kGa=VA_jyQ z36a`ue_I^$DdZKzF7(Ib$MF;6sONUA4HEWaJUFDZ0=9rJp?_zm(F7Yx5it^I=9rMf z|9}_|^jdi1KqI1fp{A?q=_#SgU=bC_svPV`#^Ge?XdVBEiC440CLZ6}$}z~1q0WX; z>O-##>Ar`}{LKH}_mvV=>6XGQh6UgUcg|3e)b01644G1D`Ld$Iughr9D+`7 zT+2Xo-Zo1{9EAT_kL7y(Pw4Jtlht@(KZAm|5}E^-w@vs;AREABGu)wVbpmo+G!|$> z(nqMMsgZR5ST*?<@e7dV;I3U5{Y>pG`5-S(0ID5ULLrOd34<@O#S|{rD*VXkB@@AP z1CL2eWJN3S1V0R13D*7h76}QY4c<6h?{YXci4GN$%7nlb^~wrVfXjsQH#+3#+1u@v z6cD<%au)K@^2*A=heh#t0JEQp#Qz=Q+mV+|GaU+r_wz=4DgIk`8WGssw!;b{A|i#k zWu?PF_qPzkeMfGU8oPSlhRy^(Km7!s-_?9>T;<>x37W#i&B#nnZZE;tLZpnfkR&ix z;Ht4`#8qYS?cG+?{_%uEqCD;G=zfvd5{>JKn3#yM2W&WM=ec7BaVTo&!N59B^c1{+ z>11GVP)b2zKTH>f$l3cfG&F-pmxbF#BW~xaaL#u^*Qc3nwAZS1IU%l|d?gl-l!A^< z4jY__@)P^u`t=K_KBJup$}x?&)eCzFMGG8uMtN>OLXGKe-MU4fSc-}VFlFo!=&|

n{eKN2UO6m_hWq&$}MIFhgD}?KeT1f zk+cgTCegd&OF9o}>$CuUK%}taQ~Yp`fU9Q|4AbMjFESPdiChbp2;7-m$V4%~N>4}` zJ#naBVyt^l*Pttls1OuKksye zkiqCafUB9nSxo=ytYh_aMr09aex6tZlzf|Brbm;58t*bBE-z}mYK??eN7Ur?-nLoRE5<)7Im^mw(r> z6SF-9u4l~X0M$EIQ&Uoi#Zs7$h%G4iifk7qG?9MES)hy?GWyj$m54rS#A?b-*FDNYJb)3>cdxHP7K!XZ2mg|uR$I&O0 zegb`fiuNg!xaI5vL8$H#bh}5>C8RXU-TmMT_=!-O_K)H&eu}_SD?nJ7W_GglX&cU5~Am$XvGaq!ViV(L9_q zJm$OTtZu}su>)kZv!e?=k*-mX@FC2fckS3{)G!sHvJJ07}UWj;zqB&Wv6Ng@yP%G)VPV$#74CQzPQkBHIh*@^>e_7iLkEpUU4ZRB$HuDa0m$*jD%TRw~ zpa2|qij&g;k0w4NgV@^v!3{0`i9L0zJU0 z0m#Gdj@mXryl+tTFDU>g{D_8()w7o`iT;=9mrxE@)=f1etk3@Muj&An&7fOhthlT0 znOsf7u?AZ5*w!j|(4+Q@7M2qbTXJ$NYzi&$cHtcL=(-_n^H)ta0!IWG?)r4zbq=tI zSst72m?RqDM8A^}gAsx_G4sFMqx6&&cpRvH3)958uSvY0F1;CgZ3cSXC46&4s>ozB zeH(4S+TwQ~YffQLp8*b~>Ef;Tsi^L|jHM?rZHRW|>5bW!Jplgq2oM}PnU;9u#lW8Q zlvB$38ICfK-&L}SPsoxD%Aou=MK@ddZh5=fcFdM^*GZM~_EG1D?E9Z`rjU|1DXyxX zqC&6x{KX5;7E`>UmD<8>E@^__ghEVWZcy-|0WUqPL{ve7a|3BK0m!55S5A zr+(hoM+E4<43fTi<#9l@a>dj}@j&k8ciCR;>EnqG85ssql=}MvFRXU$b2_(g`M3Lb zrAc`!8*>k4!lL^5*)al*BEXUw2FDv3sVyQ4Ta*@iJ(=H`{fb)tBxkOt?Kw8i^xD`d z`Ps9#jhkX)vQR=`zWhmq3&Dzyox}3xHAY#_3YK<_XWjK+R`o93xDfPvbIt%`-IF7N znBMlwgl@YJWt$PNVB!Aqtw0F~5hJDz%FSH>S&5sDxZ_s-Ml|)(IzKbNtaVXOU$v%8 zt~EF1F=-+2YAvIXh=P$|mb7Ctsqq1ta6gjRs7< zPxM2Dv=8q)Gm_`dj*%sGrO%b9)`Mp4GgsBzcPp2R(srFKPo6Y(vd>JsjKhqzHljsW#H#eNj*Ki zz=hND6kVO0mXrqqW9Z< zWoN<7GlFvCUQoyxkw#wG~(!29=D$3Y-GK2OV2(AI%7cXORu{>u7PZqQ}#aT%*P zT7ebGlI~vkVK8~fy*R0BbGSWD=7xh~4&z~u@0NjIT@;+13-*k7=^YmrkAaMxz`fRk z{#QwB+uIMJCzT0pG2{O%(#;&^FI~%EYVoMjs`|47r=|He#bL&2F>w}S^h`M{>i07oO6p}MkTuZcSY)wU%<(J^5n@!C3ja(xh!*au;mV4 zy_Ixi;jsCX`<6<6|94bTd3xh>&Ah)D!%1AwVW5ULLM6djaKP;EMN?{v@I}_Hxc7{R ze>+w|7TbB=c6dLE18yp^l@tFf#-S+lVM6xiHLMG~W7p5OTDW!dCpjIy^+#&Nwdmz zi71`f461$KuXAtflih#m!Efg7&sCD-y!M|*w=hxdcs=@y-MIv4)=6+QKvzNos;$xK z*@|`~a>$v+xP5Z55VF}n%O#vvQ@v?%aj{{r!*J-=-mt|ft31W3KgUjm2T-Ky6_C`b zZn_9qEgftI`4BH_WXMyqrc6`I zaDDxn(dV+!j4E0kGoE&~(zqU3(m!nQT+>ipY@ty}meF9l@|4co{O=AHD=ur>ovf_f z5wUM5uIh*+#N^EmX5M}ICHzsVxc-)FG)c)4oa_mf>z95_^f-9z`>e$p8Pa1Un&C1K zBRi?Ex3lyQRer&Pj=giceoY+t-QltQL_C9dhovgEV3<4V${^s7M5Sy@0k9L=M5JvA z79NopeF0#KYfR|BQYgukO-iZ$6>MalN1 zqEtG`*X(>h<<7vLpVkjtH9GxlIb3M!joDTgKHhGg8JQF|^K;=%!T#M_-q7yLyjnlf z*5XFD!cA4|6~dOJ@?mDC$E!iCVa=C4yL(h_r-D?~tSQ~sL_?u+KtqyoEwEqr+1@KG ze7)yS9;3GE*Jr2M)0<4>huMt$cgkH6e=beV(0(%_CDnvK_u7@cnu!rB+n||zBu{ggYlsEVW({hzPmLUgsHboGEL2oxPZm_GVD_wInQAWErVRdBR%fMHDZVBs0-xWb=IS4xHe)P`RJCLB5 zAc7@Q$o?`165>NYR#gq5TDNN9X4?@g;-~phzpwSnAN()z_zMc@yH;6z2mD<5~W` zZKA!|zf^W7T{$V~yj35k@IWF?6Zi83lGS%r#_tZb5A=#T0$tofh@Aubv z-uH9f&+|Ozbjp3-zj0mPbt!B?079cL*BM^TP+eANK6Ho@W}U%M`coycFVGMRbg(i6EVphT~=XiH4i35lM- zmiNBC`lc~AW6g84k~XGiq-AB1QA5ZHzY%lsRable`=IaA1K#1Bj9iKfhyQZ8=GQ6p zF|H*2yw^5axkMlSC;0mty~L`8Ln5LoqXBQ2Sv&fbMm1bb-t5lp&%Sk2QRc@@sh-n^ z{duV+18!ue=yu6;ZH7EIdRJnM!5x!rHXbbPMWtCu@&<7yzPC32bl=?AabNg|%2O}diC5+$ zeJn5HEfyKYJVJ%1M~+*_UD;dtQq8`gKA&a7z;LyIp&KjLxyB`rNRF=@??r2?yUmlv zwOl0{PL-Q)*Kh z&NR#2vnou^yDNepIMFtosJc-4+xIDki0_geuHNjD)Gy_r$@IvpqaBc%lkDu3bnZEp z|3C7y+P*2f7#wpgF*M4`zJ6~YJ+3duM@qF)@=ELRzwTF@U)(WInxf&I-LH8|xz6tH zan*nmaw8VS7Yl!8QkHLQY7ty_=ne13ceZSs9=itBkE9@t#T#D0(303T}ylHby>+JCq z&zqK0FJH*BFLLQfSqfMCyJ#qh-S&#^M?HL2lMN}j$& z<6?&+Mwci>vz>i=tlp=!S<(lF>5hH#nwr|YO?21X2{1YqlCe(*Hi57IAE~9ZeYnr$ zW?J%*2kqba9y+caGW_xLt54L3ndzg)U3uG?ndc9k`(ZD%1{1m2C7M0zcJbv>M>Zy8 zn!ij)8`{dTWTWX}$|M#j(m*D*ZTKRRJo?(bVqX9IZ2r}vw?6J~`6u#zjRoT{p|mC@ zwO=%=$qepBn=(5WuUq4i$-Gb(QkBk2pV%Eaav&+W8-2Jf>_Ct0A#(^(6y; zM^R}X+A(ek&JUULbho>BmxW%M6uj^A58QveT8dqG>cW!sG0~KP^zL6tmtDM0hLng^ z6?T8oVd`#g9eQARj$z5%zAR;}){hpW_p&Vg58IW0%(BRu{29=lSjl)5ex$uKj15Oz z_tuo{H=v{2sNc?#C+xBI(Jfj&1Y-k5+yfTM!`9%Vwrldkn)06~PoE~~OzfU*TjQjx zRu(-@8*G~*U4@&wlm4}94h03fmrdgt8vk5vSB@UJykBpjS7rOpc7y6N6+9Sk7YfeF`)n$W3{{PT@XC0@j+CVQUz~0MXBASyHr33;_d|5oWsQ!&pvTXqw`ntq zD&M3n=(p|uE9_9SWE*ib*!|`6ryXA?+dqcHN}Wi(y22-M`m~Je)K8aW*5DMzl3 zI+;QPd%q@T%WJ(R+pi;vybkK?pe_LSyImt>{NWPg!Md3jo7y!v?+zuFPIXgli{933 zmLTKU@UNt0axHww~q0ned50YJq7f9ASVUa3CHCy*vjN za$HN57iTx=FQeZ-lyAT|1UZGg=-?y4Rs|zDsRg#od5oK`#RZ(MIVr(TEis?i!%N@W zo15Je6Uelic}G%g=*8dEn`SrIJgBKIZxnd8#A~mkEctX*pj5dSV@wg3?Lp(;`#J8d z$vLg85t3oXopNMwb7(|HT%Du&;N|qJ@X1NtO^&~xf`{pA*&MgUlt&>iCZq6Wf@Xy)+1JBz6dOD|nAh}mxgm~NNXXl>$Jb2z9r&Zz4 zwZfcC#aNb*xmO3pRRRsB_uBLYS6i51TEgP5qH{YLUo4Khe{H`~xJ|fP`P9nP`(w-3 z(zD7IJF*;l1>@$2Zf*DON-6P$1ZEU12Wf=F#(??n;ODPxF{4#V7#baIn^pgR&T%); z{5$vVjgCpkims-<7)xzne?KPZVb7jis_V{?v|KYZvUkHD6+>&FM}hU0!6*R5978ar*1K7nYVW>N^-u*YRmbw!Bw+ z7I(7ML#e;~4L8|PrfguWkM;iXV0mY zTHAi(4L|wg*(R@7)p+(SSg?sITHfDgCF|xt=D9BO?~F2`Eyzwk25^qW zb+7jLad$@luL)OoXdWIgN_$cZQ252Rnzr!0HF6&CMx zKIl+z>dG^n6@S~_dF_o`!i1h)wqN>MmHDl>(*0&o(Aty}2@tpef^+eRXug60a$qa~ zNx@>hFYiqZL_5t_y5uO(lUxGat@u~+8PIoe*mlaN{WkkWc#piJ`)EgBpdt7rxV9*D zkxyg5F2i?LP~D2Q%;{rJU;FDV!3)i^J1skJwwTxJvCb!Ua6B-uc{S)?JJ2$8-EYH3 zd$zL1{hDj3l5)GKltOE_w+si?rhK%gIhGNxpXjx@^M}4gWq?1`;-d@eIHC$^N2H8D zd45ImK?$hcI}s6nEf$9(_+i)uDOO~)o%cb(?vT3S`*$2EI&B{n7Wtow_O$eR(M7}w zzm{-N-?h)G|A^)R(;p)D-o8zH{*$dRT%MxXD7T$=U(bwUMB-FMxcK%1eyuePcb*?m zOr$99E1Hlt>7R+$Sokm6ha~L3s(Q?=Aiy?RaN-dy-KtO;OG|Mswc5fZdE3eCXJ4!3ySr=&BT!7=KVdE@+<8l8igNdEyY$s(UInyUnwN(ZCN4+$ zDXBG3I_QFY9j4C2ah#Q~UD|SY!+8@)gC99Nue!VcylJPI%)Fg0fKFIYa4n@sd;{w$HNjZVUOnEt)m)CJBK=}wQrTNfsp;W*8jH&HrFGlYRw=RD<13VwF`S(H|hNPPZgWh`%v4W-I-aS&}^&zx`?oa%zxomkC;C( zVvimVBJ(GOg&&vpo))?X1(gGG16+Q8r4M+V6ZUH&9(r5V>^Re9ue~}4|1hd2Q*ALV z*fPGFZaNPAMy{)Ojc-|7#);J;vv0Kf%C>3?0i}?N5$o&+ZE$tacdgr4V$kB`74Kv7 zNliXl!B0+pydrL#Cw_6sNjK+Q=-DhN5XsC1gi4-x!)WmOnrl{37M~C+q)au4`v66( zwa{%)xR33Gf_+5#j)megP3$X*?J`$qKmHI7{yoOmBWGom_IKh~R`#6(y{E#qx6Zjb zE$)wsh;XTqX+US-Qs4EbVxOLKeLmf}p3_hzy?*x&{FYyH_SdhLB-IN-Jpd75VyaAH z$NncX5WNP4iYhY3;A!_NJ^ojZ zO}-uZ<2ZGz*6`yyn>`zfWcD$?RO{_Gd3ITqMa_+GDAaFVyoVJJ&(J!z;?Dbz<>U6` zN1Qc(Y{Gu@f$!N1bShzzoZg#5S62nLctLRiht6Hdtmy-kjH44gFLI*m0TqOpicW-O z;k8T+z74rzkjn_E1lV~p=N@v8g0d|8*uE1HW)}K2SrrMnRPCYs-8PIbKH6Wy1|+{F zW|N13fr=#YGYWUDXqTbgaD#4QW^S(bg7^%WyL<>OAt!)%tIkvcHi8Q_Ryev)B?d#_ z2~}!y+8s%udp8lp5(xAiOxi@)Zi`1?LL|~JkE|bQ=TbALgWBBFN!{s!V3|E1)XRQ)9^pZ*o(7mR?;=9ZLX@j=9XzHOiE zBd_#jkaX;jl0hQTZiN95Kr+t-Z zpgG^e847L!^zc`)T!u&F67c>X4-t)+07T0f*`~nMF?HxD^f7zQ-*LkR05t^!X&45A zY_PWMzjHeE2AP^24!jA{%#6deeH(^)p?%sS>ts=~_S{c*P1enudlESklOfTCjA#ZT zFQ;7$#(DZ~5Y-|wk65~P^75_*yG`7Fpgv(d`va}jD5RMgjjxrUf`pQzzrP<5teu6f zNDQFBd}4npsRPnHF{1T`F1RJ_R9*hjfS)bDv+8k@^Xh!vy|mPC385tzMrV)5+;hx8 zreH3SeMWz1tj(#hQtd00`9ux*H%dN5sypOt76~6f%){=nd5!G~eZ9T6&0?Ss?S@!o zY@gHf8&Sfjh1RhSGTc&nb8-JHUG{;HO|twDO2!=Y_6iR@T+rco^wxudDrns>cxB0E z|JwQ1^69E7g-=Ux8~q|0Py}?{<`0IJaoe?Td%(+fKmQ4_A#4-OY;5KgjgTFKdxRF9 z{h*gex#s}R<&q#Ef4B;h=93Z zc`_`-Ww~+FrV%XLL_J5x@h@R`tYN`~ZP%jMEekrx1a?PLRW@TIs5xRd@9y|CZ4|^%Y`S4?WpY7nkCs zW2;_tbaX(f>#2yj;%E+G3Xuc*UHa|+`Ll0%d`~N?Ws1%=Vl6?vw-?iw+{;0&KtF>d zjMuVt&VWG=EH94kad;v(*;igtzxn30^;k0-Heh&uz69j*SiPxup3;FopQYQypMo}p zo;?Tx%#deN@SwG^bi5kOhJx6Bby!=Sojx0JSMg8G=Bi2)lDD16bZ75?Dj{?GQYoO zMXyhi^yJ6& zCXL4uFUrWs0AL9_!9taI`u}AG5&X_q=X$FH=*lJCHM4X{vIKM?)&-7*M zJ2IUL>Tp~gdgrbN5H)Sm`|h4;Rsc^^_^`iNJJbxcFxXqP)5UI=p<_tH$AQ+bk8}( z1?LW!lb#1Ui6;dib}TI`8=9I5%g7LhJWzhtF4l6grJo3R6QlF$KeoeC5(@!cQELZ? zx{YALEo&cyhchCkYU@F-=Y118Laflp7{dk)*M{q}m4+6u>-Dhh;A*tGgz&^Y9*Z+# zC434qP6<#)LtRG>ZoKUKufKGfhkDkH$hnJU-y&`aOzj4B(qYzf94GyfNJ)^^It#eqUUTP3-G!vNA1@RxB5x_CaQxuJn%_~^~E4f=e@ zJT&YeI>+oA{@uHqvaODvzrij;B=U1s7zkhvAGVR@2psz3a|gR2Yg@NTU&|Ar?Tcc8ixqrMD&Wr`CVEMf|H-s}Z}6+bY~h0)ov53k zuA#95X-^pHl%$nL^y_d&sztyhYKG|^cout@7$K3y^(BC}2VE(u9Vj^jS=K8lDUn}~ zX--@5sc_We2*jOdf)r-?pVX!Q>rgc!o``u1!fqYkUG@&jMd6(1`8tAQBO^5sGRYP# zNAjyf^A8V`cT0z1Hh%2ET*mwPB0Xk$oy9KCSiV7Uj8kI^*}7M%X`%Zg^Iu3iO#!;o zGdjK~3SeSzdV0XJAQanj`15C#PGx zbb5Iypg@IQ4+D3@Rgw;6>B2%5)MCMpVgbe%&>Q=mzp~($KxT`iC!cLsJ^o)V3sF<$ zu?}g?6BQUa7>FaV0PzrWKww?sHHmTv`v5hKOS-pu1j#O!t4RGlO5$yh7e%z{Y^8`X zK`hL(kFUPAWpGJ-&8ZTPIZkp^;3MqInsa!1Qm}M1%D@eEK855aqizro6>ZG^E2*$z zWMqV(w&MPCP#6-~HVVwXzCQQgK*@;Z;|!)mh0FicucAx7^zObdc8sua1C~tnj$_A; z6>QlfOxuU6`!*7ppa#dwXrI?II|GsY`p7q?e;1z2{?&%ax>0Nh8p))V8}Lhb9m+W= zh#wD@oij~V)~BOJH7lei-u~V{%Ya!*5OQ^Q+a(sfGj|N)JB7phzMQKVLKq6JCJjzb zHbR*Wb4llph284R7}`qmbEA7z&hJAyMv(0-o(6|#*KgEFbD5G(D%*M)KK^!RuHCM1 z{0(99+o5EwQ+UYJC*+S{Ta?U4KX^dq7lKc>a{kS#XLtzGs`+B9nD0;pk;?=nR<>>cdz`T_sB>otQlnx8{4>? zeEtBrXb=d<1O=VN)U`1O&Y$;9M4d$T?AZwGA@&(2p1V59^a)5x-raoOgN)FuGZ}*H z@!QYKcVS+6@`NAb*+QY!f`Ui!Z_pwdWXJh7z0+sUS{j}B0Xw>B?TwA3I78q;m$gvK z8Gvdo>)w>d0c;_&4dJ_b2v5lAk+tUzjorX5fHoUP1zb50#Q1yR{lEx^qQvd$Rd^Oq z7@|qR_6-qf0OjoX{gXPGJpvV4R)G%ekub^Z`%=0&n zM))61hSuN_{@2PhES7zek9YpB5?tU{|N7nC_+(YsNrTe{C{$Y}=5Zo)_8x>+10qQ4 z_JJj_Bmk(6^?wkJBZhi%ZN^nAFlv6n@0%#HXI?J>bH;aOI0)uawL5pDoE+FR@^t@y5}+*Sb?2GJ4|b zfL_-W6(-Rz!vKxFa`Ep%VR`UBLV(E!YHkS$iDw@X@JEG0ptwvFMF18RMlxAA{zg(8 z;VocboYqR%{2iHv2-f~)d%33tlf>#_gXWzN522!glZXt~ z!M&mfo8|7xMKaN24K&FwL#6xGAdXf3Dg%Qnn#$aDy~OS6xm4IVoq|dlYTU!{;h+y- zkd1%8arEa6+>a43FgBYH*{l8_s^4`=+g(1r-Uz)Z+MeccL@pwD?!KJG_`YeRn2H4gIMA1z*Ciog`dQch_`u%f1UTrN>jgQ zy|m8s${O$ZZ%@YiLt5n7MOkk1yw1q9PAX9~IhJS>5h*qOW#r|Ev1UZm)so`N-xa2teshi8UU+c# z0iQpUQnPl8{aACNW>%uM5Gq5vY*{f85qe~p9Cmkqrc;MA8ZZ^qEtS1#KZ*j3*&&Kv z4c9_JkIW*1jslUhYbT$vSeq|`B_~&roKjfGvQzUx?kR1I4TNk3O@AqrsXX_N{$i*% zKj$%f1ZD-A)xH#X4)H;FVWhqq0{+f;W%=(|Pf1Q&@gvxCk>$b*?U-CtLP9vkL=k|4 z3Xg538I^D>WXt%nzY-6;ayYzc?!0#Q@Y77W{>F5;I9Y1m zm+eJrhuLMt;R3T5h}VAB_$s{t4v8 z&hDYeuYO@IRf9kfbf#BY^aL@V2)ofZa!CQ^1>4r^Qvg`mrELvEq)k0y(SN6Obe7sD z)hxx_79eSx(pOZ-{kG*H5w8=I5hb>=5~RT}V9+lzLXSWjpx9>LXL+}67Q&)Ki6^-+ zi&(B0d91JmZAQqk1QE!p23fk&v56=mX%T(?FNV=)*yB46aW$DbGC8q;|q)~EeWB%Y*L9IXUT2NgM5 zjWZQhrtCDR$C!c-BfF5{@`gjxRO@*Bnf|oVOYPlT&}zk{;6a=U#6Dp;Uw;5V3G(3p z;f~MA*s|4#lX_|)u_8kjQ^XKCKgGi8*oZ|wGnN$Y;?9M3%i!$QT-bugoMh2P#7>`- zorGMu9`h5qBi~Rc@Cpz+ja%5)-Kbb$2~tH@(bnXS2Zqt7RMcLi!2|+Ta{gfUL7#1# zg#s>fEUDdOYHUjPhb7mrZyIXP7>myKWqF+scEm9Uv3a0Y+F>Q7)u@FBM@Ft=!t~rk z2O~f~ymLGyZn7YiR-f0Y`>AMxl&3zgOD^C1=X&+VtsgMJL?<;TCkVrzv6ayrF|o2z zU%7Gxg#kDITv$~7!2+OzR6fTU|K-D8yr}BEfyOg%?+hJ8`ff`5x(ypf-Oo!R4^SDW z+3tHH^fjbHQag661`z4c%n#RgV0iZM9m%y7Z;3J+`ts#cWD$TTvq)#P-*6_tj!FZ> zQKUWFsOPJAbT+qy1T#r)D0{k$F!wqDleLc8q7X4Bx=#1Q@u&iGj;jZ3j_e8^`(YPc zCAsgH7vi)w!o&%w^?E>fpRz7J6vg0CDtx(4`0xi3nM@pkcPP2J?SG=R3ke$oL$__; zT1)Zm-pz>3Depd)<*m;8|5|_-a7wL`tY~T*cY6KyZ8e(d3wioDvO?h1Ym25q^cz#fyCUQAbo%XyB)Vwlf$Sbw9H+v{b91csG3Jv<^NKX|AN4oGU?9 z3P;~>RHEfssS&4#njX$K*?m_<04@SFE_E1P&mQQDTE-UBE{LAIgi6toQ8rEcCf?-6 zgB)tU8QWp69{bwKp@#jXM(epc+?C>_HiS--&nZ#sHa607qhD_UaldA>q zkyI`|PuI8Nb$-0ODHQ9%FhCi=fzMM$gU!3okzgwOxv^6?$?-EEz@LRbV{PTi@-<=( zY}h$Qg4=;-xVX>UmY38sWd3jpgd1L|AAVmFUBeLMbP;D=7^L1jPM`vG0 z4BeZ;ta~_~%2Z%L)(}X|M!>=Eiwej^#WA$@Y*umWgbPiLIMez7w@-Ietv{S^dI;m* zbySck$KU0Ngb*0fGz-{4_jsj(9)_`n;?Ob1FEJcFqxVvr9!9%2HtTGxt!q)4j}``( znPY&5A8>_*L+dO!nn|~b!o{v0KM(Qdk#UAZ4#}q-2XLwOiF#zN=^N%s<;(Z*wFY=@ z+djgBdPUt(hQSKgKvHfl6HJVPf`W>8@Q|ogA`PTsdh&z{?;R<9%IfODIwsjMP`hHJ z!yTOZfTdYjSs~tkm1yvHmy9YckH6t{V|HZ1xw<1>c{};AXcAQL#XedVZFoF!Akg>% zhP}f^l!R^Z&xyoyhTQJ({P+PTX2l<@8B?kybdOBIkga$RPk+2+Mz-*WiTTBjs^tKT zLU&Gk$%MQG67IVPW?XUl>!?McoF^@nN05s$&UKg$>#|DvEp-wN&!1~O@A?5zbzIL;fTxk^}g7( z%AM8V-dZ|4Z@hhbG%oYfG5VTEj~}nb)~ZF}^NV4vVr$S30Bb`P3;mAWNDsb`&E8pH!P_y*jh@UZ@p(G1;=S^F05WTp zp!etikujl3@*R|$^fKCz7eaxlt@NTu1ICVSV&7vzMP?39Eut`)g%f8GsWo4QtD@rK z41!GT?qW|5lY<;J7*dND8B#QiJSW75qU%h2Rg!$Ma&X9e*dg;p?mV`)zbZ}@B>9`B zbZiVhTnb_ZCx|uEy~#cFYXXgPFEwp@J?e1a&rHp8e !+LO~7fCp}9&G_7->gv8J zDJdH5?kN6k@)^drMw!iGbl(Notu@cj^DxnpK~}~v|6}>%Um59NE>p)~N1JWtG2*{tn!2tVT z?&#Bxs)Nx#7eGa(VHq(1ZNAy4&y<1fXeNk5Kfz7X%WbB6;he|Zg!Ux-PE>fVx`p2i=lKo0Pg$rq`o1xUGwwfnxikfYlLI)fxa50#;o;FgI;=uSD78 z6wH6G&Lppk=>|&qYUI?IikfiZS|!_xm^SPpPsEdX<@iLeb?zc~jR~n3(w!5P!Vs3ydZBwqNiIq$!g{mXH{cAi z%Bcv1Pr16Mhf}fDY8)WN>~P3#69mNEZWz^Vg0Yx>s%piH3?VLsBXSk6x{cAh&#M66 zUDzM58AN_}IMd1as=+T`I;L`ZS}-1#7XO4?z8*nJH)>L~h18O@Dr>m?H^+~kw~Biz zi#@C+jjM~$voO*XFN$}aL+^tirNLJPa>9YeTOXo8_w0b1>lPAkyG*mNZVu&ixCZC+ z+#_RO$Z0)OyXnLrcK3+fR^jF4Wt5S8(cBHMU%x<`4XmUmalY0Blb+A|7Zyqq$1ys; z{cw*0`G6Jyi;rscD*dPcRJ__kbpT^S&sDgi`KoDc-Gupq)u=ba364L3z;WaL=T}kt z)FXw3K1(+QE*fK?f~1yI7upWV`deJjRw|S zsXT=G>jJ>q8#iyRrU0}e{#rap$*(eCg5o%<2|`QpLC6G|8l{iH_joTPjYKLTAtojm zI5*;@HUjn`!=|u{1928nmGnB$kvLc2c4VcYPJ@jK1#~rue?Xi7VZL-HlAk^`foERV zbK71Ci5UzKzA!WRl4N;WFU#lN!@=xpc7|AeJ%SvR8!Kqn$O19)&&|r>X_IAODplsiG9h)$*ITs%LQIW(TIfB@$@XX znKeFbQl0H+;K@~r#!Mh`9q{BJHU4T0IlqBjM}`LC)5EG0cv2ALCKcrZfH<_ll9 zq39gyI6|0_)HR{R3g8N4ZkO9+QHMAjtDIhIt!tW^7|C28oFgBS-5b03hK?DAzr3J` zR)3tA#a@Ovm`Wlhv!*GtkhJCJQYt*d4Pi??f-%NwJ5n| z5CvpLgxhfNP8`n%x%v2#jLs)jV8i1qT#f3bv&?blz!1~09lj9gL|}L1l`k>`F$E!O zWkS2^h`XyA)_0+=F}oUn1REPHr*ly zV&>w#dLV4*xyDv>VvGl7DA?;%F~?~_>imFe4dRFS)-1j;UUTiEG}m~2kz(gkgl^%U z!ijukRHdCqf&rFOoY>y>Y0 zjJ*@5_4%)a(YOl7x^;0o@}vR@#8O-$n+J%9F!xdh(=gEi-Wv;()R-jT!-?9 zY-7^@p{Az;-dB&|W)upN#r8pRIu&uEh}O$N0XY@BhML zNc2g#{^PqfP3f>kuT=d-iuYev489EQ(5D?bZDS*f2%|}dJw8mA;Jpjilu!8I)8ZbE zk9{%cO1=|uN2eTX-a~&K@|en+!3_=hkbN#fPGIwMg}_$i%1b+&PbY&NMP_Os^Mw&7 zJcGQehsOaxkG?SP;roD?KfUn8LS`KPlk;0b4-Xao4W1TM~{tyo|H^f%kPTCRaK812lY2)Vk!cWLrCOM zK?=q;To4R4J8gEuEudrqc%bC( zBWEh^X=o#UF$6G`hd?KUi=K``i$P~VGdiaBrT$kSUdI;Za_#j6_=Pt459AtB26AZp zQKX=X)6_ZC5wkx2XE$bm*Sv3w`h2qtxNg@|j1{}ogmWb1!?=?hIZvT^N8(1!)E7XM zwHTGOU2IPZE|6-v-KC}`3>F+mXYoEvaDnNral(%&?mjoh)-xKmRR*KGzFb6gP&$!a zzI91%XLJMMUJT0|sFA?09)0wkQ3DiDT&u@b5W92d{{7eF(;ik+Q%mW1^l2+lkPm^| zg3fatU)`M6x@p=`fTjM49CwHCyCNeyzFH)8yo#FuAEmwT7Erknw^9 zux;qkBQ#2iNW4B6YRx5`gZ=o`)ugcGsJD5YNg%Ax(CHtXr+_UV{=&F`_5wM9KL8oJ>|hRNVq$6@cNYAw ztqeNMdkD3S%XEJuSLD%TuwuP;4;hTLWo(8%hKZehjAi>b!(A~>Hg&xy$ZVed#C-cl zZI(9A1nfnSID*a^jzB7+Y-|WRo_O*G>Tt({-hi#31Vi@_+St^_%F4p>0y%SWpVm`A z_F7n5BSC=4^_{iUb+a=>Lx7l(I;<<}@5bXQLb+yrcF$T0LRzYkOX9Y&r1oXs&MT_7*nO}5_}u037eFP^r2`YZaE1+0 zB`<&qP{(Ut`r+t&gml5k^2GIGTXb(8QuIP{~)6Lhf5lW>! zh@I8D2lyL04xEyxl6w9qp9dL>2pc9AmQO6KPJLS%@^K#$E!Qjx=}xCfLN^niX04%g z1R&~537!x{{^FLu_h>i}FUDk=Fjc6b3I zK(?$83C!e>q$L<7uFtlw7+oNWZIkJ~1aAD>K-G3|!lGUs92^|Ec0)=eNEPeX@1$Vi z)jvv!Ojy6$P;+2Db%j_@tRgp4=jd-`+GcIfOs%xDb2s?I+MZ8J2nf)idd8uujHh~{ zmDV zZYRxl=|hCOU}S{AiHGmzeN5PCFs7c!rutk5YzlrnD=Q;td#TenGx-I_{Oa#~`6TR% zawQZKP!a(mOP#-lg~voYwsgsrj8G!)0D$%@^6%d(oxXvnMRM_ad3jM{V^dDx>Oy%` zOuLyv((%u`KAXd+8x$jm;k!;=KG4J$&%yAgWjd z3ax_j zhaVq5KNaQ-1sIA2oy`hVP1-UIQTOlE#(vW&6*2Y>>7!iMn{1G1J;0sc5cMyCb zte5T7MaRa~Qto<%qOsXauJyftzYH_Jf%jhM)*mQ%cBi}V;Ne+?_>~gN`!;#{B;2aY zW7r~mo4hz$4AM9}KmK>(J?nWK80gyZ<2-2GFKE`WS|XFV)uj0 zy$M$IIl%Kp)Ii@9{*XTrY!vASJz90DQEOmw2i9Ui`a6QvL2uJ`xWk<6cG6cu6LVf# zy=&vj^vd6Zq~Rj?7NlS11G{+2{{hJzXyD+QS3Pnhpv|6YSU&2ns=YPEI?FonKF|1vC=ih&GauzyOPu<|k%Jy9gB=0UTh) z3BcN(uriK!bQ#6Fuza*l4) znUH?(>mq80Ae5yh=+=7IzOuS38OyePZr+`AG-pF&(2(LZB$q?bV`S#KqG6gf2S5|!X01Ss>SI6Jmbo{jfNS@FQqJ9^0EnG!Vx+%JG-iR zPC+m6V2U>edM~52Pir1zRIHQpU2GtoK5QF~!Zfx6X5O~-tBU6Jh_fKQM_Rh-`$Y2n3Wq$)j^Y+;Y*wAwMSB5vc!(c*Yl;DK}dR+?6R zHF=X|-ur_L8Ub?mK}_8(sf9L6mktOBZW#g?;FTQAg^`#-V&F;a5<;vMQ(Do;K_*hX z^wJUpB*FhtG23BwIcC&eKxgEJDc?vZWq@o0*bZWSR+BFeGKKtfXtYaGYvW{{g|HN$ z9Lx$^OHG|vT+D_fv|5P6%Pjq^pw{3K5_&5%t_Lm!zosNsWM9m2edwb|Z$my5BB7_6 z7nmtH?`NUkzqvT0tkE+1tLGWik^V~ z+8xCCcQAsYRs|K|Dgx$2B`L4*=ITIWJLL8Q@p&a?-}pdg6Y0Egy&k^KD+|(;Pfo7K zwv`1AqCAK@kG?Cr4W;ieWQ8On4ATn##Ci3jY}f<6(3EluD)(=?SAV;rv)hG@wmiME z%;;WGS@#zYs^sJ(iE#9txc3eEpcMMYXW^7W`vO!G!K!QUHa`_F9z-=0(T&iG0Rq7I_5YLT|ix9Q&druno1ifpkX<0g}=R6 zwetHQs8J++KdY(AfU42&xIhhlaKrQjW}bLwa6;wuQ9RO5+bp5~D5X<0$z#Xu00#hd z^G6Pf#k1FBLm(3r>J&xZJBnh_NvL*k%BX_uhe!s85jsntI$%F<G*eEs&+IK79Q}l;8^u9`| z%U%;GM8R>+ZHRhoeo1#{Xje5>714-hm28V_Cr~S?Nub&DQ3W&}7+!_SE!S<4Ooq za5nP_*yfIjJV5yr67Y^~pck+ev8?hghyf&RF-Vp+6RyZNR0!Tj_fMg8L{3kG)W+d( zv8_W;PL3117mbnCybMCvR~G9JG6D4cm)-6;51fKbYr^3|FbUC!Xrq{uf=+M7Z`S60 zwA_aSa*UTP{4noEtU`a>CywRvVuqzJbUyAo{~BT8gbF4cBH?mSvH|48K(cMvAov>m z%_wZp*mUZS%`UEn{VP>fXrrRSOj-vF~S2Y$TUo0^s7td@zDzt%_hw`e6s zj*ycMMOEO0ZJP&9*L5>UEd?%g!Bt(51%iD> z6soB?8Aq<3*(3D!7yzZgiHQ(g7gI$_xC60}NTq;#9x*^+ATSV)%>p5f?q<_x1yBc3 zd;o7BP5wIPK4%-jq;#W!4kH4cor~Jmj-u`4=H-2?yuFtEt2-aMRY&m@6MT}u>x3S# zQE1tB@ZbPX+kvW;<#LUVi)YvXgn|wENM9Dy#O)muNQ-!b#H$_)&B! z{MM~nL`asM3j#JmWSe$~DGI9H$+Ets;L-_lGwlC@ZvJ1hhOlG(3io{oBx2gKWgT#~ zjQYvmvP~pUl`@FiWy(&;9k-UWoBk-tvVQ? zdh5lbmZUx3!sMDSHFMA12=@K55}P|=lxi<)Zvz%OKGs1)79%Z3Kz|YT0Me=(C||h+ z1!=J(m}sfU5#^-KVwo;{$9+lMVQ&-9@3#s2uYG6wIx*cS{p|m>0G2H!SI)yPvf9GE zDjB=N(C}SWPR9hQ8|pygL0FI{cN@Mnl|ZCEMKL7gH&W7>LDrv)S zDxGxO|Hsdd+tu;?;Qmw0C56)=qol+c~C((a%)ZOOHRB8U2VS- zk7G4*-?-5ZfHTnuunquwl%a4GxE=&B@#&Rl3kh(ou!J4%B;cF*)O2ivxCW>wknJ-=4D|vC3s2;m8Ju=W7#LYz)rDK`)cNyGI@>V{ z@WM+!YTd|!oShi_1BNH0Ef1TJ1*9Bk4X2DISi9UHp#{4Y3_%kIxxOGhEd71m&u<2l zNz#b~1)xdqH0oAS%&4hpX*UGS30z}nJHL1Q_HH~W{sR4`z3%w8bSSuRP>~^(1Bs>d zfyPXnoOE~8{J(ws#uiyhy?WKcxy(Uug*a!8<$yS z*1$%%Fvz1^DsHl4SCRDOd*UcZdO4r|6nM$c9ITuTyS00B^+ZWS~><$*JW!y$s)%Nkp2a{&dR)GI6aUUqQ>FM^E zLfMi@GYoYH>ZI86c=R^7W+(b9-DY{COXCzgWpSs1z3VagFpjU4#e5leyMB>nn}&z8 z2J3mPG!})G9)b0e^Cf6;fqg!o%4I`2jxT)ySTGstIraR9Ciqrjh5?pS?Xzl)9efu< zK#8SU*HZ4^Qn~vH0w}{?jf$!C2i!6p$N8C^e;?gky&KzT{@T%R;l}I$Y+;MtZdt^E zyBQEsuas_p(kc+Tcwpc+_~936sGz5$%}gG5KFiNs)7QEd_Me_KRB!>f7kF_tq7ldE z0>Xmq-c>c?_-=i&GCP@QaeL84nVr(oGAVbqDP|@BXdO{Dx>xk42U}gZ@Tjrm0s1aR zz|^-jI-cJ_-X+m>Aw=1rd}pvGP-mbbxu;FNF$Kh?L$~+yLkGk_)}a{Q8hgJ7tp>Wa zw0!^GX82F9|0HUMkWeK=_Sg5a^Hw zWqT$5By>G?^Ivu19)=jRf5UBxsUMFTJ8T;W)eM~^6om(Ve=8vDWu3{YhWspny4aFn zcj)#+UZL(cl0MY26$C6$YFbbusP>3qKFG+kV`83kmIa_f`<2u&8J#kWS%TaUnw!V&!l$;fFv-O${M>}*b!t%6^dsdnf~CpkkYRV zzY4hZ-oXN_QN!nM8}%e4hMvwH%1J#uck9;m4>fD`vP}m;t@Tnr#jgNlu?^7M477&m zlu)OVuYzx%1oc(Z?yhVU#F&1;eebCKukU6VbbsP)I+T7(5QOjvfJC$<;B z_eY&S7)pY40_E=!^MS^upcU?FniKN#EJO$^a=!9G2E%yj2fx*eLH>#Y(dQTT zNP75|J_ZPgKsmJPaU1e@Z2*Ts7odu-*ir0nb_U!xR!PRfb959$?1A=PFW6ctu51-k zhgL>g@5Q(dNp|{4TfGl$#8Xwn4TDhT)TZFWw~r=sos0X|1RI8F3mri_Ni;rObQ?At zLHK4HtGEG5edrjmFRGzmEmfHfdkh6Nb{plz<0Byy3Mu{2OT%VN2E{eIQMl10pbsa5 zN@D9yvnSv{tc+79O z5gdHT-2Ah1f)##qBy1CLA3s|`%Z=d&TMr8eoLiW$IsQgw*bg-U+QA)Pw%#&3Gv@Rx z?&yOpp|9d9-I}|GE*qUf{5*x=>%fkS$Ge@j+$VMQmVK5iU_xx1Gl4owaRzwtLAV7h zqn-pCJ5(0``8}}m3XGwf`a2^l3=}~u=dIKHpDBY7h&`#@%42jK(>USC$OBQ>Fv%^IM2HCk`o{BY7BkHK)%{P5KCA@*045!sgSRkt z35ZgL{mjo=ae5SCkb14bphN*MF-yVyvC$cJK4 z0vab;cf~AS)BwsjLb}bjG~aESF*+UUB-@* zIV^G)ImUmeV=3a;slcS!mzYUx!D>ULef3tlGZr~m;95K#84yv48SWTtVUPa&0)$5B zyhr7>D&2?&QvrEdk7bV)?ijtlgMwJT0a@CYtg^Qpt(A5cXj^QZ%CV$iE* zHef6ih7*R&9Xh(YWIzKHYo7vffWYDb;K{Z$S%>$I6CV2C8*#dZyBRqdacy}dO<`BY z=jAYC_8W(J56rw+qr2h#n??i3sbFj*bERkllt63ycfJl)=+)EJ1(I$cKZVL45EWpu z0#`TPw;?wn?W9n2%*+_%7ec|=P$>JxcQPFD4p-M}h8UHic<9h7z|7y=#r`4o7h>KI<6FGAE0`ug{kO{|}$r}^q84Vl;p;0{o1U5FGYW>#(aGri!; zbZH-kb4^t*qPzL#^`8)Zyd4*2CXKKfKQq8~Xw`%3Q)M+F)Wj4WAX3YR43x4j{`x*j zDso)Zm)8sPh$)G%mAF3#R*o_gW#UlSJ=j-xd8{ z8HN^&kUC4mfS;t488TqaplFn}SvjDJn0YSPve(BP4=m|-r$g>Y1db`k4I4J}BEIUk z7c|`X-9pN3#MvR0=IXzuX=D)c?5kz!))}6h3T#mjdIwaM3`rRTj*;kB)3IA{)S_D6 zs^HPd^W_O)XK&kL!LGyUr&~`7MBwmVtMk|RDpDZegtLqlO$vdg78%|QL0L=CNND#t zl@f2`$0@z>dGfwAhHnf_PTDwsLnQ+TL$Rv9jnKQd4sS!0K@d?WC?Ov5@njRR{KS_d zHwu7Wt)dwII$u}7cal_zY9%{R()?MppK^h|f}Tb>dVF8UIq3I@oULKh4wEY(EwYDy zv9cz=43bn-&s!v7=rP``IGcI68Yc+_kkiDoaN{#1t$?u}qb*Xn}g z$$iIFPRA`spB7}1_Bif1UG~}LC{{T!rkp$Xu;E0QcA7Q>5B^GtgJLsGCRc!^0c!e! z<9R=TC&1g}Y=`xud)_clzc(#}^WS~+VUjF-)V3#4r4baL2QK&e)Wte+dOe+J)I4yi zQeMEg$WYLA3;);{{ukY*J8JyW^S&i~%U(MiK-%BmXT^4y_f&|ePGQ|mruvN`b+_L> z@d&bS<#5)x=Xi+c&`IfZgWf9=v87arhGO-(8*5IUUg=Pz(MX~hc@yyo{yKb!fj zY?0Igt@Dxo0!ib6>aQk5JRAF@J$#I|gsK35!6^a1v20-zv%L{^+U=v|?5%SWOhaQx?}Q^*9eZ8@!Ppe5G@Ptza~8-Sgu13orX;wpxaAV6TGP^VRNO zny`<%cPsOUZO@MP$3)nEaINM6SlLT84L2n2J=p^^|DDz@C@NvvE9=3(i9@z(y#H|a z*J*C7H4Y--0 zLut0O6vpW_l~_?RjBN}n%h2R#X!oDrJ+exotf&y7$Vg>8HrdHaDp|>U$82~y**~{~ znA!nRC&*3+#0}3wMpPVMn43Ej_)ljtpv)UefKe&jbJ!n+0VTXrPf$N+(>?Eopw_Nf z|1fS<_Z$FJtwHM8zs7kc8+q96!dlAiLh+h?ORi)IHFhQk7`MfBQ%Np- zmG(k0`SOt4PJgy<(r43urHBoaAkL+}@#==oyOOyO7k`?dt{pG;KD`=}6;{m3*|)qH z8Quiq`Ig~cM44~O2(n01tRy%R97l#r?ff-6JNoJ8+ECFm16XBTzH>B_F(A3Wv1Yx% z>!`wA)k92NZuby%C$r12lnG~)1M`u6dFV8ScJ1tydA(P)E$Jr4M2-oLx*Xl`Y+O`a z+%B*EF`E}=TL^d#WYrmC<4|I&mhiZSQ2h8Q_5UuvGTO+s%k!xcn0QZfRM8ByX@F;( ziZg5}7{O0EFM9QE$VIMubf73OtjES^G<@mFo?qU%l~@e))}r5oVZHNSjDZugg`}_0 zin>42?BDp`ix~>=_s5f|9SgGsQUgNgf9DMQvCx_a7`A2yXDPPnlqJZo#BQ=i>*&6h zIe2}xET^(#%hNNR3{Mnq-~PPude9(y+O3uqFmt#AjW}nt04B_#8N?HjzWzH`tEixd z@xRjXDuO@>igpiKTmo!oKu!96zbLZLf)#3vJYAVzhHHFZOY${s(feg~SFXW+;u=|= zl;mi3ktl&M6{vA*Q~A%CnJUbXVXJ89 zYWccw)Li#42CTcA^p9_<`FWxWx`-G~==Rdmvz$kN{2Jc(IH>xvubR-U%EY5z2Bc}z z@1}J2L}D-rIY^f2<2~@EcRBa3b1CIPGQ!xCVo-{A@8{x?RRST&SNu5aoEntP z)M*vlgFv^p0mK|mE-{S~3aCO)%O00Vxd&SuZkGI(o+?6t{j_M~{?`3+$Lsb*>C<8u zb$a+zn+BEIGtBahbU?WP1aTuL=UWevXK|z51-l?2Vk8kgKRL|C036)N|KFnqYy$#p zUm&w((N^*%JJ5Ym{UK7r zU9KaP0#i4=p5uECE4672xci;h{P75g2|{us!j42#R)Q0;17rN88A9ux(Ju3A`M)mz zEN0|0=^%IYR7^iF^Xok)4&Dm6{d~8@_CgJ2eAX#<$P~UamXd3l+AS)deJ;7*Zt4ClB38Wg@2L6(Ac)Wt7V3|DAXb*(7wY7H;A| zmH?BMaLn`yH5R%1>%05+Zbo0h` zAf1XKO!xuRWQOsZ`FY&5-z{=k>5{85#vOO-*8%AvUds0;ZYW-l25_Iy%4=rg@V8n4c1t zp-WFwQ!^v#3bF+;90M5_>lrtDWJ{e!BMjxijQ3GDAf++}G?wtsBA|Z~Vca&Szkhgi zv^%?geEu3#RGZK?krdb7K>3FcA9Tcq2|*?}h`39Nb)&`r41kG zw|)9pRogFh@B2OBr{phKB`6a!B}-4*X}MEG#D;SEl)CnlS0=CbLWJMP1Q%xz&4OqZ zNd!v*@n-CB+6qj9Jleuw)aHq?3aYjCb7JqVU8(KwkKhT>^LmnSFy)T5yTR&5m(25i z$OR+(YnOr9wJ!K^qgLVbv%Q+1GSku^r)2ObFH7Mgt|*VYh@gcxK!Km~X{)!(G12b9bhZTW}g-qX%;$1!K9xrk{j z!u4VeGBERi4zyE?=bgm?NY(3cFpa=gA~Wh-c!q*3D^LX^1|REX5ZaJqxQk;^B3CN_P#=N5lIXo;}`lZO?y1mgK1_a=Cf7L=>yY! zz4=T03+FD|HqDi|CypUCCC^7TJ=VUY6H_?0$dbto#}F`x?(P8+gO$A+0Mf5kzrR zuGRJ;mhUIJL4R|CP%CY3%CUKiOn zl^kPyZ9QR&V7PZHW^Kb(mz!5#qkD4L*C=>f@ERSxKu6N>?f^`v=hyc1^tgZbtG&U_ z5_DfX_0Ha~d-o>4h2Tbi^3xTE0v zH+->g>mC{1Pz9NzdoWfexzRJx_VVSb#DCq11CRioW~W7wyi);#N0gvFa?IlOPp02) z^t`ShlK*njIQSQLAe18sEuTM!LgSWft;rh}RK&Ddnc-&UThv0vj+24xLXqmZA3XSC zK8{Mx#~VDi=5p}9vLS?0H9jx+iM?lX=VVER^gGX-kCOHmPo4NY9UB)ni@C5t)Jkfp zZNFh<;576;s!Y^9_Xv;l!t&3V!-q^A3Wu89Pn~V4^u!bPQiiy-^??q_sl5L**)2u~ zIpvx0vxB7+8y~+)_j=9ecZ!ORo1gjhYvI$xZ?FEEZ|jbqI8mK1o*?_P&tYE>mH_8* zPPi{Q?DLzrg}m}LXJsts>#QeRSUmw^egpiCS1tHikyPK57}PcdkD8{Yj_)OsF8J(f z{SYfnPEP**)pjatTt-GlLSDY&PKKa=_@(BL%MtUJ5{7Rcs8fDUq2UbNE!!Po$|*7N zhCch#)2PA2ujIMzB^Q?$r$pI5vZK3Kef&dXBh_2-N7`ko62t7|EgP1)N1mSfwXjg* zP%t>O_2Qc$v6v^L^XK}{o|Md*A4Le^zEO$xlb_-1RbHlAkPahdEM)Q>cO6n`@BjQ=CW7MwarTq>BZwF@4kDq~)i>roj_4f%V5&Dhw@27O= z@JPG7E_-aKcQemwYnYI_fsE9@KolWo7kOCf%hEF|Dk?nTO0_rZHk)#SRxHK-_wYTn zt{(dEe9;LW3ynU3?WYF6&qg}QJocRX{jRM3cG1Uw8ON616kCS`#$3F%t=OSIKf8SO ztHLt#jn~QhXVz6t(<`V)_@7c(qVZXHdQ?S-r#jetm($=lcX@?)em#bP+y;(92L9*z z$n^9H5%yamAvl$AZ{ggwt@{1@5RR53@!GC#Zcm;*rPfZ}9B9hV8)j~2$8_-E!JP)l zl9G~NagLp2;)zi|7`S;X+wLsgJazPUH7k@JBoZ7!YOoKylQz3Nt1x53c6!z=MloF` z(y9j@^?jV(O;|9UUBpF|iYwfEg(oOFIyzZH2FI@1moc&K!zPb#q4g=&HN!uvhg>H5{tlm4});vaM#vNt`*Ue{-%Di|(nmHzn> zQ^SLaw!-!hIK7E2tZ1Y}lsJ#mH9eN`d-Yl2MRD=qkF21N#@4)kO+%xk2!$Wy zDH4*B{t)bA1C~e#@i6(>d?}Pq<}|V)BGn&NH_`%pm7!4y%1d zg=!}bny0ucb9wRlj~oN^0RyL#B9}yt6nz|5i$hu%wif*|lq2haEq^xK)H+ZfzoRY^>(P z2c`p$?z&wM9c=082{DnlZE;|ITw@XU#f4WN@gD%tH^^+;k0%D6_{G#U^$k+o*XZd7 z9QD5(sBUo+IrNzKo`L5?zMUR=PS!sQCmf8oad{2mfoiHm+ctlhyvK_rTxU0l_ zNoobWMs~(|4U?Z0&o~3A8ltkli*;_z?z0!KkIsDX{sL=9+q1Wq;g+(l}X-|($Z}{E5kl4l}8Vgy=-h4;U?F#H^;`@A(8b&Qv$6)O32|d z8Syk7k+mq$`B;0`OXHmRlntco3Vd6(i2hnaT+E;TURxR(%EE+Z==;NffydUd4Z#G0AKz}WZ==4@K~`|m-XfS0SxMuRi1 z9Bp|wG*rJ@zE)ynV#2?9xEAWB;=Z?u4~E^#ouNo4nr^w~9rx7;rO{`1-O6))3VbX) z^7>MMAuXyeMVd&IOb+k)(jSQuwA(U1K3+9)j>Nwy_`%~B=yNSr-v=om(;bo(u9Z+V z;DyWZZH%hEvZ}wBkypA+YtJ4MsntqldZ0FUtKDp`7|xeNU&+nY-(jm&ST)WNRC^PD zotGG%`TO^;C`&B=QVdS4G!H)JPdP$M3XJqAj!%lUnX_}=j+1_61qT@bD zsF|Pk92h+@ZiT@@pbxeN%lskBFW$5CV z)WZ$_%F-?i;ygQR24339+&ix%ePP3SVy^UAHWJ}$Mqznjv&h;?N=5oX+x|T_39^ z<6;CZZ6-C;wzc?YPpJ@-Sb;%7)y_P`G?ksy9h}xP5*N(T%T-lX5&VO1-sFURR@irCIHgTH^cmQIoc8*+PUT3`cMK_wV0B9I}fS`Cjs}@+y=Bd;Z$*DRsEb zV(&J;-bqytkA1?sb`2~pZG>l#q$EwCX{K>RvdAq{PME<+$2TRXXFrom7~aSdwC3sL z2VXfRhyJnv1mB6dF%9!0Ec9X9RruK{V=F1vf_gvvYjid+5H~qoUT{?kD0agdZfd&cTSHk z^#f=kY|=8G`zDJJer-fMam?&zOPRujmgsrU@rcJ3ycw2Q)7KMn8GCpq`O|IU^-Rf5HO(GaXGjr|hvsC8KMOE7* zGbo>v6s{pKde_$05(-G$Elt+3fkQ)zj__7+KI3_7`;v5aUNrD^_on#>WKqSPjtD^8tS8(=4RSglTiD#2VJM9{ad z`4_@X9z3R}{$26#I1JtuO~IXO-S_A5XnQB$oZMIOqAW^!>wB$Jrv?!)jXiEv7&jih zdMoNOJ9Vmdl)O?zs&!B3GD`|k4=vmd2%ug5wzaZrMykBuSn9DkXUaGBC#W`NuK$S% zK#)3Fi^lx0}$yuC= z>#EE+BLBG><&51scc}e7>d<}Ay7&=Sr?Igyw|A2K&mk+YZS+M=DZ0{*j*eKKtt9;m z#U46Oy-Y}pj{Ud(-nCnOjF(o4^jR~#xPymf5ZLKH?QoG?b+o+bab zK(*5iC0tXJHkvlP2E{Y%I1EU`itMVukQAdWHMO(^IGK`5|B*hXb6nP-ldG>8SlH3^ z=@#k@{2Po%Gk>9`^;42ObO=MBRFFxR&$Lf5qxKmYA6L0_Y1f3itfW@$%#1`}U|=r1 zh=yrR2ItkGAVkuXVR4-samKdips8>mazYt;TBxoZj`K z7*9*eeEH-F6&h_A>5yD%`SFBBU+IM$6SQ<3md^h6Ksws8n%v5^Me&{D0iVF42O7oG zJ1G<$rdgEC8QJ`q?0aDqN@=pXaD`8+P4rc;xCc+0c{&C|L*#*C+`pREd4d{kU1=VL-%of|NY@q;?%x9 z7qx0~?!8_0hR-mUAR>82y&*rF;(wQ@;2Grs4PG6FTSSIq%fHS2*!pB0o0d9lUUM1-@jP zlN1*hubN(b3M5W=z)+HFk4&jWtd*8_u4Lg0{*SGBqxFZ53x*fyX@-U>L>^s4k642v zf+~xSp57V!JM@Jwv33P&T>tscKnCc`E6(SuM7(>}Udcp4U*QZ9GWsh|IbJ6odaX8u z)BQ(}Ui>BFy}IHpzGn{rE=6`4&Xo1)vDGy->vVK<-miT4ev0H+n7@3y`Ny^8!M zldoIdwnJ1|hr$W}ymDA{=)GQST}!yTSQcvriAuHokor|brSN<(|VnQ+@=YiOXPRS2< z!_2RmQpx-IIbD_eN=xMu+)}h?mNXauk}^1lwX$@4wRhFb6wqOiXrZ*FQA z{7NkvbYF4k^WCdMMV^j7{!qw`d5jtC?zghXEsGg!V;9cXlxj2!s7JILWIoU!S1D%4 z=6#GFPMtmYg702fn1T1OyK&^@*js((gpLOW zhG(*6PP;)nK)h@~*QhLKU@Di4M)F1_AK_fZ!$L2qr6R{$k5dTTN?2If-K*PzdsFbS zM#_@<{H<#K1fP|wl7|o14!L0O$FnwTG{FpLd{FxLUD#DxFe*7^Tp5}Yy@f~mn(K+6 z+0)WQ#pzI3T)cIj7U=uKxVYXrj{E(mci&AH&P*pCQhl{*DnGmQkHbsE!Ake!bEj4m zZ-<_Lv??GQ#_%(66kFxUN1sm4zdiit5+%&sSnz(@Z>6+Y-<-28*&-TsiIEz;FPUo7 z#)k7gIGFZ>!iFB)JcwE>VNkr~d{WcD*|y;FyZHvjq9<3dzt(VBvhn%~|%J>j%; zojBYZ=mzFIH58hxik}u#@_FPKc?lO6X9KUZva*`Fb8&f{yu3Uc4HdiwZq^R?HV^wX z53AIVNtxD4NE|s5tSRh=VWk~g?g-phJ6%~OuiPdn60$DZGQH<2eQ@$^^xt)azBq?h+Pu0!{8++34YHMR(`mL5_?#u}OZBp#K`lcf&ukyl#pW%SVL&qjYTc zux+mm9{!VWkbHA2u;6&QWaei7+)Qq>P%kb#;|w4X5cG zI+tp@KTWlBK7{YhPIb|8X4xnWy;WZA$I^KNi)nrD5a* zBWwppnBP_!X~VrV%1zS;cG|)p|l$DsthdhtK9eBWr?X7kl;Of!_d`8MWy!D(JLq38lP#T z>Fxi0+E8nL(mkljPUls%`);}B3vMpRj8#Uavfr&j$#<5zCKueEbo7X7E3p-^o4KDq zqGsyk#D*jsr?8^GXU`sDvKm2n{x)IuzHaf3Y6^yfplajs<|<(3Vx3umQO- z&grCN+uGX~@*X{S(9csY6!scBc*C%HM=0{0_nBbbX;e6#9|O+6kzm4Q0)mBb0++b^ z$$M&NJ;9D_LS8R{YOJXDM0nPdHOR@x1`49szOlunh8tDuW!Ii0^hr zcf<#0!#YL{;w&5wN!BF?n3#qgiMDhGQG|Y>uhNGvHe~?K9Y@%i5L5z=2a9`|L2w5j z>&VJ@{@k*m`AkUm_?G}xChDTEUN*79nxqrgu9?{7Zts$~8=-WrwDS|RZV_R3>IW^0 z;b`0%5fvSfGby_>uJIf4knEkr$}JO&oO2G(?$4foZa?OpQTsQk7dEtb{#)RLd!^H*0%PDps;&2r683kx{_ zhGL-sQ4CDOQ#QG`!JfMaebr_?YIJd4Ue2)7C6%t+aVX{nW8a_q@%8w8G_yp57G;ZS zp4o3biblkcw6u-H%`zvM$+ok5)3k*)S=PRW-jccYSgk}z(ds^NaT64Itb7W`&>~2O zs-UVh+#AzgeBdI-*v~&LU%p&)eVLxV+tv#scjD}-c^!pPFAcawEe|}37~eGx3sUd> zTHfV2gUAZNH#RcSwRU#W$25?CRYY2DL-9xenD5^+q9q>n_lW=R9P|%JJJhnuxW0)6 z)P_J-3)~791=b0u;5++y@6=Hg66yz)@SwW79=aL%_#DN;mg48>A(rjs!!4U!9GK4m|~pQdjQbAHX<5u?qq)6q!6aU8sF#E$~mx z$W>-j*?W1(V!-z0Ninc&`CEr-i}h(_an`f4ve;;<$6}6@iR}YD@W~6KMXEAuKd2&!y4Y~@|MEGGCZML7p{`e#e1Tf z(b`_Xi)*&$f+ZC6<6qqIRP z)1@y5S?U2uLfuOQCltUuEL-RAHt^XxIIs}!0&s6liHp31`sDe8c9czwAQSy3);ko( zT|+I&(EXsd*l`fUCkg~~;UxWX^0PNUdN$S8zo!#4g*%x`_=n!*8%pW+X&xH1iW>KM zE1_Apa(jrfO-x>4Q}FqTp^=||L|NQ+r$QL;tuuFHQ03V=?^)=bwbf&r{-3+pGaDm;=EJG*#?$!!A>;J#;PtrlnuJyY1Xh z_)Mv}{TER^JQMa^yRw^M-FzKCUV(L4HsOZm34(9t-?R@OT#u)Uj86e$v^kxqom$Ls zEIc*i?CG=b-2aMa$1AR8ns8bf9Hkzj(BlfBe*-?zpiqPhJr?`{wV7q_v-1?I%=6uP zjr(o7n~}kRz@To+va0V>d(J3l)R|#(^jx-0r(|OYxgz~M#mq_HI_r^Uidnn)bGHZi z@tYOd39t2ZS-Iw|@!Q#HZVId6kKGa1rMEH$u(1Rcx7XrjWT&0o8?QaByH8Si;g-$1 zD3|y0m@%or?d4&JuKa9OU@!XEtEVleSnx}4E&w$UJz}MnGV$63uw_)z2T`DunjJO^ zev+E7Sy!jXe|mm)p$zvrS>nK|j1wxkJ;gHr!Td)0vUyptyS))@wb*EwSXeOdckA!> z@Ypl#w8SE)si`-RH5YRE>r|e&!K_DO@8sU{sPeNMX7U&I|NXb(=Dj+Hfwt(- zH9#x8tf2MT;aG9iw*{xjWPHaeAWD1on4&r+R(dASmG`2bR3j!8XMor666dALKMCLg1*5{tmoI2|J`y_(VxWi+5GM8 zAMyK7Y=8RnDKW5z>Jh1Zp)SrR|0mJFqx!BM{y9J}B>mGjik}anaYkjNAH!TLLV32s z|5GT10wlk@;%*r}CV_~6z@mrx6Oa2i>J8)y)Te|cAf}rMvdhYfE{yN!o4L6I30Rxf zd-BUUQL_HoLO~|yIa5_8jz;eOg8zgE3B@KysLR2>jQgm2G;pk$G+ z(oM1J>Lr-)2S8JZS;B9Jyj17pShdb+u`O=>jFXt~ZM5=h8}MzI4Af%Z$Urxc+dJT1UcEt1H&9h4 zB8kF?!aTWEcgpsI)e{@8v+smBqg6$tlx5&x* z)TsrdgPHMM39EllL-dC?THSB7+Ak|>YXo%Z2vMM-&jPMMO-+r1L<+a%J_rg3VzSGz z$K~T~EyT`6bS4w^2oUkGyxvJrui$u)3sS5JWRiyk#Rh{MYhp8fP(Mpf=Z4Lt>NWub z+rl%j?~5+ol}oN3ojpS`1Nf1Zl^Z};#+i3DCrU$!Ouifo#vjgZ zR+lbSZfKX>v*?yCnp?Kl^pLm(r&VEo@XZH}%Ivfwfx%8EH`uZ4+7v9*qpzRzc9Yr3 zJ7C*y*Clgud#Um1C+vqqp{~9@oIeyD9SPW}VATBks{CeUwTd$LNiLYh1)`)!zwKFJ zjKLF56qO8ge#G4VENT`rclRw26L`*ir9y~&BJ$p0pLa8*&V+w0XMBoB3rbX+G5>BH zMf2_fBzi(YiEXU{pjkserS05hfqAg&9XCI>`N!}ufLfE{?y8?J+qp4mjQYq`uhR`| zx7I<^5xN5|bYJgup%WgoyCAHEhHvJdcUKobcQ@31L z`Ycfz9%e}jwA2ZU^s=Q;Ldfgi=8N|^6wmW?+YuBA7%JLOx#rdGo~E(ZF+GO^Y{_Fwg-~Uez`jOB4u6CXk!opBG;R z!9`&J^+#OxgT6G!wi~gh)zswQCrS#|0f{2eAJT8Q_TX11?lbrtkU0pL=qwE)9r)z0 z`NNAwAg(dncE5@{?|&6wQ%}Jug~YI$Bl$V1f*bLdM<|R&XIt7^LrqpmOmU>pVO$4K zB~q;f-ssmOEK}{131z1I@!CqAu7E%u3UfwNHMr>Pj7>=ox1^wUSyNnwwRkheEW{IzJ~I)sf&79~+9w(RojQFG2{ADvo&73k5Z_c!BTw z6NhOT0**+CZNrPs$M$fTgTGxnK94N- z4aWaqlP=rZsvv-a7~*d@060A*H5L3A23FQv6m<6+uN=e^A{fb_;Xlc*6nN@eyJhqD z!3a1zdoPe80=BppV|+7vOt)1?L_*-UAYk7rXWS%I&E0k#V_WNI`^Ka==y;l`%M!*X zQ{qUG8IL!sQfa5Mip@$(8mYiJN{$zOT|Q-iGWi^!eJ17Q*$O+xu);GEF**L=$H8rN zxFPO6;US5Y6a))iXJ)?45@hNj&Cjq7ywJCAg6GM*yHaX(pM<2?yggcwZEf;nc)+8y z%F|m{`_jgf&u51k9VJ@Y0#=7tm-&_}Ap+|78Bw8ihTZVh^=$-^hJ98ca7K1NH=uvR z!0ib#1!6irTKlz9{|TJzk5y6I5lgKT_%Y zam!Hsv8**Y2uL$^v_lv+;*Gg@Z$`D zBB0imSKUUGBs&)yC7+~;c4gAkN@i7w@wskGSq~w~d#Qd2om%;=x2ls0jb5B>H+XX0 zH+ow30_TS;=Eb>oXP$b1CI!IHkJ4ORMn)|@Rme5n*sSECa;5kQn_Dzl%~NmS*Ew|u60v$g8Fc;H=e z(}`L3GH&V;cwa!tMEzG{?(V~cgyRPu`G1){0Z^Lg4|-2Rv}1JWz=2!$?{74$xYkag zaHEny7lr@~%z%o7F}weU4mr8G#kjs6FZv%;p~~j(X5PTf#WkX`zdNR^yd3PhHjg}G zaX(duY0wFFfh@X{f7Yk|X=xmAQf!lanDQv@+54YPnc63{Qrk*-9hj)Mj`^?0?C3nl$^OHuhpLpMeTL9s;b`EHJWn&Nw2qaS?Jw$DzGfIp zm)f@8+IfB3BXQ1$y6>M26b4^r{=1*=p1`(KCUt|y;r)cE(*R<#+SnJBg=_#l;5wj6 z`WCR&xC$NC{B(LmVXrDB!sQtYZ;9 zJ9N61`GaeCJ)Re}|4>m-L|cJ(sHA+ zno;b-ha}S7d-tke$l z2{H0{=K*fhSpEQds%C0f2L)1iH<5vkW;<*$jvW%8#Ve$wg@ zZ1;|%K?YS?Qwj}_951VMD0Tf6QvJ=K^_49oqt5#wdlXHig(9s>>;xfaOcG%%D=W)n z6}6a-ef;?K@88n6RL-#W!o#t@<{~CwacSt{VKwh?%We7MTjwdV*MEaSkwN`{0uh8U zzFIpv=tu;5fWt?m1v{yen_C*zni}A+EWlySL4Dcp$%2>Lu#@hkXEFHozlz5-DtEe# zYvlpmY=|1)9>bci8{J6jl;J(hDE4u#`hq~4BqkW8GIbBCZnTnNj%mO|#(l#{>Rok% zwAEZDv2V)Eei&_FFqy zLalINNS`wI=u;3j7JNepgWwWp9vB>?2s&Y9XuTjHQz4VV=pjjLfi)gV-0q>MPQJA= z3}6zfU+U(c40P+l&(p3krAVEIg1{Rj~jv={$qQHAMaCIhb8>U=@ znG=SgSYbxMOJAS(Orf#4nP^)O6^M2Xl%`($AaWE?K-A(J_z!2{4SDQ}(Le%klpyx^ z+zksezkZ#EFk8jhXn{Avt5*srK2d_AEv=b!AB6AMZ|pL~3@HTi?p}X-1sT>svRD+R zLg*oY6~*U)jIptSw=h-h6%$E1G~Q{=JTpcm(K(V}W=!4&UsMY-HrP!+VA; z+@8H7ijpjL{ram5+fhylZ9<$N=Xg%eZlIPSA-xmo9q{cfeSJ*j{n`V42NB+{qXq^T zOvvq=7N?AWOH421qggnWFB^Y(dYqbc_w%cJs8T?$e#LZb;2Lar6x)q(c3VGv@+SGd863Llcz7QlNIpV(%|eQ z9iLln2&xA(Lar=Nu53JLcd!RyWtG|Er3+gl{4s^S6@iX;SeSMss(g6a5muFuDJ)KZ zsRva4ZT5G<#Nl`~p*8eDK6)*_`G?EYI`aT#f$Zhj8Gj*lC=)v-|FC7`x-^Zt-WtA| zk<+Iy%k{zjOsRy!#MKK3(A{*2WS^dycHNS+WJqnp67V# zF~$EXxLPJ(+#GEmDvuJk@hw0_oiP6YYkt1kp?Hum0E96M)VKTPagmSUh<4)~B zuD+Swf4Da8`J2I6C|5HMXm+~U@*gvu(a|MGuR5L0spiSOVGlrzIk@X`gx%*Jlbo4{ z+yPgfPhH4bc8^^ioNMO0cO1}hh5}2v&!{UGr1^wRC9x$Lh$JL+&%gg0gr>%|LsOXg zqSEhUlwn63Wfiy>*1omBieG8<`#Xnycf!2`)@Yv>?j8_hk)j8y4lq5`@=sWNwZiqz z{@26@*1(4kANoQXf}+J4=DO%2@bznPaR=@yMBgh#;n4_!9S6;#d zG){qKt%@c-BK~_t6QfG{b;r_s>q@{m+gJA4vCY58H1b%Pa51&)>$%|)aPfp`dtZ-z z#-GuwtG2aeS=onIAOE4KDzSxp_K&<&i(nc2`Li*OEe2q?h~*F6R6-V4~#JvYc)TQx|}TEy`oOCB6z6=VW8F|hXy zoH{YMMd*lUJ)IyVAQZ$nGQ^6O{Ra-5jqF^?`YO!=#;XcuZ#G7Y80*+N|FWOy|5J%3 zL?tMmOgT|~#-`}ur77foyZV_itb@fU?GkszlWfUHZj<%_0tpm~>cvVxJ1>LZ{2Wr& z(u+oY4Md5bfy@^Ft3j^M3b#wS-b@!jIyg{Y?@1Y>}s#zfMQfOf03t<8Miy&NtE*~S%rKdF>W zdry0z6xD2X!=}pr#hOb26v|tx0swESom=TH1oSGNBu8>6?7bKq!#Z1}!mdi=r(|*9 zQL++899de=eX^+Ir3Q!FpH-T)A4M$R!n z)3(@ti^E0^8sMtR5ziuejlC84ZY&fe-WA1FEnre9BA+I7o#U+7Oc z!QK();xn743oj1$^im4@6)m5Jl!Jo~9VA50ZgyuAAqu_mGwurkj!0;2hHZ5{wl<$7 z7hF|hGb!#(tPx#InOvy(MZ50u=vd9Wt;ULwlQI;(_~hoJbyk)o$nQpx`@;v?JIaCw zY=M$3ul!5p`oO`3Ie;9Wf40lLmH)UEmS%xNvY+8z z#UYXkwI;JK%jqP8kDqFT7y@fKGKS~me~ei=H6Z0cK4^d=IqpI5J2zH-CJv%iCDh`= zw(Nqyfj8ml(vt|nkq>JK@P;#uSpHNS8K@G~PD5eoW2ANsBa?LkQbwxt*M++);ht|IC;{l2Hkq5dU|?F_-3sg zI?4;&(Uw^Q)GR?y(_~nFXN!vSS!`vwoA%>gYRV|7XocaAWpaSGcMyP;;omF~Jp!{;cZzaQTTMQ`1@(Lh&G zD!z%VG8q}7Wz;q^nPnjDzH+_QHs6|4wb~GFZL~2B0VWa*q=%0lDd7T0#bv!CQLu4C%D9ZD!eWR0B+WTcAT}~&^5Ka#Ous|VpYZX*>G+zQ)bl>2 zE*!45(=kVR!+WF4^7GFY6mH3W$}39!w(TI4MIE4yo(*2gMd+HXo6t(eXEOQfjwUn__xl!glk`ao1n- z0+HG(QI_~OLeVi#b~BpYxg$Hn@hMF6K=8=2Tx@Jy*0|NKT^YP9gz`N)dJ8@xWJJdV zZ=z;1vRw~s{>H!Yi#xDh1$vUyQ;EkR-X@0L@T+3|490BAM)oTtvf_3f1J}(NSPifc zjQ8ET?JMPLl0zh(rtiB7e-szTrdZFvq3Q^_f`Kipe77pl<8bL6^~yijkzMIzV4J?D zG(i3bqY9QybkKSP#2g9johi-O8De&3S}d*+01%*`&WiiHnqNWTw!BbWS$E3k?>WGq zYwJU=46}fB1HPHYp|TA%y^Wn+ag5RezY?2<&b_TYxvXh6=cC*um^R!mQ29RL6s%y; z&d%e$OOvQx(k(Vw7jsjRO{^2`uEyg|Ik|BUf1D79qO9xJe#C!#adC5_sPKcP8Qw9k z2c1Pi=04SyT|ZSuq-NsNBPK)7(fZ{}7!vhYq(_mZV$B=g zIq3Xs)B0!MX7|uu;f6*HFcXy4(9c1tga3tMUbsFd8cDU$@dm7d{Xt89MK?}Nm_c(0 zm1d#5hlK?VtdrhgV`QEAoLuEVXh7o{jizR#XKY+#%z5*p!7qlZ(EvL2qQUkgQAE-5 zLB(<4k>OV1p?!db5lTDeqZO9K(`UgWo48d$lBhyvf5=6B z|EJk*j=HWc6}7YOK^^)RHEXM8+A}Pt3yNea^nuW>aS-d?R(OD0hKkQG#rkx@NB2cw zqSxo%?JB{^Tlt%_$_3Ep?{XgKTZ|)|=lDQXy2w{JGP*V~MnDn!wKkV!8&rIsd!l1n zXgILtRGZ`z5k|xgk&qTQ?*_-mi77QnS%wl9v=wv*ufDq6AlCfTfY(3Iy@UqiP0}oA zvr1R=WV_g6KONPJp8c}=?+XOhwP;OdclpfiV(;2?){!!DBqr6C>$@i1Uz>}^)FZ%? zK=x-H>r@`s($6e+LoP(q%E!(=>-DH>$9L(yF&h9X#HK*MCs*jiLITP{Y#P+xHHh(8 z^tU+j#9Xd91V4lc^$*Mr$b5FMRsH`4;4Xx$`uex}9SE%(PV6egS6O2v%Q`3dxAJ3L zAb+5*hcVBFI@jj>W(J#B9alcR=#x4nS(B$?Dzp21Z@+|CK4X_ry0LpebKZgsrVnnN zhO`iqV-^Ppb)lWR&-qi~A5lRPB_4^e7;mf)AV(7eFj4tGC%J<3i$r6zhuo#g! zuc{=&8ziI-ECPqLEL(}p!5J88aUfJvIN-eKs~nXhN^DOkg&P|2M8q2aEFiwiDqJ?* zgA9nlfI)E4P;;f9XM}LJ9*_(*-9Zi{Jt)idB<-hbZpW$RwPkaUVZ zdwA6Nk(f#c`=n^r0kD|7=vet1=AtX3YbY?tx__S|S933u_wN~jkE8!u+-{#Agf09! z$POnb>yXBQc+R3DJEwR;joGdu=ECUaQ;2%b4lMaXO7|@@GhgSvkTgr`BK^M>fL{GQ zf24Yi}&Y; zytE<=Pb8Sk$wm8_3LL6%(6D*({=8>ygf{+N3AA(Xgj_56a6ZIT~8k}xsy5aG<#i7LWFiIgv4&E_b7BfJ2~hcq0zy71BM=2nMatYwb=)T zju0Xh^i8VuJD0-#8>plDzEVL*eTgf8q)apwK(fC1u_`FKBxn3oDRHVD6|-)L>4d^|dFjy zIo9YwlXaw8UnB49H*%E~PM>G5W8Csnz`&HXqQ*L%+uqU$Q2~NWiP4{bAUK6`zw%*;v{ zsAbu)<9S9sI1zMnNg^8knqgR4SkLYF(sce^IS?yC(r{jsJex-d7lz|KT2L8dBP~R5 zgT%^9f}-l6D^&g;mb@JsG%z}kRO**(GgH=QLd$!L-`7$PuzAI3W03tHn-|O8m|i+h zrfvR-czuhXotFGZ5!hB*2%~Bva}>x#9a^sNxc4dJGFwOwM_;(zMWv+|$NZs&sFVTB z*E^&B4S6i9()5$(Zu`=3#@w8#!KqVWh3z}}qKCXzzklh*{uu?FsspFMmP;uX;2 z$rzow#jiWQ@4Dg2Qq=SY^H^bNb>)V)V7%@GVUnzv`+lf)riG?8`RINi?=_*;r(d1wb#%?^Z9ED? zjds8INH1mE+bZkI` zedn|}Z8C+*(RgwG!9nyDr1r9-q zwV!(M7C#Ri_1jy&uT<1SQ|>DW~hqg7W=Lc#?)Bg8Hl)c<8NEyfkTH1_YHDXBPY-(vH6S6 zqgf;@jFc@lR@UFKI0L=DTEy$VzQ;%YeUf0pTg4HvD9{7Ri8&7G_`Tv=+CO~Oi+iN= zSI@@xG-IIZ(=#C6pvn92%Imtu=<#j#5kj#33~Cq>jMqMR`0yod`#tin9vn%f)bX3| zemFdTEl)qIq~8I@{79otryDA!M~y}9HWP#6v~XzJpZe1QgIP$!sA|;Pq^IYQpa!yVdIt#Qmc^XW5Y%~MGpE`@}9+pnIT+P+D|F!t#|9JWiaIV+>{}xGB*+N7% z*?X^$y|?T=vdJh!5kkmb*_#kTIQ9zJdncQ$tpEFSp7Z;k>pIuB-}h^p zdGQ&#Rh`Nykil@@YZ?G9SHJV6hdcS?TSG(lA42atY>R8i2|FLE3<2E*2o&%e*=*I9 zBsFOLcMve|F+mv68DAWrHXfI2Ehtx!iJ;Y?hJ%;)ZRL#Ij|EHEoC;gTAbb0bcylki zUXryYI=LCU^_Q043#sbokxa69u4JZMKg_SyLxsGo1(~+$#TM`t7tPcZG{bumlL5u}D;>4VL`T5OGwapu*CJwKYOCTOT?{2UY z5x@W5aFel*&$+DMn-(@Tbdu5)SN@(G?(43J05c`+?Y%(sj&nO}AXHfcQ7N!e+g1#* z6lem3Xtx-If=oNsU6-7`a&LWbDA(qDu}GbjbwPc9P=b7>9kP~TjYnz);48p@15#4t z@O|d~;Jnb26UuNqq4=IQs5f&%o@Wb9FzO&3o03_BH@i0V^!1nFFvdm@_QvSsjnO>Z20%9& z&t`Un_fA9qdzvlnxfRx{DFlmw=C1WVWPo1{q@>@UZ2?Yhu7xk!AYwA3LtRBLOt4{O zWGo~$Cjg0%l$eT{%kNxcysIoApEM~_M*G&w-Ro13keLH-YkP-auC!KF4|Sb5o+5g+ z0yiym0@Oe;m%nfMQV4E-=p8c>5UM5;J=?GDSz)i-l`{q1u$?N9C}D?lnz?@%3PPt= zT0k&DXQQL6GR#?d*Va!Vp0BVkc+u&D8s6gFyRU*iuaEzrXQDkB_V9aj!$mxygJVt3 zAcE&CRoBpP^{L3;dmzW12O;X0>gs)grUL;G7A3%eg>7tm&;0*L7+?vB!!5O zmXfdfx^MJyaMej1};l-~X0nQKLgo$8cK5GJV zUYToQ|6MrnAemY8in8%iz#^cW%s}`~5)NMMl|Mz7&glHZ#g!=hJhWcEdeKSwV73KjZ6ehiv6mA5RDGfd>f` zzcf)YZ{;zK)v^b4-xUx8B;m$Ox(Y&Rq=E_*O-L3@jpN)Z=pyjbtkt?R?}oJcoK4Nm z9v(&0BAf#)RFJ8|$@YJWqImCm$09GFz zTHumFp8#?0uw<9*BC=hP#NVm0-gjCWhXkf*?kSi9u3<-?PGP~ zH#iU6IVXINf$YG2ySuw}9dYf-1@>C#)NwaFpjX0>R&l?Tq6ybGFfYP<+%HH2{m_3S}xsSf}?p06LC z&))_qYu1Lh&H(6M!paF-^pK{*vZcJ z1_jBEMH%#O!Jv&qMkzC0*2QjBV0;;QbTU=Ew8s)#?}aIbkm4t6_s^F5!(VtRVQu23rc0@#83ha= zfJx?k(W37T#po6JC3;;e&U&eN!1~(fQsSe(Vcsw|ubi+SD>tx@*{TSP?plsBgfxrx_R!#-zH{Z5B~zL-KdtX8;t zL7V#;*3^G@4Cb&s=*J>E*?<`T3i|8^^aeANJ*LTuYdO~Q1qD!Z)C%+l6!X%dX6~P! z*R||qpVed*FjO!(o+d9%V!Fd$J!kQ8an(W}v~_fhy}UNo(WV-(@UV5O>oUK_+)UgW zz5W*Cz8DS`F#Qrbry(H!2fy9%g&Ryn0O49VI3T$1BgK+v3%JwRKRqf^w{m3dxVY;7VSUdm^5oRV&{ZEV$P_+eQP0~^&Mjpn zx@Y042zUV4vQ5=}4AgZnMQyn!5w9Tx>^yW4J&uz3AVUp0*XPd8(O`!hT+rsd|IKix zai=iY=D9Y8a_HRBvRHrDBT)}gco(c~ZL?}>;+5&l$SWbs5dww!A>CDya7N?brG`Qs zre+BL05vSCZhJ=u;PLPVe-t`m9iA<;E&xg26gSS-;qOy^X5!*(d36Tq>T%}a2;Xh2 z8ZLe~;LfBoMP&A5A|iX;c;tC~Q7cFa?VC?qyB&g3%y}K+8}c^lK1DN=@-;vI02#^^ z=I~DFH~BR@TB1i`hPSi3F%1GOUewPZ&1T@I>9fen&VB<_Q7SZYrk~7Az&i+nO+cXl z;}cHf5xIg(W=44zpAZAJrr}fd%!>|P?)vbO7z0mVLv@YE@dNh^LfHj`p9vqXT(b1A z!>@(NXgHYEmEeX;!#c+oJK%Yg29t9X8z#y(`XB7Bt(RIab^w>G9B~6w8O*e5d4R!9-;r z=+kB9Jk^_%VkU>)B7LYYk)b@2QiP3(dA+S^%g~Vx4P-O`6hjZ;kCBl#tqVva99*&4 z^XWBbJ`UdaK8r4kO5n%91Q2ZeX^uYF7*dfagn7iX7;KMkJ(q9dGJOO+BpNGF;G}~Q3+P(B$|wyDgX3C9d;6JvF2Gz~KM}bJyOK7O z1bCq}+h0k(mkeOZnCVTWT z2y%LhhJAzwAT=GX1OUE(;3A@QXfA_T<_pi4PvZ&-08)h`IZ_We@uo{PZUHb4&?JGr zovi2nLvU3Lz5s!bw`%_Bh0a=IkrV`uu#In>Wjxt9X>+xz{yG`#)Q8{;fVgIn&76V2YVuudcYoL*;y#aREsp2D1CYAY97 zf;stBVszZLN^<;FG}%bSm1vKP6MRgTX%2nOoNaXCYZ_T3cJcgIUk52M#K{GK4|CWii+K z-E|^57HqzbZOm|^)f#XRjZggiB}!4YSQ@7 zx4JkLrZg7zT=@+~6F?|jv&n&k#K6z?TzEt1j{g}_b_Kexjk)=1C728J$r(;*KOO#J z;2-f=7R=3=bfL9Mw*$p0>7$u?0P}GXVZQjH&6I??;ZefOX?F ztG&GtZ;FFULTh==-B*wQTkngZC!x=RLrGCC0YQDv%xPc0OG$R!)S_uKd{9_arDGaf z<^Gq)t%;-qDz6;`Xwn91valv?x2RvCPg&|Zfa4>(h`tYux?U%{3ngQf!*}JgX)pz< zhC8-D?>*~MOzbQ2y#Ut>wJiIw5X_)6!Ha&NNHwY+@DxmC=CB6oSJ~l??l32Zm1_6s zuv?0!pduiy9De{!2Pjk{CYD|>K|G_ZkRlP?>X13jWY7*U32i9b%?@w81Y;$g~N6BpRD%TDEZ0h^1 z7Z)HA$%u#E;Vdo2N;Lh#v@k_iTblw0Z5MRu(7sfrTMTjm2v!vZV@ovk!9kNspMt_L z&{<>QX$8Q!fu<8$=V5aPVJR#z5cBikQpfmigAebHI8Ws3cgx$ruQfwTy)2pgp z_H=AkDHi_seif>J;vopT-u9%Sf#4G%T!@H9AK|8~=Uomt<=g+jiuc+CM@9t?(kGY5 zgdAxTB9wbWr&%h?%}u;b95xq{k%T4iiQBU&yMx<*W9*8({W_9E$bLO<*`(CQp}k07eFf%|DQ#&<}wT zu*lnSpQ-cQuFx(@7CLLmxMlX=(Onn3^PA}+DT-Rl^MGHAdDgjkc*L9A@3`8$=u)ht zEPQOcPd5_t=hR2w(g3oQF_kKwspSiiM-qSI?UZlr3te$MN`zT(<|R|O3rDu~_uG(L zcd)pwn}qUD<-}%ia|`r78*^*IxlFUrZKm;)Ty}RrRK0b3jAAYkS;JF7!vb2`C`DR6 zaF4?@R10y3@Xo81KOA_)q%d6Knv)4Mc$|5%V(!FuDGiMx%|fqa{ogqxXtzd%{LRhZ zSaBk`@qT`=iM7M!Yc%TR{hh4HGc&VRHszsdVO+UhBJlYC9&vsB&-G_Lc>8cKH~1xC z0SGA5f+-0+^as^UJ&Tgna+{y2oVpbKEu*Qocmwxj?KE?3E61j-YN=(DES!X9mG6co zSS6uc0Tt*`MH-s$>45?3Olepi?C8q}Ua$dn$B8s0RrDf^>(3s-hzHmca$K31 zxPw>o%-a8hd99tuxZM?uPmo5-&duEp5wbGbs;hW2a%NKGD6d7qhv!1q-7jIGnEO&I z(m(mXXZhLKVFd|4z%8X?fKkm=yo3y-0E*3A5I$GVlHw(aZRW%jIDH`sR*7P2?=y6% zF(oD^pN(9wlZpO}S-B6}#uu#518aJOycJVhNpZj=3xc%X!cB~=aCdK03=V*XUwnOj zXBQM~u>681qBaw$Xin-ouCRBp%?(c;A9|*Asybn~&%Uy#QO*B&>LI0q2b*^4Xzm6- zJnQgfZnRPMG0RBG*zXqu|a9MHCps}R`ntpWxlaVl3ykEuaIAhNI zDQEmCx^d=kHc871UUE0k_87``6CtnE2>&O#N~bSr!dlbRa?RSth9otwB%QkJ%NN(p zzh3`;`vTDU8q965{ofmY2g_2B1XRHr#c|zk3r2ytD(}bJTMM3y=61z>b(3^AZDFk& z98`f{<^|6EzH8q3caR`G2-Js%71qx0l>>%gR>5u(k!Oi-bMRO^7-8q&=m9?mG-3kw z%b$`1^cJ+Rz`0aK17BenqRH;TuNgm1d=G}DnLUU62|37yS#bu>z-yDyS`(RMig5CS3m8tC?F_0TF;{Jc<4klAVyOY2-HHlLKlQu*(S+NPrI0?R3=ChJ)L- zP{hUsq*UDhoC2GyU+*3cm@zor)_?tC-4L6ta|?s(z`v`ODCrfFv{LcsEz6}8!h&zzxEthKiFo$oDw&3 zT3B4nm1G8EHn`%tz*~0Y+j|>4q2@}*Hy@1NnBL;&Hm%XC`DUbo=OfGmYR&iVwCvIJ?3YCB0YH%O=@V;Z z1($Mz>6dxBu!ok(KW3^uxx>!%{UPBjgl7Ohkm7(N{p9dsNbX{lD8- zD?{A^qP<=SF1BJx`t%9Fwe124Fp47ROh;HIjE^vSYh?_gA&}%y$&IIVB|CYI2^kx} zT7nN%j;oD3pSgP2O*0T~9l+e6HeCR6K=g&K9o!92yuuLO@)S+&8@$of|apeh~g8i^nLLyCDF1`ePd_P(+JQ8bv|sSi$sAhR3Xnwd?^Z`zzxQx1B4#S-;w* zV>G{GSnrMr2S!-rb8_HtgbHvoc-%lqFf=hCo1qNalpyF`gp>~$?g6jT{L4)GwXF?0 zIV~B5Fk=2&taku+1wAZsHZwUpf>&=44`K|&c$GB^WA(Rt9?jRMIMAZCY{Sv^N=*jy zW|Hyqo7AB(xcH&O&TmXf(ivfz0HjD4_Mrdur?&?{yGS)XaGV7 z^b-QG3T)&Yxn4%Il>Xlm(*P2&HWN0-c=W%*(0>+?bsw32>fxPW2ey4y6EA!7Oa>?D zBA2fF^-l>kdel|9E0V&Vg2MgD1z0r@;U4lg%p>Q1O$jgn&-6iKH9}3c6&JnSh=}1n^oYwge@AIdRHx-=o*{m)yS)F)MOj<#YzBSy zj%phE9%_K#YCz;l5aRwQq0M)``6gHhh{(xH{(NBU-Z_q+!FuyM%}VIM_oV@BgSTLA4w@$N5VxnJtsIZjH!eg-CbN;w9!mg@p=6`~~_+}fq+MYTRqyXwr& zjqypt0Uk97?0?2<5s8oiULGX8LHXQ>j=SHLd zo0D3i;0r(kiG|u*I0}Hyd^hjkU(G;-5oc~$ug?PeBiu`T(pU;o|K{hr&+FdE-AB>! zW3cVr3ITZoJo~UV{~Q?sSubK$vvza@!aW6EUVzy8p3l4h#IT`(uy-noOKHWD3 zR~aN+p984w2jvE~necs0Y%xLKNQD$>fJl2Ga}r9WgaN@3Jm}>BU5H`|e;X7Zd9K82 zolFe)wJ$GIue;U_Nz8g^7KS%Ah9O7B2}6O&0$*RHSp{(%tZq1sLtYSkvZ3keUV!5O zA$tG*J=C-~Ttdn;w4F=f1rY}2igJ=}gv|RSA9e|(lUs1Dry%%%{BWlQv!~J4M-!Kqj!;4Z?BKci~riWcf zXy7Bt>QUgQQ3mzwzkf~cwE<$BK2CoZDT6o%H#$gkh=PBWQ=usZ0w4nz3kYT~`hf`6 zXBjL1_6S%N3iXISi`Fgoc!O(4o`Oh_4|4wm$>3gs1bCx>&+RCY} zjza>j&WD~{MDwX_(`oC-;=JpPQYrQ4sV*=A-Kij`{0LevaYPb+a75m^5 z@@IB{Z&AxKY;;eKjdei9Fv`=%XiB%!20YAi1<{l0LEQjd8K0}Fpd_0BkwL+u2fQ?} zw7XhB%s$P`S?lbSU?RAit0)9!_L(uaFre^}ZwDG$aD~}bKN;>4IbFtuy@Y|60r?YN z7dpNnfanCK4CTBbiJ1UEl$VaSlwhR0>s-6sSgh0Fv12%)L22v(wj)3g%!iBQfE0jB z`O+c(?90A)1LWgC&Beq%>|!w3PN?5B_JCmm5YDE#rfuQ!x$W?QH3;X|OOYRgjB;?c9p*%)RuJXrts6U7zj#4lFtAru+Hgyhy|#vi<~JlS z!=dSntvYuU%o63=MNB^+7Dxu5H}Fj3lTHkRKoItbjQ|$_L_qbZVrml!UlH_!=2ITV z#;*Z^gKr@Qd$o^`{;f5vA0W+zL@J%QzEw7m)M{u*34!h5mhk`+!809-{-r%IYZxLk z+OSyMO4hwkj0PBSpSvTLUeSk!=HO%5T?89{7+5=<55zu!m{Md91k4>I;?97u6=^a8 z4R3B{w*0-lEDeMpkfP?lxK`+1Z(v5UslrQYVPcZW#0w+}te=Ea?%33_nabK%9boWC zFDMwVe!1*i3w6xq&Cot9_Vj58{F`*TP&6E}vVS*lF%>)x-WvGw1_mi~6impHnJ{AW zIKC&LMu49m5oI#)J`(fvR(}~>P_&_qdGpSX*U3z#q?HsY9ZR_x8PGA(GCjROs`rGM z8IeODz$>!{L~t9%PrwIo-$|Yvh+MhAxd7XoNy*098HO@8k_UlGe|$8OgLY=5r+%je8=0}EP+ zgbJRfCRPsaswO;Mkbqh^Vq@XL{Nzc}YjK^p{Nmy^oAT$wZg{MLE+`aFdWt@)uD)2G zJPa16gql=1C}`+$%fy+VU$T-%Mv79rA6`eLh=Ov~a@ati$x#R*>$)I$A3>@i9r1j! z^nwJ!^%1U1BLywPdJ^|GXQZT4e<$<7nE#)Slev>pud1USa)OCYw5zpa;g#a6g@>v} zZ;F`<+@@9+IV3r;F~vNxL-zlHes{U}p2o(zy=ayp7qo|E;XO(LX>TY}!zG>^E z*u%k7FF7yCh$ZyY)$jctJ&&(1ZCOv-^H`=*2Ob3p)sH3x#U=PP;nb8p>_)+27$2Cw zxVcew6`sAy$XZ90xes0iBK|suYxgTueH>^SJ1YcazGpw`L627Vv2SJlU`FiqaBa$Q z%xf?GXiD8I(JCXjnx7|sT+qXz@5S!~VL^gk`$w|u`!>&i{&4#ivxc5gwp~aEEbf@O8Rh&DY&fZBOY^w)*;LadQ#X6q8iI^q$@P)JOIB;Xyy!ZD#itP6J#ezHIHQ%;ZN4)E~otUkO_Pk3`B_?ZXuK~)}q~la9%{z zw8{q&BBX|;@vymoa~-s(ZB3YU5mT(n*NDr;?Ks^$aFwXxzeNdEb5Tkalx2xug5xKW zh#zv~$4vvu1!iW0uQS4eI??leXij2urL4440vrnH2g;VExl#HxzgZ{Rz$kVVNNmS)TbCuw;qH%F-H?o%!LL<1S$~Sir=Q`8nI@DE(xVq( zYE-GrX-B5&n^C6Hq$y<8ll-z_kRFZCI*>QZyw!rK&2b>lv{F{^p)aCRVkZOk|e&QZczycbXOQl zv7uXOijXlIV=-9nupUiyjJ~I&=hasfBtTKBX>WLX$2BWX-8Fdc6b~y&l0P=LyaBf+ z(cI}dMq%sgxMx`t;;z*r#%4>seI1=^6`wJA3=G1p?gnD8*mx!ru;+6|kG$4+{c|7v zkgOp{pCHbnLq}$P{PT_VfY_r5&CRnfrEv{CHs4g8;0&YyzFj?c9H5a^@TBC$kmIg9 zGafpmo7f+?Ls)ouGXG<=k%IdA`b`ecAMlg{0QMY`FgA&1Sur>jvXtpQKAh@dPZ$Zt z31u2~UA%=A8KPI?m~^;~(fZug^&^M^j9pq=O)B~BpxW+w-T*kFNOLN6Z2kBQh83CU zFD2Y-#vt8WovgBjY6mBn4IqdQ85UrTM+S8WQGMu5V?cp3UgM_mZ8bTSWZwV0p=m|y z@~_CQx7w$xvzl3&gA~gI-{Y$Vk!ilJvxn!xeW%u!>+}9MrQ_1hn|C;7&!*0IjeKHy zv(jE{rJei#s(Y={tP_%C-+F;Tu`bPKWrq6baYFiBv#K4j0`|3bn|94TE=*U9tXF1- zPK%NpzpR6Irm0B&EE)ER{(QDE#Ffc``9Y$`&)U9L*Q151)}duOjwp4F&c+6m>@>*5moW$L|6Z;B|~|@oP#k-Vs=#)K1#})sN2-4ZsUS4 zuc9Yqvad>nnSp2OLrO5?P?liK*DS31E#Qk_eIrtF=0GC!1iSzn-1(-ZNa1|mt%Y?E zfCJE@&fsQMS_=+l&D#(*2SX5u!kgv>Ao;tF{{@Op&U2z$H?RLzN`6jHVCw8VBzQUI zmIA0rx~IPPCnf?$_xhOXYQt}aSHeXD;;clU0gg&ce6kS+ze$6dR|}2>E#TCLV*`?p zls3>Y)_BAPkSHkRPVNG}hIJu+;rGq3Ezrd@?OTUYJE_^#@!YDt&Qde2$H`KLe|y3N zAJf*8`(@YovOcYwn-Qn!W-L4~$SWjPlp5hH#y{Glo?+Dv?=NoD3e>NDMa^h5+wk`Z z-b1~={;jN{6$>w9mhZk9Iee~J#)%PbSN&>aN0h<-8CA#6PP)XAH*KAXYFbUn(ss}B zoXt1`%^u15p*WrF3M?-Y9j_TUmh)k;^4?w^xDC`yUwl%nr~__w&Z3eM=-e8N zcnzd56G7PNn{iO}xC{t&%w2BHX?mI=JDdt4{sf$%R=;0=)sC=a;+g@JI0>IS!GxLWKf6!}cicr@Y##YE zUUkap?nTo|+PRT`um6Y|2D@+eg3;cStHa3CjhZ^v%htKw=YMxxCKEH#A3PuD^{q}7 zxtcoG@vOW@6+>^~zs~QC(j#aeXRVHIwH31Hjp3@0mHxo07C$Gh!ZY#WxlHGB*YZK0 z)i3FMZr!~(@r-NU!Jg!!qchSwR0q>zz$EkK(l;YQ)eMs}c^sw}`$LTlJsSUx(@UZEN`29l za>-85%1oq2qdfzR^$XOC1ZdYu)gMi1Cb-qu}4x+f0%%yf*sU8YmMF z9@%NVTC5&9s5MFVsG6lFBJz&#d?ZzteY;eFstV6&=BVv^^66DJiEHo|l5Z~QbnM&8 zn2J)f$G&dNDlXej%uGz+mFoc&-gUhC>Z7A0=hOX_0$ycgQz}TKmOY;yxFCf9y6W0q zn<@fZ11%@rL<&I#crpOc#eaFBI-1Kn^JT9+scheB+v&(TvYYwz+`oNygCWw{Lp)pY!52w+HuA z>j-WPt6>O-Qsldn=#ij(#gGn0{r)4Wn1%Xg@&XNd*6^PWJn_RmPLD6_Y(mmzBxWO0 z&n!72d_xt~Gl?bXH_ASWtznJgh6R(H-Y8;0x3abltG|PxC)~i5c z(e#qn`Rf3ByDAs`c@~0oX=p<{KL-}+TG=_YW)NjtQYIv6KE~N+<6!%T^uw@uz>rPc zFVl&v_QZIpib3TyV{fNx2GM2OGhe=Nn+Uy9EPq7d`V|0Vm=FSplW!tDbijc;{oSJt zr_4OknyEf0rq_vU;}{U6BEh)RLg`$qkH7H^P(px&VZeYm05}YRv_Bg1koRDqE+vkC z-AXw)biaM8nnU;!3}2Y|)=M?z`Yb)Yy}TS8OL+w-Nqw(pw!g34T|5ki!4$+Lpo}sp zFGAhH%8MAHJX=@t5A9i51Wp@(p2pKYM|N1I-~cLv;5ob1j{%94NS5DL;7&3Ja1cl+ zmkHQ`K>i$SpHjrk#+jN?+3@15LlaEIpOTY7OLz?+Hb{|wOVLTb;>-t%D#M-l{BBUo z{`vDqU8iR!ODY;Egt4-=o;Y?hs&#$?6|=T;V=sR;98KB+pjfkMv%%B2hdJweJo6te z$N-u=AV&~Sg1W{^{oDnMKSZTyFGRsXVhN$GpqWni&zM0Pv6lWQAlJwmjgVR-BsVaa z2*{e|+Fb@3-e+omeR<5Wx)v{!YtD`SLx+jL5L)s8cz`s;!MeY0AsL)fBMVOO(#caO z2hMD_tp7T>IWI!wUe`F>@Huz{DVrs={SluqE80^=KkP=GqE zF>TG=&25jdX`d0OqWy*)Uu+lvME*X#dOLU4FgJBrXLfI%m)B%!Tfv-tEtNcE&TeU) zqIzxt@+-+L2U3~!;=0TjI7tx1FfYHf^vT&Q;7j^K#DupNSY@Ksqn2MKCXyiPQ~nh5 z9?Vt>Xlj#H)ls`Gbsf?d?d_=`6ficH*BRx3+IA3A4^+@09jP5l8Ooi}@+{Ek)!x#= zTYkbcA%6eV>7^EF9-#Y|zalT+MhgE$dj;q{;`!Q#C@s=o8-9m{Mk`}}TVoLA=$*Ny z^=)-pMJx16Poyscz7*Srp~m~=+=eZRdPnl2A<~nMt_q)YuC-Lu?2DtlExpO=r*3Ka zs7YHjEzJq3sc_KFEsB^2fgm7h%h1R8KQ>so4=_vNv{I(5$1u4swTC13Je8$_N$Yc? zDG+jy5L-Xf4{NJtB7IzgRZ-Y-x1h2)WX32?PrC9Uh$e!72afUZNtWMg+Agzv|O);cN zF|_dF3!v^IZTmj0TUT-bZSd>@0zGYEgtcHXhLqKBP~rKqKxqr85Fq(M_{|*;G$e4* zsh)o;_(eqgsY91E7z;-by}{Z+EHm~Saj2|dAao0cq1{)bf89w6JyTeC{1tQDrkiDNe-~a%U!y*R>U;v^Vt`<88^%e&I z9nWPnG=O7kR`T1&bSZX)+=>sPvUGQkLwt9LTJ`P`Z2t&(_CI>k4jfy> z0`zAB{%bo(&r6dyLcFPgObv8ok4l9E1fIdu2s*+_BTfZK|4-mxA0;6rwQzP$Tv@r5 zSnU_5#h!qe(Pt`p71$Ge7WWvyWB5`4@2ukOoqsntgkOn`7-bgsPyx(@JZ4ULUG zg=j`r3|LcfJ^m87lp>TImC~3SFv5th8E(Aji_pCn0(r1|;v6Z#kA!eJgglbuB$?R_ z(#Hu39EPGd2k%qkZi`BR%V}Du0}8YSuokrI7bKJXx*6Y3zF%YP>ABTv?9)uqE&TCk zmw6?C&HJZ<5Qzw#$FPO~iVf6O>jG=#^+@NXDl_&ju(Z(Op(74@5P9v6>N&mu!#QLs z);V~)fnXb43u~z_`4`_Q6|h&&)s+9w^y$QO4oUWDUeF1P2%RRr*s)b< zz*iWT0kad}Qk;%w7k)s#=>JPkAoAg{avj%4lF7#Sb)0;OT(QDDUKHt`wvaIL6a$SzSm#{q% zD(E0(s4E-|6bm6VWg%DOf*$lfzy!fVhI|KbHLZZVz=FOQ-e?F2?}WRA7^xf! zzp|iU(Y+q(dZ2J5lg_hY)=i}C3m4>I!77ypdu;udbFHKnQexP=?8J)@3{Vqi-UFhe ze?Dr8@tVPG4dS%JG@+X}TOII*lhi}6^H&k27otwMCT71uA)l>lTLaMk4-0>kO=7Uh zYlqqqFeMyRrd_-T0z487v&Wa;=2~zbgQirQ3FxvS%?;Tr zBbIpV?s1^BgL7J1#96-WimNl=|2UAHgT0WL+irXwl?G@h3}O}*mgUt|lX7kE$i4)Q z5SZY^-pk?iE1?Fy1{F>-Rx2B^&;;(poy(VKQJd~{3N&*22NUJSH`_w620^2=bFAIF zday54rCIoxnmWjOIEM}Pv)NSdr(1JPX;5czY4gr>MQ2YEo_^lD@KP?Uu5ynXCu;#` z*flT!-H5@!B3}ay@Z0ckvgJ->0myj7%^jDSnK@euPc2)5Jgog#Ch7rBe$Fl~S#@>Z zWvxyT;i(0DXOTwFL@piQMpM80J)~;W)3djK&^j|5^Qx?@8Ov7YZDgb+*xRhCbn!$K z>tU5LZw?O_pfVoObi>*zlp0&a`N2=Y!VDW7xRPS5Lo`5W6}o0NX1+USRV}E z22wLKhl5Vym}ZSyw#A|{Dml3q=+WDJ{0P^`>gDAH^sX2vLwCya^732?BBLpi6{crq z_*{SecpkFwK|Y$2r>DGUOGr=m@pn}A102Q_0c47kP{73G;!=-~Un0Z{$}N3T;w^N| zBIeEpTkJn;kYFh7>B$RDRE!7QMKzen%LQ!M^2&;eswyZ&auFXXkk$9e$@?>6Xxr>Rlz0T)>MTqa|<;CVWD;N+E;2oJDPs8mvJAGz+IRFf*vW`xd z+nB*qZEd21)jrdch(%XYQgVlg_?N(3U{~oX zSX!=8NYkLTOo&H(vwXS1mww)PuRD@d?93EpruLubtRFso>U?{T%E`my_IE2zRb^#S zFqVP|u-%IDs9xIK{4wbFmtmf!W@37;=TQ3wG@7dV`aaXOH}@_xdBUh<@1J3h#3X-u ztM%dG)hS)r>e03zd)|HSXFMqe1d2YPk{z#=z8*X*9h$b!W%3unOnLfX-R)qmgWSZU z=iP%19R+-!^A*ia5knX%0zrMqA8zoe_{gZSSg&H(esfc&rZR>_jfeZCNTHm;^2)Mt z`GseM8MQ!7nMdI%y&>tdn!S#+d|cD`{3~05`hu#cCq`axlK;B!EHR@6c3E+nK&r@u z9jAXyxWwH!<)iswb-_!)5dW7CMy|XbBu%`ZaS$o7d3JILGx0rA()Z2Je+k8Po>VdvQt}ulpZcJ54cv-;)AoS4ZZeT%SmT8#;5me6xbau*=G#u$V zG@e?}C?>x(EbTBUcY@l=S-&%TSdzXs`ks-}tVS@fu&lyiH9ap64I3M~r0zEZjY6WU zG=ne#0o5>9Cck>6T!c<+xXpi~H9)&I<3o?7)Pm`cm%yJcZ@ z4C|x6Us$fT7>_H}$fZ8%MwFM|9}5brJ?!qX)DbJ9NcN9t^vv@*_3zYR`5OK(yegl# z%O>mS@c2a%8_L%1FPA!|bGv6zF!SRcNA{j|Ah2MjBi&M&3L zw43~dz%)hzS4j2oZ+;3~4dG%2FOooB~Kd0C7PHHIkF#LnY$#J(igmJ6y2t$BDt znDp#-868IN<&4qEg%nkkaTe>AnxU5^X7Qx)`QFYkYrntfL&5-xWGFm?pb$0z>`ix! z%G`|bi1c6mA!Suxj7y57aS7epOLlg424Iw!I;-M%VgacPYPe+#jEpIv&4al~Pj|A6 z>iP$({N4cqIm>>OwJ`!`BlB*&(Gr8Ruu+IS!0Bg!T#}Emv4b-g!~H2yR8K<#ViIq#Pk;?w#+tV`6MB{Xp`biUFo{4G>+7`fKy-}JtFwtY-# zy1zPEeYO44$M;TBaZ-DzcxY0wq^Gv$MwhvE&gE-D$3rUHzIwq6DYRpS^8Id9Di4wR zWUF`w&Q$lK^Bu>Zrx$UAmj{+d#oj6Yz8_nM$LdYD?95gKO7~MHrKMDeaS3Jub9)9# z&v1R0%?#@|xTn96EaREVoMT4Lc?rqA2_2O%I#~C6_cGNRB|b-p$$#%o3%M7DsR0*T z{9Jz)ZotG@7ss~?S$^ypPLy9>rZ#Lg z>y9=LJvDl)Z`l9riErBRJ=+Ic^+)MgSpTSwT_fRgufKS&(Vsu^TX>57wrN;SR;nOP%$>rK-%ezfa$UfB zrszVa@5<+{#`JWG9Hq2b+EXGz!l$ybcjD3%ve}dRT$4W+HPzPYs3S20$=S=!e2`gc z))U9<8?kZt*GON160K!@(2CQlYBHwr=zdU|8bd5K4UGva5gI0D+wd@MRh^}xxQh!1 zghVf|tqC-kAG#LlR)xyO(6Bi#%j77gg!XYeVWP!Sh1{+<3JKI__jsgWFHMrfAGMh- z8Zlv(ol%v7Bf>0aenl*nARkfRj5|jmbSFdCxj>iVd>nV#%E0ZHTM6luSa~*k{1x-n ztNl2KqGC-84>z(J_lY>IQ{UC3uU6B<9uxNZWVA1i{Toh~HmT2len{j`#GaiEIo&_) zjkI66(7Ni$9@FnJi$tyVH^L3pDFsb>^Ij7C;ZbJ-lYv?_|XL&Hiy(iEi`s z&!$vY+kE*9$=tClHTv)9>~HRRH;|*;H$QX7{pifBBG!n*8S~;gBb}{H>uo+=4<#R; zn+d%9p^iLbf6kYWP-o8%cD#%-M7PL$9Ube*c=R3^6?>+HzYJaHb~AaF{7PZ}DUFuN z?jM@(t#4#%92g!H=N<24Q#1uVy-K|!GyXQSi+Yw5y(Pi@3q!B{s(PY`p2AAll~jfH zhuW{{p(Mc!k2c@aIK7uPO*7=PshZ5+n{lq4&R2573ytx;c7RJr81FZxS~x-%D`AQA z72<)qKhm37S{{>g5Mk(h%(&5#hWHi0Uy9y(5XfLrSv$A0v$^R?^wfWhw|nsJP1)#V z@4b0CVsDz50pPeSL#4A|GYJ4=>8xp2R~K~H{rZY+b4%>R&GY3;HDzViabq-zPpbL< zw6(q2-E}fCHGLNrw$adMQw6XI9UUD72giZd6uCWj(kUd+!g0%Tv`D9+tNC?ax*EwJ zmfi%C_SIsY_ex~%s-~nrG+hsClQx#ZSGmqW6Nx3^hmN_k%ucMDMtPeZkDYiGSDpK_ z{~4z6-K+kzkd037Q|SmS?)V7eGaU9)i%YjDbypiq211mhYUk-#=AR>a6#u+Asz&{o zDs08oIK4YS__b`4)u_pnXC(e2<(kOjrrJNk1d5woc-{C6KP%A9&>uHm7Ylmx8x8Yo zQ1O&uR_)AtY09iFv)88ezq<6lJDgeXzL9@7Fx$; z=@1Z*?naOh5NVJOr9nbUKuV;fQ$k8YQc01L?(VK{Ui*HZ&tw1Cq3pHRInSA6jJ$0SZr25$5-Ja;~fHupP5Q;_ zr>0kw4#Pll6=O9o0Uo42Ha3L;R> zYg@0n`3|ob{)GLt>VVT)iNfbWA@2zf?CXLrX3mi#9q*KUv}?^ZmamWq{$)YK>cjK6 zMEib4wJ8~2)DwHr?5BI@laxb`xng5kNDGh!nfy^*@|U+b{$kHks!wt zQ&CYNwgMX^!iwhWN9ST3ILfX{vRaY8zP^~0toMUj=LDl-b7U7Bot=f(wz!jj<-bXN zh>OcZwSf_sH9UO*MeM>K{l3(dUxM0&BXjScL7dV2GL!txhA$;4kTG?%wY4=gEX)K} z!W%p9AR+yHK_x+C4mM-MN(hW(P-uJm_&`~$n9QAX65v}u6*Xd=lb;_3Fg#eJ4E|%5 z3nU1DCC9jjWM^mhD^2*M_82Ws5)$6;(>iaIiW#c6OIoZFaOY_)hrUw9hsQNCe^~wc zXzoSa$3Jt^niL{$`CRCl?C!6JV-6NX)Af7{+Z?jP!J#R09=Y}%fXQmWrtSWk}#qHbKbWaD=)w*KBJ>w}P=&-PI zDoavZhpabQu!4Vf%x)EA7w>Z_ty9r>yXdCKcNJ>HU=u#IHKFL)6}Z&wWSF(lr0C9S zD0z@986^7xqg=uXbLSD2`y$gJySDrRR_1*rx@R11V}{*xvLoz+wM_i!VXF~M1dsUS2$nocG!B5^ z6Fzr&2s5hf;tnTAN0W{SVsFs2kn&WBP+sDlhull&%p_3ndKyq)rt~I z>swpzt&HK(it5v3l2kG7c!x+ye$IISTM_2yZ7W;bH>V9iOYdU+NaBkqT}JI zRC(M6)IeuID%`%HihXYo2;9e^q4y$$8Uv?TTfy3zg@S?t85wzYdwcrg(~toFt&GmaQ|THD%U=+#5M&kPsA-$lMv{D*fU%dAVf87}g$dD?}LD6hH*@sd0M zlM4(CoLyTRzo?n8s6h3(19DQ=QQ!*4M3}98-V}$t#~`Zfa_iw^9g{NML4O zRu)pEOh9R={SIjhL`+zf3{lRz7(p>bZ9VH5d}=JflMvm9A?mnHW_j-`Q-XX5+Ot(T zDnb3u-6D#$({U6MI{dePhqVIz9Dpq0`Sg~b=1{cbCptbE6lr@{p@d^ z=fd&`GH^!A;dmWynjCMA7wMMYfe-++NuNKz1yEFFZgUV+I-SXna+{CeCK-D{aoYe| zeCZ2{t=MGt$uLp>3HijF5KBUj$>Z~KgB<98fRx^P94ZB$4UwRrps2>Eiu%Z^B3mC3 z%OlQng+PO1?GOztQc}_jC7OvX*N{ec@&_f3nm(^;CNGN3;l4_Fmc==UeAACKWZ&V* zmL~dCrT+--vYS;vVIeDYgN5g20Li2b*%Q>fFcH>JQ)_|dZhvo6L0?s&z{8mTsQLOx zwY0RLNsfb!4FC%KTfj16=+sS5BM6&YZ=K^@($btjRpmyZ?Y3ubiBQ2)5!Z^Nv2rue zrdpf&Tdc~IB;ZH`JKK&G)g-G7U32R-nIh#y;P z+B@}`bH`+4aCr8^Y!yQ-DwgBPP71)-UPwww$tfsoG(Hj#NUEsdhK{|T8h+=K;{XwI zxZlmI$5~gOl{==U8fO-Bl=C*+d}I?sV4QGu{Mx1Jdd;b7>0)$XYDx*_v$uZ#{*77l z*v-X7U}|!A>>Igbbtepv1#?#9-P~%1CyO533wYLd)e|MgzvSex^H)PhM+YJW#4I9= zdyr|U=sp~UHC<>?07{aVmltRkcQ1#}&*h{Y0?(MGL2+TH^m<0q%U{Fcy3E@Bx{u!87uyYX!jq zwoQ(56j6Kg3xl@7^Xcj7D~6NHtE&t0_W7^ej-Ocxqv6wgnYmePoF>oP-1(gx-ky=M z^Q+40?T;T%Al{}HlsHw>ltZuf@87@1Re#5IuU1!9MlTxBFffok#UkFOn_mnDo|N}1 z!I@kbii|t&uMPwQFbFWGz?_rxd-))jW?NH_?c?xtk0%>gp|S#$;4)ciA`(FdpVaf8 zmW~Rio-<&Gg1`Nh#1#O|eUoqc@JI0o2ypQ5=t%I;5!L?X<>l9sl5Gt~Ug#@ALFOzU zc5kkotZ`d>cn6(Ki=6_>ya*%XtijZ(ebr1=0kRMCFwFRaX9>aGMG+!<{^KR5GiEIY zp>w^cAuC?x2Sb7%AsoVpTABVJSaM`R4NMFZmow^IK(fCq@!IzoMwwzekD|mVfV22r z`hCqtqaDSrD{hiVkOPX4p@kkk6b$OHtEHwEbL!&}PABIiBsfKhctxNJzy&)A3=YQZ z3Q)!F)8oQo>;l)4U=vucJt8ltm z+3(p5)XA$yp2yo$!l7ztEBE8N|JXZqj2lHDb&o%KllT3q545oJOE%Wm!}IbO2@M@? z8`Ris@!xi-I`7qk8Y<64>`;>@y$AU-)`&*1zwjvB9+HPqG5ef(yo zr+tU$>VBGL!VAy5{`==oDsR}#(2%61WnSE1MhaM?z)SEcfbPX~CGzK_gGXXvVR`Db z&8DfZFAssx-bp!@4pQG9m@AAm`P858BK#*C^lz`BRl0$uChzR1xYm^xr%-|2CWqY0+??Z3V6J|#3_S7h8qlyh z6if`7mV-tG^c+`@&f`k14p?L@am&Pwvzh}D^__}`k|i)pWw;o)!c}bZ4Zl)Cu|o{O zxDfByx*(rZaUynfc(|z~kg@&u4dS4ZD;w`4&v{eH#kwn}<^atj&}^TcodNMX%Hbhs zryR=^jtEWhBKT^EyrE$9$+Zg!3UVCL(kZtYuRx3!1I_NDpg>6C88Z>cX*O5(tGOK? zACI9+1{7(K^1;WJQ&beOd;RVGd-Qkj-huC}u$|=V>FH745Q6=vubKt8(};M#LtsWp znGuH>IB5M1lTlXK>?@(K?#V=jTFhEhVTc&G zJ-)zl0gG{kaubNY-ogJbDr0sLjm6vR+Jg3EO*U4<1PWm(2M?0s^_;tq3A6 z|A(|PFSwH-Y0ZLWKFq-76%^7wEpJ#UtS38dmc?fXPkj0;4rLT$@tr?byo^c$5H@{T zakW^qnum)YlRVHbuI7Jb#Y+MN7C+YP?XUHmlv}O2hsLKg?$YQmslBeMWm?M1@cux@ zmW%nz%3-8-_kcyA+b*+lDzL*faD&mfGnT`ZtF7^ahz33L%-|8G+F7k=FF(7ZnDm4n*cw+g24y|zfsZI@XJ)Knk-`N87 z5B01_HRZTyl<|M^BS$zy1GoP!8D^|5w$pTXb)Fc?O};U9TDirrqTe%Gv05r#X1X*? zq`c51-Z1xIS#(F{Czc!%!LSP5#Boy>?G7~kSO+a%TxpowFD9^Bs5Y)jQPlr?;;AjF z!4Q4#bD`_wXpzwlot=N8T@tQ)1CP<40UEU=f=o!xaPHCqG#gY@7zG8BBO)+9=Y1*3 z&JKjH{UIUYao0oWlA>Pi9UUQPfK^6PB{QjDstwS7i3mh>UibYw?CXzTn0$5cgcy6f z3$jg7KF>odXsyGnN;Y2;hk)R3N)^&roin4fwDi@nHz^y0?kh2dU?)l_kblFtcK7hm ze563DvDgWQU|moHsdzMIs+r<&5s0T3dsuDuOIi?Um>Ab(|urT@aw0MY+GrfG5Tc2un(wTeif=r1=Q%v9mMcn+xO`PM-#Qp%jyh{X|>P})95zk zqtb=VbKGG&wgrdlqnvR@wq-R6t^VfQY-)E;ewkWIOEvw^~>c5Vu{u<5AUkZv&|~H z@$O5{$B}XNFSB)!I4-a6_+MSg)mfoQD`^WARO)&D#A}rd=DO)~vnm^l`R=;s7l(tk zdrW73iuZBHx}AOe>(!iIM`z$HrC2QCU-RJ+^{zM$zdOg6Vpl7X?LjDWOXOWa%{PQg zwghzD%3gCqB`F`@)+BOpWf7L;e6vLVWNuGY{Isu;2V-nP;k4iOAQW|%+Cle@TjRI8 z-Tyj<{Tc#8U-&g#(VlJvP!9gF&8xE#9yR8?BYuNzAy!LJ_$?^m#+Xa? ziqiLDp#Z{WXUmCpWYVetKOW6K{IL(?mtdoSJj#x+KtD&7bKA`1UX!^%y*2N zu`T{xk|aEL<+NK0|08hOAc98eVPc=EZ6<0z?MD9aT~oXAHBa4?b~rzW149547%#v8r(VJg1n+yI4mxmhQsx+ZvYe_ANS0G=`k#ibV;4UKxXNBKig*uMrkkbeHnn;0df@>wDiwp4jb(}MWNr+eIyfpyhGhA z6;zrS#-C^?ueSKxMq#Fv=0=3QeuK4#yJ_*=WBuvz_&yzbG3C@~|K~f?D%GPRO%qjN zesqLR{Q<0HdB5ngD?fB-(|UOEgnmCVSv*VO(x(f*e~|2O_Oq7KfSlghWRUiT*30jn zUo#uND%bWo%J^xU+dqnwPM>JMcloxYGx+X%A<2$DHUH$d*t`z)a>WkCNJqVYNWW1z z_{At~SZRI-Dt6flw{rR|>;;17@7!kHjZSSug=>6&k1dy;@#Uo+2Xo)|Camzd(4Ia! zSj^a_N)G4ZZ~l>6<A_I+V(Q=PsNgVvf5Lr7D(0{k)j)J z9?ke1+)j-Ca4`4$rnBjT!B~8C@@uJRhfz!Ez+6SMcXmi_(?>+cw*8&%yo^~9O9{Vh zFwK2`ASa;n*m(phO}gzaWeuOr?yY>?uF%jj{8`*9Zn?ow`+uuNe&tifr81e5W5jnjJox*;~EyxWB0`D))=aNA})D z4tw9<9SIy}0Sy}to|)OOw6uG@zF z@v$rJ^9zP_3i#jl-K)2{Uv5>rKJEO;UsjW!6jD+bU6^5@u)Y1}(r%qg%RM%^70E-< z;}E6d#LlG2o3_;MS5Cbr<>({tB(4*mr>=cQcA;Be8Yb^ObIBG}a69GoU)1MkM>)G6ae<%=S}n6$W`lL~o5Zv@iB z8%H`=#Wxwvt}Y_5w#F-)+=dw*V%D>t~2 zSs%KoaPG}}y5kv|!(o@>^7G0@?K(Ijm2BF>oy$6>{ov-3P^_l0<(NFBwqQfc=vrjq zl(8TMi;(_%nWL20ai8K}dp7f_CQr6EFN;c}Etmg%5bF<^JNT%suiulXGK1WOO6EsS z>bhmQG!yHw8Z6ATDI%6kpKM+0Hi)BdA=c3+TCeB3LnFi|-c^}GCpJ}`*q@QqITTjO zghtj`dmcS*VAcLlOR-$&U7;DT;>}gorqGABU`va=zt2z9#_84E1QNrryu03srqntf zs!V2oqt5cMv=tiHBTb6;VcfA5xbuXW$M0JDxYhU2MVc;hF*;`$A)+V z)=q`(<@MT>$nKnsYmvvt2!4vsWon0aaeb44apXJD)r5wwifV(FwSF-JxBB600OSx^ z8$N#yh0eCEoWmcO!9eQLNhM8>+S*-PR~I&g+RQB%E8xCMg;+=5X}VwsV8u=`@A1*m z5`e_ayJP9ubj#jClT9M(`0!2jH%F@-Bj~dXaK)!O zEG&NHx1(J$dq5KXg577Ayd=zKIX1%1&c}sa;C37haQb zx-yLS$LXq_9b<1S_g8P~0B(Z)S^Tm>zpZ@+`ZAqUhW%0M)h0z76-Y>k1 zDX9(lZCSnX?Vs}rE?eV9so|zi=#KUd-Rrgyk72!%# zQJ*4drM&T==NEHiw7qddsWIeZ25e#@UQC^JzDI z!=b2I1icq2rRaqi^Lu`pHf5RWm=y7Pe*r9}{*xz;tE;i>?kM+gNyu7%(TN{dyK;K1 zdz09CziqB&pSy0prlf9*t$kxCdUH8E_0O}v(QwNiWzl9jwpYnbJlN=XVPUv4dUoJh zN$s9|dP;q21=71sJIuxC;SQW_`h~w69b7w&#qQ0ntP=K@3C;iP=eFyw1Dov$FI??S zN0%EL9wBvOI?FsJcN6c$6IwPD`8Yar7Cc|ZM7|0rUUjJo-G921$K&IVvu`LYs8{`FY zJMJzBEb#8#yLV&K)2H(W&+ZZ${s6WM6fPizQhu7Fo;ke6nesb;yvIW>mJXVHuk7rW zf4oDo87q4SU04Ld3T6swYHEOQ9RwaTKx{$FU3>#4zgS7>kG3|>`9jFLkei#!TL22* zLbQ0p?-$6!gV>A}iPldA$Ko=qFkEdDPoGW()vg_W)w;j>i}u;;FC|TPO?|9vte!5D zN2FMiMf>fEdL)bQt|Ps-^4X>JMrzfo+9kdgYtBP!Hq30*%D4CxNF-)-LA*}F!G7Y{ z>1Bg_)>Jl1w+yvue||EN<|K?cxRg^%lf~wcw2BTEXhfQn8-X zyg*0mdrcI#$@ghu6ZwqQ(b3tgb%@a8%1y27cCw_B!ZnNHw=>?!A1m>>pXC1(`K1rY zB`#1SB~ypp6sgd9jWVRyZ`{W#WoP81@lU*|3{F-PMY?79r=&Ki`Ro;19T`1N?4o23 zrMT(u&Bh|X6Y6d6f-wG%!5O;++&Oo;*)z3Yt5s=g%siTNQ#9((taz`(lcjfU!A2#O z$EBhE_W`X+6QyCMCMbte=j)X3UF>B;&VpYci+u%8B|Mjxhnxa8b z*&=|y7dQS#xq&Ku#J3Tb+S4xwC!N11^Vaq-Xi^aH(wYCU<<<4s*uou6-TYaZoFqF;ibNe!1KHI)n?DWTBy z1$1Ntr8otEz+oUNWo5+#Q$KTabLf(Cj?D=b?{_^kd?VCwbroH&1RWh-8=~7LCP@)8 ziqOA)^Ty?k>(KO&lmCdX52IpVKChiSi3qe++DhLqWri%5AJ%yd5~!H=628{kZ=ZCJ zx3L`0HEqRUP~^s!uR|a9^JCq)S@5_XJ}33gA-Iz})%r7xWWJ-1YGXn;$#qA^-5QT5 z*XZq5W+8KiBcYM_q~XR#p@ar6@marc?mIGy42w@CSo~|(wn^*Grf;&WreD(CdzD|Z zv%D;9XV$`tG+4Uvaq%UueX6&*j>hD)>E)J9U%dod!%=pb#hZH8^l~8josoPx)i`bp_ zUo}kmG7FI^exDO^5pJGevOfq#Kgp@*4luRF+an=l$x2|m>8#|XyWpCi&v#FW+FhDZ zYG=hX)yj`barfe`?)lbm?$2>e?$z}nXW#J)!NTLjviTji%3l?ssQiL48XOk#zwj)+ zH?=)dpj;S2YuRMqT9&L^c>nAp%k{-&%`eY6H1lUw%Qog`Sondf!fPM%9o1yYPCufb z_KH*FxVJpTD^4?XIM|}APh}b-5pzHEDT<-ybsJOl6zIb_Z_jm5`m^xQXEMO>amx># z`T|{yO_ht=2RUw>e@jyqM`mU`-9ra&jn6z_Gwwl8g1H{hI+E-b-L=(%TTpuzp$^N<(G36Iv%?% zvPl_V=d-X<>h^xWwo>s*!NO$O)p=~HQ9Dbc;W$FyeYrLvuKuPC!)2Kv*U$&0o4RvG z&MBJ9kV|4d*Pga3HSw8;47yH<6~mRXpLwTdPB#+cmr}0~zs6(nJC`(i0?V~I%Fott zyBkM?cKgNuJ)3GJCTj54bw7yfDs9T>G_scNnS63q#8~HE#mLV79*yn&LVmd5CJA}O z`@z7B#t8hvQ7-kE0KJ^t=8zBey0JG+JjPk?d7RF zNv^SQ+Bik2}Qgq~qnzSkzhUFOm|` zxx3pls~!9^V=}Gtdm_<5jgR{WU84}LA${UcP!kHz@_<7rI=|_6wA5wbnR$RI8qfTiClh=i&y(N;d3`#As zjGYsD{nw)7f8Hdi6-*I}dEyyW->c}M&&>{`MVZ(L@A~?eo3=Y7*xv>dZ`3pf&po)E zTZ}sX(#LDyXEe1Yx~+7wrnOlpmP20gGU^2u!SE{$Y%V8}^4lyunA^0?4G)ti-mArR ze&+cblait$WkBeZklqy-^AyE>U_`TTTNH(>drB^q6H`x%y-r$7m+tPpW(W0H)34&S zxYF%b{zu&VHTJRu!eK<>59m?2sk!ey@4GKE{XLHVow)w|r~msMQpndG&Memh>Q^o}VkHH*Vpied;Y6aIypQT{WP4hVY`V?@ zbsHl}f^ml2Rt8KG7I1NTld`SitCcage`i;fkmnR)<;OA178Y4p$~-V*h>|pU{c>Z1 zyxoX1Vfji}VCY|v`iiuZHA|B7l&hV?A{}(=fdJtFt)eMZP{cv%*0u>g&B)9aqEuKK34M@x_eAgVDX~84dG5mxVT4;=Crhz-a+G1)m|Ku-4!K4lH&qx}o zr)S=w>ER6+$K)j~v^L0b^YP{s6`Uq67_s>us~&koB=M1RZ0(KnbPx5li0a{uRxc0` z{cay@d-bUQrHb9d+H)??d3SF=wqe%kjJ}6@ygYH2ALRI~qs%LBREaI{+)o3!>=bFz zekT9<-pSKyj5Q`0UxzEzO4N|ecWiF1K58M8@A%Ta2brev(|EG&dRS$BdKIM;F_*1S zIt%*CvkO68&B*Lyv(2i#+BYBLzMW7-rfGYJ&~q|y-63Se>9K@KDkA_bAdeRmJ0p}= zQL&tB4YIrxTB(Pj=KR8fUX9)J9j<_uClI)I=-3bmxC4Nu%y>zdA6>obR{$Ujz$DBq zEHLYA<^3I+hSyvalQ`c&HEvfX^)PjIZtfjq0<7)n*B|tINRDh_s1vR2%3N=9z(XAn0X>GTPy0}a_Gk>IV6B1p`*pkq=huhTs>W9>H-$`MU$+g)|rF+lXV|V*L z@93^G_p4flpZzD_XDSMk<-7ICYYM?ByRD5%!vc>8Y<5^-Mm&=kd8^HV_`e^(W z+i%+X?52JbDP5fI7$Xej@QqFSSm%{opxbmh-8F%siDxuDBcq0%o`-hA2?9W%09_7Z zemgQ@*Uib^z-v`a*BFwPK)6PI0*z60VXoMpVBj9 zz*PepL0wl@plk3*g*`Ej(*k2#{MbYse~JND&!AdB#Qt-fGviDObLt2NTIJcic-)>) zK=Mbf(aSV9BpeiaE|j-JX=s&s8Y6#h_c$8vbqZiiSX`g|X>%{|3uiHJ*R`nCHmPP! z^4!}AjTE_}3umz*F)mJ#_P<^wXSEy};(x~7e%(sBOr*{~A|0ejHr%JYwl1w`+Vg{M z<(8TAgP@?FK2dkqvgB~O1to4#{cp_^G}Ye!92#!p;^2q|!rDr^DWM3N1u9u4*bnuE zux0`<3Y&?le3h(y1a8dt>ioaS;5AfkfKL><0!?#LK574{N$REE?kx8plNL7KJmZ!KJP9M2NWwO8j9eA#;o}P8l z>NguO$ySHTlX4Li&|G~Sw{PFp)YLrmz=Z*PFrfQ@0WyFn83v?k`I?QCF83|-phE`x z#IoAj1eF%QTl@P<-CAG6KR`p7I9Bd^-(T$tw=Ej#$M``*b$@g;o|C7EAE&uKWr)jE z#W2i|eb$GT_X~D20r>)CCqD&j<{EMbtp+xZU`zLbD^n}6!(!J%_QpeX5GnhL0DWX; zzJom%xc%L|y`=wpNGw2!W@l%YS^WMa)@ku8sRfAoE--?@9a!z{?qcr{_df(6>VKs7 zo}S#VhUjo`a1h~TZ*R}$UoE1n$8rtrd}aSClTJM2>qAB3&X zF$Wdu%EyKV5!h_@YTjO7H-%-)M%*F<=#a+}?j=aYo)8c4c%M1|GKZOigR&iVtsUru zggybB6dptX36{KO{BA@uy!X)ze96+W0bB|sz}@X(xPa*nATu%khL5j#a-eJT+Ai1P z!%c2z4}uI^VimD%1h66S)F766_X)tyq1XbpZ7v^0_zW11Zf=ZJRG(FNJYdn*)Rbo9 zZ!zfyd4zpoKmi8mk-qbFZGh;(iau=M0CU5*O>Rz35MmYOIsSmg(#H07RCF{J0LuW& zhUlGGTMOB3G%Dw{f%_@eey_-o_3c{%kWN%OUDyNGjF^}hkC2eZ_Y#`)3(1@&ceuE? zAPmH2WQfyIAjQ(DY3YZjv^e}j9xdrph9zI(!)E6HpnO!QnAtfwTqdo7(~GHeau8QI z{jR-Xg6t`q2i_1BNh(L3%d(G5yI6lDFWFmO{{D>531EE41Bih2KI&53%Z-9^#AEvE zhUbFeRn>zDS#+z!v38nww~_9V?xv5;(kXp!mjm_T;p4T~>b3N0xeFJCA+fWZu((>s zhIRuRq;kEVO>&Y}gs}rn3be0evh@7?uo)um^4)70bZRu_XtvpQ=3NoiCHZZ*(o{NW z{cUJ+vd|?$7>AfxPEGA0?Ck*GIdCNayc^gd5CWSp1jk1GJZJ^?n}&mfqw03Yw>!^) za2qJ8GGC^{6~M#Ce@ICQ%mvcLP2ZEsK~JWjfF)HqFIMHO`uQX;EaCghQg|R|4R&3f z%&166+y>>p^&%z_&%9i#f|6W^5taxGXRC&@A$kTf%)4>V@wHPA&b$HQWy(upnVp%2 zE&0pRvoReW2RsX0Z28WIZZW_iUs(7a^Z^bIGHyh8kB=wqD_ytrqbS8o93-g&lZ?S5 z0r2xa>#v^>(D_o}MAbNxvFEj+?FJhr@llSGhn}JeAK9n@!vRFHK*$LKVo#qwE%QEe z;^yHYCMVCy%R@=|En{cLZda3nP{$Ay3>&v$U}OyW@`VPtB0zEgfP&%g--ks+WLH$g z0?4Saae$k~fLJcZ}qeDFZY7P#?&efcH@JbH!Wf($G&{72#g=#N)6HW(?k zUjy^Iv`}A2}2&$<4B@9UI2J^tjq)nWGTF@*Z|+z(9oc2PfOjt z3A&cxaUzGf>{41@`~YAV$c@3TRhgEtG2PW8CZJOQ#%g$e2qhqOA8dgxM1~2(50FXG zF)|L%%&0)|1z`+M$m#6+%Xn};?HwKPy<6e^fOl7G)1yB=Jp4X@Q^%WpgyDB0%B|B= zcX;1~s9Tn zaCdl;p1Hopmqeu&iv^%_y61X+SvlfGAOi@(L8ETJ1nvb%fd4LxKH}-=@0Tss9v&Ud zd%;cJUM&CYS<*p$)%le#8K&&l<{bH)R^SXsNRW1QhpjYQv7O7#bdi}1!!4xi?snr-3I#t@a^4# z8FWFn1#Ecd)G=FtF%VnQ8yS$8het={-e>y*Nx=X0{re~Q?wKP!Mhaj?!r-Yu&4mhh zPBOVb`ohR4y$TcCG-|+#7w-Mw_;|icJTWB9uzo-bAjlkmRDwVVuue+yAj!(ez;zw7 zsaAcboTCm~LIK_8lEvCtgI2%=1H8OJt}cxoHhgg(KHM@)6TQ5ipYrD9s{B^0bN{7X&dPqN0NFx8NQAk)$chLgWJ~LrhZO zilYZHV=blx?D;I%UahLB>F-kfG7e&vaD$1hUjkiMxqflxgE`0-(C!5w{Ca$CXwoVw z4(_~OgF6@4LalxgDKW8$yE_p$05||>_C1xAjZ03JgJ#0JCohZ$mP^(^wq+^N7_%{V za?2GgBh#T^+-zd&>IEm0=n6bkDAw%Bg`nplQ@!ifd{+!@COsCccmSf^KQItk&zC+B zyQa(f8-&_6VBwH71B(u!@C+T!Q{my|&3++7-7X6o0j(c%`Vk<WUc$`A z_Ox(B9i+!V`9w=AVR31>%y&x2TMSFXj{o`86b6<7CrRY#l`lxr0M`N-YFuKXETBCp zqC-G39E9YVnVDNQj`}V<0orT{_caH=fkj1ZVkdR|j+dur%zTi-C zbO!SS_ku747&L&7lSa@2Nnwe$gGlDf095M0+Pko1xZHR$jZXSLJlqsCwSZSDNF9yZ zP8L2MWPI|SNe@{PtS7vDKmh`1FI?->z#o7EhKDNYbNz>l^i)O{Anict^>3S*fSzt) z&s{P_77kb)m_L9V30x6qCV^#x!YbJN!ro+ zIP~L#1h)U~p`8Zcz2W)cHU~yRb>$D}U&Mp8|BHdE1yGeSU07ZKm^WlgO!4xlj`fhi zDCcRc5xKDe)4|K$k1&l9v(10SNdzO9p!42W-}ED7kTf*x?p=5hZSGk7;)?ib+G4}U z#m(&xnm)za5Np7w4o^;ii?I#V#z1^RB8k>!#$Yo0E1DgnN)&%eAc}oVZV6Y^SH8|^3x9iymF1o^ITwZ;c`$-NB z5prYS6H|4Pds#71aSfCd1I`c+4=>Ob^&tcY$Vz}TD^rPq;C|_7Z>CfTLQDdF1f-bh z2-h%Z6(8l=KjomeA(>Vq_%ezi909kxh@= zR&WEfU?87RWs1R`R|d-jj=Cb32x2Z^lY(Oc8k{1d#!p~6V7dU}&CbgMG1NW?Dj-z^ zmcjNgX3S=f=z)v~1^?ew0RsBmp$X5R>uX>C7AlHplmvNcPfsDCv?%aDupQ`HPY!f@ zK$S%iExVRi5(=A3Ko;+DI4H}^%1X=39OgFTlUQEPm6J6UKVqFW*qOrTtbE@YtbSwh zvBoWsgGOAHM~@!V50An)?faXJXY%suoQQ0MeU#4&R0U1P+##6(@H*HaOS~f34j42f ziU+wfso+OpX%T`T#1=?B5VtTX392H*mBhfryrYBe0sA0_M_3h1f=FK4V!5GKBqS*a z5#_JZsUT!Ol%oL2HZCr%6s$MF55Rcvz!9hx?lzw(!4E-5_&`pAxU}Ht<34`Obty^# zS9dGZ*WXQ^4^9M?+TsbkJLDb^mj|MZfGywW;#f^p6(N8pmZ35iFNvDj05ua_Wzu5_ zUicmm2;unf6&V6+p96FWQh*$@UraTVN^mp)KLy|^@vx!9@tTDDyxAGg3y1lgQlKTK?nSjU=Sh9L<;9SmKwQh;(4$+xwas z-xMIBfv^8Z5nn53B^92TOA0E~u*gVy$gFtz;OODv!wCScnKelnl{!9W&D@V5aH=CBC2gB?0PU8j$*uHi&*h2zzref+ zI_dC5`P0;vjyyqW?+5%2K0bz^x|6k?ofY5*%_%PjZoyXI`xhy+9QcjL+=m7chi4V0 ztgsgke-xL5l#C4E_`&dCA+EARp)HkS>Cxzpa>j!j6|31Ws)W+ah_Juy`S1L49HUvz3QUGTJ!i48SL{bB;fZ`kx3 zu>OVsy#s~~2uzPWYP`=$>U=oBIDVA@Q#C>+3$Ej!wVwxN(f98pA#D<_uGRi)5Mrmp zBO>U;#WR3suuSe2DWA<}*g^q$qr1as)Z3b#p63nYIaO&>5@N^Y(Z45& zUDQ)?!Sc5K!@|%YGljE~`Z{U|^yF|AfVKxpDSTyc7jDMp=5&yG&q4eF$>afdh^aDJ zF;F!8_dke-q;$zigE0MziDLQ(3X7bk^a*kjRfwc+<*g+>vL_y9#X6X((u+ zi4z8*5y4wett!W1PkjNxJo25}cX97iTeJc%Z6`$b_$X?ETfpIs&e8A#_-BO zVw&5unoZ&?goay?jae@4nJ*)*fMcQ-gn{_@r=Zq2b_$eX(4r&T$wo*^(v4(dFp`u{7?Xb7l6 z+FD>gCwzDfdL6-{UdMrr&FSy|m$v?+1z{b^o6}CfKin=pPP8?ioSX#LW4Y9ma6cCp zJOa2y8K7CLuI968fC35rFF+NUrwX~Y;;v^krfmp&gvXoMPBQ(ZlOa^Z107vix|T!W_wR!#XF zE+ACRK)D5R*Lj~+3~{yJfgQANNTWO!V`Q0FSXx2HX1*OQ z$83rqSrCzq|1$$$8xLY=`uZe%5S#npgux2cz@bP&OWTFGchr-6NKs@v${`@ zEBWscRNhDPLeDh`{rJL_h$R z*jM--fwgadm<93!kiR42Gcq)U)$C7v?14!api2PZ4Q_R12c(Ly8hyKjV0D@1|NTT@ za77S@vl&#g*)%}61(73`8Wkgc;;91|&{s_sARKDzIN09@wLoq&Q*S3|KlnK zF+c)Hk6^)7{N}8GXX1#4hUV7l)>c|fXIwJkS_HO2MF4uTKpMtm(*S&T;Pcib7z2~E zpq3t3a~ZzxTvt~okkud8ztzphzfBWXb@u&fj--SW@kSL$_u?OaGbC?_KIg!-@pJQ#4KSU1Yr)S zOw7#i`YI`0I=Z@{{VQ3yxia8CLcOTr76GS*-VlpLBlI&MwGPuRd$0Wb-EpdeG&+nm3AtjDc}8j0l)_n3JC|agWPA|p}2!Qw&YHs zW!5X6m26J1{2FB=o}W`7x~L4zKj3&YS%4K|GI8J3M+Vj45VKXmbxT4=2=@C4fx*u3 zy9@KCuA?ItNu&&9ZEVk_&Ln8h|(e5!gvd3&HEPd;dRX10dJVX>1hT)P?L0v6`-}%@U6YH>WQkD+a<7 z_~T<0FVXe49uP+N-ACMx&Ha8ZFu#I=@Tw|a=-stijDr791NskYR@V1W zGVt*65s>f`VZ?v@IP_l=D!?BNtR~i|)DjrJO-fNDf8hfmELaXIaHGSB3<{dMg-$37 zF|TSm7vOILNNrF-nK~zAD3!lk{AO_Hh2N##mw#=klQ%p#8P{Idd!zjQU0F3`*VI@y zevU4iH#9N)Le#l|%~!|#&%y>B&3CZAPH8FX?T^?`qllmADC#ZP?~4*(T(Q2KVm#Z% z!5=K3ay#ETjVrz3y2|iPv$q-YoAub9s5$HF)piwWqA>fSkA@mm!VZT<;OE@U zsnWIUjljm=#LpQdt#kd$(KqMLN%vSzvt}-l?&0ca#1cy!oGl#Yh_sztpYe?OKfWBN z^p4wUJR@_=9T)zl?JWQ?=LFGAOZxQ56lRF2qFx{2*FZVc6Nr=$YC#Zf{;(rQ-A*p| z>=_kwB;h*apkD4T=l(P`L98_aZz}BjArg`8$I!xnb}g8cyzImIYG{WH0}}+SBOn<4 zI2sR!B1Dg&i5QaMf}YL7$#EBr2=_Fh-!Gl_v7$(MXh?GvWq)bW>{;m*acQaz!`HAE z3#FG2jn7Y6*sm8k&hiNR7DhV{ei{3uiFz>jUN@E=Ou4;wR8p=uU+`Vu;*d^h@uo}YwVo<_TUL2AfKJe!xAJnc}C zKMlz%-F9FAM^^yM&!GPibFtG*8QqC{?yz~}Dd=;~3+uRugc8vK5){mL(5G%U%+fAo zW@36V_(hrw#!WV|^+`!YFg$D{wQr!N>5)(E_nWiBWP##Zr-Zb}mea>V=({?)i=air`t?qXSyubdT68883Y&rrSI7Z%xL zpZ<+^nZW1@t}B191o zkx&stP#R1OT1r|$8fgh7R1_2iM5IeVKbn& zz1aV{@B6y0Ip-K-&auf`|Lo1f^VZv=+hO8eK|eyY*F{_wiWW8|f3${0c?>9Q|2gk$ zr?gkCC_Es=Q@v?r&}E&=*fXNT#VK%fDg2(vw7*gPrLc6L?Ny_bu5ra>%`W!`WS0|1 zn$)#p*oJwwMiW8;MYd-g`%A)gE91o@6Aa#MFLX0yFtzj$pVPA4?zBo~ZB*r5`KtSRb%CnVQe4xcJ<<2!@a31@laS@3 zzQ8nJrVFmgDE*KdAj_$3jJ{5Tv@h^As7v^|jv(`2*({knjZtQ80w=9l|2r1|uqf)J zvT>VJfpUbB#R;bHp|BOih*Kc0R*3HgrY)UPZwI^#FrLP_g0l6~cR zgIiBb4omAFPqL&QX5+O=CN)3XpC5h7=Fu*RXy!?iz4YGm?k;n^yKD4+YHp@3vSo-U z9@*)|wl%MPVE&cMDi`Z#eXSCEe~)T5=g|$>Cq#z@L*$54!s#iEn9qIv^VEfZt60M8 z{BrZWtV_*liG6n_6I(Q#++bD{UHY;=zePGfrhdMBprp^vd0jHGz1Y2XV`x{PGtanm zv@+!%hurKjma`j-vNIb(+783(hUYJdY)w4w-eXx%WSFU@7<{6sS+^lRMuh$OilL(z z6Oxl?wAO+c#ia9^pFgRI0F5asDW!qy!M%gM8c7_@uc%E55* zs)zN$d!g7T+m2h6ZCOV$h0dIMMmEG5xvn_#iz>F`b5YbtymoIFqNNEf~0GoEBtxX4agFEwpzUKP!)mO>0{^T)e!lF1O>;Ps8&$J-Rm; zLT<#Kf7iS6yCnULxLX26N~+3J-Z@w>)F=Vtu&T%C_@Lzw;labCRKI`-C}Gn zi`ZH%+oA3gx+Z|9S8`CU7XRV%aJ1?zoRGRd%m(A~xwD^|Do)U2RBr0so*?NmwGy6fOfbAq5 z5U?-5_!$Y^ND%Na!8JVm0=>jOX2cxTY}3O)Q}!3xe)&Za20DO^j?8N4yHBb#a&J<} zt5 zs@Z8N!q0yQ1dpEHaN<~N;*rCL_dBH@J$x7-f^-7e>pZrXKgP=qz53Qfj{*sHPN8r8 zNc{828_<>y-<}NcJ*iFPr{-E^DiJ47IqP5{Ez?i2yYaVlpl5!=-o4J=A^W{OI9@ZB zJl+}6@?1WybS9{LxcQ%Zw+D|zl+#f@JtEE(N2*OkrcY`d5%Q$&`6Y(?O~YR&D4yJU z(PLQgv31~KLExWw9{SSrduVsP5q8P@q@2W0Y1A~hAa!nh>7T1FO7E9`P~bg3e$^!N zgHvw>jajRJS$&o^$EiPTyli1YHcoyL-rsaCUwL~nhbpJiTf(4RrwK#(_N~PRTI9_U zUy9?`xo|jli=^~J1W4l8Lg$MwB;v~MpNrbDb4zS`Y1ge~`2*_`C`1O*RTS>oA0+JN3rWR`(~2 z-;d4Ozkl~mjQxMUmDoJ~9V7X{ouCvXbDQ;-X?20ICBY^W2s{dPxOSAp6zb?>(tqmX zWivqL5Vvf8m(0PIcYqh>j+F}jVoKXYBrqyk4#O-4?*;&jb?rD=_p1G?aTW$*T*YLO z%pfbE;y?q@>cVMf^5V`H@HQY2Q0sGP=2P3&=x3zeulffA+cCY`|1b(fi`TSgjtdGp z$YfQXr6a>Td4MON`?+G87L(#`-~LA;n&;09Kyc720P*jQW@l!e6%mnwgb<}-`dpo8 z)GuQKeL$cH5rj7Sh{eB5ZGDhg?*}??IpT+Yya4-O;?DudGQpi#Y-`Rt!>}pF9Vr=Xn?kVfn|(p&~V%|IXq)3nQIV z41+8|!NE~UNz&tVAj0s|iJ)%S`FE%cCLUmPh+9+BZ6X}H&}rxZ1jDPe9#5SIWrob( zV_171qN#cDDx3D!d;o|E3@f9_`SsY0&F*p0JxiI`R8nxzKCO~GAt*@+e#_7`V9LmO z6vN~U1ufBL_{c6$CZPZ?S-P32FV{$;+(*pCj4y(kFOFseX%YDstfePEhHoE_I;i9S z3X+@dHY#3tfw=n<1G7@l(!wk+7G`Fc7htXUHH6{Gp-$FC4!h_3$A^8i%Dg4xc7?t6<{RE|p$7cn;8JwAVmQ z)m~tiLck{MI-%l%v2ZAciJEEv%m6FFI1bS6WnL_> znC*@F?GqqUfNG`c!jK#JcRJ*7kRrd|&+$Ar0ci$75E>Jsr*@BvnfWO(ljB=tA17<} zGsj{e8hH5_T}}b4l%ryffio`K>(ES+fm^`YiQdmq>xlKEASxrf?|rKQz)N~YvWJ(_hwoM{P7(k~$c5o-sLlO>J-*I#lfe`eKrzhd(y5)eQ{? zA+^Ga0a>+2-~6aHiDr-l&H-A$OM*@0A)Fu+o^+#Ax5QgD^b*!2|O1X%7Gi zVTB;+2UsD9<@C&+g{|B%QaOPzZ|l$@f&+|chb1IZ(cWU!pw+Jk?;~L@U%z(sD%>LJ zPtCtnL;BJPjm}xRa-4wx@CXdw zBMO1DXP-2Whbo8i21#*h6$V1luxCLPM4cbFAh<#jRu~BUg3-f&@paCFjNa^guepST z9;q?KLx74qCk^Nnxmfy@z=PHoA-BM4#Enfi?=3c}1jvhdl7oGvuK3fbw{rVq4?F$<2?Wf7aDz399S=iR0#yw`<$%?QHB1D<5dt{zm-pk=ZJiy?d+XjZsK;9>Sx|zT#0++>`2X@(+710-M(^eeULE3SdNQJ&P zT-fdac!Z34vDdZwq{28ltI=rvmm9-`a_U>Bp07X{6#V`@Vfeiy@N=xYd*of@dv}Fg zc<|Nqg7wCVC1H<>y_Jb$5fW1K8Fm~f!!wpwSC<5?f`2x~u8Zr;^b~=y!)!pbrI_{< z9)^z@ZV`b;|9bRES^o!cU??4NWoC~E+6O!HSGsXyCrxr0U>M0FV8%#fo}yWhA(kY+abFzlJoVqf7bFuE&2$x(Y?xr zg@txZ4m!lGHT3lbDM<{DYF32%QJiRil=*r1_^x6O9GKf&p|T{%jNzH*=3#MKIq@z| zCoHCZ+k&!UF^FZLXehm#JD$jm+zXHs?h!=4d-4ibJ8Bvco>M)4PQRe%GSTFi@F3vP zFHCiGoQ=!yL}zfB>&vn^8Fyc@U`wfk{OWg%?cd($h$w z-gu?ucoQpuHNSNdPyirKSjH&}x#jLbY(xo!38WJD?x7{$hm4GD7DB~P*vy9)7mE=g zD6~Nvr))xPku|HVsQ4VeIZ3(K!o3CY2kRQ2qm@dPjd6+Nzklz%3+ImIKOKJ;#BS^w zf|)(`*?dsFqZ{_t3$HypckCr5z9Ot5y0tP0l9_`>>E)hpVA+7Wf};^c@=jRR1t;+& ztuT+*7iztpqQ@Y5%&A=seYA6lc;@ASN4QMzbms&FfF{1&S#N5)Z}(0DbesFA z`7{sDT)3wCUv1pg8=(F`a1%b;-@oDo>7lRF;VrNl!UKl{6=&~YrT6JT<(I2xL`B1p zqoUBq4~@9s%Z%uXEC+P(eLFqo@&`CP-*|g-f8Wxv_WLnRaz>Z|yuVHwLH3L#PPk7i z1FxxRhEg+gpX__RKS`ewxdTKO(DXcQoghEmV8nL>ivbS{+RZ%~S0-vf&k)ooAgB>> zm>lx#BqS;xXsSH=H}yDP^H&H578o4PUWjAMdIIreAzFJ2nl%eBT>w_#&>~nEnI9-Zz8?D&r%(y1wg-aYUcwlJv=U_w1SlTM_B|e zcSvJ#CgX-mNl8IP_Bo~Kd$}Qns_J2=Fpi&jv~$kVUX(FZ#-L5tBufqa0;H?F`RijE zwsQm52wM8vx0|kSb-)?2Gk+vgFX?t5ftTO?1%XA-Zu%$~{kus2n!PBnDl6#CKeSFb zY|K?6aZx-Lb8rEAj*&=r#^bE4F90~B*pH>@ffS%E`vE<`D?rQIAY5K{>YoduV`MCj zlb-oDh5f7p_6btIR7=RI8x2p;k-?%5oEc>GZ-b2u?%sV;;kLKW*wVax{vQorUxIW` z)a_s86u{1^p`jts$1)kJkcNTkg1iJ-vRG3qNbsJP^MA!5%x37lo-~jNcZnx zkq!CW7*fFb;_L;50D03noUhbUoaJ4aNd7OFb=`1s5;dp`EyWB}ug{97@Ts{dUXhCs zYy{K)+}LMXiI{3=VxmCUw1b0#5cHCekleU&1G?CQkVFGy0Cs@~(eNf0F>9VAz~}Az ziue3qhW$^Ek;z|G)xCL3itI5HvC3;}EL;Sypu|N|EN)~5&`Dv0+i2z>jw$Gg!c*tK z$l3^XKhRY8yPgKFU~W)jTibVJtys#Dwam##@&_O{L1dqwEu*kr`(p&PI?b)q(5t~d zilDiJ91E~Y$-UC4v`WT7uyV+6we-(J@KX*yf0hKH2F@!Q#XfSg?_^BOJ?!Y1VU_eJn(eZ#mlifVOGi+dLwbTZ z(umQK-XJhWPJ2p};nFZ1`Q385_4B_HRUD$wlR#`%Sy>4p`oIKBYiH-{&MCH&C-?hS zT|L%kU~m5%F9LEQ;p{9%PzpGJas=J02f+u#xqJ8S9a`@faxRI$y}}lPe52r=<@BR} zQ-SxL#XXq=p&RuCB~>{w!I}}yN)?zN4lo1?D)N#sBP(gdVZ0jEfY@r4tQ9;ORfSk~ zs{~LyKu-vC1zynSl!aUBX9U3~IgpB7hOpOeSgP;iiAGpLWx}LpdN4!sUn|IEe_INq zreQ7W2l^llDIHyq*U+e`6kFoaLM;X*wcg%gX&f~$B$Lq4=yDG?`FAQ~j?!^;*u})cQN6v5h^WWA zAYfj}{HlS3g>W_y)E*0U!q9i$x+k-bXAtlF0sbFK7V3l0jewto@Bp7ksBe8kLlbQh zRTD6h`fkVLF8aLYfzZDin(_xw@dN5Ug7O;KxVQM007B<|th`CW3~8)LER|lE)8F0R z+Kl8Efyy5!?)r3rHME0ShAcGUfzTXekJl86LR4qoc++$7N;+ zNbPzY-0z;ffyG5gb7BItz7oXW4_fjrNH$_BF>-u3i%Hi@%g7W@)gHU}uL9HDq*`0ye(n|>(8T)s1^(GXUy@ciUpxW>Wxmz6>Ch7ymU%0LaRGJYqc4j+pg zEa6vmvSz_bon5hYvvo#B24U2FQIbh_>S$=!XQ)`zSpdX6H!(Ad&C5edSd0~&m((7>b?3)0o&pvQ4Gp;Go#=b=p2 zx4Rx32*(r=?Cx=HHX@wg1mc1q&j)PY+|whLiFvYvs*05-#gH4uS zcp9-1y|=2{cr|5kTVlb^J%Dat)Qv z1>Pf`SdetDzd<4!hbhpRujdwzv#^}x;$lOAhW%H(l$CPwt@6G!xd)JUK&o?!;Y!VM z=;cnFI3b4=W*3FX7l`O!B7CbdSPAF{gza>m5|A1Y@WQ)iiJtrKjDrNFuB1EYb2=gQ zhlnH?jb+HqKEu<~=Q<-ZH#bGng^ixOFhwS4c@U`~nF)7ZGr~iD4Si%SOL-zX$1se1 zzpUsYHO@*x<-fJDYV<-7Vn!L610`D%B{Ft){N_cAv_LaSVrVaOUL^?Ga0;X7$K$R! z2V(ZFg~dTY5t!W~pAaMU#~G?TB6OWVJqdm8ld7tleZOn@pCIk;EOy&SBE_#ANCpJa zr{23pi$#e92S|!j8NUk-gpFBu@gaOXA-ti90Afz+8=U2}tZZ!Q$Ur~_zk)CglB7Na z4JhiRg>xY0#<>Go&FTn$$xU_j&LRrV=XV;g-7sZ_sjWtfQv=e`h|Ng@BX&0KDt?z*p<@J9~KB+TXA7D?=cG4J(a>zwWf7zXer08BXY zXMcFIBrkqA4NWb&9U(AB&1;t58FSFi7jzQ<9z1S*ccm9Yfl)84W3J*pLcI(u|0x8i z{R^wpmMGP7t6>6kmJa{O33&v@AeD94Tx=x>g8*a@L`LU+%nQN2k}&KBFr(4wi%|F? zDx)xf_64ys=OOvO2cg|XGyQ#*j{!KWxNOgCL*)Gp*aDQh1JGBZ)^zB|Lm6KV-90Qg zcN+JMFpjNUevt~Jd{0@!?L<$`0T93wAj~=KL zmEnATu%9q`8SxkgqkbNA$bhf0@d-}K1YjyM+?cd`Xy^o@DIAZ|U{I2(ivtdFNnmnF zHFBKD{|c!t^Pq-A)_6Ck6H}S>0V_lfKW*ivv=KNOdE6a}cIaFQ_$i?UiHC>zg%D4) zjSvGAlNd%qLP|<-*M{VaUqmJ0m(IDMJ23LZz6G?^n`sYS&9WM5YwRTcu8$HgCssF| z4=@Oovy08`2hIuAHyR5ha2!2rozSzl56sQYHRA10nR+&9BQ#_9(4Csl$gnRm7p*sd z&Uiv<+oo($)KuWIunK~04>k2$%nrQf{s%}2@H}DR5JW?$_fW8-P2yst0rQ9uBv+_` zfbJ4B@lYP1Bi7tL`BqF6Rw^)JB=>|XK%qRp$^Ja>JOtA?@k2!%ZbQlFH3nsFL*x~a z*)O{Y$Q#`1%0lr2xO=k~*2Lup3baTdXd1JXWp6Ao00Z_SCyoB_Sh2JD-lE7yG~7>iZ@ z7e^|?Y2eWR;?U40wMsxXntW=|@@A*}1jp{KlCH)@+ZQyWfWlFqqCs&r^&~#$LrMxo z!moH6GUkz(zj^qbOhZaQqJ%34!lk72i@aVOSQL&Tg18^Oq$nJrw8L!svw&^9o6!{< z-G~TJ00eP#;)t>ssW}`fGb&xehVYM_i8X+C6H@vM?39;li~(!)!7~uqaG-9N89!n4 zT)oHw86F70L1^?KT2?I`wnAeHL_9l=L6~SWDdFTR?vXkW3grm^07Q0&3>;}p=w5g320qi!dm&oJzLg*RN}kg`=Xlm$3E?Xkt)z`nIKmdl0OLz~|BS0X**!Z$D91>?* zfKwW|7R-q*2?ukGv3uaAfw@}`;*X z=SC9~y11SP8lgiB@5EtEs0q-qi}pQ;1O*-DhsYm0A$`Zd@KHivFT``GW_QK0+vgMl#@vPU?+V**_R^lRY@vNXc{Cx}K-j3LX6vpI3C z`%~68RG@E63;$6L4G9hXh%5GDQryQ(`wws?MaB1!c;1@dRJl9z9M z#$BhW{?t-5qMo0nh@s5G8li>&F4%2+xV$gzt!ZbrCxjCa+cNizjx|Ob@&(H&Y!h0V zLPMqSs6g!$jkjiHXE$|p967aj+(rm}uh?Zc<595TmqYp3Q)ZB15fd8=hn9cPs)n_K z79>FFw;=LE&rM11cBHotKpcP$=&1Mr*<|Kw5R`eu^%s$Wg&`WqM2IEXknwoK;Ro&g zM*wT!G=cj1B*RS}{$N3Z92#IBgLpO?wwB*lP96WitMl`d_*a!ZbFyR&U7|NfbcBr~ z=p)p;<>PidBYT)N@JfpHdiK{IR*fdRKrJoQa$uf=&_W>5!UV}D} zzpW_6#f&IG5CcJ6m5uq_sVb`nm)R3zKQ3t=;yZ9Uff`Jed}9>@WM zH&Y*+%Ml!`(_8ju9aDUg6T%-ZUh~^qRNCsNXK~iEpN!qIABHX|R|J)LkzEKKsyyWB z*gtr>q4$HuNW@rdy4BmE8ossq$r%2JEEBwgJH||s3`DwZ2M3O7xw$c1Ja}D&O3AmK zQ^tST9cx7njTVGnZ&Opag6N(LLKUt90uE>h;^yasg!M1&cK~W2f`Ayt0dWOgoXz8e zeTjZgNQ%L;Viyv906%%ey2Kk7jv$D-{vajgB@~rht=siIPVR#84|g2hlK#CEJXO@_ z!&an18N<;gf9VgEFl{Q)&Qr&(QOjTacvE5b?wB?j%CzG}+@>?Eo&0*ft6O*OTsnAF zPo=-G-uHT_^t7n26dRNYUFw%m&;oDAv8tPP2Ti4);@9FjfZ@epm9MO?6HrcQ?Fk5Q zdiuO<4&u_b5+=fv9TkwP2&M|SijWTF52g-K($X%u>#k`{1MWiqHk*Jzu6{dM$Zel& zRzdcyb0INr{y0UX*Y;lY9`WH2;NU(PQ@ua__eTNY7a!k`?HFFZFXv#0m1;Q))&n5e5!!xt)7<Zl#n1zI@gfnj!%y)Zwfa|3>X4G6 zd_{VUv?VEdJ!S;KTCv`P^jAh?_${4N9?#190hpnhcnL$E1mihJB&f;B$*^I8mw{XJ z_|@pfyBX~(@TsT|{;Y!joZYafa9sSQ;__SBg?Y<^z%Ly+ax2HIJGl+EYdHU;t?EoK zXj{yG7MFZyJzy@k&#=dPKvX+}_m6Gz(&iMmf7JaR?GnGWDYdf32Z_R=RS#T+T%*3R zb38xGB&$*HVE)ZQdop3uaJ%S-drBUF-+rHGZN8?{;MwpiW zIvqR~%97Zb?(WZ^cDH9;khodcQZj;VY-mXZwTupEkGDQPrGHzn;Pv&pHANOG7r-(E z9}d*U#oJr!q}dORtvnQ{uYGnv7^A*MsFg4-91tZO;tA&4NYB8*fBy6d?FgUPcvj4Z z;5ml@Dq><{@KePmMIY1dy?fvJ`R%!g1P`eJ0VYAoDsU9rAmCIxs$;{hTprwMYFgU) zW?At$bhhC!V4t9e!Q~Oni-QB=(W)8xfF+8P%MJ#lq4kEaN^)}SG~I8>xKXDGEY5jj=8q`R>nRLl|@e90p zNwh3(s<7ws@j)Z%2`|<`fy#H1hSWA4RMg}>J4(T4Z;2gwbA+^gm1ZTR>m&!?uGkFW zh62ie^!pmJ$pc-58&5O8eKS*haq&+qr}&|;oI|XKucs-Umxv3Pgcd~O6~fa2_h|jZ zJapC3nwy)$yK^o@L)-%5Uvw{*iN|l|T4(E2lq@M4HNqn7# zhQ>Y;lH*)l$s<`FQ9m>7@)dr_!i#J^u0;vv5!22iGxIZ@%k%T`pV@3IElaUwq&~@^ zN5(oNrK~@<@6G2!1nf~x?jVNS7;th!p^IGfoEd)Gh73xR)s2Pv7-JcY+i?{^Xf=Y# z+fR*`1x=x1iZ{_bC*G2LVzj*XW8dMPH(Q$4?SD4K;>~v}r77L9pg0>vWY}%VE089{ zHSLl8>{;W7O0#uqy(rb|F88~ahsh?JcYb^H{@H?tUk)|HXy*wPv%CUwvm-R>F=2ge zkN7<1h>tWX8hp7{%z%VYMnOYE3OqUhTv1&IgsUXAEFDaYK~o@ovrbL_LI{jYM0JCH87DRWE`(?gI1S_?Uoj^ImDZex2Q<}DIXp6I~E7#D);HwNRRC0~iBg0KMKMO5nq;D^=94!=LHE7$ESZH|w8 zDVVg_$+1$&Iy+V8^wELeePi=}+lJBj^ku&gx3Ws!R|*>qkJkrcN>(hp-!O9BkJFd$ zOSm?=rG7K1*0_{cfJB^|B9u|$)9!{ywI3XxKCLC~FcItIcan*|u&YtUUm=qBu7}si zx@gt=Yb%2>)_oUU>Q3z@fGx{FQ4qRxupjaBVGu{yZ~&Zf*hO*RUm+p%C?1gf=%n5G zUR(Q3Cru+gcgt`owM4z$mIo&ry5b0)lD~i7!YPS9W2`{zR1_jeBHxCD{J_S?q#=>f zHfKDAx+I{CDyHwQ{wzk@5+x&}m%ICQO?RtypP|r|ADKd;ZoaPRMmEVdW9=`7?6Aq6 z$SRuT4>?s;C`rmY4vsaKh!>j)X(SuhZjp!FS&Js^HY*BIz9d0J?Rg;j5-GT`S;goRM|bT8!YZ}(In3IHya*Y?uoo?8Lj6{KlXdd zV~BtUXuKg+`T*}G@N2s+rf3z-&dv411PV_X;w(kp5e?viwMnUQ6}JllgCx2A6b>cJ zc!t>hz6U?>efxmc9i*eXfq|(+ux2APM&ph_$kCo-uC3{Y_S67B6gzW}?r!PsY9h5{ z#_o+$NzsBy@xaK4a>AhvE<0#=lLf0KG0zR`#>2zjSc#*5rn^HVJdbG3J7X3@sWgAL zP1QQ(<)2)TqavfmV!SeS1eJPl1W0<(we_V9RM4 zg7;LkU`Bp-Yb&f@e&70|pgSKH{4x?leDrs|QSenI!j*1)rX$>mqnIF&Z!`Y2lF3D* zHS*=@m*`w6e@Th20)z*^Sw_=caYCku7?A98&tq?lVBy{BDRz2{>fv$YRJgpL-S6r+ z^qr{76t<`{(jcH1d04ie+Nrq-+VBh)Cf`FM{Ivn+4*J>Q?V0wPYON z%t%i+W-AmJ)~RR^R=UT&&WX^&mz+0p1lP~Jt}34Zb`gt{iHQm3cP4DFa^FFff}_uv z%M4MzsVSw}9zx}ZP{r|mgSP?p*{_~2LLdUBJ zGdceI0l#0K_!lqw&!0ZA{QtjsKpg73JrEUO&HzX$q>uQeDBZwqdNGQsEogg699aDK zQ@5t5Gujhd9{&A?ff;$~JxWUTYbpQ!_ljLJ4UCc=lKuDV@fHmq8)P#H6NHEJ-`|;g zeEhc%(f|6HT>P;8BUqAaX>GaJ%To{63~7KO!W*MAGlAwGLW>&a^}j8B4q3zhe9AsF zW7j-HbD7I?}zgleW=Dc5M(k*L?nAu2D`4(1MUwE-ccKxL>_y2w{ zmcv#;VQo#kHy_O&jwh)VNV*_*Y`dHMlMsWCZ^X3#07T$tkb=Rbbmx;xu6qgOHf;as z&KpxJ#7dz7+7roraK*#DDvS>IF3?KuSuo)I@FP&3ukmEALvC8H6^)jfUv<~uMkc?{ zfYs^g*t3_r89sg-jk0%Z%+@4zd_&?lLgw6_7x3;BOImGbWVcB{COZZSt9-|W-j&u|!Qr50p%871c27I~HW>EM!iVC|cS1#@JxBVRhk zIkzW|$^5D-u#U~>rF@=p#>aq(u72+J;=2;T|9L=INyeZJI8un>sMIAcXgyGmwB#A! zO!*?O@hm=m3`H#AK=G^yKEw#E-YY8hooC^W2ou>l;f(TC`@krpu0(Q1*6!~&jc>YV z*BaekW#OfWz3mrJF|FulJLi5=S?Rby&8y7g1N5s~R1<`z{Qs64f(9>NT^yWt zYiSPqXrOhKiS9{7ElsPxw53qk7|t@~1R5|Yh*EN4p_rp({;spR3d=haeuVILILHq@M7v9dVjrqstbp$H0jYzg%IKhph+^QB?Cdl)8K1Ny_1IzxIDV3}@O2Me{Vy%-&MP{?a=&hO8@J}S&pBCVzX$r z`Tx8QH7Q@7_Wyd(|K+jz_j~_ezBwvkf`}^yf*m4GT1kfMR;%FsaHzxA?zhl;7f;X? z*f?;fO}>&hdDv4zQHd3msprUi!H68hfsmM?mp4034RRDq+*Qo`OTMz&`n{$GxZErgf9br`;g%)%{6D)e}hCaXTZb%9U3)+aD3PZ)vL>W z;6RYerj1@R&)b;Z{zoOTJfc`9C(pKGP$+GJ_yDc2Nes9Adg8Uih0CP}ZYlXa6Qyro zGa->VsX^uP%44-5z_i_&%>DOJYf{8JHT|N#gwPS)M5h_+nkC7i{?Cf~(|QwLEE@C4 z|1PL zEHxUtpU<#6V6h}NI%?q44TGicCO2M6f9Q2msN&3u$P1SdUS+pETbTFikeF2b7N?|d z&|=@k;PT3b4@yj8Z9&dAdnbCW+s@qoWhxm&?XTD;@<9C*cQyOqP`2V7tC8&Yc2?@u zHC2^5b{j3RN$+a@G-t=WIXZcOUHrkFuU;D+H|rj#iG*-xY`BgXV%q|gqwx#PI_RGJ_Sik$HPo^oI z>|l$N>g=!mN8@kRJ+03zx_X z(t3{9*P2g@BqYT*@zK7?_hDNcFzV>vE7l(II$r4JnysLd+W9Cg-wPreYlq&qql=Uf z6Us}1;^PTO{uPf@W#!)ycc_oJ2a4*fM+H{vaYD&}YI5)*uXZJDQ ze@dtE*~9mp^$Q<;>m1Zgrk`?;EtKTY@qJ*(ufFVcLdB~0kIMMr*ue&31&973*XQLG zQSS|`1=_1w6b!7ScX9VbtWy856E>oqk@Xv>7NrosRCdtr%U3V*nOR908ewr&@3ihL zzPZKN;Uw?I(d0_`Xs!o4w7)gh=h{tL9UT$bm!K6ZbjERRL_nG5!btz;*RKxj|I&IT z@_6hSUs}f}aclvfb9%ma)wc3X`P(nKq`!R?q2@3-7xd=UzOVJNmxTM2Y#&CrsVUV7 z4>Ar_?v1`VtMGlp;p8CgWOQnJ`bc@+Wb3MwT6jg&8TFGLLJ=X?i_4ZxBnEsVB%3=U zMi;Bfh|Vx3pYk7!IJ+_DZErlRe?)PzuXKM(vwqp@qrswX50!Sc|IsrqR-fflXkofr zr&%j6vn0RK9r8x4kl6aOU!d>AbgD9CyB*)eb$9vMg#-~^J5g6!(c31hz9WO;4K8gz z{^TW7J(6U;?j2w;Dw)#2UFXR{Z@^>JF7s?)piy}!ecO^xXfo{9c*<#eix!plqwgsljg9<*e(5sZmn}cYR--Oy_(7cLp30)$bpF#^ z)dRe-+ewa23+Ks<#>=w5ai{UI_!Dd0xu{`yteBDH9?PM$Q7+-Sd9v7^$K2C)y{GV(y7EpJwJnr?wPqC}7`B=3#bAT5ucy}?EIIQbaI z`hVEY$PO-&Yv0au+OaH_|1zcZO5pp5U0liX2DIFNOm7;uJ~pE4KVWEh_Aa$6SJjaXr{cz>!|N@NcD~W$eEfmp zw0M!%DDgMS#yQ)TZb7dob1mJmz|q`$>uAPYrxPDnvLcnVlnCu^39ls$3hMTi&8aOb zo}sD0JxozC)0_Wemp3uxJ>DNu_QQ@sPhmYJFYDo*sg%Tjv&P)#rw%){-rZS1_C;Yw z=H9(smg2Qhj$4gdUpsog{ZAJGH=Kt<9|$lU2rUhBu$r`I zlXmb^4^a1l{HvAP;M4XE6on)8$d{pcrl~2~D9n=1t7d!dnt0+@r!WH6<9Fr^V z$*l`RgA|sU%Lg(iY*|jbocZ!O{{6?Pq4CG&QIALKy7-K_ZpPT&Zh14X_Bc-7bbas? z+wvnP2fJD;w`Jqo88yKHH6{tgY@4GrBKGy&Qfhx_Vr<#NxBAOhE;p5SA5G=|pqX*- zgU50JS7~T&5D&}Dy&+PQ?@1OPcplvY=KX$hr1{z28mB0FGqo3~*(`U`$7u4eA5IWf z2-{d|6e2sbw^4-I!>njsZfW?`Qc#!xZxc_zQ2OYNQ+l>Eq81x*Q}-)-rRrN24ZC8Q zF0Bf$o@%c#==5r`9y|NH@{BZ?kKPZzj&0^?xRdeou7|<*Co(6l zx>NPVGM{aj8LBd$LO8GcVk^R9d(@Y$ejq$qNI$7fTD5w)i^urHK>tKiCEZ%JX{=QE*Ea#$i8pJ)qV^lt`s!Blm~{z+Kep#6 zo_1>%%9`s=yk|4f7JeWs<=$%cRYi9{Rw}pVWGCSc+p+3~O6}q2?a#6}Ud^$XeN=Fl z(Rf^+FeISFxw;-SH}(MUdqqDJapTr!hF|yk8)6TWjrF`*>PDjv!{;Zy-3b-ei(d}k zk6@>o9-z7CyH7UV_rUCwC5uYVgEulfO|g~d`Mf+&eCcEeJGq0&ZckEUgn_nt^-muL zOVLVVJ&T1a>VZ)K&R%zzEbbg@i9FM7&iJEe zC;cgzC8zwioqPX8O6C-cq>VkUo{ZrvC^)Pe;A9tGM^mWQ{jJ*1IxjZdrMBtam0q6d zP1lW;ep5FJhUyS{=SzE}DAS(P-xA25xb9Vu$;#Cg65n)mB&qB2TK#Ezn{xAYv7!)u zv~3o;YNvJE5J$UfypV}*7^#T6v(<86ZFg9WP`r|C3*-bZTS+zukCjCc23$z3JP6LTj32=f}<)9`x~99P2#k zzh}nru^LV27(yhEv&wVW=rTd-&)xhTJWX9FdPwyF2 zOB3qr?>~IUKtuehck`-i!tooOYeKDMT0yQp7fQumi3kj zyvw{>!7h%ZSJrJJHQmkLgsxKR$@pc~ayJ!SQSZn!`jM3*Qo~McWf5;HV;WTVg;8^? zA&cLde`eRO>WaLAZ=JlKZYz1bD;b^ZTyIRia!BG#mzLAFlu6?0$zKsO z3fuPQ$h^PY2zEEVA-usWexKMv$(6$b5t0uPK-X;`eNJ5~m8EUpOwt`fuewryXfu zIoDRTux45B)gOOW*xLP}eoIABn}@IcyniWYm#S37Xi7uT6=7VJWCZhagvgRo+R*g9 zrtcwR9g!^jq9T5#2_C%5DsGG8S3#PNJsc#RY~Nz^mTJEml=1up#bTtwx^1RWs~>TN zNbSpzwZ`HH!qYBB=f7QGSE6x9jF_X_d}JGKGQ*s>#&y_YwnNu-tS#-#gHAjBv6bcT zq7I$1Jvru$#nSY9W$(Ps5^#-kUygGsSo)JUrMfh<{mLq@Ih4ONE?(*V&{5sir$>+Q zowd~If0vw(!;>lT>FDZDa_T3eP$sS{5UkMp!t>LzGGA0wX7y6Vzfz{tJpbK zvYnoDENB&{Sn2gW(JyqG(Ufv9Vff5yU@qzPvz`uPB)cpt8AP@#+!e!}6M~}RzNLOn z?9P34-u!_6!g`2Y*n!)=KXR>m+#NIZ_w&ElsCh%v>l3hcUR_h!%?_=S*ua@l6IGiY`4m?M{5@gS$P zUS*EB+)GlLJ$a!dt^RqQY38N|)3N-91D`)|{PGqbIMnizmW$oqq(?(S+McOIUq$z4 zKF|FdcCkHn!u({#LGnMAB7f0urFx!zHPA}s9Tj~v<+fn{qRG$FK@Ra*UVQ_a0y{>Q z+$;PWmpgek!?H|Q$3%l^ovT`gHcHwPZfVW)JR>gr9$PyxJ`u84lTl}pI3Z8Iz~|b; za)0KeUR~3SgJa9N9_>GTpB3EZ#_tJtGdlSR=bz90aw}|8w7&XA)bV@ABzxB1o=GsU zx;sqf711R~&9EKBAWYSm3uUshoT|^w*hn72>RHIoscTz~^v@VCk``H6=?gwBX)seC z&+(nRthSbhD6Bx3%j-C&vftP=OJ0J)i4teN0QKo3^^qj(->&J=6%{t#E}F4cxy5nv zQ~BhdFM~r~o!zybO&ec%Z+-Q%o~ox-F?+1P*Rp~WL$#Q^3$q3b^@g@H*A}S+3iWvR z93a&$DGC29{eg4ptXb{#RI}#mh4$*A;q);o z?$3{-pUka<%`@W#eP)V#uLbqEzH8Rcs_n`Pj_Wz2vsP%ZpHIu)h4xqG8BdQA{Ze|~ zT=PlVsENubySY)X>8Ee#&c3BLD-1fsA9J^%>PzXrXkP$}!4@OqVKpZ$amOK>bMaDL zivwiE+8aU{BT`qUthnv6{zQokau|PQNbLMW*?c{7B+rLCwd92NHE+=;84GkR<{g-_ zG5BWd7}a&v3*xM6v-9zug~BuP&&cDvu0Qw~LpwX0X?Lf@V&_fm?aS*1z4~Pxc^u+r zM&y+D6PG-4UmZUaRA5E^BW`gddX?1T!@FRUyGY>loA9*fwIMC%_$=7XlRNF?M^Cu~HpL62zU`T6kqZyIRHn|Jk?taJ{eog7 z-5Y}*iI0X2eIIWPR%cNZU5>l-Saq)Ds2P3kyF;`!aq5M=Ob;z-ug!QxoFwwTz+llC zC}nZ?SZu{y8!c08;kj22BBl&xyuDMuez^2du`%69%&nm(bDPwzfWw3KTe1${s&3Px zMuD0ewyJwR^z}|Y3O8x-?mTXOzkFbkY|4UHjpomm^UC_}rmSlRPcI}?UbLd#Du3pw zTp`vzDH1lm@AbZqB5CA-i(n5u#DD?h)>ga4fdHHuQ>@3Cv6DaFG2z_7EJ6zA%Rv$_})6iA0q+qS& z9?%@uEpf_<_tm(#zmn^O@9N^{2mURyT|cAb72_M4?aHY;G+o{*nb-DvP4x8Vt&-+t zTi&hZJ%8zez3~Qzk(Y$@JX+D$-dnP<##f+x>Qg*b@5KCfnVTorV<|L~J-%Ll zN~Fzyv6MZExx3D?pk>DBO2_P2+l4oUwj@OrT*IZ8k{a~P^xC9lEjAOFEUXo_NwarY zOjg&m?vjJYn)Scx%XueO4*88Tfg`nTNcE709ku z?#W1KAp7)w^pM;*?bCpeX91sCoubvOr0Wk%j`#Rd*cRQ`P9>^d*1M~q#K+1?ZFG4b z$ue7Y%=5wxtDld0sHubZzkXdjdnVrFw5RZ5B#*_zH|*UKNvwmVbyt7ho@Psy*X=q` zT>aEFDX64~F~!kBn0URU{ArnYs;KCb9g$j-t7A&B+`ST)R9SBtJ*5^b-F$Y&BzGy9 zovx{x$!7X_Xqwom&*Dk_-&9)P>T|KM#Jrql{nhT|8p6M|7m~VKK>3FKzLiiezGuivF>w)+u4?;f6OYKJfc7i*c+Ig)t=w zWtZH|?D)j^#yOI>Ojx`^(?ra`zV*($ZOXlJ-5>UjjU>r8XSWn)Mq3_Aema`w|4sJ% zw^a?5M`9}nqLU-)-Wv4id@0*QO?~2Azni)tr9=3X{J+e|hJlgez~RM>h25t<75&Fb;saYmQknriQSi&HtVc8l?1OH*wx+M)y}J3{IL*3$+31w6P%PkxeNcTR5q z^x#rsZlA$9%Dz3raf@+=nfB`|lt=VVbX<3DIrH+v%Zme2Zw=B)BQ=k1&(mG8D<=O$ z7gaE@n>uO7HW3xG5L5p7mbdSF$Z#Fl@HQl^}+J-{_DNn++()~xMC>x*tak{r>SFo~o=Eq-$jm18_9%i7E zC7se@E1ug=!7o&|zV2B_eORhGxn59t#5EweHr;OdV8`f=%wQs+3r!1?nTt|WDF$8h z8q;dM`{b%N=7haoEXFyPuhxywBbrGt?YVZP4qjaR;QP&oI9?J zQ(oA-T{jg?e)X}|^&bXix{U=7^5RWNN7jnQ8HOY`OQ-VmTJAi0Ofllys%$+`_9Inq za(JuJoJXhSsL<{R&3)rF+b{b0Wry?IPtSfAmeGl%_u+~Bsjumm+>>N#zibp*Qe5WB zyXP$Hg_owFripI4{h73U%{O#Kn~8ym?d%qFp zbtCMbyi=j29O%DQ@|gCVksLM2hp{*Bw}PLsEt006R&?y*HjDmobM004O{r~ljq`BvSXm2UMD z-GI%vl^RF0Tm$g(8=clSq+N$Od8H9F`Fy#rJlGk0?XD_K@$^+<-~i;7)hbbMn80JPalf}n*5!nF4wczG!C*Zr}+vV>q9HPlJ^{R@3ks;p1N{@(&rwSS^ZPsLtr1Rh^i z^BoaS>{gUo#-!Hp8!rOQYo_O~H2WW+xFjQ4Y<}?%dN5wyJwh(~+x|&CXcZd0{W?s! zd3&ii$E+DP5-=TD<}rhCA8S8uQqO>V9qJ?vqkJj;g2KF^$MTZhW39pVEYCYMNJ>(C ze1CQagrLr)a`VaOsxzykMZN6pHwS9ALoyRotxnp;j$NSqcg~iT3P=oQ<61sQw zGfv#EWj?HuY0O+CpIA8$7Dz^euU9;enDl!QxEg$S=ZmA}mcYeH9Esay0Bc=i&&FHKkvE>{?13*-HYzI_+j6xqyGyGW0Y(nzcH>JI~S>a zIkQxE8H^!aBr{vua=dZ>aFHlmuHn_oI<2n8#YaJSB^~n&PmLePBBA|y1C3XA{dWy_ z6D9~$t?B<=)vx#8${>ZWfb){Z&*J*N%mwY zm}z%}J{U_Pe;!2JT_)H&YKfky(=L0=8lLC0HlsuO>vT3})e#+jDUhQ80^NKjyWxSe z*0Pze&OVn9-qk58zGB;}F?sp~!^HQfchl@sKD_A$gU!kn>fDjS;`|A+X6`+=w1o{7b+ zN}u?mm-&0{iTM{X%QExbrHocKXs_g@{Up1wsyeFeiuH9+rdaS1r8EXFV1*f@Hg*+! zE^xIv?c?@zEv4T(?^vidF6v!@V-o$I)q2rIu=K|o8c*;T{opB2KOXXv z{J}SE(w0Rx1&b5S^y$rm4STq%1)V3K+H8;I$ks(2jE&L0G%gZ3rCqB&Bdr3*kSA9! zU7-@cZ(1*HJGSGys${PdVZb-vxHf7y`Pibi_o&*8k{bAZ{&KX^N%o;T+ux77PAmJd zau%gPXbJVLM}-N&W^ngKrTy6FO9x-fX)AA@i3UEWNw>_4tF?4D>hx!JV<2Mg4es0T z|0ZJ7Wqu}maqkK8=>Be)*fA_F6`#4Y?=|@cU#5nbLbch@(vWD0nZ@9AY*W6MORuI1 zSlMH*LvRBNW!OWFP;``d9K}S_&Hd7yM*CB<`Vl80$y`jE(yG~H-jb6+RUU|Zl2<7V z>W@uxCc#d=cN&+NmK|rU%dM+O-(eN(e)$&_K~@ZUc0xA)#heZ5l&df*G5lw{qo7lo z>6vq~&1o{$CP=#0si1`VX98s3&1{tP^%O{ZCI9Mz&1ZF{nbGa^vqk zR>gePAQ0yJYZ;b~NS-ns&MGxVfxzVDwGoE5z~#Dj8&QyurQ&&?7tapg!97#?P(iq_ zWUepcH%-uCx0}w_1z32NLVGuo{!#XNEM@av>mmwHC|`~T~;gOe%W;M%utwLiXpf3I&G zhY3ttYtnI0=J8`;JcbOO`<5`LoDD)P18cI=kQhn`9^Bf~^UQrHQMP^o{^#cF`Qq}u z?vu2A$tA}TACa&s?)}-1NO6*}CF43`$rHCA^m=Q+1V`x$8ao(D(Zoc*R_BG%=4@g+ ztdH$FhCZvxo0o;MIg1sxTp$qD2$I{QumjLidHzIL9WOh0Mng%9Li(lv7o6!^J!K(9 zlr9kCKxn(!Jgl6ENq+d6Efgf~M1A`6*Gk@?N70v2$&~MG3WqSx8iND9^pRUC3$SYW zS)sl^70F_HW{mzy9pc;MxqMD6^Jg^}FL+*(6^$C9tyCsQXvn4c#FV44N;nt!Za#bE!Qa1LX8%ARN{iY@e zQkIYh$~VqS-o}MjdwUK!6nXK83Xy^kx5{hYd>p&0!B_RY&7XpSIkHwDPrM;>D*N$a z=Xu!Wv!#xi-h_5~}?Z5dv*ey`*QmEQ+Q5%+YUO zfBdL5P)+_Zz*wn-9V_wJ5=u%F5qmp5bLCBt)`+hEW{75hG_#SOo>xpvl5+X0Q5y~} zuIQ9(5f`b7`%Xl$q#j5C1%z#l!Xiq@U?ra|nSh(%_1=y%N`2}z!M=?&P}1SP9f9jDresn_o}2i(V1dlxzG7f5_8o8WkJ zHZq?*npWXW#yQok2z8>N_T_?#m7n?9(mc{-;zqSYe5K)Qo(456?)tpNAq+p#JVjJg7q8kX zn}9-@TuFBTWAVb~d0iI#K0CQEGZml#O~8)DCauMrspzS7gWD^OQnOMu+;nd;L=fv@N1CTK zA)f88-kps!JAF3F?~WxD#DY;PJcz#pIcanv(i2w1&AV-}eqpm?RCGifSP7>Jk@b`U z{g~m3&%%)KXQ6(gdV1Kzgs!K$4>e>GhQ)FT+&R9q{IXxkC^`W+&$0OYkN1aGCB&i3 zD8j{R1|kcnxYxyAKawrN&AI`Z7gpZfZ-9P9f*qvM{4i_E`VlC#IthoAD|X>&BBW&7oOG zt~Edx-rw!4==hw!j4r6l`2xima$*+l1DZ)75lSAt+@(Vk8n223%0Di*(tAR`R=BDk z!?FsDsyeFq!Plhaqp`s2@6^%s?N$7yS~Aw_wSUX8{=pA#W8Jy49R7ow{@)<*e|G=> zq!s^f?D_`ai2~#fJ~Xd@daAj(4)huAzh(?9b4l%nf#H|o;Tkj{fQbTmt(f=k-%H0U z{tx&W(^_`yg4BjkZvXZ-oxgm95YGOcp)wh-$xjEbMvWVl%)v zcp7ppf9tN4SW_7d4EJ+hj{&nBUwQP|P;ennCzP$}9bsaXu;6qfkHmK>HMo$1+chea zZ`~zw8`GFY+J?&y{g0Jd!t~OaB%7W2lv)~4I2lrNhguP|FHhsPHT7GLE4}WHmPuFW zk>Pb~)~&vCNb-7OGlZRph9| zCS8-d|0#n0q>n%95~fH|L+Muc>Rvw>D0HNHIzHB zfddYaAh>@MS|L66&K^xv|kHs&uH zZ!0>zbgo%l6=yya->b14j)U9vnL~2N71ofpcEg9Mz@74vz2H$^Z$ff0M($ZvB;Evi z(vdf3>YJZwYov`Tq#@fJ4aAFU8@zkRS9*CUkMc@vAs`@M?E%<;qGn#PjWQO(Ahc};$Tt@=r zu7W~8eS@7}oX&4`Gy#E!m?49xb2kRxz15CB(p(12LRP1b8EFHdwl-PLYa@4?liYm% zbT4k2S2o?xv-9QTx+3iv+>F!ad-b5VXzS~|h*&$@Q=<#w4~#Z=GurNLJ8oGEkr2u= zeprLb%d(a_UI*C96j-~uvIuTzt-YDmS;-LjdF70q64b(Z>TCB)0oIb=BPTY5g??oQ z$4#%D?p_j1H)(H)@II%i?(xgVFL9>#ibQvc`ZrIbTT=JHo-`IM6kT0}(w0GQT4Z*n z%yZsMpaupOxFqU!%W%;wnL8M5&!D^f{>0B!V%`==f0|I6I@Ee3S(-F@iO&1@HJ`~T zgvFUXOxUC+vY${-&jL@BgO~d>xOZ_}o#q87)P4_9Dl(AwzWuO-c7eJmKppt|I-goO zqb;PrWPZ&QgKU=6?{Z~2OyOUsaTv}VYmeqPSlgWX`WnrlYlp}0KIQyymzW-9V3gT` zF8g6iaJP+d&qs(|?F{ncN{FnA24{_TmAw+++q5d$oL3@nITn|-tD);x*V4bk2B;i= zkCo2FGA;+E?T2~CLmqf|Wy@t{tKc(b=feohasNb3QTN=Kt5C!?eDXy7lxAY6QlLjfrI zBw)9Fq`##!Yhj660GgtW8L_+YA3=wg*tSp5C!H`oXA8*63!ALTFgcbq6mPYuA;46t7IMiUlCZO0ssI2 diff --git a/localization/initial_pose_button_panel/package.xml b/localization/initial_pose_button_panel/package.xml deleted file mode 100644 index f0b4d41bc4f51..0000000000000 --- a/localization/initial_pose_button_panel/package.xml +++ /dev/null @@ -1,30 +0,0 @@ - - - - initial_pose_button_panel - 0.1.0 - The initial_pose_button_panel package - Yamato ANDO - Masahiro Sakamoto - Apache License 2.0 - - Yamato ANDO - - ament_cmake_auto - autoware_cmake - - geometry_msgs - libqt5-core - libqt5-widgets - qtbase5-dev - rviz_common - tier4_localization_msgs - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - - diff --git a/localization/initial_pose_button_panel/plugins/plugin_description.xml b/localization/initial_pose_button_panel/plugins/plugin_description.xml deleted file mode 100644 index eea08b60d03e1..0000000000000 --- a/localization/initial_pose_button_panel/plugins/plugin_description.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - initial button. - - - diff --git a/localization/initial_pose_button_panel/src/initial_pose_button_panel.cpp b/localization/initial_pose_button_panel/src/initial_pose_button_panel.cpp deleted file mode 100644 index 654095641c7f4..0000000000000 --- a/localization/initial_pose_button_panel/src/initial_pose_button_panel.cpp +++ /dev/null @@ -1,123 +0,0 @@ -// Copyright 2020 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 "initial_pose_button_panel.hpp" - -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -namespace tier4_localization_rviz_plugin -{ -InitialPoseButtonPanel::InitialPoseButtonPanel(QWidget * parent) : rviz_common::Panel(parent) -{ - topic_label_ = new QLabel("PoseWithCovarianceStamped "); - topic_label_->setAlignment(Qt::AlignCenter); - - topic_edit_ = new QLineEdit("/sensing/gnss/pose_with_covariance"); - connect(topic_edit_, SIGNAL(textEdited(QString)), SLOT(editTopic())); - - initialize_button_ = new QPushButton("Wait for subscribe topic"); - initialize_button_->setEnabled(false); - connect(initialize_button_, SIGNAL(clicked(bool)), SLOT(pushInitializeButton())); - - status_label_ = new QLabel("Not Initialize"); - status_label_->setAlignment(Qt::AlignCenter); - status_label_->setStyleSheet("QLabel { background-color : gray;}"); - - QSizePolicy q_size_policy(QSizePolicy::Expanding, QSizePolicy::Expanding); - initialize_button_->setSizePolicy(q_size_policy); - - auto * topic_layout = new QHBoxLayout; - topic_layout->addWidget(topic_label_); - topic_layout->addWidget(topic_edit_); - - auto * v_layout = new QVBoxLayout; - v_layout->addLayout(topic_layout); - v_layout->addWidget(initialize_button_); - v_layout->addWidget(status_label_); - - setLayout(v_layout); -} -void InitialPoseButtonPanel::onInitialize() -{ - rclcpp::Node::SharedPtr raw_node = - this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - - pose_cov_sub_ = raw_node->create_subscription( - topic_edit_->text().toStdString(), 10, - std::bind(&InitialPoseButtonPanel::callbackPoseCov, this, std::placeholders::_1)); - - client_ = raw_node->create_client( - "/localization/initialize"); -} - -void InitialPoseButtonPanel::callbackPoseCov( - const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr msg) -{ - pose_cov_msg_ = *msg; - initialize_button_->setText("Pose Initializer Let's GO!"); - initialize_button_->setEnabled(true); -} - -void InitialPoseButtonPanel::editTopic() -{ - pose_cov_sub_.reset(); - rclcpp::Node::SharedPtr raw_node = - this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - pose_cov_sub_ = raw_node->create_subscription( - topic_edit_->text().toStdString(), 10, - std::bind(&InitialPoseButtonPanel::callbackPoseCov, this, std::placeholders::_1)); - initialize_button_->setText("Wait for subscribe topic"); - initialize_button_->setEnabled(false); -} - -void InitialPoseButtonPanel::pushInitializeButton() -{ - // lock button - initialize_button_->setEnabled(false); - - status_label_->setStyleSheet("QLabel { background-color : dodgerblue;}"); - status_label_->setText("Initializing..."); - - std::thread thread([this] { - auto req = std::make_shared(); - req->pose_with_covariance = pose_cov_msg_; - - client_->async_send_request( - req, [this]([[maybe_unused]] rclcpp::Client< - tier4_localization_msgs::srv::PoseWithCovarianceStamped>::SharedFuture result) { - status_label_->setStyleSheet("QLabel { background-color : lightgreen;}"); - status_label_->setText("OK!!!"); - - // unlock button - initialize_button_->setEnabled(true); - }); - }); - - thread.detach(); -} - -} // end namespace tier4_localization_rviz_plugin - -PLUGINLIB_EXPORT_CLASS(tier4_localization_rviz_plugin::InitialPoseButtonPanel, rviz_common::Panel) diff --git a/localization/initial_pose_button_panel/src/initial_pose_button_panel.hpp b/localization/initial_pose_button_panel/src/initial_pose_button_panel.hpp deleted file mode 100644 index 44defe637b7df..0000000000000 --- a/localization/initial_pose_button_panel/src/initial_pose_button_panel.hpp +++ /dev/null @@ -1,65 +0,0 @@ -// Copyright 2020 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. - -#pragma once - -#ifndef INITIAL_POSE_BUTTON_PANEL_HPP_ -#define INITIAL_POSE_BUTTON_PANEL_HPP_ - -#include -#include -#include -#include - -#include -#ifndef Q_MOC_RUN - -#include -#include -#include -#endif -#include -#include - -namespace tier4_localization_rviz_plugin -{ -class InitialPoseButtonPanel : public rviz_common::Panel -{ - Q_OBJECT - -public: - explicit InitialPoseButtonPanel(QWidget * parent = nullptr); - void onInitialize() override; - void callbackPoseCov(const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr msg); - -public Q_SLOTS: - void editTopic(); - void pushInitializeButton(); - -protected: - rclcpp::Subscription::SharedPtr pose_cov_sub_; - - rclcpp::Client::SharedPtr client_; - - QLabel * topic_label_; - QLineEdit * topic_edit_; - QPushButton * initialize_button_; - QLabel * status_label_; - - geometry_msgs::msg::PoseWithCovarianceStamped pose_cov_msg_; -}; - -} // end namespace tier4_localization_rviz_plugin - -#endif // INITIAL_POSE_BUTTON_PANEL_HPP_ From 58d8e8e2d5ed60499437bac4b92c9daa5dad6a86 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 12 Aug 2023 13:00:03 +0900 Subject: [PATCH 10/16] feat(dynamic_avoidance): object polygon based drivable area generation (#4598) Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance_module.hpp | 5 +- .../dynamic_avoidance_module.cpp | 61 ++++++++++++++++++- .../dynamic_avoidance/manager.cpp | 4 ++ 3 files changed, 67 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp index 1f54786df83d7..dd0e06fffb255 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp @@ -74,6 +74,7 @@ struct DynamicAvoidanceParameters double max_oncoming_crossing_object_angle{0.0}; // drivable area generation + std::string polygon_generation_method{}; double lat_offset_from_obstacle{0.0}; double max_lat_offset_to_avoid{0.0}; double max_time_for_lat_shift{0.0}; @@ -335,7 +336,9 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::pair getAdjacentLanes( const double forward_distance, const double backward_distance) const; - std::optional calcDynamicObstaclePolygon( + std::optional calcEgoPathBasedDynamicObstaclePolygon( + const DynamicAvoidanceObject & object) const; + std::optional calcObjectPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const; void printIgnoreReason(const std::string & obj_uuid, const std::string & reason) diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp index 7f69397cb3cf5..b69e95875c5fb 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/dynamic_avoidance_module.cpp @@ -274,7 +274,15 @@ BehaviorModuleOutput DynamicAvoidanceModule::plan() // create obstacles to avoid (= extract from the drivable area) std::vector obstacles_for_drivable_area; for (const auto & object : target_objects_) { - const auto obstacle_poly = calcDynamicObstaclePolygon(object); + const auto obstacle_poly = [&]() { + if (parameters_->polygon_generation_method == "ego_path_base") { + return calcEgoPathBasedDynamicObstaclePolygon(object); + } + if (parameters_->polygon_generation_method == "object_path_base") { + return calcObjectPathBasedDynamicObstaclePolygon(object); + } + throw std::logic_error("The polygon_generation_method's string is invalid."); + }(); if (obstacle_poly) { obstacles_for_drivable_area.push_back( {object.pose, obstacle_poly.value(), object.is_collision_left}); @@ -836,7 +844,8 @@ MinMaxValue DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( } // NOTE: object does not have const only to update min_bound_lat_offset. -std::optional DynamicAvoidanceModule::calcDynamicObstaclePolygon( +std::optional +DynamicAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const { if (!object.lon_offset_to_avoid || !object.lat_offset_to_avoid) { @@ -896,4 +905,52 @@ std::optional DynamicAvoidanceModule::calcDynam boost::geometry::correct(obj_poly); return obj_poly; } + +std::optional +DynamicAvoidanceModule::calcObjectPathBasedDynamicObstaclePolygon( + const DynamicAvoidanceObject & object) const +{ + const auto obj_path = *std::max_element( + object.predicted_paths.begin(), object.predicted_paths.end(), + [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); + + // calculate left and right bound + std::vector obj_left_bound_points; + std::vector obj_right_bound_points; + for (size_t i = 0; i < obj_path.path.size(); ++i) { + const double lon_offset = [&]() { + if (i == 0) return -object.shape.dimensions.x / 2.0 - parameters_->lat_offset_from_obstacle; + if (i == obj_path.path.size() - 1) + return object.shape.dimensions.x / 2.0 + parameters_->lat_offset_from_obstacle; + return 0.0; + }(); + + const auto & obj_pose = obj_path.path.at(i); + obj_left_bound_points.push_back( + tier4_autoware_utils::calcOffsetPose( + obj_pose, lon_offset, + object.shape.dimensions.y / 2.0 + parameters_->lat_offset_from_obstacle, 0.0) + .position); + obj_right_bound_points.push_back( + tier4_autoware_utils::calcOffsetPose( + obj_pose, lon_offset, + -object.shape.dimensions.y / 2.0 - parameters_->lat_offset_from_obstacle, 0.0) + .position); + } + + // create obj_polygon from inner/outer bound points + tier4_autoware_utils::Polygon2d obj_poly; + for (const auto & bound_point : obj_right_bound_points) { + const auto obj_poly_point = tier4_autoware_utils::Point2d(bound_point.x, bound_point.y); + obj_poly.outer().push_back(obj_poly_point); + } + std::reverse(obj_left_bound_points.begin(), obj_left_bound_points.end()); + for (const auto & bound_point : obj_left_bound_points) { + const auto obj_poly_point = tier4_autoware_utils::Point2d(bound_point.x, bound_point.y); + obj_poly.outer().push_back(obj_poly_point); + } + + boost::geometry::correct(obj_poly); + return obj_poly; +} } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp index e378d43f6497c..3b2e2caf92e6f 100644 --- a/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/dynamic_avoidance/manager.cpp @@ -81,6 +81,8 @@ DynamicAvoidanceModuleManager::DynamicAvoidanceModuleManager( { // drivable_area_generation std::string ns = "dynamic_avoidance.drivable_area_generation."; + p.polygon_generation_method = + node->declare_parameter(ns + "polygon_generation_method"); p.lat_offset_from_obstacle = node->declare_parameter(ns + "lat_offset_from_obstacle"); p.max_lat_offset_to_avoid = node->declare_parameter(ns + "max_lat_offset_to_avoid"); p.max_time_for_lat_shift = @@ -178,6 +180,8 @@ void DynamicAvoidanceModuleManager::updateModuleParams( { // drivable_area_generation const std::string ns = "dynamic_avoidance.drivable_area_generation."; + updateParam( + parameters, ns + "polygon_generation_method", p->polygon_generation_method); updateParam(parameters, ns + "lat_offset_from_obstacle", p->lat_offset_from_obstacle); updateParam(parameters, ns + "max_lat_offset_to_avoid", p->max_lat_offset_to_avoid); updateParam( From 9ac3a7cdebc73b8d459f285dc25f5c48ce9557be Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 12 Aug 2023 23:27:35 +0900 Subject: [PATCH 11/16] feat(obstacle_avoidance_planner): faster optimization by sparser re-formulation (#4600) * feat(obstacle_avoidance_planner): re-formulate for faster QP Signed-off-by: Takayuki Murooka * minor change Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../mpt_optimizer.hpp | 3 +- .../state_equation_generator.hpp | 1 + .../src/mpt_optimizer.cpp | 211 ++++++++---------- .../src/state_equation_generator.cpp | 43 ++-- 4 files changed, 116 insertions(+), 142 deletions(-) diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp index ca51c791b8f0c..eabbf695496a3 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/mpt_optimizer.hpp @@ -237,6 +237,7 @@ class MPTOptimizer // previous data int prev_mat_n_ = 0; int prev_mat_m_ = 0; + int prev_solution_status_ = 0; std::shared_ptr> prev_ref_points_ptr_{nullptr}; std::shared_ptr> prev_optimized_traj_points_ptr_{nullptr}; @@ -295,7 +296,7 @@ class MPTOptimizer const std::vector & ref_points) const; std::optional> calcMPTPoints( - std::vector & ref_points, const Eigen::VectorXd & U, + std::vector & ref_points, const Eigen::VectorXd & optimized_variables, const StateEquationGenerator::Matrix & mpt_matrix) const; void publishDebugTrajectories( diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/state_equation_generator.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/state_equation_generator.hpp index d4f70e8e09227..b6f4eadb682fd 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/state_equation_generator.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/state_equation_generator.hpp @@ -31,6 +31,7 @@ class StateEquationGenerator public: struct Matrix { + Eigen::MatrixXd A; Eigen::MatrixXd B; Eigen::VectorXd W; }; diff --git a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp index 81b5974ac3deb..74711ed886ff0 100644 --- a/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp +++ b/planning/obstacle_avoidance_planner/src/mpt_optimizer.cpp @@ -497,15 +497,15 @@ std::vector MPTOptimizer::optimizeTrajectory( const auto const_mat = calcConstraintMatrix(mpt_mat, ref_points); // 6. optimize steer angles - const auto optimized_steer_angles = calcOptimizedSteerAngles(ref_points, obj_mat, const_mat); - if (!optimized_steer_angles) { + const auto optimized_variables = calcOptimizedSteerAngles(ref_points, obj_mat, const_mat); + if (!optimized_variables) { RCLCPP_INFO_EXPRESSION( logger_, enable_debug_info_, "return std::nullopt since could not solve qp"); return get_prev_optimized_traj_points(); } // 7. convert to points with validation - const auto mpt_traj_points = calcMPTPoints(ref_points, *optimized_steer_angles, mpt_mat); + const auto mpt_traj_points = calcMPTPoints(ref_points, *optimized_variables, mpt_mat); if (!mpt_traj_points) { RCLCPP_WARN(logger_, "return std::nullopt since lateral or yaw error is too large."); return get_prev_optimized_traj_points(); @@ -1160,13 +1160,14 @@ MPTOptimizer::ValueMatrix MPTOptimizer::calcValueMatrix( const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); + const size_t N_ref = ref_points.size(); - const size_t D_v = D_x + (N_ref - 1) * D_u; + const size_t N_x = N_ref * D_x; + const size_t N_u = (N_ref - 1) * D_u; const bool is_goal_contained = geometry_utils::isSamePoint(ref_points.back(), traj_points.back()); // update Q - Eigen::SparseMatrix Q_sparse_mat(D_x * N_ref, D_x * N_ref); std::vector> Q_triplet_vec; for (size_t i = 0; i < N_ref; ++i) { const auto adaptive_error_weight = [&]() -> std::array { @@ -1198,51 +1199,50 @@ MPTOptimizer::ValueMatrix MPTOptimizer::calcValueMatrix( Q_triplet_vec.push_back( Eigen::Triplet(i * D_x + 1, i * D_x + 1, adaptive_yaw_error_weight)); } + Eigen::SparseMatrix Q_sparse_mat(N_x, N_x); Q_sparse_mat.setFromTriplets(Q_triplet_vec.begin(), Q_triplet_vec.end()); // update R - Eigen::SparseMatrix R_sparse_mat(D_v, D_v); std::vector> R_triplet_vec; for (size_t i = 0; i < N_ref - 1; ++i) { const double adaptive_steer_weight = interpolation::lerp( mpt_param_.steer_input_weight, mpt_param_.avoidance_steer_input_weight, ref_points.at(i).normalized_avoidance_cost); - R_triplet_vec.push_back( - Eigen::Triplet(D_x + D_u * i, D_x + D_u * i, adaptive_steer_weight)); + R_triplet_vec.push_back(Eigen::Triplet(D_u * i, D_u * i, adaptive_steer_weight)); } + Eigen::SparseMatrix R_sparse_mat(N_u, N_u); addSteerWeightR(R_triplet_vec, ref_points); R_sparse_mat.setFromTriplets(R_triplet_vec.begin(), R_triplet_vec.end()); - ValueMatrix m; - m.Q = Q_sparse_mat; - m.R = R_sparse_mat; - time_keeper_ptr_->toc(__func__, " "); - return m; + return ValueMatrix{Q_sparse_mat, R_sparse_mat}; } MPTOptimizer::ObjectiveMatrix MPTOptimizer::calcObjectiveMatrix( - const StateEquationGenerator::Matrix & mpt_mat, const ValueMatrix & val_mat, + [[maybe_unused]] const StateEquationGenerator::Matrix & mpt_mat, const ValueMatrix & val_mat, const std::vector & ref_points) const { time_keeper_ptr_->tic(__func__); - const size_t N_ref = ref_points.size(); const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); - const size_t D_xn = D_x * N_ref; - const size_t D_v = D_x + (N_ref - 1) * D_u; + + const size_t N_ref = ref_points.size(); const size_t N_slack = getNumberOfSlackVariables(); + const size_t N_x = N_ref * D_x; + const size_t N_u = (N_ref - 1) * D_u; + const size_t N_s = N_ref * N_slack; + + const size_t N_v = N_x + N_u + N_s; + // generate T matrix and vector to shift optimization center // NOTE: Z is defined as time-series vector of shifted deviation - // error where Z = sparse_T_mat * (B * U + W) + T_vec - Eigen::SparseMatrix sparse_T_mat(D_xn, D_xn); - Eigen::VectorXd T_vec = Eigen::VectorXd::Zero(D_xn); + // error where Z = sparse_T_mat * X + T_vec std::vector> triplet_T_vec; + Eigen::VectorXd T_vec = Eigen::VectorXd::Zero(N_x); const double offset = mpt_param_.optimization_center_offset; - for (size_t i = 0; i < N_ref; ++i) { const double alpha = ref_points.at(i).alpha; @@ -1252,38 +1252,26 @@ MPTOptimizer::ObjectiveMatrix MPTOptimizer::calcObjectiveMatrix( T_vec(i * D_x) = -offset * std::sin(alpha); } + Eigen::SparseMatrix sparse_T_mat(N_x, N_x); sparse_T_mat.setFromTriplets(triplet_T_vec.begin(), triplet_T_vec.end()); - const Eigen::MatrixXd B = sparse_T_mat * mpt_mat.B; - const Eigen::MatrixXd QB = val_mat.Q * B; - const Eigen::MatrixXd R = val_mat.R; - - // calculate H, and extend it for slack variables // NOTE: min J(v) = min (v'Hv + v'g) - Eigen::MatrixXd H = Eigen::MatrixXd::Zero(D_v, D_v); - H.triangularView() = B.transpose() * QB + R; - H.triangularView() = H.transpose(); - - Eigen::MatrixXd extended_H = Eigen::MatrixXd::Zero(D_v + N_ref * N_slack, D_v + N_ref * N_slack); - extended_H.block(0, 0, D_v, D_v) = H; + Eigen::MatrixXd H_x = Eigen::MatrixXd::Zero(N_x, N_x); + H_x.triangularView() = + Eigen::MatrixXd(sparse_T_mat.transpose() * val_mat.Q * sparse_T_mat); + H_x.triangularView() = H_x.transpose(); - // calculate g, and extend it for slack variables - Eigen::VectorXd g = (sparse_T_mat * mpt_mat.W + T_vec).transpose() * QB; - /* - Eigen::VectorXd extended_g(D_v + N_ref * N_slack); + Eigen::MatrixXd H = Eigen::MatrixXd::Zero(N_v, N_v); + H.block(0, 0, N_x, N_x) = H_x; + H.block(N_x, N_x, N_u, N_u) = val_mat.R; - extended_g.segment(0, D_v) = g; - if (N_slack > 0) { - extended_g.segment(D_v, N_ref * N_slack) = - mpt_param_.soft_collision_free_weight * Eigen::VectorXd::Ones(N_ref * N_slack); - } - */ - Eigen::VectorXd extended_g(D_v + N_ref * N_slack); - extended_g << g, mpt_param_.soft_collision_free_weight * Eigen::VectorXd::Ones(N_ref * N_slack); + Eigen::VectorXd g = Eigen::VectorXd::Zero(N_v); + g.segment(0, N_x) = T_vec.transpose() * val_mat.Q * sparse_T_mat; + g.segment(N_x + N_u, N_s) = mpt_param_.soft_collision_free_weight * Eigen::VectorXd::Ones(N_s); ObjectiveMatrix obj_matrix; - obj_matrix.hessian = extended_H; - obj_matrix.gradient = extended_g; + obj_matrix.hessian = H; + obj_matrix.gradient = g; time_keeper_ptr_->toc(__func__, " "); return obj_matrix; @@ -1300,15 +1288,19 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); + const size_t N_ref = ref_points.size(); + const size_t N_x = N_ref * D_x; const size_t N_u = (N_ref - 1) * D_u; - const size_t D_v = D_x + N_u; - const size_t N_collision_check = vehicle_circle_longitudinal_offsets_.size(); // NOTE: The number of one-step slack variables. // The number of all slack variables will be N_ref * N_slack. const size_t N_slack = getNumberOfSlackVariables(); + const size_t N_v = N_x + N_u + (mpt_param_.soft_constraint ? N_ref * N_slack : 0); + + const size_t N_collision_check = vehicle_circle_longitudinal_offsets_.size(); + // calculate indices of fixed points std::vector fixed_points_indices; for (size_t i = 0; i < N_ref; ++i) { @@ -1319,6 +1311,7 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( // calculate rows and cols of A size_t A_rows = 0; + A_rows += N_x; if (mpt_param_.soft_constraint) { // NOTE: 3 means expecting slack variable constraints to be larger than lower bound, // smaller than upper bound, and positive. @@ -1332,22 +1325,23 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( A_rows += N_u; } - const size_t A_cols = [&] { - if (mpt_param_.soft_constraint) { - return D_v + N_ref * N_slack; // initial state + steer angles + soft variables - } - return D_v; // initial state + steer angles - }(); - - Eigen::MatrixXd A = Eigen::MatrixXd::Zero(A_rows, A_cols); + Eigen::MatrixXd A = Eigen::MatrixXd::Zero(A_rows, N_v); Eigen::VectorXd lb = Eigen::VectorXd::Constant(A_rows, -autoware::common::osqp::INF); Eigen::VectorXd ub = Eigen::VectorXd::Constant(A_rows, autoware::common::osqp::INF); size_t A_rows_end = 0; + // 1. State equation + A.block(0, 0, N_x, N_x) = Eigen::MatrixXd::Identity(N_x, N_x) - mpt_mat.A; + A.block(0, N_x, N_x, N_u) = -mpt_mat.B; + lb.segment(0, N_x) = mpt_mat.W; + ub.segment(0, N_x) = mpt_mat.W; + A_rows_end += N_x; + + // 2. collision free // CX = C(Bv + w) + C \in R^{N_ref, N_ref * D_x} for (size_t l_idx = 0; l_idx < N_collision_check; ++l_idx) { // create C := [cos(beta) | l cos(beta)] - Eigen::SparseMatrix C_sparse_mat(N_ref, N_ref * D_x); + Eigen::SparseMatrix C_sparse_mat(N_ref, N_x); std::vector> C_triplet_vec; Eigen::VectorXd C_vec = Eigen::VectorXd::Zero(N_ref); @@ -1362,10 +1356,6 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( } C_sparse_mat.setFromTriplets(C_triplet_vec.begin(), C_triplet_vec.end()); - // calculate CB, and CW - const Eigen::MatrixXd CB = C_sparse_mat * mpt_mat.B; - const Eigen::VectorXd CW = C_sparse_mat * mpt_mat.W + C_vec; - // calculate bounds const double bounds_offset = vehicle_info_.vehicle_width_m / 2.0 - vehicle_circle_radiuses_.at(l_idx); @@ -1373,36 +1363,30 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( // soft constraints if (mpt_param_.soft_constraint) { - size_t A_offset_cols = D_v; const size_t A_blk_rows = 3 * N_ref; - // A := [C * B | O | ... | O | I | O | ... - // -C * B | O | ... | O | I | O | ... + // A := [C | O | ... | O | I | O | ... + // -C | O | ... | O | I | O | ... // O | O | ... | O | I | O | ... ] - Eigen::MatrixXd A_blk = Eigen::MatrixXd::Zero(A_blk_rows, A_cols); - A_blk.block(0, 0, N_ref, D_v) = CB; - A_blk.block(N_ref, 0, N_ref, D_v) = -CB; + Eigen::MatrixXd A_blk = Eigen::MatrixXd::Zero(A_blk_rows, N_v); + A_blk.block(0, 0, N_ref, N_x) = C_sparse_mat; + A_blk.block(N_ref, 0, N_ref, N_x) = -C_sparse_mat; - size_t local_A_offset_cols = A_offset_cols; - if (!mpt_param_.l_inf_norm) { - local_A_offset_cols += N_ref * l_idx; - } + const size_t local_A_offset_cols = N_x + N_u + (!mpt_param_.l_inf_norm ? N_ref * l_idx : 0); A_blk.block(0, local_A_offset_cols, N_ref, N_ref) = Eigen::MatrixXd::Identity(N_ref, N_ref); A_blk.block(N_ref, local_A_offset_cols, N_ref, N_ref) = Eigen::MatrixXd::Identity(N_ref, N_ref); A_blk.block(2 * N_ref, local_A_offset_cols, N_ref, N_ref) = Eigen::MatrixXd::Identity(N_ref, N_ref); - // lb := [lower_bound - CW - // CW - upper_bound + // lb := [lower_bound - C + // C - upper_bound // O ] Eigen::VectorXd lb_blk = Eigen::VectorXd::Zero(A_blk_rows); - lb_blk.segment(0, N_ref) = -CW + part_lb; - lb_blk.segment(N_ref, N_ref) = CW - part_ub; - - A_offset_cols += N_ref * N_slack; + lb_blk.segment(0, N_ref) = -C_vec + part_lb; + lb_blk.segment(N_ref, N_ref) = C_vec - part_ub; - A.block(A_rows_end, 0, A_blk_rows, A_cols) = A_blk; + A.block(A_rows_end, 0, A_blk_rows, N_v) = A_blk; lb.segment(A_rows_end, A_blk_rows) = lb_blk; A_rows_end += A_blk_rows; @@ -1412,33 +1396,31 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix( if (mpt_param_.hard_constraint) { const size_t A_blk_rows = N_ref; - Eigen::MatrixXd A_blk = Eigen::MatrixXd::Zero(A_blk_rows, A_cols); - A_blk.block(0, 0, N_ref, N_ref) = CB; + Eigen::MatrixXd A_blk = Eigen::MatrixXd::Zero(A_blk_rows, N_v); + A_blk.block(0, 0, N_ref, N_ref) = C_sparse_mat; - A.block(A_rows_end, 0, A_blk_rows, A_cols) = A_blk; - lb.segment(A_rows_end, A_blk_rows) = part_lb - CW; - ub.segment(A_rows_end, A_blk_rows) = part_ub - CW; + A.block(A_rows_end, 0, A_blk_rows, N_v) = A_blk; + lb.segment(A_rows_end, A_blk_rows) = part_lb - C_vec; + ub.segment(A_rows_end, A_blk_rows) = part_ub - C_vec; A_rows_end += A_blk_rows; } } - // fixed points constraint + // 3. fixed points constraint // X = B v + w where point is fixed for (const size_t i : fixed_points_indices) { - A.block(A_rows_end, 0, D_x, D_v) = mpt_mat.B.block(i * D_x, 0, D_x, D_v); + A.block(A_rows_end, D_x * i, D_x, D_x) = Eigen::MatrixXd::Identity(D_x, D_x); - lb.segment(A_rows_end, D_x) = - ref_points[i].fixed_kinematic_state->toEigenVector() - mpt_mat.W.segment(i * D_x, D_x); - ub.segment(A_rows_end, D_x) = - ref_points[i].fixed_kinematic_state->toEigenVector() - mpt_mat.W.segment(i * D_x, D_x); + lb.segment(A_rows_end, D_x) = ref_points.at(i).fixed_kinematic_state->toEigenVector(); + ub.segment(A_rows_end, D_x) = ref_points.at(i).fixed_kinematic_state->toEigenVector(); A_rows_end += D_x; } - // steer limit + // 4. steer angle limit if (mpt_param_.steer_limit_constraint) { - A.block(A_rows_end, D_x, N_u, N_u) = Eigen::MatrixXd::Identity(N_u, N_u); + A.block(A_rows_end, N_x, N_u, N_u) = Eigen::MatrixXd::Identity(N_u, N_u); // TODO(murooka) use curvature by stabling optimization // Currently, when using curvature, the optimization result is weird with sample_map. @@ -1468,13 +1450,13 @@ void MPTOptimizer::addSteerWeightR( std::vector> & R_triplet_vec, const std::vector & ref_points) const { - const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); + const size_t N_ref = ref_points.size(); - const size_t D_v = D_x + (N_ref - 1) * D_u; + const size_t N_u = (N_ref - 1) * D_u; // add steering rate : weight for (u(i) - u(i-1))^2 - for (size_t i = D_x; i < D_v - 1; ++i) { + for (size_t i = 0; i < N_u - 1; ++i) { R_triplet_vec.push_back(Eigen::Triplet(i, i, mpt_param_.steer_rate_weight)); R_triplet_vec.push_back(Eigen::Triplet(i + 1, i, -mpt_param_.steer_rate_weight)); R_triplet_vec.push_back(Eigen::Triplet(i, i + 1, -mpt_param_.steer_rate_weight)); @@ -1490,10 +1472,12 @@ std::optional MPTOptimizer::calcOptimizedSteerAngles( const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); + const size_t N_ref = ref_points.size(); - const size_t D_v = D_x + (N_ref - 1) * D_u; + const size_t N_x = N_ref * D_x; + const size_t N_u = (N_ref - 1) * D_u; const size_t N_slack = getNumberOfSlackVariables(); - const size_t D_un = D_v + N_ref * N_slack; + const size_t N_v = N_x + N_u + N_ref * N_slack; // for manual warm start, calculate initial solution const auto u0 = [&]() -> std::optional { @@ -1522,7 +1506,9 @@ std::optional MPTOptimizer::calcOptimizedSteerAngles( const autoware::common::osqp::CSC_Matrix P_csc = autoware::common::osqp::calCSCMatrixTrapezoidal(H); const autoware::common::osqp::CSC_Matrix A_csc = autoware::common::osqp::calCSCMatrix(A); - if (mpt_param_.enable_warm_start && prev_mat_n_ == H.rows() && prev_mat_m_ == A.rows()) { + if ( + prev_solution_status_ == 1 && mpt_param_.enable_warm_start && prev_mat_n_ == H.rows() && + prev_mat_m_ == A.rows()) { RCLCPP_INFO_EXPRESSION(logger_, enable_debug_info_, "warm start"); osqp_solver_ptr_->updateCscP(P_csc); osqp_solver_ptr_->updateQ(f); @@ -1546,6 +1532,7 @@ std::optional MPTOptimizer::calcOptimizedSteerAngles( // check solution status const int solution_status = std::get<3>(result); + prev_solution_status_ = solution_status; if (solution_status != 1) { osqp_solver_ptr_->logUnsolvedStatus("[MPT]"); return std::nullopt; @@ -1565,15 +1552,15 @@ std::optional MPTOptimizer::calcOptimizedSteerAngles( RCLCPP_WARN(logger_, "optimization failed: result contains NaN values"); return std::nullopt; } - const Eigen::VectorXd optimized_steer_angles = - Eigen::Map(&optimization_result[0], D_un); + const Eigen::VectorXd optimized_variables = + Eigen::Map(&optimization_result[0], N_v); time_keeper_ptr_->toc(__func__, " "); if (u0) { // manual warm start - return static_cast(optimized_steer_angles + *u0); + return static_cast(optimized_variables + *u0); } - return optimized_steer_angles; + return optimized_variables; } Eigen::VectorXd MPTOptimizer::calcInitialSolutionForManualWarmStart( @@ -1649,30 +1636,30 @@ MPTOptimizer::updateMatrixForManualWarmStart( } std::optional> MPTOptimizer::calcMPTPoints( - std::vector & ref_points, const Eigen::VectorXd & U, - const StateEquationGenerator::Matrix & mpt_mat) const + std::vector & ref_points, const Eigen::VectorXd & optimized_variables, + [[maybe_unused]] const StateEquationGenerator::Matrix & mpt_mat) const { time_keeper_ptr_->tic(__func__); const size_t D_x = state_equation_generator_.getDimX(); const size_t D_u = state_equation_generator_.getDimU(); + const size_t N_ref = ref_points.size(); - const size_t D_v = D_x + (N_ref - 1) * D_u; + const size_t N_x = N_ref * D_x; + const size_t N_u = (N_ref - 1) * D_u; const size_t N_slack = getNumberOfSlackVariables(); - const Eigen::VectorXd steer_angles = U.segment(0, D_v); - const Eigen::VectorXd slack_variables = U.segment(D_v, N_ref * N_slack); - - // predict time-series states from optimized control inputs - const Eigen::VectorXd X = state_equation_generator_.predict(mpt_mat, steer_angles); + const Eigen::VectorXd states = optimized_variables.segment(0, N_x); + const Eigen::VectorXd steer_angles = optimized_variables.segment(N_x, N_u); + const Eigen::VectorXd slack_variables = optimized_variables.segment(N_x + N_u, N_ref * N_slack); // calculate trajectory points from optimization result std::vector traj_points; for (size_t i = 0; i < N_ref; ++i) { auto & ref_point = ref_points.at(i); - const double lat_error = X(i * D_x); - const double yaw_error = X(i * D_x + 1); + const double lat_error = states(i * D_x); + const double yaw_error = states(i * D_x + 1); // validate optimization result if (mpt_param_.enable_optimization_validation) { @@ -1688,7 +1675,7 @@ std::optional> MPTOptimizer::calcMPTPoints( if (i == N_ref - 1) { ref_point.optimized_input = 0.0; } else { - ref_point.optimized_input = steer_angles(D_x + i * D_u); + ref_point.optimized_input = steer_angles(i * D_u); } std::vector tmp_slack_variables; diff --git a/planning/obstacle_avoidance_planner/src/state_equation_generator.cpp b/planning/obstacle_avoidance_planner/src/state_equation_generator.cpp index a6eaf7ffdd2ac..7460ce9c1f764 100644 --- a/planning/obstacle_avoidance_planner/src/state_equation_generator.cpp +++ b/planning/obstacle_avoidance_planner/src/state_equation_generator.cpp @@ -25,31 +25,27 @@ StateEquationGenerator::Matrix StateEquationGenerator::calcMatrix( { time_keeper_ptr_->tic(__func__); - const size_t N_ref = ref_points.size(); const size_t D_x = vehicle_model_ptr_->getDimX(); const size_t D_u = vehicle_model_ptr_->getDimU(); - const size_t D_v = D_x + D_u * (N_ref - 1); + + const size_t N_ref = ref_points.size(); + const size_t N_x = N_ref * D_x; + const size_t N_u = (N_ref - 1) * D_u; // matrices for whole state equation - Eigen::MatrixXd B = Eigen::MatrixXd::Zero(D_x * N_ref, D_v); - Eigen::VectorXd W = Eigen::VectorXd::Zero(D_x * N_ref); + Eigen::MatrixXd A = Eigen::MatrixXd::Zero(N_x, N_x); + Eigen::MatrixXd B = Eigen::MatrixXd::Zero(N_x, N_u); + Eigen::VectorXd W = Eigen::VectorXd::Zero(N_x); // matrices for one-step state equation Eigen::MatrixXd Ad(D_x, D_x); Eigen::MatrixXd Bd(D_x, D_u); Eigen::MatrixXd Wd(D_x, 1); - // calculate one-step state equation considering kinematics N_ref times - for (size_t i = 0; i < N_ref; ++i) { - if (i == 0) { - B.block(0, 0, D_x, D_x) = Eigen::MatrixXd::Identity(D_x, D_x); - continue; - } - - const int idx_x_i = i * D_x; - const int idx_x_i_prev = (i - 1) * D_x; - const int idx_u_i_prev = (i - 1) * D_u; + A.block(0, 0, D_x, D_x) = Eigen::MatrixXd::Identity(D_x, D_x); + // calculate one-step state equation considering kinematics N_ref times + for (size_t i = 1; i < N_ref; ++i) { // get discrete kinematics matrix A, B, W const auto & p = ref_points.at(i - 1); @@ -59,24 +55,13 @@ StateEquationGenerator::Matrix StateEquationGenerator::calcMatrix( // p.delta_arc_length); vehicle_model_ptr_->calculateStateEquationMatrix(Ad, Bd, Wd, 0.0, p.delta_arc_length); - B.block(idx_x_i, 0, D_x, D_x) = Ad * B.block(idx_x_i_prev, 0, D_x, D_x); - B.block(idx_x_i, D_x + idx_u_i_prev, D_x, D_u) = Bd; - - for (size_t j = 0; j < i - 1; ++j) { - size_t idx_u_j = j * D_u; - B.block(idx_x_i, D_x + idx_u_j, D_x, D_u) = - Ad * B.block(idx_x_i_prev, D_x + idx_u_j, D_x, D_u); - } - - W.segment(idx_x_i, D_x) = Ad * W.block(idx_x_i_prev, 0, D_x, 1) + Wd; + A.block(i * D_x, (i - 1) * D_x, D_x, D_x) = Ad; + B.block(i * D_x, (i - 1) * D_u, D_x, D_u) = Bd; + W.segment(i * D_x, D_x) = Wd; } - Matrix mat; - mat.B = B; - mat.W = W; - time_keeper_ptr_->toc(__func__, " "); - return mat; + return Matrix{A, B, W}; } Eigen::VectorXd StateEquationGenerator::predict( From d8efc136d2c10c75106d798e3a0c119452439a03 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 13 Aug 2023 01:47:49 +0900 Subject: [PATCH 12/16] feat(obstacle_avoidance_planner): add depth argument in plotter (#4605) Signed-off-by: Takayuki Murooka --- .../scripts/calculation_time_plotter.py | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py b/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py index 042c2ff5f0345..eb4e028f5245d 100755 --- a/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py +++ b/planning/obstacle_avoidance_planner/scripts/calculation_time_plotter.py @@ -28,6 +28,7 @@ def __init__(self, args): super().__init__("calculation_cost_analyzer") self.functions_name = args.functions.split(",") + self.depth = args.depth self.calculation_cost_hist = [] self.sub_calculation_cost = self.create_subscription( @@ -67,7 +68,7 @@ def CallbackCalculationCost(self, msg): if not is_found: self.y_vec[f_idx].append(None) - if len(self.y_vec[f_idx]) > 100: + if len(self.y_vec[f_idx]) > self.depth: self.y_vec[f_idx].popleft() x_vec = list(range(len(self.y_vec[f_idx]))) @@ -99,7 +100,13 @@ def CallbackCalculationCost(self, msg): "-f", "--functions", type=str, - default="onPath, getModelPredictiveTrajectory, getEBTrajectory", + default="onPath, optimizeTrajectory, publishDebugMarkerOfOptimization, solveOsqp", + ) + parser.add_argument( + "-d", + "--depth", + type=float, + default=500, ) args = parser.parse_args() From d4782c44377e1f3fb4187bcad120f0f8e167c219 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 13 Aug 2023 13:21:32 +0900 Subject: [PATCH 13/16] feat(route_handler): support shoulder lane in getLeft(Right)Lanelet (#4604) Signed-off-by: kosuke55 --- planning/route_handler/src/route_handler.cpp | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 4e009836b53d4..26d226a6746e2 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -942,6 +942,16 @@ bool RouteHandler::isBijectiveConnection( boost::optional RouteHandler::getRightLanelet( const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const { + // right road lanelet of shoulder lanelet + if (isShoulderLanelet(lanelet)) { + for (const auto & road_lanelet : road_lanelets_) { + if (lanelet::geometry::rightOf(road_lanelet, lanelet)) { + return road_lanelet; + } + } + return boost::none; + } + // routable lane const auto & right_lane = routing_graph_ptr_->right(lanelet); if (right_lane) { @@ -999,6 +1009,16 @@ bool RouteHandler::getLeftLaneletWithinRoute( boost::optional RouteHandler::getLeftLanelet( const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const { + // left road lanelet of shoulder lanelet + if (isShoulderLanelet(lanelet)) { + for (const auto & road_lanelet : road_lanelets_) { + if (lanelet::geometry::leftOf(road_lanelet, lanelet)) { + return road_lanelet; + } + } + return boost::none; + } + // routable lane const auto & left_lane = routing_graph_ptr_->left(lanelet); if (left_lane) { From c2b7b7dd2b65a4b30521d9a60bca5116f62b11eb Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 13 Aug 2023 19:02:24 +0900 Subject: [PATCH 14/16] chore(scenario_selector): fix typo (#4613) chore(scneario_selector): fix typo Signed-off-by: kosuke55 --- .../src/scenario_selector_node/scenario_selector_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp b/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp index cffb490464de0..1d5c7b44dcc45 100644 --- a/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp +++ b/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp @@ -197,7 +197,7 @@ void ScenarioSelectorNode::onMap( void ScenarioSelectorNode::onRoute( const autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr msg) { - // When the route id is the same (e.g. reporting with modified goal) keep the current scenario. + // When the route id is the same (e.g. rerouting with modified goal) keep the current scenario. // Otherwise, reset the scenario. if (!route_handler_ || route_handler_->getRouteUuid() != msg->uuid) { current_scenario_ = tier4_planning_msgs::msg::Scenario::EMPTY; From 7f02d6a7adf7451cd1808bd658d4d1e70a2b7b1e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 13 Aug 2023 19:02:37 +0900 Subject: [PATCH 15/16] fix(start_planner): fix geometric parallel parking lane ids (#4603) * fix(start_planner): fix geometric parallel parking lane ids Signed-off-by: kosuke55 * fix stop path drivable lanes Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../start_planner/start_planner_module.hpp | 2 +- .../start_planner/start_planner_module.cpp | 38 ++++++++++++--- .../geometric_parallel_parking.cpp | 48 ++++++++++++------- 3 files changed, 64 insertions(+), 24 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp index 1405e3cd1f10e..3214de2c37bd7 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/start_planner/start_planner_module.hpp @@ -143,7 +143,7 @@ class StartPlannerModule : public SceneModuleInterface const std::vector & start_pose_candidates, const Pose & goal_pose, const std::string search_priority); PathWithLaneId generateStopPath() const; - lanelet::ConstLanelets getPathLanes(const PathWithLaneId & path) const; + lanelet::ConstLanelets getPathRoadLanes(const PathWithLaneId & path) const; std::vector generateDrivableLanes(const PathWithLaneId & path) const; void updatePullOutStatus(); static bool isOverlappedWithLane( diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index 32398c7944435..fb471a4675fa7 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -534,19 +534,23 @@ PathWithLaneId StartPlannerModule::generateStopPath() const return path; } -lanelet::ConstLanelets StartPlannerModule::getPathLanes(const PathWithLaneId & path) const +lanelet::ConstLanelets StartPlannerModule::getPathRoadLanes(const PathWithLaneId & path) const { + const auto & route_handler = planner_data_->route_handler; + const auto & lanelet_layer = route_handler->getLaneletMapPtr()->laneletLayer; + std::vector lane_ids; for (const auto & p : path.points) { for (const auto & id : p.lane_ids) { + if (route_handler->isShoulderLanelet(lanelet_layer.get(id))) { + continue; + } if (std::find(lane_ids.begin(), lane_ids.end(), id) == lane_ids.end()) { lane_ids.push_back(id); } } } - const auto & lanelet_layer = planner_data_->route_handler->getLaneletMapPtr()->laneletLayer; - lanelet::ConstLanelets path_lanes; path_lanes.reserve(lane_ids.size()); for (const auto & id : lane_ids) { @@ -561,7 +565,22 @@ lanelet::ConstLanelets StartPlannerModule::getPathLanes(const PathWithLaneId & p std::vector StartPlannerModule::generateDrivableLanes( const PathWithLaneId & path) const { - return utils::generateDrivableLanesWithShoulderLanes(getPathLanes(path), status_.pull_out_lanes); + const auto path_road_lanes = getPathRoadLanes(path); + + if (!path_road_lanes.empty()) { + return utils::generateDrivableLanesWithShoulderLanes( + getPathRoadLanes(path), status_.pull_out_lanes); + } + + // if path_road_lanes is empty, use only pull_out_lanes as drivable lanes + std::vector drivable_lanes; + for (const auto & lane : status_.pull_out_lanes) { + DrivableLanes drivable_lane; + drivable_lane.right_lane = lane; + drivable_lane.left_lane = lane; + drivable_lanes.push_back(drivable_lane); + } + return drivable_lanes; } void StartPlannerModule::updatePullOutStatus() @@ -702,10 +721,15 @@ bool StartPlannerModule::hasFinishedPullOut() const const auto current_pose = planner_data_->self_odometry->pose.pose; // check that ego has passed pull out end point - const auto path_lanes = getPathLanes(getFullPath()); - const auto arclength_current = lanelet::utils::getArcCoordinates(path_lanes, current_pose); + const double backward_path_length = + planner_data_->parameters.backward_path_length + parameters_->max_back_distance; + const auto current_lanes = utils::getExtendedCurrentLanes( + planner_data_, backward_path_length, std::numeric_limits::max(), + /*forward_only_in_route*/ true); + + const auto arclength_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose); const auto arclength_pull_out_end = - lanelet::utils::getArcCoordinates(path_lanes, status_.pull_out_path.end_pose); + lanelet::utils::getArcCoordinates(current_lanes, status_.pull_out_path.end_pose); // offset to not finish the module before engage constexpr double offset = 0.1; diff --git a/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp b/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp index 678e19e616f26..4f8c7ff9a94b4 100644 --- a/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp +++ b/planning/behavior_path_planner/src/utils/geometric_parallel_parking/geometric_parallel_parking.cpp @@ -368,7 +368,8 @@ std::vector GeometricParallelParking::planOneTrial( { clearPaths(); - const auto common_params = planner_data_->parameters; + const auto & common_params = planner_data_->parameters; + const auto & route_handler = planner_data_->route_handler; const Pose arc_end_pose = calcOffsetPose(goal_pose, end_pose_offset, 0, 0); const double self_yaw = tf2::getYaw(start_pose.orientation); @@ -435,34 +436,49 @@ std::vector GeometricParallelParking::planOneTrial( PathWithLaneId path_turn_left = generateArcPath( Cl, R_E_l, -M_PI_2, normalizeRadian(-M_PI_2 + theta_l), arc_path_interval, is_forward, is_forward); - path_turn_left.header = planner_data_->route_handler->getRouteHeader(); + path_turn_left.header = route_handler->getRouteHeader(); PathWithLaneId path_turn_right = generateArcPath( Cr, R_E_r, normalizeRadian(psi + M_PI_2 + theta_l), M_PI_2, arc_path_interval, !is_forward, is_forward); - path_turn_right.header = planner_data_->route_handler->getRouteHeader(); + path_turn_right.header = route_handler->getRouteHeader(); - auto setLaneIds = [lanes](PathPointWithLaneId & p) { - for (const auto & lane : lanes) { - p.lane_ids.push_back(lane.id()); + // Need to add straight path to last right_turning for parking in parallel + if (std::abs(end_pose_offset) > 0) { + PathPointWithLaneId straight_point{}; + straight_point.point.pose = goal_pose; + // setLaneIds(straight_point); + path_turn_right.points.push_back(straight_point); + } + + // Populate lane ids for a given path. + // It checks if each point in the path is within a lane + // and if its ID hasn't been added yet, it appends the ID to the container. + std::vector path_lane_ids; + const auto populateLaneIds = [&](const auto & path) { + for (const auto & p : path.points) { + for (const auto & lane : lanes) { + if ( + lanelet::utils::isInLanelet(p.point.pose, lane) && + std::find(path_lane_ids.begin(), path_lane_ids.end(), lane.id()) == path_lane_ids.end()) { + path_lane_ids.push_back(lane.id()); + } + } } }; - auto setLaneIdsToPath = [setLaneIds](PathWithLaneId & path) { + populateLaneIds(path_turn_left); + populateLaneIds(path_turn_right); + + // Set lane ids to each point in a given path. + // It assigns the accumulated lane ids from path_lane_ids to each point's lane_ids member. + const auto setLaneIdsToPath = [&](PathWithLaneId & path) { for (auto & p : path.points) { - setLaneIds(p); + p.lane_ids = path_lane_ids; } }; setLaneIdsToPath(path_turn_left); setLaneIdsToPath(path_turn_right); - // Need to add straight path to last right_turning for parking in parallel - if (std::abs(end_pose_offset) > 0) { - PathPointWithLaneId straight_point{}; - straight_point.point.pose = goal_pose; - setLaneIds(straight_point); - path_turn_right.points.push_back(straight_point); - } - // generate arc path vector paths_.push_back(path_turn_left); paths_.push_back(path_turn_right); From e0e9fcfd601b6ccde71a75d4e04898e5f92f049e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 14 Aug 2023 08:36:16 +0900 Subject: [PATCH 16/16] fix(avoidance): fix dying with empty lanes (#4606) Signed-off-by: kosuke55 --- planning/behavior_path_planner/src/utils/avoidance/utils.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp index ed38cc663bc84..c88fc377dc473 100644 --- a/planning/behavior_path_planner/src/utils/avoidance/utils.cpp +++ b/planning/behavior_path_planner/src/utils/avoidance/utils.cpp @@ -855,6 +855,10 @@ void filterTargetObjects( using lanelet::geometry::toArcCoordinates; using lanelet::utils::to2D; + if (data.current_lanelets.empty()) { + return; + } + const auto & rh = planner_data->route_handler; const auto & path_points = data.reference_path_rough.points; const auto & ego_pos = planner_data->self_odometry->pose.pose.position;